diff --git a/.cproject b/.cproject index efdaf0c8a..df6fdc5f5 100644 --- a/.cproject +++ b/.cproject @@ -35,10 +35,6 @@ @@ -285,6 +281,8 @@ + + @@ -439,156 +437,18 @@ true true - + make - -j2 - check + -j5 + testPoseRTV.run 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 + -j5 + testIMUSystem.run true true true @@ -745,34 +605,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 @@ -793,6 +701,14 @@ true true + + make + -j5 + testKey.run + true + true + true + make -j5 @@ -865,6 +781,30 @@ true true + + make + -j5 + testInvDepthFactor3.run + true + true + true + + + make + -j5 + testPoseTranslationPrior.run + true + true + true + + + make + -j5 + testPoseRotationPrior.run + true + true + true + make -j5 @@ -873,6 +813,22 @@ true true + + make + -j5 + testDiscreteMarginals.run + true + true + true + + + make + -j5 + testInference.run + true + true + true + make -j2 @@ -881,6 +837,14 @@ true true + + make + -j5 + testInvDepthCamera3.run + true + true + true + make -j2 @@ -897,22 +861,6 @@ true true - - make - -j2 - testGaussianJunctionTree.run - true - true - true - - - make - -j2 - testGaussianFactorGraph.run - true - true - true - make -j2 @@ -921,42 +869,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 @@ -969,10 +901,10 @@ true true - + make - -j2 - testNonlinearFactorGraph.run + -j5 + testGradientDescentOptimizer.run true true true @@ -985,14 +917,6 @@ true true - - make - -j2 - testPose2SLAMwSPCG.run - true - true - true - make -j2 @@ -1017,14 +941,6 @@ true true - - make - -j5 - tests.testBoundingConstraint.run - true - true - true - make -j2 @@ -1049,6 +965,118 @@ true true + + make + -j5 + testNonlinearFactor.run + true + 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 + -j5 + testNonlinearFactorGraph.run + true + true + true + + + make + -j5 + testIterative.run + true + true + true + + + make + -j5 + testSubgraphSolver.run + true + true + true + + + make + -j5 + testGaussianFactorGraphB.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + all + true + true + true + make -j2 @@ -1185,6 +1213,14 @@ true true + + make + -j5 + testLinearContainerFactor.run + true + true + true + make -j2 @@ -1513,6 +1549,14 @@ true true + + make + -j5 + testSimpleCamera.run + true + true + true + make -j2 @@ -1742,18 +1786,18 @@ true true - + make - -j2 - CameraResectioning + -j5 + CameraResectioning.run true true true - + make - -j2 - PlanarSLAMExample_easy.run + -j5 + PlanarSLAMExample.run true true true @@ -1782,26 +1826,10 @@ true true - + make - -j2 - PlanarSLAMSelfContained_advanced.run - true - true - true - - - make - -j2 - Pose2SLAMExample_advanced.run - true - true - true - - - make - -j2 - Pose2SLAMExample_easy.run + -j5 + Pose2SLAMExample.run true true true @@ -1822,6 +1850,22 @@ true true + + make + -j5 + LocalizationExample.run + true + true + true + + + make + -j5 + OdometryExample.run + true + true + true + make -j2 @@ -1855,10 +1899,10 @@ make - -j2 + -j1 install true - true + false true @@ -1869,12 +1913,12 @@ true true - + make - -j5 + -j1 check true - true + false true @@ -2092,6 +2136,126 @@ true true + + make + -j5 + check.discrete_unstable + true + true + true + + + make + -j5 + check.base_unstable + true + true + true + + + make + -j5 + check.dynamics_unstable + true + true + true + + + make + -j5 + check.slam_unstable + true + true + true + + + make + -j5 + check.unstable + true + true + true + + + make + -j5 + wrap_gtsam_build + true + true + true + + + make + -j5 + wrap_gtsam_unstable_build + true + true + true + + + make + -j5 + wrap_gtsam_unstable + true + true + true + + + make + -j5 + wrap + true + true + true + + + make + -j5 + check.nonlinear_unstable + true + true + true + + + make + -j5 + wrap_gtsam_distclean + true + true + true + + + make + -j5 + wrap_gtsam_unstable_distclean + true + true + true + + + make + -j5 + doc + true + true + true + + + make + -j5 + doc_clean + true + true + true + + + make + -j5 + check + true + true + true + make -j2 @@ -2227,18 +2391,18 @@ false true - + make -j5 - wrap.testSpirit.run + testSpirit.run true true true - + make -j5 - wrap.testWrap.run + testWrap.run true true true @@ -2251,14 +2415,6 @@ true true - - make - -j5 - wrap_gtsam - true - true - true - make -j5 diff --git a/.settings/org.eclipse.cdt.core.prefs b/.settings/org.eclipse.cdt.core.prefs deleted file mode 100644 index a915be654..000000000 --- a/.settings/org.eclipse.cdt.core.prefs +++ /dev/null @@ -1,6 +0,0 @@ -#Wed Oct 06 11:57:41 EDT 2010 -eclipse.preferences.version=1 -environment/project/cdt.managedbuild.toolchain.gnu.macosx.base.1359703544.1441575890/append=true -environment/project/cdt.managedbuild.toolchain.gnu.macosx.base.1359703544.1441575890/appendContributed=true -environment/project/cdt.managedbuild.toolchain.gnu.macosx.base.1359703544/append=true -environment/project/cdt.managedbuild.toolchain.gnu.macosx.base.1359703544/appendContributed=true diff --git a/CMakeLists.txt b/CMakeLists.txt index e6c9bc422..6b7ce4599 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,16 +1,26 @@ + project(GTSAM CXX C) cmake_minimum_required(VERSION 2.6) # Set the version number for the library set (GTSAM_VERSION_MAJOR 2) -set (GTSAM_VERSION_MINOR 0) +set (GTSAM_VERSION_MINOR 1) set (GTSAM_VERSION_PATCH 0) # Set the default install path to home #set (CMAKE_INSTALL_PREFIX ${HOME} CACHE PATH "Install prefix for library") +set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +include(GtsamMakeConfigFile) + +# Record the root dir for gtsam - needed during external builds, e.g., ROS +set(GTSAM_SOURCE_ROOT_DIR ${CMAKE_CURRENT_SOURCE_DIR}) +message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") + +# Load build type flags and default to Debug mode +include(GtsamBuildTypes) + # Use macros for creating tests/timing scripts -set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${PROJECT_SOURCE_DIR}/cmake") include(GtsamTesting) include(GtsamPrinting) @@ -26,40 +36,46 @@ else() set(GTSAM_UNSTABLE_AVAILABLE 0) endif() -# Load build type flags and default to Debug mode -include(GtsamBuildTypes) - -# Check build types -if(${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} VERSION_GREATER 2.8 OR ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} VERSION_EQUAL 2.8) - set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS None Debug Release Timing Profiling RelWithDebInfo MinSizeRel) -endif() -string(TOLOWER "${CMAKE_BUILD_TYPE}" cmake_build_type_tolower) -if( NOT cmake_build_type_tolower STREQUAL "" - AND NOT cmake_build_type_tolower STREQUAL "none" - AND NOT cmake_build_type_tolower STREQUAL "debug" - AND NOT cmake_build_type_tolower STREQUAL "release" - AND NOT cmake_build_type_tolower STREQUAL "timing" - AND NOT cmake_build_type_tolower STREQUAL "profiling" - AND NOT cmake_build_type_tolower STREQUAL "relwithdebinfo") - message(FATAL_ERROR "Unknown build type \"${CMAKE_BUILD_TYPE}\". Allowed values are None, Debug, Release, Timing, Profiling, RelWithDebInfo (case-insensitive).") -endif() - # Configurable Options option(GTSAM_BUILD_TESTS "Enable/Disable building of tests" ON) -option(GTSAM_BUILD_TIMING "Enable/Disable building of timing scripts" ON) +#option(GTSAM_BUILD_TIMING "Enable/Disable building of timing scripts" ON) # These do not currently work option(GTSAM_BUILD_EXAMPLES "Enable/Disable building of examples" ON) if(GTSAM_UNSTABLE_AVAILABLE) - option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" OFF) + option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON) +endif() +if(NOT MSVC) + option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON) + option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" ON) +else() + set(GTSAM_BUILD_STATIC_LIBRARY ON) endif() -option(GTSAM_BUILD_WRAP "Enable/Disable building of matlab wrap utility (necessary for matlab interface)" ON) -option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON) -option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" ON) option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices" OFF) -option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" ON) -option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" ON) -option(GTSAM_INSTALL_MATLAB_EXAMPLES "Enable/Disable installation of matlab examples" ON) -option(GTSAM_INSTALL_MATLAB_TESTS "Enable/Disable installation of matlab tests" ON) -option(GTSAM_INSTALL_WRAP "Enable/Disable installation of wrap utility" ON) +if(NOT MSVC) + option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" ON) +endif() + + +# Options relating to MATLAB wrapper +# TODO: Check for matlab mex binary before handling building of binaries +option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" OFF) +option(GTSAM_BUILD_WRAP "Enable/Disable building of matlab wrap utility (necessary for matlab interface)" ON) +option(GTSAM_INSTALL_WRAP "Enable/Disable installation of wrap utility for wrapping other libraries" ON) +set(GTSAM_TOOLBOX_INSTALL_PATH "" CACHE PATH "Matlab toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/toolbox") +set(GTSAM_BUILD_MEX_BINARY_FLAGS "" CACHE STRING "Extra flags for running Matlab MEX compilation") +set(MEX_COMMAND "mex" CACHE FILEPATH "Command to use for executing mex (if on path, 'mex' will work)") + +# Check / set dependent variables for MATLAB wrapper +set(GTSAM_WRAP_HEADER_PATH "${PROJECT_SOURCE_DIR}/wrap") +if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT GTSAM_BUILD_WRAP) + message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX is enabled, please also enable GTSAM_BUILD_WRAP") +endif() +if(GTSAM_INSTALL_WRAP AND NOT GTSAM_BUILD_WRAP) + message(FATAL_ERROR "GTSAM_INSTALL_WRAP is enabled, please also enable GTSAM_BUILD_WRAP") +endif() +if(NOT GTSAM_TOOLBOX_INSTALL_PATH) + set(GTSAM_TOOLBOX_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/borg/toolbox") +endif() + # Flags for choosing default packaging tools set(CPACK_SOURCE_GENERATOR "TGZ" CACHE STRING "CPack Default Source Generator") @@ -72,18 +88,14 @@ endif() # Add the Quaternion Build Flag if requested if (GTSAM_USE_QUATERNIONS) - set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DGTSAM_DEFAULT_QUATERNIONS") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DGTSAM_DEFAULT_QUATERNIONS") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DGTSAM_DEFAULT_QUATERNIONS") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DGTSAM_DEFAULT_QUATERNIONS") endif(GTSAM_USE_QUATERNIONS) -# Avoid building non-installed exes and unit tests when installing -# FIXME: breaks generation and install of matlab toolbox -# FIXME: can't add install dependencies, so libraries never get built -#set(CMAKE_SKIP_INSTALL_ALL_DEPENDENCY TRUE) - -# Alternative version to keep tests from building during make install -# Use the EXCLUDE_FROM_ALL property on test executables -option(GTSAM_ENABLE_INSTALL_TEST_FIX "Enable/Disable fix to remove dependency of tests on 'all' target" ON) +# Flags to determine whether tests and examples are build during 'make install' +# Note that these remove the targets from the 'all' +option(GTSAM_DISABLE_TESTS_ON_INSTALL "Disables building tests during install" ON) +option(GTSAM_DISABLE_EXAMPLES_ON_INSTALL "Disables building examples during install" OFF) # Pull in infrastructure if (GTSAM_BUILD_TESTS) @@ -93,7 +105,11 @@ if (GTSAM_BUILD_TESTS) endif() # Find boost -find_package(Boost 1.40 COMPONENTS serialization REQUIRED) +if(CYGWIN OR MSVC OR WIN32) + set(Boost_USE_STATIC_LIBS 1) +endif() +find_package(Boost 1.43 COMPONENTS serialization system filesystem thread date_time regex REQUIRED) +set(GTSAM_BOOST_LIBRARIES ${Boost_SERIALIZATION_LIBRARY} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY}) # General build settings include_directories( @@ -107,28 +123,45 @@ link_directories(${Boost_LIBRARY_DIRS}) # Build CppUnitLite add_subdirectory(CppUnitLite) +# Build wrap +if (GTSAM_BUILD_WRAP) + add_subdirectory(wrap) +endif(GTSAM_BUILD_WRAP) + # Build GTSAM library add_subdirectory(gtsam) # Build Tests add_subdirectory(tests) -# Build wrap -if (GTSAM_BUILD_WRAP) - add_subdirectory(wrap) -endif(GTSAM_BUILD_WRAP) - # Build examples if (GTSAM_BUILD_EXAMPLES) add_subdirectory(examples) endif(GTSAM_BUILD_EXAMPLES) +# Matlab toolbox +if (GTSAM_INSTALL_MATLAB_TOOLBOX) + add_subdirectory(matlab) +endif() + # Build gtsam_unstable if (GTSAM_BUILD_UNSTABLE) add_subdirectory(gtsam_unstable) endif(GTSAM_BUILD_UNSTABLE) -# Set up CPack +# Install config and export files +GtsamMakeConfigFile(GTSAM) +export(TARGETS ${GTSAM_EXPORTED_TARGETS} FILE GTSAM-exports.cmake) + +# Check for doxygen availability - optional dependency +find_package(Doxygen) + +# Doxygen documentation - enabling options in subfolder +if (DOXYGEN_FOUND) + add_subdirectory(doc) +endif() + +## Set up CPack set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "GTSAM") set(CPACK_PACKAGE_VENDOR "Frank Dellaert, Georgia Institute of Technology") set(CPACK_PACKAGE_CONTACT "Frank Dellaert, dellaert@cc.gatech.edu") @@ -138,30 +171,39 @@ set(CPACK_PACKAGE_VERSION_MAJOR ${GTSAM_VERSION_MAJOR}) set(CPACK_PACKAGE_VERSION_MINOR ${GTSAM_VERSION_MINOR}) set(CPACK_PACKAGE_VERSION_PATCH ${GTSAM_VERSION_PATCH}) set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") -set(CPACK_INSTALLED_DIRECTORIES "doc;.") # Include doc directory -set(CPACK_SOURCE_IGNORE_FILES "/build;/\\\\.;/makedoc.sh$;/gtsam_unstable/") +#set(CPACK_INSTALLED_DIRECTORIES "doc;.") # Include doc directory +#set(CPACK_INSTALLED_DIRECTORIES ".") # FIXME: throws error +set(CPACK_SOURCE_IGNORE_FILES "/build*;/\\\\.;/makestats.sh$") +set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/gtsam_unstable/") +set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/package_scripts/") set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") #set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-aspn${GTSAM_VERSION_PATCH}") # Used for creating ASPN tarballs -# Record the root dir for gtsam - needed during external builds, e.g., ROS -set(GTSAM_SOURCE_ROOT_DIR ${CMAKE_CURRENT_SOURCE_DIR}) -message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") +# Deb-package specific cpack +set(CPACK_DEBIAN_PACKAGE_NAME "libgtsam-dev") +set(CPACK_DEBIAN_PACKAGE_DEPENDS "libboost-dev (>= 1.43)") #Example: "libc6 (>= 2.3.1-6), libgcc1 (>= 1:3.4.2-12)") # print configuration variables message(STATUS "===============================================================") message(STATUS "================ Configuration Options ======================") message(STATUS "Build flags ") -print_config_flag(${GTSAM_BUILD_TIMING} "Build Timing scripts ") +#print_config_flag(${GTSAM_BUILD_TIMING} "Build Timing scripts ") print_config_flag(${GTSAM_BUILD_EXAMPLES} "Build Examples ") print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") -print_config_flag(${GTSAM_BUILD_SHARED_LIBRARY} "Build shared GTSAM Library ") -print_config_flag(${GTSAM_BUILD_STATIC_LIBRARY} "Build static GTSAM Library ") -print_config_flag(${GTSAM_BUILD_CONVENIENCE_LIBRARIES} "Build Convenience Libraries ") -if(GTSAM_UNSTABLE_AVAILABLE) - print_config_flag(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") +if (DOXYGEN_FOUND) + print_config_flag(${GTSAM_BUILD_DOCS} "Build Docs ") endif() -print_config_flag(${GTSAM_ENABLE_INSTALL_TEST_FIX} "Tests excluded from all target ") +if(NOT MSVC) + print_config_flag(${GTSAM_BUILD_SHARED_LIBRARY} "Build shared GTSAM Library ") + print_config_flag(${GTSAM_BUILD_STATIC_LIBRARY} "Build static GTSAM Library ") + print_config_flag(${GTSAM_BUILD_CONVENIENCE_LIBRARIES} "Build Convenience Libraries ") +endif() +print_config_flag(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build-type in library name ") +if(GTSAM_UNSTABLE_AVAILABLE) + print_config_flag(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") +endif() +print_config_flag(${GTSAM_DISABLE_TESTS_ON_INSTALL} "Tests excluded from all/install target ") +print_config_flag(${GTSAM_DISABLE_EXAMPLES_ON_INSTALL} "Examples excluded from all/install target ") string(TOUPPER "${CMAKE_BUILD_TYPE}" cmake_build_type_toupper) message(STATUS " Build type : ${CMAKE_BUILD_TYPE}") message(STATUS " C compilation flags : ${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${cmake_build_type_toupper}}") @@ -176,8 +218,7 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") -print_config_flag(${GTSAM_INSTALL_MATLAB_EXAMPLES} "Install matlab examples ") -print_config_flag(${GTSAM_INSTALL_MATLAB_TESTS} "Install matlab tests ") +print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") print_config_flag(${GTSAM_INSTALL_WRAP} "Install wrap utility ") message(STATUS "===============================================================") diff --git a/CppUnitLite/CMakeLists.txt b/CppUnitLite/CMakeLists.txt index 642e8e462..35ecd71f8 100644 --- a/CppUnitLite/CMakeLists.txt +++ b/CppUnitLite/CMakeLists.txt @@ -3,10 +3,14 @@ file(GLOB cppunitlite_headers "*.h") file(GLOB cppunitlite_src "*.cpp") -add_library(CppUnitLite STATIC ${cppunitlite_src}) +add_library(CppUnitLite STATIC ${cppunitlite_src} ${cppunitlite_headers}) +list(APPEND GTSAM_EXPORTED_TARGETS CppUnitLite) +set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) + +gtsam_assign_source_folders("${cppunitlite_headers};${cppunitlite_src}") # MSVC project structure option(GTSAM_INSTALL_CPPUNITLITE "Enable/Disable installation of CppUnitLite library" ON) if (GTSAM_INSTALL_CPPUNITLITE) install(FILES ${cppunitlite_headers} DESTINATION include/CppUnitLite) - install(TARGETS CppUnitLite ARCHIVE DESTINATION lib) + install(TARGETS CppUnitLite EXPORT GTSAM-exports ARCHIVE DESTINATION lib) endif(GTSAM_INSTALL_CPPUNITLITE) diff --git a/CppUnitLite/Failure.cpp b/CppUnitLite/Failure.cpp deleted file mode 100644 index d0c919165..000000000 --- a/CppUnitLite/Failure.cpp +++ /dev/null @@ -1,71 +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 - - * -------------------------------------------------------------------------- */ - - - -#include "Failure.h" - -#include -#include - - -Failure::Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - long theLineNumber, - const SimpleString& theCondition) -: message (theCondition), - testName (theTestName), - fileName (theFileName), - lineNumber (theLineNumber) -{ -} - -Failure::Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - const SimpleString& theCondition) -: message (theCondition), - testName (theTestName), - fileName (theFileName), - lineNumber (-1) -{ -} - - -Failure::Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - long theLineNumber, - const SimpleString& expected, - const SimpleString& actual) -: testName (theTestName), - fileName (theFileName), - lineNumber (theLineNumber) -{ - const char *part1 = "expected "; - const char *part3 = " but was: "; - - char *stage = new char [strlen (part1) - + expected.size () - + strlen (part3) - + actual.size () - + 1]; - - sprintf(stage, "%s%s%s%s", - part1, - expected.asCharString(), - part3, - actual.asCharString()); - - message = SimpleString(stage); - - delete stage; -} - - diff --git a/CppUnitLite/Failure.h b/CppUnitLite/Failure.h index 1f898f08c..93c99df12 100644 --- a/CppUnitLite/Failure.h +++ b/CppUnitLite/Failure.h @@ -21,37 +21,50 @@ /////////////////////////////////////////////////////////////////////////////// -#ifndef FAILURE_H -#define FAILURE_H - -#include "SimpleString.h" +#pragma once +#include class Failure { public: - Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - long theLineNumber, - const SimpleString& theCondition); + Failure (const std::string& theTestName, + const std::string& theFileName, + long theLineNumber, + const std::string& theCondition) + : message (theCondition), + testName (theTestName), + fileName (theFileName), + lineNumber (theLineNumber) + { + } - Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - long theLineNumber, - const SimpleString& expected, - const SimpleString& actual); - - Failure (const SimpleString& theTestName, - const SimpleString& theFileName, - const SimpleString& theCondition); + Failure (const std::string& theTestName, + const std::string& theFileName, + const std::string& theCondition) + : message (theCondition), + testName (theTestName), + fileName (theFileName), + lineNumber (-1) + { + } - SimpleString message; - SimpleString testName; - SimpleString fileName; + Failure (const std::string& theTestName, + const std::string& theFileName, + long theLineNumber, + const std::string& expected, + const std::string& actual) + : message("expected " + expected + " but was: " + actual), + testName (theTestName), + fileName (theFileName), + lineNumber (theLineNumber) + { + } + + std::string message; + std::string testName; + std::string fileName; long lineNumber; }; - - -#endif diff --git a/CppUnitLite/SimpleString.cpp b/CppUnitLite/SimpleString.cpp deleted file mode 100644 index 19dc7f258..000000000 --- a/CppUnitLite/SimpleString.cpp +++ /dev/null @@ -1,115 +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 - - * -------------------------------------------------------------------------- */ - - - -#include "SimpleString.h" -#include -#include -#include - - -static const int DEFAULT_SIZE = 20; - -SimpleString::SimpleString () -: buffer_(new char [1]) -{ - buffer_ [0] = '\0'; -} - - -SimpleString::SimpleString (const char *otherBuffer) -: buffer_ (new char [strlen (otherBuffer) + 1]) -{ - strcpy (buffer_, otherBuffer); -} - -SimpleString::SimpleString (const SimpleString& other) -{ - buffer_ = new char [other.size() + 1]; - strcpy(buffer_, other.buffer_); -} - - -SimpleString SimpleString::operator= (const SimpleString& other) -{ - delete buffer_; - buffer_ = new char [other.size() + 1]; - strcpy(buffer_, other.buffer_); - return *this; -} - -SimpleString SimpleString::operator+ (const SimpleString& other) -{ - SimpleString ret; - delete ret.buffer_; - ret.buffer_ = new char [size() + other.size() - 1]; - strcpy(ret.buffer_, buffer_); - strcat(ret.buffer_, other.buffer_); - return ret; -} - -char *SimpleString::asCharString () const -{ - return buffer_; -} - -int SimpleString::size() const -{ - return strlen (buffer_); -} - -SimpleString::~SimpleString () -{ - delete [] buffer_; -} - - -bool operator== (const SimpleString& left, const SimpleString& right) -{ - return !strcmp (left.asCharString (), right.asCharString ()); -} - - -SimpleString StringFrom (bool value) -{ - char buffer [sizeof ("false") + 1]; - sprintf (buffer, "%s", value ? "true" : "false"); - return SimpleString(buffer); -} - -SimpleString StringFrom (const char *value) -{ - return SimpleString(value); -} - -SimpleString StringFrom (long value) -{ - char buffer [DEFAULT_SIZE]; - sprintf (buffer, "%ld", value); - - return SimpleString(buffer); -} - -SimpleString StringFrom (double value) -{ - char buffer [DEFAULT_SIZE]; - sprintf (buffer, "%lg", value); - - return SimpleString(buffer); -} - -SimpleString StringFrom (const SimpleString& value) -{ - return SimpleString(value); -} - - diff --git a/CppUnitLite/SimpleString.h b/CppUnitLite/SimpleString.h deleted file mode 100644 index c454e5571..000000000 --- a/CppUnitLite/SimpleString.h +++ /dev/null @@ -1,57 +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 - - * -------------------------------------------------------------------------- */ - - -/////////////////////////////////////////////////////////////////////////////// -// -// SIMPLESTRING.H -// -// One of the design goals of CppUnitLite is to compilation with very old C++ -// compilers. For that reason, I've added a simple string class that provides -// only the operations needed in CppUnitLite. -// -/////////////////////////////////////////////////////////////////////////////// - -#ifndef SIMPLE_STRING -#define SIMPLE_STRING - - - -class SimpleString -{ - friend bool operator== (const SimpleString& left, const SimpleString& right); - -public: - SimpleString (); - SimpleString (const char *value); - SimpleString (const SimpleString& other); - ~SimpleString (); - - SimpleString operator= (const SimpleString& other); - SimpleString operator+ (const SimpleString& other); - - char *asCharString () const; - int size() const; - -private: - char *buffer_; -}; - - - -SimpleString StringFrom (bool value); -SimpleString StringFrom (const char *value); -SimpleString StringFrom (long value); -SimpleString StringFrom (double value); -SimpleString StringFrom (const SimpleString& other); - - -#endif diff --git a/CppUnitLite/Test.cpp b/CppUnitLite/Test.cpp index 1d9902b37..e6a2ad51f 100644 --- a/CppUnitLite/Test.cpp +++ b/CppUnitLite/Test.cpp @@ -10,21 +10,21 @@ * -------------------------------------------------------------------------- */ - #include "Test.h" #include "TestRegistry.h" #include "TestResult.h" #include "Failure.h" +#include -Test::Test (const SimpleString& testName) - : name_ (testName) +Test::Test (const std::string& testName) + : name_ (testName), next_(0), lineNumber_(-1), safeCheck_(true) { TestRegistry::addTest (this); } -Test::Test (const SimpleString& testName, const SimpleString& filename, long lineNumber, bool safeCheck = true) - : name_(testName), filename_(filename), lineNumber_(lineNumber), safeCheck_(safeCheck) +Test::Test (const std::string& testName, const std::string& filename, long lineNumber, bool safeCheck) + : name_(testName), next_(0), filename_(filename), lineNumber_(lineNumber), safeCheck_(safeCheck) { TestRegistry::addTest (this); } @@ -40,31 +40,31 @@ void Test::setNext(Test *test) next_ = test; } -bool Test::check(long expected, long actual, TestResult& result, const SimpleString& fileName, long lineNumber) +bool Test::check(long expected, long actual, TestResult& result, const std::string& fileName, long lineNumber) { if (expected == actual) return true; result.addFailure ( Failure ( name_, - StringFrom (__FILE__), + boost::lexical_cast (__FILE__), __LINE__, - StringFrom (expected), - StringFrom (actual))); + boost::lexical_cast (expected), + boost::lexical_cast (actual))); return false; } -bool Test::check(const SimpleString& expected, const SimpleString& actual, TestResult& result, const SimpleString& fileName, long lineNumber) +bool Test::check(const std::string& expected, const std::string& actual, TestResult& result, const std::string& fileName, long lineNumber) { if (expected == actual) return true; result.addFailure ( Failure ( name_, - StringFrom (__FILE__), + boost::lexical_cast (__FILE__), __LINE__, expected, actual)); diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index 22566131e..820ed48cf 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -23,17 +23,15 @@ #include -#include "SimpleString.h" +#include class TestResult; - - class Test { public: - Test (const SimpleString& testName); - Test (const SimpleString& testName, const SimpleString& filename, long lineNumber, bool safeCheck); + Test (const std::string& testName); + Test (const std::string& testName, const std::string& filename, long lineNumber, bool safeCheck); virtual ~Test() {}; virtual void run (TestResult& result) = 0; @@ -41,19 +39,19 @@ public: void setNext(Test *test); Test *getNext () const; - SimpleString getName() const {return name_;} - SimpleString getFilename() const {return filename_;} + std::string getName() const {return name_;} + std::string getFilename() const {return filename_;} long getLineNumber() const {return lineNumber_;} bool safe() const {return safeCheck_;} protected: - bool check (long expected, long actual, TestResult& result, const SimpleString& fileName, long lineNumber); - bool check (const SimpleString& expected, const SimpleString& actual, TestResult& result, const SimpleString& fileName, long lineNumber); + bool check (long expected, long actual, TestResult& result, const std::string& fileName, long lineNumber); + bool check (const std::string& expected, const std::string& actual, TestResult& result, const std::string& fileName, long lineNumber); - SimpleString name_; + std::string name_; Test *next_; - SimpleString filename_; + std::string filename_; long lineNumber_; /// This is the line line number of the test, rather than the a single check bool safeCheck_; @@ -102,17 +100,17 @@ protected: #define THROWS_EXCEPTION(condition)\ { try { condition; \ - result_.addFailure (Failure (name_, __FILE__,__LINE__, SimpleString("Didn't throw: ") + StringFrom(#condition))); \ + result_.addFailure (Failure (name_, __FILE__,__LINE__, std::string("Didn't throw: ") + boost::lexical_cast(#condition))); \ return; } \ catch (...) {} } #define CHECK_EXCEPTION(condition, exception_name)\ { try { condition; \ - result_.addFailure (Failure (name_, __FILE__,__LINE__, SimpleString("Didn't throw: ") + StringFrom(#condition))); \ + result_.addFailure (Failure (name_, __FILE__,__LINE__, std::string("Didn't throw: ") + boost::lexical_cast(#condition))); \ return; } \ - catch (exception_name& e) {} \ + catch (exception_name&) {} \ catch (...) { \ - result_.addFailure (Failure (name_, __FILE__,__LINE__, SimpleString("Wrong exception: ") + StringFrom(#condition) + StringFrom(", expected: ") + StringFrom(#exception_name))); \ + result_.addFailure (Failure (name_, __FILE__,__LINE__, std::string("Wrong exception: ") + boost::lexical_cast(#condition) + boost::lexical_cast(", expected: ") + boost::lexical_cast(#exception_name))); \ return; } } #define EQUALITY(expected,actual)\ @@ -120,21 +118,21 @@ protected: result_.addFailure(Failure(name_, __FILE__, __LINE__, #expected, #actual)); } #define CHECK_EQUAL(expected,actual)\ -{ if ((expected) == (actual)) return; result_.addFailure(Failure(name_, __FILE__, __LINE__, StringFrom(expected), StringFrom(actual))); } +{ if ((expected) == (actual)) return; result_.addFailure(Failure(name_, __FILE__, __LINE__, boost::lexical_cast(expected), boost::lexical_cast(actual))); } #define LONGS_EQUAL(expected,actual)\ { long actualTemp = actual; \ long expectedTemp = expected; \ if ((expectedTemp) != (actualTemp)) \ -{ result_.addFailure (Failure (name_, __FILE__, __LINE__, StringFrom(expectedTemp), \ -StringFrom(actualTemp))); return; } } +{ result_.addFailure (Failure (name_, __FILE__, __LINE__, boost::lexical_cast(expectedTemp), \ +boost::lexical_cast(actualTemp))); return; } } #define DOUBLES_EQUAL(expected,actual,threshold)\ { double actualTemp = actual; \ double expectedTemp = expected; \ if (fabs ((expectedTemp)-(actualTemp)) > threshold) \ { result_.addFailure (Failure (name_, __FILE__, __LINE__, \ -StringFrom((double)expectedTemp), StringFrom((double)actualTemp))); return; } } +boost::lexical_cast((double)expectedTemp), boost::lexical_cast((double)actualTemp))); return; } } /* EXPECTs: tests will continue running after a failure */ @@ -146,15 +144,15 @@ StringFrom((double)expectedTemp), StringFrom((double)actualTemp))); return; } } { long actualTemp = actual; \ long expectedTemp = expected; \ if ((expectedTemp) != (actualTemp)) \ -{ result_.addFailure (Failure (name_, __FILE__, __LINE__, StringFrom(expectedTemp), \ -StringFrom(actualTemp))); } } +{ result_.addFailure (Failure (name_, __FILE__, __LINE__, boost::lexical_cast(expectedTemp), \ +boost::lexical_cast(actualTemp))); } } #define EXPECT_DOUBLES_EQUAL(expected,actual,threshold)\ { double actualTemp = actual; \ double expectedTemp = expected; \ if (fabs ((expectedTemp)-(actualTemp)) > threshold) \ { result_.addFailure (Failure (name_, __FILE__, __LINE__, \ -StringFrom((double)expectedTemp), StringFrom((double)actualTemp))); } } +boost::lexical_cast((double)expectedTemp), boost::lexical_cast((double)actualTemp))); } } #define FAIL(text) \ diff --git a/CppUnitLite/TestRegistry.cpp b/CppUnitLite/TestRegistry.cpp index fa5295229..1d06b225c 100644 --- a/CppUnitLite/TestRegistry.cpp +++ b/CppUnitLite/TestRegistry.cpp @@ -17,7 +17,6 @@ #include "Failure.h" #include "TestResult.h" #include "TestRegistry.h" -#include "SimpleString.h" void TestRegistry::addTest (Test *test) { @@ -65,12 +64,12 @@ int TestRegistry::run (TestResult& result) // catch standard exceptions and derivatives result.addFailure( Failure(test->getName(), test->getFilename(), test->getLineNumber(), - SimpleString("Exception: ") + SimpleString(e.what()))); + std::string("Exception: ") + std::string(e.what()))); } catch (...) { // catch all other exceptions result.addFailure( Failure(test->getName(), test->getFilename(), test->getLineNumber(), - SimpleString("ExceptionThrown!"))); + "ExceptionThrown!")); } } else { diff --git a/CppUnitLite/TestResult.cpp b/CppUnitLite/TestResult.cpp index 3bc8a8ad5..a9e599989 100644 --- a/CppUnitLite/TestResult.cpp +++ b/CppUnitLite/TestResult.cpp @@ -32,16 +32,16 @@ void TestResult::addFailure (const Failure& failure) if (failure.lineNumber < 0) // allow for no line number fprintf (stdout, "%s%s%s%s\n", "Failure: \"", - failure.message.asCharString (), + failure.message.c_str (), "\" in ", - failure.fileName.asCharString ()); + failure.fileName.c_str ()); else fprintf (stdout, "%s%s%ld%s%s%s\n", - failure.fileName.asCharString(), // Format matches Eclipse error flagging + failure.fileName.c_str(), // Format matches Eclipse error flagging ":", failure.lineNumber, ": Failure: \"", - failure.message.asCharString(), + failure.message.c_str(), "\" "); failureCount++; diff --git a/README b/README index 8ec8a99f8..d7486c8b8 100644 --- a/README +++ b/README @@ -37,7 +37,7 @@ of licensing in LICENSE and as follows: - CCOLAMD 2.73: Tim Davis' constrained column approximate minimum degree ordering library - http://www.cise.ufl.edu/research/sparse - Licenced under LGPL v2.1, provided in gtsam/3rdparty/CCOLAMD/Doc/lesser.txt - - Eigen 3.0.5: General C++ matrix and linear algebra library + - Eigen 3.1: General C++ matrix and linear algebra library - Licenced under LGPL v3, provided in gtsam/3rdparty/Eigen/COPYING.LGPL @@ -51,17 +51,20 @@ Important Installation Notes 1) GTSAM requires the following libraries to be installed on your system: - - BOOST version 1.40 or greater (install through Linux repositories or MacPorts) + - BOOST version 1.43 or greater (install through Linux repositories or MacPorts) - Cmake version 2.6 or higher + - Support for XCode 4.3 command line tools on Mac requires CMake 2.8.8 or higher Tested compilers - GCC 4.2-4.7 - Clang 2.9-3.2 - OSX GCC 4.2 + - MSVC 2010, 2012 Tested systems: - Ubuntu 11.04, 11.10, 12.04 - MacOS 10.6, 10.7 + - Windows 7 2) GTSAM makes extensive use of debug assertions, and we highly recommend you work @@ -71,8 +74,8 @@ will run up to 10x faster in Release mode! See the end of this document for additional debugging tips. 3) -GTSAM has Doxygen documentation. To generate, run the the script -makedoc.sh. +GTSAM has Doxygen documentation. To generate, run 'make doc' from your +build directory. 4) The instructions below install the library to the default system install path and @@ -147,6 +150,12 @@ just the geometry tests, run "make check.geometry". Individual tests can be run appending ".run" to the name of the test, for example, to run testMatrix, run "make testMatrix.run". +MEX_COMMAND: Path to the mex compiler. Defaults to assume the path is included in your +shell's PATH environment variable. mex is installed with matlab at +$MATLABROOT/bin/mex + +$MATLABROOT can be found by executing the command 'matlabroot' in MATLAB + Debugging tips: Another useful debugging symbol is _GLIBCXX_DEBUG, which enables debug checks diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt new file mode 100644 index 000000000..4cb6d4a40 --- /dev/null +++ b/doc/CMakeLists.txt @@ -0,0 +1,79 @@ +# Doxygen documentation configuration +option(GTSAM_BUILD_DOCS "Enable/Disable building of doxygen docs" ON) + +# configure doxygen +option(GTSAM_BUILD_DOC_HTML "Enable/Disable doxygen HTML output" ON) +option(GTSAM_BUILD_DOC_LATEX "Enable/Disable doxygen LaTeX output" OFF) + +# add a target to generate API documentation with Doxygen +if (GTSAM_BUILD_DOCS) + # Convert configuration to YES/NO variables + if (GTSAM_BUILD_DOC_HTML) + set(GTSAM_BUILD_DOC_HTML_YN "YES") + else() + set(GTSAM_BUILD_DOC_HTML_YN "NO") + endif() + + if (GTSAM_BUILD_DOC_LATEX) + set(GTSAM_BUILD_DOC_LATEX_YN "YES") + else() + set(GTSAM_BUILD_DOC_LATEX_YN "NO") + endif() + + # GTSAM core subfolders + set(gtsam_doc_subdirs + gtsam/base + gtsam/geometry + gtsam/inference + gtsam/discrete + gtsam/linear + gtsam/nonlinear + gtsam/slam + gtsam + ) + + # Optional GTSAM_UNSTABLE subfolders + set(gtsam_unstable_doc_subdirs + gtsam_unstable/base + gtsam_unstable/discrete + gtsam_unstable/linear + gtsam_unstable/nonlinear + gtsam_unstable/slam + gtsam_unstable/dynamics + gtsam_unstable + ) + + # Build a list of folders to include depending on build options + set(doc_subdirs ${gtsam_doc_subdirs}) + if (GTSAM_BUILD_UNSTABLE) + list(APPEND doc_subdirs ${gtsam_unstable_doc_subdirs}) + endif() + if (GTSAM_BUILD_EXAMPLES) + list(APPEND doc_subdirs examples) + endif() + + # From subfolders, build a list with whitespace separation of paths + set(GTSAM_DOXYGEN_INPUT_PATHS "") + foreach(dir ${doc_subdirs}) + set(GTSAM_DOXYGEN_INPUT_PATHS "${GTSAM_DOXYGEN_INPUT_PATHS} ${PROJECT_SOURCE_DIR}/${dir}") + endforeach() + + # Generate Doxyfile + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile @ONLY) + + # Add target to actually build documentation as configured + add_custom_target(doc + ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMENT "Generating API documentation with Doxygen" VERBATIM + ) + + # Clean target + add_custom_target(doc_clean + COMMAND + cmake -E remove_directory ${CMAKE_CURRENT_SOURCE_DIR}/latex + COMMAND + cmake -E remove_directory ${CMAKE_CURRENT_SOURCE_DIR}/html + COMMENT "Removing Doxygen documentation" + ) +endif() diff --git a/Doxyfile b/doc/Doxyfile.in similarity index 99% rename from Doxyfile rename to doc/Doxyfile.in index d7dd6adff..f12e12217 100644 --- a/Doxyfile +++ b/doc/Doxyfile.in @@ -32,7 +32,7 @@ PROJECT_NAME = gtsam # This could be handy for archiving the generated documentation or # if some version control system is used. -PROJECT_NUMBER = 2.0.0 +PROJECT_NUMBER = @GTSAM_VERSION_MAJOR@.@GTSAM_VERSION_MINOR@.@GTSAM_VERSION_PATCH@ # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer @@ -52,7 +52,7 @@ PROJECT_LOGO = # If a relative path is entered, it will be relative to the location # where doxygen was started. If left blank the current directory will be used. -OUTPUT_DIRECTORY = doc +OUTPUT_DIRECTORY = . # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create # 4096 sub-directories (in 2 levels) under the output directory of each output @@ -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 @@ -638,19 +638,7 @@ WARN_LOGFILE = # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = gtsam/base \ - gtsam/geometry \ - gtsam/inference \ - gtsam/discrete \ - gtsam/linear \ - gtsam/nonlinear \ - gtsam -# gtsam/slam \ -# gtsam_unstable/slam \ -# gtsam_unstable/base \ -# gtsam_unstable/geometry \ -# gtsam_unstable/dynamics \ -# gtsam_unstable +INPUT = @GTSAM_DOXYGEN_INPUT_PATHS@ # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is @@ -880,7 +868,7 @@ IGNORE_PREFIX = # If the GENERATE_HTML tag is set to YES (the default) Doxygen will # generate HTML output. -GENERATE_HTML = YES +GENERATE_HTML = @GTSAM_BUILD_DOC_HTML_YN@ # The HTML_OUTPUT tag is used to specify where the HTML docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be @@ -1234,7 +1222,7 @@ SERVER_BASED_SEARCH = NO # If the GENERATE_LATEX tag is set to YES (the default) Doxygen will # generate Latex output. -GENERATE_LATEX = NO +GENERATE_LATEX = @GTSAM_BUILD_DOC_LATEX_YN@ # The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be diff --git a/DoxygenLayout.xml b/doc/DoxygenLayout.xml similarity index 100% rename from DoxygenLayout.xml rename to doc/DoxygenLayout.xml diff --git a/doc/LieGroups.lyx b/doc/LieGroups.lyx new file mode 100644 index 000000000..03116dbc9 --- /dev/null +++ b/doc/LieGroups.lyx @@ -0,0 +1,4065 @@ +#LyX 2.0 created this file. For more info see http://www.lyx.org/ +\lyxformat 413 +\begin_document +\begin_header +\textclass article +\use_default_options false +\begin_modules +theorems-std +\end_modules +\maintain_unincluded_children false +\language english +\language_package default +\inputencoding auto +\fontencoding global +\font_roman times +\font_sans default +\font_typewriter default +\font_default_family rmdefault +\use_non_tex_fonts false +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\default_output_format default +\output_sync 0 +\bibtex_command default +\index_command default +\paperfontsize 12 +\spacing single +\use_hyperref false +\papersize default +\use_geometry true +\use_amsmath 1 +\use_esint 0 +\use_mhchem 1 +\use_mathdots 1 +\cite_engine basic +\use_bibtopic false +\use_indices false +\paperorientation portrait +\suppress_date false +\use_refstyle 0 +\index Index +\shortcut idx +\color #008000 +\end_index +\leftmargin 1in +\topmargin 1in +\rightmargin 1in +\bottommargin 1in +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\paragraph_indentation default +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\html_math_output 0 +\html_css_as_file 0 +\html_be_strict false +\end_header + +\begin_body + +\begin_layout Title +Lie Groups for Beginners +\end_layout + +\begin_layout Author +Frank Dellaert +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\AAdd}[1]{\mathbf{\mathop{Ad}}{}_{#1}} +{\mathbf{\mathop{Ad}}{}_{#1}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2), 1 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}} +{\mathfrak{\mathbb{R}^{2}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2), 3 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3), 3 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathfrak{\mathbb{R}^{3}}} +{\mathfrak{\mathbb{R}^{3}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3),6 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathfrak{\mathbb{R}^{6}}} +{\mathfrak{\mathbb{R}^{6}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Aff(2),6 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Afftwo}{Aff(2)} +{Aff(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\afftwo}{\mathfrak{aff(2)}} +{\mathfrak{aff(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\aa}{a} +{a} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\ahat}{\hat{a}} +{\hat{a}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status collapsed + +\begin_layout Plain Layout +SL(3),8 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SLthree}{SL(3)} +{SL(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\slthree}{\mathfrak{sl(3)}} +{\mathfrak{sl(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\hh}{h} +{h} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\hhat}{\hat{h}} +{\hat{h}} +\end_inset + + +\end_layout + +\begin_layout Section +Motivation: Rigid Motions in the Plane +\end_layout + +\begin_layout Standard +We will start with a small example of a robot moving in a plane, parameterized + by a +\emph on +2D pose +\emph default + +\begin_inset Formula $(x,\, y,\,\theta)$ +\end_inset + +. + When we give it a small forward velocity +\begin_inset Formula $v_{x}$ +\end_inset + +, we know that the location changes as +\begin_inset Formula +\[ +\dot{x}=v_{x} +\] + +\end_inset + +The solution to this trivial differential equation is, with +\begin_inset Formula $x_{0}$ +\end_inset + + the initial +\begin_inset Formula $x$ +\end_inset + +-position of the robot, +\begin_inset Formula +\[ +x_{t}=x_{0}+v_{x}t +\] + +\end_inset + +A similar story holds for translation in the +\begin_inset Formula $y$ +\end_inset + + direction, and in fact for translations in general: +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0}+v_{x}t,\, y_{0}+v_{y}t,\,\theta_{0}) +\] + +\end_inset + +Similarly for rotation we have +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0},\, y_{0},\,\theta_{0}+\omega t) +\] + +\end_inset + +where +\begin_inset Formula $\omega$ +\end_inset + + is angular velocity, measured in +\begin_inset Formula $rad/s$ +\end_inset + + in counterclockwise direction. + +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/circular.pdf + +\end_inset + + +\begin_inset Caption + +\begin_layout Plain Layout +Robot moving along a circular trajectory. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +However, if we combine translation and rotation, the story breaks down! + We cannot write +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0}+v_{x}t,\, y_{0}+v_{y}t,\,\theta_{0}+\omega t) +\] + +\end_inset + +The reason is that, if we move the robot a tiny bit according to the velocity + vector +\begin_inset Formula $(v_{x},\, v_{y},\,\omega)$ +\end_inset + +, we have (to first order) +\begin_inset Formula +\[ +(x_{\delta},\, y_{\delta},\,\theta_{\delta})=(x_{0}+v_{x}\delta,\, y_{0}+v_{y}\delta,\,\theta_{0}+\omega\delta) +\] + +\end_inset + +but now the robot has rotated, and for the next incremental change, the + velocity vector would have to be rotated before it can be applied. + In fact, the robot will move on a +\emph on +circular +\emph default + trajectory. + +\end_layout + +\begin_layout Standard +The reason is that +\emph on +translation and rotation do not commute +\emph default +: if we rotate and then move we will end up in a different place than if + we moved first, then rotated. + In fact, someone once said (I forget who, kudos for who can track down + the exact quote): +\end_layout + +\begin_layout Quote +If rotation and translation commuted, we could do all rotations before leaving + home. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/n-steps.pdf + +\end_inset + + +\begin_inset Caption + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:n-step-program" + +\end_inset + +Approximating a circular trajectory with +\begin_inset Formula $n$ +\end_inset + + steps. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + +To make progress, we have to be more precise about how the robot behaves. + Specifically, let us define composition of two poses +\begin_inset Formula $T_{1}$ +\end_inset + + and +\begin_inset Formula $T_{2}$ +\end_inset + + as +\begin_inset Formula +\[ +T_{1}T_{2}=(x_{1},\, y_{1},\,\theta_{1})(x_{2},\, y_{2},\,\theta_{2})=(x_{1}+\cos\theta_{1}x_{2}-\sin\theta y_{2},\, y_{1}+\sin\theta_{1}x_{2}+\cos\theta_{1}y_{2},\,\theta_{1}+\theta_{2}) +\] + +\end_inset + +This is a bit clumsy, so we resort to a trick: embed the 2D poses in the + space of +\begin_inset Formula $3\times3$ +\end_inset + + matrices, so we can define composition as matrix multiplication: +\begin_inset Formula +\[ +T_{1}T_{2}=\left[\begin{array}{cc} +R_{1} & t_{1}\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R_{2} & t_{2}\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +R_{1}R_{2} & R_{1}t_{2}+t_{1}\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where the matrices +\begin_inset Formula $R$ +\end_inset + + are 2D rotation matrices defined as +\begin_inset Formula +\[ +R=\left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right] +\] + +\end_inset + +Now a +\begin_inset Quotes eld +\end_inset + +tiny +\begin_inset Quotes erd +\end_inset + + motion of the robot can be written as +\begin_inset Formula +\[ +T(\delta)=\left[\begin{array}{ccc} +\cos\omega\delta & -\sin\omega\delta & v_{x}\delta\\ +\sin\omega\delta & \cos\omega\delta & v_{y}\delta\\ +0 & 0 & 1 +\end{array}\right]\approx\left[\begin{array}{ccc} +1 & -\omega\delta & v_{x}\delta\\ +\omega\delta & 1 & v_{y}\delta\\ +0 & 0 & 1 +\end{array}\right]=I+\delta\left[\begin{array}{ccc} +0 & -\omega & v_{x}\\ +\omega & 0 & v_{y}\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +Let us define the +\emph on +2D twist +\emph default + vector +\begin_inset Formula $\xi=(v,\omega)$ +\end_inset + +, and the matrix above as +\begin_inset Formula +\[ +\xihat\define\left[\begin{array}{ccc} +0 & -\omega & v_{x}\\ +\omega & 0 & v_{y}\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +If we wanted +\begin_inset Formula $t$ +\end_inset + + to be large, we could split up +\begin_inset Formula $t$ +\end_inset + + into smaller timesteps, say +\begin_inset Formula $n$ +\end_inset + + of them, and compose them as follows: +\begin_inset Formula +\[ +T(t)\approx\left(I+\frac{t}{n}\xihat\right)\ldots\mbox{n times}\ldots\left(I+\frac{t}{n}\xihat\right)=\left(I+\frac{t}{n}\xihat\right)^{n} +\] + +\end_inset + +The result is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:n-step-program" + +\end_inset + +. +\end_layout + +\begin_layout Standard +Of course, the perfect solution would be obtained if we take +\begin_inset Formula $n$ +\end_inset + + to infinity: +\begin_inset Formula +\[ +T(t)=\lim_{n\rightarrow\infty}\left(I+\frac{t}{n}\xihat\right)^{n} +\] + +\end_inset + +For real numbers, this series is familiar and is actually a way to compute + the exponential function: +\begin_inset Formula +\[ +e^{x}=\lim_{n\rightarrow\infty}\left(1+\frac{x}{n}\right)^{n}=\sum_{k=0}^{\infty}\frac{x^{k}}{k!} +\] + +\end_inset + +The series can be similarly defined for square matrices, and the final result + is that we can write the motion of a robot along a circular trajectory, + resulting from the 2D twist +\begin_inset Formula $\xi=(v,\omega)$ +\end_inset + + +\begin_inset Formula $ $ +\end_inset + + as the +\emph on +matrix exponential +\emph default + of +\begin_inset Formula $\xihat$ +\end_inset + +: +\begin_inset Formula +\[ +T(t)=e^{t\xihat}\define\lim_{n\rightarrow\infty}\left(I+\frac{t}{n}\xihat\right)^{n}=\sum_{k=0}^{\infty}\frac{t^{k}}{k!}\xihat^{k} +\] + +\end_inset + +We call this mapping from 2D twists matrices +\begin_inset Formula $\xihat$ +\end_inset + + to 2D rigid transformations the +\emph on +exponential map. +\end_layout + +\begin_layout Standard +The above has all elements of Lie group theory. + We call the space of 2D rigid transformations, along with the composition + operation, the +\emph on +special Euclidean group +\emph default + +\begin_inset Formula $\SEtwo$ +\end_inset + +. + It is called a Lie group because it is simultaneously a topological group + and a manifold, which implies that the multiplication and the inversion + operations are smooth. + The space of 2D twists, together with a special binary operation to be + defined below, is called the Lie algebra +\begin_inset Formula $\setwo$ +\end_inset + + associated with +\begin_inset Formula $\SEtwo$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Basic Lie Group Concepts +\end_layout + +\begin_layout Standard +We now define the concepts illustrated above, introduce some notation, and + see what we can say in general. + After this we then introduce the most commonly used Lie groups and their + Lie algebras. +\end_layout + +\begin_layout Subsection +A Manifold and a Group +\end_layout + +\begin_layout Standard +A +\series bold +Lie group +\series default + +\begin_inset Formula $G$ +\end_inset + + is both a group +\emph on +and +\emph default + a manifold that possesses a smooth group operation. + Associated with it is a +\series bold +Lie Algebra +\series default + +\begin_inset Formula $\gg$ +\end_inset + + which, loosely speaking, can be identified with the tangent space at the + identity and completely defines how the groups behaves around the identity. + There is a mapping from +\begin_inset Formula $\gg$ +\end_inset + + back to +\begin_inset Formula $G$ +\end_inset + +, called the +\series bold +exponential map +\series default + +\begin_inset Formula +\[ +\exp:\gg\rightarrow G +\] + +\end_inset + +which is typically a many-to-one mapping. + The corresponding inverse can be define locally around the origin and hence + is a +\begin_inset Quotes eld +\end_inset + +logarithm +\begin_inset Quotes erd +\end_inset + + +\begin_inset Formula +\[ +\log:G\rightarrow\gg +\] + +\end_inset + +that maps elements in a neighborhood of +\begin_inset Formula $id$ +\end_inset + + in G to an element in +\begin_inset Formula $\gg$ +\end_inset + +. +\end_layout + +\begin_layout Standard +An important family of Lie groups are the matrix Lie groups, whose elements + are +\begin_inset Formula $n\times n$ +\end_inset + + invertible matrices. + The set of all such matrices, together with the matrix multiplication, + is called the general linear group +\begin_inset Formula $GL(n)$ +\end_inset + + of dimension +\begin_inset Formula $n$ +\end_inset + +, and any closed subgroup of it is a +\series bold + matrix Lie group +\series default +. + Most if not all Lie groups we are interested in will be matrix Lie groups. +\end_layout + +\begin_layout Subsection +Lie Algebra +\end_layout + +\begin_layout Standard +The Lie Algebra +\begin_inset Formula $\gg$ +\end_inset + + is called an algebra because it is endowed with a binary operation, the + +\series bold +Lie bracket +\series default + +\begin_inset Formula $[X,Y]$ +\end_inset + +, the properties of which are closely related to the group operation of + +\begin_inset Formula $G$ +\end_inset + +. + For example, for algebras associated with matrix Lie groups, the Lie bracket + is given by +\begin_inset Formula $[A,B]\define AB-BA$ +\end_inset + +. +\end_layout + +\begin_layout Standard +The relationship of the Lie bracket to the group operation is as follows: + for commutative Lie groups vector addition +\begin_inset Formula $X+Y$ +\end_inset + + in +\begin_inset Formula $\gg$ +\end_inset + + mimicks the group operation. + For example, if we have +\begin_inset Formula $Z=X+Y$ +\end_inset + + in +\begin_inset Formula $\gg$ +\end_inset + +, when mapped backed to +\begin_inset Formula $G$ +\end_inset + + via the exponential map we obtain +\begin_inset Formula +\[ +e^{Z}=e^{X+Y}=e^{X}e^{Y} +\] + +\end_inset + +However, this does +\emph on +not +\emph default + hold for non-commutative Lie groups: +\begin_inset Formula +\[ +Z=\log(e^{X}e^{Y})\neq X+Y +\] + +\end_inset + +Instead, +\begin_inset Formula $Z$ +\end_inset + + can be calculated using the Baker-Campbell-Hausdorff (BCH) formula +\begin_inset CommandInset citation +LatexCommand cite +key "Hall00book" + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Baker–Campbell–Hausdorff_formula +\end_layout + +\end_inset + +: +\begin_inset Formula +\[ +Z=X+Y+[X,Y]/2+[X-Y,[X,Y]]/12-[Y,[X,[X,Y]]]/24+\ldots +\] + +\end_inset + +For commutative groups the bracket is zero and we recover +\begin_inset Formula $Z=X+Y$ +\end_inset + +. + For non-commutative groups we can use the BCH formula to approximate it. +\end_layout + +\begin_layout Subsection +Exponential Coordinates +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix Lie groups, as a vector space the Lie algebra +\begin_inset Formula $\gg$ +\end_inset + + is isomorphic to +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, and we can define the hat operator +\begin_inset CommandInset citation +LatexCommand cite +after "page 41" +key "Murray94book" + +\end_inset + +, +\begin_inset Formula +\[ +\hat{}:x\in\mathbb{R}^{n}\rightarrow\xhat\in\gg +\] + +\end_inset + +which maps +\begin_inset Formula $n$ +\end_inset + +-vectors +\begin_inset Formula $x\in\mathbb{R}^{n}$ +\end_inset + + to elements of +\begin_inset Formula $\gg$ +\end_inset + +. + In the case of matrix Lie groups, the elements +\begin_inset Formula $\xhat$ +\end_inset + + of +\begin_inset Formula $\gg$ +\end_inset + + are also +\begin_inset Formula $n\times n$ +\end_inset + + matrices, and the map is given by +\begin_inset Formula +\begin{equation} +\xhat=\sum_{i=1}^{n}x_{i}G^{i}\label{eq:generators} +\end{equation} + +\end_inset + +where the +\begin_inset Formula $G^{i}$ +\end_inset + + are +\begin_inset Formula $n\times n$ +\end_inset + + matrices known as Lie group generators. + The meaning of the map +\begin_inset Formula $x\rightarrow\xhat$ +\end_inset + + will depend on the group +\begin_inset Formula $G$ +\end_inset + + and will generally have an intuitive interpretation. +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +An important concept is that of a group element acting on an element of + a manifold +\begin_inset Formula $M$ +\end_inset + +. + For example, 2D rotations act on 2D points, 3D rotations act on 3D points, + etc. + In particular, a +\series bold +left action +\series default + of +\begin_inset Formula $G$ +\end_inset + + on +\begin_inset Formula $M$ +\end_inset + + is defined as a smooth map +\begin_inset Formula $\Phi:G\times M\rightarrow M$ +\end_inset + + such that +\begin_inset CommandInset citation +LatexCommand cite +after "Appendix A" +key "Murray94book" + +\end_inset + +: +\end_layout + +\begin_layout Enumerate +The identity element +\begin_inset Formula $e$ +\end_inset + + has no effect, i.e., +\begin_inset Formula $\Phi(e,p)=p$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +Composing two actions can be combined into one action: +\begin_inset Formula $\Phi(g,\Phi(h,p))=\Phi(gh,p)$ +\end_inset + + +\end_layout + +\begin_layout Standard +The (usual) action of an +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix group +\begin_inset Formula $G$ +\end_inset + + is matrix-vector multiplication on +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, +\begin_inset Formula +\[ +q=Ap +\] + +\end_inset + +with +\begin_inset Formula $p,q\in\mathbb{R}^{n}$ +\end_inset + + and +\begin_inset Formula $A\in G\subseteq GL(n)$ +\end_inset + +. + +\end_layout + +\begin_layout Subsection +The Adjoint Map and Adjoint Representation +\end_layout + +\begin_layout Standard +Suppose a point +\begin_inset Formula $p$ +\end_inset + + is specified as +\begin_inset Formula $p'$ +\end_inset + + in the frame +\begin_inset Formula $T$ +\end_inset + +, i.e., +\begin_inset Formula $p'=Tp$ +\end_inset + +, where +\begin_inset Formula $T$ +\end_inset + + transforms from the global coordinates +\begin_inset Formula $p$ +\end_inset + + to the local frame +\begin_inset Formula $p'$ +\end_inset + +. + To apply an action +\begin_inset Formula $A$ +\end_inset + + we first need to undo +\begin_inset Formula $T$ +\end_inset + +, then apply +\begin_inset Formula $A$ +\end_inset + +, and then transform the result back to +\begin_inset Formula $T$ +\end_inset + +: +\begin_inset Formula +\[ +q'=TAT^{-1}p' +\] + +\end_inset + +The matrix +\begin_inset Formula $TAT^{-1}$ +\end_inset + + is said to be conjugate to +\begin_inset Formula $A$ +\end_inset + +, and this is a central element of group theory. +\end_layout + +\begin_layout Standard +In general, the +\series bold +adjoint map +\series default + +\begin_inset Formula $\AAdd g$ +\end_inset + + maps a group element +\begin_inset Formula $a\in G$ +\end_inset + + to its +\series bold +conjugate +\series default + +\begin_inset Formula $gag^{-1}$ +\end_inset + + by +\begin_inset Formula $g$ +\end_inset + +. + This map captures conjugacy in the group +\begin_inset Formula $G$ +\end_inset + +, but there is an equivalent notion in the Lie algebra +\begin_inset Formula $\mathfrak{\gg}$ +\end_inset + +, +\begin_inset Note Note +status open + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Exponential_map +\end_layout + +\end_inset + + +\begin_inset Formula +\[ +\AAdd ge^{\xhat}=g\exp\left(\xhat\right)g^{-1}=\exp(\Ad g{\xhat}) +\] + +\end_inset + +where +\begin_inset Formula $\Ad g:\gg\rightarrow\mathfrak{\gg}$ +\end_inset + + is a map parameterized by a group element +\begin_inset Formula $g$ +\end_inset + +, and is called the +\emph on +adjoint representation +\emph default +. + The intuitive explanation is that a change +\begin_inset Formula $\exp\left(\xhat\right)$ +\end_inset + + defined around the origin, but applied at the group element +\begin_inset Formula $g$ +\end_inset + +, can be written in one step by taking the adjoint +\begin_inset Formula $\Ad g{\xhat}$ +\end_inset + + of +\begin_inset Formula $\xhat$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +In the special case of matrix Lie groups the adjoint can be written as +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Adjoint_representation_of_a_Lie_group +\end_layout + +\end_inset + + +\begin_inset Formula +\[ +\Ad T{\xhat}\define T\xhat T^{-1} +\] + +\end_inset + +and hence we have +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +Te^{\xhat}T^{-1}=e^{T\xhat T^{-1}}\label{eq:matrixAdjoint} +\end{equation} + +\end_inset + +where both +\begin_inset Formula $T\in G$ +\end_inset + + and +\begin_inset Formula $\xhat\in\gg$ +\end_inset + + are +\begin_inset Formula $n\times n$ +\end_inset + + matrices for an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rotations +\end_layout + +\begin_layout Standard +We first look at a very simple group, the 2D rotations. +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SOtwo$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(2)$ +\end_inset + + of +\begin_inset Formula $2\times2$ +\end_inset + + invertible matrices. + Its Lie algebra +\begin_inset Formula $\sotwo$ +\end_inset + + is the vector space of +\begin_inset Formula $2\times2$ +\end_inset + + skew-symmetric matrices. + Since +\begin_inset Formula $\SOtwo$ +\end_inset + + is a one-dimensional manifold, +\begin_inset Formula $\sotwo$ +\end_inset + + is isomorphic to +\begin_inset Formula $\mathbb{R}$ +\end_inset + + and we define +\begin_inset Formula +\[ +\hat{}:\mathbb{R}\rightarrow\sotwo +\] + +\end_inset + + +\begin_inset Formula +\[ +\hat{}:\omega\rightarrow\what=\skew{\omega} +\] + +\end_inset + +which maps the angle +\begin_inset Formula $\omega$ +\end_inset + + to the +\begin_inset Formula $2\times2$ +\end_inset + + skew-symmetric matrix +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\skew{\omega}$ +\end_inset + +: +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + +\begin_inset Formula +\[ +\skew{\omega}=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right] +\] + +\end_inset + +The exponential map can be computed in closed form as +\begin_inset Formula +\[ +e^{\skew{\omega}}=\left[\begin{array}{cc} +\cos\omega & -\sin\omega\\ +\sin\omega & \cos\omega +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:Diagonalized2D" + +\end_inset + +Diagonalized Form +\end_layout + +\begin_layout Standard +The matrix +\begin_inset Formula $\skew 1$ +\end_inset + + can be diagonalized (see +\begin_inset CommandInset citation +LatexCommand cite +key "Hall00book" + +\end_inset + +) with eigenvalues +\begin_inset Formula $-i$ +\end_inset + + and +\begin_inset Formula $i$ +\end_inset + + , and eigenvectors +\begin_inset Formula $\left[\begin{array}{c} +1\\ +i +\end{array}\right]$ +\end_inset + + and +\begin_inset Formula $\left[\begin{array}{c} +i\\ +1 +\end{array}\right]$ +\end_inset + + . + Readers familiar with projective geometry will recognize these as the circular + points when promoted to homogeneous coordinates. + In particular: +\begin_inset Formula +\[ +\skew{\omega}=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]=\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]\left[\begin{array}{cc} +-i\omega & 0\\ +0 & i\omega +\end{array}\right]\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]^{-1} +\] + +\end_inset + +and hence +\begin_inset Formula +\[ +e^{\skew{\omega}}=\frac{1}{2}\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{-i\omega} & 0\\ +0 & e^{i\omega} +\end{array}\right]\left[\begin{array}{cc} +1 & -i\\ +-i & 1 +\end{array}\right]=\left[\begin{array}{cc} +\cos\omega & -\sin\omega\\ +\sin\omega & \cos\omega +\end{array}\right] +\] + +\end_inset + +where the latter can be shown using +\begin_inset Formula $e^{i\omega}=\cos\omega+i\sin\omega$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Adjoint +\end_layout + +\begin_layout Standard +The adjoint for +\begin_inset Formula $\sotwo$ +\end_inset + + is trivially equal to the identity, as is the case for +\emph on +all +\emph default + commutative groups: +\begin_inset Formula +\begin{eqnarray*} +\Ad R\what & = & \left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right]\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]\left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right]^{T}\\ + & = & \omega\left[\begin{array}{cc} +-\sin\theta & -\cos\theta\\ +\cos\theta & -\sin\theta +\end{array}\right]\left[\begin{array}{cc} +\cos\theta & \sin\theta\\ +-\sin\theta & \cos\theta +\end{array}\right]=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +i.e., +\begin_inset Formula +\[ +\Ad R\what=\what +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + + the vector space is +\begin_inset Formula $\Rtwo$ +\end_inset + +, and the group action corresponds to rotating a point +\begin_inset Formula +\[ +q=Rp +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\omega$ +\end_inset + + would do: +\begin_inset Formula +\[ +q(\text{\omega})=Re^{\skew{\omega}}p +\] + +\end_inset + +For small angles +\begin_inset Formula $\omega$ +\end_inset + + we have +\begin_inset Formula +\[ +e^{\skew{\omega}}\approx\skew{\omega}=\omega\skew 1 +\] + +\end_inset + +where +\begin_inset Formula $\skew 1$ +\end_inset + + acts like a restricted +\begin_inset Quotes eld +\end_inset + +cross product +\begin_inset Quotes erd +\end_inset + + in the plane on points: +\begin_inset Formula +\begin{equation} +\skew 1\left[\begin{array}{c} +x\\ +y +\end{array}\right]=R_{\pi/2}\left[\begin{array}{c} +x\\ +y +\end{array}\right]=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]\label{eq:RestrictedCross} +\end{equation} + +\end_inset + +Hence the derivative of the action is given as +\begin_inset Formula +\[ +\deriv{q(\omega)}{\omega}=R\deriv{}{\omega}\left(e^{\skew{\omega}}p\right)=R\deriv{}{\omega}\left(\omega\skew 1p\right)=RH_{p} +\] + +\end_inset + +where +\begin_inset Formula $H_{p}$ +\end_inset + + is a +\begin_inset Formula $2\times1$ +\end_inset + + matrix that depends on +\begin_inset Formula $p$ +\end_inset + +: +\begin_inset Formula +\[ +H_{p}\define\skew 1p=\left[\begin{array}{c} +-p_{y}\\ +p_{x} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rigid Transformations +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SEtwo$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices of the form +\begin_inset Formula +\[ +T\define\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $R\in\SOtwo$ +\end_inset + + is a rotation matrix and +\begin_inset Formula $t\in\Rtwo$ +\end_inset + + is a translation vector. + +\begin_inset Formula $\SEtwo$ +\end_inset + + is the +\emph on +semi-direct product +\emph default + of +\begin_inset Formula $\Rtwo$ +\end_inset + + by +\begin_inset Formula $SO(2)$ +\end_inset + +, written as +\begin_inset Formula $\SEtwo=\Rtwo\rtimes\SOtwo$ +\end_inset + +. + In particular, any element +\begin_inset Formula $T$ +\end_inset + + of +\begin_inset Formula $\SEtwo$ +\end_inset + + can be written as +\begin_inset Formula +\[ +T=\left[\begin{array}{cc} +0 & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R & 0\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +and they compose as +\begin_inset Formula +\[ +T_{1}T_{2}=\left[\begin{array}{cc} +R_{1} & t_{1}\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R_{2} & t_{2}\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +R_{1}R_{2} & R_{1}t_{2}+t_{1}\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +Hence, an alternative way of writing down elements of +\begin_inset Formula $\SEtwo$ +\end_inset + + is as the ordered pair +\begin_inset Formula $(R,\, t)$ +\end_inset + +, with composition defined a +\begin_inset Formula +\[ +(R_{1},\, t_{1})(R_{2},\, t_{2})=(R_{1}R_{2},\, R{}_{1}t_{2}+t_{1}) +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +The corresponding Lie algebra +\begin_inset Formula $\setwo$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + twists +\begin_inset Formula $\xihat$ +\end_inset + + parameterized by the +\emph on +twist coordinates +\emph default + +\begin_inset Formula $\xi\in\Rthree$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +\xi\define\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]\rightarrow\xihat\define\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + +Note we think of robots as having a pose +\begin_inset Formula $(x,y,\theta)$ +\end_inset + + and hence I reserved the first two components for translation and the last + for rotation. + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +The corresponding Lie group generators are +\begin_inset Formula +\[ +G^{x}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{y}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{\theta}=\left[\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Applying the exponential map to a twist +\begin_inset Formula $\xi$ +\end_inset + + yields a screw motion yielding an element in +\begin_inset Formula $\SEtwo$ +\end_inset + +: +\begin_inset Formula +\[ +T=e^{\xihat}=\left(e^{\skew{\omega}},(I-e^{\skew{\omega}})\frac{v^{\perp}}{\omega}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +The adjoint is +\begin_inset Formula +\begin{eqnarray} +\Ad T{\xihat} & = & T\xihat T^{-1}\nonumber \\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{cc} +\skew{\omega} & -\skew{\omega}t+Rv\\ +0 & 0 +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{cc} +\skew{\omega} & Rv-\omega R_{\pi/2}t\\ +0 & 0 +\end{array}\right]\label{eq:adjointSE2} +\end{eqnarray} + +\end_inset + +From this we can express the Adjoint map in terms of plane twist coordinates: +\begin_inset Formula +\[ +\left[\begin{array}{c} +v'\\ +\omega' +\end{array}\right]=\left[\begin{array}{cc} +R & -R_{\pi/2}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEtwo$ +\end_inset + + on 2D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{3}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +Analoguous to +\begin_inset Formula $\SEthree$ +\end_inset + +, we can compute a velocity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + in the local +\begin_inset Formula $T$ +\end_inset + + frame: +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\skew{\omega}p+v\\ +0 +\end{array}\right] +\] + +\end_inset + +By only taking the top two rows, we can write this as a velocity in +\begin_inset Formula $\Rtwo$ +\end_inset + +, as the product of a +\begin_inset Formula $2\times3$ +\end_inset + + matrix +\begin_inset Formula $H_{p}$ +\end_inset + + that acts upon the exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + directly: +\begin_inset Formula +\[ +\skew{\omega}p+v=v+R_{\pi/2}p\omega=\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]=H_{p}\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rotations +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SOthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices. + Its Lie algebra +\begin_inset Formula $\sothree$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + skew-symmetric matrices +\begin_inset Formula $\what$ +\end_inset + +. + Since +\begin_inset Formula $\SOthree$ +\end_inset + + is a three-dimensional manifold, +\begin_inset Formula $\sothree$ +\end_inset + + is isomorphic to +\begin_inset Formula $\Rthree$ +\end_inset + + and we define the map +\begin_inset Formula +\[ +\hat{}:\Rthree\rightarrow\sothree +\] + +\end_inset + + +\begin_inset Formula +\[ +\hat{}:\omega\rightarrow\what=\Skew{\omega} +\] + +\end_inset + +which maps 3-vectors +\begin_inset Formula $\omega$ +\end_inset + + to skew-symmetric matrices +\begin_inset Formula $\Skew{\omega}$ +\end_inset + + : +\begin_inset Formula +\[ +\Skew{\omega}=\left[\begin{array}{ccc} +0 & -\omega_{z} & \omega_{y}\\ +\omega_{z} & 0 & -\omega_{x}\\ +-\omega_{y} & \omega_{x} & 0 +\end{array}\right]=\omega_{x}G^{x}+\omega_{y}G^{y}+\omega_{z}G^{z} +\] + +\end_inset + +Here the matrices +\begin_inset Formula $G^{i}$ +\end_inset + + are the generators for +\begin_inset Formula $\SOthree$ +\end_inset + +, +\begin_inset Formula +\[ +G^{x}=\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & -1\\ +0 & 1 & 0 +\end{array}\right)\mbox{}G^{y}=\left(\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +-1 & 0 & 0 +\end{array}\right)\mbox{ }G^{z}=\left(\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + +corresponding to a rotation around +\begin_inset Formula $X$ +\end_inset + +, +\begin_inset Formula $Y$ +\end_inset + +, and +\begin_inset Formula $Z$ +\end_inset + +, respectively. + The Lie bracket +\begin_inset Formula $[x,y]$ +\end_inset + + in +\begin_inset Formula $\sothree$ +\end_inset + + corresponds to the cross product +\begin_inset Formula $x\times y$ +\end_inset + + in +\begin_inset Formula $\Rthree$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Hence, for every +\begin_inset Formula $3$ +\end_inset + +-vector +\begin_inset Formula $\omega$ +\end_inset + + there is a corresponding rotation matrix +\begin_inset Formula +\[ +R=e^{\Skew{\omega}} +\] + +\end_inset + +which defines a canonical parameterization of +\begin_inset Formula $\SOthree$ +\end_inset + +, with +\begin_inset Formula $\omega$ +\end_inset + + known as the canonical or exponential coordinates. + It is equivalent to the axis-angle representation for rotations, where + the unit vector +\begin_inset Formula $\omega/\theta$ +\end_inset + + defines the rotation axis, and its magnitude the amount of rotation +\begin_inset Formula $\theta$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +The exponential map can be computed in closed form using +\series bold +Rodrigues' formula +\series default + +\begin_inset CommandInset citation +LatexCommand cite +after "page 28" +key "Murray94book" + +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +e^{\what}=I+\frac{\sin\theta}{\theta}\what+\frac{1\text{−}\cos\theta}{\theta^{2}}\what^{2}\label{eq:Rodrigues} +\end{equation} + +\end_inset + +where +\begin_inset Formula $\what^{2}=\omega\omega^{T}-I$ +\end_inset + +, with +\begin_inset Formula $\omega\omega^{T}$ +\end_inset + + the outer product of +\begin_inset Formula $\omega$ +\end_inset + +. + Hence, a slightly more efficient variant is +\begin_inset Formula +\begin{equation} +e^{\what}=\left(\cos\theta\right)I+\frac{\sin\theta}{\theta}\what+\frac{1\text{−}cos\theta}{\theta^{2}}\omega\omega^{T}\label{eq:Rodrigues2} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Diagonalized Form +\end_layout + +\begin_layout Standard +Because a 3D rotation +\begin_inset Formula $R$ +\end_inset + + leaves the axis +\begin_inset Formula $\omega$ +\end_inset + + unchanged, +\begin_inset Formula $R$ +\end_inset + + can be diagonalized as +\begin_inset Formula +\[ +R=C\left(\begin{array}{ccc} +e^{-i\theta} & 0 & 0\\ +0 & e^{i\theta} & 0\\ +0 & 0 & 1 +\end{array}\right)C^{-1} +\] + +\end_inset + +with +\begin_inset Formula $C=\left(\begin{array}{ccc} +c_{1} & c_{2} & \omega/\theta\end{array}\right)$ +\end_inset + +, where +\begin_inset Formula $c_{1}$ +\end_inset + + and +\begin_inset Formula $c_{2}$ +\end_inset + + are the complex eigenvectors corresponding to the 2D rotation around +\begin_inset Formula $\omega$ +\end_inset + +. + This also means that, by +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:matrixAdjoint" + +\end_inset + +, +\begin_inset Formula +\[ +\hat{\omega}=C\left(\begin{array}{ccc} +-i\theta & 0 & 0\\ +0 & i\theta & 0\\ +0 & 0 & 0 +\end{array}\right)C^{-1} +\] + +\end_inset + +In this case, +\begin_inset Formula $C$ +\end_inset + + has complex columns, but we also have +\begin_inset Formula +\begin{equation} +\hat{\omega}=B\left(\begin{array}{ccc} +0 & -\theta & 0\\ +\theta & 0 & 0\\ +0 & 0 & 0 +\end{array}\right)B^{T}\label{eq:OmegaDecomposed} +\end{equation} + +\end_inset + +with +\begin_inset Formula $B=\left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)$ +\end_inset + +, where +\begin_inset Formula $b_{1}$ +\end_inset + + and +\begin_inset Formula $b_{2}$ +\end_inset + + form a basis for the 2D plane through the origin and perpendicular to +\begin_inset Formula $\omega$ +\end_inset + +. + Clearly, from Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Diagonalized2D" + +\end_inset + +, we have +\begin_inset Formula +\[ +c_{1}=B\left(\begin{array}{c} +1\\ +i\\ +0 +\end{array}\right)\mbox{\,\,\,\ and\,\,\,\,\,}c_{2}=B\left(\begin{array}{c} +i\\ +1\\ +0 +\end{array}\right) +\] + +\end_inset + +and when we exponentiate +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:OmegaDecomposed" + +\end_inset + + we expose the 2D rotation around the axis +\begin_inset Formula $\omega/\theta$ +\end_inset + + with magnitude +\begin_inset Formula $\theta$ +\end_inset + +: +\begin_inset Formula +\[ +R=B\left(\begin{array}{ccc} +\cos\theta & -\sin\theta & 0\\ +\sin\theta & \cos\theta & 0\\ +0 & 0 & 1 +\end{array}\right)B^{T} +\] + +\end_inset + +The latter form for +\begin_inset Formula $R$ +\end_inset + + can be used to prove Rodrigues' formula. + Expanding the above, we get +\begin_inset Formula +\[ +R=\left(\cos\theta\right)\left(b_{1}b_{1}^{T}+b_{2}b_{2}^{T}\right)+\left(\sin\theta\right)\left(b_{2}b_{1}^{T}-b_{1}b_{2}^{T}\right)+\omega\omega^{T}/\theta^{2} +\] + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +\begin_inset Formula +\begin{eqnarray*} +R & = & \left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)\left(\begin{array}{ccc} +\cos\theta & -\sin\theta & 0\\ +\sin\theta & \cos\theta & 0\\ +0 & 0 & 1 +\end{array}\right)\left(\begin{array}{c} +b_{1}^{T}\\ +b_{2}^{T}\\ +\omega^{T}/\theta +\end{array}\right)\\ + & = & \left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)\left(\begin{array}{c} +b_{1}^{T}\cos\theta-b_{2}^{T}\sin\theta\\ +b_{1}^{T}\sin\theta+b_{2}^{T}\cos\theta\\ +\omega^{T}/\theta +\end{array}\right)\\ + & = & b_{1}b_{1}^{T}\cos\theta-b_{1}b_{2}^{T}\sin\theta+b_{2}b_{1}^{T}\sin\theta+b_{2}b_{2}^{T}\cos\theta+\omega\omega^{T}/\theta^{2} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\end_inset + +Because +\begin_inset Formula $B$ +\end_inset + + is a rotation matrix, we have +\begin_inset Formula $BB^{T}=b_{1}b_{1}^{T}+b_{2}b_{2}^{T}+\omega\omega^{T}/\theta^{2}=I$ +\end_inset + +, and using +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:OmegaDecomposed" + +\end_inset + + it is easy to show that +\begin_inset Formula $b_{2}b_{1}^{T}-b_{1}b_{2}^{T}=\hat{\omega}/\theta$ +\end_inset + +, hence +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit + +\begin_inset Formula +\[ +R=\left(\cos\theta\right)(I-\omega\omega^{T}/\theta^{2})+\left(\sin\theta\right)\left(\hat{\omega}/\theta\right)+\omega\omega^{T}/\theta^{2} +\] + +\end_inset + +which is equivalent to +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Rodrigues2" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +For rotation matrices +\begin_inset Formula $R$ +\end_inset + + we can prove the following identity (see +\begin_inset CommandInset ref +LatexCommand vref +reference "proof1" + +\end_inset + +): +\begin_inset Formula +\begin{equation} +R\Skew{\omega}R^{T}=\Skew{R\omega}\label{eq:property1} +\end{equation} + +\end_inset + +Hence, given property +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:property1" + +\end_inset + +, the adjoint map for +\begin_inset Formula $\sothree$ +\end_inset + + simplifies to +\begin_inset Formula +\[ +\Ad R{\Skew{\omega}}=R\Skew{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +and this can be expressed in exponential coordinates simply by rotating + the axis +\begin_inset Formula $\omega$ +\end_inset + + to +\begin_inset Formula $R\omega$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +As an example, to apply an axis-angle rotation +\begin_inset Formula $\omega$ +\end_inset + + to a point +\begin_inset Formula $p$ +\end_inset + + in the frame +\begin_inset Formula $R$ +\end_inset + +, we could: +\end_layout + +\begin_layout Enumerate +First transform +\begin_inset Formula $p$ +\end_inset + + back to the world frame, apply +\begin_inset Formula $\omega$ +\end_inset + +, and then rotate back: +\begin_inset Formula +\[ +q=Re^{\Skew{\omega}}R^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Enumerate +Immediately apply the transformed axis-angle transformation +\begin_inset Formula $\Ad R{\Skew{\omega}}=\Skew{R\omega}$ +\end_inset + +: +\begin_inset Formula +\[ +q=e^{\Skew{R\omega}}p +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOthree$ +\end_inset + + the vector space is +\begin_inset Formula $\Rthree$ +\end_inset + +, and the group action corresponds to rotating a point +\begin_inset Formula +\[ +q=Rp +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\omega$ +\end_inset + + would do: +\begin_inset Formula +\[ +q(\omega)=Re^{\Skew{\omega}}p +\] + +\end_inset + +hence the derivative is: +\begin_inset Formula +\[ +\deriv{q(\omega)}{\omega}=R\deriv{}{\omega}\left(e^{\Skew{\omega}}p\right)=R\deriv{}{\omega}\left(\Skew{\omega}p\right)=R\Skew{-p} +\] + +\end_inset + +To show the last equality note that +\begin_inset Formula +\[ +\Skew{\omega}p=\omega\times p=-p\times\omega=\Skew{-p}\omega +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rigid Transformations +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SEthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(4)$ +\end_inset + + of +\begin_inset Formula $4\times4$ +\end_inset + + invertible matrices of the form +\begin_inset Formula +\[ +T\define\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $R\in\SOthree$ +\end_inset + + is a rotation matrix and +\begin_inset Formula $t\in\Rthree$ +\end_inset + + is a translation vector. + An alternative way of writing down elements of +\begin_inset Formula $\SEthree$ +\end_inset + + is as the ordered pair +\begin_inset Formula $(R,\, t)$ +\end_inset + +, with composition defined as +\begin_inset Formula +\[ +(R_{1},\, t_{1})(R_{2},\, t_{2})=(R_{1}R_{2},\, R{}_{1}t_{2}+t_{1}) +\] + +\end_inset + + Its Lie algebra +\begin_inset Formula $\sethree$ +\end_inset + + is the vector space of +\begin_inset Formula $4\times4$ +\end_inset + + twists +\begin_inset Formula $\xihat$ +\end_inset + + parameterized by the +\emph on +twist coordinates +\emph default + +\begin_inset Formula $\xi\in\Rsix$ +\end_inset + +, with the mapping +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + + +\begin_inset Formula +\[ +\xi\define\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\rightarrow\xihat\define\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + +Note we follow Frank Park's convention and reserve the first three components + for rotation, and the last three for translation. + Hence, with this parameterization, the generators for +\begin_inset Formula $\SEthree$ +\end_inset + + are +\begin_inset Formula +\[ +G^{1}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & -1 & 0\\ +0 & 1 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{}G^{2}=\left(\begin{array}{cccc} +0 & 0 & 1 & 0\\ +0 & 0 & 0 & 0\\ +-1 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{ }G^{3}=\left(\begin{array}{cccc} +0 & -1 & 0 & 0\\ +1 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{4}=\left(\begin{array}{cccc} +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{}G^{5}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{ }G^{6}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + +Applying the exponential map to a twist +\begin_inset Formula $\xi$ +\end_inset + + yields a screw motion yielding an element in +\begin_inset Formula $\SEthree$ +\end_inset + +: +\begin_inset Formula +\[ +T=\exp\xihat +\] + +\end_inset + +A closed form solution for the exponential map is given in +\begin_inset CommandInset citation +LatexCommand cite +after "page 42" +key "Murray94book" + +\end_inset + +. +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +\begin_inset Formula +\[ +\exp\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]t\right)=\left[\begin{array}{cc} +e^{\Skew{\omega}t} & (I-e^{\Skew{\omega}t})\left(\omega\times v\right)+\omega\omega^{T}vt\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +The adjoint is +\begin_inset Formula +\begin{eqnarray*} +\Ad T{\xihat} & = & T\xihat T^{-1}\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +\Skew{R\omega} & -\Skew{R\omega}t+Rv\\ +0 & 0 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +\Skew{R\omega} & t\times R\omega+Rv\\ +0 & 0 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +From this we can express the Adjoint map in terms of twist coordinates (see + also +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + + and FP): +\begin_inset Formula +\[ +\left[\begin{array}{c} +\omega'\\ +v' +\end{array}\right]=\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEthree$ +\end_inset + + on 3D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{c} +Rp+t\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\xi$ +\end_inset + + would do: +\begin_inset Formula +\[ +\hat{q}(\xi)=Te^{\xihat}\hat{p} +\] + +\end_inset + +hence the derivative is +\begin_inset Formula +\[ +\deriv{\hat{q}(\xi)}{\xi}=T\deriv{}{\xi}\left(\xihat\hat{p}\right) +\] + +\end_inset + +where +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + corresponds to a velocity in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + (in the local +\begin_inset Formula $T$ +\end_inset + + frame): +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\omega\times p+v\\ +0 +\end{array}\right] +\] + +\end_inset + +Notice how velocities are analogous to points at infinity in projective + geometry: they correspond to free vectors indicating a direction and magnitude + of change. +\end_layout + +\begin_layout Standard +By only taking the top three rows, we can write this as a velocity in +\begin_inset Formula $\Rthree$ +\end_inset + +, as the product of a +\begin_inset Formula $3\times6$ +\end_inset + + matrix +\begin_inset Formula $H_{p}$ +\end_inset + + that acts upon the exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + directly: +\begin_inset Formula +\[ +\omega\times p+v=-p\times\omega+v=\left[\begin{array}{cc} +-\Skew p & I_{3}\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + +The inverse action +\begin_inset Formula $T^{-1}p$ +\end_inset + + is +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{c} +R^{T}(p-t)\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T^{-1}\hat{p} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Affine Transformations +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $Aff(2)$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices that maps the line infinity to itself, and hence preserves + paralellism. + The affine transformation matrices +\begin_inset Formula $A$ +\end_inset + + can be written as +\begin_inset CommandInset citation +LatexCommand cite +key "Mei08tro" + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +\left[\begin{array}{ccc} +m_{11} & m_{12} & t_{1}\\ +m_{21} & m_{22} & t_{2}\\ +0 & 0 & k +\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $M\in GL(2)$ +\end_inset + +, +\begin_inset Formula $t\in\Rtwo$ +\end_inset + +, and +\begin_inset Formula $k$ +\end_inset + + a scalar chosen such that +\begin_inset Formula $det(A)=1$ +\end_inset + +. + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Note that just as +\begin_inset Formula $\SEtwo$ +\end_inset + + is a semi-direct product, so too is +\begin_inset Formula $Aff(2)=\Rtwo\rtimes GL(2)$ +\end_inset + +. + In particular, any affine transformation +\begin_inset Formula $A$ +\end_inset + + can be written as +\begin_inset Formula +\[ +A=\left[\begin{array}{cc} +0 & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +M & 0\\ +0 & k +\end{array}\right] +\] + +\end_inset + +and they compose as +\begin_inset Formula +\[ +A_{1}A_{2}=\left[\begin{array}{cc} +M_{1} & t_{1}\\ +0 & k_{1} +\end{array}\right]\left[\begin{array}{cc} +M_{2} & t_{2}\\ +0 & k_{2} +\end{array}\right]=\left[\begin{array}{cc} +M_{1}M_{2} & M_{2}t_{2}+k_{2}t_{1}\\ +0 & k_{1}k_{2} +\end{array}\right] +\] + +\end_inset + +From this it can be gleaned that the groups +\begin_inset Formula $\SOtwo$ +\end_inset + + and +\begin_inset Formula $\SEtwo$ +\end_inset + + are both subgroups, with +\begin_inset Formula $\SOtwo\subset\SEtwo\subset\Afftwo$ +\end_inset + +. + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +By choosing the generators carefully we maintain this hierarchy among the + associated Lie algebras. + In particular, +\begin_inset Formula $\setwo$ +\end_inset + + +\begin_inset Formula +\[ +G^{1}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{2}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{3}=\left[\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +can be extended to the +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Lie algebra +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\afftwo$ +\end_inset + + using the three additional generators +\begin_inset Formula +\[ +G^{4}=\left[\begin{array}{ccc} +0 & 1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Hence, the Lie algebra +\begin_inset Formula $\afftwo$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + incremental affine transformations +\begin_inset Formula $\ahat$ +\end_inset + + parameterized by 6 parameters +\begin_inset Formula $\aa\in\mathbb{R}^{6}$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +\aa\rightarrow\ahat\define\left[\begin{array}{ccc} +a_{5} & a_{4}-a_{3} & a_{1}\\ +a_{4}+a_{3} & -a_{5}-a_{6} & a_{2}\\ +0 & 0 & a_{6} +\end{array}\right] +\] + +\end_inset + +Note that +\begin_inset Formula $G_{5}$ +\end_inset + + and +\begin_inset Formula $G_{6}$ +\end_inset + + change the relative scale of +\begin_inset Formula $x$ +\end_inset + + and +\begin_inset Formula $y$ +\end_inset + + but without changing the determinant: +\begin_inset Formula +\[ +e^{xG_{5}}=\exp\left[\begin{array}{ccc} +x & 0 & 0\\ +0 & -x & 0\\ +0 & 0 & 0 +\end{array}\right]=\left[\begin{array}{ccc} +e^{x} & 0 & 0\\ +0 & 1/e^{x} & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +e^{xG_{6}}=\exp\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -x & 0\\ +0 & 0 & x +\end{array}\right]=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & 1/e^{x} & 0\\ +0 & 0 & e^{x} +\end{array}\right] +\] + +\end_inset + +It might be nicer to have the correspondence with scaling +\begin_inset Formula $x$ +\end_inset + + and +\begin_inset Formula $y$ +\end_inset + + more direct, by choosing +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & 0 & 0\\ +0 & 0 & -1 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 1 & 0\\ +0 & 0 & -1 +\end{array}\right] +\] + +\end_inset + +and hence +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + +\begin_inset Formula +\[ +e^{xG_{5}}=\exp\left[\begin{array}{ccc} +x & 0 & 0\\ +0 & 0 & 0\\ +0 & 0 & -x +\end{array}\right]=\left[\begin{array}{ccc} +e^{x} & 0 & 0\\ +0 & 1 & 0\\ +0 & 0 & 1/e^{x} +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +e^{xG_{6}}=\exp\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & x & 0\\ +0 & 0 & -x +\end{array}\right]=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & e^{x} & 0\\ +0 & 0 & 1/e^{x} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Section +2D Homographies +\end_layout + +\begin_layout Standard +When viewed as operations on images, represented by 2D projective space + +\begin_inset Formula $\mathcal{P}^{3}$ +\end_inset + +, 3D rotations are a special case of 2D homographies. + These are now treated, loosely based on the exposition in +\begin_inset CommandInset citation +LatexCommand cite +key "Mei06iros,Mei08tro" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SLthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices with determinant +\begin_inset Formula $1$ +\end_inset + +. + The homographies generalize transformations of the 2D projective space, + and +\begin_inset Formula $\Afftwo\subset\SLthree$ +\end_inset + +. + +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +We can extend +\begin_inset Formula $\afftwo$ +\end_inset + + to the Lie algebra +\begin_inset Formula $\slthree$ +\end_inset + + by adding two generators +\begin_inset Formula +\[ +G^{7}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right]\mbox{ }G^{8}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +0 & 1 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +obtaining the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + incremental homographies +\begin_inset Formula $\hhat$ +\end_inset + + parameterized by 8 parameters +\begin_inset Formula $\hh\in\mathbb{R}^{8}$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +h\rightarrow\hhat\define\left[\begin{array}{ccc} +h_{5} & h_{4}-h_{3} & h_{1}\\ +h_{4}+h_{3} & -h_{5}-h_{6} & h_{2}\\ +h_{7} & h_{8} & h_{6} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Tensor Notation +\end_layout + +\begin_layout Itemize +A homography between 2D projective spaces +\begin_inset Formula $A$ +\end_inset + + and +\begin_inset Formula $B$ +\end_inset + + can be written in tensor notation +\begin_inset Formula $H_{A}^{B}$ +\end_inset + + +\end_layout + +\begin_layout Itemize +Applying a homography is then a tensor contraction +\begin_inset Formula $x^{B}=H_{A}^{B}x^{A}$ +\end_inset + +, mapping points in +\begin_inset Formula $A$ +\end_inset + + to points in +\begin_inset Formula $B$ +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +The inverse of a homography can be found by contracting with two permutation + tensors: +\begin_inset Formula +\[ +H_{B}^{A}=H_{A_{1}}^{B_{1}}H_{A_{2}}^{B_{2}}\epsilon_{B_{1}B_{2}B}\epsilon^{A_{1}A_{2}A} +\] + +\end_inset + + +\end_layout + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Plain Layout +The adjoint can be done using tensor notation. + Denoting an incremental homography in space +\begin_inset Formula $A$ +\end_inset + + as +\begin_inset Formula $\hhat_{A_{1}}^{A_{2}}$ +\end_inset + +, we have, for example for +\begin_inset Formula $G_{1}$ +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\hhat_{B_{1}}^{B_{2}}=\Ad{H_{A}^{B}}{\hhat_{A_{1}}^{A_{2}}} & = & H_{A_{2}}^{B_{2}}\hhat_{A_{1}}^{A_{2}}H_{B_{1}}^{A_{1}}\\ + & = & H_{A_{2}}^{B_{2}}\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]H_{A_{2}}^{B_{2}}H_{A_{3}}^{B_{3}}\epsilon_{B_{1}B_{2}B_{3}}\epsilon^{A_{1}A_{2}A_{3}}\\ + & = & H_{1}^{B_{2}}H_{A_{2}}^{B_{2}}H_{A_{3}}^{B_{3}}\epsilon_{B_{1}B_{2}B_{3}}\epsilon^{3A_{2}A_{3}} +\end{eqnarray*} + +\end_inset + +This does not seem to help. +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix: Proof of Property +\begin_inset CommandInset ref +LatexCommand ref +reference "proof1" + +\end_inset + + +\end_layout + +\begin_layout Standard +We can prove the following identity for rotation matrices +\begin_inset Formula $R$ +\end_inset + +, +\begin_inset Formula +\begin{eqnarray} +R\Skew{\omega}R^{T} & = & R\Skew{\omega}\left[\begin{array}{ccc} +a_{1} & a_{2} & a_{3}\end{array}\right]\nonumber \\ + & = & R\left[\begin{array}{ccc} +\omega\times a_{1} & \omega\times a_{2} & \omega\times a_{3}\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +a_{1}(\omega\times a_{1}) & a_{1}(\omega\times a_{2}) & a_{1}(\omega\times a_{3})\\ +a_{2}(\omega\times a_{1}) & a_{2}(\omega\times a_{2}) & a_{2}(\omega\times a_{3})\\ +a_{3}(\omega\times a_{1}) & a_{3}(\omega\times a_{2}) & a_{3}(\omega\times a_{3}) +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +\omega(a_{1}\times a_{1}) & \omega(a_{2}\times a_{1}) & \omega(a_{3}\times a_{1})\\ +\omega(a_{1}\times a_{2}) & \omega(a_{2}\times a_{2}) & \omega(a_{3}\times a_{2})\\ +\omega(a_{1}\times a_{3}) & \omega(a_{2}\times a_{3}) & \omega(a_{3}\times a_{3}) +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +0 & -\omega a_{3} & \omega a_{2}\\ +\omega a_{3} & 0 & -\omega a_{1}\\ +-\omega a_{2} & \omega a_{1} & 0 +\end{array}\right]\nonumber \\ + & = & \Skew{R\omega}\label{proof1} +\end{eqnarray} + +\end_inset + +where +\begin_inset Formula $a_{1}$ +\end_inset + +, +\begin_inset Formula $a_{2}$ +\end_inset + +, and +\begin_inset Formula $a_{3}$ +\end_inset + + are the +\emph on +rows +\emph default + of +\begin_inset Formula $R$ +\end_inset + +. + Above we made use of the orthogonality of rotation matrices and the triple + product rule: +\begin_inset Formula +\[ +a(b\times c)=b(c\times a)=c(a\times b) +\] + +\end_inset + +Similarly, without proof +\begin_inset CommandInset citation +LatexCommand cite +after "Lemma 2.3" +key "Murray94book" + +\end_inset + +: +\begin_inset Formula +\[ +R(a\times b)=Ra\times Rb +\] + +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix: Alternative Generators for +\begin_inset Formula $\slthree$ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset CommandInset citation +LatexCommand cite +key "Mei06iros" + +\end_inset + + uses the following generators for +\begin_inset Formula $\slthree$ +\end_inset + +: +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +G^{1}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{2}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{3}=\left[\begin{array}{ccc} +0 & 1 & 0\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{4}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{7}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right]\mbox{ }G^{8}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +0 & 1 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +We choose to use a different linear combination as the basis. +\end_layout + +\begin_layout Standard +\begin_inset CommandInset bibtex +LatexCommand bibtex +bibfiles "../../../papers/refs" +options "plain" + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/LieGroups.pdf b/doc/LieGroups.pdf new file mode 100644 index 000000000..f271f35c0 Binary files /dev/null and b/doc/LieGroups.pdf differ diff --git a/doc/cholesky.lyx b/doc/cholesky.lyx new file mode 100644 index 000000000..99157fadc --- /dev/null +++ b/doc/cholesky.lyx @@ -0,0 +1,170 @@ +#LyX 1.6.7 created this file. For more info see http://www.lyx.org/ +\lyxformat 345 +\begin_document +\begin_header +\textclass article +\use_default_options true +\language english +\inputencoding auto +\font_roman default +\font_sans default +\font_typewriter default +\font_default_family default +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\paperfontsize default +\use_hyperref false +\papersize default +\use_geometry false +\use_amsmath 1 +\use_esint 1 +\cite_engine basic +\use_bibtopic false +\paperorientation portrait +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\defskip medskip +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\author "" +\author "" +\end_header + +\begin_body + +\begin_layout Section +Basic solving with Cholesky +\end_layout + +\begin_layout Standard +Solving a linear least-squares system: +\begin_inset Formula \[ +\arg\min_{x}\left\Vert Ax-b\right\Vert ^{2}\] + +\end_inset + +Set derivative equal to zero: +\begin_inset Formula \begin{align*} +0 & =2A^{T}\left(Ax-b\right)\\ +0 & =A^{T}Ax-A^{T}b\end{align*} + +\end_inset + +For comparison, with QR we do +\begin_inset Formula \begin{align*} +0 & =R^{T}Q^{T}QRx-R^{T}Qb\\ + & =R^{T}Rx-R^{T}Qb\\ +Rx & =Qb\\ +x & =R^{-1}Qb\end{align*} + +\end_inset + +But with Cholesky we do +\begin_inset Formula \begin{align*} +0 & =R^{T}RR^{T}Rx-R^{T}Rb\\ + & =R^{T}Rx-b\\ + & =Rx-R^{-T}b\\ +x & =R^{-1}R^{-T}b\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Section +Frontal (rank-deficient) solving with Cholesky +\end_layout + +\begin_layout Standard +To do multi-frontal elimination, we decompose into rank-deficient conditionals. + +\begin_inset Formula \[ +\left[\begin{array}{cccccc} +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\\ +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\\ +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\end{array}\right]\to\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \[ +\left[\begin{array}{cc} +R^{T} & 0\\ +S^{T} & C^{T}\end{array}\right]\left[\begin{array}{cc} +R & S\\ +0 & C\end{array}\right]=\left[\begin{array}{cc} +F^{T}F & F^{T}G\\ +G^{T}F & G^{T}G\end{array}\right]\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \[ +R^{T}R=F^{T}F\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \begin{align*} +R^{T}S & =F^{T}G\\ +S & =R^{-T}F^{T}G\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \begin{align*} +S^{T}S+C^{T}C & =G^{T}G\\ +G^{T}FR^{-1}R^{-T}F^{T}G+C^{T}C & =G^{T}G\\ +G^{T}QRR^{-1}R^{-T}R^{T}Q^{T}G+C^{T}C & =G^{T}G\\ +\textbf{if }R\textbf{ is invertible, }G^{T}G+C^{T}C & =G^{T}G\\ +C^{T}C & =0\end{align*} + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/images/circular.pdf b/doc/images/circular.pdf new file mode 100644 index 000000000..b0f43f649 Binary files /dev/null and b/doc/images/circular.pdf differ diff --git a/doc/images/circular.png b/doc/images/circular.png new file mode 100644 index 000000000..71c346a8e Binary files /dev/null and b/doc/images/circular.png differ diff --git a/doc/images/gtsam-structure.graffle b/doc/images/gtsam-structure.graffle new file mode 100644 index 000000000..22eb72dc3 --- /dev/null +++ b/doc/images/gtsam-structure.graffle @@ -0,0 +1,1302 @@ + + + + + ActiveLayerIndex + 0 + ApplicationVersion + + com.omnigroup.OmniGraffle + 138.14.0.129428 + + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {559.29, 782.89}} + Class + SolidGraphic + ID + 2 + Style + + fill + + GradientColor + + w + 0.666667 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + CanvasOrigin + {0, 0} + CanvasSize + {559.29, 782.89} + ColumnAlign + 1 + ColumnSpacing + 36 + CreationDate + 2010-07-13 00:07:47 -0400 + Creator + Frank Dellaert + DisplayScale + 1 0/72 in = 1 0/72 in + FileType + flat + GraphDocumentVersion + 6 + GraphicsList + + + Class + LineGraphic + Head + + ID + 19 + + ID + 35 + Points + + {191.649, 522.933} + {191.649, 558.208} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 34 + + + + Bounds + {{156.649, 558.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 19 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 tests} + + + + Class + Group + Graphics + + + Class + LineGraphic + Head + + ID + 30 + + ID + 22 + Points + + {220.827, 437.595} + {201.125, 473.266} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 25 + + + + Class + LineGraphic + Head + + ID + 28 + + ID + 23 + Points + + {198.977, 245.588} + {219.976, 281.282} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 33 + + + + Class + LineGraphic + Head + + ID + 25 + + ID + 24 + Points + + {234.015, 373.654} + {229.931, 409.211} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 27 + + + + Bounds + {{193.649, 409.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 25 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 nonlinear} + + + + Class + LineGraphic + Head + + ID + 27 + + ID + 26 + Points + + {230.126, 309.655} + {233.82, 345.213} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 28 + + + + Bounds + {{200.649, 345.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 27 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 linear} + + + + Bounds + {{193.649, 281.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 28 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 inference} + + + + Class + LineGraphic + Head + + ID + 30 + + ID + 29 + Points + + {152.743, 373.628} + {188.492, 473.239} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 32 + + + + Bounds + {{158.649, 473.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 30 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 slam} + + + + Class + LineGraphic + Head + + ID + 32 + + ID + 31 + Points + + {185.872, 245.631} + {152.363, 345.234} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 33 + + + + Bounds + {{112.649, 345.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 32 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 geometry} + + + + Bounds + {{155.649, 217.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 33 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 base} + + + + ID + 21 + + + Bounds + {{86.649, 196.433}, {210, 326}} + Class + ShapedGraphic + ID + 34 + Shape + Rectangle + Style + + Text + + Align + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf0 gtsam} + + TextPlacement + 0 + + + GridInfo + + GuidesLocked + NO + GuidesVisible + YES + HPages + 1 + ImageCounter + 3 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + AutoLayout + 2 + LineLength + 0.4643835723400116 + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2010-07-13 00:17:24 -0400 + Modifier + Frank Dellaert + NotesVisible + NO + Orientation + 2 + OriginVisible + NO + OutlineStyle + Basic + PageBreaks + NO + PrintInfo + + NSBottomMargin + + float + 41 + + NSLeftMargin + + float + 18 + + NSPaperSize + + size + {595.29, 841.89} + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + PrintOnePage + + QuickLookPreview + + JVBERi0xLjMKJcTl8uXrp/Og0MTGCjUgMCBvYmoKPDwgL0xlbmd0aCA2IDAgUiAvRmls + dGVyIC9GbGF0ZURlY29kZSA+PgpzdHJlYW0KeAGlV8tuWzcQ3d+v4NJemCZn+NzWbYF6 + 1dQCuii6cAW5kSHZjeQW6N/3DHl5TclXUoNYSOQwnPeZM8Mv6pP6ogw+3mcVE6ndSv2q + XtTt3d6q5V7Z8tkv1Y3RXhnN2RjrglzXVCR0yhAantTtz6vdcvXX29+PG7VbQy0xFdXs + kopeB5dyVuS8dj6q5Vbd/rS16vvX4kKuV71R1jlczcoTaZusH+pNmrlpbLnJ2ZWbo865 + my6WmxTCJZ2Jyk3n0yWdKR9YP+PnqJPZXNKJ5EjsiHvGz9tfVpvHt/U/q7vXzetuvV29 + 7dZLSXUKkCrJDaYkl6xRTEGK+YQC3is7PNeS3j2Ukhj1cIcK2fKPG/lC7aWSSPakzeag + HbOq2rzO+JFSP6BiwAcJPowCNjpFNteaOOJW5u8Wytbq3uD7xhqDv1xUi+1w+6PVqLha + PKnf1NWf14IyUldv10AavveP7WR7rX5Xi3v1w6LaPsSm9TVtnqOOTF5Foyhqh5zEoeSg + 87APtQmShaBJB4KSvINIh+NITamV9/ZUpKyNNdEph1hVH+tw9UeLbApxvzofox2BafJX + xjgKMrD11TGOfXO6muRPxzjVE5HVwr62X7bTUav17t8+/Jl6SX/Z5HWKRIVFAluncIbi + ewtkMuM/vUlq0+pWUCLkVlBqPekcgHHHGRULaRDhpDkA484FbRJaZoMzZDoGj7MIzHtR + +LmcHkjD9BMU3+PP8zDjr7TSZJId2oHBh51J5qCTwKMzyezQhY6GA5OdtCDSlg/QKN4L + XRDo4hj3U+8PVj33HXqI/6rARb6MDXR6H6fNXI3nidCPOx15DDHHj/hHa2+uh4qJqQEO + evxMQqNjpxgeB8QtCQUowCdpcIF1JuNPAiBFAQgptmhZzqkIo8bRepxlnRNGGqoBKmRC + ERi0kH2gCoAZ6QkAJxM8Cg0uCkvAtvg7mnQBgDTRdiaVC05n5hFzzWQn/TD0ABhrUOon + xBcQBH7SRH8TDICZWRiUtmqlFBwJDc6qOSDDI9onGoEEjzHdRekRGAhTHf1Fc2BYN1p4 + ab88jRNg1VCymwhjurM8T5hkKj+7Rpgfgjo7Gpr4RJsfxPsBMcyMQgIfSXcekqfRxgAG + C3RvPxSRnYg1SSZFPxWvNuuX1ePuWi2e6+w70Rckq4VklxFt8NC0lfVLxxziIMTIwZ/s + C2LpJZCTEKMPkYswpgXYqZBgYicsRZR1soRGAzGSdaLwM8x8lL7YF01oEGpjotibFH+N + 98LFzWQh9xBLDJ3JTnq2L0rxvr0vCoS+qS8Y6/J7X8xjoHSIR4jH68LVy+vLBxyA1mWu + He1uhPlhrOfKj94J3xBjyQqgRc5Zc/RCZ2Mv1wE5jAOygMhFXMS2DhwIuRaFiF9xYm0j + VRwkzEpjy1nysfJjkx466f+BA+BWTDoTBQf5wCT8jTYGDEPhl2oSZ4ap8mMz2UvXAYmN + 9xzdJXB+AEliJfIpyRYBOIPq8S6hiK5xmcckEcaCsdg4vGGN+77cjdo76waPORKClZlB + 2LI44hZ40OaxM2Zkz2ZEaHMySFHeF2gyOasG4ZzVSIVMjNEgRacplpmHvmgGmyw2nAv5 + kC2FyOiEFnRYn30GPnBksO5bizPMo2AMowaiiQxpA5ooI5RSKPVCzNi8I86w0OAxJt5J + thJaWMZqdCC8QhWjNAYr4qjSZxNSvGsmZQgGwwWVzaTDg854EwUizaSsAdZhBvYmVSdd + UyJbVNmh5PGEJxceO8c7VB0Q5f00j6a641UFHsvYuf16bkS01xJeWEIPou5obMryHtF+ + PScM9bnUNudpMu7byf7CKl3cLg+1FAZ5Z2PjQNGrNxj/mB+ahe+OiKIwjuSsynogJ6CB + sD2JsDzbkx+EMcqZLFKyFUBPd4ZNekb6LArqiiLvSvHNh+rbu8ne38lkF8O7yaGTFhR8 + +g8FPYzxCmVuZHN0cmVhbQplbmRvYmoKNiAwIG9iagoxNDU4CmVuZG9iagozIDAgb2Jq + Cjw8IC9UeXBlIC9QYWdlIC9QYXJlbnQgNCAwIFIgL1Jlc291cmNlcyA3IDAgUiAvQ29u + dGVudHMgNSAwIFIgL01lZGlhQm94IFswIDAgNTU5LjI5IDc4Mi44OV0KPj4KZW5kb2Jq + CjcgMCBvYmoKPDwgL1Byb2NTZXQgWyAvUERGIC9UZXh0IC9JbWFnZUIgL0ltYWdlQyAv + SW1hZ2VJIF0gL0NvbG9yU3BhY2UgPDwgL0NzMSA4IDAgUgovQ3MyIDEzIDAgUiA+PiAv + Rm9udCA8PCAvRjEuMCAxNCAwIFIgPj4gL1hPYmplY3QgPDwgL0ltMSA5IDAgUiAvSW0y + IDExIDAgUgo+PiA+PgplbmRvYmoKOSAwIG9iago8PCAvTGVuZ3RoIDEwIDAgUiAvVHlw + ZSAvWE9iamVjdCAvU3VidHlwZSAvSW1hZ2UgL1dpZHRoIDQ2NCAvSGVpZ2h0IDY5NiAv + SW50ZXJwb2xhdGUKdHJ1ZSAvQ29sb3JTcGFjZSAxNSAwIFIgL0ludGVudCAvUGVyY2Vw + dHVhbCAvU01hc2sgMTYgMCBSIC9CaXRzUGVyQ29tcG9uZW50CjggL0ZpbHRlciAvRmxh + dGVEZWNvZGUgPj4Kc3RyZWFtCngB7dCBAAAAAMOg+VNf4QCFUGHAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAwDswyVIAAQplbmRzdHJlYW0KZW5kb2Jq + CjEwIDAgb2JqCjQyNDgKZW5kb2JqCjExIDAgb2JqCjw8IC9MZW5ndGggMTIgMCBSIC9U + eXBlIC9YT2JqZWN0IC9TdWJ0eXBlIC9JbWFnZSAvV2lkdGggMTg0IC9IZWlnaHQgMTAw + IC9JbnRlcnBvbGF0ZQp0cnVlIC9Db2xvclNwYWNlIDE1IDAgUiAvSW50ZW50IC9QZXJj + ZXB0dWFsIC9TTWFzayAxOCAwIFIgL0JpdHNQZXJDb21wb25lbnQKOCAvRmlsdGVyIC9G + bGF0ZURlY29kZSA+PgpzdHJlYW0KeAHt0IEAAAAAw6D5Ux/khVBhwIABAwYMGDBgwIAB + AwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBg + wIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYM + GDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIAB + AwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBg + wIABAwYMGDBgwIABAwYMGDBgwIABA48DA9egAAEKZW5kc3RyZWFtCmVuZG9iagoxMiAw + IG9iagoyNjMKZW5kb2JqCjE2IDAgb2JqCjw8IC9MZW5ndGggMTcgMCBSIC9UeXBlIC9Y + T2JqZWN0IC9TdWJ0eXBlIC9JbWFnZSAvV2lkdGggNDY0IC9IZWlnaHQgNjk2IC9Db2xv + clNwYWNlCi9EZXZpY2VHcmF5IC9JbnRlcnBvbGF0ZSB0cnVlIC9CaXRzUGVyQ29tcG9u + ZW50IDggL0ZpbHRlciAvRmxhdGVEZWNvZGUgPj4Kc3RyZWFtCngB7drtT1TnogVwlXdm + GGZwGGCAgsPrgEinYEdACwSColBfsdgKQUdNsSDVOJEUtRiqRKIorQQ1ipSIBi0BQ9QY + Nedfu89Gc0+ruHrOp+5173o+nJxk9STL9euz9wbPmjU6WkALaAEtoAW0gBbQAlrg/8MC + a3Vsu8B/9e+f+VOs+/eJ0bHRAv92WWeY/gPWd5bmTxAbG6dj0wViYw2QRft3pCua7yjj + ExIS350kHZss8B4kISHe/ItmUP9G9L1mXFy8oUxKTnY4HE6nM0XHNgsYDoOSnJyUmGiZ + YlGLM8Y8ZQ2moXSmuFypbrdHx1YLuN2pLleKUU02pO9EP/HQXeE0d9PSTHGlejxp673e + 9HSfL0PHJgv4fOnpXu/6NI8n1ZViiZo7ah66q4Nat9O6nJam21j6MjKz/P7snJxcHZss + kJOT7fdnZWb4jKl7RdRcUQt0lQ/dFU7z4nQ4jabBNJK5efn5GwIFOrZZILAhPz8v16ga + UiPqdFiv0dVB11rvzoQkczk9632ZfmMZKCgqLikNBsvKynVssEBZWTBYWlJcVBAwpv5M + 33qPuaJJCdZX0ccX1FxPw5noSEn1eDP8ufmBwuJg2caKyspQKPSFji0WMBSVlRUby4LF + hYH8XH+G15OaYm5oXOwqT1xzPc2nUPIKZ3ZeoKi0vKIyVLX5y3BNrTl1Ov/4ApZDTfjL + zVWhyory0qJAXvYKaLL5KFrlgq411zMx2enyeDOz8wpKyjeFqsM1ddvqGxqbmpqadWyw + gIFobKjfVlcTrg5tKi8pyMvO9HpczuREc0E/fOC+u54Ow5mRnV8YrAhVb6mrb2xu2dG6 + q639ax1bLNDetqt1R0tzY33dlupQRbAw37qhLsdqF9TyNE9bt+HMKwxWVoW3NjRt39m+ + e9/+joOdOjZZ4GDH/n2723dub2rYGq6qDBZaj1x3irmgHz1wzeM2PtHhSvP58wqCm6pr + 65tb2/Ye6Pyuq7vnaCRyTMcGC0QiR3u6u77rPLC3rbW5vrZ6U7Agz+9Lsy7oRw/ctevM + zyrmembmBkoqqmobWnbt6TjU1RM50ftDX/+pAR0bLHCqv++H3hORnq5DHXt2tTTUVlWU + BHIzzQU1P7N8+AK1Hrfm7enz5xeVh8L1LW37Og8fOd7bN3DmbPTcoI4tFjgXPXtmoK/3 + +JHDnfvaWurDofKifL/PeoOaB+5ff0W04pm6PiM3ULqpemuz4eyO9Pafjg4OXbg4fEnH + FgsMX7wwNBg93d8b6TagzVurN5UGcjPWp67qGZ/kdHuz8grLQ1saWvd0dh87ORAdvDA8 + cnn06piOLRa4Onp5ZPjCYHTg5LHuzj2tDVtC5YV5WV63Myn+o/sZG5+UYj1uiyuq65ra + Ow5HTv4YHRr+ZXTs+o2bv+rYYoGbN66Pjf4yPBT98WTkcEd7U111RbH1wE1JMh9EHzxv + YxOSXWkZOYHSyvBX2/ceOvL9QHTo0pWx8Ylbk7dv39GxwQK3b0/emhgfu3JpKDrw/ZFD + e7d/Fa4sDeRkpLmSE1bxdLjM67OgLFTTuPNA1/E+wzl67eatqbv3ph/M6NhggQfT9+5O + 3bp5bdSA9h3vOrCzsSZUVmBeoC7HKp7m89ab9VnRxirzuO3s6T09+POVaxOTd+7PzD6c + e6RjgwXmHs7O3L8zOXHtys+Dp3t7Os0Dt2pj0WdZXvOB+9H9ND+upHqt1+fmbS27v430 + Rc+PjN2cvDv9+9zj+SdPdWywwJP5x3O/T9+dvDk2cj7aF/l2d8u2zdYL1Gt94H74/jSe + buNZUhmu37Gv68TA4PDo+K0707OPnjxdWFzSscECiwtPnzyanb5za3x0eHDgRNe+HfXh + yhLj6V7V0+lO928wn0MNrfu7e8/8NDI2MXXfcC4sPVvWscUCz5YWDOj9qYmxkZ/O9Hbv + b20wH0Qb/Olu52r30+lJzw4EP69p3NXRc/Ls+cvXf7s7Mze/sLT8/MVLHRss8OL58tLC + /NzM3d+uXz5/9mRPx67Gms+Dgex0zyc8fTmBYKi2qe3g0b7oxdHxyXuzj/9YXH7+8pWO + LRZ4+Xx58Y/Hs/cmx0cvRvuOHmxrqg0FAzm+T3uaH1eM5zeR/nPDV29MTT+cX3hmOF+/ + 0bHBAq9fvXz+bGH+4fTUjavD5/oj31ieZQV/69neGTk1eGls4vaDuSeLyy8M51sdGyzw + 5vWrF8uLT+Ye3J4YuzR4KmJ+YPmUp/nrskSnx5ezcj9X8fyXzj++wFvs+Zf/x8namDjz + 61vz66HyL+qav+48NmDu5693Zh49XVp++erN23/8z6ICZoG3b169XF56+mjmzq/mfg4c + 6/y6ue6LcvMLIvML3LgYebL9SyJPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M + 95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonh + vvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHc + V554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7 + yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBf + eeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4r + T7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33l + ifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK88 + 8T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un + 3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE + +7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554 + H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPv + w5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ9 + 2FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wP + WypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdh + S+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5s + qTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3oct + lSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl + 8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZU + nmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bK + k00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M + 95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonh + vvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHc + V554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7 + yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBf + eeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4r + T7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33l + ifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK88 + 8T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un + 3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE + +7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554 + H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPv + w5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ9 + 2FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wP + WypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdh + S+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5s + qTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3oct + lSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl + 8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZU + nmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bK + k00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS/8bz3VxiU6PL6egLFTb + 1N4ZOTV4aWzi9oO5J4vLL169fvOW7Y/+f7Hv2zevX71YXnwy9+D2xNilwVORzvam2lBZ + QY7P40yMW7d2zZ/P33i+1fnnF8Cef9Zcs+bPnm3fRPrPDV+9MTX9cH7h2fOX5oLq2GCB + 169ePn+2MP9weurG1eFz/ZFv2v58P1f1DATN87bt4NG+6MXR8cl7s4//WFw2oDq2WODl + 8+XFPx7P3pscH70Y7Tt60PIMBt4/b1fxTM8OBD+vadzV0XPy7PnL13+7OzM3v7C0/PzF + Sx0bLPDi+fLSwvzczN3frl8+f/ZkT8euxprPg4Hs9JX358ee7nT/htLKcEPr/u7eMz+N + jE1M3Z999GRh6dmyji0WeLa08OTR7P2pibGRn870du9vbQhXlm7wp7ut76GPPB1urz+/ + pDJcv2Nf14mBweHR8Vt3pg3o04XFJR0bLLC48NRwTt+5NT46PDhwomvfjvpwZUm+3+t2 + rOqZajyLKzZva9n9baQven5k7Obk3enf5x7PP3mqY4MFnsw/nvt9+u7kzbGR89G+yLe7 + W7Ztrig2nqmreMYmOlzerM+KNlbVmR9Ae3pPD/585drE5J37M7MP5x7p2GCBuYezM/fv + TE5cu/Lz4OneHvPjZ13VxqLPsrwuR2Lsh8/b2ASHa31GrvmFQk3jzgNdx/uiQ5dGr928 + NXX33vSDGR0bLPBg+t7dqVs3r41eGor2He86sLOxxvw6ITdjvcuRsIpnsistIydgPoi+ + 2r730JHvBwzolbHxiVuTt2/f0bHBArdvT96aGB+7YjgHvj9yaO/2r8znUCAnI82VvIpn + fFKKx2e9QKvNA7fjcOTkj9Gh4V9Gx67fuPmrji0WuHnj+tjoL8ND0R9PRg53mMdttfX6 + 9HlSkuI/up8x8UlOtzcrr7A8tKWhdU9n97GTA9HBC8Mjl0evjunYYoGro5dHhi8MRgdO + Huvu3NPasCVUXpiX5XU7k+JjPnx/xsQlOlLNCzRQuql6a3Pbvs7uSG//6ejg0IWLw5d0 + bLHA8MULQ4PR0/29ke7OfW3NW6s3lQbM69P6vF3V02U9cIvKQ+H6FgN6+Mjx3r6BM2ej + 5wZ1bLHAuejZMwN9vcePHDacLfXhUHmR9bg1n7cfea5dF5eQlOL2ZuYGSiqqahtadu3p + ONTVEznR+0Nf/6kBHRsscKq/74feE5GerkMde3a1NNRWVZQEcjO97pSkhA//umzN2nWx + 8eYn0DSfP68guKm6tr65tW3vgc7vurp7jkYix3RssEAkcrSnu+u7zgN721qb62urNwUL + 8vy+NHM9zefQX//603iaF2iyuaAZ2XmFwcqq8NaGpu0723fv299xsFPHJgsc7Ni/b3f7 + zu1NDVvDVZXBwrzsDHM9k63H7Sqe1gX1GND8wmBFqHpLXX1jc8uO1l1t7V/r2GKB9rZd + rTtamhvr67ZUhyqChfmG03p7xn/saT1wzQV1GtDM7LyCkvJNoepwTd22+obGpqamZh0b + LGAgGhvqt9XVhKtDm8pLCvKyMw2n01zPjx63a1YeuPHmiZtq3dC8QFFpeUVlqGrzl+Ga + WnPqdP7xBSyHmvCXm6tClRXlpUUB62HrSTVP29Wup/E0FzQh0bEC6s/NDxQWB8s2VlRW + hkKhL3RssYChqKys2FgWLC4M5Of6VzgdiQnmen74+jR/GWq+iAxokiPF5Vnvy/Tn5uUH + CoqKS0qDwbKych0bLFBWFgyWlhQXFQTy83L9mb71HleKw/ysEvvR15D1d9vmgsbExZsb + 6nS507y+DH92jjHN3xAo0LHNAoEN+cYyJ9uf4fOmuV1Oczutp+0q1/M9qHnkJpsr6k5b + b0gzs/xGNSdXxyYL5BhJf1amwVxvNFMcyeZh+ynONWtXbmhcfOKKaKrHY0y96ek+X4aO + TRbw+dLTvcbS40ld0TSfQiucH/zw+f7/SrQCGhtnrqgRdThTXK5Ut9ujY6sF3O5UlyvF + 6TB307qc5t25bu3qnOaJa26o9VVkvUYTk5INqsPpdKbo2GYBw2FQkpOTDKa5m5bmpzmt + j6J3oobUmBrUlZOkY5MF3oMkWJZxsX+rufKZa4mui4mJibVQdWy5gKGMsa4mvJvv36LW + JV0xtf55c8z/Usc2C7wzWflPw/S/ZP/JfzH/vI5NF/hP/PTPaAEtoAW0gBbQAlpAC2gB + /gX+B05tLvoKZW5kc3RyZWFtCmVuZG9iagoxNyAwIG9iago2NTUwCmVuZG9iagoxOCAw + IG9iago8PCAvTGVuZ3RoIDE5IDAgUiAvVHlwZSAvWE9iamVjdCAvU3VidHlwZSAvSW1h + Z2UgL1dpZHRoIDE4NCAvSGVpZ2h0IDEwMCAvQ29sb3JTcGFjZQovRGV2aWNlR3JheSAv + SW50ZXJwb2xhdGUgdHJ1ZSAvQml0c1BlckNvbXBvbmVudCA4IC9GaWx0ZXIgL0ZsYXRl + RGVjb2RlID4+CnN0cmVhbQp4Ae2b+VeS6RvGrdxARBAERRQFXAAVUQrFUgwzUcxdcVwG + Qx1pMKqRkaPlkilFrpnjMu7jMuo4Wk46TXXmX/vezwuVC1Jzjt/HfuD6Jc/hxPvx6n5f + 6Lmvy8vLI48DHgc8Dvy/HbjwDeg//Y7Ae/GzLp2LPl//IuB8Bb6DGVi9vX3OXd7eAIJ+ + hS+hE9QOZF8/P3+HSNjlvLCfny9YB/BfIHdS+/j4AjKJTA4ICKBQKIHnILgsXJxMJvn7 + I3b35Aj7EkwHQAMyJZBKDaLR6OckGi2ISg0EejKgO8hPGRYCG7xG1IHUIDo9mMFkhoSw + WGzsYrFCQphMRjCdHkQNROTgOQyLa3DkNjIbUdOAmcUODeNwwrncCOzicsM5nLBQNgvY + aQQ5WI7AXTxYCGwY7AAKUAM0EEfwoqKi+YJzED86KooXAfSADuSUADTmrsEvoNn2I4HZ + dAYrlAPMfEFMbFy8SCQWS7BKLBaJ4uNiYwR8YOeEshh0sJzkh+7Ok4aD3YDtHxAYRGey + ORFRfGGsSJyQKJXKZLIUzIJLSqWJCWJRrJAfFcFhM+lBgeC4j7eLSQG74ZYkE9jhPH5M + vCRRKku9fEWRrgRlYBS6XrriyuVUmTRREh/D54UT4GS4OV0YfgHs9idTqHRmaDhPECdJ + kskV6RnXslTZarU6B6vggtmqrGsZ6Qq5LEkSJ+CFhzLpVArZHww/PigOuwMAmx0eJRQl + yuRpGVnZObl5mgJt4S3MKtQWaPJyc7KzMtLkskSRMAo5Tg1wZTjihimhATZPKJKmKq6q + 1DfzC4tKyyoqddhVWVFWWlSYf1OtuqpIlYqEaFRogWD4iUGBMfH1D6AGszg8gShJrszK + 0WhLynU1dfX62wZDI1YZDLf19XU1uvISrSYnSylPEgl4HFYwMvzEoFy4CM9AsDs0gh+X + mKpU5RYUV1TX6Q3Nxh9NrXfNWHW31fSjsdmgr6uuKC7IVSlTE+P4EaFgODwLjw84GhOY + bhYnKkYiU2Tlakt1tQ1NRpP5QZul3YpZ7Za2B2aTsamhVleqzc1SyCQxURwWmnAYlKMf + mQR3EIMdwY9Pkl/NAex6g7H1vsXa+airpxezeroedVot91uNhnoAz7kqT4rnR7AZQS65 + fUkUGjOMJ5TI0lSaYl194x2zxfqop6/f9syOWc9s/X09j6wW853Gel2xRpUmkwh5YUwa + heR7wm9vX1IgGpPYRHmGurCi1nDnnqWz54nNPjQy+gKzRkeG7LYnPZ2We3cMtRWF6gx5 + YiwalEAS3JjH5sTbj0wNZnP58VJF5s2S6oYWs6Wzd8A+PPZyYmpqGqumpiZejg3bB3o7 + LeaWhuqSm5kKaTyfyw6mkv1ccAdQYbwFYll6dn55XZMJsG2Doy8nZ2bnFxaxamF+dmby + 5eigDcBNTXXl+dnpMrEABpwa4IIbHifMsMiYhFQYE53eeN/aPTA4NjE9t7i8srqGVasr + y4tz0xNjgwPd1vtGvQ4GJTUhJjKMCQ+UE37DYzCIicb78rXcou8MJsvDPvvoxMz80ur6 + xuYWVm1urK8uzc9MjNr7HlpMhu+Kcq9dRgPORA+U4/MN3DTgjpMqsvJK65rN1h7b8Mvp + +eW1za3tnV2s2tne2lxbnp9+OWzrsZqb60rzshTSOOCmueSm0EI40XBbqjRl9cYHHX32 + sck5wN7efbWHWa92twF8bnLM3tfxwFhfplHBjRnNCaFRXPlNoYeE80XJ6dkFFfo7bQ/7 + h8ZnFlc3tnf33uwfYNX+m73d7Y3VxZnxof6HbXf0FQXZ6ckifngI/RRuFpcvkinV2srb + JkuXbXhidnn9j529NwdvMevgzd7OH+vLsxPDti6L6XalVq2Uifhc1unc8BgE7ipDa3vP + s5HJ+ZWN7VeA/e49Vr17e/Dm1fbGyvzkyLOe9lZDFeIWC77IXagz3LX22semFlY3d/b2 + AfsDVr1/93Z/b2dzdWFqzN5rvWuAB+Fp3PA11p9CZ3EJv11w/4tRH9xzH/mf2oVLPvD1 + BD4uJSkZObd0jWbw+8X04trW7t7B2/cfMFLDpT68f3uwt7u1tjj9Avw2N+pu5WSkSOAD + E76g+FzycJ/1v4bH77N21P37efx2789Zv+rx+6wddf9+Hr/d+3PWr3r8PmtH3b+fx2/3 + /pz1qx6/z9pR9+/n8du9P2f9qsfvs3bU/ft5/Hbvz1m/+h/89vrC+cm3eu5zOvfr/b// + wXrKBhf75+/91193XnWEmzgf7H76LZwPPu3+uvNBdB57XVvZ8Ok8duu8zmO3Pp3HNlRq + r7s/jz16/j04PrMAB7K7r//ax6y/XsP598rCzPjgV51/H9o3tDzoeGwfnZxdWtvY3sG/ + b9jZ3lhbmp0ctT/ueNDypX2DY7+TdCUrr6S22dzebRsah/3O6sbW9p87WPXn9tbGKux3 + xods3e3m5tqSvKwrSafvd5z7NLljn9YG+7QRtE9bWf99E7N+X19B+7QR2Ke1OfZpxMLY + 5T7NG/aXjFDH/lJbpTfes3b1Px+dmJpdWPptZRWrVn5bWpidmhh93t9lvWfUw7qB2F+G + wt715P7S2+/zvliD9sVtHb0Dz0fGf5n+dW5+Aavm536d/mV85PlAb0cb2hdr3O6LYT9P + d+7nc4ur9cR+vt8+NDo+MTmFWZMT46ND9n5iP6+vLs517ufpLvfzKA8R4sxDaCEPYYRg + QXefzT44PDKGWSPDg3ZbXzfECoyQh4AxIcY7xGUe4pIjfxIpFEP+JK+4CmIz5jZrZ/fj + JwNPMQdQnj0dePK4u9PaBtj1VcV5kD8RC2E97zJ/gnJKH/M+GeoClPdpMd1ra+942NWN + OfDT0931sKO97Z6pBeV9CsBuN3kf+EJI5Kt4znxVSVWNvrHFZL7/k+VnzAGr9p8tP903 + m1oa9TVVJc58FQTaiHzVxWO5AiLPBkEllGdLSFGqbuQXletq9YamH1CgrfUuRrWiONsP + TQZ9ra68KP+GSpmS4MizUVzk2Zz5QUgqRQogGZaeqc7TFpVVVtfUf48ChHh1W/99fU11 + ZVmRNk+dmQ5TIoh02O0qP4jymhQagw3Bx/ikFEWGSp2r0RaVlJZXVFbhDWxWVVaUl5YU + aTW5alWGIgWweRw2g4YCsifyml5EHNmRjwXwBEj1KjNV6hs3NfkFWm0hVmm1BfmamzfU + qkwlJHsTAPtQPvZoLMzLC+WRIbVOBHshjyxOlKVeSVNey1Spsq9DQBirrmerVJnXlGlX + UmWJYpRHJmK9KLl+PK6JuIn8NwpSszmR0cI4cYJUliK/rFCkEQlwlMrGpfQ0heKyPEUm + TRDHCaMjUXAdxahPyX878vYUR96eFy2MjRdJEpKkyckQf8es5GRpUoJEFB8rjIamAIqt + o4aDy7w9MpwoCoDjqN/AjYyKFghjiYIDNBxwSkTUG2KFguioSK6j3+DAPnlXwrR/qsFA + n4QOfZIwDjcikiiUYG+U8Ik6SWQElxMGfRI69EnIqHvkuk/yCZyEmjB0BjOE7SjwQIMH + t8Id9R12CJOBqANIbrC9nDUvoi9FgYoXnc5wFqZY2EXUpRh0OpS9KI6+FKqoue5LfQRH + TS+So592fgU1op5G9NOgWuds1p2CDSMOM04064g+IAn1AYlGILTzcIu4NJn0VX1AdHMS + 5KgU6OP7uYDprEPi/gPql0T/kqiOnmq28wPUWdJFfddzL7wCwse665FU1fHP+s/oyPbD + wtkxPnxd+BmM/Brow78L+ivnqcMsnp89Dngc8DjgceCoA/8DzflMvgplbmRzdHJlYW0K + ZW5kb2JqCjE5IDAgb2JqCjI4MjgKZW5kb2JqCjIwIDAgb2JqCjw8IC9MZW5ndGggMjEg + MCBSIC9OIDMgL0FsdGVybmF0ZSAvRGV2aWNlUkdCIC9GaWx0ZXIgL0ZsYXRlRGVjb2Rl + ID4+CnN0cmVhbQp4AYVUz2sTQRT+Nm6p0CIIWmsOsniQIklZq2hF1Db9EWJrDNsftkWQ + ZDNJ1m426+4mtaWI5OLRKt5F7aEH/4AeevBkL0qFWkUo3qsoYqEXLfHNbky2perAzn7z + 3jfvfW923wANctI09YAE5A3HUqIRaWx8Qmr8iACOoglBNCVV2+xOJAZBg3P5e+fYeg+B + W1bDe/t3snetmtK2mgeE/UDgR5rZKrDvF3EKWRICiDzfoSnHdAjf49jy7I85Tnl4wbUP + Kz3EWSJ8QDUtzn9NuFPNJdNAg0g4lPVxUj6c14uU1x0HaW5mxsgQvU+QprvM7qtioZxO + 9g6QvZ30fk6z3j7CIcILGa0/RriNnvWM1T/iYeGk5sSGPRwYNfT4YBW3Gqn4NcIUXxBN + J6JUcdkuDfGYrv1W8kqCcJA4ymRhgHNaSE/XTG74uocFfSbXE6/id1ZR4XmPE2fe1N3v + RdoCrzAOHQwaDJoNSFAQRQRhmLBQQIY8GjE0snI/I6sGG5N7MnUkart0YkSxQXs23D23 + UaTdPP4oInGUQ7UIkvxB/iqvyU/lefnLXLDYVveUrZuauvLgO8XlmbkaHtfTyONzTV58 + ldR2k1dHlqx5erya7Bo/7FeXMeaCNY/Ec7D78S1flcyXKYwUxeNV8+pLhHVaMTffn2x/ + Oz3iLs8utdZzrYmLN1abl2f9akj77qq8k+ZV+U9e9fH8Z83EY+IpMSZ2iuchiZfFLvGS + 2EurC+JgbccInZWGKdJtkfok1WBgmrz1L10/W3i9Rn8M9VGUGczSVIn3f8IqZDSduQ5v + +o/bx/wX5PeK558oAi9s4MiZum1Tce8QoWWlbnOuAhe/0X3wtm5ro344/ARYPKsWrVI1 + nyC8ARx2h3oe6CmY05aWzTlShyyfk7rpymJSzFDbQ1JS1yXXZUsWs5lVYul22JnTHW4c + oTlC98SnSmWT+q/xEbD9sFL5+axS2X5OGtaBl/pvwLz9RQplbmRzdHJlYW0KZW5kb2Jq + CjIxIDAgb2JqCjczNwplbmRvYmoKOCAwIG9iagpbIC9JQ0NCYXNlZCAyMCAwIFIgXQpl + bmRvYmoKMjIgMCBvYmoKPDwgL0xlbmd0aCAyMyAwIFIgL04gMSAvQWx0ZXJuYXRlIC9E + ZXZpY2VHcmF5IC9GaWx0ZXIgL0ZsYXRlRGVjb2RlID4+CnN0cmVhbQp4AYVST0gUURz+ + zTYShIhBhXiIdwoJlSmsrKDadnVZlW1bldKiGGffuqOzM9Ob2TXFkwRdojx1D6JjdOzQ + oZuXosCsS9cgqSAIPHXo+83s6iiEb3k73/v9/X7fe0RtnabvOylBVHNDlSulp25OTYuD + HylFHdROWKYV+OlicYyx67mSv7vX1mfS2LLex7V2+/Y9tZVlYCHqLba3EPohkWYAH5mf + KGWAs8Adlq/YPgE8WA6sGvAjogMPmrkw09GcdKWyLZFT5qIoKq9iO0mu+/m5xr6LtYmD + /lyPZtaOvbPqqtFM1LT3RKG8D65EGc9fVPZsNRSnDeOcSEMaKfKu1d8rTMcRkSsQSgZS + NWS5n2pOnXXgdRi7XbqT4/j2EKU+yWCoibXpspkdhX0AdirL7BDwBejxsmIP54F7Yf9b + UcOTwCdhP2SHedatH/YXrlPge4Q9NeDOFK7F8dqKH14tAUP3VCNojHNNxNPXOXOkiO8x + 1BmY90Y5pgsxd5aqEzeAO2EfWapmCrFd+67qJe57AnfT4zvRmzkLXKAcSXKxFdkU0DwJ + WBR9i7BJDjw+zh5V4HeomMAcuYnczSj3HtURG2ejUoFWeo1Xxk/jufHF+GVsGM+Afqx2 + 13t8/+njFXXXtj48+Y163DmuvZ0bVWFWcWUL3f/HMoSP2Sc5psHToVlYa9h25A+azEyw + DCjEfwU+l/qSE1Xc1e7tuEUSzFA+LGwluktUbinU6j2DSqwcK9gAdnCSxCxaHLhTa7o5 + eHfYInpt+U1XsuuG/vr2evva8h5tyqgpKBPNs0RmlLFbo+TdeNv9ZpERnzg6vue9ilrJ + /klFED+FOVoq8hRV9FZQ1sRvZw5+G7Z+XD+l5/VB/TwJPa2f0a/ooxG+DHRJz8JzUR+j + SfCwaSHiEqCKgzPUTlRjjQPiKfHytFtkkf0PQBn9ZgplbmRzdHJlYW0KZW5kb2JqCjIz + IDAgb2JqCjcwNAplbmRvYmoKMTMgMCBvYmoKWyAvSUNDQmFzZWQgMjIgMCBSIF0KZW5k + b2JqCjI0IDAgb2JqCjw8IC9MZW5ndGggMjUgMCBSIC9OIDMgL0FsdGVybmF0ZSAvRGV2 + aWNlUkdCIC9GaWx0ZXIgL0ZsYXRlRGVjb2RlID4+CnN0cmVhbQp4AdWWd1gTSR/HZ3fT + Cy0QWoDQe+8gvQYQkCqISkgooYQQioDYkMMTPAsqImABPRBR8CyAnAURxcIhYK8X5BBQ + z8OCqKi5Dbx4/vHef+8/7+yzM5/9zm9/Mzsz+zxfACg9bIEgHZYBIIOfIwzz82Qujoll + 4h8AHGAAMpAFMmxOtsAjNDQI/Gt5fwdAks6bppJc/xr23ztkuYnZHACgULQ7gZvNyUD5 + JMpfOQJhDgCwhAdW5AhQRkpQlheiE0S5SsLJc3xEwglz3DUbExHmhcbcAoBAYbOFyQCQ + RajOzOMko3koKAILPpfHR9kCZVdOCpuLsgBlk4yMTAnXomyQ8F2e5O+YzU74lpPNTv7G + c9+CvokO7M3LFqSzC2Yf/pdVRnouul6zRQ6tKfz04CC0paP3OJftHTjPgvTZPZvVE/mR + 4fM6PyE4ZJ6ThL5h8yzI8fyOQyPm9cIUr+B5Tsz2+ZYnlR0g2bPZ/MLcsMh5zs4L95nn + wpSI6HnmJnp/05N4vqx5nZfD+jZWWmbgtzkAb+ADgtCLCayAxezlC9ARcxLz0T0EwCtT + UCDkJafkMD3QU5dowmTxOWYmTCsLS8mW/v8Uyf82N9u3N2b/I0hJcpT/o+UvAcBdGT3L + 0/9oUej53zsEgOKtfzQDTQA0FQBoT+DkCvPm8mEkDRaQgDSQB8pAHWgDA2CKrqYdcAbu + 6OoGgBAQAWLAMsABKSADCMEKUATWgVJQDraCnaAa7AMHwCFwFBwH7eAMuAAug+tgANwG + D4EIjIIXYBK8BzMQBOEhKkSDlCENSBcyhqwgB8gV8oGCoDAoBoqHkiE+lAsVQeuhcqgC + qobqoCboF+g0dAG6Cg1C96FhaAJ6A32CEZgCy8NqsB5sDjvAHnAgHAEvhZPhLLgQLoE3 + w1VwPXwEboMvwNfh27AIfgFPIQAhI3REEzFFHBAvJASJRZIQIbIaKUMqkXqkBelEepGb + iAh5iXzE4DA0DBNjinHG+GMiMRxMFmY1ZhOmGnMI04bpwdzEDGMmMV+xVCwDa4x1wrKw + i7HJ2BXYUmwltgF7CnsJexs7in2Pw+HoOH2cPc4fF4NLxa3EbcLtwbXiunCDuBHcFB6P + V8Yb413wIXg2Pgdfit+NP4I/jx/Cj+I/EMgEDYIVwZcQS+ATigmVhMOEc4QhwhhhhihD + 1CU6EUOIXGIBcQvxILGTeIM4SpwhyZL0SS6kCFIqaR2pitRCukR6RHpLJpO1yI7kRWQe + eS25inyMfIU8TP5IkaMYUbwocZRcymZKI6WLcp/ylkql6lHdqbHUHOpmahP1IvUJ9YMU + TcpMiiXFlVojVSPVJjUk9UqaKK0r7SG9TLpQulL6hPQN6ZcyRBk9GS8ZtsxqmRqZ0zJ3 + ZaZkabKWsiGyGbKbZA/LXpUdl8PL6cn5yHHlSuQOyF2UG6EhNG2aF41DW087SLtEG5XH + yevLs+RT5cvlj8r3y08qyCnYKEQp5CvUKJxVENERuh6dRU+nb6Efp9+hf1JUU/RQTFTc + qNiiOKQ4raSq5K6UqFSm1Kp0W+mTMlPZRzlNeZtyu/JjFYyKkcoilRUqe1UuqbxUlVd1 + VuWolqkeV33AgBlGjDDGSsYBRh9jSk1dzU9NoLZb7aLaS3W6urt6qvoO9XPqExo0DVcN + nsYOjfMaz5kKTA9mOrOK2cOc1GRo+mvmatZp9mvOaOlrRWoVa7VqPdYmaTtoJ2nv0O7W + ntTR0FmoU6TTrPNAl6jroJuiu0u3V3daT18vWm+DXrveuL6SPku/UL9Z/5EB1cDNIMug + 3uCWIc7QwTDNcI/hgBFsZGuUYlRjdMMYNrYz5hnvMR40wZo4mvBN6k3umlJMPUzzTJtN + h83oZkFmxWbtZq/MdcxjzbeZ95p/tbC1SLc4aPHQUs4ywLLYstPyjZWRFceqxuqWNdXa + 13qNdYf1axtjm0SbvTb3bGm2C2032HbbfrGztxPatdhN2OvYx9vX2t91kHcIddjkcMUR + 6+jpuMbxjONHJzunHKfjTn85mzqnOR92Hl+gvyBxwcEFIy5aLmyXOheRK9M13nW/q8hN + 043tVu/21F3bneve4D7mYeiR6nHE45WnhafQ85TntJeT1yqvLm/E28+7zLvfR84n0qfa + 54mvlm+yb7PvpJ+t30q/Ln+sf6D/Nv+7LDUWh9XEmgywD1gV0BNICQwPrA58GmQUJAzq + XAgvDFi4feGjYN1gfnB7CAhhhWwPeRyqH5oV+usi3KLQRTWLnoVZhhWF9YbTwpeHHw5/ + H+EZsSXiYaRBZG5kd5R0VFxUU9R0tHd0RbRosfniVYuvx6jE8GI6YvGxUbENsVNLfJbs + XDIaZxtXGndnqf7S/KVXl6ksS192drn0cvbyE/HY+Oj4w/Gf2SHsevZUAiuhNmGS48XZ + xXnBdefu4E4kuiRWJI4luSRVJI0nuyRvT55IcUupTHnJ8+JV816n+qfuS51OC0lrTBOn + R6e3ZhAy4jNO8+X4afyeTPXM/MxBgbGgVCDKcsramTUpDBQ2ZEPZS7M7cuRRY9OXa5D7 + Q+5wnmteTd6HFVErTuTL5vPz+wqMCjYWjBX6Fv68ErOSs7K7SLNoXdHwKo9Vdauh1Qmr + u9dorylZM7rWb+2hdaR1aet+K7Yorih+tz56fWeJWsnakpEf/H5oLpUqFZbe3eC8Yd+P + mB95P/ZvtN64e+PXMm7ZtXKL8sryz5s4m679ZPlT1U/izUmb+7fYbdm7FbeVv/XONrdt + hypkKworRrYv3N62g7mjbMe7nct3Xq20qdy3i7Qrd5eoKqiqY7fO7q27P1enVN+u8axp + rWXUbqyd3sPdM7TXfW/LPrV95fs+7eftv1fnV9dWr1dfeQB3IO/As4NRB3t/dvi5qUGl + obzhSyO/UXQo7FBPk31T02HG4S3NcHNu88SRuCMDR72PdrSYttS10lvLj4Fjucee/xL/ + y53jgce7TzicaDmpe7L2FO1UWRvUVtA22Z7SLuqI6Rg8HXC6u9O589SvZr82ntE8U3NW + 4eyWc6RzJefE5wvPT3UJul5eSL4w0r28++HFxRdv9Szq6b8UeOnKZd/LF3s9es9fcbly + 5qrT1dPXHK61X7e73tZn23fqN9vfTvXb9bfdsL/RMeA40Dm4YPDckNvQhZveNy/fYt26 + fjv49uCdyDv37sbdFd3j3hu/n37/9YO8BzMP1z7CPip7LPO48gnjSf3vhr+3iuxEZ4e9 + h/uehj99OMIZefFH9h+fR0ueUZ9VjmmMNY1bjZ+Z8J0YeL7k+egLwYuZl6V/yv5Z+8rg + 1cm/3P/qm1w8Ofpa+Fr8ZtNb5beN72zedU+FTj15n/F+Zrrsg/KHQx8dPvZ+iv40NrPi + M/5z1RfDL51fA78+EmeIxQK2kD3rBRC0hpOSAHjTCAA1BgDaAACkrjk/PBuBOvhh/3n6 + N57zzLNRdgDUuQMgsXdBXQDsQls99JmBthJbiFo6eO0/N6pISnaStdUsQBQV1Jp0icVv + xADg4wH40i8Wz1SJxV8qUa/zDoDzwXM+XBItg/r7/YiFjW9QZ6bb7OvfV38DJafpNwpl + bmRzdHJlYW0KZW5kb2JqCjI1IDAgb2JqCjI2NjMKZW5kb2JqCjE1IDAgb2JqClsgL0lD + Q0Jhc2VkIDI0IDAgUiBdCmVuZG9iago0IDAgb2JqCjw8IC9UeXBlIC9QYWdlcyAvTWVk + aWFCb3ggWzAgMCA2MTIgNzkyXSAvQ291bnQgMSAvS2lkcyBbIDMgMCBSIF0gPj4KZW5k + b2JqCjI2IDAgb2JqCjw8IC9UeXBlIC9DYXRhbG9nIC9PdXRsaW5lcyAyIDAgUiAvUGFn + ZXMgNCAwIFIgL1ZlcnNpb24gLzEuNCA+PgplbmRvYmoKMiAwIG9iago8PCAvTGFzdCAy + NyAwIFIgL0ZpcnN0IDI4IDAgUiA+PgplbmRvYmoKMjggMCBvYmoKPDwgL1BhcmVudCAy + OSAwIFIgL0NvdW50IDAgL0Rlc3QgWyAzIDAgUiAvWFlaIDAgNzgyLjg5IDAgXSAvVGl0 + bGUgKENhbnZhcyAxKQo+PgplbmRvYmoKMjkgMCBvYmoKPDwgPj4KZW5kb2JqCjI3IDAg + b2JqCjw8IC9QYXJlbnQgMjkgMCBSIC9Db3VudCAwIC9EZXN0IFsgMyAwIFIgL1hZWiAw + IDc4Mi44OSAwIF0gL1RpdGxlIChDYW52YXMgMSkKPj4KZW5kb2JqCjMwIDAgb2JqCjw8 + IC9MZW5ndGggMzEgMCBSIC9MZW5ndGgxIDkxNDQgL0ZpbHRlciAvRmxhdGVEZWNvZGUg + Pj4Kc3RyZWFtCngBvVp5eFRFtj91917S6e70vqS701s6+0ICbULShE5IgIRAEBMkmAQS + EiQaMcbBESYqjBIVRQSi+DkuGAKM0oQIDQw8hg9F33PGZRSXcRZHdHzzzOe8eTijI+l+ + 594OEfKNfvzhN31TVedU1a069Tunzql7b3rX3tYOSdAPNNQvbe3pAOmX1gtAwiu6W3sS + vPYClnNX9PU6EzybDkCv6ehZ1Z3ghUcB5PZVa9ZN3J+yEkA13NneiqX0u4h5cSdWJFgy + DUtPZ3fvjxK8dhTL0JqbV0y0p4SQT+tu/dHE/PAh8s6bWrvbscRfWj1mnp6bb+2VWEhT + YhnuWds+0Z80onyvA8FaNdwMMrgReKCQVkMzAP+Z3A4Mtort+FuZpdh2Q3Lpl6ARJP6G + 2oek8mXXL8591X7Rr9gqfI0Vskv9xZILxAIASoLtY4qtky3SfZipo9CQGYUaTOWYijBl + Zs4yQT8ZgocxPYWJhi5yP6zDtBnTY5iYSWovckfJ/SOMEDpG1oGFzA0pGMdindlhkisc + b0UJN/qk433Tx8eJGbX3ETGPJIFslpw8RX4GK8FBngMvuQOqIZ08fiiwxtGCTXuhB1M/ + JlrKCdk7klrgOEmywMsQvMcHqQw57Phzfrbjk/woRUYcp/1RBotfpiIXSnacsj/p+A/7 + KsdJTPsTTfsC2OOwY699jWNbapQ8PuJ4xB4leM/WRHGbHW897OgO7HCszJfa5++IUvtH + HEFsXxJSOIpnuBxF9vOOXH9UIMhn2+c7MvJ/5fDgjdjNiYN6QxqHzb7NcQ02pdor/ddg + Ok72kV2QQXaNeOc6jiGJyz1UE5ixI0p+fKg6Pd8bJXeEiqvTdwSq/d7AfIc3UOX3I73k + FX4jfz0/iy/gM/l03se7eCuvE7SCWlAJSkEuCAIfJT8fKXdwx8l+KEdY9h8SOIGNkhew + kjlOnpcqnz8iMAIlgKCLxv+IxktAFyX7R9UihcRhTqK4KHn+UKLq+ZCDESlGalBTIo0Z + 5kARgYK5ECEPRjnYZOgrN5VryzTBqvB3ZS1Sy6U887t/JmKP7JjX0BjZZ2+KFIhE3N50 + qbvpEvGdZe9t2NRekZk5b9G6Q309qzsq292VLe7Kdkwtkfv7Ok2R/jan8+DqHrHBGaF9 + LW0rOsWytT3S424PR1a7w86DfdJ9U5o7xOY+d/ggdFQubjzYEWoPj/SF+irdreGmQ20V + a5uvmGvz5FxrK/7FXBXiYGvFudqk+6bM1Sw2t4lzNYtzNYtztYXapLnExVd2NVTc2ovW + 6azsmueMpDdEahYubYw4W5vCUTKEleHbgD0FavYEpLP9YGFywQEQfx/TB2IZuzb+KXsW + 1LHu+P/SJajUo2KiYuWlcAoehF1wADgYRjodlsMgvEpW495eBqNwjqRCDvpeBqIwH14j + 8fib0AG7sX8vnIbtcBCUeE836LF1C/HG70A+hHQbbIw/Ax6YAT+FExDEUbfAWHxv/BC2 + LoJrYR/sx/v/i7ipg0xK/IX4eRBgIY65EVvejM+PHwAtZEEF1GPtRjhJvPQH8U4wQQlK + 9wT8DJ6GX8Ln5G4yGu+M98XfiH+EpmoCGzTgtZ6Mko/oA8xP40/E/xKPIRLpkIGztsA2 + eBbHP4DXKXStleRG0ku2ke1UiLqbGmU2scbYOOIQgDl4VaNXvg8ROApn4G/wNfmCMtFq + upd+KV4U/z9QwDxcpbiSdujD6168tuCajhOO5JHZpJ6sJ4+S7eQ3VAZ1LdVI3U79iPqU + rqOX0evo3zC3MiPsA+wgp4h9GT8ePxt/B4xgh+thLWzA1Z2GN+AC/JPQOJaNeEkJqSDL + 8eonu6ij5GlylKonp8gb1D7yB/Ix+YJ8Q7GUktJTmVQvtY3aT52mfk130dvpx+g/0F8y + ZSzFPs1+wnn538baYptjv46XxD+Kf4UuVgAXaqYC6uAGaMXV9sA0+Amu4nm8DqDWzsBL + 8Kp0fUxsMAZfIQpAtMRCCkgtXnVkAekgXeRJcgyvk5Isf6dQEZSM0lBGykY1UG1UN9VP + vUP101Y6g55LL6UP4PUKfY7+hv6GYZkURs/MYWrgAaabeRyvIWaYGWFeZ4NsGVvHLmH7 + 2c3sA/QK9k32HLeB28KNcF9wf0W3OJ+/mX8AtfMq2uwv0Za//THEg9IXwE2wgoRJG+xA + bTxNWmEArWsluQ/x6oH0eDO9gZ5D5aE1nIQfo7U+DuthM70Mno6/R++Dd9FS1uCQ/bCH + qQA7uxO1czfkoRVNXKFARiDd7/N63GkuJ7p8m9ViNhkNel2KVqNOUirkMoHnWIamCGRV + uqtanBFfS4Txuaurs0Xe3YoVrZdVtOBWdkaqruwTcYr3tWLTFT1D2LNjSs9QomdosidR + O0uhNDvLWel2Rn4VdjujZOnCRqQfDLubnJExia6V6IclOglplwtvcFaaOsPOCGlxVkaq + +joHKlvC2VnkaAjhkGdniY4jBApx4AjMbl2PDhZmiz0qIxZ3uDJidiONbbS3snVlpH5h + Y2XY6nI1YR1WLWrEObKzuiIoJ9yvXOleeX80BG0tItW6rDFCtzZFqBZxLE1mxOgOR4x3 + fGL6lr1EVT5wWWOE8la1tg9URUIt9yO4Itsicq0PIDevwYnDUpuaGiNk04QQooyrUVJR + 3ERM8LasdkZk7gp358DqFgQXFjWOWEIWyflGoL5xxBwyS0x21lHThhIXrv5o9qzsWWJZ + 4jJtSJR/vidR/9YpsTRtOPNHLOctmgSAiAi4a1DOiHOFNIkbhZ0hZu0zYGDFDMQJf00E + l9mF8syOUGgztDfCemtaI/0Nl8ToDCeEa1kdHpGZLVIQqmjC/i0D6mtQU9hf7XYOfInR + usU99vmVNa0TNZxX/SWIjaKiJ20lQlov0X1isPTiqjtN7k5Rv32STpF3myovq0BehEaU + OaLDAF7f6Io4m7ACT5NZ86Igq288SMiWpiiJb4pC2H4Uz6j0DcuxOUs0ta4wzo9MdhZW + ZLiQyslyVuHMVaKtOAecAzUrB5xVzk40JsYrldjQPtCUiwg2NCJOsBhnDDVZJ8n2pqZr + cJxccRy8BbsPNOEIqydGwFKqyh3HTnlZGExpX33jwsZIf9gaCYWbUAtovqfqGyOn0HKb + mrBX/qSkKPH6LtOEzAUoc34GthcmRsGzSz8O0TQwII7Z0Oh2RU4NDFgHxP2W4KMEplaE + JiqiIHYRIY+S/nq8Fwu3yyrpwOV2oVhNIqbT0KQvWRSe2b8f4eJJufHO6ShtsYTwjB8I + 4eDVIHzNVSFcMinpFQiXoswlIsIz/30Il12BcPn3IxyalBuFnIXShiSEK34ghGdfDcLh + q0K4clLSKxCuQpkrRYTn/PsQrr4C4ZrvR3jupNwo5DyUdq6E8PwfCOHaq0G47qoQXjAp + 6RUI16PMC0SEF/77EF50BcIN34/w4km5UchrUdrFEsJLfiCEr7sahBuvCuGmSUmvQHgp + ytwkInz9JMIhawQu98P9U9wu/OCOedllkONJidVCBXMrLMLUhw/VJVhWU0GwYTmTnIWN + mDZz+2Aj8mIqofbBZuxXgX2MWOpxiEvvfpT4RFKKfCuYpQdyGmkGWKzF10SYAM/xMpDj + E4n4U+K7FpVEiVnyBDUNYqST/IUapYEexrP3V0wv8wZbzW7hbuJO8ouxF4XPAYB1J/C5 + gIfyxLshIRcDOCYB3xXBG5hEHmn6wygwmMR3SPyHcEySY0nmMRyFhSWZefmFGpfGj6mC + 2RK9+Cf2xD9nR5nab/A9A46+KP6hdOJPxme5UvhdaEZGHpGrFValzV9Yre6SrVbzQUGr + lNHWAt4js6uV9pJMKidQcqSEKinI8GrVPCvY/GlGW5QMhNxGu4P323MUlL1IUcqXltp0 + fCBj2GMpswZsc5P9M8wzy35BduKDzlGyA/B9Qt2F2rELY3Xqv9eeHz+jDeZCefmYeI1p + gxqtMdis0QZzxnLGCJYaYzA/b/a6UHrxdH0aELOXFCe7wJRqdYHBqXMRVxpMp1xgsRtd + RO/CDN+fZRJ1qfi8ftddd0EzafYYCgumF88kKpJMOJ7Tk+LpxUXTfO40nuPdZaSwAB8Z + NDrshFOoiDvN7/OLha9oWvH0FKJaW3dD0w5XZ0F3W34DGS3TK++548ESl3yY/cezJ/pu + M3qVqZqMLF9zhkE2/dd3bj9xbOfA60uzaoa26m2cKsmWu4qsEbJM2csa5mc0vLyrunpw + fKctjaY3KbkKd6h69Yv3bd+dQs6Luu+L/57xsqdBA6nQE8oZ4vfY3rXRaUJyKsUCGO0s + r5Gn2hUKnV+wOC056hwSAI3Z4bzXdaJZArW0dvz8eRHVMUA08U8T1CTQM2kNnNzA6XxE + K8dMzxt9JEWW6kOwiIgTNKcUakQotBodJSGgd3sSIHF6ndFQ2HegZHfLK1///YM7FhcE + h6iOrVsf/PFR35zT7Onx/6ldGBuLXYjFIiXu2s3rPzu59/eH39y5/KBkz/iUS7/B1IEF + rLAnlLvHTAZNw8I+Ez1X0OzS0bSOs1v4JLtOYeWtVqParyW0n9JY7HK/0WzDV3/8Idfa + 9RMWgysrrR0LBtFKJiwGCfWYZB7TwCx4lXq5D1QpalylJlnNm5FjgXYRQjG0wpDkg2Qt + ZjIT5yMM4Vy4cslURGNRl0omI9kLGIzuHDQANJWEVRSK5kAVqaGQp859bDygXrvh53Pz + 7nuk5x7zgdS/Hn/rn0T7to2pi7y74p7h7qee/nDz7e+8RAo/xUf0a3B+qI5/wFjw6dqG + b2K8RBlat1N4zLLHQbMqKpnV6VXaZL0upAzphICFzFMcps+Sl+mz1veE92XnHO+5PzN+ + 5lac1ZzVUssE1uVJftxg9wQ5nje47DZebjcovPxO2x7bEbQVxmtI9tpYs1zJa1T+ZLuf + tfg9ObzfbPb533YNJYwEbUQykbfHg9ogbrcgFrnNiR2IVOl4qXoMayVUq8DNsDS+uiAs + wzl8GrVWnaLWqRlO6U2zenzgBLuPpNplRt4HCr3KR5JUbosLq1jMBBPin6TGTNySiT0p + gZyRmXEXuaUZbmluRqjx0rtS0fSmF09HoHFPcu400CDYxOfHTcrxhBo9N6NYq774Bfvw + zgcX5+kO8gvyF62bteiV2F+I6U/EoUif+/ydwyxxM3NuvHbhmrnPPPtSc/Gckq059TY1 + ceP7G4pUxHy3Vd19aICIHwjQg9twwxnZt/CNT20ok7dzcjtNknVBQxKnlZuNRosqSRMw + anltssqholQXdWaT+aJr1YaEJY43B89IQNVVtoc/Rehw45WWj72NpqidXlxYYDDqRfvh + 9IV6twavosKiF93loxqP0WZWLHKOjI5s385WTFtGUbspcu0LWy6upJ/YMiz55ZmxEvoz + tBUHZOMbvyOh2mJdjVAjaxSaZPcp91qH7Xv9Q5lHrYqQQBvSAqoz8jR0vQwXsJvlWrs8 + OYfPyWFtdI4hJzvAWvKUKn9Smc9vM+fm3etaWzHpeYOiBYyf/xL1fMn3lo9Jak/oPcud + bklVaDxetc+d6vNBugUzjULlgmSVMslrT/MRvzWA+0mpdUnaRYebcLkJnwuo1aJCjY7n + XGk+fyGqWFSv5FU9omZBcr7S7kJXTKg7lxcWDZX2xF59/nPVkST/zHteD/no4sH1L8S+ + IfwxEt79k5NV3m13nl6QFXuTqShzz773YsFrfR/seq7aX/rIkt8tqv8HsZMkkhN7+tTI + DY+/eOLAio1UtuR/NqKySybiaXHIxn/CoPI5Wi5DHaNdBHgaHYdsn6stAU5p7Znx0jOT + ai2vRZWiZ3RrUJMbj+CPyfjmHHviNcmGNuPYM6WxAyE8K9ByFgfFMYE2M+xlQ46XXhow + Mdjm0VExGEtjoHycl5kDPtgUKuEFXsUlGwWjypjsF/y4havNSxSrFEq3V26xu81yijF6 + XXajPYnjgbPavHSKPB3n1ATwowIZsQTEbykhOZAcLyrH7E+PkqRD3y5t/Lz6wtiF8Qlh + jKWi3Y7hXjcGxUArbnkxDOgxOooh0XgpMro1Yqzk9IjCNGlDIrVxJDSt6Zb+uixP6TPt + 79VlHL+xdvVjRyyBno49o0zu4ALPzHJP1ZKGJxZvGZ9OfXZj/Zah8a3U8e6CeU++Pv6K + GOtw3fQY2rkZI8PyUP4R7ixHMZyO8+v6uF6e1SkpnUmNEQ84k0Ju4S0WUAZkFhvJMQXM + YLbisYO7YmWSS0tYM65rTBMMksSCiLiky5YirgB9jIrgKsjG/fP3dZ6vzzpiz9sQCsyd + kW0dJXtQ/uWLfnbdM+MLqWfbSlcmGSqKbukafx2FRV9eEn+fcWE8U+J7bjM8HCocFHao + HzM8xwwLQ+q9hqjwivAu84nqv3XKawTObuKVdq3CzJvNesqfbLHK/HqzxRolMoxqE95Y + OgV9G9Ekt5uFx0+fIkWGnlND+QhvRIpNQkquU/qAqDETDBjEaBVmkm8Vs0wMXh5t0YSO + MHJp0YtSeD5KBK4/bsqbf+y5HTuexY8JF2P/+F3sItH+meslyUM7lj96cWT/efqD2OcY + xsdjL5DMi3hYCrG4VdDGqUfQPjWwIOTz076k6fQchlEJakol08iUfkFUkUYuWFJIjjqg + AbM2JUoqUTUJVymeSOrUoousLT8zfkaMNqKtTViaqJZJX6lxb96v330ja7Krrer7HkEz + Olq8i6JP0tSBteODos1UxN+lDzPz0C/mkpzQQzNkg+wO7WO6Qf1gBpfu8fqLXVWuOZ45 + /iWe6/wdnlW+dcp1SetUfe5eT6+31zeUOpyVQmOYYrOZnBSw6K1Gm0mfrctJT1Z0CT5v + sZfypiXJmcwU08s2ewrP2HMez1Tk8jKVmuIh15VrcZgMJr+xLN3H+9Mt+SqHX10G/hxz + Xv7IZGzF7ZXwrUE1UuJyg7mYozmKAVY84Yrb7RZJy/NJNuXTey0+l8rhAhl+YiR0Fp6R + 2Qyk7Fqss+pMLuJMTnOBK02VJPjlLuLzyuQkm3Hhd2XMUjU2FzEbMJNCrOSEpUyyiktG + gUfgFMkF44HO78sVwyoebcU9zrsTIVY84jmIGIl1HB58/eQLwRseXjk403/rQ5tn9f72 + 6N9unE3tY31lj3V0VabX3X66ouv9339xlidHSP3SvOuuu77Sg6eStIyauwZ/sWVp58yC + OXWhqgxzij03q/LRh954/ynqa7QlY/wLSsYuxZ2z6MWkHPkpFYmS8pCXMQSNNKeSayzo + yvBrSwD0Kn0y7aAp+qLBbLZg3J04AU6Ju7mJwDumHj8vOVYx2opn1UvneF+RGHqHD+/f + 79PnJ6XqHLP9G5Zu3coujb2zbbxyRoqCUFtkwl2rqJe2SbFCH6uRYq+4s/8zdNOA/j7T + HhPNc0ZuhrZa26hdxd9O384/oBuEneygfqdhp3EYhg3qapinn2N8Vc+E2ZdZ6l52CIbI + HnbYyHrSWZPeaMB4o1cqku2CSnQEBiuuEnfWAaPedED5kAH9wduJg4UZn4rOm8aDQfwz + S07alHBotePBAnOuqby0tFTcP/iRNaTV68Fg6NYajSaWkG4tgOnenEz1+jNSIWBJmtHK + biHN+ABUyNEUT0mKLRIPWsXTy8h0Ukho2nXWd09bxRP9T/gCqbkZ6oJcNVumivW+RhyE + yV0V2xr7/IVYxygn7E7iXCbhUQ9Td3GQvlvci9Iv3o7f3f7VD79dQxgqoQq/39XgJ+v5 + sED6hih+qVsC18Ey6SaCXxeJRHH4/xYwp6ZhSU1FZnX7mr723q4VrdiSaBW7VGMSn5BX + YhL/lwPjBzyKaTemUUxnML2N6TymC3gjg0mHyYNpWnzih20wSRN8lr+Sb5vCr5jCS2u9 + 7P6OKe2rpvBdU3jxW9bl80v/E3PZeDdNab95Cr92Cn/rFL53Cr9O5P8fJ4dYIAplbmRz + dHJlYW0KZW5kb2JqCjMxIDAgb2JqCjU5MDEKZW5kb2JqCjMyIDAgb2JqCjw8IC9UeXBl + IC9Gb250RGVzY3JpcHRvciAvQXNjZW50IDc3MCAvQ2FwSGVpZ2h0IDcxNyAvRGVzY2Vu + dCAtMjMwIC9GbGFncyAzMgovRm9udEJCb3ggWy05NTEgLTQ4MSAxNDQ1IDExMjJdIC9G + b250TmFtZSAvR0lTVklCK0hlbHZldGljYSAvSXRhbGljQW5nbGUgMAovU3RlbVYgMCAv + TWF4V2lkdGggMTUwMCAvWEhlaWdodCA2MzcgL0ZvbnRGaWxlMiAzMCAwIFIgPj4KZW5k + b2JqCjMzIDAgb2JqClsgNTU2IDU1NiA1MDAgMCA1NTYgMjc4IDU1NiAwIDIyMiAwIDAg + MjIyIDgzMyA1NTYgNTU2IDAgMCAzMzMgNTAwIDI3OCAwIDAKMCAwIDUwMCBdCmVuZG9i + agoxNCAwIG9iago8PCAvVHlwZSAvRm9udCAvU3VidHlwZSAvVHJ1ZVR5cGUgL0Jhc2VG + b250IC9HSVNWSUIrSGVsdmV0aWNhIC9Gb250RGVzY3JpcHRvcgozMiAwIFIgL1dpZHRo + cyAzMyAwIFIgL0ZpcnN0Q2hhciA5NyAvTGFzdENoYXIgMTIxIC9FbmNvZGluZyAvTWFj + Um9tYW5FbmNvZGluZwo+PgplbmRvYmoKMzQgMCBvYmoKKE1hYyBPUyBYIDEwLjYuNCBR + dWFydHogUERGQ29udGV4dCkKZW5kb2JqCjM1IDAgb2JqCihEOjIwMTAwNzEzMDQxODIy + WjAwJzAwJykKZW5kb2JqCjEgMCBvYmoKPDwgL1Byb2R1Y2VyIDM0IDAgUiAvQ3JlYXRp + b25EYXRlIDM1IDAgUiAvTW9kRGF0ZSAzNSAwIFIgPj4KZW5kb2JqCnhyZWYKMCAzNgow + MDAwMDAwMDAwIDY1NTM1IGYgCjAwMDAwMjgyNzAgMDAwMDAgbiAKMDAwMDAyMTQwMiAw + MDAwMCBuIAowMDAwMDAxNTc0IDAwMDAwIG4gCjAwMDAwMjEyMzkgMDAwMDAgbiAKMDAw + MDAwMDAyMiAwMDAwMCBuIAowMDAwMDAxNTU0IDAwMDAwIG4gCjAwMDAwMDE2ODQgMDAw + MDAgbiAKMDAwMDAxNzUxNCAwMDAwMCBuIAowMDAwMDAxODU3IDAwMDAwIG4gCjAwMDAw + MDYzMjUgMDAwMDAgbiAKMDAwMDAwNjM0NiAwMDAwMCBuIAowMDAwMDA2ODMwIDAwMDAw + IG4gCjAwMDAwMTgzNzggMDAwMDAgbiAKMDAwMDAyODAwMSAwMDAwMCBuIAowMDAwMDIx + MjAyIDAwMDAwIG4gCjAwMDAwMDY4NTAgMDAwMDAgbiAKMDAwMDAxMzU5MiAwMDAwMCBu + IAowMDAwMDEzNjEzIDAwMDAwIG4gCjAwMDAwMTY2MzMgMDAwMDAgbiAKMDAwMDAxNjY1 + NCAwMDAwMCBuIAowMDAwMDE3NDk0IDAwMDAwIG4gCjAwMDAwMTc1NTAgMDAwMDAgbiAK + MDAwMDAxODM1OCAwMDAwMCBuIAowMDAwMDE4NDE1IDAwMDAwIG4gCjAwMDAwMjExODEg + MDAwMDAgbiAKMDAwMDAyMTMyMiAwMDAwMCBuIAowMDAwMDIxNTY4IDAwMDAwIG4gCjAw + MDAwMjE0NTAgMDAwMDAgbiAKMDAwMDAyMTU0NiAwMDAwMCBuIAowMDAwMDIxNjY0IDAw + MDAwIG4gCjAwMDAwMjc2NTUgMDAwMDAgbiAKMDAwMDAyNzY3NiAwMDAwMCBuIAowMDAw + MDI3OTAxIDAwMDAwIG4gCjAwMDAwMjgxNzYgMDAwMDAgbiAKMDAwMDAyODIyOCAwMDAw + MCBuIAp0cmFpbGVyCjw8IC9TaXplIDM2IC9Sb290IDI2IDAgUiAvSW5mbyAxIDAgUiAv + SUQgWyA8NjJjM2U5NGRkYzI0MzQ5YjFiNDQ0MjFmMDRiOTg4MzE+Cjw2MmMzZTk0ZGRj + MjQzNDliMWI0NDQyMWYwNGI5ODgzMT4gXSA+PgpzdGFydHhyZWYKMjgzNDUKJSVFT0YK + MSAwIG9iago8PC9BdXRob3IgKEZyYW5rIERlbGxhZXJ0KS9DcmVhdGlvbkRhdGUgKEQ6 + MjAxMDA3MTMwNDA3MDBaKS9DcmVhdG9yIChPbW5pR3JhZmZsZSA1LjIuMikvTW9kRGF0 + ZSAoRDoyMDEwMDcxMzA0MTcwMFopL1Byb2R1Y2VyIDM0IDAgUiA+PgplbmRvYmoKeHJl + ZgoxIDEKMDAwMDAyOTIyMyAwMDAwMCBuIAp0cmFpbGVyCjw8L0lEIFs8NjJjM2U5NGRk + YzI0MzQ5YjFiNDQ0MjFmMDRiOTg4MzE+IDw2MmMzZTk0ZGRjMjQzNDliMWI0NDQyMWYw + NGI5ODgzMT5dIC9JbmZvIDEgMCBSIC9QcmV2IDI4MzQ1IC9Sb290IDI2IDAgUiAvU2l6 + ZSAzNj4+CnN0YXJ0eHJlZgoyOTM3MwolJUVPRgo= + + QuickLookThumbnail + + TU0AKgAABZyAP+BP8AQWDQeEQmFQuGQ2HQ+IRGJROFwOCQZsRkAQOKR2PR+QSGJxaDtC + TAB+SkABmWAABS8APiZAAETWVy2RTmdTuIySDLigAB20MABSjRuBAB90sABKnAAd1GeV + OqVSfQVn1kACOuAAHV+q2GxWODVcANe0AAU2uyRiNRy2wgA3MACi7XGEWa0Ne1Wy43u+ + imEYCXgIAAXEAB/YsAPrHAAVZGIYC14K8WW4QXKX625vLQZwaEAOPSS6YUt9gB+6sAEP + XZO05XL5ikwbPXjb7Oz7HOZe9bzP2SMtikReHPnkAAD8uYzPCgADdGGXMA3W77rf3zZb + qJtrvAATeGUSpveUACH0YfE9yHdnA+yHPb5AB0/Xz+mD0N2gD5PYAA7AD4Ia9ztwEhR0 + QQ9QCgACcGoYbsIAADEJgABcLQMg8CN7DCDO8bT7hDBSGHrEgAGrE4ABfFTlOZAUNODA + 0SHqAB1RrECKDdHIACVHgACRH8DRfDiCnPIsWAOpqnoO4bioQ5B8gAeUpAACsqpA6jrB + QikhSHDwABFMAAAJMaEGnMzwPEeE1AAC02ybLDMoLLEsIO3KJS4+EZAAdc+AAEE/oYY9 + BAAd1CgBNR4AActFgADVHREmR8K8sEEHQAA00wwbgS3OM7PZIpzyPJIJIZT03rojk6No + AFVM1TaR07V74S9MARTFMiF1MsVdPbWLtQ2uM9T4dc/UAh8mTiiFhypKyHywu0tVg2tX + V/GC41BUSnVIuLQnBYoQLxPDLmzcitq7MYCLwbl1gAEl3XDXz3riel6KEogP3w7kmWhe + Fpt3aq8EFgQAB/guCYMuL+gAM+GAASWHgACOJLHcSxlTi4ACfjSaJs3Ra4+AAgZFCsLr + Fislrffy8We663OJZKxZZaNe39XlqQlChw51SYHAAeef59oCjApQlDAZo+I4nAAO01gE + 603CBu6CecRaOBgAHjrKiqPRwNVLWUB3jAqEsBdAAGbtFvsUxgIbaAFsQsBecAwADym8 + AAhbzpt5NtTZzb+AFKtU1iONIcYACJxIAAfxmv6dmjjX/vmybA3HK5sqnMQzsVgZdJqP + ykeWeIhmSEWRlSFz1uKKdKh+TrCcXYgBtoIdG3Wo3MEd+8jzSeayeMoynpd9I1fi49eq + qOS8EvmNMwy4y88ITd3p/HsvRZygABXt6SCKx2wZXw4zjfj85ay23oegAHZ9m1LFuwAE + z+QAET+vqb76zuS89EQsRBZC3TuRIYYsfyTQBwHdIXR4yd3zIGcE2ZobjgAAngoqxVBS + XBITbonBlRz3quTIg8gvCkVFKMK47ohaghjwleyoUdxCEqgVT2n1qyh01gXhwAAKcO29 + tjhDA1IbuANxDY4AiHrnWwwCVbEd88SXeOVQE+wdjgx+gAhwBd0zKYBMxgUy0nsQEOGo + AAN+MiaHpkThI9h3KQYwJDIKt1ZkMnVkPjgxJ7zjAHxsZrFBDg74/AAHvIFRqjyFs/ao + stWsboRICNXFVdY3IJwVIW7iDTJG5JDkWhwQsmwAA2k8AAIsoQACqlIACPw72FsNjcbS + J7+S4wBIYtg+o6QAAwlsAAYEuQAAsl41tohB3WmzkyVV3pO5ilWja5Z/MKjGmPdCAABM + 0QAA4moACGquY+FkmG5lyr8EnyAkESwDLi3GvbAVBKHz5Y9yuM7Nmbk7JtTJlfFplcXW + Zm+nlKufRO5tz7n9Axf0sJ/0DJEWaghD41RDA3QcirMKGELoTESh5eaHUTIRRGhdFpWU + aIbRijhBaDUfIMjkNwAAo0nAAEGlVFqQoYoEQ6R5N5xxzIdMGfDqEMTHJzTonlLUDG3m + eMSoUFjqnRAMqIHlSTYTwYpRVARt4CAAXINl51FCCQLIbTyflTj4VaJBV4nNPkBUvLJT + Z+9Iq0EOICAADwEAAAMAAAABACUAAAEBAAMAAAABAEMAAAECAAMAAAAEAAAGVgEDAAMA + AAABAAUAAAEGAAMAAAABAAIAAAERAAQAAAABAAAACAESAAMAAAABAAEAAAEVAAMAAAAB + AAQAAAEWAAMAAAABAEMAAAEXAAQAAAABAAAFlAEcAAMAAAABAAEAAAE9AAMAAAABAAIA + AAFSAAMAAAABAAEAAAFTAAMAAAAEAAAGXodzAAcAAAzEAAAGZgAAAAAACAAIAAgACAAB + AAEAAQABAAAMxGFwcGwCEAAAbW50clJHQiBYWVogB9oABgAcAAsAEQAQYWNzcEFQUEwA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPbWAAEAAAAA0y1hcHBsAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAARZGVzYwAAAVAAAABiZHNj + bQAAAbQAAAD+Y3BydAAAArQAAADQd3RwdAAAA4QAAAAUclhZWgAAA5gAAAAUZ1hZWgAA + A6wAAAAUYlhZWgAAA8AAAAAUclRSQwAAA9QAAAgMYWFyZwAAC+AAAAAgdmNndAAADAAA + AAAwbmRpbgAADDAAAAA+Y2hhZAAADHAAAAAsbW1vZAAADJwAAAAoYlRSQwAAA9QAAAgM + Z1RSQwAAA9QAAAgMYWFiZwAAC+AAAAAgYWFnZwAAC+AAAAAgZGVzYwAAAAAAAAAIRGlz + cGxheQAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAG1sdWMAAAAAAAAAEgAAAAxu + bE5MAAAAFgAAAOhkYURLAAAAFgAAAOhwbFBMAAAAFgAAAOhlblVTAAAAFgAAAOhuYk5P + AAAAFgAAAOhmckZSAAAAFgAAAOhwdEJSAAAAFgAAAOhwdFBUAAAAFgAAAOh6aENOAAAA + FgAAAOhlc0VTAAAAFgAAAOhqYUpQAAAAFgAAAOhydVJVAAAAFgAAAOhzdlNFAAAAFgAA + AOh6aFRXAAAAFgAAAOhkZURFAAAAFgAAAOhmaUZJAAAAFgAAAOhpdElUAAAAFgAAAOhr + b0tSAAAAFgAAAOgARABFAEwATAAgADIAMAAwADAARgBQAAB0ZXh0AAAAAENvcHlyaWdo + dCBBcHBsZSwgSW5jLiwgMjAxMAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAWFlaIAAAAAAAAPPP + AAEAAAABGGJYWVogAAAAAAAAeFsAAEAZAAAD91hZWiAAAAAAAABWWgAAntIAABfUWFla + IAAAAAAAACghAAAhFQAAt2JjdXJ2AAAAAAAABAAAAAAFAAoADwAUABkAHgAjACgALQAy + ADYAOwBAAEUASgBPAFQAWQBeAGMAaABtAHIAdwB8AIEAhgCLAJAAlQCaAJ8AowCoAK0A + sgC3ALwAwQDGAMsA0ADVANsA4ADlAOsA8AD2APsBAQEHAQ0BEwEZAR8BJQErATIBOAE+ + AUUBTAFSAVkBYAFnAW4BdQF8AYMBiwGSAZoBoQGpAbEBuQHBAckB0QHZAeEB6QHyAfoC + AwIMAhQCHQImAi8COAJBAksCVAJdAmcCcQJ6AoQCjgKYAqICrAK2AsECywLVAuAC6wL1 + AwADCwMWAyEDLQM4A0MDTwNaA2YDcgN+A4oDlgOiA64DugPHA9MD4APsA/kEBgQTBCAE + LQQ7BEgEVQRjBHEEfgSMBJoEqAS2BMQE0wThBPAE/gUNBRwFKwU6BUkFWAVnBXcFhgWW + BaYFtQXFBdUF5QX2BgYGFgYnBjcGSAZZBmoGewaMBp0GrwbABtEG4wb1BwcHGQcrBz0H + TwdhB3QHhgeZB6wHvwfSB+UH+AgLCB8IMghGCFoIbgiCCJYIqgi+CNII5wj7CRAJJQk6 + CU8JZAl5CY8JpAm6Cc8J5Qn7ChEKJwo9ClQKagqBCpgKrgrFCtwK8wsLCyILOQtRC2kL + gAuYC7ALyAvhC/kMEgwqDEMMXAx1DI4MpwzADNkM8w0NDSYNQA1aDXQNjg2pDcMN3g34 + DhMOLg5JDmQOfw6bDrYO0g7uDwkPJQ9BD14Peg+WD7MPzw/sEAkQJhBDEGEQfhCbELkQ + 1xD1ERMRMRFPEW0RjBGqEckR6BIHEiYSRRJkEoQSoxLDEuMTAxMjE0MTYxODE6QTxRPl + FAYUJxRJFGoUixStFM4U8BUSFTQVVhV4FZsVvRXgFgMWJhZJFmwWjxayFtYW+hcdF0EX + ZReJF64X0hf3GBsYQBhlGIoYrxjVGPoZIBlFGWsZkRm3Gd0aBBoqGlEadxqeGsUa7BsU + GzsbYxuKG7Ib2hwCHCocUhx7HKMczBz1HR4dRx1wHZkdwx3sHhYeQB5qHpQevh7pHxMf + Ph9pH5Qfvx/qIBUgQSBsIJggxCDwIRwhSCF1IaEhziH7IiciVSKCIq8i3SMKIzgjZiOU + I8Ij8CQfJE0kfCSrJNolCSU4JWgllyXHJfcmJyZXJocmtyboJxgnSSd6J6sn3CgNKD8o + cSiiKNQpBik4KWspnSnQKgIqNSpoKpsqzysCKzYraSudK9EsBSw5LG4soizXLQwtQS12 + Last4S4WLkwugi63Lu4vJC9aL5Evxy/+MDUwbDCkMNsxEjFKMYIxujHyMioyYzKbMtQz + DTNGM38zuDPxNCs0ZTSeNNg1EzVNNYc1wjX9Njc2cjauNuk3JDdgN5w31zgUOFA4jDjI + OQU5Qjl/Obw5+To2OnQ6sjrvOy07azuqO+g8JzxlPKQ84z0iPWE9oT3gPiA+YD6gPuA/ + IT9hP6I/4kAjQGRApkDnQSlBakGsQe5CMEJyQrVC90M6Q31DwEQDREdEikTORRJFVUWa + Rd5GIkZnRqtG8Ec1R3tHwEgFSEtIkUjXSR1JY0mpSfBKN0p9SsRLDEtTS5pL4kwqTHJM + uk0CTUpNk03cTiVObk63TwBPSU+TT91QJ1BxULtRBlFQUZtR5lIxUnxSx1MTU19TqlP2 + VEJUj1TbVShVdVXCVg9WXFapVvdXRFeSV+BYL1h9WMtZGllpWbhaB1pWWqZa9VtFW5Vb + 5Vw1XIZc1l0nXXhdyV4aXmxevV8PX2Ffs2AFYFdgqmD8YU9homH1YklinGLwY0Njl2Pr + ZEBklGTpZT1lkmXnZj1mkmboZz1nk2fpaD9olmjsaUNpmmnxakhqn2r3a09rp2v/bFds + r20IbWBtuW4SbmtuxG8eb3hv0XArcIZw4HE6cZVx8HJLcqZzAXNdc7h0FHRwdMx1KHWF + deF2Pnabdvh3VnezeBF4bnjMeSp5iXnnekZ6pXsEe2N7wnwhfIF84X1BfaF+AX5ifsJ/ + I3+Ef+WAR4CogQqBa4HNgjCCkoL0g1eDuoQdhICE44VHhauGDoZyhteHO4efiASIaYjO + iTOJmYn+imSKyoswi5aL/IxjjMqNMY2Yjf+OZo7OjzaPnpAGkG6Q1pE/kaiSEZJ6kuOT + TZO2lCCUipT0lV+VyZY0lp+XCpd1l+CYTJi4mSSZkJn8mmia1ZtCm6+cHJyJnPedZJ3S + nkCerp8dn4uf+qBpoNihR6G2oiailqMGo3aj5qRWpMelOKWpphqmi6b9p26n4KhSqMSp + N6mpqhyqj6sCq3Wr6axcrNCtRK24ri2uoa8Wr4uwALB1sOqxYLHWskuywrM4s660JbSc + tRO1irYBtnm28Ldot+C4WbjRuUq5wro7urW7LrunvCG8m70VvY++Cr6Evv+/er/1wHDA + 7MFnwePCX8Lbw1jD1MRRxM7FS8XIxkbGw8dBx7/IPci8yTrJuco4yrfLNsu2zDXMtc01 + zbXONs62zzfPuNA50LrRPNG+0j/SwdNE08bUSdTL1U7V0dZV1tjXXNfg2GTY6Nls2fHa + dtr724DcBdyK3RDdlt4c3qLfKd+v4DbgveFE4cziU+Lb42Pj6+Rz5PzlhOYN5pbnH+ep + 6DLovOlG6dDqW+rl63Dr++yG7RHtnO4o7rTvQO/M8Fjw5fFy8f/yjPMZ86f0NPTC9VD1 + 3vZt9vv3ivgZ+Kj5OPnH+lf65/t3/Af8mP0p/br+S/7c/23//3BhcmEAAAAAAAMAAAAC + ZmYAAPKnAAANWQAAE9AAAArAdmNndAAAAAAAAAABAADhSAAAAAAAAQAAAADhSAAAAAAA + AQAAAADhSAAAAAAAAQAAbmRpbgAAAAAAAAA2AAChQAAAVwAAAEzAAACXAAAAJkAAABwA + AABQAAAAVAAAAoAAAAKAAAACgAAAAAAAAAAAAHNmMzIAAAAAAAEMGgAABcD///L/AAAH + YAAA/c7///uY///9lgAAA/QAAL9ObW1vZAAAAAAAABCsAACgAzA0Rky6bz8AAAAAAAAA + AAAAAAAAAAAAAA== + + ReadOnly + NO + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UniqueID + 1 + UseEntirePage + + VPages + 1 + WindowInfo + + CurrentSheet + 0 + ExpandedCanvases + + FitInWindow + + Frame + {{470, 267}, {700, 891}} + ListView + + OutlineWidth + 142 + RightSidebar + + Sidebar + + SidebarWidth + 138 + VisibleRegion + {{1, 1}, {558, 782}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 0.0 + 1 + + + + saveQuickLookFiles + YES + + diff --git a/doc/images/gtsam-structure.pdf b/doc/images/gtsam-structure.pdf new file mode 100644 index 000000000..37c2ed3c1 Binary files /dev/null and b/doc/images/gtsam-structure.pdf differ diff --git a/doc/images/n-steps.pdf b/doc/images/n-steps.pdf new file mode 100644 index 000000000..165accc2d Binary files /dev/null and b/doc/images/n-steps.pdf differ diff --git a/doc/images/n-steps.png b/doc/images/n-steps.png new file mode 100644 index 000000000..988fe5dfc Binary files /dev/null and b/doc/images/n-steps.png differ diff --git a/doc/macros.lyx b/doc/macros.lyx new file mode 100644 index 000000000..1e57e1675 --- /dev/null +++ b/doc/macros.lyx @@ -0,0 +1,294 @@ +#LyX 1.6.5 created this file. For more info see http://www.lyx.org/ +\lyxformat 345 +\begin_document +\begin_header +\textclass article +\use_default_options true +\language english +\inputencoding auto +\font_roman default +\font_sans default +\font_typewriter default +\font_default_family default +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\paperfontsize default +\use_hyperref false +\papersize default +\use_geometry false +\use_amsmath 1 +\use_esint 1 +\cite_engine basic +\use_bibtopic false +\paperorientation portrait +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\defskip medskip +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\author "" +\author "" +\end_header + +\begin_body + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}} +{\mathfrak{\mathbb{R}^{2}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathfrak{\mathbb{R}^{3}}} +{\mathfrak{\mathbb{R}^{3}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathfrak{\mathbb{R}^{6}}} +{\mathfrak{\mathbb{R}^{6}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/math.lyx b/doc/math.lyx new file mode 100644 index 000000000..878a7b167 --- /dev/null +++ b/doc/math.lyx @@ -0,0 +1,5746 @@ +#LyX 2.0 created this file. For more info see http://www.lyx.org/ +\lyxformat 413 +\begin_document +\begin_header +\textclass article +\use_default_options false +\begin_modules +eqs-within-sections +figs-within-sections +theorems-ams-bytype +\end_modules +\maintain_unincluded_children false +\language english +\language_package default +\inputencoding auto +\fontencoding global +\font_roman times +\font_sans default +\font_typewriter default +\font_default_family rmdefault +\use_non_tex_fonts false +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\default_output_format default +\output_sync 0 +\bibtex_command default +\index_command default +\paperfontsize 12 +\spacing single +\use_hyperref false +\papersize default +\use_geometry true +\use_amsmath 1 +\use_esint 0 +\use_mhchem 1 +\use_mathdots 1 +\cite_engine basic +\use_bibtopic false +\use_indices false +\paperorientation portrait +\suppress_date false +\use_refstyle 0 +\index Index +\shortcut idx +\color #008000 +\end_index +\leftmargin 1in +\topmargin 1in +\rightmargin 1in +\bottommargin 1in +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\paragraph_indentation default +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\html_math_output 0 +\html_css_as_file 0 +\html_be_strict false +\end_header + +\begin_body + +\begin_layout Title +Derivatives and Differentials +\end_layout + +\begin_layout Author +Frank Dellaert +\end_layout + +\begin_layout Standard +\begin_inset Box Frameless +position "t" +hor_pos "c" +has_inner_box 1 +inner_pos "t" +use_parbox 0 +use_makebox 0 +width "100col%" +special "none" +height "1in" +height_special "totalheight" +status collapsed + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SqrMah}[3]{\Vert{#1}-{#2}\Vert_{#3}^{2}} +{\Vert{#1}-{#2}\Vert_{#3}^{2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SqrZMah}[2]{\Vert{#1}\Vert_{#2}^{2}} +{\Vert{#1}\Vert_{#2}^{2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rone}{\mathbb{R}} +{\mathbb{R}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Reals}[1]{\mathbb{R}^{#1}} +{\mathbb{R}^{#1}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\OneD}[1]{\Reals{#1}\rightarrow\Rone} +{\Reals{#1}\rightarrow\Rone} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Multi}[2]{\Reals{#1}\rightarrow\Reals{#2}} +{\Reals{#1}\rightarrow\Reals{#2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Man}{\mathcal{M}} +{\mathcal{M}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathbb{R}^{2}} +{\mathbb{R}^{2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathbb{R}^{3}} +{\mathbb{R}^{3}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathbb{R}^{6}} +{\mathbb{R}^{6}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Part +Theory +\end_layout + +\begin_layout Section +Optimization +\end_layout + +\begin_layout Standard +We will be concerned with minimizing a non-linear least squares objective + of the form +\begin_inset Formula +\begin{equation} +x^{*}=\arg\min_{x}\SqrMah{h(x)}z{\Sigma}\label{eq:objective} +\end{equation} + +\end_inset + +where +\begin_inset Formula $x\in\Man$ +\end_inset + + is a point on an +\begin_inset Formula $n$ +\end_inset + +-dimensional manifold (which could be +\begin_inset Formula $\Reals n$ +\end_inset + +, an n-dimensional Lie group +\begin_inset Formula $G$ +\end_inset + +, or a general manifold +\begin_inset Formula $\Man)$ +\end_inset + +, +\begin_inset Formula $z\in\Reals m$ +\end_inset + + is an observed measurement, +\begin_inset Formula $h:\Man\rightarrow\Reals m$ +\end_inset + + is a measurement function that predicts +\begin_inset Formula $z$ +\end_inset + + from +\begin_inset Formula $x$ +\end_inset + +, and +\begin_inset Formula $\SqrZMah e{\Sigma}\define e^{T}\Sigma^{-1}e$ +\end_inset + + is the squared Mahalanobis distance with covariance +\begin_inset Formula $\Sigma$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +To minimize +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:objective" + +\end_inset + + we need a notion of how the non-linear measurement function +\begin_inset Formula $h(x)$ +\end_inset + + behaves in the neighborhood of a linearization point +\begin_inset Formula $a$ +\end_inset + +. + Loosely speaking, we would like to define an +\begin_inset Formula $m\times n$ +\end_inset + + Jacobian matrix +\begin_inset Formula $H_{a}$ +\end_inset + + such that +\begin_inset Formula +\begin{equation} +h(a\oplus\xi)\approx h(a)+H_{a}\xi\label{eq:LocalBehavior} +\end{equation} + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + +, and the operation +\begin_inset Formula $\oplus$ +\end_inset + + +\begin_inset Quotes eld +\end_inset + +increments +\begin_inset Quotes erd +\end_inset + + +\begin_inset Formula $a\in\Man$ +\end_inset + +. + Below we more formally develop this notion, first for functions from +\begin_inset Formula $\Multi nm$ +\end_inset + +, then for Lie groups, and finally for manifolds. +\end_layout + +\begin_layout Standard +Once equipped with the approximation +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:LocalBehavior" + +\end_inset + +, we can minimize the objective function +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:objective" + +\end_inset + + with respect to +\begin_inset Formula $\delta x$ +\end_inset + + instead: +\begin_inset Formula +\begin{equation} +\xi^{*}=\arg\min_{\xi}\SqrMah{h(a)+H_{a}\xi}z{\Sigma}\label{eq:ApproximateObjective} +\end{equation} + +\end_inset + +This can be done by setting the derivative of +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:ApproximateObjective" + +\end_inset + + to zero, +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\begin_inset Formula +\[ +\frac{1}{2}H_{a}^{T}(h(a)+H_{a}\xi-z)=0 +\] + +\end_inset + + +\end_layout + +\end_inset + + yielding the +\series bold +normal equations +\series default +, +\begin_inset Formula +\[ +H_{a}^{T}H_{a}\xi=H_{a}^{T}\left(z-h(a)\right) +\] + +\end_inset + +which can be solved using Cholesky factorization. + Of course, we might have to iterate this multiple times, and use a trust-region + method to bound +\begin_inset Formula $\xi$ +\end_inset + + when the approximation +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:LocalBehavior" + +\end_inset + + is not good. +\end_layout + +\begin_layout Section +Multivariate Differentiation +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +For a vector space +\begin_inset Formula $\Reals n$ +\end_inset + +, the notion of an increment is just done by vector addition +\begin_inset Formula +\[ +a\oplus\xi\define a+\xi +\] + +\end_inset + +and for the approximation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:LocalBehavior" + +\end_inset + + we will use a Taylor expansion using multivariate differentiation. + However, loosely following +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + +, we use a perhaps unfamiliar way to define derivatives: +\end_layout + +\begin_layout Definition +\begin_inset CommandInset label +LatexCommand label +name "def:differentiable" + +\end_inset + +We define a function +\begin_inset Formula $f:\Multi nm$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)\in\Reals{m\times n}$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\delta x\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f(a+\xi)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +where +\begin_inset Formula $\left|e\right|\define\sqrt{e^{T}e}$ +\end_inset + + is the usual norm. + If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then the matrix +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear map +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + When no confusion is likely, we use the notation +\begin_inset Formula $F_{a}\define f'(a)$ +\end_inset + + to stress that +\begin_inset Formula $f'(a)$ +\end_inset + + is a matrix. +\end_layout + +\begin_layout Standard +The benefit of using this definition is that it generalizes the notion of + a scalar derivative +\begin_inset Formula $f'(a):\Rone\rightarrow\Rone$ +\end_inset + + to multivariate functions from +\begin_inset Formula $\Multi nm$ +\end_inset + +. + In particular, the derivative +\begin_inset Formula $Df_{a}$ +\end_inset + + maps vector increments +\begin_inset Formula $\xi$ +\end_inset + + on +\begin_inset Formula $a$ +\end_inset + + to increments +\begin_inset Formula $f'(a)\xi$ +\end_inset + + on +\begin_inset Formula $f(a)$ +\end_inset + +, such that this linear map locally approximates +\begin_inset Formula $f$ +\end_inset + +: +\begin_inset Formula +\[ +f(a+\xi)\approx f(a)+f'(a)\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:projection" + +\end_inset + +The function +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + projects a 3D point +\begin_inset Formula $(x,y,z)$ +\end_inset + + to the image plane, and has the Jacobian matrix +\begin_inset Formula +\[ +\pi'(x,y,z)=\frac{1}{z}\left[\begin{array}{ccc} +1 & 0 & -x/z\\ +0 & 1 & -y/z +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Properties of Derivatives +\end_layout + +\begin_layout Standard +This notion of a multivariate derivative obeys the usual rules: +\end_layout + +\begin_layout Theorem +(Chain rule) If +\begin_inset Formula $f:\Multi np$ +\end_inset + + is differentiable at +\begin_inset Formula $a$ +\end_inset + + and +\begin_inset Formula $g:\Multi pm$ +\end_inset + + is differentiable at +\begin_inset Formula $f(a)$ +\end_inset + +, +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + then +\begin_inset Formula $D(g\circ f)_{a}=Dg_{f(a)}\circ Df_{a}$ +\end_inset + + and +\end_layout + +\end_inset + + then the Jacobian matrix +\begin_inset Formula $H_{a}$ +\end_inset + + of +\begin_inset Formula $h=g\circ f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + is the +\begin_inset Formula $m\times n$ +\end_inset + + matrix product +\begin_inset Formula +\[ +H_{a}=G_{f(a)}F_{a} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +See +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:chain-rule" + +\end_inset + +If we follow the projection +\begin_inset Formula $\pi$ +\end_inset + + by a calibration step +\begin_inset Formula $\gamma:(x,y)\mapsto(u_{0}+fx,u_{0}+fy)$ +\end_inset + +, with +\begin_inset Formula +\[ +\gamma'(x,y)=\left[\begin{array}{cc} +f & 0\\ +0 & f +\end{array}\right] +\] + +\end_inset + +then the combined function +\begin_inset Formula $\gamma\circ\pi$ +\end_inset + + has the Jacobian matrix +\begin_inset Formula +\[ +(\gamma\circ\pi)'(x,y)=\frac{f}{z}\left[\begin{array}{ccc} +1 & 0 & -x/z\\ +0 & 1 & -y/z +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +(Inverse) If +\begin_inset Formula $f:\Multi nn$ +\end_inset + + is differentiable and has a differentiable inverse +\begin_inset Formula $g\define f^{-1}$ +\end_inset + +, then its Jacobian matrix +\begin_inset Formula $G_{a}$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + is just the inverse of that of +\begin_inset Formula $f$ +\end_inset + +, evaluated at +\begin_inset Formula $g(a)$ +\end_inset + +: +\begin_inset Formula +\[ +G_{a}=\left[F_{g(a)}\right]^{-1} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +See +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:inverse" + +\end_inset + +The function +\begin_inset Formula $f:(x,y)\mapsto(x^{2},xy)$ +\end_inset + + has the Jacobian matrix +\end_layout + +\begin_layout Example +\begin_inset Formula +\[ +F_{(x,y)}=\left[\begin{array}{cc} +2x & 0\\ +y & x +\end{array}\right] +\] + +\end_inset + +and, for +\begin_inset Formula $x\geq0$ +\end_inset + +, its inverse is the function +\begin_inset Formula $g:(x,y)\mapsto(x^{1/2},x^{-1/2}y)$ +\end_inset + + with the Jacobian matrix +\begin_inset Formula +\[ +G_{(x,y)}=\frac{1}{2}\left[\begin{array}{cc} +x^{-1/2} & 0\\ +-x^{-3/2}y & 2x^{-1/2} +\end{array}\right] +\] + +\end_inset + +It is easily verified that +\begin_inset Formula +\[ +g'(a,b)f'(a^{1/2},a^{-1/2}b)=\frac{1}{2}\left[\begin{array}{cc} +a^{-1/2} & 0\\ +-a^{-3/2}b & 2a^{-1/2} +\end{array}\right]\left[\begin{array}{cc} +2a^{1/2} & 0\\ +a^{-1/2}b & a^{1/2} +\end{array}\right]=\left[\begin{array}{cc} +1 & 0\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Problem +Verify the above for +\begin_inset Formula $(a,b)=(4,6)$ +\end_inset + +. + Sketch the situation graphically to get insight. +\end_layout + +\begin_layout Subsection +Computing Multivariate Derivatives +\end_layout + +\begin_layout Standard +Computing derivatives is made easy by defining the concept of a partial + derivative: +\end_layout + +\begin_layout Definition +For +\begin_inset Formula $f:\OneD n$ +\end_inset + +, the +\series bold +partial derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, +\series bold + +\series default + +\begin_inset Formula +\[ +D_{j}f(a)\define\lim_{h\rightarrow0}\frac{f\left(a^{1},\ldots,a^{j}+h,\ldots,a^{n}\right)-f\left(a^{1},\ldots,a^{n}\right)}{h} +\] + +\end_inset + +which is the ordinary derivative of the scalar function +\begin_inset Formula $g(x)\define f\left(a^{1},\ldots,x,\ldots,a^{n}\right)$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +Using this definition, one can show that the Jacobian matrix +\begin_inset Formula $F_{a}$ +\end_inset + + of a differentiable +\emph on +multivariate +\emph default + function +\begin_inset Formula $f:\Multi nm$ +\end_inset + + consists simply of the +\begin_inset Formula $m\times n$ +\end_inset + + partial derivatives +\begin_inset Formula $D_{j}f^{i}(a)$ +\end_inset + +, evaluated at +\begin_inset Formula $a\in\Reals n$ +\end_inset + +: +\begin_inset Formula +\[ +F_{a}=\left[\begin{array}{ccc} +D_{1}f^{1}(a) & \cdots & D_{n}f^{1}(a)\\ +\vdots & \ddots & \vdots\\ +D_{1}f^{m}(a) & \ldots & D_{n}f^{m}(a) +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Problem +Verify the derivatives in Examples +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + + to +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:inverse" + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Multivariate Functions on Lie Groups +\end_layout + +\begin_layout Subsection +Lie Groups +\end_layout + +\begin_layout Standard +Lie groups are not as easy to treat as the vector space +\begin_inset Formula $\Reals n$ +\end_inset + + but nevertheless have a lot of structure. + To generalize the concept of the total derivative above we just need to + replace +\begin_inset Formula $a\oplus\xi$ +\end_inset + + in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:ApproximateObjective" + +\end_inset + + with a suitable operation in the Lie group +\begin_inset Formula $G$ +\end_inset + +. + In particular, the notion of an exponential map allows us to define an + incremental transformation as tracing out a geodesic curve on the group + manifold along a certain +\series bold +tangent vector +\series default + +\begin_inset Formula $\xi$ +\end_inset + +, +\begin_inset Formula +\[ +a\oplus\xi\define a\exp\left(\hat{\xi}\right) +\] + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + + for an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group, +\begin_inset Formula $\hat{\xi}\in\mathfrak{g}$ +\end_inset + + the Lie algebra element corresponding to the vector +\begin_inset Formula $\xi$ +\end_inset + +, and +\begin_inset Formula $\exp\hat{\xi}$ +\end_inset + + the exponential map. + Note that if +\begin_inset Formula $G$ +\end_inset + + is equal to +\begin_inset Formula $\Reals n$ +\end_inset + + then composing with the exponential map +\begin_inset Formula $ae^{\xihat}$ +\end_inset + + is just vector addition +\begin_inset Formula $a+\xi$ +\end_inset + +. +\end_layout + +\begin_layout Example +For the Lie group +\begin_inset Formula $\SOthree$ +\end_inset + + of 3D rotations the vector +\begin_inset Formula $\xi$ +\end_inset + + is denoted as +\begin_inset Formula $\omega$ +\end_inset + + and represents an angular displacement. + The Lie algebra element +\begin_inset Formula $\xihat$ +\end_inset + + is a skew symmetric matrix denoted as +\begin_inset Formula $\Skew{\omega}\in\sothree$ +\end_inset + +, and is given by +\begin_inset Formula +\[ +\Skew{\omega}=\left[\begin{array}{ccc} +0 & -\omega_{z} & \omega_{y}\\ +\omega_{z} & 0 & -\omega_{x}\\ +-\omega_{y} & \omega_{x} & 0 +\end{array}\right] +\] + +\end_inset + +Finally, the increment +\begin_inset Formula $a\oplus\xi=ae^{\xihat}$ +\end_inset + + corresponds to an incremental rotation +\begin_inset Formula $R\oplus\omega=Re^{\Skew{\omega}}$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +We can generalize Definition +\begin_inset CommandInset ref +LatexCommand ref +reference "def:differentiable" + +\end_inset + + to map exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + to increments +\begin_inset Formula $f'(a)\xi$ +\end_inset + + on +\begin_inset Formula $f(a)$ +\end_inset + +, such that the linear map +\begin_inset Formula $Df_{a}$ +\end_inset + + locally approximates a function +\begin_inset Formula $f$ +\end_inset + + from +\begin_inset Formula $G$ +\end_inset + + to +\begin_inset Formula $\Reals m$ +\end_inset + +: +\begin_inset Formula +\[ +f(ae^{\xihat})\approx f(a)+f'(a)\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Definition +We define a function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a\in G$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)\in\Reals{m\times n}$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f(ae^{\hat{\xi}})\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then the matrix +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear map +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Note that the vectors +\begin_inset Formula $\xi$ +\end_inset + + can be viewed as lying in the tangent space to +\begin_inset Formula $G$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, but defining this rigorously would take us on a longer tour of differential + geometry. + Informally, +\begin_inset Formula $\xi$ +\end_inset + + is simply the direction, in a local coordinate frame, that is locally tangent + at +\begin_inset Formula $a$ +\end_inset + + to a geodesic curve +\begin_inset Formula $\gamma:t\mapsto ae^{\widehat{t\xi}}$ +\end_inset + + traced out by the exponential map, with +\begin_inset Formula $\gamma(0)=a$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Derivative of an Action +\begin_inset CommandInset label +LatexCommand label +name "sec:Derivatives-of-Actions" + +\end_inset + + +\end_layout + +\begin_layout Standard +The (usual) action of an +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix group +\begin_inset Formula $G$ +\end_inset + + is matrix-vector multiplication on +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, i.e., +\begin_inset Formula $f:G\times\Reals n\rightarrow\Reals n$ +\end_inset + + with +\begin_inset Formula +\[ +f(T,p)=Tp +\] + +\end_inset + +Since this is a function defined on the product +\begin_inset Formula $G\times\Reals n$ +\end_inset + + the derivative is a linear transformation +\begin_inset Formula $Df:\Multi{2n}n$ +\end_inset + + with +\begin_inset Formula +\[ +Df_{(T,p)}\left(\xi,\delta p\right)=D_{1}f_{(T,p)}\left(\xi\right)+D_{2}f_{(T,p)}\left(\delta p\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "th:Action" + +\end_inset + +The Jacobian matrix of the group action +\begin_inset Formula $f(T,P)=Tp$ +\end_inset + + at +\begin_inset Formula $(T,p)$ +\end_inset + + is given by +\begin_inset Formula +\[ +F_{(T,p)}=\left[\begin{array}{cc} +TH(p) & T\end{array}\right]=T\left[\begin{array}{cc} +H(p) & I_{n}\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $H:\Reals n\rightarrow\Reals{n\times n}$ +\end_inset + + a linear mapping that depends on +\begin_inset Formula $p$ +\end_inset + +, and +\begin_inset Formula $I_{n}$ +\end_inset + + the +\begin_inset Formula $n\times n$ +\end_inset + + identity matrix. +\end_layout + +\begin_layout Proof +First, the derivative +\begin_inset Formula $D_{2}f$ +\end_inset + + with respect to in +\begin_inset Formula $p$ +\end_inset + + is easy, as its matrix is simply T: +\begin_inset Formula +\[ +f(T,p+\delta p)=T(p+\delta p)=Tp+T\delta p=f(T,p)+D_{2}f(\delta p) +\] + +\end_inset + +For the derivative +\begin_inset Formula $D_{1}f$ +\end_inset + + with respect to a change in the first argument +\begin_inset Formula $T$ +\end_inset + +, we want +\end_layout + +\begin_layout Proof + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +\begin_inset Formula +\[ +f(Te^{\hat{\xi}},p)=Te^{\hat{\xi}}p\approx Tp+D_{1}f(\xi) +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +Since the matrix exponential is given by the series +\begin_inset Formula $e^{A}=I+A+\frac{A^{2}}{2!}+\frac{A^{3}}{3!}+\ldots$ +\end_inset + + we have, to first order +\begin_inset Formula +\[ +Te^{\hat{\xi}}p\approx T(I+\hat{\xi})p=Tp+T\hat{\xi}p +\] + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Note also that +\begin_inset Formula +\[ +T\hat{\xi}p=\left(T\hat{\xi}T^{-1}\right)Tp=\left(\Ad T\xihat\right)\left(Tp\right) +\] + +\end_inset + + +\end_layout + +\end_inset + +Hence, we need to show that +\begin_inset Formula +\begin{equation} +\xihat p=H(p)\xi\label{eq:Hp} +\end{equation} + +\end_inset + +with +\begin_inset Formula $H(p)$ +\end_inset + + an +\begin_inset Formula $n\times n$ +\end_inset + + matrix that depends on +\begin_inset Formula $p$ +\end_inset + +. + Expressing the map +\begin_inset Formula $\xi\rightarrow\hat{\xi}$ +\end_inset + + in terms of the Lie algebra generators +\begin_inset Formula $G^{i}$ +\end_inset + +, using tensors and Einstein summation, we have +\begin_inset Formula $\hat{\xi}_{j}^{i}=G_{jk}^{i}\xi^{k}$ +\end_inset + + allowing us to calculate +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\hat{\xi}p$ +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + as +\begin_inset Formula +\[ +\left(\hat{\xi}p\right)^{i}=\hat{\xi}_{j}^{i}p^{j}=G_{jk}^{i}\xi^{k}p^{j}=\left(G_{jk}^{i}p^{j}\right)\xi^{k}=H_{k}^{i}(p)\xi^{k} +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + +, we have +\begin_inset Formula $\hat{\omega}=\Skew{\omega}$ +\end_inset + + and +\begin_inset Formula +\[ +G_{k=1}:\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & -1\\ +0 & 1 & 0 +\end{array}\right)\mbox{}G_{k=2}:\left(\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +-1 & 0 & 0 +\end{array}\right)\mbox{ }G_{k=3}:\left(\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +The matrices +\begin_inset Formula $\left(G_{k}^{i}\right)_{j}$ +\end_inset + + are obtained by assembling the +\begin_inset Formula $j^{th}$ +\end_inset + + columns of the generators above, yielding +\begin_inset Formula $H(p)$ +\end_inset + + equal to: +\begin_inset Formula +\[ +\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & -1 & 0 +\end{array}\right)p^{1}+\left(\begin{array}{ccc} +0 & 0 & -1\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right)p^{2}+\left(\begin{array}{ccc} +0 & 1 & 0\\ +-1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right)p^{3}=\left(\begin{array}{ccc} +0 & p^{3} & -p^{2}\\ +-p^{3} & 0 & p^{1}\\ +p^{2} & -p^{1} & 0 +\end{array}\right)=\Skew{-p} +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Hence, the Jacobian matrix of +\begin_inset Formula $f(R,p)=Rp$ +\end_inset + + is given by +\begin_inset Formula +\[ +F_{(R,p)}=R\left(\begin{array}{cc} +\Skew{-p} & I_{3}\end{array}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivative of an Inverse Action +\end_layout + +\begin_layout Standard +Applying the action by the inverse of +\begin_inset Formula $T\in G$ +\end_inset + + yields a function +\begin_inset Formula $g:G\times\Reals n\rightarrow\Reals n$ +\end_inset + + defined by +\begin_inset Formula +\[ +g(T,p)=T^{-1}p +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "Th:InverseAction" + +\end_inset + +The Jacobian matrix of the inverse group action +\begin_inset Formula $g(T,p)=T^{-1}p$ +\end_inset + + is given by +\begin_inset Formula +\[ +G_{(T,p)}=\left[\begin{array}{cc} +-H(T^{-1}p) & T^{-1}\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $H:\Reals n\rightarrow\Reals{n\times n}$ +\end_inset + + is the same mapping as before. +\end_layout + +\begin_layout Proof +Again, the derivative +\begin_inset Formula $D_{2}g$ +\end_inset + + with respect to in +\begin_inset Formula $p$ +\end_inset + + is easy, the matrix of which is simply +\begin_inset Formula $T^{-1}$ +\end_inset + +: +\begin_inset Formula +\[ +g(T,p+\delta p)=T^{-1}(p+\delta p)=T^{-1}p+T^{-1}\delta p=g(T,p)+D_{2}g(\delta p) +\] + +\end_inset + +Conversely, a change in +\begin_inset Formula $T$ +\end_inset + + yields +\begin_inset Formula +\[ +g(Te^{\xihat},p)=\left(Te^{\xihat}\right)^{-1}p=e^{-\xihat}T^{-1}p +\] + +\end_inset + +Similar to before, if we expand the matrix exponential we get +\begin_inset Formula +\[ +e^{-A}=I-A+\frac{A^{2}}{2!}-\frac{A^{3}}{3!}+\ldots +\] + +\end_inset + +so +\begin_inset Formula +\[ +e^{-\xihat}T^{-1}p\approx(I-\xihat)T^{-1}p=g(T,p)-\xihat\left(T^{-1}p\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $R^{-1}=R^{T}$ +\end_inset + +, +\begin_inset Formula $H(p)=-\Skew p$ +\end_inset + +, and hence the Jacobian matrix of +\begin_inset Formula $g(R,p)=R^{T}p$ +\end_inset + + is given by +\begin_inset Formula +\[ +G_{(R,p)}=\left(\begin{array}{cc} +\Skew{R^{T}p} & R^{T}\end{array}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +My earlier attempt: because the wedge operator is linear, we have +\end_layout + +\begin_layout Plain Layout +\begin_inset Formula +\begin{eqnarray*} +f(\xi+x) & = & \exp\widehat{\left(\xi+x\right)}\\ + & = & \exp\left(\xihat+\hat{x}\right) +\end{eqnarray*} + +\end_inset + +However, except for commutative Lie groups, it is not true that +\begin_inset Formula $\exp\left(\xihat+\hat{x}\right)=\exp\xihat\exp\hat{x}$ +\end_inset + +. + However, if we expand the matrix exponential to second order and assume + +\begin_inset Formula $x\rightarrow0$ +\end_inset + + we do have +\begin_inset Formula +\[ +\exp\left(\xihat+\hat{x}\right)\approx I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat +\] + +\end_inset + +Now, if we ask what +\begin_inset Formula $\hat{y}$ +\end_inset + + would effect the same change: +\begin_inset Formula +\begin{eqnarray*} +\exp\xihat\exp\yhat & = & I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat\\ +\exp\xihat(I+\yhat) & = & I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat\\ +\left(\exp\xihat\right)\yhat & = & \xhat+\xhat\xihat +\end{eqnarray*} + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Section +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For matrix Lie groups, if we have a matrix +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + + that depends on a parameter +\begin_inset Formula $t$ +\end_inset + +, i.e., +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + + follows a curve on the manifold, then it would be of interest to find the + velocity of a point +\begin_inset Formula $q^{n}(t)=T_{b}^{n}(t)p^{b}$ +\end_inset + + acted upon by +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + +. + We can express the velocity of +\begin_inset Formula $q(t)$ +\end_inset + + in both the n-frame and b-frame: +\begin_inset Formula +\[ +\dot{q}^{n}=\dot{T}_{b}^{n}p^{b}=\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1}p^{n}\mbox{\,\,\,\,\ and\,\,\,\,}\dot{q}^{b}=\left(T_{b}^{n}\right)^{-1}\dot{q}^{n}=\left(T_{b}^{n}\right)^{-1}\dot{T}_{b}^{n}p^{b} +\] + +\end_inset + +Both the matrices +\begin_inset Formula $\xihat_{nb}^{n}\define\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1}$ +\end_inset + + and +\begin_inset Formula $\xihat_{nb}^{b}\define\left(T_{b}^{n}\right)^{-1}\dot{T}_{b}^{n}$ +\end_inset + + are skew-symmetric Lie algebra elements that describe the +\series bold +instantaneous velocity +\series default + +\begin_inset CommandInset citation +LatexCommand cite +after "page 51 for rotations, page 419 for SE(3)" +key "Murray94book" + +\end_inset + +. + We will revisit this for both rotations and rigid 3D transformations. +\end_layout + +\begin_layout Section +Differentials: Smooth Mapping between Lie Groups +\end_layout + +\begin_layout Subsection +Motivation and Definition +\end_layout + +\begin_layout Standard +The above shows how to compute the derivative of a function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + +. + However, what if the argument to +\begin_inset Formula $f$ +\end_inset + + is itself the result of a mapping between Lie groups? In other words, +\begin_inset Formula $f=g\circ\varphi$ +\end_inset + +, with +\begin_inset Formula $g:G\rightarrow\Reals m$ +\end_inset + + and where +\begin_inset Formula $\varphi:H\rightarrow G$ +\end_inset + + is a smooth mapping from the +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group +\begin_inset Formula $H$ +\end_inset + + to the +\begin_inset Formula $p$ +\end_inset + +-dimensional Lie group +\begin_inset Formula $G$ +\end_inset + +. + In this case, one would expect that we can arrive at +\begin_inset Formula $Df_{a}$ +\end_inset + + by composing linear maps, as follows: +\begin_inset Formula +\[ +f'(a)=(g\circ\varphi)'(a)=G_{\varphi(a)}\varphi'(a) +\] + +\end_inset + +where +\begin_inset Formula $\varphi'(a)$ +\end_inset + + is an +\begin_inset Formula $n\times p$ +\end_inset + + matrix that is the best linear approximation to the map +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Formula $\varphi:H\rightarrow G$ +\end_inset + +. + The corresponding linear map +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + is called the +\family default +\series bold +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +differential +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +or +\series bold +pushforward +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + of +\begin_inset Formula $ $ +\end_inset + +the mapping +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +Because a rigorous definition will lead us too far astray, here we only + informally define the pushforward of +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + as the linear map +\begin_inset Formula $D\varphi_{a}:\Multi np$ +\end_inset + + such that +\begin_inset Formula $D\varphi_{a}\left(\xi\right)\define\varphi'(a)\xi$ +\end_inset + + and +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit + +\begin_inset Formula +\begin{equation} +\varphi\left(ae^{\xihat}\right)\approx\varphi\left(a\right)\exp\left(\widehat{\varphi'(a)\xi}\right)\label{eq:pushforward} +\end{equation} + +\end_inset + +with equality for +\begin_inset Formula $\xi\rightarrow0$ +\end_inset + +. + We call +\begin_inset Formula $\varphi'(a)$ +\end_inset + + the +\series bold +Jacobian matrix +\series default + of the map +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + Below we show that even with this informal definition we can deduce the + pushforward in a number of useful cases. +\end_layout + +\begin_layout Subsection +Left Multiplication with a Constant +\end_layout + +\begin_layout Theorem +Suppose +\begin_inset Formula $G$ +\end_inset + + is an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group, and +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as +\begin_inset Formula $\varphi(g)=hg$ +\end_inset + +, with +\begin_inset Formula $h\in G$ +\end_inset + + a constant. + Then +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + is the identity mapping and +\begin_inset Formula +\[ +\varphi'(a)=I_{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +\varphi(a)e^{\yhat} & = & \varphi(ae^{\xhat})\\ +hae^{\yhat} & = & hae^{\xhat}\\ +y & = & x +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforward of the Inverse Mapping +\end_layout + +\begin_layout Standard +A well known property of Lie groups is the the fact that applying an incremental + change +\begin_inset Formula $\xihat$ +\end_inset + + in a different frame +\begin_inset Formula $g$ +\end_inset + + can be applied in a single step by applying the change +\begin_inset Formula $Ad_{g}\xihat$ +\end_inset + + in the original frame, +\begin_inset Formula +\begin{equation} +ge^{\xihat}g^{-1}=\exp\left(Ad_{g}\xihat\right)\label{eq:Adjoint2} +\end{equation} + +\end_inset + +where +\begin_inset Formula $Ad_{g}:\mathfrak{g}\rightarrow\mathfrak{g}$ +\end_inset + + is the +\series bold +adjoint representation +\series default +. + This comes in handy in the following: +\end_layout + +\begin_layout Theorem +Suppose that +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as the mapping from an element +\begin_inset Formula $g$ +\end_inset + + to its +\series bold +inverse +\series default + +\begin_inset Formula $g^{-1}$ +\end_inset + +, i.e., +\begin_inset Formula $\varphi(g)=g^{-1}$ +\end_inset + +, then the pushforward +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + satisfies +\begin_inset Formula +\begin{align} +\left(D\varphi_{a}x\right)\hat{} & =-Ad_{a}\xhat\label{eq:Dinverse} +\end{align} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In other words, and this is intuitive in hindsight, approximating the inverse + is accomplished by negation of +\begin_inset Formula $\xihat$ +\end_inset + +, along with an adjoint to make sure it is applied in the right frame. + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Note, however, that +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Dinverse" + +\end_inset + + does not immediately yield a useful expression for the Jacobian matrix + +\begin_inset Formula $\varphi'(a)$ +\end_inset + +, but in many important cases this will turn out to be easy. + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +\varphi(a)e^{\yhat} & = & \varphi(ae^{\xhat})\\ +a^{-1}e^{\yhat} & = & \left(ae^{\xhat}\right)^{-1}\\ +e^{\yhat} & = & -ae^{\xhat}a^{-1}\\ +\yhat & = & -\Ad a\xhat +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula +\[ +Ad_{g}(\hat{\omega})=R\hat{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +and hence the pushforward for the inverse mapping +\begin_inset Formula $\varphi(R)=R^{T}$ +\end_inset + + has the matrix +\begin_inset Formula $\varphi'(R)=-R$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Right Multiplication with a Constant +\end_layout + +\begin_layout Theorem +Suppose +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as +\begin_inset Formula $\varphi(g)=gh$ +\end_inset + +, with +\begin_inset Formula $h\in G$ +\end_inset + + a constant. + Then +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + satisfies +\begin_inset Formula +\[ +\left(D\varphi_{a}x\right)\hat{}=\Ad{h^{-1}}\xhat +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{align*} +\varphi(a)e^{\yhat} & =\varphi(ae^{\xhat})\\ +ahe & =ae^{\xhat}h\\ +e^{\yhat} & =h^{-1}e^{\xhat}h=\exp\left(\Ad{h^{-1}}\xhat\right)\\ +\yhat & =\Ad{h^{-1}}\xhat +\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Example +In the case of 3D rotations, right multiplication with a constant rotation + +\begin_inset Formula $R$ +\end_inset + + is done through the mapping +\begin_inset Formula $\varphi(A)=AR$ +\end_inset + +, and satisfies +\begin_inset Formula +\[ +\Skew{D\varphi_{A}x}=\Ad{R^{T}}\Skew x +\] + +\end_inset + +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula +\[ +Ad_{R^{T}}(\hat{\omega})=R^{T}\hat{\omega}R=\Skew{R^{T}\omega} +\] + +\end_inset + +and hence the Jacobian matrix of +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $A$ +\end_inset + + is +\begin_inset Formula $\varphi'(A)=R^{T}$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Pushforward of Compose +\end_layout + +\begin_layout Theorem +If we define the mapping +\begin_inset Formula $\varphi:G\times G\rightarrow G$ +\end_inset + + as the product of two group elements +\begin_inset Formula $g,h\in G$ +\end_inset + +, i.e., +\begin_inset Formula $\varphi(g,h)=gh$ +\end_inset + +, then the pushforward will satisfy +\begin_inset Formula +\[ +D\varphi_{(a,b)}(x,y)=D_{1}\varphi_{(a,b)}x+D_{2}\varphi_{(a,b)}y +\] + +\end_inset + +with +\begin_inset Formula +\[ +\left(D_{1}\varphi_{(a,b)}x\right)\hat{}=\Ad{b^{-1}}\xhat\mbox{\;\ and\;}D_{2}\varphi_{(a,b)}y=y +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Looking at the first argument, the proof is very similar to right multiplication + with a constant +\begin_inset Formula $b$ +\end_inset + +. + Indeed, defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{align} +\varphi(a,b)e^{\yhat} & =\varphi(ae^{\xhat},b)\nonumber \\ +abe^{\yhat} & =ae^{\xhat}b\nonumber \\ +e^{\yhat} & =b^{-1}e^{\xhat}b=\exp\left(\Ad{b^{-1}}\xhat\right)\nonumber \\ +\yhat & =\Ad{b^{-1}}\xhat\label{eq:Dcompose1} +\end{align} + +\end_inset + +In other words, to apply an incremental change +\begin_inset Formula $\xhat$ +\end_inset + + to +\begin_inset Formula $a$ +\end_inset + + we first need to undo +\begin_inset Formula $b$ +\end_inset + +, then apply +\begin_inset Formula $\xhat$ +\end_inset + +, and then apply +\begin_inset Formula $b$ +\end_inset + + again. + Using +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Adjoint2" + +\end_inset + + this can be done in one step by simply applying +\begin_inset Formula $\Ad{b^{-1}}\xhat$ +\end_inset + +. + +\end_layout + +\begin_layout Proof +The second argument is quite a bit easier and simply yields the identity + mapping: +\begin_inset Formula +\begin{align} +\varphi(a,b)e^{\yhat} & =\varphi(a,be^{\xhat})\nonumber \\ +abe^{\yhat} & =abe^{\xhat}\nonumber \\ +y & =x\label{eq:Dcompose2} +\end{align} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status open + +\begin_layout Plain Layout +In summary, the Jacobian matrix of +\begin_inset Formula $\varphi(g,h)=gh$ +\end_inset + + at +\begin_inset Formula $(a,b)\in G\times G$ +\end_inset + + is given by +\begin_inset Formula +\[ +\varphi'(a,b)=? +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $A,B\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $\varphi(A,B)=AB$ +\end_inset + +, and +\begin_inset Formula $\Ad{B^{T}}\Skew{\omega}=\Skew{B^{T}\omega}$ +\end_inset + +, hence the Jacobian matrix +\begin_inset Formula $\varphi'(A,B)$ +\end_inset + + of composing two rotations is given by +\begin_inset Formula +\[ +\varphi'(A,B)=\left[\begin{array}{cc} +B^{T} & I_{3}\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforward of Between +\end_layout + +\begin_layout Standard +Finally, let us find the pushforward of +\series bold +between +\series default +, defined as +\begin_inset Formula $\varphi(g,h)=g^{-1}h$ +\end_inset + +. + For the first argument we reason as: +\begin_inset Formula +\begin{align} +\varphi(g,h)e^{\yhat} & =\varphi(ge^{\xhat},h)\nonumber \\ +g^{-1}he^{\yhat} & =\left(ge^{\xhat}\right)^{-1}h=-e^{\xhat}g^{-1}h\nonumber \\ +e^{\yhat} & =-\left(h^{-1}g\right)e^{\xhat}\left(h^{-1}g\right)^{-1}=-\exp\Ad{\left(h^{-1}g\right)}\xhat\nonumber \\ +\yhat & =-\Ad{\left(h^{-1}g\right)}\xhat=-\Ad{\varphi\left(h,g\right)}\xhat\label{eq:Dbetween1} +\end{align} + +\end_inset + +The second argument yields the identity mapping. +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $A,B\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $\varphi(A,B)=A^{T}B$ +\end_inset + +, and +\begin_inset Formula $\Ad{B^{T}A}\Skew{-\omega}=\Skew{-B^{T}A\omega}$ +\end_inset + +, hence the Jacobian matrix +\begin_inset Formula $\varphi'(A,B)$ +\end_inset + + of between is given by +\begin_inset Formula +\[ +\varphi'(A,B)=\left[\begin{array}{cc} +\left(-B^{T}A\right) & I_{3}\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Numerical PushForward +\end_layout + +\begin_layout Standard +Let's examine +\begin_inset Formula +\[ +f\left(g\right)e^{\yhat}=f\left(ge^{\xhat}\right) +\] + +\end_inset + +and multiply with +\begin_inset Formula $f(g)^{-1}$ +\end_inset + + on both sides: +\begin_inset Formula +\[ +e^{\yhat}=f\left(g\right)^{-1}f\left(ge^{\xhat}\right) +\] + +\end_inset + +We then take the log (which in our case returns +\begin_inset Formula $y$ +\end_inset + +, not +\begin_inset Formula $\yhat$ +\end_inset + +): +\begin_inset Formula +\[ +y(x)=\log\left[f\left(g\right)^{-1}f\left(ge^{\xhat}\right)\right] +\] + +\end_inset + +Let us look at +\begin_inset Formula $x=0$ +\end_inset + +, and perturb in direction +\begin_inset Formula $i$ +\end_inset + +, +\begin_inset Formula $e_{i}=[0,0,1,0,0]$ +\end_inset + +. + Then take derivative, +\begin_inset Formula +\[ +\deriv{y(d)}d\define\lim_{d\rightarrow0}\frac{y(d)-y(0)}{d}=\lim_{d\rightarrow0}\frac{1}{d}\log\left[f\left(g\right)^{-1}f\left(ge^{\widehat{de_{i}}}\right)\right] +\] + +\end_inset + +which is the basis for a numerical derivative scheme. +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Not understood yet: Let us also look at a chain rule. + If we know the behavior at the origin +\begin_inset Formula $I$ +\end_inset + +, we can extrapolate +\begin_inset Formula +\[ +f(ge^{\xhat})=f(ge^{\xhat}g^{-1}g)=f(e^{\Ad g\xhat}g) +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivative of the Exponential and Logarithm Map +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "D-exp" + +\end_inset + +The derivative of the function +\begin_inset Formula $f:\Reals n\rightarrow G$ +\end_inset + + that applies the wedge operator followed by the exponential map, i.e., +\begin_inset Formula $f(\xi)=\exp\xihat$ +\end_inset + +, is the identity map for +\begin_inset Formula $\xi=0$ +\end_inset + +. +\end_layout + +\begin_layout Proof +For +\begin_inset Formula $\xi=0$ +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +f(\xi)e^{\yhat} & = & f(\xi+x)\\ +f(0)e^{\yhat} & = & f(0+x)\\ +e^{\yhat} & = & e^{\xhat} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Corollary +The derivative of the inverse +\begin_inset Formula $f^{-1}$ +\end_inset + + is the identity as well, i.e., for +\begin_inset Formula $T=e$ +\end_inset + +, the identity element in +\begin_inset Formula $G$ +\end_inset + +. +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\xi\neq0$ +\end_inset + +, things are not simple, see . + +\begin_inset Flex URL +status collapsed + +\begin_layout Plain Layout + +http://deltaepsilons.wordpress.com/2009/11/06/helgasons-formula-for-the-differenti +al-of-the-exponential/ +\end_layout + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +General Manifolds +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\retract}{\mathcal{R}} +{\mathcal{R}} +\end_inset + + +\end_layout + +\begin_layout Standard +General manifolds that are not Lie groups do not have an exponential map, + but can still be handled by defining a +\series bold +retraction +\series default + +\begin_inset Formula $\retract:\Man\times\Reals n\rightarrow\Man$ +\end_inset + +, such that +\begin_inset Formula +\[ +a\oplus\xi\define\retract_{a}\left(\xi\right) +\] + +\end_inset + +A retraction +\begin_inset CommandInset citation +LatexCommand cite +key "Absil07book" + +\end_inset + + is required to be tangent to geodesics on the manifold +\begin_inset Formula $\Man$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + We can define many retractions for a manifold +\begin_inset Formula $\Man$ +\end_inset + +, even for those with more structure. + For the vector space +\begin_inset Formula $\Reals n$ +\end_inset + + the retraction is just vector addition, and for Lie groups the obvious + retraction is simply the exponential map, i.e., +\begin_inset Formula $\retract_{a}(\xi)=a\cdot\exp\xihat$ +\end_inset + +. + However, one can choose other, possibly computationally attractive retractions, + as long as around a they agree with the geodesic induced by the exponential + map, i.e., +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|a\cdot\exp\xihat-\retract_{a}\left(\xi\right)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For +\begin_inset Formula $\SEthree$ +\end_inset + +, instead of using the true exponential map it is computationally more efficient + to define the retraction, which uses a first order approximation of the + translation update +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+Rv\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +Equipped with a retraction, then, we can generalize the notion of a derivative + for functions +\begin_inset Formula $f$ +\end_inset + + from general a manifold +\begin_inset Formula $\Man$ +\end_inset + + to +\begin_inset Formula $\Reals m$ +\end_inset + +: +\end_layout + +\begin_layout Definition +We define a function +\begin_inset Formula $f:\Man\rightarrow\Reals m$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a\in\Man$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f\left(\retract_{a}(\xi)\right)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + + for an +\begin_inset Formula $n$ +\end_inset + +-dimensional manifold, and +\begin_inset Formula $\retract_{a}:\Reals n\rightarrow\Man$ +\end_inset + + a retraction +\begin_inset Formula $\retract$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear transformation +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. +\end_layout + +\begin_layout Definition +For manifolds that are also Lie groups, the derivative of any function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + + will agree no matter what retraction +\begin_inset Formula $\retract$ +\end_inset + + is used. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Part +Practice +\end_layout + +\begin_layout Standard +Below we apply the results derived in the theory part to the geometric objects + we use in GTSAM. + Above we preferred the modern notation +\begin_inset Formula $D_{1}f$ +\end_inset + + for the partial derivative. + Below (because this was written earlier) we use the more classical notation + +\begin_inset Formula +\[ +\deriv{f(x,y)}x +\] + +\end_inset + +In addition, for Lie groups we will abuse the notation and take +\begin_inset Formula +\[ +\at{\deriv{\varphi(g)}{\xi}}a +\] + +\end_inset + +to be the Jacobian matrix +\begin_inset Formula $\varphi'($ +\end_inset + +a) of the mapping +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a\in G$ +\end_inset + +, associated with the pushforward +\begin_inset Formula $D\varphi_{a}$ +\end_inset + +. +\end_layout + +\begin_layout Section +SLAM Example +\end_layout + +\begin_layout Standard +Let us examine a visual SLAM example. + We have 2D measurements +\begin_inset Formula $z_{ij}$ +\end_inset + +, where each measurement is predicted by +\begin_inset Formula +\[ +z_{ij}=h(T_{i},p_{j})=\pi(T_{i}^{-1}p_{j}) +\] + +\end_inset + +where +\begin_inset Formula $T_{i}$ +\end_inset + + is the 3D pose of the +\begin_inset Formula $i^{th}$ +\end_inset + + camera, +\begin_inset Formula $p_{j}$ +\end_inset + + is the location of the +\begin_inset Formula $j^{th}$ +\end_inset + + point, and +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + is the camera projection function from Example +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + +. +\end_layout + +\begin_layout Section +BetweenFactor +\end_layout + +\begin_layout Standard +BetweenFactor is often used to summarize +\end_layout + +\begin_layout Standard +Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "D-exp" + +\end_inset + + about the derivative of the exponential map +\begin_inset Formula $f:\xi\mapsto\exp\xihat$ +\end_inset + + being identity only at +\begin_inset Formula $\xi=0$ +\end_inset + + has implications for GTSAM. + Given two elements +\begin_inset Formula $T_{1}$ +\end_inset + + and +\begin_inset Formula $T_{2}$ +\end_inset + +, BetweenFactor evaluates +\begin_inset Formula +\[ +g(T_{1},T_{2};Z)=f^{-1}\left(\mathop{between}(Z,\mathop{between}(T_{1},T_{2})\right)=f^{-1}\left(Z^{-1}\left(T_{1}^{-1}T_{2}\right)\right) +\] + +\end_inset + +but because it is assumed that +\begin_inset Formula $Z\approx T_{1}^{-1}T_{2}$ +\end_inset + +, and hence we have +\begin_inset Formula $Z^{-1}T_{1}^{-1}T_{2}\approx e$ +\end_inset + + and the derivative should be good there. + Note that the derivative of +\emph on +between +\emph default + is identity in its second argument. +\end_layout + +\begin_layout Section +Point3 +\end_layout + +\begin_layout Standard +A cross product +\begin_inset Formula $a\times b$ +\end_inset + + can be written as a matrix multiplication +\begin_inset Formula +\[ +a\times b=\Skew ab +\] + +\end_inset + +where +\begin_inset Formula $\Skew a$ +\end_inset + + is a skew-symmetric matrix defined as +\begin_inset Formula +\[ +\Skew{x,y,z}=\left[\begin{array}{ccc} +0 & -z & y\\ +z & 0 & -x\\ +-y & x & 0 +\end{array}\right] +\] + +\end_inset + +We also have +\begin_inset Formula +\[ +a^{T}\Skew b=-(\Skew ba)^{T}=-(a\times b)^{T} +\] + +\end_inset + +The derivative of a cross product +\begin_inset Formula +\begin{equation} +\frac{\partial(a\times b)}{\partial a}=\Skew{-b}\label{eq:Dcross1} +\end{equation} + +\end_inset + + +\begin_inset Formula +\begin{equation} +\frac{\partial(a\times b)}{\partial b}=\Skew a\label{eq:Dcross2} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rotations +\end_layout + +\begin_layout Subsection +Rot2 in GTSAM +\end_layout + +\begin_layout Standard +A rotation is stored as +\begin_inset Formula $(\cos\theta,\sin\theta)$ +\end_inset + +. + An incremental rotation is applied using the trigonometric sum rule: +\begin_inset Formula +\[ +\cos\theta'=\cos\theta\cos\delta-\sin\theta\sin\delta +\] + +\end_inset + + +\begin_inset Formula +\[ +\sin\theta'=\sin\theta\cos\delta+\cos\theta\sin\delta +\] + +\end_inset + +where +\begin_inset Formula $\delta$ +\end_inset + + is an incremental rotation angle. +\end_layout + +\begin_layout Subsection +Derivatives of Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + + the vector space is +\begin_inset Formula $\Rtwo$ +\end_inset + +, and the group action +\begin_inset Formula $f(R,p)$ +\end_inset + + corresponds to rotating the 2D point +\begin_inset Formula $p$ +\end_inset + + +\begin_inset Formula +\[ +f(R,p)=Rp +\] + +\end_inset + +According to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + +, the Jacobian matrix of +\begin_inset Formula $f$ +\end_inset + + is given by +\begin_inset Formula +\[ +f'(R,p)=\left[\begin{array}{cc} +RH(p) & R\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $H:\Reals 2\rightarrow\Reals{2\times2}$ +\end_inset + + a linear mapping that depends on +\begin_inset Formula $p$ +\end_inset + +. + In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + +, we can find +\begin_inset Formula $H(p)$ +\end_inset + + by equating (as in Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Hp" + +\end_inset + +): +\begin_inset Formula +\[ +\skew wp=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]\left[\begin{array}{c} +x\\ +y +\end{array}\right]=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]\omega=H(p)\omega +\] + +\end_inset + +Note that +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Formula +\[ +H(p)=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]=\left[\begin{array}{cc} +0 & -1\\ +1 & 0 +\end{array}\right]\left[\begin{array}{c} +x\\ +y +\end{array}\right]=R_{\pi/2}p +\] + +\end_inset + +and since 2D rotations commute, we also have, with +\begin_inset Formula $q=Rp$ +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +: +\begin_inset Formula +\[ +f'(R,p)=\left[\begin{array}{cc} +R\left(R_{\pi/2}p\right) & R\end{array}\right]=\left[\begin{array}{cc} +R_{\pi/2}q & R\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +Since +\begin_inset Formula $\Ad R\skew{\omega}=\skew{\omega}$ +\end_inset + +, we have the derivative of +\series bold +inverse +\series default +, +\begin_inset Formula +\[ +\frac{\partial R^{T}}{\partial\omega}=-\Ad R=-1\mbox{ } +\] + +\end_inset + + +\series bold +compose, +\series default + +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{1}}=\Ad{R_{2}^{T}}=1\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=1 +\] + +\end_inset + +and +\series bold +between: +\series default + +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{1}}=-\Ad{R_{2}^{T}R_{1}}=-1\mbox{ and }\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{2}}=1 +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rigid Transformations +\end_layout + +\begin_layout Subsection +The derivatives of Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEtwo$ +\end_inset + + on 2D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{3}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +f(T,p)=\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +To find the derivative, we write the quantity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + as the product of the +\begin_inset Formula $3\times3$ +\end_inset + + matrix +\begin_inset Formula $H(p)$ +\end_inset + + with +\begin_inset Formula $\xi$ +\end_inset + +: +\begin_inset Formula +\begin{equation} +\xihat\hat{p}=\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\skew{\omega}p+v\\ +0 +\end{array}\right]=\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]=H(p)\xi\label{eq:HpSE2} +\end{equation} + +\end_inset + +Hence, by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + + we have +\begin_inset Formula +\begin{equation} +\deriv{\left(T\hat{p}\right)}{\xi}=TH(p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R & RR_{\pi/2}p\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R & R_{\pi/2}q\\ +0 & 0 +\end{array}\right]\label{eq:SE2Action} +\end{equation} + +\end_inset + +Note that, looking only at the top rows of +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:HpSE2" + +\end_inset + + and +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:SE2Action" + +\end_inset + +, we can recognize the quantity +\begin_inset Formula $\skew{\omega}p+v=v+\omega\left(R_{\pi/2}p\right)$ +\end_inset + + as the velocity of +\begin_inset Formula $p$ +\end_inset + + in +\begin_inset Formula $\Rtwo$ +\end_inset + +, and +\begin_inset Formula $\left[\begin{array}{cc} +R & R_{\pi/2}q\end{array}\right]$ +\end_inset + + is the derivative of the action on +\begin_inset Formula $\Rtwo$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +The derivative of the inverse action +\begin_inset Formula $g(T,p)=T^{-1}\hat{p}$ +\end_inset + + is given by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + + specialized to +\begin_inset Formula $\SEtwo$ +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\xi}=-H(T^{-1}p)=\left[\begin{array}{cc} +-I_{2} & -R_{\pi/2}\left(T^{-1}p\right)\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +We can just define all derivatives in terms of the adjoint map, which in + the case of +\begin_inset Formula $\SEtwo$ +\end_inset + +, in twist coordinates, is the linear mapping +\begin_inset Formula +\[ +\Ad T\xi=\left[\begin{array}{cc} +R & -R_{\pi/2}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right] +\] + +\end_inset + +and we have +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial T^{^{-1}}}{\partial\xi} & = & -\Ad T +\end{eqnarray*} + +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{1}} & = & \Ad{T_{2}^{^{-1}}}\mbox{ and }\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{2}}=I_{3} +\end{eqnarray*} + +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}^{-1}T_{2}\right)}{\partial\xi_{1}} & = & -\Ad{T_{2}^{^{-1}}T_{1}}=-\Ad{between(T_{2},T_{1})}\mbox{ and }\frac{\partial\left(T_{1}^{-1}T_{2}\right)}{\partial\xi_{2}}=I_{3} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rotations +\end_layout + +\begin_layout Subsection +Derivatives of Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOthree$ +\end_inset + + the vector space is +\begin_inset Formula $\Rthree$ +\end_inset + +, and the group action +\begin_inset Formula $f(R,p)$ +\end_inset + + corresponds to rotating a point +\begin_inset Formula +\[ +q=f(R,p)=Rp +\] + +\end_inset + +To calculate +\begin_inset Formula $H(p)$ +\end_inset + + for use in Theorem +\begin_inset CommandInset ref +LatexCommand eqref +reference "th:Action" + +\end_inset + + we make use of +\begin_inset Formula +\[ +\Skew{\omega}p=\omega\times p=-p\times\omega=\Skew{-p}\omega +\] + +\end_inset + +so +\begin_inset Formula $H(p)\define\Skew{-p}$ +\end_inset + +. + Hence, the final derivative of an action in its first argument is +\begin_inset Formula +\[ +\deriv{\left(Rp\right)}{\omega}=RH(p)=-R\Skew p +\] + +\end_inset + +Likewise, according to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + +, the derivative of the inverse action is given by +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +\deriv{\left(R^{T}p\right)}{\omega}=-H(R^{T}p)=\Skew{R^{T}p} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:3DAngularVelocities" + +\end_inset + +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For 3D rotations +\begin_inset Formula $R_{b}^{n}$ +\end_inset + + from a body frame +\begin_inset Formula $b$ +\end_inset + + to a navigation frame +\begin_inset Formula $n$ +\end_inset + + we have the spatial angular velocity +\begin_inset Formula $\omega_{nb}^{n}$ +\end_inset + + measured in the navigation frame, +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{n}}\define\dot{R}_{b}^{n}\left(R_{b}^{n}\right)^{T}=\dot{R}_{b}^{n}R_{n}^{b} +\] + +\end_inset + +and the body angular velocity +\begin_inset Formula $\omega_{nb}^{b}$ +\end_inset + + measured in the body frame: +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{b}}\define\left(R_{b}^{n}\right)^{T}\dot{R}_{b}^{n}=R_{n}^{b}\dot{R}_{b}^{n} +\] + +\end_inset + +These quantities can be used to derive the velocity of a point +\begin_inset Formula $p$ +\end_inset + +, and we choose between spatial or body angular velocity depending on the + frame in which we choose to represent +\begin_inset Formula $p$ +\end_inset + +: +\begin_inset Formula +\[ +v^{n}=\Skew{\omega_{nb}^{n}}p^{n}=\omega_{nb}^{n}\times p^{n} +\] + +\end_inset + + +\begin_inset Formula +\[ +v^{b}=\Skew{\omega_{nb}^{b}}p^{b}=\omega_{nb}^{b}\times p^{b} +\] + +\end_inset + +We can transform these skew-symmetric matrices from navigation to body frame + by conjugating, +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{b}}=R_{n}^{b}\Skew{\omega_{nb}^{n}}R_{b}^{n} +\] + +\end_inset + +but because the adjoint representation satisfies +\begin_inset Formula +\[ +Ad_{R}\Skew{\omega}\define R\Skew{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +we can even more easily transform between spatial and body angular velocities + as 3-vectors: +\begin_inset Formula +\[ +\omega_{nb}^{b}=R_{n}^{b}\omega_{nb}^{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\SOthree$ +\end_inset + + we have +\begin_inset Formula $\Ad R\Skew{\omega}=\Skew{R\omega}$ +\end_inset + + and, in terms of angular velocities: +\begin_inset Formula $\Ad R\omega=R\omega$ +\end_inset + +. + Hence, the Jacobian matrix of the +\series bold +inverse +\series default + mapping is (see Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dinverse" + +\end_inset + +) +\begin_inset Formula +\[ +\frac{\partial R^{T}}{\partial\omega}=-\Ad R=-R +\] + +\end_inset + +for +\series bold +compose +\series default + we have (Equations +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dcompose1" + +\end_inset + + and +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dcompose2" + +\end_inset + +): +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{1}}=R_{2}^{T}\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=I_{3} +\] + +\end_inset + +and +\series bold +between +\series default + (Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dbetween1" + +\end_inset + +): +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{1}}=-R_{2}^{T}R_{1}=-between(R_{2},R_{1})\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=I_{3} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +Absil +\begin_inset CommandInset citation +LatexCommand cite +after "page 58" +key "Absil07book" + +\end_inset + + discusses two possible retractions for +\begin_inset Formula $\SOthree$ +\end_inset + + based on the QR decomposition or the polar decomposition of the matrix + +\begin_inset Formula $R\Skew{\omega}$ +\end_inset + +, but they are expensive. + Another retraction is based on the Cayley transform +\begin_inset Formula $\mathcal{C}:\sothree\rightarrow\SOthree$ +\end_inset + +, a mapping from the skew-symmetric matrices to rotation matrices: +\begin_inset Formula +\[ +Q=\mathcal{C}(\Omega)=(I-\Omega)(I+\Omega)^{-1} +\] + +\end_inset + +Interestingly, the inverse Cayley transform +\begin_inset Formula $\mathcal{C}^{-1}:\SOthree\rightarrow\sothree$ +\end_inset + + has the same form: +\begin_inset Formula +\[ +\Omega=\mathcal{C}^{-1}(Q)=(I-Q)(I+Q)^{-1} +\] + +\end_inset + +The retraction needs a factor +\begin_inset Formula $-\frac{1}{2}$ +\end_inset + + however, to make it locally align with a geodesic: +\begin_inset Formula +\[ +R'=\retract_{R}(\omega)=R\mathcal{C}(-\frac{1}{2}\Skew{\omega}) +\] + +\end_inset + +Note that given +\begin_inset Formula $\omega=(x,y,z)$ +\end_inset + + this has the closed-form expression below +\begin_inset Formula +\[ +\frac{1}{4+x^{2}+y^{2}+z^{2}}\left[\begin{array}{ccc} +4+x^{2}-y^{2}-z^{2} & 2xy-4z & 2xz+4y\\ +2xy+4z & 4-x^{2}+y^{2}-z^{2} & 2yz-4x\\ +2xz-4y & 2yz+4x & 4-x^{2}-y^{2}+z^{2} +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +=\frac{1}{4+x^{2}+y^{2}+z^{2}}\left\{ 4(I+\Skew{\omega})+\left[\begin{array}{ccc} +x^{2}-y^{2}-z^{2} & 2xy & 2xz\\ +2xy & -x^{2}+y^{2}-z^{2} & 2yz\\ +2xz & 2yz & -x^{2}-y^{2}+z^{2} +\end{array}\right]\right\} +\] + +\end_inset + +so it can be seen to be a second-order correction on +\begin_inset Formula $(I+\Skew{\omega})$ +\end_inset + +. + The corresponding approximation to the logarithmic map is: +\begin_inset Formula +\[ +\Skew{\omega}=\retract_{R}^{-1}(R')=-2\mathcal{C}^{-1}\left(R^{T}R'\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Section +3D Rigid Transformations +\end_layout + +\begin_layout Subsection +The derivatives of Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEthree$ +\end_inset + + on 3D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=f(T,p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +The quantity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + corresponds to a velocity in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + (in the local +\begin_inset Formula $T$ +\end_inset + + frame), and equating it to +\begin_inset Formula $H(p)\xi$ +\end_inset + + as in Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Hp" + +\end_inset + + yields the +\begin_inset Formula $4\times6$ +\end_inset + + matrix +\begin_inset Formula $H(p)$ +\end_inset + + +\begin_inset Foot +status collapsed + +\begin_layout Plain Layout +\begin_inset Formula $H(p)$ +\end_inset + + can also be obtained by taking the +\begin_inset Formula $j^{th}$ +\end_inset + + column of each of the 6 generators to multiply with components of +\begin_inset Formula $\hat{p}$ +\end_inset + + +\end_layout + +\end_inset + +: +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\omega\times p+v\\ +0 +\end{array}\right]=\left[\begin{array}{cc} +\Skew{-p} & I_{3}\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]=H(p)\xi +\] + +\end_inset + +Note how velocities are analogous to points at infinity in projective geometry: + they correspond to free vectors indicating a direction and magnitude of + change. + According to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + +, the derivative of the group action is then +\begin_inset Formula +\[ +\deriv{\left(T\hat{p}\right)}{\xi}=TH(p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\Skew{-p} & I_{3}\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R\Skew{-p} & R\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{\left(T\hat{p}\right)}{\hat{p}}=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +in homogenous coordinates. + In +\begin_inset Formula $\Rthree$ +\end_inset + + this becomes +\begin_inset Formula $R\left[\begin{array}{cc} +-\Skew p & I_{3}\end{array}\right]$ +\end_inset + +. +\end_layout + +\begin_layout Standard +The derivative of the inverse action +\begin_inset Formula $T^{-1}p$ +\end_inset + + is given by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + +: +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\xi}=-H\left(T^{-1}\hat{p}\right)=\left[\begin{array}{cc} +\Skew{T^{-1}\hat{p}} & -I_{3}\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\hat{p}}=\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Example +Let us examine a visual SLAM example. + We have 2D measurements +\begin_inset Formula $z_{ij}$ +\end_inset + +, where each measurement is predicted by +\begin_inset Formula +\[ +z_{ij}=h(T_{i},p_{j})=\pi(T_{i}^{-1}p_{j})=\pi(q) +\] + +\end_inset + +where +\begin_inset Formula $T_{i}$ +\end_inset + + is the 3D pose of the +\begin_inset Formula $i^{th}$ +\end_inset + + camera, +\begin_inset Formula $p_{j}$ +\end_inset + + is the location of the +\begin_inset Formula $j^{th}$ +\end_inset + + point, +\begin_inset Formula $q=(x',y',z')=T^{-1}p$ +\end_inset + + is the point in camera coordinates, and +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + is the camera projection function from Example +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + +. + By the chain rule, we then have +\begin_inset Formula +\[ +\deriv{h(T,p)}{\xi}=\deriv{\pi(q)}q\deriv{(T^{-1}p)}{\xi}=\frac{1}{z'}\left[\begin{array}{ccc} +1 & 0 & -x'/z'\\ +0 & 1 & -y'/z' +\end{array}\right]\left[\begin{array}{cc} +\Skew q & -I_{3}\end{array}\right]=\left[\begin{array}{cc} +\pi'(q)\Skew q & -\pi'(q)\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{h(T,p)}p=\pi'(q)R^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For rigid 3D transformations +\begin_inset Formula $T_{b}^{n}$ +\end_inset + + from a body frame +\begin_inset Formula $b$ +\end_inset + + to a navigation frame +\begin_inset Formula $n$ +\end_inset + + we have the instantaneous spatial twist +\begin_inset Formula $\xi_{nb}^{n}$ +\end_inset + + measured in the navigation frame, +\begin_inset Formula +\[ +\hat{\xi}_{nb}^{n}\define\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1} +\] + +\end_inset + +and the instantaneous body twist +\begin_inset Formula $\xi_{nb}^{b}$ +\end_inset + + measured in the body frame: +\begin_inset Formula +\[ +\hat{\xi}_{nb}^{b}\define\left(T_{b}^{n}\right)^{T}\dot{T}_{b}^{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +As we can express the Adjoint representation in terms of twist coordinates, + we have +\begin_inset Formula +\[ +\left[\begin{array}{c} +\omega'\\ +v' +\end{array}\right]=\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + +Hence, as with +\begin_inset Formula $\SOthree$ +\end_inset + +, we are now in a position to simply posit the derivative of +\series bold +inverse +\series default +, +\begin_inset Formula +\[ +\frac{\partial T^{-1}}{\partial\xi}=\Ad T=-\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right] +\] + +\end_inset + + +\series bold +compose +\series default + in its first argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{1}}=\Ad{T_{2}^{-1}} +\] + +\end_inset + + in its second argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{2}}=I_{6} +\] + +\end_inset + + +\series bold +between +\series default + in its first argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{1}}=\Ad{T_{2}^{^{-1}}T_{1}} +\] + +\end_inset + +and in its second argument, +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{1}} & = & I_{6} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\SEthree$ +\end_inset + +, instead of using the true exponential map it is computationally more efficient + to design other retractions. + A first-order approximation to the exponential map does not quite cut it, + as it yields a +\begin_inset Formula $4\times4$ +\end_inset + + matrix which is not in +\begin_inset Formula $\SEthree$ +\end_inset + +: +\begin_inset Formula +\begin{eqnarray*} +T\exp\xihat & \approx & T(I+\xihat)\\ + & = & T\left(I_{4}+\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +I_{3}+\Skew{\omega} & v\\ +0 & 1 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +R\left(I_{3}+\Skew{\omega}\right) & t+Rv\\ +0 & 1 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +However, we can make it into a retraction by using any retraction defined + for +\begin_inset Formula $\SOthree$ +\end_inset + +, including, as below, using the exponential map +\begin_inset Formula $Re^{\Skew{\omega}}$ +\end_inset + +: +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+Rv\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +Similarly, for a second order approximation we have +\begin_inset Formula +\begin{eqnarray*} +T\exp\xihat & \approx & T(I+\xihat+\frac{\xihat^{2}}{2})\\ + & = & T\left(I_{4}+\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]+\frac{1}{2}\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left(\left[\begin{array}{cc} +I_{3}+\Skew{\omega}+\frac{1}{2}\Skew{\omega}^{2} & v+\frac{1}{2}\Skew{\omega}v\\ +0 & 1 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R\left(I_{3}+\Skew{\omega}+\frac{1}{2}\Skew{\omega}^{2}\right) & t+R\left[v+\left(\omega\times v\right)/2\right]\\ +0 & 1 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +inspiring the retraction +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v+\left(\omega\times v\right)/2\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+R\left[v+\left(\omega\times v\right)/2\right]\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Line Segments (Ocaml) +\end_layout + +\begin_layout Standard +The error between an infinite line +\begin_inset Formula $(a,b,c)$ +\end_inset + + and a 2D line segment +\begin_inset Formula $((x1,y1),(x2,y2))$ +\end_inset + + is defined in Line3.ml. +\end_layout + +\begin_layout Section +Line3vd (Ocaml) +\end_layout + +\begin_layout Standard +One representation of a line is through 2 vectors +\begin_inset Formula $(v,d)$ +\end_inset + +, where +\begin_inset Formula $v$ +\end_inset + + is the direction and the vector +\begin_inset Formula $d$ +\end_inset + + points from the orgin to the closest point on the line. +\end_layout + +\begin_layout Standard +In this representation, transforming a 3D line from a world coordinate frame + to a camera at +\begin_inset Formula $(R_{w}^{c},t^{w})$ +\end_inset + + is done by +\begin_inset Formula +\[ +v^{c}=R_{w}^{c}v^{w} +\] + +\end_inset + + +\begin_inset Formula +\[ +d^{c}=R_{w}^{c}\left(d^{w}+(t^{w}v^{w})v^{w}-t^{w}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Section +Line3 (Ocaml) +\end_layout + +\begin_layout Standard +For 3D lines, we use a parameterization due to C.J. + Taylor, using a rotation matrix +\begin_inset Formula $R$ +\end_inset + + and 2 scalars +\begin_inset Formula $a$ +\end_inset + + and +\begin_inset Formula $b$ +\end_inset + +. + The line direction +\begin_inset Formula $v$ +\end_inset + + is simply the Z-axis of the rotated frame, i.e., +\begin_inset Formula $v=R_{3}$ +\end_inset + +, while the vector +\begin_inset Formula $d$ +\end_inset + + is given by +\begin_inset Formula $d=aR_{1}+bR_{2}$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Now, we will +\emph on +not +\emph default + use the incremental rotation scheme we used for rotations: because the + matrix R translates from the line coordinate frame to the world frame, + we need to apply the incremental rotation on the right-side: +\begin_inset Formula +\[ +R'=R(I+\Omega) +\] + +\end_inset + +Projecting a line to 2D can be done easily, as both +\begin_inset Formula $v$ +\end_inset + + and +\begin_inset Formula $d$ +\end_inset + + are also the 2D homogenous coordinates of two points on the projected line, + and hence we have +\begin_inset Formula +\begin{eqnarray*} +l & = & v\times d\\ + & = & R_{3}\times\left(aR_{1}+bR_{2}\right)\\ + & = & a\left(R_{3}\times R_{1}\right)+b\left(R_{3}\times R_{2}\right)\\ + & = & aR_{2}-bR_{1} +\end{eqnarray*} + +\end_inset + +This can be written as a rotation of a point, +\begin_inset Formula +\[ +l=R\left(\begin{array}{c} +-b\\ +a\\ +0 +\end{array}\right) +\] + +\end_inset + +but because the incremental rotation is now done on the right, we need to + figure out the derivatives again: +\begin_inset Formula +\begin{equation} +\frac{\partial(R(I+\Omega)x)}{\partial\omega}=\frac{\partial(R\Omega x)}{\partial\omega}=R\frac{\partial(\Omega x)}{\partial\omega}=R\Skew{-x}\label{eq:rotateRight} +\end{equation} + +\end_inset + +and hence the derivative of the projection +\begin_inset Formula $l$ +\end_inset + + with respect to the rotation matrix +\begin_inset Formula $R$ +\end_inset + +of the 3D line is +\begin_inset Formula +\begin{equation} +\frac{\partial(l)}{\partial\omega}=R\Skew{\left(\begin{array}{c} +b\\ +-a\\ +0 +\end{array}\right)}=\left[\begin{array}{ccc} +aR_{3} & bR_{3} & -(aR_{1}+bR_{2})\end{array}\right] +\end{equation} + +\end_inset + +or the +\begin_inset Formula $a,b$ +\end_inset + + scalars: +\begin_inset Formula +\[ +\frac{\partial(l)}{\partial a}=R_{2} +\] + +\end_inset + + +\begin_inset Formula +\[ +\frac{\partial(l)}{\partial b}=-R_{1} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +Transforming a 3D line +\begin_inset Formula $(R,(a,b))$ +\end_inset + + from a world coordinate frame to a camera frame +\begin_inset Formula $(R_{w}^{c},t^{w})$ +\end_inset + + is done by +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +R'=R_{w}^{c}R +\] + +\end_inset + + +\begin_inset Formula +\[ +a'=a-R_{1}^{T}t^{w} +\] + +\end_inset + + +\begin_inset Formula +\[ +b'=b-R_{2}^{T}t^{w} +\] + +\end_inset + +Again, we need to redo the derivatives, as R is incremented from the right. + The first argument is incremented from the left, but the result is incremented + on the right: +\begin_inset Formula +\begin{eqnarray*} +R'(I+\Omega')=(AB)(I+\Omega') & = & (I+\Skew{S\omega})AB\\ +I+\Omega' & = & (AB)^{T}(I+\Skew{S\omega})(AB)\\ +\Omega' & = & R'^{T}\Skew{S\omega}R'\\ +\Omega' & = & \Skew{R'^{T}S\omega}\\ +\omega' & = & R'^{T}S\omega +\end{eqnarray*} + +\end_inset + +For the second argument +\begin_inset Formula $R$ +\end_inset + + we now simply have: +\begin_inset Formula +\begin{eqnarray*} +AB(I+\Omega') & = & AB(I+\Omega)\\ +\Omega' & = & \Omega\\ +\omega' & = & \omega +\end{eqnarray*} + +\end_inset + +The scalar derivatives can be found by realizing that +\begin_inset Formula +\[ +\left(\begin{array}{c} +a'\\ +b'\\ +... +\end{array}\right)=\left(\begin{array}{c} +a\\ +b\\ +0 +\end{array}\right)-R^{T}t^{w} +\] + +\end_inset + +where we don't care about the third row. + Hence +\begin_inset Formula +\[ +\frac{\partial(\left(R(I+\Omega_{2})\right)^{T}t^{w})}{\partial\omega}=-\frac{\partial(\Omega_{2}R^{T}t^{w})}{\partial\omega}=-\Skew{R^{T}t^{w}}=\left[\begin{array}{ccc} +0 & R_{3}^{T}t^{w} & -R_{2}^{T}t^{w}\\ +-R_{3}^{T}t^{w} & 0 & R_{1}^{T}t^{w}\\ +... & ... & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Section + +\series bold +Aligning 3D Scans +\end_layout + +\begin_layout Standard +Below is the explanaition underlying Pose3.align, i.e. + aligning two point clouds using SVD. + Inspired but modified from CVOnline... +\end_layout + +\begin_layout Standard + +\emph on +Our +\emph default + model is +\begin_inset Formula +\[ +p^{c}=R\left(p^{w}-t\right) +\] + +\end_inset + +i.e., +\begin_inset Formula $R$ +\end_inset + + is from camera to world, and +\begin_inset Formula $t$ +\end_inset + + is the camera location in world coordinates. + The objective function is +\begin_inset Formula +\begin{equation} +\frac{1}{2}\sum\left(p^{c}-R(p^{w}-t)\right)^{2}=\frac{1}{2}\sum\left(p^{c}-Rp^{w}+Rt\right)^{2}=\frac{1}{2}\sum\left(p^{c}-Rp^{w}-t'\right)^{2}\label{eq:J} +\end{equation} + +\end_inset + +where +\begin_inset Formula $t'=-Rt$ +\end_inset + + is the location of the origin in the camera frame. + Taking the derivative with respect to +\begin_inset Formula $t'$ +\end_inset + + and setting to zero we have +\begin_inset Formula +\[ +\sum\left(p^{c}-Rp^{w}-t'\right)=0 +\] + +\end_inset + +or +\begin_inset Formula +\begin{equation} +t'=\frac{1}{n}\sum\left(p^{c}-Rp^{w}\right)=\bar{p}^{c}-R\bar{p}^{w}\label{eq:t} +\end{equation} + +\end_inset + +here +\begin_inset Formula $\bar{p}^{c}$ +\end_inset + + and +\begin_inset Formula $\bar{p}^{w}$ +\end_inset + + are the point cloud centroids. + Substituting back into +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:J" + +\end_inset + +, we get +\begin_inset Formula +\[ +\frac{1}{2}\sum\left(p^{c}-R(p^{w}-t)\right)^{2}=\frac{1}{2}\sum\left(\left(p^{c}-\bar{p}^{c}\right)-R\left(p^{w}-\bar{p}^{w}\right)\right)^{2}=\frac{1}{2}\sum\left(\hat{p}^{c}-R\hat{p}^{w}\right)^{2} +\] + +\end_inset + +Now, to minimize the above it suffices to maximize (see CVOnline) +\begin_inset Formula +\[ +\mathop{trace}\left(R^{T}C\right) +\] + +\end_inset + +where +\begin_inset Formula $C=\sum\hat{p}^{c}\left(\hat{p}^{w}\right)^{T}$ +\end_inset + + is the correlation matrix. + Intuitively, the cloud of points is rotated to align with the principal + axes. + This can be achieved by SVD decomposition on +\begin_inset Formula $C$ +\end_inset + + +\begin_inset Formula +\[ +C=USV^{T} +\] + +\end_inset + +and setting +\begin_inset Formula +\[ +R=UV^{T} +\] + +\end_inset + +Clearly, from +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:t" + +\end_inset + + we then also recover the optimal +\begin_inset Formula $t$ +\end_inset + + as +\begin_inset Formula +\[ +t=\bar{p}^{w}-R^{T}\bar{p}^{c} +\] + +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix +\end_layout + +\begin_layout Subsection* +Differentiation Rules +\end_layout + +\begin_layout Standard +Spivak +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + also notes some multivariate derivative rules defined component-wise, but + they are not that useful in practice: +\end_layout + +\begin_layout Itemize +Since +\begin_inset Formula $f:\Multi nm$ +\end_inset + + is defined in terms of +\begin_inset Formula $m$ +\end_inset + + component functions +\begin_inset Formula $f^{i}$ +\end_inset + +, then +\begin_inset Formula $f$ +\end_inset + + is differentiable at +\begin_inset Formula $a$ +\end_inset + + iff each +\begin_inset Formula $f^{i}$ +\end_inset + + is, and the Jacobian matrix +\begin_inset Formula $F_{a}$ +\end_inset + + is the +\begin_inset Formula $m\times n$ +\end_inset + + matrix whose +\begin_inset Formula $i^{th}$ +\end_inset + + row is +\begin_inset Formula $\left(f^{i}\right)'(a)$ +\end_inset + +: +\begin_inset Formula +\[ +F_{a}\define f'(a)=\left[\begin{array}{c} +\left(f^{1}\right)'(a)\\ +\vdots\\ +\left(f^{m}\right)'(a) +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Itemize +Scalar differentiation rules: if +\begin_inset Formula $f,g:\OneD n$ +\end_inset + + are differentiable at +\begin_inset Formula $a$ +\end_inset + +, then +\begin_inset Formula +\[ +(f+g)'(a)=F_{a}+G_{a} +\] + +\end_inset + + +\begin_inset Formula +\[ +(f\cdot g)'(a)=g(a)F_{a}+f(a)G_{a} +\] + +\end_inset + + +\begin_inset Formula +\[ +(f/g)'(a)=\frac{1}{g(a)^{2}}\left[g(a)F_{a}-f(a)G_{a}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection* +Tangent Spaces and the Tangent Bundle +\end_layout + +\begin_layout Standard +The following is adapted from Appendix A in +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + +. +\end_layout + +\begin_layout Standard +The +\series bold +tangent space +\series default + +\begin_inset Formula $T_{p}M$ +\end_inset + + of a manifold +\begin_inset Formula $M$ +\end_inset + + at a point +\begin_inset Formula $p\in M$ +\end_inset + + is the vector space of +\series bold +tangent vectors +\series default + at +\begin_inset Formula $p$ +\end_inset + +. + The +\series bold +tangent bundle +\series default + +\begin_inset Formula $TM$ +\end_inset + + is the set of all tangent vectors +\begin_inset Formula +\[ +TM\define\bigcup_{p\in M}T_{p}M +\] + +\end_inset + +A +\series bold +vector field +\series default + +\begin_inset Formula $X:M\rightarrow TM$ +\end_inset + + assigns a single tangent vector +\begin_inset Formula $x\in T_{p}M$ +\end_inset + + to each point +\begin_inset Formula $p$ +\end_inset + +. +\end_layout + +\begin_layout Standard +If +\begin_inset Formula $F:M\rightarrow N$ +\end_inset + + is a smooth map from a manifold +\begin_inset Formula $M$ +\end_inset + + to a manifold +\begin_inset Formula $N$ +\end_inset + +, then we can define the +\series bold + tangent map +\series default + of +\begin_inset Formula $F$ +\end_inset + + at +\begin_inset Formula $p$ +\end_inset + + as the linear map +\begin_inset Formula $F_{*p}:T_{p}M\rightarrow T_{F(p)}N$ +\end_inset + + that maps tangent vectors in +\begin_inset Formula $T_{p}M$ +\end_inset + + at +\begin_inset Formula $p$ +\end_inset + + to tangent vectors in +\begin_inset Formula $T_{F(p)}N$ +\end_inset + + at the image +\begin_inset Formula $F(p)$ +\end_inset + +. +\end_layout + +\begin_layout Subsection* +Homomorphisms +\end_layout + +\begin_layout Standard +The following +\emph on +might be +\emph default + relevant +\begin_inset CommandInset citation +LatexCommand cite +after "page 45" +key "Hall00book" + +\end_inset + +: suppose that +\begin_inset Formula $\Phi:G\rightarrow H$ +\end_inset + + is a mapping (Lie group homomorphism). + Then there exists a unique linear map +\begin_inset Formula $\phi:\gg\rightarrow\mathfrak{h}$ +\end_inset + + +\begin_inset Formula +\[ +\phi(\xhat)\define\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(e^{t\xhat}\right) +\] + +\end_inset + +such that +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\Phi\left(e^{\xhat}\right)=e^{\phi\left(\xhat\right)}$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\phi\left(T\xhat T^{-1}\right)=\Phi(T)\phi(\xhat)\Phi(T^{-1})$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\phi\left([\xhat,\yhat]\right)=\left[\phi(\xhat),\phi(\yhat)\right]$ +\end_inset + + +\end_layout + +\begin_layout Standard +In other words, the map +\begin_inset Formula $\phi$ +\end_inset + + is the derivative of +\begin_inset Formula $\Phi$ +\end_inset + + at the identity. + As an example, suppose +\begin_inset Formula $\Phi(g)=g^{-1}$ +\end_inset + +, then the corresponding derivative +\emph on +at the identity +\emph default +is +\begin_inset Formula +\[ +\phi(\xhat)\define\lim_{t\rightarrow0}\frac{d}{dt}\left(e^{t\xhat}\right)^{-1}=\lim_{t\rightarrow0}\frac{d}{dt}e^{-t\xhat}=-\xhat\lim_{t\rightarrow0}e^{-t\xhat}=-\xhat +\] + +\end_inset + +In general it suffices to compute +\begin_inset Formula $\phi$ +\end_inset + + for a basis of +\begin_inset Formula $\gg$ +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Undercooked: What if we want the derivative of +\begin_inset Formula $\Phi$ +\end_inset + + at some other element +\begin_inset Formula $g$ +\end_inset + +? In other words, if we apply +\begin_inset Formula $\Phi$ +\end_inset + + at +\begin_inset Formula $g$ +\end_inset + + incremented by some Lie algebra element +\begin_inset Formula $e^{\xhat}$ +\end_inset + +, then we are looking for a +\begin_inset Formula $\yhat\in\gg$ +\end_inset + + will yield the same result: +\begin_inset Formula +\[ +\Phi\left(g\right)\lim_{t\rightarrow0}\frac{d}{dt}e^{t\yhat}=\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(ge^{t\xhat}\right) +\] + +\end_inset + + +\begin_inset Formula +\[ +\lim_{t\rightarrow0}\frac{d}{dt}e^{t\yhat}=\Phi\left(g\right)^{-1}\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(ge^{t\xhat}\right) +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Let us define two mappings +\begin_inset Formula +\[ +\Phi_{1}(A)=AB\mbox{ and }\Phi_{2}(B)=AB +\] + +\end_inset + +Then +\begin_inset Formula +\[ +\phi_{1}(\xhat)=\lim_{t\rightarrow0}\frac{d}{dt}\Phi_{1}\left(e^{t\xhat}B\right)= +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset CommandInset bibtex +LatexCommand bibtex +bibfiles "/Users/dellaert/papers/refs" +options "plain" + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/math.pdf b/doc/math.pdf new file mode 100644 index 000000000..ee50857ce Binary files /dev/null and b/doc/math.pdf differ diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 55f2db60b..9f799d294 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,4 +1,6 @@ -add_custom_target(examples) +if(NOT MSVC) + add_custom_target(examples) +endif() # Build example executables FILE(GLOB example_srcs "*.cpp") @@ -6,10 +8,25 @@ foreach(example_src ${example_srcs} ) get_filename_component(example_base ${example_src} NAME_WE) set( example_bin ${example_base} ) message(STATUS "Adding Example ${example_bin}") - add_dependencies(examples ${example_bin}) + if(NOT MSVC) + add_dependencies(examples ${example_bin}) + endif() add_executable(${example_bin} ${example_src}) + + # Disable building during make all/install + if (GTSAM_DISABLE_EXAMPLES_ON_INSTALL) + set_target_properties(${example_bin} PROPERTIES EXCLUDE_FROM_ALL ON) + endif() + target_link_libraries(${example_bin} gtsam-static) - add_custom_target(${example_bin}.run ${EXECUTABLE_OUTPUT_PATH}${example_bin} ${ARGN}) + if(NOT MSVC) + add_custom_target(${example_bin}.run ${EXECUTABLE_OUTPUT_PATH}${example_bin} ${ARGN}) + endif() + + # Set up Visual Studio folder + if(MSVC) + set_property(TARGET ${example_bin} PROPERTY FOLDER "Examples") + endif() + endforeach(example_src) -add_subdirectory(vSLAMexample) diff --git a/examples/CameraResectioning.cpp b/examples/CameraResectioning.cpp index 7d0e37e7f..4133d1e1e 100644 --- a/examples/CameraResectioning.cpp +++ b/examples/CameraResectioning.cpp @@ -17,86 +17,82 @@ */ #include -#include -#include -#include -#include -#include #include +#include +#include using namespace gtsam; +using namespace gtsam::noiseModel; +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) { + } - 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(pose, *K_); + 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 = Diagonal::Sigmas(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/Balbianello/BalbianelloMedium-1.jpg b/examples/Data/Balbianello/BalbianelloMedium-1.jpg new file mode 100644 index 000000000..0e75c8725 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-1.jpg differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-1.key.gz b/examples/Data/Balbianello/BalbianelloMedium-1.key.gz new file mode 100644 index 000000000..fdbdc4188 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-1.key.gz differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-2.jpg b/examples/Data/Balbianello/BalbianelloMedium-2.jpg new file mode 100644 index 000000000..5e51ee16e Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-2.jpg differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-2.key.gz b/examples/Data/Balbianello/BalbianelloMedium-2.key.gz new file mode 100644 index 000000000..46889971f Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-2.key.gz differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-3.jpg b/examples/Data/Balbianello/BalbianelloMedium-3.jpg new file mode 100644 index 000000000..641d3e286 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-3.jpg differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-3.key.gz b/examples/Data/Balbianello/BalbianelloMedium-3.key.gz new file mode 100644 index 000000000..89a831c3b Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-3.key.gz differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-4.jpg b/examples/Data/Balbianello/BalbianelloMedium-4.jpg new file mode 100644 index 000000000..259929b65 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-4.jpg differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-4.key.gz b/examples/Data/Balbianello/BalbianelloMedium-4.key.gz new file mode 100644 index 000000000..efc9cf008 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-4.key.gz differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-5.jpg b/examples/Data/Balbianello/BalbianelloMedium-5.jpg new file mode 100644 index 000000000..4f4dd16c8 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-5.jpg differ diff --git a/examples/Data/Balbianello/BalbianelloMedium-5.key.gz b/examples/Data/Balbianello/BalbianelloMedium-5.key.gz new file mode 100644 index 000000000..f299c5cb4 Binary files /dev/null and b/examples/Data/Balbianello/BalbianelloMedium-5.key.gz differ diff --git a/examples/Data/VO_calibration.txt b/examples/Data/VO_calibration.txt new file mode 100644 index 000000000..138eb3646 --- /dev/null +++ b/examples/Data/VO_calibration.txt @@ -0,0 +1 @@ +721.5377 721.5377 0.0 609.5593 172.854 0.537150588 \ No newline at end of file diff --git a/examples/Data/VO_camera_poses_large.txt b/examples/Data/VO_camera_poses_large.txt new file mode 100644 index 000000000..879d091b6 --- /dev/null +++ b/examples/Data/VO_camera_poses_large.txt @@ -0,0 +1,26 @@ +1 1 0 0 0 0 1 0 0 -0 0 1 0 0 0 0 1 +2 0.999997 -0.00240146 0.00061075 0.00314304 0.0024019 0.999997 -0.00071977 0.00414596 -0.00060902 0.000721235 1 0.95998 0 0 0 1 +3 0.999993 -0.00371801 0.000595621 0.00280572 0.00371612 0.999988 0.00314729 0.00981461 -0.000607315 -0.00314506 0.999995 1.91967 0 0 0 1 +4 0.999981 -0.00619252 -0.000161076 0.00419847 0.00619374 0.999939 0.00918605 0.0120306 0.000104181 -0.00918687 0.999958 2.87292 0 0 0 1 +5 0.999948 -0.0100179 -0.00177824 0.00741887 0.010034 0.999907 0.00925915 0.0175144 0.00168532 -0.00927651 0.999956 3.8158 0 0 0 1 +6 0.999913 -0.0128105 -0.00298253 0.00649213 0.0128298 0.999896 0.00655406 0.0221085 0.00289826 -0.00659176 0.999974 4.75923 0 0 0 1 +7 0.999901 -0.0135442 -0.00393541 0.00202365 0.0135567 0.999903 0.00315259 0.0274932 0.00389233 -0.00320563 0.999987 5.69454 0 0 0 1 +8 0.999901 -0.0131232 -0.00504356 -0.00337588 0.0131365 0.99991 0.00261558 0.0312754 0.00500879 -0.00268157 0.999984 6.62905 0 0 0 1 +9 0.999898 -0.0127525 -0.00649016 -0.00834529 0.0127815 0.999908 0.00443934 0.0363095 0.00643296 -0.00452184 0.999969 7.56509 0 0 0 1 +10 0.999891 -0.0126057 -0.0076649 -0.0140367 0.012663 0.999892 0.00747804 0.0406566 0.00756981 -0.00757428 0.999943 8.50119 0 0 0 1 +11 0.99988 -0.012916 -0.00853732 -0.0314704 0.0129905 0.999878 0.00872879 0.0502508 0.00842353 -0.00883865 0.999925 9.44031 0 0 0 1 +12 0.999851 -0.0144077 -0.00947329 -0.0383227 0.0144958 0.999852 0.00930193 0.0627772 0.00933787 -0.00943787 0.999912 10.3736 0 0 0 1 +13 0.999838 -0.0146038 -0.0105024 -0.0473225 0.0147016 0.999849 0.00930217 0.0696137 0.010365 -0.00945507 0.999902 11.2945 0 0 0 1 +14 0.999827 -0.0148804 -0.0111878 -0.0611688 0.0149688 0.999857 0.00785918 0.0760175 0.0110692 -0.00802528 0.999907 12.2087 0 0 0 1 +15 0.999804 -0.015194 -0.0126986 -0.0750261 0.0152691 0.999866 0.0058357 0.0827557 0.0126082 -0.00602846 0.999902 13.1154 0 0 0 1 +16 0.999759 -0.0166787 -0.0142956 -0.0893963 0.0167446 0.99985 0.00450347 0.0886196 0.0142183 -0.00474176 0.999888 14.0218 0 0 0 1 +17 0.999738 -0.0164046 -0.0159548 -0.110797 0.0164665 0.999857 0.00375294 0.0939735 0.0158909 -0.00401468 0.999866 14.9288 0 0 0 1 +18 0.999731 -0.0152362 -0.0175058 -0.134602 0.0152899 0.999879 0.00293826 0.0949048 0.0174589 -0.00320513 0.999842 15.8347 0 0 0 1 +19 0.999721 -0.013717 -0.0192196 -0.158411 0.0137759 0.999901 0.00293494 0.0977547 0.0191774 -0.00319889 0.999811 16.7344 0 0 0 1 +20 0.999683 -0.0142193 -0.0207555 -0.182009 0.0142987 0.999891 0.00368405 0.101695 0.0207008 -0.00397966 0.999778 17.6352 0 0 0 1 +21 0.999659 -0.0137778 -0.0221853 -0.207494 0.01389 0.999891 0.00491306 0.105966 0.0221152 -0.00521954 0.999742 18.5239 0 0 0 1 +22 0.999637 -0.013439 -0.0233607 -0.237562 0.0135682 0.999893 0.0053802 0.112022 0.023286 -0.00569521 0.999713 19.408 0 0 0 1 +23 0.999585 -0.0146657 -0.0247774 -0.266515 0.0147976 0.999877 0.00515018 0.116865 0.0246988 -0.00551469 0.99968 20.2912 0 0 0 1 +24 0.999541 -0.0147341 -0.0264658 -0.293414 0.0148605 0.999879 0.00458559 0.12245 0.0263951 -0.00497678 0.999639 21.1689 0 0 0 1 +25 0.999508 -0.0146117 -0.0277547 -0.320586 0.0147561 0.999879 0.00500356 0.126076 0.0276782 -0.00541065 0.999602 22.0409 0 0 0 1 +26 0.999474 -0.0145772 -0.0289811 -0.347714 0.0147851 0.999866 0.00697181 0.131533 0.0288756 -0.00739663 0.999556 22.9037 0 0 0 1 diff --git a/examples/Data/VO_stereo_factors_large.txt b/examples/Data/VO_stereo_factors_large.txt new file mode 100644 index 000000000..a2451cf75 --- /dev/null +++ b/examples/Data/VO_stereo_factors_large.txt @@ -0,0 +1,8189 @@ +1 3 209.979 185.87 61.5418 -8.90263 -2.48003 16.0758 +2 3 183.871 158.526 58.5288 -9.02175 -2.42293 15.2918 +3 3 154.533 127.498 45.2523 -9.04073 -2.53526 14.3359 +1 7 402.088 390.052 9.90739 -9.25908 -7.27203 32.201 +2 7 394.391 382.151 5.65911 -9.4424 -7.33715 31.6638 +1 8 363.621 350.3 19.013 -9.91743 -6.20361 29.0959 +2 8 354.573 340.708 15.0627 -9.87834 -6.11295 27.9529 +1 11 328.245 314.688 36.8183 -11.1456 -5.38969 28.5871 +2 11 317.629 303.492 33.1041 -11.0929 -5.31025 27.4172 +1 13 354.416 341.486 73.4162 -10.5993 -4.13089 29.9745 +2 13 345.335 332.443 71.2318 -11.0089 -4.23409 30.0629 +1 14 368.212 355.083 79.6458 -9.87405 -3.81336 29.5197 +2 14 359.443 346.409 77.3278 -10.308 -3.9369 29.7366 +1 19 408.795 393 106.946 -6.82736 -2.24133 24.5372 +2 19 401.89 386.918 105.831 -7.45048 -2.40457 25.8863 +3 19 393.846 380.541 101.098 -8.70882 -2.89695 29.1301 +4 19 386.237 372.998 94.8054 -9.06118 -3.16678 29.276 +5 19 379.773 365.851 93.1127 -8.86588 -3.07667 27.8392 +6 19 372.598 357.905 93.1789 -8.66334 -2.91293 26.3795 +7 19 364.788 347.748 92.7894 -7.716 -2.5239 22.7453 +8 19 354.593 338.217 89.9263 -8.36348 -2.72022 23.6681 +1 22 301.371 288.22 123.147 -12.5881 -2.0303 29.4716 +2 22 290.134 277.334 122.566 -13.4053 -2.1104 30.2806 +3 22 279.457 266.441 118.448 -13.6226 -2.24522 29.7763 +1 24 286.858 267.821 24.4042 -9.10534 -4.18865 20.3589 +2 24 270.266 249.809 17.1811 -8.90883 -4.08751 18.9454 +1 25 309.828 295.159 40.0603 -10.9759 -4.86279 26.4221 +2 25 297.643 283.051 37.0473 -11.4821 -4.99925 26.5609 +3 25 284.476 269.313 30.9841 -11.5164 -5.0259 25.5613 +4 25 271.874 255.971 22.6085 -11.4056 -5.07468 24.3706 +5 25 259.223 243.056 18.2877 -11.6401 -5.13554 23.9734 +6 25 245.695 229.056 15.8812 -11.7463 -5.0674 23.2927 +1 26 363.837 351.125 88.2117 -10.3829 -3.57654 30.4884 +2 26 355.143 341.918 86.1881 -10.3332 -3.51996 29.3055 +1 27 370.625 357.942 91.0858 -10.1195 -3.46309 30.5589 +2 27 362.093 348.932 89.118 -10.0997 -3.41747 29.4477 +3 27 353.648 339.913 83.786 -10.0087 -3.48344 28.2193 +4 27 344.918 330.558 76.9125 -9.89867 -3.58861 26.9885 +1 31 363.348 350.145 50.9786 -10.0172 -4.95853 29.356 +2 31 354.105 340.884 47.9673 -10.3787 -5.07395 29.315 +3 31 345.08 331.083 40.9019 -10.1498 -5.06386 27.6901 +1 34 320.828 308.065 68.3594 -12.1511 -4.3976 30.3656 +2 34 309.484 299.53 65.6399 -16.1932 -5.78567 38.9369 +3 34 300.833 288.357 60.6176 -13.2921 -4.83229 31.0655 +1 35 381.449 368.573 103.554 -9.51642 -2.8911 30.1014 +2 35 373.428 360.047 102.291 -9.47902 -2.83262 28.9646 +3 35 364.836 351.587 97.66 -9.92143 -3.04847 29.2522 +1 36 412.916 399.447 45.4646 -7.8421 -5.08028 28.7748 +2 36 405.446 391.636 42.1742 -7.93906 -5.08285 28.0645 +3 36 397.898 383.772 34.6847 -8.04846 -5.25392 27.4366 +4 36 390.21 375.548 25.8328 -8.03628 -5.3864 26.4349 +1 37 382.101 369.058 62.9139 -9.36758 -4.52773 29.7155 +2 37 373.575 360.402 60.3917 -9.62259 -4.58581 29.4217 +3 37 365.323 351.075 53.9171 -9.20802 -4.48407 27.2029 +4 37 356.369 341.205 45.643 -8.9685 -4.50607 25.5583 +5 37 347.182 331.951 41.7721 -9.2533 -4.62288 25.4465 +6 37 337.847 321.154 39.2487 -8.74323 -4.29919 23.2179 +1 38 368.271 355.646 103.567 -10.2656 -2.94784 30.6979 +2 38 359.673 346.474 102.328 -10.1689 -2.87003 29.3625 +3 38 351.187 337.872 97.0015 -10.4237 -3.06016 29.1094 +4 38 342.757 328.886 90.5172 -10.3321 -3.18854 27.942 +5 38 334.312 320.334 88.4566 -10.5774 -3.2433 27.7279 +6 38 325.334 311.295 87.9228 -10.8748 -3.24956 27.6068 +7 38 316.262 301.112 87.151 -10.3992 -3.03871 25.583 +8 38 306.084 290.382 83.6732 -10.3816 -3.0508 24.6832 +9 38 295.124 279.798 77.689 -11.0205 -3.33539 25.2888 +1 39 368.271 355.646 103.567 -10.2656 -2.94784 30.6979 +2 39 359.673 346.474 102.328 -10.1689 -2.87003 29.3625 +3 39 351.187 337.872 97.0015 -10.4237 -3.06016 29.1094 +4 39 342.757 328.886 90.5172 -10.3321 -3.18854 27.942 +5 39 334.312 320.334 88.4566 -10.5774 -3.2433 27.7279 +1 40 399.549 387.359 100.33 -9.25423 -3.19583 31.7949 +2 40 392.339 379.894 99.3608 -9.3758 -3.17216 31.1435 +3 40 385.548 371.692 93.9091 -8.68421 -3.06044 27.9717 +4 40 377.86 361.977 88.3166 -7.83547 -2.85884 24.4006 +5 40 369.704 353.079 86.7024 -7.7496 -2.78352 23.3125 +6 40 360.838 344.13 87.6479 -7.99653 -2.73942 23.1978 +1 41 314.778 303.477 61.5898 -14.0112 -5.28847 34.2952 +2 41 305.745 293.424 58.7429 -13.2453 -4.97487 31.4567 +3 41 295.126 280.156 52.0137 -11.2824 -4.33594 25.8899 +1 42 322.734 309.225 27.9559 -11.4054 -5.76176 28.6914 +2 42 311.74 297.908 23.4169 -11.5653 -5.80315 28.0198 +1 43 413.858 400.794 69.7088 -8.04664 -4.24101 29.6674 +2 43 406.585 392.833 66.8017 -7.92805 -4.14233 28.1828 +3 43 399.186 384.6 60.1878 -7.74727 -4.14907 26.5715 +4 43 391.12 376.876 52.5636 -8.23759 -4.53629 27.21 +5 43 383.947 369.869 49.2025 -8.60844 -4.71803 27.5309 +6 43 376.647 362.427 47.1554 -8.79808 -4.74816 27.2555 +7 43 369.289 354.616 44.9048 -8.79618 -4.68415 26.4151 +1 44 429.786 416.985 10.8113 -7.54372 -6.79969 30.2774 +2 44 422.927 409.032 6.22854 -7.21468 -6.44127 27.8926 +1 45 429.786 416.985 10.8113 -7.54372 -6.79969 30.2774 +2 45 422.927 409.032 6.22854 -7.21468 -6.44127 27.8926 +1 47 476.875 462.803 22.9268 -5.06458 -5.72276 27.5413 +2 47 471.267 456.98 18.7569 -5.19929 -5.79349 27.1272 +1 49 534.551 521.959 30.0889 -3.19959 -6.08989 30.7784 +2 49 531.222 518.03 26.2453 -3.18982 -5.96976 29.3803 +1 51 438.047 425.403 38.834 -7.28628 -5.69352 30.6528 +2 51 431.401 418.237 35.3691 -7.2697 -5.61002 29.4421 +1 52 536.646 523.91 44.453 -3.07516 -5.41537 30.4312 +2 52 533.182 520.347 41.0937 -3.1965 -5.51432 30.1972 +1 56 433.895 420.782 74.4585 -7.19587 -4.03064 29.5568 +2 56 427.255 413.599 72.1036 -7.17079 -3.96294 28.3811 +3 56 420.734 406.674 65.7893 -7.21386 -4.09028 27.5655 +4 56 413.867 399.322 57.9083 -7.2269 -4.24494 26.6464 +1 59 427.689 414.944 90.0841 -7.66535 -3.48853 30.4109 +2 59 421.003 407.495 88.2374 -7.49811 -3.36485 28.6925 +3 59 414.164 400.243 82.4393 -7.5395 -3.48873 27.8411 +1 61 476.203 463.728 119.273 -5.74205 -2.3071 31.068 +2 61 471.246 458.29 118.352 -5.73435 -2.2596 29.9143 +3 61 466.603 453.213 113.763 -5.73513 -2.3706 28.9466 +4 61 461.992 448.016 107.789 -5.6716 -2.5007 27.7315 +1 62 549.824 538.317 13.0527 -2.7883 -7.45917 33.6798 +2 62 547.191 535.348 8.33458 -2.8288 -7.46196 32.7262 +1 63 494.158 482.317 49.1257 -5.23515 -5.6129 32.7324 +2 63 490.361 477.694 46.2753 -5.05459 -5.36754 30.5967 +3 63 486.219 472.742 39.6488 -4.91601 -5.30919 28.7585 +4 63 482.93 468.924 31.7027 -4.8562 -5.41312 27.6708 +1 65 555.494 543.327 74.0345 -2.38699 -4.36286 31.8557 +2 65 552.415 540.886 71.3792 -2.66241 -4.72779 33.617 +3 65 550.653 538.6 65.114 -2.6252 -4.80152 32.1559 +1 66 456.271 443.352 85.912 -6.37377 -3.61506 30.0017 +2 66 450.683 437.004 83.9661 -6.239 -3.49059 28.3344 +1 67 480.016 466.663 91.5877 -5.21084 -3.26892 29.0237 +2 67 474.718 461.005 89.4507 -5.2816 -3.26684 28.262 +3 67 469.735 455.72 83.7122 -5.35873 -3.41635 27.6528 +1 68 495.411 483.037 98.2553 -4.95513 -3.2383 31.3217 +2 68 490.935 478.057 96.7302 -4.94811 -3.1753 30.097 +1 69 444.061 431.758 124.931 -7.22597 -2.09239 31.5037 +2 69 437.98 425.397 124.035 -7.32459 -2.08407 30.8019 +3 69 432.417 419.076 119.726 -7.1323 -2.13909 29.0514 +4 69 426.738 412.661 114.091 -6.97622 -2.24233 27.5329 +5 69 421.113 406.568 112.795 -6.95966 -2.2181 26.6477 +6 69 414.964 399.796 113.254 -6.89092 -2.11055 25.5508 +7 69 408.313 392.652 113.573 -6.90237 -2.03324 24.7474 +1 74 477.818 464.863 47.7721 -5.46253 -5.18639 29.9178 +2 74 472.705 459.099 44.6283 -5.40304 -5.06238 28.4865 +1 75 477.818 464.863 47.7721 -5.46253 -5.18639 29.9178 +2 75 472.705 459.099 44.6283 -5.40304 -5.06238 28.4865 +1 76 422.265 408.875 55.2521 -7.51344 -4.71768 28.945 +2 76 415.112 401.023 52.1342 -7.41364 -4.60265 27.5099 +3 76 408.035 393.207 45.1294 -7.30047 -4.62698 26.1386 +4 76 400.304 385.596 36.6259 -7.64224 -4.9752 26.3514 +1 79 451.106 438.208 77.5776 -6.59924 -3.96805 30.0504 +2 79 445.036 431.574 75.2566 -6.56457 -3.89418 28.7897 +1 80 461.33 448.183 77.9245 -6.05615 -3.8785 29.4796 +2 80 455.329 441.776 75.6553 -6.11249 -3.85221 28.5962 +3 80 449.704 435.837 69.5686 -6.19193 -4.00072 27.9485 +4 80 443.847 429.056 61.6947 -6.01783 -4.03675 26.2026 +5 80 438.513 423.674 58.3238 -6.1917 -4.14587 26.1189 +6 80 432.69 417.137 56.6184 -6.10855 -4.01443 24.9198 +7 80 426.329 410.32 54.916 -6.1478 -3.9571 24.2093 +8 80 419.855 403.607 50.4711 -6.27153 -4.04591 23.8536 +1 83 524.861 512.387 99.0037 -3.64712 -3.18001 31.0695 +2 83 521.387 508.737 97.3619 -3.74378 -3.2054 30.6365 +3 83 518.54 505.038 91.9327 -3.62084 -3.21914 28.7036 +1 86 451.632 438.453 41.5387 -6.43651 -5.35192 29.4072 +2 86 445.619 432.262 37.972 -6.59294 -5.42433 29.0169 +3 86 439.939 425.582 30.5923 -6.34627 -5.32265 26.996 +1 87 519.097 508.425 56.748 -4.55329 -5.84403 36.3176 +2 87 515.739 502.233 53.8001 -3.73134 -4.73491 28.6964 +3 87 512.106 497.923 47.0277 -3.69077 -4.76531 27.3262 +4 87 508.534 494.589 38.4066 -3.89132 -5.17871 27.7925 +5 87 505.435 491.51 34.0653 -4.0166 -5.35378 27.8333 +6 87 502.467 486.81 31.7197 -3.67409 -4.84199 24.7543 +1 88 534.071 522.238 63.8388 -3.42661 -4.94851 32.7527 +2 88 531.165 518.834 61.4406 -3.41475 -4.85304 31.4294 +1 89 534.071 522.238 63.8388 -3.42661 -4.94851 32.7527 +2 89 531.165 518.834 61.4406 -3.41475 -4.85304 31.4294 +1 92 435.312 422.269 78.4345 -7.1758 -3.88835 29.7142 +2 92 428.787 415.335 76.4018 -7.21856 -3.8515 28.8123 +3 92 422.68 408.458 70.1035 -7.05831 -3.88082 27.252 +1 93 450.491 437.056 88.6618 -6.35949 -3.36598 28.8469 +2 93 444.629 430.861 86.4587 -6.43476 -3.37071 28.1507 +3 93 438.781 424.649 80.6644 -6.49125 -3.50411 27.4255 +1 94 455.793 443.363 111.853 -6.64468 -2.63603 31.1797 +2 94 450 436.592 110.47 -6.39219 -2.4992 28.906 +3 94 444.45 431.11 105.548 -6.64812 -2.71008 29.0528 +4 94 439.122 425.417 99.4872 -6.68009 -2.87553 28.2799 +5 94 433.783 419.592 97.7756 -6.65366 -2.84194 27.3123 +1 96 516.839 504.605 114.884 -4.07104 -2.54525 31.6802 +2 96 513.501 500.595 113.958 -3.99767 -2.45111 30.0285 +1 97 545.632 534.021 117.895 -2.95751 -2.5426 33.3807 +2 97 543.43 531.117 117.068 -2.88466 -2.4335 31.4748 +1 98 455.088 441.992 55.321 -6.3357 -4.82066 29.5942 +2 98 448.718 435.522 52.1503 -6.54678 -4.91306 29.3691 +3 98 443.134 428.998 45.1421 -6.3241 -4.85301 27.4182 +4 98 437.065 422.379 36.5361 -6.30915 -4.98596 26.391 +5 98 431.182 415.996 32.1223 -6.30939 -4.97784 25.5216 +1 100 427.579 414.128 66.7824 -7.26719 -4.23585 28.8138 +2 100 420.199 406.208 64.0832 -7.26993 -4.17594 27.7013 +3 100 413.155 398.753 57.4381 -7.32551 -4.3048 26.912 +1 101 427.579 414.128 66.7824 -7.26719 -4.23585 28.8138 +2 101 420.199 406.208 64.0832 -7.26993 -4.17594 27.7013 +3 101 413.155 398.753 57.4381 -7.32551 -4.3048 26.912 +1 103 542.696 530.061 22.2283 -2.84256 -6.40353 30.6746 +2 103 539.496 526.632 18.0308 -2.92561 -6.46493 30.1291 +3 103 538.168 524.086 12.1824 -2.72324 -6.12886 27.5232 +1 104 535.956 523.649 89.7316 -3.21258 -3.62806 31.4931 +2 104 533.076 520.355 87.8891 -3.22957 -3.58772 30.4676 +3 104 530.458 517.095 82.3061 -3.17958 -3.6397 29.0032 +4 104 528.051 514.081 74.7953 -3.13395 -3.77029 27.7427 +1 105 535.956 523.649 89.7316 -3.21258 -3.62806 31.4931 +2 105 533.076 520.355 87.8891 -3.22957 -3.58772 30.4676 +3 105 530.458 517.095 82.3061 -3.17958 -3.6397 29.0032 +4 105 528.051 514.081 74.7953 -3.13395 -3.77029 27.7427 +5 105 526.05 511.39 72.3354 -3.05982 -3.68304 26.4374 +1 107 566.9 555.395 21.5232 -1.99174 -7.06559 33.6884 +2 107 564.716 552.833 17.392 -2.02712 -7.02754 32.6166 +1 112 658.214 646.669 88.116 2.26369 -3.9425 33.5701 +2 112 658.897 647.085 85.9733 2.24356 -3.95075 32.8107 +1 113 675.96 664.671 103.316 3.15958 -3.30888 34.3333 +2 113 677.522 665.531 101.535 3.04463 -3.195 32.324 +1 114 658.454 646.975 119.766 2.28803 -2.48428 33.7645 +2 114 659.332 647.379 118.527 2.23661 -2.44124 32.423 +3 114 660.767 648.4 113.81 2.22421 -2.56458 31.3399 +1 115 606.492 600.958 15.8831 -0.297771 -15.2365 70.0367 +2 115 605.534 599.882 14.2559 -0.382556 -15.0733 68.5755 +1 116 670.748 663.186 44.3523 4.34633 -9.12761 51.2516 +2 116 671.336 663.146 42.0262 4.05203 -8.58126 47.3271 +3 116 672.087 664.058 35.3488 4.18339 -9.1997 48.2741 +1 120 683.092 671.693 102.585 3.46491 -3.31111 33.9993 +2 120 684.634 672.737 100.791 3.38946 -3.25346 32.5757 +3 120 686.62 674.585 95.205 3.43928 -3.46554 32.2029 +1 123 661.897 656.37 19.4334 5.08714 -14.9123 70.1326 +2 123 661.865 656.089 16.9831 4.86425 -14.4954 67.1001 +3 123 662.228 656.907 12.0509 5.3169 -16.2332 72.8397 +1 125 559.802 547.566 36.2278 -2.18429 -5.9978 31.675 +2 125 557.384 544.657 32.6228 -2.20213 -5.9186 30.4532 +3 125 555.609 542.186 24.9967 -2.15891 -5.91676 28.8736 +1 128 617.818 606.749 109.389 0.400776 -3.07971 35.0133 +2 128 617.902 605.737 108.604 0.368359 -2.8369 31.8587 +1 129 653.913 642.678 111.773 2.1206 -2.92037 34.4978 +2 129 654.56 642.954 110.278 2.08274 -2.89618 33.3948 +3 129 655.858 643.64 105.386 2.03546 -2.96612 31.7211 +1 137 602.716 594.449 115.366 -0.444616 -3.73531 46.8819 +2 137 601.999 593.818 114.699 -0.496396 -3.81847 47.3762 +3 137 601.865 593.596 110.463 -0.499836 -4.05281 46.8702 +4 137 602.121 593.372 104.753 -0.456636 -4.18086 44.2967 +5 137 602.843 594.424 103.369 -0.428459 -4.43296 46.0323 +6 137 603.467 594.713 103.946 -0.373832 -4.22829 44.2745 +7 137 603.853 595.565 105.065 -0.369797 -4.39337 46.7625 +8 137 604.348 596.35 104.046 -0.349984 -4.62099 48.4572 +9 137 604.468 597.4 101.689 -0.386891 -5.40807 54.8323 +10 137 604.594 597.884 98.157 -0.397409 -5.97905 57.7547 +11 137 605.128 597.873 95.5003 -0.328109 -5.72721 53.4221 +12 137 605.24 597.958 93.2712 -0.318643 -5.87072 53.2269 +13 137 605.91 597.8 91.4634 -0.241676 -5.39044 47.7869 +14 137 606.321 597.561 90.6788 -0.198521 -5.0384 44.2396 +15 137 607.307 597.928 90.2342 -0.129002 -4.73185 41.3243 +16 137 608.425 598.542 89.0036 -0.0616454 -4.55718 39.2148 +17 137 609.738 598.96 87.3804 0.00892867 -4.25958 35.9579 +18 137 610.907 599.775 85.9568 0.065012 -4.19324 34.8179 +1 138 822.785 817.07 56.4723 20.0396 -10.9379 67.8124 +2 138 825.065 819.162 54.809 19.6106 -10.7418 65.6584 +3 138 828.256 822.273 49.8178 19.6342 -11.046 64.7783 +4 138 832.16 825.974 42.8032 19.3275 -11.2918 62.6482 +5 138 836.094 829.929 39.856 19.7394 -11.589 62.8721 +1 142 823.365 817.614 40.2749 19.9696 -12.383 67.3921 +2 142 825.659 819.737 38.3195 19.6034 -12.2042 65.454 +3 142 828.962 822.701 32.8848 18.8242 -12.009 61.9061 +4 142 832.943 826.714 25.6717 19.2645 -12.693 62.2252 +5 142 837.133 830.349 22.3407 18.0184 -11.9171 57.1286 +6 142 840.876 834.064 21.6241 18.24 -11.9249 56.8952 +1 144 815.798 810.929 59.8465 22.7486 -12.465 79.5871 +2 144 817.787 812.929 58.1828 23.0257 -12.6803 79.7871 +3 144 821.963 815.798 53.8181 18.5089 -10.3729 62.8752 +1 145 815.798 810.929 59.8465 22.7486 -12.465 79.5871 +2 145 817.787 812.929 58.1828 23.0257 -12.6803 79.7871 +1 146 777.011 765.364 70.4036 7.72293 -4.72504 33.2775 +2 146 781.246 769.121 67.4527 7.60553 -4.66916 31.9633 +3 146 786.571 774.015 60.9102 7.57279 -4.78911 30.8683 +1 148 764.595 753.222 100.942 7.32281 -3.39666 34.0805 +2 148 768.801 756.5 98.7651 6.95374 -3.2353 31.508 +1 151 769.692 758.18 119.424 7.47199 -2.4931 33.6678 +2 151 774.14 761.647 117.907 7.07619 -2.36246 31.0226 +1 152 769.692 758.18 119.424 7.47199 -2.4931 33.6678 +2 152 774.14 761.647 117.907 7.07619 -2.36246 31.0226 +1 153 769.692 758.18 119.424 7.47199 -2.4931 33.6678 +2 153 774.14 761.647 117.907 7.07619 -2.36246 31.0226 +3 153 779.344 766.681 112.851 7.2019 -2.54521 30.606 +4 153 785.385 772.087 106.408 7.10183 -2.68385 29.1438 +1 155 829.479 823.269 46.3632 19.0214 -10.9405 62.4074 +2 155 832.007 825.885 44.4532 19.5195 -11.267 63.314 +1 158 819.357 810.23 71.9845 12.3472 -5.93645 42.4645 +2 158 824.128 814.918 69.5689 12.5149 -6.02419 42.0843 +3 158 830.206 820.885 63.3726 12.7145 -6.30875 41.5779 +1 159 788.924 777.307 74.6425 8.29323 -4.54096 33.3615 +2 159 793.683 781.418 71.6578 8.0637 -4.43188 31.5997 +3 159 799.1 786.642 65.4656 8.17271 -4.63044 31.1117 +1 160 700.033 688.956 119.498 4.38707 -2.58723 34.9873 +2 160 702.16 690.617 117.977 4.30911 -2.55363 33.5761 +3 160 704.427 692.419 114.085 4.2437 -2.62889 32.2765 +4 160 707.853 695.704 106.898 4.34587 -2.9161 31.9013 +5 160 711.594 699.221 103.299 4.42958 -3.01954 31.3238 +1 170 863.862 853.773 32.7773 13.5388 -7.45754 38.414 +2 170 869.634 859.099 29.2066 13.2603 -7.32407 36.7887 +3 170 876.662 865.763 21.815 13.1645 -7.44417 35.562 +4 170 884.614 873.711 12.4026 13.5511 -7.90493 35.5478 +1 171 863.862 853.773 32.7773 13.5388 -7.45754 38.414 +2 171 869.634 859.099 29.2066 13.2603 -7.32407 36.7887 +3 171 876.662 865.763 21.815 13.1645 -7.44417 35.562 +1 179 1082.33 1035.83 56.9512 5.46202 -1.33906 8.33616 +2 179 1143.34 1090.25 40.9695 5.3999 -1.33418 7.29928 +3 179 1223.79 1163.7 16.1894 5.49146 -1.40065 6.45087 +1 180 1057.33 1012.89 113.1 5.41204 -0.722226 8.72091 +2 180 1112.37 1062.54 104.89 5.41996 -0.732605 7.77771 +1 186 1032 985.776 48.4555 4.90898 -1.44557 8.38463 +2 186 1085.42 1033.06 31.4657 4.88201 -1.45056 7.40254 +1 187 1051.8 1005.3 52.7114 5.10833 -1.38778 8.33454 +2 187 1108.05 1055.56 36.3784 5.10147 -1.39666 7.38407 +1 188 1034.71 988.427 55.8301 4.93464 -1.35829 8.37485 +2 188 1088.88 1036.23 39.7023 4.88985 -1.35836 7.36084 +3 188 1160.46 1100.97 15.2843 4.97444 -1.42279 6.51521 +1 190 1085.46 1039.22 62.8393 5.52829 -1.27798 8.38169 +2 190 1146.8 1094.21 47.6122 5.48765 -1.27929 7.3702 +3 190 1228.58 1168.42 24.1453 5.52629 -1.32759 6.44148 +1 200 988.3 953.944 70.9989 5.92163 -1.59251 11.2813 +2 200 1023.27 984.786 60.7993 5.77461 -1.56408 10.0713 +1 215 1121.65 1072.48 96.7775 5.59467 -0.83115 7.88293 +2 215 1190.71 1135.86 85.0304 5.69168 -0.860135 7.06666 +1 216 1114.65 1067.01 105.103 5.69499 -0.763898 8.1354 +2 216 1182.5 1128.17 94.7334 5.66503 -0.772428 7.13431 +1 237 210.085 185.84 137.162 -8.85046 -0.790769 15.9858 +2 237 183.701 157.797 136.103 -8.83093 -0.762093 14.9624 +3 237 154.206 126.701 131.097 -8.89254 -0.815468 14.0908 +4 237 120.892 91.407 124.845 -8.90252 -0.874626 13.1449 +5 237 83.6969 52.3843 122.984 -9.02091 -0.855497 12.3776 +6 237 40.457 6.88333 122.431 -9.10517 -0.806727 11.544 +1 240 233.309 211.384 152.123 -9.21776 -0.507897 17.677 +2 240 210.927 187.364 152.182 -9.08737 -0.471248 16.4484 +1 241 247.363 226.057 154.126 -9.13145 -0.472163 18.1909 +2 241 226.5 204.026 154.334 -9.15527 -0.442627 17.245 +3 241 203.845 180.072 150.647 -9.16719 -0.50176 16.3033 +4 241 178.941 153.663 146.228 -9.15062 -0.565794 15.3326 +5 241 151.895 125.153 146.121 -9.19282 -0.536973 14.4931 +6 241 121.048 92.3682 147.761 -9.14939 -0.469974 13.5138 +7 241 85.7016 55.22 149.113 -9.23148 -0.418372 12.715 +8 241 44.8783 12.1284 147.369 -9.26166 -0.417996 11.8344 +1 242 169.398 130.429 172.472 -6.06716 -0.00526316 9.94565 +2 242 121.259 78.4461 174.148 -6.1265 0.0162394 9.05283 +3 242 62.9069 15.062 170.919 -6.13722 -0.0217269 8.10065 +1 244 198.722 159.782 183.988 -5.66712 0.153588 9.95296 +2 244 153.949 110.823 185.737 -5.67482 0.160468 8.98706 +3 244 99.5174 52.2933 184.678 -5.80147 0.134492 8.20713 +1 248 153.264 112.671 215.892 -6.03788 0.569499 9.54767 +2 248 101.213 54.7982 222.337 -5.88293 0.572656 8.35014 +1 250 250.408 229.298 143.187 -9.13888 -0.754889 18.3601 +2 250 229.829 207.584 142.855 -9.16905 -0.724368 17.4224 +3 250 207.652 183.818 138.455 -9.05798 -0.775256 16.2616 +4 250 182.912 157.583 133.247 -9.04803 -0.839961 15.3018 +5 250 156.152 129.646 132.288 -9.18832 -0.82207 14.622 +1 251 237.073 199.188 213.088 -5.2813 0.57046 10.2303 +2 251 197.788 154.774 218.598 -5.14202 0.571228 9.01026 +3 251 149.919 103.382 220.938 -5.30536 0.55501 8.32829 +1 257 149.933 109.493 183.2 -6.10513 0.137418 9.58405 +2 257 97.4448 52.1235 186.248 -6.06961 0.158748 8.55171 +1 259 213.322 173.629 209.6 -5.36207 0.497268 9.7642 +2 259 169.407 125.269 214.78 -5.35649 0.510221 8.78085 +3 259 115.44 65.2534 217.94 -5.28857 0.482561 7.72264 +1 261 178.996 139.801 198.259 -5.90075 0.34817 9.88848 +2 261 132.041 86.9993 201.993 -5.69471 0.347504 8.6048 +1 262 333.213 323.106 130.685 -14.6866 -2.24109 38.3467 +2 262 325.173 314.327 131.089 -14.084 -2.0684 35.7336 +1 267 369.828 364.654 174.805 -24.8885 0.202538 74.9088 +2 267 365.959 360.729 175.687 -25.0161 0.290933 74.0972 +3 267 362.774 357.494 173.18 -25.1037 0.0331967 73.397 +4 267 360.036 353.975 169.42 -22.1126 -0.304293 63.9424 +1 268 369.828 364.654 174.805 -24.8885 0.202538 74.9088 +2 268 365.959 360.729 175.687 -25.0161 0.290933 74.0972 +1 271 294.822 278.521 151.287 -10.3709 -0.710667 23.7754 +2 271 280.927 264.104 151.174 -10.4929 -0.692219 23.038 +1 272 410.988 398.967 155.075 -8.87279 -0.794414 32.2406 +2 272 404.17 391.695 155.345 -8.8438 -0.753917 31.0685 +3 272 397.602 384.572 152.265 -8.73752 -0.84875 29.7439 +4 272 391.037 377.367 147.684 -8.5869 -0.98908 28.353 +1 277 369.935 343.004 202.032 -4.77944 0.581967 14.3915 +2 277 352.309 325.113 205.285 -5.08097 0.64055 14.2511 +1 278 387.725 362.06 208.921 -4.64288 0.754866 15.1014 +2 278 372.185 344.818 212.205 -4.65911 0.772375 14.1621 +3 278 355.163 325.756 212.535 -4.64686 0.724826 13.1798 +4 278 336.134 304.545 211.981 -4.64945 0.665325 12.2694 +1 279 400.396 388.152 144.735 -9.17646 -1.23364 31.6554 +2 279 393.192 379.931 144.938 -8.76416 -1.13078 29.2265 +3 279 385.587 372.293 140.736 -9.04968 -1.29773 29.154 +4 279 378.352 365.226 135.65 -9.46123 -1.52241 29.526 +5 279 371.587 357.672 135.333 -9.1861 -1.44838 27.8525 +6 279 364.083 349.746 136.725 -9.19725 -1.35366 27.0338 +7 279 356.183 341.436 138.169 -9.22888 -1.26334 26.281 +1 283 414.424 402.048 140.439 -8.46959 -1.40694 31.3174 +2 283 407.504 394.489 140.311 -8.3393 -1.34314 29.7796 +1 286 499.484 487.406 139.935 -4.89543 -1.46405 32.0894 +2 286 495.346 482.82 139.606 -4.8976 -1.42573 30.9404 +3 286 491.777 478.785 135.778 -4.86991 -1.53295 29.8332 +4 286 488.221 474.689 130.363 -4.81667 -1.68671 28.6422 +5 286 484.855 471.162 129.375 -4.89186 -1.70558 28.3042 +6 286 481.486 466.958 130.254 -4.7353 -1.57505 26.6777 +1 289 531.473 526.051 196.881 -7.73553 2.3802 71.4786 +2 289 529.822 524.184 197.884 -7.59719 2.38483 68.7462 +3 289 528.636 522.904 195.553 -7.58422 2.12739 67.6232 +4 289 528.016 522.032 191.722 -7.31916 1.69352 64.7637 +5 289 527.787 521.889 192.151 -7.44745 1.75748 65.7141 +1 291 479.204 465.176 214.205 -4.99177 1.58349 27.6302 +2 291 473.956 459.294 216.308 -4.96799 1.59197 26.4344 +3 291 469.048 453.819 214.869 -4.95603 1.48195 25.4497 +4 291 464.399 448.024 212.3 -4.76159 1.29392 23.6681 +5 291 459.723 442.514 214.256 -4.67682 1.29229 22.5213 +6 291 454.337 436.307 218.306 -4.62439 1.3541 21.4961 +1 292 522.943 511.09 132.329 -3.92529 -1.8365 32.6986 +2 292 519.637 507.412 131.797 -3.95098 -1.80394 31.7026 +3 292 516.822 503.931 127.713 -3.86421 -1.88095 30.0652 +1 296 531.061 525.918 176.772 -8.199 0.40921 75.3631 +2 296 529.451 524.016 177.291 -7.91708 0.438507 71.3093 +3 296 528.319 522.921 174.764 -8.08394 0.190106 71.7979 +4 296 527.636 522.104 170.883 -7.95483 -0.191421 70.0622 +5 296 527.479 521.966 171.135 -7.99646 -0.16751 70.2941 +1 301 507.029 494.856 133.434 -4.52437 -1.73951 31.8394 +2 301 503.049 490.236 132.817 -4.46482 -1.67833 30.2464 +3 301 499.402 486.37 128.686 -4.54046 -1.82052 29.7402 +1 302 485.752 473.968 155.378 -5.64344 -0.796582 32.8894 +2 302 481.313 469.276 155.829 -5.7229 -0.759738 32.1982 +3 302 477.287 464.805 152.36 -5.69238 -0.881947 31.0516 +1 304 428.273 408.13 198.088 -4.83443 0.672934 19.2415 +2 304 418.082 396.722 199.886 -4.81535 0.679817 18.1455 +1 305 496.602 484.583 151.777 -5.04838 -0.942 32.2476 +2 305 492.598 480.12 151.98 -5.03486 -0.898551 31.0603 +1 307 490.529 484.539 188.439 -10.6737 1.39753 64.702 +2 307 488.889 482.129 189.605 -9.5883 1.33103 57.3324 +3 307 486.189 480.876 186.564 -12.4715 1.38594 72.9401 +1 308 551.405 545.697 143.957 -5.47186 -2.71896 67.8914 +2 308 550.025 544.086 144.076 -5.38513 -2.60304 65.2656 +1 309 551.405 545.697 143.957 -5.47186 -2.71896 67.8914 +2 309 550.025 544.086 144.076 -5.38513 -2.60304 65.2656 +1 310 520.101 510.811 150.347 -5.17255 -1.30135 41.72 +2 310 516.955 508.282 150.336 -5.73496 -1.39453 44.6848 +3 310 514.055 506.669 146.515 -6.94508 -1.91539 52.4704 +4 310 513.008 504.775 140.898 -6.29942 -2.08492 47.0764 +5 310 511.394 501.728 140.078 -5.455 -1.82134 40.0957 +6 310 510.664 500.781 140.578 -5.375 -1.75424 39.2159 +7 310 508.202 499.604 142.502 -6.33206 -1.89619 45.0764 +1 311 464.267 450.582 217.603 -5.70264 1.75636 28.32 +2 311 458.952 443.719 219.95 -5.31048 1.66063 25.4418 +3 311 453.448 437.263 218.975 -5.1809 1.53065 23.9459 +4 311 446.795 429.168 217.075 -4.95973 1.34751 21.9866 +5 311 441.779 423.308 219.517 -4.87939 1.35705 20.9837 +6 311 435.01 416.48 224.158 -5.05993 1.48724 20.9163 +7 311 427.524 409.158 229.184 -5.32418 1.64755 21.1035 +1 312 515.702 509.891 192.267 -8.67551 1.79441 66.6938 +2 312 514 507.993 193.153 -8.54553 1.81528 64.5245 +3 312 512.406 507.133 190.606 -9.8982 1.80859 73.5118 +4 312 511.563 506.823 186.65 -11.1061 1.56353 81.7732 +1 318 686.818 675.925 139.14 3.80978 -1.66252 35.5803 +2 318 688.609 677.34 138.442 3.76817 -1.64036 34.3947 +3 318 690.674 679.138 134.251 3.77688 -1.79745 33.5964 +4 318 693.662 681.709 128.707 3.77949 -1.98391 32.4252 +5 318 697.195 685.214 126.825 3.9289 -2.06358 32.348 +1 319 610.566 605.699 179.775 0.111087 0.763803 79.6311 +2 319 610.018 604.999 180.363 0.0491049 0.803582 77.2208 +3 319 610.026 604.926 177.531 0.0491093 0.492557 75.9944 +1 320 635.977 625.928 187.016 1.41209 0.75696 38.5672 +2 320 636.043 625.551 187.688 1.35581 0.759406 36.9387 +1 322 692.634 678.588 213.728 3.17692 1.56309 27.5928 +2 322 694.818 680.64 215.184 3.23022 1.60376 27.3372 +3 322 698.073 683.155 213.718 3.18692 1.47129 25.9787 +4 322 701.94 686.672 210.75 3.25005 1.33321 25.3843 +5 322 706.61 690.806 211.915 3.29853 1.32758 24.5233 +6 322 711.207 694.607 215.188 3.2892 1.36989 23.3481 +7 322 716.102 698.764 219.41 3.30073 1.44231 22.3534 +8 322 721.375 703.401 221.79 3.34156 1.46244 21.5628 +9 322 727.242 708.538 222.734 3.37958 1.43245 20.7209 +10 322 733.374 713.158 222.938 3.28994 1.33082 19.1724 +11 322 739.791 719.25 223.952 3.40557 1.33621 18.8682 +12 322 747.23 725.347 225.967 3.37927 1.30371 17.7109 +13 322 755.387 731.279 229.23 3.24915 1.2561 16.0764 +1 323 688.137 666.354 243.3 1.93767 1.73714 17.7926 +2 323 692.151 669.119 247.446 1.92619 1.73962 16.8275 +3 323 697.552 672.808 249.132 1.91021 1.65589 15.6637 +1 324 589.594 586.133 147.343 -3.09841 -3.95915 111.977 +2 324 588.715 585.09 147.561 -3.08888 -3.74822 106.924 +3 324 588.403 584.702 144.434 -3.07079 -4.12513 104.729 +1 327 665.129 654.299 168.14 2.75618 -0.233815 35.7875 +2 327 665.902 654.698 168.083 2.70112 -0.228723 34.5912 +3 327 666.961 655.852 165.339 2.77556 -0.363362 34.8889 +1 330 665.864 651.899 197.081 2.16575 0.931873 27.7537 +2 330 667.357 652.809 198.601 2.13411 0.950695 26.642 +1 331 575.869 564.711 213.44 -1.62189 1.95388 34.7358 +2 331 574.557 562.881 215.065 -1.61031 1.94197 33.1951 +3 331 573.626 561.193 213.489 -1.55246 1.75559 31.1734 +4 331 573.046 560.657 210.633 -1.58307 1.63795 31.283 +5 331 573.087 560.279 212.033 -1.52968 1.64316 30.2615 +6 331 572.649 559.042 215.716 -1.45711 1.69205 28.4842 +7 331 571.991 558.163 219.794 -1.45933 1.82336 28.028 +8 331 571.673 556.853 221.651 -1.37319 1.76863 26.1521 +9 331 571.114 556.432 222.138 -1.40658 1.80311 26.3984 +1 332 570.084 565.184 135.206 -4.32726 -4.12691 79.0945 +2 332 568.958 563.923 135.318 -4.33144 -4.00442 76.9746 +3 332 568.316 563.209 131.985 -4.33776 -4.29836 75.8873 +4 332 568.134 562.859 127.131 -4.21806 -4.65573 73.4701 +1 334 626.108 618.472 141.066 1.1641 -2.23605 50.7547 +2 334 625.391 617.732 140.948 1.11042 -2.23792 50.6095 +1 335 662.586 651.19 145.552 2.4995 -1.28694 34.0112 +2 335 663.474 651.762 145.045 2.47269 -1.27537 33.0916 +3 335 665.034 652.988 141.195 2.47368 -1.41172 32.1743 +4 335 667.208 654.647 135.495 2.4652 -1.59758 30.8547 +5 335 669.95 656.936 134.031 2.49274 -1.60248 29.7829 +6 335 672.499 659.114 134.756 2.52589 -1.52893 28.9568 +7 335 675.255 661.561 136.302 2.57693 -1.43374 28.3023 +1 337 675.015 662.015 199.212 2.7046 1.08908 29.8137 +2 337 676.679 663.261 200.438 2.68685 1.10422 28.8835 +3 337 679.1 665.174 198.221 2.68239 0.97848 27.8319 +4 337 682.316 667.624 194.636 2.66007 0.796375 26.3804 +5 337 686.006 670.882 195.195 2.71507 0.793443 25.626 +6 337 689.921 673.886 198.03 2.69196 0.84334 24.1701 +7 337 693.83 677.261 201.577 2.73194 0.931153 23.3912 +8 337 698.16 680.72 203.146 2.72894 0.933013 22.2237 +9 337 702.737 684.638 203.214 2.76533 0.901027 21.4138 +10 337 708 688.326 202.443 2.6878 0.807903 19.7007 +11 337 712.416 692.845 203.665 2.82303 0.845643 19.8035 +12 337 718.127 697.887 204.78 2.88134 0.847311 19.1493 +13 337 725.87 703.27 205.51 2.76446 0.776159 17.1495 +1 338 640.55 630.438 204.686 1.64616 1.69087 38.3268 +2 338 640.85 630.438 205.961 1.61433 1.70802 37.2252 +3 338 641.751 630.781 203.785 1.57626 1.51451 35.3299 +1 339 632.275 625.475 149.404 1.7945 -1.85256 57.0009 +2 339 631.984 625.147 149.378 1.76174 -1.84433 56.6855 +3 339 632.144 625.364 146.023 1.78931 -2.12573 57.1657 +4 339 632.719 625.941 141.053 1.83546 -2.52028 57.1832 +5 339 633.645 627.001 140.514 1.9473 -2.61462 58.3352 +1 340 599.5 595.468 183.52 -1.34039 1.42123 96.1396 +2 340 599.173 595.017 184.163 -1.34244 1.46162 93.2578 +1 342 624.655 617.54 135.728 1.13968 -2.80284 54.4725 +2 342 624.395 616.767 135.312 1.0447 -2.64369 50.8107 +1 343 660.78 647.805 210.659 2.12043 1.56503 29.8701 +2 343 661.867 648.486 212.372 2.0997 1.58627 28.9633 +3 343 663.579 649.634 210.798 2.08085 1.46163 27.794 +1 344 642.72 629.748 218.493 1.37315 1.88988 29.8781 +2 344 643.347 629.94 220.463 1.35367 1.9074 28.9076 +3 344 644.416 630.59 218.991 1.35425 1.79253 28.0332 +4 344 646.288 631.717 216.326 1.35393 1.60251 26.5978 +5 344 648.142 633.297 217.246 1.39613 1.60638 26.1095 +1 345 579.806 576.717 159.441 -5.17454 -2.33273 125.485 +2 345 579.177 575.836 159.897 -4.88469 -2.08312 116.003 +3 345 578.875 575.557 156.674 -4.96669 -2.61906 116.793 +4 345 579.038 575.396 152.432 -4.50193 -3.01217 106.426 +5 345 579.537 576.041 152.303 -4.61274 -3.15752 110.861 +6 345 579.748 576.412 154.081 -4.79979 -3.02258 116.171 +7 345 580.251 576.763 156.558 -4.51327 -2.50947 111.113 +8 345 580.505 576.966 156.853 -4.41047 -2.42886 109.528 +9 345 581.114 578.167 155.212 -5.18347 -3.21492 131.484 +1 346 636.877 629.635 174.24 2.02613 0.102827 53.5153 +2 346 635.509 630.287 175.473 2.66926 0.269408 74.218 +1 347 774.783 762.768 136.097 7.38642 -1.64324 32.2567 +2 347 779.298 766.882 134.926 7.34377 -1.64099 31.2175 +1 350 810.057 763.39 202.609 2.30779 0.34249 8.30512 +2 350 835.394 782.873 205.824 2.30972 0.337204 7.37951 +1 353 798.626 786.985 149.078 8.72386 -1.09706 33.2929 +2 353 803.783 791.558 148.35 8.53417 -1.0767 31.7043 +3 353 810.225 797.41 144.147 8.41055 -1.20319 30.2419 +1 355 818.21 772.076 206.806 2.42935 0.395303 8.40095 +2 355 844.8 792.258 210.735 2.40492 0.387268 7.37644 +1 358 699.456 687.721 208.052 4.11504 1.6112 33.0286 +2 358 702.183 689.926 209.521 4.05906 1.60685 31.6201 +1 359 699.456 687.721 208.052 4.11504 1.6112 33.0286 +2 359 702.183 689.926 209.521 4.05906 1.60685 31.6201 +1 361 795.151 748.333 203.255 2.12933 0.348793 8.27834 +2 361 817.154 764.575 206.726 2.12079 0.34604 7.37122 +1 363 789.715 742.271 231.988 2.03971 0.66951 8.16922 +2 363 814.103 759.278 239.761 2.00402 0.65552 7.06928 +1 364 789.715 742.271 231.988 2.03971 0.66951 8.16922 +2 364 814.103 759.278 239.761 2.00402 0.65552 7.06928 +3 364 846.492 782.668 246.463 1.99403 0.619496 6.07248 +4 364 891.32 815.63 255.331 1.9996 0.585323 5.1206 +5 364 956.026 863.015 272.891 2.00089 0.577728 4.16697 +1 365 754.218 715.233 251.825 1.99316 1.08809 9.94163 +2 365 769.232 725.583 259.485 1.96494 1.06609 8.87927 +1 366 754.218 715.233 251.825 1.99316 1.08809 9.94163 +2 366 769.232 725.583 259.485 1.96494 1.06609 8.87927 +3 366 788.42 739.905 266.646 1.9803 1.03844 7.98868 +4 366 812.84 758.241 274.748 1.99989 1.00244 7.09852 +1 368 831.261 783.945 195.065 2.51685 0.25215 8.19121 +2 368 858.478 804.644 198.913 2.48369 0.260014 7.19943 +1 369 704.549 676.668 247.806 1.8301 1.44405 13.9014 +2 369 710.646 681.542 252.631 1.86572 1.47242 13.3172 +3 369 720.207 688.1 254.787 1.85114 1.37073 12.0713 +1 373 920.796 903.078 148.221 9.43584 -0.746804 21.875 +2 373 934.698 916.032 146.87 9.35656 -0.747756 20.7638 +1 374 905.585 887.988 149.178 9.03607 -0.722686 22.0247 +2 374 918.698 900.376 147.738 9.06321 -0.736337 21.1538 +1 376 964.801 947.282 159.213 10.8923 -0.418259 22.1236 +2 376 980.443 961.835 158.006 10.7063 -0.428609 20.8286 +3 376 998.791 979.231 153.994 10.6886 -0.517908 19.8139 +4 376 1020.64 998.959 148.41 10.1837 -0.605556 17.8745 +5 376 1044.97 1022.91 146.141 10.6016 -0.650414 17.5683 +6 376 1070.86 1047.46 144.359 10.5879 -0.65403 16.5609 +7 376 1099.2 1074.87 144.077 10.8101 -0.635332 15.9297 +1 379 890.799 844.616 204.389 3.27104 0.36678 8.39206 +2 379 927.285 874.597 207.56 3.23914 0.353816 7.35591 +1 380 884.037 840.656 212.428 3.39859 0.490001 8.93409 +2 380 917.344 868.115 216.494 3.35833 0.476174 7.87291 +3 380 960.447 904.561 219.076 3.37256 0.444262 6.93507 +1 381 939.435 890.978 218.888 3.65673 0.510297 7.99837 +2 381 985.252 928.717 223.784 3.56951 0.483896 6.85544 +1 382 943.491 895.035 224.425 3.70176 0.571685 7.99852 +2 382 988.819 933.219 230.536 3.66402 0.557259 6.97075 +3 382 1050.08 985.159 235.581 3.6448 0.518997 5.96989 +4 382 1134.12 1056.71 241.65 3.63991 0.477376 5.00675 +1 385 947.024 929.838 167.431 10.5476 -0.169509 22.552 +2 385 961.84 943.797 167.344 10.4878 -0.16405 21.481 +3 385 978.967 959.803 163.817 10.3543 -0.253307 20.2244 +4 385 998.49 978 158.645 10.1959 -0.372488 18.9153 +5 385 1020.27 999.019 156.865 10.38 -0.404102 18.2355 +6 385 1044.11 1021.55 157.299 10.3482 -0.370434 17.1826 +1 388 854.495 839.589 182.781 8.82635 0.35774 26.0009 +2 388 863.336 848.357 183.544 9.10046 0.383329 25.8744 +1 389 838.951 792.657 205.914 2.66166 0.383599 8.37209 +2 389 868.362 815.624 209.757 2.63596 0.375862 7.34901 +3 389 906.902 846.241 211.533 2.63296 0.342501 6.38919 +1 390 937.62 887.32 230.089 3.50337 0.611211 7.70532 +2 390 982.895 925.98 237.504 3.52342 0.610146 6.80963 +3 390 1043.88 977.275 244.352 3.50261 0.576599 5.81888 +4 390 1129.17 1049.92 253.511 3.5219 0.54669 4.89054 +1 392 876.7 828.867 205.525 2.9999 0.366886 8.10261 +2 392 910.441 857.951 209.218 3.07902 0.372121 7.38373 +1 395 937.46 919.194 170.868 9.64259 -0.0584029 21.2183 +2 395 952.242 933.45 170.48 9.79553 -0.0678654 20.625 +1 398 976.273 959.787 156.597 11.9486 -0.529704 23.5099 +2 398 993.132 974.366 155.107 10.9797 -0.507994 20.654 +3 398 1011.57 992.634 151.087 11.405 -0.61753 20.4701 +4 398 1033.2 1012.75 144.713 11.1239 -0.738906 18.9458 +1 400 1083.21 1039.09 127.876 5.76605 -0.547544 8.78375 +2 400 1140.39 1091.38 121.309 5.8176 -0.564906 7.90761 +3 400 1216.25 1159.9 110.525 5.78323 -0.594145 6.87796 +1 415 259.007 217.185 256.709 -4.50242 1.07702 9.26727 +2 415 218.215 171.349 267.747 -4.48529 1.08759 8.26973 +3 415 167.602 114.581 277.26 -4.47746 1.05774 7.30988 +1 416 201.382 152.1 270.963 -4.44895 1.06934 7.86443 +2 416 144.271 88.767 285.992 -4.50287 1.09491 6.98276 +1 417 205.004 156.896 285.391 -4.51706 1.25653 8.05633 +2 417 149.529 95.1647 301.613 -4.54538 1.27222 7.12924 +1 421 195.091 144.94 334.27 -4.43922 1.72886 7.72813 +2 421 136.285 79.4364 357.923 -4.4719 1.74869 6.8177 +1 425 229.586 182.448 269.579 -4.32993 1.10221 8.22218 +2 425 178.462 126.304 284.068 -4.43966 1.14533 7.43076 +1 436 332.346 285.831 322.802 -3.20126 1.7316 8.33232 +2 436 296.323 243.699 343.111 -3.19729 1.73786 7.36495 +1 446 425.861 378.733 322.767 -2.09374 1.70866 8.22387 +2 446 401.545 349.215 342.963 -2.13521 1.74612 7.40637 +1 447 480.992 431.698 330.818 -1.40099 1.72132 7.86256 +2 447 463.194 407.066 353.247 -1.40074 1.72639 6.90521 +1 452 455.002 405.959 331.829 -1.69284 1.74121 7.90284 +2 452 431.732 376.06 354.407 -1.71574 1.75169 6.96166 +1 455 546.492 504.783 304.327 -0.812196 1.69316 9.29219 +2 455 539.346 492.75 319.582 -0.809405 1.69146 8.31777 +3 455 529.688 477.461 334.664 -0.82146 1.66419 7.42091 +1 456 490.233 442.106 320.836 -1.33182 1.65165 8.0532 +2 456 473.383 419.909 342.152 -1.36787 1.70058 7.24778 +1 462 605.072 576.669 264.484 -0.0848646 1.73289 13.6455 +2 462 604.607 575.037 271.669 -0.0899541 1.79498 13.1067 +1 463 571.496 540.856 270.315 -0.667285 1.70859 12.6493 +2 463 568.135 535.384 278.22 -0.679415 1.72813 11.8341 +3 463 564.973 529.698 284.29 -0.678935 1.69689 10.9873 +1 465 581.276 540.074 304.322 -0.368739 1.71397 9.40678 +2 465 578.339 531.903 319.333 -0.361141 1.6944 8.34638 +1 468 568.133 527.905 301.686 -0.553147 1.72025 9.63445 +2 468 563.476 518.61 316.11 -0.551724 1.71511 8.63853 +1 474 592.642 550.446 307.936 -0.215356 1.71957 9.18508 +2 474 590.395 542.902 324.398 -0.216749 1.71397 8.16059 +3 474 588.127 534.956 339.543 -0.216514 1.68395 7.28924 +1 475 687.419 661.468 258.422 1.6116 1.77113 14.9348 +2 475 692.101 664.494 264.165 1.60602 1.77663 14.039 +3 475 698.282 668.884 267.943 1.62112 1.73744 13.1837 +4 475 705.865 673.63 270.362 1.60478 1.62482 12.0233 +5 475 715.686 680.388 279.64 1.61498 1.62501 10.9799 +6 475 726.454 688.129 291.175 1.63834 1.65833 10.1127 +1 477 650.58 623.285 263.076 0.807267 1.77553 14.1996 +2 477 652.949 623.479 269.856 0.790871 1.76806 13.1514 +1 478 650.58 623.285 263.076 0.807267 1.77553 14.1996 +2 478 652.949 623.479 269.856 0.790871 1.76806 13.1514 +3 478 656.491 625.074 274.467 0.802405 1.73732 12.3364 +4 478 661.997 627.335 279.702 0.812625 1.65582 11.1816 +1 481 787.377 734.589 341.862 1.8094 1.71975 7.34205 +2 481 815.002 753.067 367.098 1.78177 1.68465 6.25777 +1 484 747.544 710.125 268.737 1.9808 1.37643 10.3579 +2 484 761.439 720.004 276.5 1.96895 1.34365 9.35396 +3 484 778.08 732.05 281.906 1.96656 1.27258 8.41999 +4 484 799.174 749.14 287.597 2.03563 1.23184 7.74617 +1 485 762.908 723.442 278.149 2.08714 1.43311 9.82042 +2 485 779.121 735.129 289.005 2.07035 1.4182 8.80995 +1 486 732.386 697.336 282.934 1.88233 1.68698 11.0576 +2 486 743.835 705.467 293.342 1.87987 1.68684 10.1016 +3 486 758.118 715.439 302.367 1.86975 1.63004 9.08121 +1 487 763.391 720.389 307.654 1.92156 1.68383 9.01297 +2 487 781.565 733.123 323.485 1.90729 1.67027 8.00076 +3 487 805.402 750.122 340.307 1.903 1.62714 7.0112 +1 488 823.527 768.191 308.848 2.07699 1.32009 7.00396 +2 488 857.331 792.801 329.47 2.06246 1.30367 6.0061 +3 488 904.079 827.318 354.042 2.06095 1.26789 5.04907 +1 492 826.313 770.574 319.292 2.08882 1.4112 6.95335 +2 492 860.264 795.613 341.055 2.08297 1.3975 5.99488 +1 493 809.863 756.939 279.357 2.03297 1.08095 7.3232 +2 493 839.559 778.515 294.995 2.02386 1.07477 6.3491 +3 493 880.283 808.335 312.462 2.02117 1.04229 5.38686 +4 493 938.537 850.934 337.143 2.01718 1.00736 4.42423 +1 494 742.197 706.391 280.364 1.98976 1.61281 10.8241 +2 494 754.669 715.839 289.956 2.0074 1.61995 9.98153 +3 494 771.974 728.172 298.808 1.99169 1.54457 8.84818 +4 494 791.375 744.547 307.541 2.08556 1.54496 8.2766 +1 495 759.986 719.86 287.221 2.01369 1.53097 9.65888 +2 495 774.963 731.453 298.07 2.04197 1.54584 8.90764 +1 496 837.499 781.55 265.122 2.1884 0.885843 6.92733 +2 496 873.77 808.434 279.271 2.17215 0.874881 5.93196 +1 498 914.864 854.941 305.794 2.73679 1.19169 6.46796 +2 498 967.992 897.175 328.029 2.71873 1.17701 5.47289 +1 501 837.177 780.387 273.327 2.15292 0.950318 6.82465 +2 501 874.003 807.727 289.103 2.14325 0.94217 5.84787 +1 502 931.895 872.647 276.328 2.92236 0.938121 6.54161 +2 502 986.831 917.346 293.085 2.91649 0.929447 5.57783 +1 509 846.36 789.952 264.856 2.25497 0.876105 6.87095 +2 509 884.421 818.551 279.337 2.24141 0.86833 5.8839 +3 509 938.303 859.458 295.827 2.23965 0.837786 4.91566 +1 510 858.053 800.764 268.743 2.32991 0.899066 6.76524 +2 510 898.951 831.732 284.076 2.31256 0.888784 5.76589 +3 510 956.533 876.112 301.865 2.31751 0.861693 4.8193 +1 511 962.419 902.44 309.239 3.16011 1.22143 6.46188 +2 511 1023.6 952.881 331.871 3.14496 1.20787 5.48067 +1 513 965.564 907.144 281.252 3.27333 0.996675 6.63427 +2 513 1025.47 957.304 298.674 3.27731 0.991434 5.68557 +3 513 1108.51 1026.8 320.106 3.27989 0.967973 4.74308 +1 514 876.357 819.829 283.773 2.53519 1.05398 6.85627 +2 514 920.262 852.613 301.399 2.46708 1.02069 5.72925 +1 518 988.984 930.435 280.229 3.48094 0.985089 6.61957 +2 518 1052.12 983.753 296.977 3.47697 0.97516 5.6687 +3 518 1140.76 1059.53 317.381 3.51257 0.95569 4.7712 +1 525 978.788 920.953 263.944 3.42925 0.846003 6.70135 +2 525 1039.6 972.177 277.002 3.42606 0.829724 5.74836 +1 527 996.271 939.064 320.413 3.63111 1.38554 6.77503 +2 527 1059.82 993.085 344.44 3.62392 1.381 5.80723 +1 532 1000.42 944.463 270.368 3.75215 0.936118 6.92661 +2 532 1064.46 998.474 285.329 3.70313 0.915609 5.87372 +3 532 1155.65 1075.58 303.864 3.66384 0.878984 4.84099 +1 533 987.143 929.75 270.161 3.53388 0.910719 6.75301 +2 533 1048.79 981.895 286.378 3.52684 0.911549 5.79363 +1 534 988.933 929.916 308.319 3.45291 1.23295 6.56715 +2 534 1052.04 983.524 331.223 3.46894 1.24157 5.65667 +2 557 853.073 845.388 40.7428 17.0212 -9.23434 50.4342 +3 557 857.109 849.004 35.3553 16.4058 -9.1124 47.8182 +4 557 861.475 853.331 28.6391 16.6156 -9.51194 47.5903 +5 557 866.399 858.393 25.5112 17.2302 -9.88456 48.4047 +6 557 871.264 863.019 24.6064 17.0506 -9.65864 47.0097 +7 557 876.727 868.196 23.716 16.8216 -9.39013 45.43 +2 560 201.363 175.335 161.388 -8.42435 -0.236643 14.8911 +3 560 173.382 148.648 160.342 -9.47263 -0.271733 15.6699 +4 560 145.681 117.274 156.715 -8.77173 -0.305177 13.644 +2 562 293.429 256.308 232.221 -4.57452 0.859058 10.4409 +3 562 261.858 221.022 235.582 -4.57354 0.825109 9.49087 +4 562 224.079 178.421 239.628 -4.53506 0.78558 8.48868 +2 563 297.584 263.907 211.344 -4.97604 0.613916 11.5086 +3 563 269.501 232.823 211.173 -4.98012 0.561179 10.5668 +2 566 893.452 875.89 131.337 8.68313 -1.26985 22.0689 +3 566 906.713 888.303 126.217 8.66994 -1.36069 21.052 +4 566 921.874 902.317 119.093 8.57805 -1.47661 19.8178 +5 566 938.639 918.144 115.369 8.62473 -1.5066 18.9105 +6 566 956.889 935.125 113.714 8.57237 -1.45962 17.8081 +7 566 976.911 954.009 112.723 8.61617 -1.41035 16.9235 +8 566 999.513 975.237 110.048 8.6286 -1.38972 15.9657 +9 566 1025.19 999.509 104.801 8.6928 -1.42331 15.0907 +10 566 1053.98 1026.68 98.3738 8.74192 -1.46504 14.1928 +11 566 1086.59 1057.6 91.908 8.83746 -1.49959 13.3671 +12 566 1124.19 1092.4 84.4277 8.69407 -1.49385 12.1894 +2 570 445.209 401.894 317.991 -2.0381 1.79985 8.94777 +3 570 426.761 376.16 332.678 -1.94046 1.69659 7.65935 +2 577 276.951 257.663 35.0199 -9.26244 -3.8384 20.0933 +3 577 260.036 239.234 25.8438 -9.02546 -3.79612 18.6317 +2 578 184.424 158.869 65.6354 -8.93616 -2.25369 15.1664 +3 578 154.929 128.715 55.8539 -9.31594 -2.39748 14.7852 +2 589 414.999 401.329 38.6684 -7.64509 -5.27273 28.3523 +3 589 408.193 394.207 31.2295 -7.73353 -5.43914 27.7109 +2 591 326.081 312.959 82.5963 -11.6048 -3.69489 29.5377 +3 591 316.211 302.332 76.7242 -11.3534 -3.72049 27.9255 +4 591 306.196 291.902 69.4215 -11.4002 -3.88691 27.1148 +2 595 413.166 399.779 119.131 -7.88002 -2.15558 28.9508 +3 595 405.803 392.737 114.96 -8.37632 -2.38 29.6621 +4 595 399.07 385.12 109.113 -8.10509 -2.45442 27.7835 +5 595 392.359 377.71 107.956 -7.96393 -2.37958 26.4562 +6 595 385.94 369.396 107.917 -7.2607 -2.10844 23.4276 +2 597 348.214 334.007 40.6692 -9.88118 -4.99776 27.2805 +3 597 338.569 324.256 34.1953 -10.1698 -5.20364 27.0782 +2 600 381.732 367.766 109.08 -8.76268 -2.45289 27.7518 +3 600 373.224 360.325 104.48 -9.84175 -2.84731 30.0471 +4 600 365.416 352.331 98.2845 -10.0224 -3.06117 29.62 +2 601 381.732 367.766 109.08 -8.76268 -2.45289 27.7518 +3 601 373.224 360.325 104.48 -9.84175 -2.84731 30.0471 +4 601 365.416 352.331 98.2845 -10.0224 -3.06117 29.62 +2 610 412.68 399.123 98.6219 -7.80095 -2.94129 28.5895 +3 610 405.039 391.339 93.7471 -8.0189 -3.10165 28.2903 +2 614 540.23 527.944 54.5704 -3.03121 -5.17157 31.5469 +3 614 537.724 524.725 47.944 -2.96827 -5.16136 29.8144 +2 617 489.205 476.099 89.3296 -4.93269 -3.42323 29.5721 +3 617 485.142 471.521 83.7163 -4.9064 -3.51515 28.4539 +2 619 543.89 531.016 94.0029 -2.74 -3.28998 30.1054 +3 619 541.544 528.4 88.1693 -2.77954 -3.46075 29.4866 +2 620 418.691 404.85 102.766 -7.40726 -2.72001 28.0017 +3 620 411.587 398.106 97.7433 -7.88822 -2.9928 28.7498 +2 621 513.819 501.12 107.994 -4.04941 -2.74331 30.5182 +3 621 510.753 497.045 102.818 -3.87168 -2.74431 28.2731 +2 622 468.92 455.647 109.274 -5.69158 -2.57305 29.2003 +3 622 464.191 450.399 104.418 -5.66159 -2.66535 28.1015 +4 622 459.384 445.33 98.053 -5.73948 -2.85879 27.5762 +5 622 454.748 440.398 95.9516 -5.79493 -2.87862 27.0087 +6 622 450.401 436.079 95.905 -5.96905 -2.88589 27.0605 +2 623 449.085 435.923 123.968 -6.54934 -1.99517 29.4477 +3 623 443.481 429.69 119.514 -6.46898 -2.07766 28.1048 +4 623 438.012 423.774 113.759 -6.47169 -2.22937 27.2203 +5 623 432.558 418.006 112.176 -6.53335 -2.23972 26.6329 +6 623 426.998 411.543 112.751 -6.34467 -2.0888 25.0761 +7 623 420.708 404.467 113.307 -6.24593 -1.9694 23.8636 +8 623 413.912 397.312 111.393 -6.33056 -1.98869 23.3468 +2 627 549.52 536.564 77.1756 -2.48916 -3.96671 29.9141 +3 627 547.177 533.98 71.0587 -2.53918 -4.14343 29.3691 +4 627 545.017 531.313 63.2481 -2.52967 -4.29592 28.2801 +5 627 543.347 528.952 59.5195 -2.47066 -4.22901 26.9237 +6 627 541.362 526.314 58.0262 -2.43438 -4.09891 25.7561 +7 627 539.511 523.864 56.1633 -2.40474 -4.00593 24.77 +8 627 537.665 521.454 52.1534 -2.38209 -3.99923 23.907 +9 627 535.742 518.904 45.9403 -2.35481 -4.04863 23.0175 +10 627 533.148 515.772 38.2928 -2.36207 -4.15964 22.3046 +2 630 433.119 419.682 97.7795 -7.05355 -3.00125 28.8448 +3 630 426.918 413.274 92.3757 -7.19082 -3.16852 28.4078 +4 630 420.823 405.841 85.7855 -6.76689 -3.12173 25.8698 +5 630 414.37 399.391 83.1189 -6.99978 -3.21803 25.8754 +2 631 433.119 419.682 97.7795 -7.05355 -3.00125 28.8448 +3 631 426.918 413.274 92.3757 -7.19082 -3.16852 28.4078 +4 631 420.823 405.841 85.7855 -6.76689 -3.12173 25.8698 +5 631 414.37 399.391 83.1189 -6.99978 -3.21803 25.8754 +2 632 459.855 446.381 100.785 -5.96806 -2.87309 28.7646 +3 632 454.281 440.683 95.476 -6.13378 -3.05657 28.5021 +4 632 449.548 434.715 88.5968 -5.79431 -3.05112 26.1283 +5 632 444.181 429.185 86.3221 -5.92381 -3.09955 25.8453 +2 633 509.746 496.623 67.0067 -4.08527 -4.33225 29.532 +3 633 506.206 492.601 60.4153 -4.08072 -4.43944 28.4886 +4 633 502.693 488.657 52.5717 -4.08986 -4.6033 27.6138 +5 633 499.561 485.351 49.0013 -4.15781 -4.6815 27.2734 +6 633 496.376 481.238 46.851 -4.01617 -4.47105 25.6028 +2 636 547.677 534.804 86.0468 -2.58225 -3.62231 30.1084 +3 636 545.065 532.193 80.2105 -2.69134 -3.86603 30.1099 +2 638 524.435 513.736 121.373 -4.27386 -2.58469 36.2262 +3 638 521.934 510.719 117.308 -4.19698 -2.66046 34.5594 +2 639 499.493 486.588 105.175 -4.58116 -2.81695 30.0318 +3 639 495.843 482.128 99.9568 -4.45374 -2.85504 28.2592 +2 641 533.076 520.355 87.8891 -3.22957 -3.58772 30.4676 +3 641 530.458 517.095 82.3061 -3.17958 -3.6397 29.0032 +2 642 492.483 479.306 73.1739 -4.77253 -4.06339 29.413 +3 642 488.345 475.242 67.1691 -4.96897 -4.33237 29.5782 +4 642 484.344 470.38 59.5055 -4.81669 -4.36021 27.7556 +5 642 480.578 466.297 56.2752 -4.85112 -4.38467 27.1379 +6 642 476.732 462.422 54.8662 -4.98591 -4.42888 27.0842 +7 642 472.991 457.777 53.6322 -4.82162 -4.2092 25.4744 +8 642 469.476 453.417 50.1251 -4.68556 -4.10508 24.1342 +9 642 465.42 448.75 44.4298 -4.64457 -4.13817 23.2499 +10 642 459.408 440.079 36.6007 -4.17274 -3.78652 20.0517 +2 643 588.959 575.923 34.9086 -0.848802 -5.68385 29.7299 +3 643 588.152 575.029 27.7365 -0.87627 -5.94012 29.5348 +4 643 588.415 574.54 19.4264 -0.818598 -5.93989 27.934 +2 648 658.897 647.085 85.9733 2.24356 -3.95075 32.8107 +3 648 660.457 648.002 80.2344 2.19515 -3.99459 31.1192 +4 648 662.435 649.622 72.9155 2.2167 -4.18972 30.249 +5 648 664.5 651.613 69.2991 2.2901 -4.31651 30.0761 +6 648 666.512 653.477 67.7207 2.34694 -4.33238 29.7334 +7 648 668.924 655.428 66.3572 2.36268 -4.23849 28.7166 +2 649 611.561 599.385 101.845 0.088307 -3.13246 31.8298 +3 649 610.385 599.381 95.9327 0.0403276 -3.7546 35.219 +2 650 659.332 647.379 118.527 2.23661 -2.44124 32.423 +3 650 660.767 648.4 113.81 2.22421 -2.56458 31.3399 +2 656 781.246 769.121 67.4527 7.60553 -4.66916 31.9633 +3 656 786.571 774.015 60.9102 7.57279 -4.78911 30.8683 +2 657 772.785 760.858 69.2424 7.35098 -4.66621 32.4949 +3 657 777.78 765.388 63.4073 7.29173 -4.7441 31.276 +2 669 852.066 842.2 72.964 13.2031 -5.43846 39.2837 +3 669 858.362 848.268 66.8993 13.2396 -5.6382 38.3954 +2 674 1097.55 1045.33 40.1344 5.01974 -1.36524 7.4222 +3 674 1170.31 1110.47 16.0142 5.03386 -1.40795 6.47725 +2 677 1097.14 1047.69 112.492 5.29668 -0.655724 7.83817 +3 677 1166.51 1109.2 99.2657 5.22018 -0.689732 6.76286 +2 697 120.23 75.0816 225.546 -5.82177 0.626903 8.58446 +3 697 57.463 7.26515 229.922 -5.9078 0.61067 7.72094 +2 711 215.121 168.221 232.783 -4.5176 0.686387 8.26396 +3 711 163.985 111.682 237.982 -4.57603 0.668865 7.41016 +4 711 98.7715 38.863 244.469 -4.57981 0.642114 6.46943 +2 712 245.762 202.547 233.438 -4.52189 0.753048 8.9685 +3 712 202.525 154.757 237.775 -4.57706 0.730029 8.11364 +4 712 148.866 93.7082 243.031 -4.48639 0.683407 7.02659 +2 738 549.296 543.925 135.768 -6.02671 -3.70888 72.1585 +3 738 548.39 542.982 132.309 -6.07585 -4.02726 71.669 +4 738 547.847 542.206 127.507 -5.87707 -4.31849 68.7142 +5 738 547.694 542.129 127.104 -5.97144 -4.41591 69.645 +6 738 547.571 541.669 128.585 -5.64146 -4.02889 65.6665 +7 738 547.165 541.417 130.23 -5.83049 -3.98302 67.425 +8 738 546.995 541 130.05 -5.60597 -3.83531 64.6516 +9 738 546.839 540.879 127.838 -5.65281 -4.05716 65.0297 +2 739 455.646 442.42 128.903 -6.25055 -1.7849 29.3023 +3 739 450.39 436.72 124.68 -6.25433 -1.89292 28.3518 +4 739 445.096 430.981 119.054 -6.2587 -2.04738 27.4583 +5 739 440.187 425.604 117.828 -6.23863 -2.02681 26.577 +6 739 434.623 419.484 118.443 -6.20716 -1.93062 25.6019 +2 740 459.603 446.679 137.403 -6.23285 -1.47351 29.9903 +3 740 454.654 441.448 133.398 -6.30043 -1.60478 29.347 +2 741 459.603 446.679 137.403 -6.23285 -1.47351 29.9903 +3 741 454.654 441.448 133.398 -6.30043 -1.60478 29.347 +4 741 449.841 435.902 128.064 -6.15475 -1.72599 27.8046 +5 741 445.061 430.787 127.248 -6.1904 -1.71622 27.1528 +2 745 567.571 564.461 171.803 -7.25179 -0.181515 124.618 +3 745 567.271 564.086 169.124 -7.13128 -0.629027 121.676 +4 745 567.334 564.082 164.978 -6.97645 -1.30124 119.211 +5 745 567.949 564.587 165.171 -6.64975 -1.22778 115.308 +6 745 568.372 564.886 167.122 -6.34678 -0.883316 111.185 +7 745 568.525 565.172 169.608 -6.57437 -0.519998 115.602 +2 746 610.018 604.999 180.363 0.0491049 0.803582 77.2208 +3 746 610.026 604.926 177.531 0.0491093 0.492557 75.9944 +2 749 678.375 666.394 152.668 3.08513 -0.904954 32.3477 +3 749 680.106 667.88 149.015 3.09967 -1.04744 31.703 +4 749 682.483 669.848 143.687 3.10015 -1.23996 30.6743 +5 749 685.378 672.663 141.959 3.20302 -1.30516 30.4817 +6 749 688.216 674.933 141.759 3.18078 -1.25745 29.1783 +2 751 656.495 642.32 215.489 1.77866 1.61571 27.3434 +3 751 658.555 644.374 213.719 1.85589 1.54792 27.3308 +2 752 557.587 537.695 238.293 -1.40341 1.76706 19.4839 +3 752 554.424 534.317 239.285 -1.47296 1.77473 19.276 +4 752 552.718 531.836 238.377 -1.46217 1.6855 18.5606 +2 757 801.227 751.989 231.713 2.09095 0.642105 7.87143 +3 757 829.397 775.704 236.347 2.19926 0.635186 7.21828 +2 762 711.096 692.739 195.144 2.97115 0.652242 21.1135 +3 762 711.511 697.525 191.974 3.91557 0.734335 27.7113 +4 762 712.395 704.669 188.143 7.14949 1.06298 50.1637 +5 762 715.713 710.331 188.524 10.5951 1.56405 72.0161 +2 765 928.983 880.21 222.143 3.51789 0.542831 7.94648 +3 765 974.324 917.451 225.997 3.44514 0.501926 6.81479 +2 769 903.53 885.506 137.066 8.76103 -1.06658 21.5035 +3 769 917.841 898.746 131.823 8.67187 -1.1542 20.2966 +4 769 934.025 913.833 124.528 8.63168 -1.28562 19.1949 +5 769 952.037 930.773 120.798 8.65104 -1.31495 18.2261 +6 769 971.655 949.164 119.056 8.64799 -1.28487 17.2326 +7 769 993.462 969.653 118.198 8.66116 -1.23308 16.2785 +8 769 1017.98 992.572 115.153 8.63322 -1.21967 15.2517 +9 769 1045.98 1019.21 110.001 8.7584 -1.26138 14.4804 +2 771 880.082 861.388 158.478 7.77351 -0.413107 20.7335 +3 771 891.831 874.219 154.611 8.60919 -0.556418 22.0067 +2 772 965.528 947.473 176.201 10.59 0.0995581 21.4657 +3 772 982.844 963.797 172.858 10.5273 0.000115867 20.3486 +2 773 927.285 874.597 207.56 3.23914 0.353816 7.35591 +3 773 974.559 913.839 208.891 3.22889 0.318794 6.38292 +4 773 1038.05 968.067 210.248 3.28881 0.287008 5.53802 +5 773 1127.83 1043.38 216.7 3.29676 0.27891 4.58979 +2 774 949.824 935.35 155.428 12.6272 -0.646688 26.7762 +3 774 966.027 947.254 150.703 10.1995 -0.633796 20.6452 +4 774 984.732 964.551 144.268 9.98584 -0.760858 19.2049 +2 775 888.144 870.955 155.939 8.70537 -0.528553 22.547 +3 775 901.2 882.864 152.01 8.54364 -0.61063 21.1375 +2 776 888.144 870.955 155.939 8.70537 -0.528553 22.547 +3 776 901.2 882.864 152.01 8.54364 -0.61063 21.1375 +2 777 972.39 954.481 170.607 10.8829 -0.0673897 21.6422 +3 777 989.557 970.846 166.796 10.9086 -0.173904 20.7132 +2 786 998.94 942.951 238.717 3.7357 0.631889 6.9224 +3 786 1061.3 996.57 244.331 3.74883 0.593165 5.98781 +2 788 982.895 925.98 237.504 3.52342 0.610146 6.80963 +3 788 1043.88 977.275 244.352 3.50261 0.576599 5.81888 +4 788 1129.17 1049.92 253.511 3.5219 0.54669 4.89054 +2 819 259.035 216.895 262.189 -4.46803 1.13873 9.19725 +3 819 218.638 172.339 269.71 -4.53545 1.12372 8.37124 +2 825 222.648 176.292 323.001 -4.48334 1.73983 8.36082 +3 825 173.564 120.758 340.036 -4.43506 1.70062 7.33968 +2 836 294.264 258 255.512 -4.67027 1.22435 10.6877 +3 836 263.599 220.853 260.58 -4.34738 1.10238 9.06693 +2 837 338.247 296.021 311.438 -3.45134 1.76292 9.17862 +3 837 307.99 259.383 323.935 -3.33262 1.66958 7.97365 +4 837 268.877 214.728 339.179 -3.37951 1.64991 7.15753 +2 849 562.287 527.651 283.497 -0.733126 1.71591 11.19 +3 849 558.142 520.437 290.01 -0.732494 1.66902 10.2791 +2 850 569.067 533.169 288.956 -0.605885 1.73725 10.7965 +3 850 565.873 526.247 297.307 -0.592188 1.68702 9.78074 +4 850 561.837 518.492 306.186 -0.591398 1.65233 8.94167 +5 850 558.022 509.486 321.721 -0.570365 1.64752 7.98527 +2 852 568.287 542.409 255.051 -0.856682 1.70615 14.9768 +3 852 565.698 538.202 257.917 -0.85688 1.6618 14.096 +2 856 601.725 555.517 318.299 -0.091076 1.69077 8.38774 +3 856 600.609 549.155 333.365 -0.0934329 1.67564 7.53246 +4 856 600.922 541.632 351.917 -0.0782462 1.62224 6.53685 +2 859 593.355 550.797 308.012 -0.204515 1.70589 9.10682 +3 859 591.318 544.534 321.476 -0.209437 1.7064 8.2843 +2 861 706.918 678.631 263.691 1.84878 1.72494 13.7015 +3 861 714.774 683.844 267.265 1.82725 1.63962 12.5309 +2 869 873.77 808.434 279.271 2.17215 0.874881 5.93196 +3 869 924.215 846.466 295.506 2.17388 0.847372 4.98492 +4 869 999.007 902.584 319.262 2.16952 0.8156 4.0195 +2 870 873.77 808.434 279.271 2.17215 0.874881 5.93196 +3 870 924.215 846.466 295.506 2.17388 0.847372 4.98492 +4 870 999.007 902.584 319.262 2.16952 0.8156 4.0195 +2 873 920.075 851.828 287.073 2.44396 0.898976 5.67897 +3 873 983.192 901.033 305.745 2.44278 0.868833 4.71737 +2 874 950.711 889.643 298.077 3.00075 1.10146 6.3466 +3 874 1012.37 939.095 319.366 2.95298 1.07408 5.28962 +2 877 885.799 819.035 292.56 2.22248 0.963087 5.80511 +3 877 940.354 860.76 311.748 2.23243 0.937355 4.86944 +4 877 1021.58 922.113 340.781 2.22512 0.906899 3.89671 +2 879 938.986 867.633 323.096 2.47994 1.13102 5.43177 +3 879 1010.09 923.177 348.951 2.47535 1.0883 4.4592 +2 883 1012.25 940.889 326.173 3.03126 1.15412 5.43142 +3 883 1096.97 1011.11 353.831 3.04934 1.13224 4.51412 +2 890 995.6 925.071 318.595 2.94008 1.10996 5.49523 +3 890 1075.91 990.741 344.84 2.94132 1.08474 4.55084 +3 899 445.478 431.317 60.1668 -6.22417 -4.27461 27.3704 +4 899 439.667 424.754 52.3866 -6.11948 -4.33921 25.9896 +3 920 797.764 747.801 292.132 2.02338 1.28235 7.75722 +4 920 824.706 767.696 303.568 2.02712 1.23159 6.79834 +5 920 861.037 794.546 323.696 2.03157 1.21858 5.82895 +3 938 184.488 159.608 61.5349 -9.17722 -2.40336 15.5779 +4 938 156.275 129.879 52.3439 -9.22397 -2.45229 14.6827 +3 941 381.341 366.953 37.9663 -8.52041 -5.03595 26.9382 +4 941 373.204 357.631 29.2037 -8.15252 -4.95488 24.8877 +5 941 364.706 348.493 24.6857 -8.11228 -4.90899 23.9054 +3 943 397.687 384.241 121.804 -8.46393 -2.03935 28.8242 +4 943 390.908 376.878 116.264 -8.37156 -2.16668 27.6257 +5 943 384.021 369.871 115.314 -8.56161 -2.18428 27.3902 +6 943 376.838 361.953 116.312 -8.39805 -2.04039 26.0376 +7 943 369.082 354.103 117.014 -8.62367 -2.00245 25.8748 +8 943 360.868 343.886 115.24 -7.86623 -1.82235 22.8226 +9 943 352.075 334.221 111.444 -7.74648 -1.84753 21.7076 +10 943 341.228 324.177 107.235 -8.45318 -2.06719 22.7304 +11 943 331.071 312.899 103.5 -8.23178 -2.05003 21.3278 +12 943 318.121 301.914 100.718 -9.65973 -2.39096 23.9154 +13 943 307.212 285.567 96.9564 -7.50325 -1.88352 17.9061 +3 947 334.727 320.95 51.6793 -10.7148 -4.72422 28.1305 +4 947 325.356 310.394 43.4164 -10.2034 -4.64705 25.9045 +5 947 315.69 300.219 39.72 -10.2028 -4.62225 25.0509 +6 947 305.227 289.406 37.9446 -10.332 -4.58014 24.496 +3 949 364.218 350.891 83.1032 -9.88794 -3.61722 29.08 +4 949 355.653 341.842 76.0564 -9.87563 -3.76492 28.064 +3 950 375.122 361.315 113.609 -9.1209 -2.30497 28.0718 +4 950 367.023 353.042 107.869 -9.31787 -2.49663 27.7204 +5 950 359.332 345.122 106.501 -9.45897 -2.50823 27.2752 +6 950 351.319 336.146 107.109 -9.14225 -2.32751 25.5439 +7 950 342.471 327.113 107.264 -9.34136 -2.294 25.2356 +3 951 311.621 296.465 37.9967 -10.5598 -4.77971 25.5733 +4 951 301.167 286.633 29.5782 -11.3977 -5.29526 26.667 +3 954 414.474 400.893 108.175 -7.71589 -2.55813 28.5378 +4 954 407.945 393.716 102.064 -7.61105 -2.67236 27.2385 +5 954 401.677 387.24 100.424 -7.73465 -2.69491 26.8461 +3 955 346.373 332.188 56.3857 -9.9661 -4.41032 27.3225 +4 955 336.943 322.715 48.7021 -10.2918 -4.68698 27.2395 +5 955 327.685 313.47 45.5398 -10.6516 -4.81099 27.2657 +6 955 318.593 303.398 43.8276 -10.286 -4.56123 25.5072 +7 955 308.955 292.299 41.2054 -9.69433 -4.2456 23.2692 +3 957 342.847 332.282 110.607 -13.5596 -3.16465 36.6829 +4 957 335.941 324.871 103.712 -13.2766 -3.35492 35.0107 +5 957 329.299 316.874 103.238 -12.1152 -3.0094 31.1911 +3 958 548.237 534.762 20.8996 -2.44459 -6.05755 28.7636 +4 958 546.071 532.415 11.3436 -2.49739 -6.35317 28.3824 +5 958 544.663 529.911 6.24662 -2.36306 -6.06666 26.2733 +3 959 449.512 435.291 27.9061 -6.04531 -5.47496 27.2539 +4 959 443.932 429.844 18.7764 -6.31509 -5.87473 27.5111 +3 963 436.37 422.283 59.5516 -6.60395 -4.32038 27.5133 +4 963 430.262 415.466 51.5451 -6.50894 -4.40383 26.1937 +5 963 424.241 409.173 47.8614 -6.60655 -4.45595 25.7226 +3 964 436.37 422.283 59.5516 -6.60395 -4.32038 27.5133 +4 964 430.262 415.466 51.5451 -6.50894 -4.40383 26.1937 +5 964 424.241 409.173 47.8614 -6.60655 -4.45595 25.7226 +6 964 418.142 402.058 45.8219 -6.39281 -4.24251 24.0973 +7 964 411.222 394.64 43.722 -6.42452 -4.18284 23.372 +8 964 403.904 386.581 38.7822 -6.37703 -4.15735 22.3737 +9 964 395.926 377.967 31.5157 -6.38985 -4.22748 21.5815 +10 964 387.016 368.327 23.052 -6.39649 -4.3057 20.7389 +11 964 377.577 357.702 15.1993 -6.2698 -4.26094 19.501 +3 973 468.123 454.933 95.8098 -5.76021 -3.13774 29.3857 +4 973 463.838 449.735 88.7635 -5.54997 -3.2027 27.4807 +3 975 468.123 454.933 95.8098 -5.76021 -3.13774 29.3857 +4 975 463.838 449.735 88.7635 -5.54997 -3.2027 27.4807 +3 979 513.853 499.988 23.8379 -3.70804 -5.77344 27.9551 +4 979 510.436 496.242 14.2882 -3.75108 -6.00053 27.3048 +3 980 506.206 492.601 60.4153 -4.08072 -4.43944 28.4886 +4 980 502.693 488.657 52.5717 -4.08986 -4.6033 27.6138 +3 981 422.68 408.458 70.1035 -7.05831 -3.88082 27.252 +4 981 416.15 401.223 62.6082 -6.95962 -3.96708 25.9638 +3 983 505.368 492.961 72.8901 -4.51101 -4.32798 31.2393 +4 983 502.421 489.218 65.3477 -4.35909 -4.37405 29.3568 +5 983 499.299 486.041 62.1634 -4.46735 -4.48477 29.234 +6 983 496.322 482.609 60.7704 -4.4356 -4.39041 28.2633 +7 983 493.018 478.687 59.4166 -4.36819 -4.25184 27.0445 +8 983 489.756 474.203 55.4086 -4.13782 -4.05637 24.9207 +9 983 486.035 469.596 49.1526 -4.03614 -4.04193 23.5762 +3 986 466.881 452.561 62.8512 -5.35194 -4.12628 27.0654 +4 986 461.639 447.123 54.8235 -5.47354 -4.36752 26.6993 +5 986 456.744 441.822 51.0415 -5.50071 -4.38475 25.9724 +6 986 451.966 436.213 49.2805 -5.37352 -4.21353 24.6026 +3 989 662.089 649.392 70.0208 2.2223 -4.35038 30.5248 +4 989 663.844 650.793 62.1679 2.23427 -4.55565 29.6973 +5 989 666.305 652.757 58.226 2.24985 -4.54477 28.6076 +3 992 584.023 575.209 113.681 -1.55643 -3.60653 43.9767 +4 992 583.74 575.345 107.892 -1.65219 -4.15692 46.1709 +3 995 686.399 676.13 27.7165 4.01956 -7.59232 37.7445 +4 995 688.007 677.484 19.1442 4.0046 -7.84658 36.8331 +3 996 643.775 631.715 118.594 1.52398 -2.41675 32.1375 +4 996 645.522 632.609 112.464 1.49603 -2.51223 30.0161 +5 996 647.54 634.021 110.724 1.50905 -2.46853 28.6679 +3 998 752.259 723.561 36.8507 2.67094 -2.5456 13.5052 +4 998 763.276 732.417 21.7422 2.67571 -2.63037 12.5596 +5 998 776.253 742.443 9.02526 2.64834 -2.60282 11.4634 +3 999 745.194 715.49 55.0278 2.45272 -2.13068 13.0477 +4 999 755.974 725.128 40.7615 2.54964 -2.30024 12.5647 +3 1007 699.07 687.434 43.8215 4.13208 -5.95654 33.3084 +4 1007 702.321 689.839 35.1557 3.99204 -5.92591 31.0517 +3 1010 747.867 719.289 32.1223 2.59957 -2.64513 13.5617 +4 1010 758.636 727.771 16.7944 2.59446 -2.71599 12.5573 +3 1012 714.013 701.819 113.976 4.60104 -2.59349 31.7827 +4 1012 717.412 705.671 107.405 4.93428 -2.99431 33.0104 +5 1012 721.185 709.425 105.216 5.09858 -3.0894 32.9568 +6 1012 725.213 712.747 105.003 4.98345 -2.92364 31.0905 +7 1012 729.864 716.532 105.592 4.84725 -2.7101 29.0719 +3 1017 949.158 929.626 112.754 9.33933 -1.65282 19.8431 +4 1017 967.501 946.61 104.64 9.20359 -1.75396 18.5526 +5 1017 987.965 966.129 99.6801 9.30872 -1.80007 17.7497 +6 1017 1010.06 986.923 96.9815 9.29888 -1.76163 16.7529 +3 1021 848.201 841.99 35.2174 20.6394 -11.9038 62.4038 +4 1021 852.488 846.074 27.9442 20.3448 -12.1359 60.4275 +5 1021 856.942 850.582 24.8217 20.8908 -12.5009 60.9319 +6 1021 861.246 854.578 23.8695 20.2751 -12.0017 58.1248 +3 1022 848.201 841.99 35.2174 20.6394 -11.9038 62.4038 +4 1022 852.488 846.074 27.9442 20.3448 -12.1359 60.4275 +3 1062 134.947 86.5898 222.667 -5.27197 0.553323 8.01481 +4 1062 70.6845 15.0658 226.94 -5.20431 0.522345 6.96842 +3 1071 265.903 252.246 161.042 -13.5167 -0.464597 28.3795 +4 1071 254.332 240.708 157.412 -14.0063 -0.608844 28.4495 +5 1071 242.989 228.919 158.415 -13.9952 -0.551273 27.5474 +3 1072 182.405 132.976 230.072 -4.64194 0.621797 7.84103 +4 1072 124.878 68.1168 235.204 -4.58674 0.590041 6.82821 +3 1077 176.819 151.281 184.028 -9.10202 0.235028 15.1764 +4 1077 148.365 121.241 181.416 -9.13347 0.169557 14.2893 +3 1078 225.687 180.301 232.976 -4.5432 0.711551 8.53953 +4 1078 178.251 127.429 237.938 -4.55867 0.687896 7.62621 +5 1078 119.148 61.934 249.406 -4.60421 0.718704 6.77413 +3 1080 317.013 306.984 127.253 -15.6685 -2.44234 38.6449 +4 1080 309.803 299.618 121.822 -15.8088 -2.69137 38.0532 +3 1081 413.033 399.157 128.947 -7.60813 -1.69975 27.9329 +4 1081 406.542 392.388 123.699 -7.70467 -1.86545 27.3829 +5 1081 400.624 385.96 122.794 -7.65365 -1.83379 26.4311 +3 1082 413.033 399.157 128.947 -7.60813 -1.69975 27.9329 +4 1082 406.542 392.388 123.699 -7.70467 -1.86545 27.3829 +5 1082 400.624 386.224 122.794 -7.79388 -1.86739 26.9154 +6 1082 393.486 378.395 123.306 -7.6909 -1.76361 25.6824 +3 1083 384.865 372.169 158.806 -9.50629 -0.594356 30.5266 +4 1083 378.566 365.088 154.424 -9.20601 -0.734514 28.7562 +5 1083 371.422 358.599 155.172 -9.97548 -0.740675 30.2249 +6 1083 364.915 350.51 156.882 -9.12252 -0.595565 26.9053 +7 1083 356.955 342.697 159.057 -9.5166 -0.519799 27.1831 +8 1083 348.448 332.926 159.007 -9.03627 -0.479191 24.9702 +9 1083 339.944 324.025 157.024 -9.09759 -0.534157 24.3467 +10 1083 329.671 314.275 154.062 -9.76512 -0.655647 25.174 +11 1083 320.052 303.269 152.276 -9.26596 -0.658622 23.0935 +3 1101 492.324 488.13 179.33 -15.0149 0.829406 92.411 +4 1101 491.408 487.083 175.423 -14.673 0.31909 89.6066 +5 1101 491.132 487.082 175.858 -15.7091 0.398474 95.7099 +6 1101 490.707 486.305 178.201 -14.5017 0.652361 88.0382 +7 1101 489.997 485.677 180.844 -14.8651 0.993452 89.7085 +3 1102 499.181 492.411 195.056 -8.75832 1.7617 57.2525 +4 1102 498.317 491.409 191.091 -8.64911 1.41797 56.0998 +5 1102 497.156 490.319 192.103 -8.83145 1.51237 56.6905 +3 1103 528.245 516.024 213.816 -3.5741 1.80043 31.7146 +4 1103 526.582 513.762 210.799 -3.47646 1.58976 30.2301 +5 1103 524.564 510.849 212.459 -3.32876 1.5511 28.2584 +6 1103 522.193 508.047 216.114 -3.31768 1.64275 27.3998 +7 1103 519.793 505.644 220.108 -3.40782 1.79393 27.392 +3 1105 496.149 486.608 162.613 -6.38432 -0.576502 40.6184 +4 1105 493.036 483.734 158.277 -6.729 -0.841803 41.6675 +5 1105 491.332 481.185 157.729 -6.25856 -0.800675 38.1958 +3 1110 682.87 677.512 154.334 7.34946 -1.8566 72.3344 +4 1110 684.533 678.989 149.337 7.2651 -2.2789 69.9187 +3 1111 615.692 609.584 161.866 0.539311 -0.966286 63.4507 +4 1111 616.322 610.113 157.237 0.585035 -1.35108 62.4228 +3 1115 646.931 637.023 184.872 2.02598 0.651513 39.1153 +4 1115 648.247 637.663 180.713 1.96338 0.398843 36.6173 +5 1115 650.093 639.671 180.829 2.08923 0.411081 37.1905 +6 1115 652.095 641.188 182.991 2.09481 0.499244 35.5343 +3 1117 683.813 671.84 129.977 3.33128 -1.92362 32.3706 +4 1117 684.83 673.708 124.37 3.63511 -2.3415 34.8458 +5 1117 689.174 676.183 122.329 3.2919 -2.08908 29.8339 +6 1117 691.624 679.256 122.767 3.56417 -2.17535 31.3372 +3 1119 560.345 555.261 183.443 -5.19987 1.11879 76.2362 +4 1119 560.161 555.01 179.427 -5.15096 0.685418 75.2381 +5 1119 560.494 555.278 179.708 -5.05252 0.705807 74.3005 +6 1119 560.579 555.196 181.982 -4.88681 0.910729 71.9892 +7 1119 560.589 554.957 184.694 -4.67047 1.12924 68.8162 +8 1119 560.471 554.819 185.295 -4.6647 1.18223 68.5658 +9 1119 560.534 554.986 184.117 -4.74657 1.09043 69.858 +10 1119 560.349 554.781 182.184 -4.74711 0.900043 69.6037 +3 1121 578.875 575.557 156.674 -4.96669 -2.61906 116.793 +4 1121 579.038 575.396 152.432 -4.50193 -3.01217 106.426 +5 1121 579.537 576.041 152.303 -4.61274 -3.15752 110.861 +3 1136 757.311 730.269 224.897 2.93486 1.03375 14.3322 +4 1136 768.794 741.31 223.852 3.11216 0.996742 14.1021 +5 1136 783.084 750.819 227.056 2.88886 0.902363 12.0123 +3 1142 951.843 931.935 130.115 9.23562 -1.1532 19.4688 +4 1142 970.447 949.351 122.638 9.18884 -1.27859 18.3716 +5 1142 991.158 969.135 118.582 9.3074 -1.32372 17.5987 +3 1148 868.844 855.402 143.788 10.3611 -1.16149 28.8328 +4 1148 878.222 864.408 137.688 10.4468 -1.36741 28.0566 +5 1148 888.997 874.72 135.445 10.5134 -1.40746 27.1467 +6 1148 900.161 885.128 135.336 10.3834 -1.34054 25.781 +3 1149 933.819 914.377 132.591 8.95898 -1.11244 19.9354 +4 1149 950.809 930.375 125.434 8.97035 -1.24651 18.9669 +5 1149 970.217 948.657 121.606 8.98551 -1.27682 17.9766 +6 1149 991.355 968.207 119.854 8.85938 -1.22985 16.7429 +7 1149 1014.99 990.332 118.819 8.83225 -1.17715 15.7186 +8 1149 1041.57 1015.51 115.886 8.90479 -1.17423 14.8725 +9 1149 1071.59 1044.46 110.88 9.14892 -1.22719 14.2876 +10 1149 1106.25 1076.84 104.181 9.07286 -1.25444 13.1801 +11 1149 1145.91 1114.19 97.6875 9.08347 -1.27301 12.2198 +3 1152 968.746 949.506 165.762 10.0278 -0.198007 20.1439 +4 1152 987.742 967.556 159.535 10.0635 -0.354428 19.2003 +3 1155 927.41 864.445 231.18 2.71158 0.497581 6.15543 +4 1155 986.515 911.209 236.911 2.68879 0.456913 5.14665 +3 1183 183.949 133.272 269.913 -4.51119 1.02876 7.64783 +4 1183 124.397 66.6161 280.922 -4.51022 1.00463 6.70764 +3 1184 183.949 133.272 269.913 -4.51119 1.02876 7.64783 +4 1184 124.397 66.6161 280.922 -4.51022 1.00463 6.70764 +3 1185 211.938 164.315 272.531 -4.48479 1.12426 8.13827 +4 1185 160.94 107.173 282.525 -4.4819 1.09566 7.20847 +5 1185 95.1345 33.5235 300.895 -4.48497 1.11631 6.29067 +3 1203 416.102 374.778 307.151 -2.51466 1.74566 9.37894 +4 1203 395.18 347.133 318.223 -2.39666 1.62516 8.06646 +3 1204 398.67 349.985 327.288 -2.3268 1.70391 7.96092 +4 1204 371.527 317.991 343.569 -2.38829 1.71287 7.23954 +3 1211 426.761 376.16 332.678 -1.94046 1.69659 7.65935 +4 1211 402.571 345.037 350.99 -1.93249 1.66311 6.73643 +3 1216 595.253 570.739 252.114 -0.313475 1.73674 15.8103 +4 1216 593.97 568.266 252.142 -0.325779 1.6569 15.0782 +5 1216 594.393 566.459 258.346 -0.291649 1.64396 13.8748 +6 1216 595.211 564.038 267.989 -0.24724 1.63929 12.4329 +7 1216 593.906 561.679 275.928 -0.260904 1.71801 12.0264 +3 1218 574.996 522.624 334.345 -0.354496 1.65631 7.40039 +4 1218 570.559 511.208 353.498 -0.352976 1.63492 6.53027 +3 1225 699.719 673.039 256.025 1.81519 1.6745 14.5268 +4 1225 706.662 678.174 257.216 1.83087 1.59064 13.6045 +5 1225 715.152 684.614 263.241 1.85728 1.58983 12.6912 +3 1227 727.899 693.655 279.055 1.85628 1.66587 11.3181 +4 1227 738.468 701.603 283.345 1.87831 1.60995 10.5134 +5 1227 752.314 712.618 293.744 1.9317 1.63584 9.76355 +6 1227 769.66 724.199 308.793 1.89172 1.60623 8.52556 +7 1227 788.753 738.407 327.071 1.91185 1.64536 7.69818 +3 1230 807.493 755.119 293.232 2.03003 1.23461 7.40018 +4 1230 836.405 777.064 305.514 2.05339 1.20083 6.5313 +5 1230 875.752 806.322 327.097 2.05941 1.19331 5.58222 +3 1235 860.228 795.502 255.48 2.08026 0.685703 5.98793 +4 1235 908.975 831.676 266.045 2.08064 0.647582 5.01395 +5 1235 974.737 884.69 287.811 2.17835 0.685741 4.3041 +4 1264 182.877 157.484 65.35 -9.02565 -2.27404 15.2628 +5 1264 155.892 129.263 60.1074 -9.151 -2.27423 14.5543 +6 1264 125.522 97.1212 55.5513 -9.15488 -2.21861 13.6468 +7 1264 91.1756 60.6842 49.693 -9.13207 -2.16966 12.7109 +8 1264 51.0493 18.3713 39.8911 -9.1806 -2.1856 11.8604 +4 1270 839.905 833.095 32.5549 18.1697 -11.0668 56.9151 +5 1270 844.218 837.435 29.6839 18.5839 -11.3384 57.1425 +6 1270 848.132 841.119 27.0998 18.2735 -11.164 55.2661 +4 1289 385.877 349.211 286.86 -3.2769 1.67017 10.5704 +5 1289 365.454 325.234 299.016 -3.26007 1.68492 9.63626 +4 1294 713.601 682.341 262.787 1.78781 1.54538 12.3987 +5 1294 723.575 689.808 269.942 1.81373 1.54445 11.478 +6 1294 734.804 697.78 280.251 1.81705 1.55812 10.4681 +7 1294 747.957 707.57 293.089 1.84071 1.59913 9.59651 +8 1294 763.701 718.865 306.225 1.84665 1.59781 8.64417 +9 1294 783.127 733.222 320.538 1.86819 1.5896 7.76626 +10 1294 807.536 750.452 338.359 1.86292 1.55737 6.7895 +4 1312 259.97 246.586 114.883 -14.0309 -2.32667 28.9592 +5 1312 249.448 236.31 113.971 -14.7227 -2.40738 29.4992 +4 1322 341.525 327.014 58.9578 -9.92209 -4.2162 26.7098 +5 1322 333.288 318.204 56.2269 -9.83859 -4.15333 25.6954 +4 1329 337.085 322.981 73.7054 -10.3773 -3.77612 27.4801 +5 1329 328.16 313.786 71.0786 -10.5157 -3.80327 26.9633 +6 1329 318.82 303.547 70.0138 -10.2256 -3.61698 25.3771 +7 1329 308.733 293.086 68.9814 -10.3274 -3.56595 24.7704 +4 1331 359.297 346.219 105.078 -10.2792 -2.78382 29.6363 +5 1331 351.789 338.495 103.44 -10.4151 -2.80463 29.1534 +6 1331 344.145 329.18 102.892 -9.52652 -2.51114 25.8981 +4 1337 370.658 354.815 16.7176 -8.09976 -5.29369 24.4632 +5 1337 361.564 346.418 11.4744 -8.79557 -5.72359 25.5905 +4 1342 472.274 456.906 23.2156 -4.79833 -5.23011 25.219 +5 1342 467.42 451.522 18.1563 -4.80253 -5.22684 24.3789 +6 1342 462.412 446.149 14.7885 -4.86009 -5.22072 23.8315 +4 1346 486.831 473.484 124.76 -4.93932 -1.9356 29.0389 +5 1346 483.51 469.708 123.618 -4.90573 -1.91623 28.0816 +6 1346 479.931 465.451 124.368 -4.80889 -1.79871 26.7672 +7 1346 475.979 461.01 125.332 -4.79353 -1.70533 25.8924 +8 1346 471.856 456.39 123.932 -4.78261 -1.69912 25.0599 +9 1346 467.427 451.666 120.613 -4.844 -1.78041 24.5906 +4 1348 439.433 423.927 71.0036 -5.89342 -3.52825 24.9952 +5 1348 433.025 417.863 67.4245 -6.25409 -3.73506 25.562 +6 1348 426.906 411.233 66.135 -6.26006 -3.65757 24.7292 +7 1348 420.167 404.358 64.6403 -6.43525 -3.67693 24.5167 +4 1349 483.129 468.76 84.1126 -4.72655 -3.31756 26.9744 +5 1349 479.657 464.162 81.1447 -4.50332 -3.17928 25.0135 +6 1349 475.555 459.648 80.1565 -4.52517 -3.13029 24.3655 +7 1349 470.688 455.436 79.4999 -4.89057 -3.28762 25.4101 +8 1349 465.764 450.884 76.1377 -5.19061 -3.4912 26.0456 +4 1350 449.548 434.715 88.5968 -5.79431 -3.05112 26.1283 +5 1350 444.181 429.185 86.3221 -5.92381 -3.09955 25.8453 +4 1353 526.63 512.952 47.5809 -3.25658 -4.91941 28.3344 +5 1353 524.218 509.911 43.6821 -3.20421 -4.84986 27.0907 +4 1355 420.93 406.178 52.2388 -6.86828 -4.39178 26.2723 +5 1355 414.6 399.655 48.8784 -7.00717 -4.4559 25.9333 +6 1355 407.999 391.638 46.9964 -6.61719 -4.13189 23.688 +7 1355 401.156 383.586 45.0378 -6.37128 -3.90759 22.0588 +8 1355 393.535 375.18 40.1255 -6.32201 -3.88433 21.1159 +9 1355 384.543 366.008 32.4742 -6.52101 -4.06824 20.9103 +10 1355 375.238 356.223 24.6263 -6.61934 -4.18727 20.3827 +4 1356 433.52 418.692 61.3856 -6.37724 -4.03807 26.1385 +5 1356 427.709 412.434 58.0977 -6.39501 -4.03555 25.3738 +6 1356 421.459 405.459 56.4312 -6.31511 -3.90867 24.2242 +7 1356 414.795 398.228 54.678 -6.31487 -3.83164 23.3945 +8 1356 407.47 390.552 50.2229 -6.41638 -3.89357 22.909 +9 1356 400.117 382.253 43.5698 -6.29738 -3.88724 21.6948 +10 1356 391.345 373.518 35.6975 -6.57481 -4.13254 21.74 +11 1356 382.27 363.671 28.336 -6.5645 -4.17392 20.8392 +12 1356 372.442 352.595 21.2322 -6.41751 -4.1036 19.5282 +13 1356 362.632 340.15 14.2982 -5.8996 -3.78823 17.239 +4 1358 663.844 650.793 62.1679 2.23427 -4.55565 29.6973 +5 1358 666.305 652.757 58.226 2.24985 -4.54477 28.6076 +4 1363 566.659 561.228 104.697 -4.24335 -6.74148 71.3686 +5 1363 566.829 561.601 103.973 -4.38994 -7.07652 74.1279 +4 1364 566.659 561.228 104.697 -4.24335 -6.74148 71.3686 +5 1364 566.829 561.601 103.973 -4.38994 -7.07652 74.1279 +6 1364 566.826 561.384 104.959 -4.2175 -6.7009 71.2117 +4 1365 678.241 669.681 16.872 4.30974 -9.78772 45.2758 +5 1365 680.025 671.435 13.325 4.40618 -9.97523 45.1172 +6 1365 681.82 672.868 11.996 4.33624 -9.65286 43.2984 +7 1365 683.789 674.766 11.0718 4.4191 -9.63135 42.9552 +8 1365 686.125 676.818 7.97833 4.41872 -9.51518 41.6408 +4 1367 614.695 602.195 68.0845 0.220701 -4.50214 31.0058 +5 1367 615.443 602.166 64.9201 0.238039 -4.36663 29.1909 +6 1367 616.073 601.904 64.3107 0.246942 -4.11498 27.3541 +4 1368 587.964 584.344 99.6874 -3.20426 -10.8562 107.059 +5 1368 588.303 584.635 98.8302 -3.1128 -10.8399 105.661 +4 1369 664.859 652.114 117.908 2.33073 -2.31585 30.4109 +5 1369 667.437 654.325 116.187 2.37115 -2.32156 29.5603 +6 1369 669.992 656.292 116.198 2.36948 -2.22143 28.2906 +7 1369 672.609 658.511 116.901 2.40232 -2.13194 27.4922 +4 1371 638.891 627.56 86.2246 1.39054 -4.10688 34.2063 +5 1371 641.188 628.908 84.1821 1.38352 -3.87871 31.5617 +6 1371 642.623 630.568 83.711 1.47327 -3.97211 32.1509 +4 1379 695.067 683.177 116.574 3.863 -2.5426 32.5971 +5 1379 698.357 686.125 114.58 3.89931 -2.55894 31.6842 +6 1379 701.414 688.812 114.583 3.91542 -2.48387 30.7565 +7 1379 704.79 691.805 113.827 3.93916 -2.4416 29.8458 +4 1381 698.702 688.35 123.612 4.62554 -2.55512 37.4398 +5 1381 702.099 691.468 122.263 4.67559 -2.55614 36.4558 +6 1381 706.067 694.264 123.014 4.39201 -2.26819 32.8368 +4 1387 904.163 892.22 21.3687 13.2493 -6.81278 32.4499 +5 1387 913.773 901.626 15.4111 13.4523 -6.96213 31.9064 +4 1388 971.663 956.01 62.7587 12.4255 -3.77788 24.7593 +5 1388 987.273 970.573 56.7972 12.1497 -3.73312 23.2092 +4 1391 951.304 930.826 109.817 8.96395 -1.65346 18.9259 +5 1391 970.439 948.971 105.12 9.02961 -1.69479 18.0537 +4 1392 914.962 896.086 115.108 8.69082 -1.64327 20.5327 +5 1392 930.797 910.888 111.18 8.6667 -1.66392 19.4664 +4 1395 873.948 864.367 29.8495 14.8232 -8.01769 40.4537 +5 1395 882.581 871.879 22.8676 13.7032 -7.52791 36.2144 +6 1395 890.545 879.175 19.5899 13.2746 -7.24067 34.0877 +4 1400 869.11 856.88 49.4908 11.3998 -5.41827 31.6908 +5 1400 878.448 863.993 45.125 9.99256 -4.74673 26.8141 +4 1401 983.166 966.615 29.5373 12.1252 -4.65128 23.4172 +5 1401 999.535 982.371 20.6076 12.2043 -4.76456 22.5806 +4 1408 991.653 970.639 109.128 9.76656 -1.62888 18.443 +5 1408 1013.62 991.577 104.149 9.84809 -1.67455 17.5861 +6 1408 1037.77 1014.34 101.091 9.81542 -1.64495 16.539 +7 1408 1064.18 1039.67 98.9347 9.96037 -1.6195 15.8082 +8 1408 1094.28 1068.23 94.644 9.99389 -1.61253 14.8766 +4 1415 1027.62 998.908 81.3012 7.82131 -1.71282 13.499 +5 1415 1060.87 1029.59 72.9485 7.74961 -1.7155 12.3897 +6 1415 1098.48 1064.92 65.4033 7.82456 -1.71961 11.5473 +4 1446 137.795 93.7093 203.969 -5.74802 0.379108 8.79129 +5 1446 82.3853 34.1208 210.237 -5.86708 0.416049 8.03022 +4 1458 193.027 142.707 226.679 -4.44632 0.574566 7.70213 +5 1458 138.444 83.6562 235.782 -4.61889 0.616955 7.07408 +4 1459 270.918 257.885 129.738 -13.958 -1.77713 29.74 +5 1459 261.033 251.484 129.877 -19.6072 -2.41779 40.5919 +4 1463 259.651 246.746 143.761 -14.564 -1.21094 30.032 +5 1463 249.286 236.004 144.187 -14.5707 -1.15939 29.1814 +6 1463 238.204 224.303 146.576 -14.3491 -1.01537 27.8801 +4 1466 160.221 133.474 190.698 -9.02412 0.358371 14.4907 +5 1466 130.109 102.127 193.937 -9.20348 0.404703 13.8506 +4 1471 173.357 119.425 220.026 -4.34443 0.469814 7.18628 +5 1471 109.872 53.2002 229.942 -4.73616 0.541098 6.83891 +4 1474 320.685 314.416 174.53 -24.7494 0.143634 61.8181 +5 1474 317.289 311.287 176.116 -26.1587 0.291941 64.579 +6 1474 313.908 307.311 179.086 -24.0705 0.507343 58.7443 +7 1474 309.992 303.2 181.843 -23.6902 0.710892 57.0604 +4 1477 353.912 324.603 214.38 -4.6853 0.76106 13.2238 +5 1477 335.783 303.986 218.721 -4.62491 0.774835 12.1889 +6 1477 314.116 279.373 225.58 -4.56775 0.815174 11.1554 +7 1477 288.18 250.776 233.04 -4.61524 0.86432 10.3618 +8 1477 257.704 216.725 239.49 -4.61216 0.873472 9.45799 +9 1477 220.923 175.473 245.025 -4.59308 0.852949 8.52747 +4 1480 334.221 303.808 200.723 -4.86294 0.492208 12.7436 +5 1480 313.786 279.297 204.262 -4.60656 0.489176 11.2377 +6 1480 287.623 251.683 209.595 -4.81158 0.549127 10.7839 +4 1486 429.768 410.128 203.086 -4.9172 0.826821 19.7337 +5 1486 422.229 401.153 205.682 -4.7745 0.836685 18.3898 +4 1487 523.031 513.286 127.837 -4.76984 -2.48153 39.7744 +5 1487 521.638 511.762 127.918 -4.78246 -2.44429 39.2477 +6 1487 520.168 509.821 129.381 -4.64075 -2.25691 37.4587 +7 1487 517.999 508.097 130.224 -4.96671 -2.31249 39.1399 +4 1491 428.56 407.997 201.977 -4.72809 0.760757 18.8482 +5 1491 420.178 398.645 204.206 -4.72431 0.782109 17.9995 +6 1491 410.363 387.768 208.389 -4.7356 0.844802 17.1535 +7 1491 400.048 375.936 213.181 -4.66736 0.898379 16.074 +8 1491 387.936 363.15 215.975 -4.803 0.934514 15.6371 +4 1493 452.269 439.836 190.543 -6.79512 0.764187 31.1713 +5 1493 449.669 434.888 191.828 -5.81046 0.689533 26.2209 +6 1493 444.673 431.437 195.156 -6.69131 0.905041 29.281 +4 1494 548.425 542.072 136.297 -5.16928 -3.09108 61.0104 +5 1494 548.248 541.889 136.394 -5.17908 -3.07981 60.9495 +4 1500 693.662 681.709 128.707 3.77949 -1.98391 32.4252 +5 1500 697.195 685.214 126.825 3.9289 -2.06358 32.348 +6 1500 700.311 688.2 126.973 4.02489 -2.03484 32.0005 +7 1500 704.033 690.921 128.193 3.87011 -1.82955 29.5577 +8 1500 708.193 694.163 127.365 3.7762 -1.74155 27.624 +9 1500 712.556 698.159 124.644 3.84277 -1.79869 26.9203 +10 1500 717.128 702.121 121.009 3.8504 -1.85578 25.8274 +11 1500 721.807 706.258 117.995 3.87761 -1.89511 24.9256 +12 1500 726.66 710.316 115.661 3.84858 -1.87968 23.7137 +13 1500 732.501 715.346 113.379 3.84949 -1.86226 22.5924 +4 1504 557.659 553.751 166.094 -7.13398 -0.92923 99.1788 +5 1504 557.891 554.052 166.136 -7.23024 -0.940049 100.969 +6 1504 558.015 554.362 168.231 -7.57911 -0.679701 106.095 +4 1505 661.012 644.983 218.753 1.72428 1.53816 24.18 +5 1505 664 647.276 220.355 1.74856 1.52567 23.1747 +6 1505 667.286 649.492 224.278 1.74257 1.55232 21.7807 +7 1505 671.059 652.238 229.115 1.75523 1.6057 20.593 +8 1505 674.433 655.333 231.961 1.82443 1.66225 20.2915 +9 1505 678.002 658.323 233.245 1.86816 1.64838 19.6945 +4 1506 687.033 666.433 231.05 2.0201 1.51744 18.8138 +5 1506 692.237 670.428 234.133 2.0363 1.50927 17.771 +6 1506 698.19 675.076 239.285 2.05966 1.54375 16.7675 +7 1506 704.239 679.821 245.722 2.08279 1.60297 15.8725 +8 1506 711.495 685.337 250.628 2.09323 1.59706 14.8166 +9 1506 719.31 691.266 254.591 2.10212 1.56555 13.82 +4 1509 616.543 611.004 177.916 0.677267 0.490902 69.9781 +5 1509 617.733 612.144 178.023 0.785559 0.496785 69.3438 +6 1509 618.165 612.935 180.642 0.883935 0.800032 74.1167 +7 1509 619.125 613.322 182.805 0.885419 0.921146 66.7882 +8 1509 619.839 613.905 183.532 0.930433 0.966462 65.3046 +9 1509 620.803 615.114 182.091 1.06165 0.872163 68.1259 +10 1509 621.393 615.74 180.204 1.12446 0.698432 68.5614 +11 1509 622.275 616.151 179.272 1.11528 0.562961 63.2857 +12 1509 622.911 616.961 178.836 1.20534 0.540052 65.1384 +13 1509 623.772 617.77 178.901 1.27185 0.54113 64.5662 +4 1510 662.567 650.24 152.422 2.30984 -0.890362 31.4417 +5 1510 665.098 652.758 151.64 2.41756 -0.923436 31.4081 +6 1510 667.452 654.707 152.959 2.4399 -0.838477 30.4093 +7 1510 669.864 656.824 154.779 2.48413 -0.74455 29.7223 +4 1524 709.607 695.341 204.379 3.76716 1.18705 27.1686 +5 1524 714.444 699.695 205.183 3.81989 1.17743 26.2783 +6 1524 719.962 703.927 208.251 3.69834 1.18576 24.1705 +7 1524 725.052 708.406 212.088 3.72676 1.26603 23.2828 +8 1524 730.557 713.179 214.037 3.73986 1.2729 22.3016 +9 1524 736.682 718.73 214.396 3.80366 1.24298 21.5892 +10 1524 743.402 724.598 214.177 3.82331 1.1804 20.6112 +4 1528 926.558 906.217 141.308 8.37085 -0.833033 19.0533 +5 1528 944.101 923.195 138.512 8.59595 -0.882406 18.5397 +6 1528 963.018 940.9 137.985 8.58409 -0.846826 17.5232 +4 1530 845.45 830.866 150.377 8.68796 -0.827824 26.5746 +5 1530 855.267 840.217 148.524 8.76947 -0.868359 25.7522 +4 1531 869.758 855.055 158.013 9.50637 -0.542233 26.3614 +5 1531 880.526 865.563 156.431 9.72721 -0.589538 25.9018 +6 1531 892.02 876.29 157.066 9.64535 -0.539117 24.6387 +7 1531 904.195 887.847 158.736 9.6807 -0.463859 23.7072 +8 1531 917.488 900.229 158.599 9.58402 -0.443668 22.4573 +9 1531 932.171 914.201 156.672 9.64348 -0.483699 21.5681 +10 1531 947.942 929.116 153.865 9.65487 -0.541808 20.5872 +4 1535 915.709 844.116 207.359 2.29697 0.25888 5.41351 +5 1535 982.216 894.669 213.627 2.28647 0.250165 4.42706 +4 1536 943.155 864.817 242.716 2.28741 0.479034 4.94747 +5 1536 1022.96 925.974 257.851 2.28952 0.47073 3.99602 +4 1538 927.661 907.428 132.254 8.44501 -1.07784 19.1555 +5 1538 945.619 924.154 128.675 8.4098 -1.10557 18.0563 +6 1538 964.575 942.033 127.846 8.45961 -1.07249 17.1934 +7 1538 986.131 962.233 127.445 8.46389 -1.02062 16.2174 +8 1538 1010.63 985.158 125.077 8.45777 -1.00753 15.2158 +4 1540 928.895 857.362 214.585 2.39795 0.313366 5.41817 +5 1540 997.485 909.82 221.973 2.37694 0.300967 4.42108 +4 1543 907.306 889.285 134.185 8.87494 -1.1526 21.5069 +5 1543 923.519 904.048 130.788 8.66103 -1.16044 19.9046 +4 1546 1022.92 1001.92 141.888 10.5755 -0.792249 18.4601 +5 1546 1046.8 1024.86 138.654 10.7033 -0.837187 17.6625 +6 1546 1072.8 1049.67 137.511 10.7547 -0.820525 16.7513 +4 1547 1022.92 1001.92 141.888 10.5755 -0.792249 18.4601 +5 1547 1046.8 1024.86 138.654 10.7033 -0.837187 17.6625 +6 1547 1072.8 1049.67 137.511 10.7547 -0.820525 16.7513 +4 1549 1033.2 1012.75 144.713 11.1239 -0.738906 18.9458 +5 1549 1057.34 1035.88 141.681 11.2099 -0.780397 18.0633 +6 1549 1083.72 1060.97 140.869 11.1954 -0.755208 17.0362 +7 1549 1113.01 1089.14 141.112 11.3294 -0.714312 16.2371 +8 1549 1146.4 1121 139.768 11.3563 -0.699907 15.2634 +4 1589 385.877 349.211 286.86 -3.2769 1.67017 10.5704 +5 1589 365.454 325.234 299.016 -3.26007 1.68492 9.63626 +4 1599 479.17 445.01 276.098 -2.05031 1.62346 11.3458 +5 1599 468.667 433.305 285.87 -2.14012 1.71669 10.96 +4 1602 553.902 512.682 297.551 -0.725289 1.62497 9.4026 +5 1602 548.885 503.381 311.991 -0.716245 1.64247 8.51751 +4 1610 570.709 534.624 281.714 -0.578314 1.62045 10.7406 +5 1610 568.388 528.996 292.253 -0.561418 1.62814 9.83895 +4 1619 818.656 763.088 317.578 2.02123 1.39897 6.97472 +5 1619 853.043 788.726 339.877 2.03349 1.39492 6.02603 +4 1622 941.294 860.982 260.357 2.21873 0.585243 4.82584 +5 1622 1022.15 922.783 279.219 2.23036 0.574982 3.90046 +5 1637 392.927 377.696 17.4474 -7.63972 -5.48055 25.4457 +6 1637 385.447 368.913 14.1677 -7.28082 -5.1553 23.4409 +5 1652 699.869 684.711 208.129 3.2002 1.24999 25.5683 +6 1652 704.452 688.599 211.446 3.21532 1.30765 24.4484 +5 1654 1042.54 1020.63 133.069 10.6171 -0.975559 17.6929 +6 1654 1068.18 1044.92 131.828 10.5918 -0.947503 16.6639 +7 1654 1096.74 1072.14 131.68 10.6343 -0.898743 15.7498 +8 1654 1129.13 1103.32 129.6 10.8129 -0.900167 15.0159 +9 1654 1166.62 1139.37 125.395 10.9831 -0.935711 14.226 +10 1654 1208.93 1179.77 119.94 11.0417 -0.974781 13.2922 +5 1658 307.811 271.79 286.816 -4.49974 1.69943 10.7597 +6 1658 280.015 240.392 300.835 -4.46746 1.73497 9.78152 +5 1662 787.466 734.519 331.217 1.80486 1.60659 7.31996 +6 1662 814.937 754.044 356.106 1.81169 1.61651 6.36487 +5 1669 114.006 83.5661 33.2752 -8.74476 -2.46307 12.7326 +6 1669 74.6704 45.9895 27.4996 -10.0177 -2.72227 13.5133 +5 1671 251.787 236.819 74.1286 -12.8385 -3.54271 25.892 +6 1671 239.395 222.356 73.4267 -11.6692 -3.13437 22.746 +7 1671 224.214 207.772 71.9841 -12.5888 -3.29531 23.5718 +5 1678 237.942 222 93.0028 -12.5215 -2.69055 24.3119 +6 1678 224.01 207.477 93.6769 -12.5259 -2.57235 23.4417 +5 1683 344.039 329.41 70.8441 -9.74946 -3.74563 26.4936 +6 1683 335.113 319.5 69.9166 -9.4424 -3.54159 24.8247 +5 1687 400.87 385.392 72.7718 -7.24237 -3.47327 25.0403 +6 1687 393.693 377.366 71.818 -7.10196 -3.32407 23.7385 +7 1687 385.312 369.948 70.2496 -7.83961 -3.58702 25.2248 +8 1687 377.897 361.634 66.8088 -7.65176 -3.50265 23.8322 +9 1687 369.163 352.03 60.7893 -7.53676 -3.51339 22.6212 +5 1689 396.04 380.661 94.8594 -7.45774 -2.72417 25.2017 +6 1689 388.452 372.602 94.3301 -7.49323 -2.66114 24.4526 +5 1690 412.603 397.066 100.968 -6.80961 -2.4854 24.9465 +6 1690 405.561 389.628 100.819 -6.87726 -2.42846 24.3248 +5 1692 357.759 343.012 76.6405 -9.17193 -3.50462 26.2823 +6 1692 349.221 333.952 76.0135 -9.15842 -3.40675 25.383 +7 1692 340.28 324.492 74.9487 -9.16152 -3.33097 24.5484 +5 1700 494.273 480.354 35.7987 -4.44892 -5.28899 27.8443 +6 1700 491.699 476.885 33.5842 -4.27354 -5.04985 26.1626 +7 1700 488.134 472.122 31.2903 -4.07331 -4.74887 24.2046 +8 1700 484.066 467.747 26.2403 -4.1307 -4.82589 23.7499 +9 1700 479.472 463.454 18.9708 -4.36217 -5.16012 24.1951 +10 1700 474.635 458.139 10.3666 -4.3935 -5.29104 23.4953 +5 1707 522.23 507.95 101.157 -3.28479 -2.6968 27.1399 +6 1707 519.682 504.7 100.957 -3.22234 -2.57771 25.869 +7 1707 516.956 501.634 100.864 -3.24649 -2.52381 25.2956 +8 1707 514.085 498.263 98.4742 -3.24126 -2.52513 24.4956 +9 1707 511.158 494.833 94.1553 -3.23779 -2.5895 23.7415 +10 1707 507.793 490.68 88.658 -3.19432 -2.64281 22.6482 +11 1707 504.231 486.416 83.9314 -3.17581 -2.68116 21.7555 +12 1707 499.945 481.166 79.465 -3.13533 -2.67124 20.6384 +13 1707 495.566 475.902 75.2113 -3.11383 -2.66721 19.7096 +5 1708 526.069 512.767 20.0401 -3.37141 -6.17075 29.1363 +6 1708 523.806 510.982 17.1477 -3.59175 -6.52172 30.2214 +7 1708 521.462 507.04 14.2692 -3.28126 -5.9066 26.8742 +5 1710 451.289 436.571 36.4342 -5.77665 -4.97913 26.3351 +6 1710 446.197 430.636 33.8231 -5.63905 -4.79917 24.9066 +7 1710 441.002 425.456 31.2411 -5.82397 -4.893 24.9305 +5 1711 548.341 534.803 53.5746 -2.42909 -4.73288 28.6299 +6 1711 547.02 532.754 51.8198 -2.35476 -4.55722 27.1676 +7 1711 545.775 531.158 50.0561 -2.34391 -4.51251 26.5146 +8 1711 544.02 528.839 45.7643 -2.31889 -4.49667 25.5294 +5 1712 481.524 468.998 65.3079 -5.4906 -4.61195 30.942 +6 1712 478.405 464.791 64.2432 -5.17507 -4.28554 28.4703 +7 1712 474.146 459.934 63.4202 -5.11834 -4.13636 27.2726 +8 1712 469.703 455.226 60.3073 -5.18916 -4.17589 26.7716 +5 1713 494.237 479.548 73.05 -4.21714 -3.64966 26.3854 +6 1713 490.522 475.323 71.9644 -4.20685 -3.56549 25.4995 +5 1716 550.253 535.964 25.8492 -2.22928 -5.52583 27.1222 +6 1716 549.218 534.224 24.0934 -2.16165 -5.32914 25.8481 +7 1716 547.915 532.035 21.4713 -2.08504 -5.12035 24.4052 +5 1717 513.2 498.395 49.2194 -3.49611 -4.48569 26.1787 +6 1717 510.956 495.574 47.2326 -3.44338 -4.38689 25.1972 +5 1718 541.498 528.061 69.6389 -2.72084 -4.12613 28.8442 +6 1718 539.408 525.336 68.4207 -2.67779 -3.98639 27.5423 +5 1719 499.299 486.041 62.1634 -4.46735 -4.48477 29.234 +6 1719 496.322 482.609 60.7704 -4.4356 -4.39041 28.2633 +5 1720 504.281 490.126 101.473 -3.99533 -2.7089 27.3823 +6 1720 501.074 486.322 101.142 -3.95009 -2.61112 26.2722 +7 1720 497.902 482.606 101.209 -3.92114 -2.516 25.3387 +8 1720 494.375 478.624 98.9496 -3.92829 -2.52045 24.6075 +9 1720 490.715 474.574 94.5828 -3.95499 -2.60477 24.0119 +10 1720 486.945 469.712 89.5215 -3.82187 -2.59747 22.4903 +11 1720 482.536 464.857 85.1864 -3.85935 -2.66362 21.9226 +12 1720 477.302 459.105 80.8643 -3.90418 -2.71549 21.2994 +5 1722 488.292 473.582 90.7628 -4.42833 -2.99773 26.3484 +6 1722 484.515 469.295 90.2094 -4.41319 -2.91677 25.4652 +7 1722 480.434 464.821 89.7117 -4.44244 -2.86043 24.8238 +5 1726 676.983 664.213 98.7511 2.83613 -3.1171 30.3511 +6 1726 679.665 666.522 98.1673 2.86521 -3.05242 29.489 +5 1729 589.952 582.634 111.74 -1.43938 -4.48633 52.9676 +6 1729 589.908 582.643 112.643 -1.45294 -4.45167 53.3467 +7 1729 590.68 582.645 112.99 -1.26207 -4.00187 48.2345 +8 1729 590.736 582.792 112.478 -1.2727 -4.0822 48.7855 +5 1735 563.82 553.255 85.7068 -2.32546 -4.4307 36.6841 +6 1735 564.059 555.613 83.6463 -2.89363 -5.67326 45.8869 +7 1735 565.724 555.128 81.1001 -2.22209 -4.65121 36.5763 +5 1736 770.793 736.64 39.6448 2.53585 -2.09508 11.3482 +6 1736 785.372 747.97 29.5178 2.52493 -2.05852 10.3623 +7 1736 803.003 761.762 18.1731 2.51953 -2.01466 9.39777 +5 1738 701.638 688.465 62.2708 3.75446 -4.50895 29.4202 +6 1738 705.168 691.673 60.4286 3.80566 -4.47503 28.7204 +7 1738 708.926 695.252 59.0137 3.90347 -4.47206 28.3446 +8 1738 713.237 698.737 55.7625 3.84056 -4.33744 26.728 +9 1738 718.295 702.99 50.3678 3.81635 -4.29897 25.3242 +5 1739 732.098 719.261 68.0609 5.12735 -4.38482 30.191 +6 1739 736.221 722.951 66.0504 5.12733 -4.32347 29.2082 +5 1741 728.5 721.213 78.2405 8.76741 -6.97419 53.1863 +6 1741 732.858 725.571 77.1863 9.08835 -7.05166 53.1845 +5 1742 824.905 811.378 83.8949 8.5509 -3.53237 28.6507 +6 1742 833.077 818.795 82.2573 8.4062 -3.40722 27.136 +5 1747 728.344 715.536 27.7976 4.98171 -6.08351 30.2605 +6 1747 732.415 721.702 24.2503 6.16032 -7.45142 36.18 +5 1760 899.65 887.992 17.8237 13.3651 -7.14256 33.2427 +6 1760 908.513 896.276 14.7111 13.1228 -6.94181 31.6725 +7 1760 918.089 905.504 11.9901 13.1686 -6.86595 30.7965 +5 1761 958.728 937.035 125.27 8.6457 -1.17822 17.8658 +6 1761 978.932 955.978 123.769 8.64389 -1.14867 16.8851 +7 1761 1001.4 977.189 123.112 8.69412 -1.10368 16.0095 +5 1764 851.888 841.565 105.08 12.61 -3.52673 37.5465 +6 1764 859.557 847.959 104.583 11.5787 -3.162 33.4182 +7 1764 867.809 855.395 104.789 11.1749 -2.94532 31.2223 +5 1766 951.188 937.337 54.1353 13.2488 -4.60407 27.9822 +6 1766 964.383 949.308 50.7745 12.6431 -4.34994 25.7098 +5 1767 992.156 975.121 12.9975 12.0637 -5.04047 22.751 +6 1767 1009.06 991.111 6.88293 11.9565 -4.96731 21.5947 +5 1768 974.095 958.498 54.1005 12.5542 -4.08975 24.849 +6 1768 989.352 972.937 50.1266 12.4285 -4.0162 23.612 +5 1771 1033.3 1011.35 102.242 10.3695 -1.72799 17.6571 +6 1771 1058.38 1035.09 99.1157 10.3532 -1.70097 16.6442 +7 1771 1086.13 1061.79 96.8715 10.5139 -1.67629 15.9182 +8 1771 1117.51 1091.77 92.5275 10.599 -1.67611 15.0557 +5 1772 1033.3 1011.35 102.242 10.3695 -1.72799 17.6571 +6 1772 1058.38 1035.09 99.1157 10.3532 -1.70097 16.6442 +7 1772 1086.13 1061.79 96.8715 10.5139 -1.67629 15.9182 +8 1772 1117.51 1091.77 92.5275 10.599 -1.67611 15.0557 +9 1772 1153.33 1126.22 85.86 10.7732 -1.72352 14.2951 +10 1772 1194.31 1165.06 77.4078 10.7356 -1.7523 13.2468 +5 1773 1058.54 1040.85 28.2019 13.6363 -4.39336 21.9145 +6 1773 1079.81 1061.16 21.8404 13.5468 -4.35037 20.7859 +7 1773 1102.92 1083.63 16.818 13.7357 -4.34421 20.0884 +8 1773 1128.91 1108.71 9.30908 13.8111 -4.34912 19.1877 +5 1774 1065.19 1047.52 31.674 13.849 -4.29122 21.9314 +6 1774 1087.25 1068.31 25.6272 13.5506 -4.17637 20.4678 +5 1775 1079.76 1051.54 65.9494 8.94787 -2.03437 13.7307 +6 1775 1117.33 1085.14 58.1104 8.47242 -1.91454 12.0391 +5 1776 1057.58 1026.21 80.6419 7.67275 -1.57923 12.3571 +6 1776 1095.19 1061.62 73.8964 7.77172 -1.58366 11.547 +7 1776 1139.12 1103.1 67.2889 7.89799 -1.57443 10.7612 +5 1777 1057.58 1026.21 80.6419 7.67275 -1.57923 12.3571 +6 1777 1095.19 1061.62 73.8964 7.77172 -1.58366 11.547 +7 1777 1139.12 1103.1 67.2889 7.89799 -1.57443 10.7612 +5 1778 1090.82 1059.43 96.5786 8.23475 -1.30513 12.3461 +6 1778 1132.22 1097.85 90.5545 8.16753 -1.28608 11.2753 +5 1780 1020.11 997.952 116.873 9.95316 -1.35718 17.4926 +6 1780 1044.42 1021.13 114.565 10.0293 -1.34435 16.6411 +7 1780 1071.64 1046.99 113.32 10.0686 -1.29722 15.7221 +8 1780 1102.47 1076.36 110.014 10.1427 -1.29308 14.8473 +9 1780 1137.98 1110.36 104.185 10.2784 -1.3357 14.0347 +10 1780 1178.25 1148.64 97.0598 10.3149 -1.37475 13.0872 +5 1781 1070 1038.95 70.834 7.96602 -1.76505 12.4833 +6 1781 1108.36 1074.87 64.2635 8.0005 -1.74174 11.5731 +7 1781 1153.33 1117.22 57.4653 8.09035 -1.71679 10.7353 +5 1806 187.932 138.551 235.126 -4.58635 0.677373 7.84869 +6 1806 131.831 75.7331 246.976 -4.57438 0.709741 6.90891 +5 1809 239.846 226.062 150.685 -14.4074 -0.863897 28.1177 +6 1809 227.922 213.416 153.242 -14.1322 -0.726226 26.7188 +7 1809 214.927 199.785 155.236 -13.9994 -0.624992 25.5962 +5 1819 370.837 357.282 148.825 -9.45989 -0.952197 28.5925 +6 1819 363.489 349.293 150.687 -9.3114 -0.838819 27.3032 +7 1819 355.641 341.203 152.679 -9.44658 -0.750573 26.8435 +5 1821 292.593 255.469 220.954 -4.58629 0.695981 10.4402 +6 1821 262.562 221.254 228.697 -4.51214 0.726148 9.38243 +5 1823 404.517 381.366 204.431 -4.7573 0.732645 16.7408 +6 1823 393.507 368.191 210.56 -4.58419 0.800047 15.3096 +7 1823 380.538 352.938 215.228 -4.45708 0.824661 14.0422 +8 1823 365.702 336.542 218.671 -4.49203 0.843974 13.2912 +9 1823 348.553 317.143 220.222 -4.46353 0.810052 12.3392 +10 1823 329.537 295.432 222.597 -4.41029 0.783444 11.3641 +5 1827 471.789 458.02 131.699 -5.37484 -1.60556 28.1493 +6 1827 467.835 453.419 132.636 -5.28084 -1.49858 26.8855 +7 1827 463.457 448.591 133.906 -5.2794 -1.40737 26.0726 +5 1829 439.246 421.204 191.875 -5.07069 0.5663 21.4821 +6 1829 432.383 413.066 195.31 -4.92664 0.624429 20.0634 +7 1829 424.415 403.795 199.344 -4.823 0.690053 18.796 +5 1832 470.123 456.096 148.007 -5.33937 -0.951446 27.6296 +6 1832 465.774 451.505 149.511 -5.41263 -0.878726 27.1616 +5 1834 514.47 508.512 184.066 -8.57353 1.01087 65.0557 +6 1834 512.466 508.278 187.402 -12.4549 1.86614 92.5571 +5 1836 609.859 601.686 127.048 0.0197242 -3.01026 47.4176 +6 1836 610.696 601.854 128.045 0.0690378 -2.72211 43.8328 +7 1836 611.202 602.609 129.598 0.102679 -2.70404 45.105 +8 1836 612.123 602.931 129.036 0.149811 -2.56052 42.1637 +9 1836 612.682 603.769 126.73 0.188182 -2.77985 43.4867 +10 1836 613.516 603.972 123.432 0.22268 -2.7815 40.6089 +11 1836 614.165 604.767 121.331 0.26326 -2.94495 41.2414 +5 1837 561.732 556.025 129.916 -4.5012 -4.04104 67.9067 +6 1837 561.73 555.849 131.435 -4.36844 -3.78297 65.901 +7 1837 561.655 555.784 133.584 -4.38332 -3.59327 66.0216 +8 1837 561.655 555.686 133.282 -4.31148 -3.5615 64.9392 +9 1837 561.732 555.671 131.303 -4.239 -3.68273 63.9504 +10 1837 561.666 555.642 128.594 -4.27122 -3.94714 64.3476 +5 1839 666.623 654.399 175.783 2.50763 0.128702 31.7076 +6 1839 669.283 656.399 177.771 2.49002 0.204982 30.0828 +7 1839 671.792 658.591 180.622 2.5322 0.316074 29.3588 +5 1840 639.833 628.641 180.589 1.45291 0.371229 34.6278 +6 1840 641.288 630.505 182.65 1.58058 0.488017 35.944 +5 1841 589.13 585.286 139.668 -2.85473 -4.6374 100.828 +6 1841 589.648 585.612 141.579 -2.65044 -4.16303 96.0436 +7 1841 590.082 586.06 143.841 -2.60124 -3.87483 96.3643 +8 1841 590.391 586.311 144.051 -2.52295 -3.79119 94.972 +9 1841 591.054 587.063 142.452 -2.49077 -4.09202 97.1159 +10 1841 591.292 587.318 139.99 -2.46921 -4.44223 97.5291 +11 1841 591.857 587.515 138.679 -2.18992 -4.22768 89.2596 +12 1841 592.021 587.831 138.012 -2.2489 -4.46764 92.5187 +13 1841 592.311 588.029 137.85 -2.1638 -4.39118 90.5154 +14 1841 592.681 588.388 138.568 -2.11137 -4.28907 90.262 +15 1841 593.73 589.077 139.715 -1.8273 -3.82549 83.2931 +16 1841 594.726 589.978 140.356 -1.67844 -3.67714 81.6418 +17 1841 595.634 590.922 140.394 -1.58717 -3.69982 82.2413 +18 1841 596.837 591.931 140.715 -1.39307 -3.5191 79.0049 +19 1841 597.93 593.063 140.315 -1.28373 -3.59173 79.646 +20 1841 598.857 593.585 139.413 -1.09055 -3.40743 73.5203 +21 1841 599.806 594.5 138.023 -0.987431 -3.52631 73.0492 +22 1841 600.621 595.281 137.242 -0.899131 -3.58228 72.5799 +23 1841 601.682 596.038 136.836 -0.74959 -3.42755 68.663 +24 1841 602.884 597.203 136.751 -0.631095 -3.41337 68.2189 +5 1845 676.016 659.668 193.247 2.18356 0.670064 23.7075 +6 1845 679.584 662.388 195.938 2.18744 0.721109 22.5396 +7 1845 683.279 665.405 199.366 2.21538 0.796711 21.6832 +8 1845 687.226 668.52 201.148 2.23018 0.812452 20.7187 +9 1845 691.647 672.213 201.364 2.26887 0.788005 19.943 +10 1845 696.308 676.08 200.053 2.30354 0.722232 19.1597 +5 1847 645.165 633.726 200.783 1.67191 1.31145 33.8805 +6 1847 647.013 635.152 203.46 1.69615 1.38608 32.6765 +7 1847 648.664 636.664 206.8 1.75049 1.51956 32.2993 +8 1847 650.721 637.845 208.109 1.71719 1.47077 30.1012 +9 1847 652.59 639.64 207.824 1.78488 1.45052 29.9289 +10 1847 654.614 641.176 206.817 1.80092 1.35756 28.841 +5 1848 664.815 648.592 211.49 1.8295 1.27922 23.8897 +6 1848 667.864 650.628 215.007 1.81696 1.3136 22.4852 +5 1849 669.537 654.561 208.686 2.15127 1.28522 25.8799 +6 1849 672.688 656.874 211.964 2.14429 1.32845 24.5084 +7 1849 675.799 659.417 216.04 2.1719 1.41599 23.6582 +8 1849 678.919 661.559 218.754 2.14618 1.42027 22.3264 +9 1849 682.253 665.399 219.259 2.31688 1.47902 22.9967 +10 1849 686.757 668.158 219.026 2.22957 1.3335 20.839 +11 1849 691.149 671.707 220.213 2.25414 1.30841 19.9344 +12 1849 695.398 674.894 222.483 2.24871 1.30013 18.902 +13 1849 700.536 678.813 225.001 2.24954 1.2894 17.8411 +14 1849 706.516 682.027 228.773 2.1267 1.22655 15.8266 +15 1849 713.047 688.551 233.973 2.26925 1.3402 15.8216 +16 1849 720.557 694.598 238.64 2.2968 1.36126 14.9303 +17 1849 729.335 702.675 242.158 2.41325 1.39633 14.5376 +18 1849 738.704 709.966 248.234 2.41391 1.40897 13.4866 +19 1849 749.463 718.281 254.94 2.41007 1.41406 12.4297 +5 1852 831.855 816.27 171.759 7.66147 -0.0377382 24.8679 +6 1852 841.764 825.377 173.084 7.61165 0.00753939 23.652 +5 1854 803.11 769.852 183.973 3.12605 0.179577 11.6536 +6 1854 821.299 785.298 186.699 3.15925 0.206581 10.7657 +5 1860 699.104 682.832 192.422 2.95598 0.645967 23.8189 +6 1860 703.732 686.758 195.118 2.98005 0.704522 22.8326 +5 1867 962.3 941.342 168.654 9.04092 -0.107656 18.4934 +6 1867 982.1 960.154 169.852 9.11832 -0.0734668 17.6604 +7 1867 1004 980.753 171.887 9.11373 -0.022341 16.6714 +8 1867 1028.91 1003.95 171.686 9.02438 -0.0251254 15.5275 +9 1867 1056.86 1030.64 170.718 9.16475 -0.0437579 14.7836 +10 1867 1088.25 1060.31 168.091 9.20441 -0.0915883 13.8741 +11 1867 1123.48 1094.47 166.821 9.51659 -0.111725 13.3611 +12 1867 1164.69 1132.81 164.56 9.35277 -0.139731 12.1564 +13 1867 1212.49 1178.34 164.22 9.48215 -0.135791 11.3474 +5 1869 970.862 949.156 133.039 8.94089 -0.985281 17.8553 +6 1869 992.381 969.117 132.042 8.83913 -0.942331 16.6599 +7 1869 1015.89 991.642 131.858 8.99981 -0.908014 15.9812 +8 1869 1042.64 1016.58 129.734 8.92511 -0.888623 14.8696 +9 1869 1073.18 1045.61 125.573 9.03399 -0.921317 14.0598 +10 1869 1107.78 1078.36 120.014 9.09596 -0.964694 13.1729 +11 1869 1147.79 1116.38 114.701 9.20588 -0.994659 12.3412 +12 1869 1193.84 1159.88 108.379 9.24185 -1.01984 11.413 +5 1870 899.915 885.543 138.383 10.8515 -1.28827 26.966 +6 1870 911.709 896.649 139.127 10.7765 -1.20289 25.7344 +5 1872 900.012 883.057 151.838 9.20181 -0.665805 22.859 +6 1872 915.79 895.08 151.04 7.94252 -0.565769 18.7141 +7 1872 930.164 911.065 152.895 9.01673 -0.561341 20.2926 +5 1874 918.559 901.164 146.314 9.54151 -0.819534 22.2801 +6 1874 934.997 914.988 146.48 8.73643 -0.708005 19.3698 +5 1879 998.596 976.805 142.539 9.58998 -0.747294 17.7863 +6 1879 1021.55 998.427 141.858 9.57155 -0.720113 16.7632 +7 1879 1046.71 1022.48 142.274 9.69311 -0.678068 15.999 +8 1879 1075.39 1049.65 140.885 9.72115 -0.667148 15.0573 +5 1880 992.39 971.215 167.295 9.71138 -0.141025 18.3035 +6 1880 1014.76 991.783 168.06 9.47198 -0.112072 16.8666 +7 1880 1039.36 1015.23 170.018 9.56692 -0.0631239 16.0605 +8 1880 1067.98 1042.04 170.703 9.49195 -0.0445359 14.94 +9 1880 1098.93 1071.93 169.008 9.73755 -0.0765257 14.3573 +5 1882 989.735 967.903 131 9.35356 -1.02973 17.7522 +6 1882 1012.09 988.946 129.706 9.34413 -1.00162 16.7496 +7 1882 1037.06 1012.56 129.5 9.37374 -0.950626 15.8212 +8 1882 1065.25 1039.26 127.173 9.41813 -0.944109 14.9124 +5 1887 1054.2 1033.62 131.393 11.607 -1.08231 18.8354 +6 1887 1080.39 1058.44 129.9 11.5217 -1.05113 17.6568 +7 1887 1109.31 1085.46 129.523 11.2524 -0.97564 16.2461 +5 1888 1054.2 1033.62 131.393 11.607 -1.08231 18.8354 +6 1888 1080.39 1058.44 129.9 11.5217 -1.05113 17.6568 +7 1888 1109.31 1085.46 129.523 11.2524 -0.97564 16.2461 +5 1890 983.973 962.989 151.623 9.58411 -0.54346 18.4697 +6 1890 1004.51 983.166 151.523 9.93848 -0.536773 18.1566 +7 1890 1027.68 1004.62 152.642 9.74353 -0.471013 16.8143 +8 1890 1054.26 1029.21 152.323 9.53553 -0.440247 15.4716 +5 1894 1023.93 1002.39 145.984 10.3319 -0.669982 17.9908 +6 1894 1047.49 1025.2 145.294 10.5559 -0.664322 17.3922 +7 1894 1072.67 1049.91 144.754 10.9291 -0.663142 17.0276 +5 1916 179.961 128.39 306.289 -4.47461 1.38983 7.51538 +6 1916 120.666 64.0623 328.474 -4.63944 1.47678 6.84716 +5 1917 241.346 195.5 317.66 -4.31414 1.69661 8.45383 +6 1917 197.335 145.683 339.27 -4.28693 1.73065 7.50363 +7 1917 140.195 80.2428 365.806 -4.20536 1.72879 6.46476 +5 1947 629.004 588.391 293.483 0.257175 1.59546 9.54315 +6 1947 632.232 587.914 309.398 0.2748 1.65499 8.74544 +5 1950 813.808 773.088 283.537 2.69429 1.46004 9.51797 +6 1950 837.336 791.955 297.303 2.69606 1.47303 8.54042 +7 1950 866.492 815.279 315.245 2.69485 1.49348 7.5679 +8 1950 903.775 844.908 336.006 2.68466 1.48873 6.58389 +5 1951 771.425 724.374 311.055 1.8479 1.57774 8.23728 +6 1951 793.363 740.116 330.44 1.85419 1.58971 7.27879 +7 1951 821.602 760.245 356.09 1.85632 1.60414 6.3167 +6 1976 390.034 373.181 65.5509 -6.99669 -3.41996 22.9968 +7 1976 382.648 365.711 64.0793 -7.19667 -3.44987 22.8841 +8 1976 374.081 357.683 60.1814 -7.71353 -3.6908 23.6353 +9 1976 365.916 349.681 54.0038 -8.06107 -3.93222 23.8724 +10 1976 356.878 340.791 46.7583 -8.43726 -4.21045 24.0928 +6 1979 478.15 463.917 144.577 -4.95958 -1.06721 27.2319 +7 1979 474.288 459.541 146.173 -4.9271 -0.971818 26.2812 +6 1980 692.421 688.3 158.603 10.8009 -1.85756 94.0521 +7 1980 693.932 689.688 160.892 10.6784 -1.51397 91.3199 +8 1980 695.417 691.19 161.269 10.9091 -1.47203 91.6785 +9 1980 697.198 692.849 159.834 10.8251 -1.60828 89.1243 +6 1986 198.032 149.404 314.142 -4.54581 1.56069 7.97024 +7 1986 145.352 87.7801 335.41 -4.33107 1.51665 6.73198 +6 1990 483.359 435.758 327.917 -1.42413 1.74983 8.14228 +7 1990 468.868 413.732 351.145 -1.37066 1.73697 7.02945 +6 1998 91.3479 61.3802 39.2567 -9.28857 -2.39464 12.933 +7 1998 51.7405 19.4721 31.6723 -9.28565 -2.35016 12.011 +6 2008 255.119 240.962 47.0085 -13.4483 -4.7749 27.377 +7 2008 243.871 230.548 47.0951 -14.7432 -5.07013 29.0897 +6 2015 248.967 235.332 53.1655 -14.205 -4.71496 28.424 +7 2015 237.692 224.262 53.3465 -14.8724 -4.77956 28.8571 +6 2022 375.621 360.153 28.6846 -8.12366 -5.00638 25.0559 +7 2022 367.785 351.637 26.2115 -8.04237 -4.87791 24.0012 +8 2022 359.204 341.888 20.6338 -7.76635 -4.72206 22.383 +9 2022 349.676 331.678 12.7411 -7.75649 -4.77873 21.535 +6 2026 312.958 299.362 96.0535 -11.7178 -3.03416 28.5058 +7 2026 303.885 289.778 96.2216 -11.6388 -2.91785 27.4732 +6 2028 291.797 278.239 113.168 -12.5894 -2.36471 28.5866 +7 2028 282.123 272.317 114.275 -17.9366 -3.20887 39.5249 +6 2029 353.994 339.315 114.403 -9.35234 -2.13898 26.4044 +7 2029 345.414 330.024 114.948 -9.21919 -2.02105 25.1831 +8 2029 336.182 319.996 113.097 -9.07219 -1.98306 23.9447 +9 2029 325.984 309.842 109.139 -9.43675 -2.1203 24.0111 +6 2035 303.049 290.531 45.5233 -13.1523 -5.46372 30.961 +7 2035 293.677 278.665 43.6084 -11.3029 -4.62468 25.8181 +8 2035 283.223 268.122 39.2179 -11.6083 -4.75365 25.6662 +6 2042 405.561 389.628 100.819 -6.87726 -2.42846 24.3248 +7 2042 398.319 381.948 100.642 -6.93112 -2.36937 23.6747 +6 2043 396.249 381.068 103.502 -7.54794 -2.45399 25.5314 +7 2043 389.058 373.302 103.624 -7.51702 -2.36009 24.5977 +6 2045 350.412 335.304 96.4251 -9.21373 -2.71736 25.6536 +7 2045 341.697 326.176 96.2581 -9.27061 -2.65095 24.9721 +8 2045 332.09 316.363 93.8092 -9.47688 -2.69975 24.6439 +6 2046 337.847 321.154 39.2487 -8.74323 -4.29919 23.2179 +7 2046 327.267 310.681 37.3673 -9.14249 -4.38795 23.3681 +8 2046 317.36 300.306 31.3714 -9.2035 -4.45633 22.7265 +9 2046 303.338 284.154 24.5407 -8.57431 -4.15283 20.2033 +10 2046 287.519 268.958 17.2158 -9.31965 -4.50408 20.8809 +11 2046 272.038 253.956 10.1072 -10.0265 -4.83462 21.4343 +6 2047 402.79 386.902 58.4488 -6.99023 -3.86769 24.393 +7 2047 395.674 378.994 56.4471 -6.88772 -3.74864 23.2356 +8 2047 387.888 370.792 52.0791 -6.96477 -3.79467 22.6703 +6 2048 340.438 325.458 88.9231 -9.65044 -3.00968 25.8737 +7 2048 331.19 315.859 88.4885 -9.75306 -2.95587 25.2801 +6 2049 375.187 359.027 18.259 -7.79019 -5.13851 23.9829 +7 2049 366.673 350.408 15.1086 -8.0214 -5.2096 23.829 +6 2051 391.303 375.856 43.8927 -7.58939 -4.48435 25.0899 +7 2051 383.823 367.202 41.769 -7.29513 -4.23628 23.318 +8 2051 375.237 358.24 36.6604 -7.40494 -4.30393 22.8017 +6 2054 513.139 498.333 11.4877 -3.49817 -5.85444 26.1777 +7 2054 510.598 494.296 8.85451 -3.26069 -5.40365 23.7741 +6 2058 475.505 461.094 26.0955 -4.99651 -5.47003 26.8934 +7 2058 471.181 456.445 23.9549 -5.04387 -5.42737 26.3 +8 2058 467.089 451.762 19.9383 -4.99284 -5.3589 25.2861 +6 2059 479.514 465.98 36.4002 -5.16124 -5.41558 28.6364 +7 2059 475.808 461.797 34.3797 -5.12737 -5.30844 27.6603 +6 2060 512.662 497.746 79.9801 -3.4896 -3.34469 25.9849 +7 2060 509.787 494.38 79.15 -3.47844 -3.26687 25.1555 +6 2063 429.293 414.475 39.1107 -6.53456 -4.84812 26.1553 +7 2063 423.449 408.159 37.1539 -6.53855 -4.7675 25.3495 +8 2063 417.256 400.795 32.0456 -6.2751 -4.59476 23.5447 +9 2063 410.459 393.115 24.7107 -6.16613 -4.588 22.346 +10 2063 402.798 383.779 16.2075 -5.83972 -4.42429 20.3789 +11 2063 394.317 374.074 8.19564 -5.71148 -4.36922 19.1461 +6 2064 427.849 411.914 46.3855 -6.12503 -4.26297 24.3214 +7 2064 421.402 404.888 44.1088 -6.12035 -4.1878 23.47 +8 2064 414.665 397.426 39.1905 -6.07273 -4.16484 22.4825 +9 2064 407.374 389.454 32.0309 -6.06069 -4.2213 21.6288 +6 2067 473.023 457.262 72.4456 -4.6533 -3.42202 24.5907 +7 2067 468.035 452.117 70.9058 -4.77557 -3.44013 24.3475 +8 2067 463.028 447.02 66.8419 -4.9168 -3.5572 24.2109 +6 2069 538.074 523.345 20.8788 -2.60692 -5.54225 26.3131 +7 2069 536.577 520.763 17.8969 -2.47898 -5.2634 24.5084 +6 2073 454.699 439.755 86.2852 -5.56658 -3.11177 25.9362 +7 2073 449.834 434.238 85.9411 -5.50112 -2.99338 24.8506 +6 2076 510.207 495.3 58.653 -3.58011 -4.11516 26.0002 +7 2076 507.184 491.841 57.0741 -3.58396 -4.05324 25.2597 +6 2078 536.267 522.393 105.962 -2.83774 -2.58991 27.9365 +7 2078 533.997 520.358 106.53 -2.97603 -2.61219 28.4178 +8 2078 532.278 517.74 104.837 -2.85527 -2.51301 26.6583 +6 2079 489.454 474.843 122.61 -4.41557 -1.84716 26.5267 +7 2079 485.907 470.636 123.229 -4.34943 -1.74555 25.3799 +8 2079 482.099 466.584 121.77 -4.41302 -1.76868 24.9815 +9 2079 478.114 462.048 118.301 -4.39468 -1.82391 24.1236 +6 2080 419.932 404.725 13.2286 -6.69794 -5.63822 25.4859 +7 2080 413.502 397.6 9.92688 -6.62237 -5.50331 24.3719 +6 2084 467.541 452.54 101.329 -5.08526 -2.56112 25.8362 +7 2084 463.237 447.867 101.391 -5.11351 -2.49742 25.2155 +8 2084 458.53 443.329 99.0937 -5.33691 -2.60646 25.4969 +9 2084 453.749 437.78 94.7034 -5.24089 -2.6287 24.2699 +6 2090 666.126 652.438 89.8262 2.21984 -3.25828 28.3154 +7 2090 668.716 654.464 89.4 2.22957 -3.14529 27.194 +8 2090 671.576 656.759 86.7025 2.24828 -3.12321 26.1576 +9 2090 674.867 659.603 82.0994 2.2982 -3.19368 25.3911 +10 2090 678.179 662.121 76.2454 2.29532 -3.23154 24.1353 +11 2090 681.584 664.996 71.5825 2.33227 -3.27933 23.3646 +12 2090 685.4 667.826 66.2498 2.31805 -3.25831 22.0535 +13 2090 689.514 671.156 61.3688 2.33941 -3.26196 21.1116 +14 2090 693.781 674.404 57.4242 2.33472 -3.19985 20.0019 +15 2090 698.951 678.662 53.2746 2.36657 -3.16576 19.1021 +16 2090 704.495 683.086 48.2533 2.38187 -3.12614 18.1028 +17 2090 711.076 688.513 42.3819 2.41684 -3.1062 17.1779 +18 2090 718.205 694.346 36.0791 2.44606 -3.07937 16.2448 +6 2092 657.485 643.168 42.8839 1.79806 -4.87612 27.0701 +7 2092 660.12 644.878 40.5299 1.78186 -4.66333 25.4283 +6 2096 666.141 656.479 17.2601 3.14566 -8.65028 40.1141 +7 2096 667.815 657.844 16.5925 3.13848 -8.41852 38.8725 +8 2096 669.725 659.499 12.597 3.16023 -8.4175 37.8988 +9 2096 671.92 662.026 6.88308 3.38571 -9.011 39.1742 +6 2101 691.715 677.821 70.9974 3.17626 -3.93795 27.8959 +7 2101 695.049 680.952 69.4912 3.2576 -3.93868 27.4945 +8 2101 698.871 684.058 66.0577 3.23862 -3.87266 26.1645 +9 2101 703.247 687.877 60.6209 3.2742 -3.92234 25.2164 +10 2101 707.159 691.82 54.4319 3.41794 -4.14716 25.2684 +6 2102 662.281 648.482 95.5104 2.05226 -3.01071 28.0869 +7 2102 664.557 650.501 95.3702 2.10176 -2.96105 27.5737 +8 2102 667.193 652.528 92.9465 2.11103 -2.92686 26.4286 +9 2102 670.143 655.156 88.5538 2.17145 -3.02151 25.8615 +6 2109 725.93 713.253 98.9409 4.93081 -3.1318 30.5726 +7 2109 730.323 717.166 98.7499 4.93046 -3.02548 29.4585 +8 2109 735.195 721.217 96.4874 4.82809 -2.93472 27.7283 +6 2110 721.969 709.315 108.024 4.77169 -2.75195 30.6285 +7 2110 726.348 713.643 108.477 4.93759 -2.72173 30.5052 +6 2112 709.133 695.995 27.8974 4.07098 -5.92639 29.4993 +7 2112 713.044 699.371 25.362 4.06537 -5.79418 28.3454 +6 2115 723.112 710.791 50.5712 4.95054 -5.33114 31.4568 +7 2115 727.255 714.023 48.5725 4.77761 -5.04493 29.2892 +8 2115 731.946 717.997 44.5132 4.71275 -4.94203 27.7843 +9 2115 737.301 722.6 37.846 4.66722 -4.93269 26.3623 +10 2115 742.45 727.699 29.8792 4.83897 -5.20615 26.2734 +11 2115 748.437 732.679 23.0123 4.73409 -5.10785 24.596 +12 2115 753.953 737.874 15.4455 4.82352 -5.25827 24.1031 +13 2115 761.574 744.197 10.0749 4.69878 -5.03149 22.3027 +6 2119 773.446 737.356 35.8799 2.43927 -2.03871 10.7393 +7 2119 789.662 749.892 25.6815 2.43255 -1.98778 9.74541 +6 2122 900.37 888.794 69.8403 13.4937 -4.77986 33.4795 +7 2122 909.439 897.482 69.2137 13.4717 -4.65592 32.4143 +8 2122 919.29 906.991 66.5722 13.5277 -4.64192 31.5136 +9 2122 929.953 917.339 61.8504 13.6445 -4.72728 30.7279 +10 2122 941.154 927.966 56.1176 13.5061 -4.75477 29.3888 +6 2123 887.868 876.718 91.8122 13.407 -3.90404 34.7588 +7 2123 896.304 884.865 91.6761 13.4651 -3.81199 33.8823 +8 2123 905.486 893.745 89.8416 13.5376 -3.79751 33.0077 +6 2132 975.779 953.16 112.177 8.69707 -1.44097 17.1353 +7 2132 997.97 973.921 110.941 8.67518 -1.38283 16.1156 +8 2132 1023.09 997.506 107.414 8.68155 -1.37382 15.1477 +9 2132 1051.97 1024.85 101.906 8.76145 -1.40505 14.2893 +10 2132 1084.55 1055.29 94.8234 8.71832 -1.43223 13.2436 +11 2132 1121.88 1090.55 87.8273 8.78349 -1.45773 12.3703 +12 2132 1164.54 1131.11 79.399 8.9182 -1.50177 11.5947 +6 2133 1093.99 1059.79 80.1701 7.60818 -1.45565 11.3321 +7 2133 1138.56 1101.64 73.9184 7.69461 -1.43906 10.4951 +6 2136 995.349 979.131 55.1485 12.7781 -3.89862 23.8987 +7 2136 1012.1 994.825 52.6518 12.5194 -3.73844 22.4408 +8 2136 1030.6 1012.7 47.8807 12.6362 -3.75071 21.6548 +6 2145 1113.48 1079.75 80.804 8.02543 -1.466 11.4913 +7 2145 1159.23 1122.86 74.7814 8.11736 -1.4483 10.6554 +6 2150 129.994 101.261 206.034 -8.96513 0.620268 13.4886 +7 2150 95.2696 64.9797 211.426 -9.12024 0.684024 12.7955 +8 2150 55.2378 22.9293 215.039 -9.21597 0.701361 11.996 +6 2154 223.695 177.957 233.783 -4.53168 0.715558 8.4739 +7 2154 177.234 126.478 243.791 -4.57526 0.750721 7.63597 +6 2155 161.288 109.213 233.733 -4.62389 0.627959 7.44261 +7 2155 98.2502 39.2727 245.356 -4.65686 0.660329 6.57157 +6 2156 193.195 143.825 235.685 -4.53017 0.683616 7.85054 +7 2156 137.699 81.8722 246.828 -4.54007 0.711752 6.94238 +6 2159 254.266 241.675 131.339 -15.1573 -1.77109 30.7817 +7 2159 244.366 230.198 133.506 -13.8456 -1.49182 27.3558 +6 2164 376.402 363.022 188.849 -9.36052 0.642144 28.9674 +7 2164 369.542 355.655 192.131 -9.28378 0.745622 27.9089 +6 2165 377.474 363.077 149.646 -8.65886 -0.865856 26.9198 +7 2165 369.887 354.976 151.346 -8.63385 -0.774806 25.9924 +8 2165 361.944 346.18 150.799 -8.43741 -0.751504 24.5861 +9 2165 353.096 337.209 148.376 -8.67085 -0.827598 24.3947 +10 2165 343.61 326.877 145.291 -8.53774 -0.884838 23.1634 +11 2165 333.54 316.168 143.166 -8.53462 -0.917963 22.3102 +6 2169 398.098 373.894 199.807 -4.69289 0.598148 16.0128 +7 2169 386.432 360.839 203.978 -4.68305 0.653234 15.1438 +8 2169 372.261 345.394 206.224 -4.74433 0.667161 14.4258 +9 2169 357.759 330.106 206.882 -4.89115 0.660988 14.0157 +10 2169 339.551 310.992 207.039 -5.07838 0.642954 13.5709 +11 2169 322.138 289.831 208.35 -4.77873 0.590163 11.9964 +6 2174 380.577 365.655 132.075 -8.24294 -1.46797 25.9741 +7 2174 372.699 357.326 133.034 -8.27621 -1.39135 25.2115 +8 2174 364.501 348.565 131.765 -8.26038 -1.38502 24.3214 +9 2174 355.706 339.253 128.553 -8.28761 -1.44632 23.5562 +10 2174 345.822 328.959 124.337 -8.40121 -1.54548 22.9842 +11 2174 335.648 317.784 121.06 -8.23607 -1.55736 21.6955 +6 2175 555.113 549.179 127.683 -4.92903 -4.08929 65.3207 +7 2175 554.742 549.106 129.779 -5.22465 -4.10546 68.77 +6 2177 485.932 471.724 135.2 -4.67409 -1.42362 27.2798 +7 2177 482.179 467.527 136.459 -4.67007 -1.33434 26.4532 +6 2178 485.932 471.724 135.2 -4.67409 -1.42362 27.2798 +7 2178 482.179 467.527 136.459 -4.67007 -1.33434 26.4532 +8 2178 478.19 462.956 135.496 -4.63197 -1.31723 25.4409 +9 2178 474.3 458.421 132.746 -4.57526 -1.35669 24.4067 +10 2178 469.739 453.169 128.953 -4.53246 -1.4231 23.3896 +11 2178 464.87 447.595 126.241 -4.49899 -1.4494 22.4356 +12 2178 459.025 441.184 123.951 -4.5321 -1.4723 21.7232 +13 2178 453.275 434.33 121.676 -4.4312 -1.45107 20.4581 +14 2178 446.693 426.939 120.673 -4.42871 -1.41891 19.6202 +6 2180 520.093 516.041 156.722 -11.8586 -2.13827 95.6386 +7 2180 519.896 515.856 159.134 -11.92 -1.82394 95.9232 +6 2182 453.089 437.552 200.35 -5.40962 0.95062 24.9455 +7 2182 448.227 432.024 204.685 -5.34843 1.05525 23.9201 +6 2183 452.202 435.027 226.76 -4.92127 1.6859 22.5657 +7 2183 445.871 428.354 231.516 -5.01947 1.79886 22.1258 +6 2184 548.876 528.118 240.202 -1.57029 1.74275 18.6711 +7 2184 546.417 524.262 246.717 -1.53089 1.79081 17.4937 +8 2184 543.652 519.988 251.288 -1.49599 1.78034 16.3778 +9 2184 540.859 515.914 254.726 -1.47937 1.76299 15.5373 +6 2188 478.15 463.917 144.577 -4.95958 -1.06721 27.2319 +7 2188 474.288 459.541 146.173 -4.9271 -0.971818 26.2812 +6 2190 452.929 445.482 162.551 -11.2987 -0.743204 52.0487 +7 2190 448.971 443.3 164.716 -15.2095 -0.770715 68.3378 +6 2191 693.774 680.61 138.262 3.43638 -1.41152 29.4423 +7 2191 696.943 683.512 139.528 3.49481 -1.33285 28.857 +6 2193 612.249 606.879 175.354 0.269066 0.25008 72.1724 +7 2193 612.864 607.463 177.862 0.328648 0.498026 71.7557 +6 2194 567.865 551.004 224.507 -1.32828 1.64553 22.9863 +7 2194 566.681 549.449 229.112 -1.33666 1.75373 22.4926 +6 2195 556.191 551.056 151.822 -5.58316 -2.20029 75.484 +7 2195 556.207 550.95 154.163 -5.45152 -1.9098 73.726 +8 2195 556.361 551.141 154.253 -5.47495 -1.91437 74.2571 +9 2195 556.35 551.078 152.558 -5.42143 -2.06788 73.516 +10 2195 556.293 550.476 150.018 -4.91864 -2.10873 66.627 +6 2196 629.382 620.345 132.151 1.17822 -2.41926 42.8861 +7 2196 630.406 621.548 133.77 1.26421 -2.37019 43.7567 +8 2196 632.526 622.298 133.202 1.20613 -2.08239 37.8927 +6 2198 655.119 641.156 127.899 1.75266 -1.72938 27.757 +7 2198 656.668 642.087 128.774 1.73545 -1.62389 26.581 +8 2198 659.225 643.579 127.632 1.70504 -1.55247 24.7704 +6 2199 602.863 597.382 141.459 -0.656162 -3.07647 70.7042 +7 2199 603.442 597.648 143.484 -0.567232 -2.72319 66.9008 +8 2199 604.154 598.042 143.307 -0.475118 -2.59703 63.4184 +9 2199 604.491 598.661 140.839 -0.46697 -2.94958 66.4763 +10 2199 604.831 599.091 137.743 -0.442485 -3.28581 67.5239 +11 2199 605.672 599.634 136.304 -0.345775 -3.25129 64.1837 +6 2202 736.66 722.695 203.648 4.88867 1.18441 27.7524 +7 2202 741.732 727.711 207.191 5.06356 1.31545 27.6423 +8 2202 747.566 732.716 209.083 4.99189 1.31047 26.099 +9 2202 753.526 738.164 209.287 5.03395 1.27391 25.2293 +6 2204 819.131 783.245 211.257 3.13692 0.574829 10.8001 +7 2204 839.894 800.653 217.398 3.15289 0.609734 9.8766 +6 2207 732.641 701.161 246.951 2.10017 1.26433 12.3118 +7 2207 743.342 710.559 254.384 2.19208 1.3359 11.8227 +8 2207 754.588 720.938 260.751 2.31506 1.40308 11.5177 +9 2207 766.369 731.802 265.883 2.43678 1.44565 11.2125 +10 2207 779.744 743.104 271.32 2.49492 1.44351 10.5778 +11 2207 795.713 757.219 279.099 2.59763 1.48257 10.0685 +12 2207 814.604 773.16 288.564 2.65758 1.49972 9.35184 +6 2208 698.504 672.182 251.147 1.81512 1.59775 14.7246 +7 2208 705.416 677.126 258.962 1.82004 1.63494 13.6999 +6 2216 710.672 706.428 153.907 12.798 -2.39813 91.3264 +7 2216 712.456 707.905 156.36 12.143 -1.94645 85.1494 +6 2219 701.519 684.351 186.626 2.87725 0.430897 22.5756 +7 2219 705.7 688.793 189.286 3.05445 0.522055 22.9238 +8 2219 710.226 692.843 189.959 3.11058 0.528541 22.2953 +6 2221 860.834 844.925 162.191 8.484 -0.360038 24.3619 +7 2221 871.739 855.152 164.155 8.49041 -0.281705 23.3663 +8 2221 883.633 866.345 164.232 8.51567 -0.267879 22.4187 +6 2224 918.28 840.415 250.204 2.1297 0.533595 4.9775 +7 2224 988.614 894.735 271.097 2.16885 0.562123 4.12846 +6 2228 1083.72 1060.97 140.869 11.1954 -0.755208 17.0362 +7 2228 1113.01 1089.14 141.112 11.3294 -0.714312 16.2371 +6 2229 1048.35 1025.91 166.854 10.5047 -0.143641 17.2738 +7 2229 1074.8 1051.32 168.894 10.6438 -0.0905984 16.5075 +8 2229 1104.57 1079.74 169.258 10.7077 -0.0777888 15.6078 +9 2229 1138.24 1112.39 167.725 10.9878 -0.106602 14.9961 +6 2260 180.334 129.964 275.35 -4.57734 1.09303 7.69461 +7 2260 120.919 62.8745 292.711 -4.52197 1.10918 6.67725 +6 2262 225.138 178.825 283.781 -4.45866 1.28657 8.36865 +7 2262 178.159 126.354 300.323 -4.47304 1.32168 7.48137 +8 2262 118.237 59.2508 318.462 -4.4742 1.32597 6.57064 +6 2265 192.237 142.664 316.124 -4.52197 1.55243 7.81835 +7 2265 136.55 80.0387 338.376 -4.49604 1.57332 6.85835 +6 2266 181.404 131.843 320.181 -4.64039 1.59675 7.8201 +7 2266 124.051 67.74 342.875 -4.63123 1.62182 6.88271 +6 2271 184.303 133.646 261.37 -4.50928 0.938598 7.65094 +7 2271 126.433 69.1076 276.17 -4.527 0.968097 6.76097 +6 2286 294.289 257.574 272.019 -4.61255 1.45083 10.5564 +7 2286 264.591 225.301 284.195 -4.71624 1.52221 9.86451 +6 2291 514.381 478.379 284.518 -1.42007 1.66603 10.7654 +7 2291 506.691 467.219 297.734 -1.39984 1.69939 9.81879 +8 2291 496.209 452.807 311.609 -1.40284 1.71725 8.92985 +6 2299 579.021 552.404 254.91 -0.616265 1.65591 14.5609 +7 2299 577.931 548.828 263.215 -0.583761 1.66777 13.3173 +8 2299 576.217 545.348 270.066 -0.580187 1.69158 12.5554 +9 2299 574.424 541.123 276.116 -0.566733 1.66563 11.6384 +10 2299 571.805 536.092 282.686 -0.567862 1.65197 10.8526 +11 2299 569.398 530.131 291.621 -0.549379 1.62466 9.87016 +12 2299 566.096 522.695 303.488 -0.537931 1.61681 8.93021 +13 2299 562.35 514.254 318.563 -0.527247 1.62732 8.05832 +14 2299 556.763 503.07 337.935 -0.52817 1.65147 7.21827 +6 2300 571.298 537.447 277.435 -0.607124 1.65948 11.4493 +7 2300 568.571 531.557 289.393 -0.594835 1.69123 10.4711 +8 2300 565.796 524.591 303.428 -0.570496 1.70217 9.40599 +6 2301 561.825 535.499 258.585 -0.973974 1.74927 14.7223 +7 2301 559.785 530.762 266.475 -0.921231 1.73274 13.3542 +8 2301 556.774 525.681 274.139 -0.911885 1.74974 12.4649 +9 2301 553.885 520.097 280.11 -0.885093 1.70512 11.4708 +10 2301 549.485 513.686 287.598 -0.901406 1.72171 10.8265 +11 2301 544.063 504.634 297.939 -0.892291 1.7041 9.82985 +6 2303 672.766 626.493 315.554 0.733723 1.65652 8.3759 +7 2303 681.71 629.301 336.302 0.739495 1.67524 7.39529 +6 2316 826.288 782.277 286.102 2.64513 1.38218 8.80624 +7 2316 853.258 803.686 301.963 2.64065 1.39899 7.81839 +6 2319 723.747 690.921 256.236 1.86855 1.36445 11.8072 +7 2319 733.893 698.378 265.767 1.8805 1.40526 10.913 +8 2319 746.568 707.161 275.059 1.86754 1.39314 9.83514 +9 2319 761.746 718.347 284.083 1.88362 1.37668 8.93047 +10 2319 780.016 732.033 294.288 1.90821 1.35941 8.07739 +6 2320 829.264 785.813 279.014 2.71602 1.31237 8.91976 +7 2320 856.102 807.133 294.273 2.70441 1.3319 7.91482 +8 2320 889.418 834.413 311.567 2.73293 1.35459 7.04609 +9 2320 932.674 869.663 332.006 2.75445 1.35672 6.15089 +6 2321 812.519 776.224 257.326 3.00369 1.25015 10.6784 +7 2321 834.176 794.055 267.988 3.00718 1.27365 9.65997 +7 2345 737.716 723.591 76.5932 4.8737 -3.66072 27.4395 +8 2345 742.823 728.242 73.8079 4.90951 -3.64892 26.5819 +9 2345 748.464 733.469 68.9689 4.97576 -3.7213 25.8464 +7 2348 200.571 185.158 164.427 -14.2537 -0.293703 25.1464 +8 2348 185.651 169.675 164.387 -14.2526 -0.284663 24.2595 +7 2352 473.952 458.957 143.206 -4.8579 -1.06208 25.8478 +8 2352 469.898 454.199 142.44 -4.77882 -1.04068 24.6889 +9 2352 465.247 449.252 139.962 -4.84612 -1.10452 24.2298 +7 2353 479.16 464.811 219.132 -4.88161 1.73243 27.0113 +8 2353 474.831 460.318 221.01 -4.98642 1.7823 26.7048 +9 2353 470.832 455.695 221.247 -4.92306 1.71733 25.6054 +10 2353 466.454 450.801 220.834 -4.91109 1.64658 24.7617 +11 2353 461.684 445.259 221.586 -4.83602 1.5937 23.5967 +12 2353 456.274 439.48 223.051 -4.90266 1.60551 23.0776 +7 2354 458.556 452.625 187.505 -13.6761 1.32696 65.3482 +8 2354 457.425 450.601 187.387 -11.9764 1.14409 56.8011 +7 2373 189.23 171.362 65.4947 -12.6359 -3.22744 21.6909 +8 2373 171.664 154.662 61.0097 -13.8346 -3.53353 22.7958 +9 2373 154.185 136.305 54.8355 -13.6801 -3.54544 21.676 +7 2375 204.974 188.577 105.035 -13.254 -2.22172 23.6371 +8 2375 190.122 172.834 102.714 -13.0326 -2.17937 22.4194 +7 2376 226.959 213.432 114.281 -15.1928 -2.32587 28.6517 +8 2376 214.765 200.617 112.135 -14.9891 -2.30532 27.3946 +9 2376 202.047 187.438 108.043 -14.9835 -2.38299 26.5296 +10 2376 187.768 170.605 102.928 -13.2008 -2.18847 22.582 +11 2376 170.903 153.454 99.3511 -13.5041 -2.2628 22.2126 +7 2380 196.294 180.781 34.3775 -14.3098 -4.7949 24.984 +8 2380 181.532 164.708 28.9245 -13.6655 -4.59518 23.0363 +7 2385 227.686 211.771 22.7174 -12.8883 -5.06713 24.352 +8 2385 214.651 198.502 18.6998 -13.1356 -5.12753 24 +7 2387 243.125 229.758 72.3502 -14.7255 -4.03885 28.9957 +8 2387 232.464 219.68 66.6107 -15.8449 -4.46416 30.3178 +7 2389 346.029 328.781 18.4135 -8.20724 -4.8098 22.4711 +8 2389 335.933 317.806 12.264 -8.10823 -4.75869 21.381 +7 2391 404.772 388.135 31.6923 -6.61171 -4.55752 23.2954 +8 2391 397.218 379.855 26.2419 -6.56938 -4.53586 22.3228 +9 2391 389.103 371.018 18.6022 -6.54782 -4.58147 21.4306 +10 2391 379.909 361.099 9.47332 -6.55818 -4.6657 20.6051 +7 2392 300.114 284.16 57.8377 -10.4189 -3.87255 24.2939 +8 2392 289.006 272.29 53.7301 -10.3006 -3.82792 23.1858 +9 2392 277.214 259.242 47.3994 -9.9334 -3.74969 21.5659 +10 2392 263.163 245.012 39.6095 -10.251 -3.94315 21.3527 +11 2392 248.915 229.996 32.8746 -10.2393 -3.97424 20.4856 +12 2392 233.01 212.79 26.5037 -10.0031 -3.8878 19.1677 +13 2392 215.363 194.805 19.6471 -10.2997 -4.00305 18.8526 +14 2392 197.388 175.319 13.7408 -10.032 -3.8727 17.5617 +15 2392 177.587 154.309 7.08925 -9.96781 -3.82504 16.6496 +7 2393 299.891 284.034 71.3477 -10.4901 -3.43854 24.4422 +8 2393 289.057 271.923 66.2443 -10.0472 -3.34204 22.6191 +9 2393 276.845 259.527 61.2144 -10.3199 -3.46275 22.3801 +10 2393 262.898 244.975 54.6881 -10.3891 -3.54132 21.6238 +11 2393 248.269 229.735 48.6017 -10.4706 -3.60097 20.9109 +7 2396 341.786 326.969 39.8496 -9.70755 -4.82179 26.1578 +8 2396 333.735 318.305 36.2983 -9.60234 -4.75394 25.119 +7 2399 341.697 326.176 96.2581 -9.27061 -2.65095 24.9721 +8 2399 332.09 316.363 93.8092 -9.47688 -2.69975 24.6439 +7 2400 372.05 355.839 98.4407 -7.86979 -2.46566 23.9079 +8 2400 363.45 346.778 95.9434 -7.92907 -2.47788 23.2463 +9 2400 353.724 336.848 90.7656 -8.14344 -2.61293 22.9671 +10 2400 343.609 326.484 84.74 -8.34208 -2.76388 22.6325 +11 2400 333.069 315.136 79.563 -8.28193 -2.79441 21.6127 +12 2400 321.334 302.101 75.7761 -8.04969 -2.71124 20.1515 +13 2400 308.561 288.311 71.6365 -7.98405 -2.68482 19.139 +14 2400 294.231 273.153 67.729 -8.03587 -2.67902 18.3878 +15 2400 279.314 256.843 63.7476 -7.89396 -2.60801 17.2472 +16 2400 262.505 238.975 59.6325 -7.92277 -2.58469 16.4717 +17 2400 244.351 219.643 53.9833 -7.93948 -2.58421 15.686 +7 2401 372.05 355.839 98.4407 -7.86979 -2.46566 23.9079 +8 2401 363.45 346.778 95.9434 -7.92907 -2.47788 23.2463 +7 2402 316.262 301.112 87.151 -10.3992 -3.03871 25.583 +8 2402 306.084 290.382 83.6732 -10.3816 -3.0508 24.6832 +7 2403 331.19 315.859 88.4885 -9.75306 -2.95587 25.2801 +8 2403 321.464 305.409 85.4978 -9.6388 -2.92267 24.1404 +9 2403 310.979 294.47 80.6148 -9.71483 -3.00117 23.4765 +10 2403 299.393 282.067 74.3987 -9.61554 -3.05224 22.3686 +7 2407 525.288 510.077 52.8609 -2.97588 -4.23732 25.4797 +8 2407 522.661 507.292 49.0978 -3.03715 -4.32533 25.2181 +7 2411 525.279 510.634 86.9426 -3.09134 -3.15115 26.4654 +8 2411 522.905 507.538 83.9799 -3.02911 -3.10669 25.2221 +9 2411 520.551 504.697 79.0079 -3.0157 -3.1796 24.4464 +7 2412 477.829 462.197 88.0338 -4.52626 -2.91444 24.7922 +8 2412 473.815 457.298 84.953 -4.41474 -2.85875 23.4661 +9 2412 469.004 452.049 80.0816 -4.45273 -2.939 22.8581 +10 2412 463.69 445.977 74.0752 -4.42364 -2.99556 21.8813 +11 2412 457.791 439.328 68.9725 -4.41537 -3.0222 20.9916 +7 2417 490.804 475.097 90.3469 -4.06122 -2.82159 24.6753 +8 2417 487.068 470.768 87.5672 -4.03662 -2.81057 23.7778 +9 2417 482.894 466.203 82.6486 -4.07621 -2.9029 23.2198 +10 2417 478.265 461.015 76.6534 -4.08837 -2.99559 22.4679 +11 2417 473.826 455.613 71.6251 -4.00311 -2.98549 21.2799 +7 2419 539.564 526.943 34.2628 -2.9792 -5.89881 30.7105 +8 2419 538.947 525.179 28.5442 -2.75492 -5.63019 28.1505 +9 2419 537.86 523.479 21.5735 -2.67807 -5.65055 26.9505 +10 2419 536.104 521.475 13.9937 -2.69711 -5.83301 26.4933 +7 2420 450.126 434.276 70.3935 -5.40294 -3.47223 24.4518 +8 2420 444.856 427.947 66.4348 -5.23199 -3.38054 22.9205 +9 2420 438.871 421.436 60.5732 -5.25879 -3.45929 22.2301 +7 2423 507.62 492.244 80.5246 -3.56113 -3.22543 25.2061 +8 2423 504.384 488.324 77.4386 -3.51788 -3.19143 24.1338 +9 2423 501.353 484.61 72.0816 -3.47162 -3.23311 23.1493 +10 2423 497.471 479.99 65.7818 -3.44418 -3.29005 22.171 +11 2423 493.312 475.411 60.2387 -3.48831 -3.37931 21.6516 +7 2424 432.751 416.142 84.8063 -5.71826 -2.8476 23.3357 +8 2424 426.619 408.556 81.5232 -5.44018 -2.71595 21.4567 +7 2425 418.429 402.218 26.5005 -6.3329 -4.84928 23.9074 +8 2425 411.714 394.847 20.9372 -6.30043 -4.83783 22.9776 +7 2430 562.223 547.395 35.6788 -1.71484 -4.96939 26.1389 +8 2430 561.574 545.753 30.6156 -1.62917 -4.82921 24.4973 +7 2431 558.321 542.941 63.2431 -1.78946 -3.82808 25.1992 +8 2431 557.108 541.166 59.4752 -1.76728 -3.82019 24.3115 +9 2431 556.042 539.36 53.4668 -1.72332 -3.84438 23.2342 +7 2436 670.295 656.075 105.169 2.29423 -2.55674 27.2553 +8 2436 673.077 658.457 103.179 2.33372 -2.55997 26.5103 +9 2436 676.292 661.163 99.1996 2.36939 -2.61516 25.6188 +10 2436 679.418 663.753 94.4252 2.39548 -2.68936 24.7418 +11 2436 682.937 666.583 90.5187 2.41005 -2.70425 23.6984 +7 2437 670.295 656.075 105.169 2.29423 -2.55674 27.2553 +8 2437 673.077 658.457 103.179 2.33372 -2.55997 26.5103 +9 2437 676.292 661.163 99.1996 2.36939 -2.61516 25.6188 +7 2440 651.4 636.897 111.183 1.54963 -2.28405 26.7231 +8 2440 653.785 638.602 109.51 1.56456 -2.24087 25.5254 +9 2440 656.482 641.668 106.009 1.70136 -2.42369 26.1618 +7 2443 807.201 767.448 27.5698 2.67061 -1.96314 9.7497 +8 2443 829.081 785.001 12.8959 2.67504 -1.94921 8.79249 +7 2444 737.294 723.607 43.8264 5.01311 -5.06386 28.3177 +8 2444 742.347 728.046 39.786 4.98742 -4.99794 27.1005 +9 2444 748.094 732.95 33.5938 4.91364 -4.93936 25.5919 +10 2444 754.166 738.209 25.9352 4.86791 -4.94574 24.2892 +11 2444 760.542 744.01 19.0734 4.90571 -4.99662 23.4441 +7 2445 713.943 699.492 74.3513 3.87976 -3.66116 26.8182 +8 2445 718.156 703.444 71.0328 3.96485 -3.71747 26.3432 +7 2448 716.671 702.567 95.3216 4.07946 -2.95291 27.4806 +8 2448 721.074 706.478 92.9739 4.10395 -2.93975 26.554 +9 2448 725.99 711.201 88.7028 4.22889 -3.05648 26.2072 +7 2449 716.671 702.567 95.3216 4.07946 -2.95291 27.4806 +8 2449 721.074 706.478 92.9739 4.10395 -2.93975 26.554 +9 2449 725.99 711.201 88.7028 4.22889 -3.05648 26.2072 +10 2449 730.118 715.676 83.4813 4.4839 -3.324 26.8358 +11 2449 736.064 720.418 78.9572 4.34305 -3.22358 24.7712 +12 2449 741.596 725.045 74.3629 4.28516 -3.19646 23.417 +13 2449 747.515 729.993 70.0984 4.2292 -3.1501 22.1196 +14 2449 753.991 735.83 66.6572 4.27179 -3.14093 21.3406 +15 2449 760.951 742.077 62.9975 4.30855 -3.12647 20.5347 +7 2452 732.755 718.701 57.1309 4.70862 -4.42302 27.5777 +8 2452 737.969 723.06 53.5086 4.62627 -4.29969 25.9951 +9 2452 743.643 728.367 47.6578 4.7147 -4.40219 25.371 +10 2452 749.562 733.67 40.7496 4.73196 -4.46499 24.3872 +11 2452 755.969 739.307 34.5283 4.71986 -4.45924 23.2604 +12 2452 762.262 744.573 28.2165 4.63703 -4.39212 21.9105 +13 2452 769.753 751.58 21.7542 4.73498 -4.46619 21.3271 +14 2452 777.564 758.793 15.6273 4.80758 -4.49915 20.6473 +7 2455 706.69 693.374 52.3447 3.91811 -4.86115 29.1057 +8 2455 711.013 697.569 50.0104 4.05356 -4.90821 28.829 +7 2459 901.66 889.835 24.3414 13.2684 -6.74604 32.7751 +8 2459 911.037 898.93 20.6083 13.376 -6.75488 32.0134 +7 2464 1006.69 989.561 60.1087 12.4542 -3.53574 22.6277 +8 2464 1024.86 1007.16 55.8747 12.6034 -3.55001 21.8968 +9 2464 1045.25 1026.68 49.198 12.5977 -3.57539 20.8626 +10 2464 1067.04 1047.81 41.4239 12.7767 -3.6706 20.1512 +11 2464 1091.06 1070.71 33.7748 12.7075 -3.67049 19.0424 +12 2464 1116.7 1095.77 25.3878 13.0145 -3.78434 18.5164 +7 2467 1102.82 1078.33 108.705 10.8184 -1.40694 15.8251 +8 2467 1136.04 1110.16 105.019 10.9299 -1.40829 14.9794 +9 2467 1174.02 1146.58 99.049 11.0528 -1.4452 14.1287 +10 2467 1217.57 1188.24 91.3797 11.1367 -1.49234 13.2162 +7 2472 1092.57 1068.77 107.222 10.9007 -1.48117 16.2837 +8 2472 1124.93 1099.04 103.403 10.6921 -1.44085 14.9693 +7 2473 1090.75 1065.84 124.782 10.3741 -1.03639 15.5557 +8 2473 1123.01 1097 121.835 10.6044 -1.0537 14.902 +7 2474 1102.92 1083.63 16.818 13.7357 -4.34421 20.0884 +8 2474 1128.91 1108.71 9.30908 13.8111 -4.34912 19.1877 +7 2475 1110.61 1086.26 96.3278 11.0548 -1.68843 15.9195 +8 2475 1144.17 1118.36 92.0628 11.1262 -1.68142 15.0166 +7 2476 1039.39 1014.32 115.512 9.21184 -1.22892 15.4636 +8 2476 1068.14 1041.64 112.409 9.29504 -1.22517 14.625 +9 2476 1100.93 1072.92 107.031 9.42353 -1.26234 13.8376 +7 2478 976.079 960.706 65.3416 12.8068 -3.75667 25.2118 +8 2478 991.984 975.555 61.2477 12.503 -3.64885 23.5899 +9 2478 1009.29 992.438 55.1905 12.7433 -3.7511 23.0026 +10 2478 1027.05 1009.02 46.631 12.4386 -3.76064 21.4972 +7 2493 208.006 192.5 170.432 -13.9099 -0.0838986 24.9943 +8 2493 193.207 177.678 170.832 -14.4022 -0.0699357 24.9589 +9 2493 178.203 162.291 169.117 -14.5614 -0.126139 24.3572 +10 2493 161.771 144.986 166.458 -14.3304 -0.20469 23.0911 +7 2498 141.925 86.924 241.027 -4.56705 0.665793 7.04674 +8 2498 72.2684 8.32949 251.673 -4.51378 0.662155 6.06164 +7 2499 232.976 216.607 130.051 -12.3576 -1.40459 23.6773 +8 2499 218.721 202.691 128.439 -13.097 -1.48837 24.1788 +9 2499 204.077 188.104 125.024 -13.6354 -1.60841 24.2635 +10 2499 188.718 174.65 121.107 -16.0688 -1.97583 27.5501 +7 2501 264.078 228.97 209.013 -5.28578 0.553219 11.0394 +8 2501 233.448 191.297 211.931 -4.79303 0.497983 9.19501 +7 2503 238.597 194.914 230.826 -4.56156 0.712862 8.87245 +8 2503 196.213 147.611 237.712 -4.56841 0.716822 7.97461 +9 2503 143.279 88.452 244.552 -4.56828 0.702442 7.0691 +7 2506 190.11 173.138 153.695 -13.2755 -0.606387 22.8365 +8 2506 173.017 158.91 152.533 -16.6222 -0.773775 27.474 +9 2506 158.75 142.444 150.627 -14.851 -0.732232 23.7696 +7 2512 369.542 355.655 192.131 -9.28378 0.745622 27.9089 +8 2512 361.976 347.934 192.845 -9.47074 0.764709 27.6008 +9 2512 354.478 340.049 192.172 -9.49562 0.719142 26.8599 +7 2514 365.238 336.847 212.66 -4.62253 0.75313 13.6514 +8 2514 348.308 318.11 215.998 -4.64703 0.76743 12.8344 +9 2514 329.199 296.763 217.8 -4.6429 0.744323 11.949 +10 2514 306.432 271.16 219.46 -4.61631 0.709759 10.9882 +11 2514 280.333 240.327 222.561 -4.42042 0.667407 9.68787 +7 2517 278.803 245.009 206.851 -5.25733 0.540381 11.4687 +8 2517 250.813 214.823 209.765 -5.35438 0.550901 10.7691 +7 2528 526.753 520.731 197.668 -7.38637 2.21344 64.3613 +8 2528 526.08 520.061 198.334 -7.45019 2.27402 64.394 +9 2528 525.777 519.539 197.404 -7.21434 2.11394 62.1302 +10 2528 525.076 518.747 195.695 -7.16951 1.9384 61.2322 +11 2528 524.528 518.073 194.953 -7.0758 1.839 60.0424 +12 2528 523.627 517.037 194.876 -7.00423 1.79502 58.8117 +13 2528 522.887 516.262 195.304 -7.0272 1.82021 58.5007 +14 2528 522.204 515.263 196.684 -6.76018 1.8441 55.8376 +15 2528 521.674 514.897 198.507 -6.96598 2.03331 57.1904 +7 2533 547.457 541.01 140.317 -5.17399 -2.71079 60.1145 +8 2533 547.129 540.545 140.111 -5.09279 -2.67104 58.8602 +7 2534 514.821 507.701 188.546 -7.14681 1.18378 54.4311 +8 2534 514.514 507.292 189.001 -7.06906 1.20095 53.665 +7 2536 514.821 507.701 188.546 -7.14681 1.18378 54.4311 +8 2536 514.514 507.292 189.001 -7.06906 1.20095 53.665 +9 2536 513.643 507.241 187.78 -8.04692 1.2522 60.5337 +7 2537 468.9 449.425 237.356 -3.87959 1.77905 19.901 +8 2537 464.463 443.648 240.177 -3.74439 1.73735 18.6201 +9 2537 458.742 437.613 241.639 -3.83413 1.74867 18.3432 +10 2537 453.282 430.62 242.219 -3.7042 1.64413 17.1024 +11 2537 445.045 423.264 244.646 -4.05717 1.7705 17.7942 +7 2540 619.227 612.189 160.982 0.737863 -0.906033 55.0672 +8 2540 620.262 613.36 161.285 0.832914 -0.900299 56.1516 +9 2540 620.935 615.971 159.25 1.23102 -1.47219 78.0839 +10 2540 621.606 614.755 156.809 0.944578 -1.25805 56.5749 +11 2540 622.405 615.443 155.029 0.991072 -1.37521 55.6677 +12 2540 623.163 616.119 154.127 1.03736 -1.42808 55.0228 +7 2541 619.227 612.189 160.982 0.737863 -0.906033 55.0672 +8 2541 620.262 613.36 161.285 0.832914 -0.900299 56.1516 +9 2541 620.935 614.37 159.25 0.930768 -1.11311 59.0386 +10 2541 621.606 614.755 156.809 0.944578 -1.25805 56.5749 +11 2541 622.405 615.443 155.029 0.991072 -1.37521 55.6677 +12 2541 623.163 616.119 154.127 1.03736 -1.42808 55.0228 +7 2542 605.695 597.091 183.754 -0.241272 0.680534 45.0481 +8 2542 605.815 597.421 183.956 -0.239585 0.710466 46.1732 +9 2542 606.47 598.122 182.865 -0.19881 0.644233 46.4308 +7 2547 628.484 620.079 127.59 1.20946 -2.89277 46.1129 +8 2547 629.462 620.754 127.009 1.22764 -2.82781 44.5056 +9 2547 630.496 621.654 124.636 1.27192 -2.92922 43.8331 +10 2547 631.721 622.692 121.68 1.31854 -3.04471 42.9296 +11 2547 632.711 623.708 119.059 1.38129 -3.2096 43.0495 +12 2547 633.9 624.426 117.601 1.38011 -3.13286 40.9111 +13 2547 635.095 624.856 115.594 1.33958 -3.00375 37.8507 +7 2548 652.444 636.367 225.663 1.43287 1.76445 24.1081 +8 2548 655.347 638.462 228.494 1.45658 1.77001 22.9534 +9 2548 657.477 639.775 229.433 1.45401 1.71682 21.8941 +10 2548 661.415 641.601 230.584 1.40577 1.56503 19.5604 +7 2549 641.966 636.84 171.641 3.39589 -0.12715 75.609 +8 2549 643.53 637.859 172.203 3.2173 -0.0616831 68.3349 +7 2555 741.732 727.711 207.191 5.06356 1.31545 27.6423 +8 2555 747.566 732.716 209.083 4.99189 1.31047 26.099 +7 2557 704.033 690.921 128.193 3.87011 -1.82955 29.5577 +8 2557 708.193 694.163 127.365 3.7762 -1.74155 27.624 +7 2563 742.426 719.007 231.355 3.04746 1.3418 16.5493 +8 2563 747.532 726.82 233.371 3.57821 1.56947 18.7125 +7 2564 938.865 925.741 130.587 13.4782 -1.72997 29.532 +8 2564 950.753 937.244 129.647 13.5666 -1.71802 28.6899 +9 2564 963.43 949.575 127.126 13.7191 -1.77281 27.9732 +7 2570 870.724 853.714 156.515 8.24738 -0.515984 22.7857 +8 2570 882.555 865.452 156.295 8.57361 -0.520041 22.6603 +7 2572 909.486 880.174 194.39 5.49638 0.39466 13.2227 +8 2572 933.78 901.405 196.139 5.37926 0.386323 11.9713 +7 2574 937.587 915.526 168.31 7.987 -0.110646 17.5684 +8 2574 956.383 934.404 169.303 8.47621 -0.0867961 17.634 +9 2574 973.724 953.808 167.882 9.82222 -0.134104 19.4613 +7 2575 912.062 891.67 180.323 7.9681 0.196726 19.0057 +8 2575 928.327 907.54 181.752 8.23721 0.22994 18.6451 +7 2578 1093.21 1068.94 139.04 10.7026 -0.748256 15.9668 +8 2578 1125.22 1099.65 137.567 10.8344 -0.741411 15.16 +9 2578 1161.93 1134.93 134.046 10.9917 -0.772248 14.358 +10 2578 1203.66 1174.76 129.263 11.0444 -0.810366 13.4135 +7 2581 1057.97 1034.2 156.437 10.132 -0.370957 16.3034 +8 2581 1087.97 1062.63 156.361 10.142 -0.349653 15.2962 +9 2581 1121.75 1094.94 154.125 10.2639 -0.375309 14.4591 +10 2581 1160.03 1131.4 150.762 10.3284 -0.414517 13.5381 +7 2582 990.348 967.021 177.816 8.7684 0.114262 16.6148 +8 2582 1014.22 989.569 178.82 8.81704 0.129986 15.7213 +9 2582 1040.81 1015.02 177.818 8.97938 0.103367 15.0235 +10 2582 1070.45 1043.21 176.049 9.08971 0.0630043 14.2302 +7 2618 213.368 165.958 263.394 -4.48885 1.02582 8.17503 +8 2618 164.045 111.068 275.194 -4.51721 1.03766 7.31591 +9 2618 100.82 40.3329 288.321 -4.51781 1.0254 6.40755 +7 2620 196.14 147.081 279.109 -4.52662 1.16341 7.90027 +8 2620 142.232 87.0182 292.75 -4.54639 1.16641 7.01947 +7 2626 199.125 149.624 335.078 -4.45372 1.76033 7.82957 +8 2626 145.491 89.5544 356.947 -4.45634 1.7678 6.92876 +7 2627 228.303 177.865 338.246 -4.06026 1.76137 7.68416 +8 2627 176.78 119.066 361.025 -4.02793 1.75133 6.71544 +7 2631 145.953 90.9391 256.83 -4.52662 0.819936 7.04504 +8 2631 76.9287 13.3546 269.886 -4.5003 0.819846 6.09642 +7 2633 222.504 177.349 261.178 -4.6043 1.05068 8.5832 +8 2633 176.345 126.09 272.454 -4.63045 1.06459 7.71222 +7 2659 600.748 564.848 286.271 -0.131835 1.69699 10.7959 +8 2659 601.425 561.169 297.324 -0.108531 1.66083 9.62762 +9 2659 601.012 557.318 308.374 -0.105072 1.66602 8.87022 +7 2662 681.71 629.301 336.302 0.739495 1.67524 7.39529 +8 2662 693.123 632.329 359.802 0.73833 1.65179 6.37516 +7 2663 666.481 625.118 302.009 0.739192 1.67722 9.36998 +8 2663 674.134 627.628 317.219 0.745851 1.66745 8.33395 +9 2663 682.259 630.369 333.406 0.752569 1.66199 7.46914 +10 2663 693.076 634.039 353.907 0.759881 1.64732 6.56496 +7 2671 751.332 711.885 287.809 1.93051 1.56533 9.82516 +8 2671 766.997 723.34 300.049 1.93709 1.56499 8.87768 +9 2671 785.88 737.509 313.037 1.95801 1.55671 8.01254 +10 2671 809.622 754.532 329.144 1.95068 1.52388 7.03523 +7 2672 830.666 781.071 294.9 2.39472 1.32183 7.8147 +8 2672 861.374 805.349 311.551 2.4143 1.32977 6.91782 +7 2676 792.766 739.415 334.165 1.84455 1.6241 7.26454 +8 2676 820.869 759.306 358.119 1.84374 1.61649 6.29562 +7 2677 781.857 733.554 310.961 1.91603 1.53582 8.02386 +8 2677 806.01 750.73 329.693 1.90889 1.52399 7.01112 +9 2677 837.115 773.947 352.039 1.93502 1.5237 6.13559 +7 2680 750.695 714.062 267.396 2.06951 1.3863 10.5801 +8 2680 765.182 725.373 276.728 2.09985 1.40159 9.73581 +7 2682 771.632 731.163 283.529 2.15118 1.46898 9.57688 +8 2682 789.708 743.773 294.335 2.10658 1.42054 8.43732 +7 2684 871.374 821.019 289.485 2.79281 1.24412 7.69673 +8 2684 908.553 850.918 305.78 2.78661 1.23886 6.72471 +7 2686 892.993 841.299 292.819 2.94518 1.24657 7.49756 +8 2686 934.21 875.154 310.055 2.95292 1.24794 6.56288 +9 2686 988.625 919.897 331.209 2.96261 1.23763 5.63922 +10 2686 1063.7 981.423 359.945 2.96498 1.22148 4.71079 +8 2705 526.228 518.639 118.091 -5.89835 -3.87622 51.0719 +9 2705 525.393 517.984 115.35 -6.10212 -4.16909 52.3118 +8 2711 403.779 388.385 168.783 -7.18045 -0.142046 25.1771 +9 2711 396.681 381.299 167.398 -7.43372 -0.19051 25.1961 +10 2711 389.237 374.769 164.974 -8.18001 -0.292554 26.7889 +8 2719 484.303 437.315 323.05 -1.43188 1.71697 8.2483 +9 2719 470.036 416.8 340.367 -1.4078 1.69022 7.28036 +10 2719 451.226 389.921 362.336 -1.3873 1.66022 6.32203 +8 2722 844.003 787.552 325.072 2.23082 1.44841 6.8657 +9 2722 881.388 816.395 346.746 2.2466 1.43717 5.96333 +8 2731 233.898 219.871 50.7938 -14.3862 -4.67438 27.6318 +9 2731 222.079 207.42 44.3823 -14.198 -4.70746 26.4386 +8 2742 166.227 149.63 113.107 -14.3485 -1.93371 23.3527 +9 2742 148.879 131.905 109.049 -14.5782 -2.0191 22.833 +10 2742 129.897 112.023 104.165 -14.4149 -2.06426 21.6838 +11 2742 109.32 90.6973 99.8983 -14.4288 -2.10432 20.8119 +12 2742 86.377 66.6449 96.7544 -14.2421 -2.07159 19.6418 +13 2742 61.5518 41.3502 92.9106 -14.5712 -2.12565 19.1853 +8 2746 169.002 152.89 38.7737 -14.6874 -4.47001 24.0549 +9 2746 152.722 136.227 31.9312 -14.8765 -4.58901 23.4962 +10 2746 134.141 120.02 24.1187 -18.0844 -5.65774 27.4466 +8 2752 259.739 242.506 34.4545 -10.9037 -4.31382 22.4899 +9 2752 246.024 228.527 26.7544 -11.1602 -4.48514 22.1506 +10 2752 230.589 212.296 18.2403 -11.1278 -4.53997 21.1868 +8 2754 274.864 258.764 29.4761 -11.1669 -4.78372 24.0737 +9 2754 262.735 246.905 22.0774 -11.7684 -5.11613 24.4831 +8 2759 323.804 305.673 13.6857 -8.46604 -4.71566 21.3769 +9 2759 311.867 293.073 5.15347 -8.50876 -4.79327 20.6232 +8 2760 323.804 305.673 13.6857 -8.46604 -4.71566 21.3769 +9 2760 311.867 293.073 5.15347 -8.50876 -4.79327 20.6232 +8 2761 334.766 316.446 17.8184 -8.05707 -4.54572 21.1558 +9 2761 323.039 304.137 8.96567 -8.14234 -4.65737 20.5046 +8 2762 285 268.593 23.6877 -10.626 -4.88367 23.623 +9 2762 272.702 254.695 16.0934 -10.0482 -4.67606 21.523 +8 2765 385.255 367.777 46.5672 -6.89328 -3.88102 22.1742 +9 2765 376.402 358.723 39.5457 -7.08435 -4.05049 21.9235 +8 2766 285.101 267.772 47.523 -10.0576 -3.88503 22.3663 +9 2766 272.508 254.328 40.8355 -9.95857 -3.90064 21.3187 +8 2767 311.333 294.064 60.5025 -9.27632 -3.49469 22.4434 +9 2767 300.388 281.346 54.5457 -8.72105 -3.33722 20.353 +8 2771 379.226 362.91 109.879 -7.58291 -2.07324 23.7541 +9 2771 370.801 354.174 105.899 -7.71342 -2.16307 23.3102 +10 2771 361.434 344.1 100.778 -7.68929 -2.23358 22.3601 +11 2771 351.793 333.402 96.8926 -7.52845 -2.21857 21.0736 +8 2776 354.002 338.217 89.9434 -8.69692 -2.82154 24.5548 +9 2776 344.305 328.254 85.0143 -8.8768 -2.93958 24.1464 +10 2776 333.727 317.93 79.1998 -9.37918 -3.18454 24.5345 +11 2776 323.638 305.411 74.0651 -8.42576 -2.91119 21.2629 +8 2777 369.139 351.821 21.1346 -7.45744 -4.70608 22.3809 +9 2777 360.109 342.112 13.1938 -7.44516 -4.76526 21.5352 +8 2783 497.805 481.582 61.7483 -3.70023 -3.67875 23.8903 +9 2783 494.21 477.426 56.0019 -3.69158 -3.73968 23.0918 +10 2783 490.039 472.499 48.9954 -3.66023 -3.79309 22.0966 +8 2792 546.915 534.266 101.205 -2.66016 -3.04256 30.6397 +9 2792 545.957 532.473 97.2767 -2.53359 -3.01061 28.7424 +8 2793 442.165 426.049 104.01 -5.57929 -2.29458 24.049 +9 2793 436.38 419.715 99.6435 -5.58216 -2.35982 23.2576 +8 2794 442.165 426.049 104.01 -5.57929 -2.29458 24.049 +9 2794 436.38 419.715 99.6435 -5.58216 -2.35982 23.2576 +8 2795 444.856 427.947 66.4348 -5.23199 -3.38054 22.9205 +9 2795 438.871 421.436 60.5732 -5.25879 -3.45929 22.2301 +8 2798 536.134 520.746 63.3993 -2.56294 -3.82058 25.1857 +9 2798 534.187 517.991 57.7239 -2.49987 -3.8185 23.9311 +10 2798 531.804 514.874 50.8846 -2.46703 -3.86984 22.8929 +11 2798 529.267 511.564 44.8181 -2.43613 -3.88473 21.8922 +12 2798 526.3 507.509 38.683 -2.37996 -3.83527 20.6251 +13 2798 523.209 503.553 32.6603 -2.3597 -3.83109 19.7176 +14 2798 519.984 499.409 27.2465 -2.33852 -3.80133 18.837 +8 2799 516.439 500.946 34.7371 -3.22836 -4.78836 25.0149 +9 2799 513.75 497.787 27.8829 -3.22411 -4.87846 24.2806 +10 2799 510.84 494.309 19.9813 -3.20774 -4.96739 23.4454 +8 2800 516.439 500.946 34.7371 -3.22836 -4.78836 25.0149 +9 2800 513.75 497.787 27.8829 -3.22411 -4.87846 24.2806 +10 2800 510.84 494.309 19.9813 -3.20774 -4.96739 23.4454 +8 2801 440.624 423.602 42.3363 -5.33082 -4.11854 22.7684 +9 2801 434.56 416.484 35.5702 -5.20018 -4.07945 21.4408 +10 2801 427.476 408.846 27.4708 -5.25014 -4.19193 20.8046 +11 2801 420.274 400.976 20.2799 -5.26867 -4.24683 20.0837 +8 2807 594.316 579.164 43.4487 -0.540404 -4.58764 25.5797 +9 2807 594.078 578.888 36.5022 -0.547482 -4.8219 25.5162 +8 2816 639.745 623.713 13.8883 1.01139 -5.32622 24.1754 +9 2816 641.024 625.037 6.73975 1.05723 -5.58163 24.2445 +8 2817 632.73 618.7 33.5968 0.887115 -5.33155 27.6245 +9 2817 634.613 620.228 28.3807 0.935517 -5.39471 26.9426 +8 2822 724.273 709.948 75.0106 4.30162 -3.66901 27.0568 +9 2822 728.654 714.749 69.7932 4.60076 -3.98136 27.8738 +10 2822 733.636 719.066 63.6602 4.57416 -4.02548 26.5998 +11 2822 739.245 724.271 58.113 4.6519 -4.11581 25.8819 +8 2826 738.458 723.283 29.6115 4.5627 -5.07043 25.5407 +9 2826 744.295 728.517 22.897 4.58676 -5.10492 24.563 +8 2827 713.237 698.737 55.7625 3.84056 -4.33744 26.728 +9 2827 718.295 702.99 50.3678 3.81635 -4.29897 25.3242 +8 2829 703.559 688.752 80.8335 3.40998 -3.33819 26.175 +9 2829 707.883 692.553 76.0806 3.44517 -3.39084 25.282 +10 2829 712.444 696.682 70.12 3.50629 -3.50116 24.5899 +8 2830 703.559 688.752 80.8335 3.40998 -3.33819 26.175 +9 2830 707.883 692.553 76.0806 3.44517 -3.39084 25.282 +10 2830 712.444 696.682 70.12 3.50629 -3.50116 24.5899 +8 2832 708.434 695.244 114.528 4.02649 -2.37519 29.3831 +9 2832 713.691 698.992 110.47 3.80527 -2.27968 26.367 +10 2832 718.134 702.871 106.265 3.82107 -2.34344 25.393 +8 2835 737.969 723.06 53.5086 4.62627 -4.29969 25.9951 +9 2835 743.643 728.367 47.6578 4.7147 -4.40219 25.371 +8 2836 737.969 723.06 53.5086 4.62627 -4.29969 25.9951 +9 2836 743.643 728.367 47.6578 4.7147 -4.40219 25.371 +8 2849 1062.7 1036.34 114.012 9.23392 -1.19905 14.7032 +9 2849 1094.82 1067.44 108.601 9.52094 -1.26068 14.1569 +10 2849 1131.42 1101.9 101.531 9.49596 -1.29783 13.1294 +11 2849 1174.07 1142.29 94.4264 9.54141 -1.32559 12.1955 +12 2849 1223.27 1188.75 86.045 9.54822 -1.35059 11.2258 +8 2850 1067.58 1041.81 119.742 9.54666 -1.10702 15.0392 +9 2850 1100.17 1072.83 114.774 9.64097 -1.14133 14.179 +8 2851 1067.58 1041.81 119.742 9.54666 -1.10702 15.0392 +9 2851 1100.17 1072.83 114.774 9.64097 -1.14133 14.179 +10 2851 1136.64 1107.67 108.4 9.77345 -1.19514 13.3792 +11 2851 1179.12 1147.99 101.967 9.82707 -1.22307 12.4492 +12 2851 1227.94 1193.95 94.2436 9.77262 -1.24232 11.4028 +8 2852 1024.18 1006.28 42.0685 12.4399 -3.92391 21.648 +9 2852 1044.35 1025.77 34.9142 12.576 -3.98986 20.8702 +10 2852 1066.14 1046.74 25.181 12.6429 -4.0891 19.9795 +11 2852 1090.02 1069.86 16.926 12.8023 -4.15485 19.2261 +8 2853 1041.35 1015.16 96.3803 8.85674 -1.5686 14.7999 +9 2853 1071.06 1043.98 89.7487 9.15486 -1.64857 14.3133 +10 2853 1105.62 1076.5 81.74 9.14813 -1.68027 13.3062 +8 2854 1041.35 1015.16 96.3803 8.85674 -1.5686 14.7999 +9 2854 1071.06 1043.98 89.7487 9.15486 -1.64857 14.3133 +10 2854 1105.62 1076.5 81.74 9.14813 -1.68027 13.3062 +8 2855 1040.15 1014.34 103.792 8.96309 -1.43759 15.0195 +9 2855 1070.65 1043.17 97.9712 9.01229 -1.46362 14.1028 +10 2855 1105 1075.73 90.4506 9.09309 -1.51239 13.2427 +8 2856 987.974 964.696 105.009 8.7321 -1.56555 16.6498 +9 2856 1011.87 987.239 99.7961 8.7729 -1.59311 15.734 +8 2865 1116.07 1089.75 124.232 10.3378 -0.992368 14.7265 +9 2865 1153.04 1125.09 119.606 10.4446 -1.02331 13.8664 +8 2874 1135.55 1110.9 89.2804 11.4585 -1.8206 15.7183 +9 2874 1172.73 1145.55 82.1042 11.13 -1.79348 14.2597 +10 2874 1214.34 1186.41 73.0455 11.6347 -1.92012 13.881 +8 2885 206.829 191.198 169.775 -13.839 -0.105801 24.7943 +9 2885 192.632 176.614 168.124 -13.9807 -0.158596 24.1952 +10 2885 176.292 159.481 165.92 -13.8441 -0.22157 23.0551 +8 2889 271.342 232.038 231.265 -4.62228 0.798284 9.86097 +9 2889 237.348 194.494 235.842 -4.66546 0.789517 9.04407 +8 2896 179.956 129.294 244.497 -4.55494 0.759612 7.65023 +9 2896 122.35 64.9472 252.334 -4.55906 0.743739 6.75179 +8 2899 207.522 191.776 166.001 -13.715 -0.233784 24.6143 +9 2899 192.737 176.421 163.744 -13.7233 -0.299925 23.7555 +10 2899 176.613 159.675 160.895 -13.7298 -0.379241 22.8818 +11 2899 159.254 141.482 159.426 -13.6103 -0.405871 21.8082 +12 2899 139.732 121.774 158.731 -14.0531 -0.42245 21.5821 +13 2899 119.34 100.518 159.04 -13.9905 -0.394243 20.5921 +14 2899 96.8592 77.2008 159.933 -14.0092 -0.353064 19.7155 +15 2899 73.2873 52.5437 161.054 -13.8867 -0.305558 18.6841 +8 2902 361.976 347.934 192.845 -9.47074 0.764709 27.6008 +9 2902 354.478 340.049 192.172 -9.49562 0.719142 26.8599 +10 2902 346.092 331.091 190.721 -9.4339 0.639774 25.8359 +8 2910 310.855 297.923 165.189 -12.4069 -0.318389 29.9697 +9 2910 302.631 291.423 165.264 -14.7095 -0.363744 34.5795 +10 2910 296.207 283.982 164.063 -13.7682 -0.386276 31.7033 +11 2910 288.676 276.52 165.031 -14.1799 -0.345719 31.8849 +12 2910 281.348 270.067 165.747 -15.6281 -0.338421 34.3566 +8 2911 488.227 473.175 137.624 -4.33011 -1.25728 25.7502 +9 2911 484.625 468.914 135.162 -4.27119 -1.28859 24.6676 +10 2911 480.497 464.141 131.573 -4.23831 -1.35564 23.6949 +11 2911 476.11 458.782 128.974 -4.13666 -1.36021 22.3663 +8 2912 454.517 447.52 193.295 -11.901 1.56907 55.3852 +9 2912 452.686 445.652 192.3 -11.9805 1.48512 55.104 +8 2913 473.451 457.934 130.323 -4.71173 -1.47232 24.9778 +9 2913 469.136 453.083 127.227 -4.69851 -1.52668 24.1424 +10 2913 464.285 447.67 123.147 -4.6966 -1.60699 23.3267 +11 2913 459.092 441.771 120.142 -4.6661 -1.63465 22.3755 +8 2914 458.842 443.546 132.711 -5.29297 -1.40974 25.3393 +9 2914 454.072 438.301 129.989 -5.29577 -1.45996 24.5749 +10 2914 448.667 432.262 126.521 -5.2682 -1.51712 23.6258 +11 2914 442.959 425.956 123.671 -5.26302 -1.55373 22.7939 +12 2914 436.397 418.773 121.412 -5.27752 -1.56783 21.9906 +8 2919 507.198 495.877 140.877 -4.85698 -1.5173 34.2363 +9 2919 505.121 492.863 138.134 -4.57655 -1.52145 31.6183 +8 2921 613.547 608 178.411 0.386165 0.538116 69.8656 +9 2921 614.345 608.826 177.07 0.465774 0.410327 70.2187 +10 2921 614.95 609.302 174.935 0.512695 0.197892 68.6281 +11 2921 615.702 609.996 174.047 0.578297 0.112361 67.9321 +12 2921 616.203 610.415 173.597 0.616601 0.0689624 66.9621 +8 2923 644.326 633.529 185.834 1.72967 0.645773 35.8971 +9 2923 646.151 635.096 184.687 1.77796 0.574962 35.0588 +10 2923 647.984 637.22 182.672 1.91739 0.489933 36.0044 +11 2923 650.055 638.788 181.736 1.93059 0.423423 34.3981 +12 2923 652.046 640.171 181.17 1.92188 0.376197 32.6389 +13 2923 654.23 641.898 181.264 1.94569 0.366324 31.4276 +14 2923 656.31 643.236 182.394 1.92081 0.391966 29.6454 +15 2923 659.089 645.616 183.957 1.97474 0.442677 28.7675 +16 2923 661.854 647.754 184.973 1.99216 0.461665 27.4868 +17 2923 664.733 650.553 185.628 2.09002 0.483887 27.3322 +18 2923 668.153 653.382 186.503 2.13079 0.49635 26.239 +19 2923 672.053 656.595 186.795 2.17149 0.484402 25.0713 +20 2923 676.056 659.868 186.348 2.2065 0.447755 23.942 +21 2923 680.736 663.153 185.566 2.17439 0.388343 22.0423 +22 2923 685.508 666.809 185.076 2.18171 0.351097 20.727 +8 2924 659.806 645.061 216.89 1.83052 1.60427 26.2862 +9 2924 662.469 647.309 216.969 1.87473 1.5631 25.5658 +8 2925 655.916 644.075 186.426 2.10281 0.615637 32.7299 +9 2925 658.039 645.758 185.468 2.12053 0.551761 31.5607 +8 2926 655.916 644.075 186.426 2.10281 0.615637 32.7299 +9 2926 658.039 645.758 185.468 2.12053 0.551761 31.5607 +8 2934 814.586 770.035 167.03 2.472 -0.0702146 8.69957 +9 2934 839.943 791.166 165.031 2.53706 -0.0861457 7.9458 +8 2936 725.766 715.111 181.038 5.85813 0.412574 36.3735 +9 2936 729.686 718.775 179.884 5.91353 0.346066 35.5194 +8 2939 698.16 680.72 203.146 2.72894 0.933013 22.2237 +9 2939 702.737 684.638 203.214 2.76533 0.901027 21.4138 +10 2939 708 688.326 202.443 2.6878 0.807903 19.7007 +11 2939 712.416 692.845 203.665 2.82303 0.845643 19.8035 +12 2939 718.127 697.887 204.78 2.88134 0.847311 19.1493 +13 2939 725.87 703.27 205.51 2.76446 0.776159 17.1495 +8 2940 730.557 713.179 214.037 3.73986 1.2729 22.3016 +9 2940 736.682 718.73 214.396 3.80366 1.24298 21.5892 +8 2946 944.542 925.636 180.134 9.51723 0.206838 20.4997 +9 2946 963.101 943.221 179.031 9.55267 0.166897 19.4959 +8 2953 939.655 915.594 185.399 7.36937 0.280067 16.1083 +9 2953 958.206 937.816 185.347 9.18452 0.329104 19.0077 +10 2953 980.379 955.253 184.231 7.92748 0.243215 15.4252 +8 2955 1025.32 999.68 135.099 8.71043 -0.790995 15.1167 +9 2955 1053.82 1026.79 131.551 8.82974 -0.82092 14.3408 +10 2955 1086.14 1057.25 126.499 8.86041 -0.861805 13.4144 +8 2956 1066.03 1040.29 139.314 9.52515 -0.699872 15.0562 +9 2956 1098.5 1070.96 135.929 9.53699 -0.720244 14.0739 +10 2956 1135 1105.84 131.253 9.677 -0.766149 13.2884 +8 2958 1014.44 989.07 143.794 8.57108 -0.615171 15.2744 +9 2958 1042.62 1015.49 140.748 8.57531 -0.635747 14.2876 +8 2960 1060.13 1035.35 173.967 9.76658 0.0241194 15.6399 +9 2960 1090.28 1063.91 173.034 9.78985 0.00366094 14.694 +8 2962 1008.25 983.099 136.522 8.51601 -0.77606 15.4121 +9 2962 1035.33 1008.83 133.017 8.62876 -0.807338 14.6228 +10 2962 1065.98 1037.33 128.087 8.55672 -0.83925 13.5269 +11 2962 1101.14 1070.26 123.6 8.5526 -0.856927 12.5535 +12 2962 1140.63 1108.62 118.445 8.91215 -0.913054 12.1084 +8 2966 995.823 972.149 177.229 8.76405 0.0992695 16.3712 +9 2966 1020.79 995.421 176.745 8.70588 0.0823752 15.275 +8 2970 1134.06 1108.58 136.102 11.0584 -0.774873 15.2128 +9 2970 1171.77 1144.58 132.413 11.1102 -0.799191 14.2589 +10 2970 1214.66 1185.57 127.456 11.1708 -0.838082 13.3202 +8 2971 1112.99 1087.43 134.539 10.5804 -0.805252 15.1642 +9 2971 1148.49 1121.02 130.671 10.5384 -0.824861 14.1091 +10 2971 1189.94 1159.69 125.776 10.304 -0.835826 12.8101 +8 2987 164.045 111.068 275.194 -4.51721 1.03766 7.31591 +9 2987 100.82 40.3329 288.321 -4.51781 1.0254 6.40755 +8 2990 190.967 140.592 337.166 -4.46348 1.75207 7.69381 +9 2990 135.021 78.075 358.244 -4.47617 1.74872 6.80603 +8 2993 288.592 250.864 299.331 -4.56971 1.8007 10.2728 +9 2993 258.237 215.744 310.385 -4.44095 1.73849 9.12074 +10 2993 220.186 172.959 323.221 -4.42867 1.71025 8.20666 +8 3002 508.711 469.835 300.081 -1.39343 1.7579 9.96952 +9 3002 499.219 456.528 310.776 -1.38835 1.73539 9.07868 +10 3002 488.098 440.736 324.394 -1.37755 1.71868 8.18327 +8 3006 626.911 587.275 298.629 0.235156 1.7045 9.77824 +9 3006 629.992 585.728 310.415 0.247954 1.66929 8.75582 +10 3006 633.374 583.368 324.321 0.255813 1.627 7.75048 +11 3006 637.78 582.055 343.025 0.272029 1.64034 6.95515 +8 3007 653.44 607.102 316.917 0.508666 1.67 8.36418 +9 3007 659.325 607.789 332.298 0.518695 1.66184 7.52037 +8 3011 630.014 598.138 275.416 0.344691 1.72835 12.1591 +9 3011 632.632 597.844 283.263 0.356258 1.70482 11.1412 +8 3014 726.193 692.234 277.072 1.84484 1.64845 11.4128 +9 3014 737.852 699.999 284.901 1.82052 1.58998 10.2389 +8 3017 774.344 730.256 292.995 2.00767 1.46374 8.7909 +9 3017 794.648 745.398 305.685 2.01867 1.44872 7.86945 +8 3018 804.029 751.202 321.355 1.97739 1.50997 7.33666 +9 3018 833.286 772.785 341.318 1.98635 1.4957 6.40616 +8 3020 812.206 756.929 327.095 1.96923 1.49885 7.01161 +9 3020 844.342 780.55 348.925 1.97694 1.48258 6.07557 +8 3024 786.652 750.235 263.906 2.61212 1.34302 10.6427 +9 3024 806.324 765.712 272.604 2.60247 1.31933 9.54328 +10 3024 829.993 781.878 281.394 2.46089 1.21173 8.05517 +8 3025 712.935 676.401 280.136 1.51991 1.57736 10.6086 +9 3025 723.861 684.598 288.737 1.56371 1.58535 9.87102 +10 3025 734.677 692.625 297.753 1.59817 1.59536 9.21639 +8 3027 799.172 747.821 334.753 1.98341 1.69351 7.54751 +9 3027 828.633 765.799 357.63 1.87279 1.5796 6.1682 +8 3034 925.841 866.752 330.883 2.87517 1.43657 6.55916 +9 3034 979.08 910.157 355.291 2.87988 1.42183 5.62334 +8 3041 928.007 869.34 313.897 2.91567 1.29137 6.60632 +9 3041 981.171 912.865 335.695 2.92231 1.28056 5.67408 +9 3064 405.983 381.599 201.355 -4.48466 0.627868 15.895 +10 3064 395.221 370.005 200.512 -4.56584 0.589179 15.3702 +11 3064 381.189 355.364 201.508 -4.75008 0.596003 15.0079 +12 3064 368.169 340.705 202.446 -4.72124 0.578783 14.1122 +13 3064 351.766 323.079 204.341 -4.82714 0.589596 13.5107 +9 3066 681.797 666.939 132.673 2.61155 -1.45264 26.0852 +10 3066 685.088 669.666 128.722 2.63065 -1.53712 25.131 +11 3066 688.78 672.828 126.148 2.66748 -1.57266 24.2951 +12 3066 692.389 675.667 123.634 2.66062 -1.58103 23.1769 +13 3066 696.522 679.285 121.872 2.70996 -1.58871 22.4848 +14 3066 700.805 682.846 120.427 2.72915 -1.56808 21.581 +15 3066 706.146 687.226 119.513 2.74226 -1.51446 20.4857 +9 3067 687.996 672.872 148.049 2.7859 -0.881039 25.6275 +10 3067 691.522 676.113 145.271 2.85722 -0.961544 25.1527 +11 3067 695.433 679.523 142.972 2.8992 -1.00887 24.36 +12 3067 699.219 682.79 141.602 2.93154 -1.02182 23.5916 +13 3067 703.648 686.583 139.865 2.96146 -1.03832 22.7104 +9 3069 770.379 760.836 157.275 9.05198 -0.876914 40.6128 +10 3069 775.234 764.762 154.695 8.49789 -0.93141 37.0095 +9 3075 316.317 266.243 337.205 -3.14566 1.76302 7.74006 +10 3075 278.012 220.939 357.058 -3.1204 1.73366 6.79085 +9 3079 796.436 743.812 331.03 1.90752 1.61456 7.36499 +10 3079 823.747 763.385 351.323 1.90602 1.58816 6.42083 +9 3102 184.688 168.122 107.051 -13.7763 -2.13365 23.3956 +10 3102 167.37 149.963 101.882 -13.6456 -2.19015 22.266 +11 3102 149.298 131.257 97.2804 -13.704 -2.25015 21.4833 +12 3102 128.495 111.704 93.8931 -15.3891 -2.52594 23.0818 +13 3102 110.176 91.8278 90.6876 -14.6197 -2.40546 21.1234 +9 3103 193.296 178.621 109.061 -15.2369 -2.33508 26.4112 +10 3103 178.817 162.756 105.322 -14.4056 -2.2585 24.1308 +9 3106 160.173 143.356 81.0696 -14.3534 -2.93159 23.0459 +10 3106 141.562 123.938 72.0242 -14.264 -3.07317 21.9916 +9 3108 302.504 285.003 35.5425 -9.42463 -4.21458 22.1466 +10 3108 289.945 270.858 27.1964 -8.99503 -4.09929 20.3065 +9 3113 387.915 371.155 103.817 -7.10366 -2.21261 23.1251 +10 3113 378.925 361.498 98.6353 -7.10892 -2.28767 22.2402 +11 3113 370.323 351.476 94.9318 -6.8183 -2.2208 20.564 +9 3114 387.915 371.155 103.817 -7.10366 -2.21261 23.1251 +10 3114 378.925 361.498 98.6353 -7.10892 -2.28767 22.2402 +11 3114 370.323 351.476 94.9318 -6.8183 -2.2208 20.564 +9 3115 379.406 362.466 110.49 -7.29781 -1.97748 22.8789 +10 3115 370.408 352.954 105.871 -7.36005 -2.06146 22.2059 +11 3115 361.043 342.967 102.228 -7.3849 -2.09872 21.4412 +12 3115 350.39 331.588 98.7995 -7.40399 -2.1156 20.613 +9 3116 379.406 362.466 110.49 -7.29781 -1.97748 22.8789 +10 3116 370.408 352.954 105.871 -7.36005 -2.06146 22.2059 +11 3116 361.043 342.967 102.228 -7.3849 -2.09872 21.4412 +12 3116 350.39 331.588 98.7995 -7.40399 -2.1156 20.613 +9 3118 335.478 319.08 117.058 -8.97833 -1.82776 23.636 +10 3118 325.424 307.953 112.83 -8.73564 -1.84542 22.1834 +11 3118 313.384 296.375 109.091 -9.35311 -2.01361 22.7859 +12 3118 301.555 282.69 106.246 -8.76982 -1.89653 20.5444 +9 3122 343.208 327.118 61.2091 -8.89188 -3.72716 24.0879 +10 3122 333.909 315.639 53.7966 -8.10433 -3.50038 21.2138 +9 3124 370.799 353.597 119.45 -7.45547 -1.66759 22.5306 +10 3124 361.667 343.126 115.01 -7.18159 -1.67576 20.9034 +9 3128 286.649 269.75 59.0498 -10.2639 -3.61733 22.9345 +10 3128 273.937 256.685 51.5133 -10.4496 -3.77796 22.4652 +11 3128 259.581 242.312 45.4093 -10.8857 -3.96405 22.4428 +9 3134 415.813 398.907 113.505 -6.15614 -1.88577 22.9262 +10 3134 408.253 390.587 108.825 -6.1206 -1.94676 21.938 +11 3134 400.269 381.879 105.056 -6.11293 -1.98023 21.0746 +12 3134 391.182 371.943 101.62 -6.09694 -1.98881 20.1448 +9 3138 331.058 314.702 79.7257 -9.14616 -3.0584 23.6958 +10 3138 320.329 303.156 74.0261 -9.04667 -3.09118 22.5685 +11 3138 308.679 290.768 68.8982 -9.02342 -3.11764 21.639 +9 3140 476.48 460.011 30.2943 -4.34044 -4.64964 23.5332 +10 3140 471.828 454.644 22.2875 -4.30524 -4.70644 22.554 +11 3140 466.84 448.84 15.0808 -4.25907 -4.7083 21.5323 +9 3141 445.109 427.998 36.467 -5.16259 -4.28159 22.6512 +10 3141 438.766 421.061 28.5771 -5.18165 -4.37718 21.8905 +9 3144 536.537 519.719 62.511 -2.33225 -3.52424 23.0451 +10 3144 534.053 516.728 55.9623 -2.34107 -3.62423 22.3713 +9 3146 529.022 513.269 67.9489 -2.7461 -3.57698 24.6025 +10 3146 526.668 509.986 60.9519 -2.66903 -3.60316 23.233 +11 3146 524.216 506.502 55.4181 -2.58795 -3.56113 21.8799 +12 3146 520.895 501.917 50.0926 -2.50952 -3.4746 20.4222 +13 3146 517.239 497.713 44.6574 -2.53966 -3.52661 19.8491 +14 3146 513.494 493.122 39.6393 -2.53292 -3.51244 19.0246 +15 3146 509.607 488.702 33.9441 -2.56832 -3.56935 18.5402 +16 3146 505.701 483.413 27.983 -2.503 -3.49142 17.3892 +17 3146 501.61 477.661 20.4609 -2.42125 -3.41809 16.1837 +9 3147 521 504.788 73.235 -2.93436 -3.3008 23.9076 +10 3147 518.421 501.029 66.8705 -2.81486 -3.27337 22.2851 +9 3149 508.329 491.743 82.0862 -3.27828 -2.93947 23.3666 +10 3149 504.994 487.533 76.1483 -3.21687 -2.97507 22.1975 +11 3149 501.025 482.964 70.8665 -3.22786 -3.03316 21.4589 +12 3149 496.545 477.728 65.7562 -3.22616 -3.05726 20.5973 +13 3149 491.928 472.379 60.8856 -3.23214 -3.07656 19.8257 +9 3152 464.4 451.442 55.4143 -6.01759 -4.86845 29.9113 +10 3152 459.845 446.468 48.7544 -6.01186 -4.98328 28.9737 +11 3152 456.304 441.583 42.7007 -5.59211 -4.74916 26.3281 +9 3153 482.894 466.203 82.6486 -4.07621 -2.9029 23.2198 +10 3153 478.265 461.015 76.6534 -4.08837 -2.99559 22.4679 +9 3155 535.742 518.904 45.9403 -2.35481 -4.04863 23.0175 +10 3155 533.148 515.772 38.2928 -2.36207 -4.15964 22.3046 +9 3156 517.91 502.374 80.3729 -3.16877 -3.19752 24.947 +10 3156 514.588 500.831 74.3943 -3.70817 -3.84437 28.1725 +9 3160 479.052 462.027 61.7532 -4.11745 -3.50518 22.7642 +10 3160 474.273 456.689 54.8573 -4.13281 -3.60462 22.0419 +9 3161 419.562 400.366 76.1348 -5.31665 -2.70647 20.1906 +10 3161 411.638 391.407 69.7631 -5.25523 -2.73727 19.1583 +11 3161 402.364 382.385 64.3559 -5.57084 -2.91717 19.3999 +9 3163 422.561 406.264 124.102 -6.1633 -1.60682 23.7812 +10 3163 415.714 398.455 119.652 -6.0329 -1.65576 22.4559 +9 3164 484.996 468.095 33.6627 -3.95871 -4.42361 22.931 +10 3164 480.218 462.951 25.6518 -4.02363 -4.57925 22.446 +11 3164 475.478 457.572 18.1307 -4.02241 -4.64165 21.6459 +9 3168 515.024 498.605 60.6111 -3.09279 -3.67209 23.6055 +10 3168 512.134 495.366 54.168 -3.1209 -3.80195 23.1135 +11 3168 508.426 491.056 48.1135 -3.12737 -3.85738 22.3123 +9 3177 677.633 662.174 44.8928 2.36546 -4.44649 25.0725 +10 3177 681.067 664.834 37.6217 2.36624 -4.47495 23.8763 +11 3177 684.635 668.051 31.0175 2.43167 -4.59403 23.3703 +9 3181 678.795 663.769 111.796 2.47515 -2.1828 25.7948 +10 3181 682.128 666.401 107.327 2.47855 -2.23803 24.6437 +11 3181 685.684 669.346 103.739 2.50278 -2.27231 23.7222 +12 3181 689.197 672.17 100.213 2.51223 -2.29151 22.7613 +9 3186 741.159 724.982 52.7121 4.36995 -3.98949 23.9597 +10 3186 746.826 730.955 46.0189 4.6458 -4.29273 24.4204 +9 3189 787.792 772.862 121.48 6.41227 -1.84829 25.9587 +10 3189 795.208 779.694 117.342 6.42805 -1.92209 24.9832 +11 3189 803.365 787.121 114.09 6.40841 -1.9431 23.8584 +9 3191 781.467 766.579 60.5613 6.20255 -4.05161 26.0336 +10 3191 788.636 773.117 54.1768 6.1983 -4.10773 24.9743 +11 3191 796.266 780.236 48.6011 6.25613 -4.16344 24.1771 +12 3191 804.15 787.412 42.6735 6.24478 -4.17775 23.1556 +13 3191 812.914 795.48 37.2077 6.26533 -4.17924 22.2305 +14 3191 822.211 803.952 32.5519 6.256 -4.12755 21.2269 +15 3191 832.852 813.747 27.4173 6.27783 -4.08892 20.2859 +16 3191 844.325 824.228 21.2783 6.27484 -4.05134 19.2854 +17 3191 857.295 836.319 14.7039 6.34389 -4.04982 18.4768 +9 3194 788.717 774.016 65.3318 6.54621 -3.92874 26.3642 +10 3194 796.243 780.522 59.2692 6.37831 -3.88078 24.6523 +11 3194 804.338 788.03 54.0317 6.41528 -3.91355 23.7647 +12 3194 812.601 795.589 48.5075 6.41098 -3.9262 22.7823 +13 3194 821.846 804.125 43.6009 6.4346 -3.91778 21.8704 +14 3194 831.844 813.197 38.6014 6.4032 -3.86732 20.7848 +15 3194 843.293 823.654 34.9931 6.39282 -3.77061 19.7347 +16 3194 855.578 834.838 29.0336 6.37157 -3.72476 18.6869 +9 3219 975.178 960.327 74.6218 13.2239 -3.55292 26.097 +10 3219 989.602 974.411 68.9648 13.4384 -3.67355 25.5138 +9 3223 1051.13 1024.25 96.0029 8.82308 -1.53556 14.4171 +10 3223 1083.33 1054.3 88.6157 8.7676 -1.55893 13.3529 +11 3223 1120.45 1089.35 80.874 8.82437 -1.58872 12.4627 +12 3223 1162.65 1129.16 71.9209 8.87199 -1.61904 11.574 +13 3223 1213.13 1176.49 62.8435 8.84989 -1.61305 10.5797 +9 3224 1039.48 1013.01 97.1345 8.72259 -1.53625 14.6391 +10 3224 1069.86 1041.89 89.8544 8.83834 -1.59368 13.8543 +11 3224 1104.6 1074.57 82.7642 8.85367 -1.61122 12.9044 +12 3224 1144.18 1111.84 74.3603 8.87854 -1.6357 11.9827 +13 3224 1190.31 1155.7 66.1625 9.0128 -1.65576 11.1976 +9 3226 1076.92 1049.01 118.253 8.99367 -1.05072 13.8849 +10 3226 1111.15 1082.59 112.172 9.43306 -1.14121 13.5695 +11 3226 1151.1 1120.73 106.305 9.57674 -1.17686 12.7598 +12 3226 1197.58 1163.75 99.21 9.33744 -1.16943 11.4577 +9 3234 1011.87 987.239 99.7961 8.7729 -1.59311 15.734 +10 3234 1038.49 1012.34 93.2403 8.81065 -1.63535 14.8212 +9 3239 1145.1 1117.59 109.072 10.4582 -1.24556 14.0904 +10 3239 1185.94 1156.68 102.567 10.5803 -1.29023 13.2449 +9 3242 1131.27 1103.45 125.325 10.0753 -0.917886 13.9345 +10 3242 1171.6 1141.91 119.843 10.1689 -0.959126 13.0547 +11 3242 1217.8 1186.01 114.311 10.2784 -0.989293 12.193 +9 3244 1114.14 1086.37 80.1687 9.76095 -1.79298 13.958 +10 3244 1152.09 1122.69 70.9961 9.91153 -1.86085 13.1818 +11 3244 1196.28 1164.72 61.7647 9.98542 -1.89063 12.2799 +9 3247 1181.77 1154.41 122.475 11.2361 -0.98927 14.1684 +10 3247 1225.69 1196.48 116.471 11.3326 -1.03707 13.2714 +9 3250 134.947 119.699 166.78 -16.7191 -0.213971 25.4175 +10 3250 117.395 102.85 163.992 -18.1754 -0.327273 26.6461 +11 3250 99.5289 82.9929 162.389 -16.5677 -0.339946 23.4383 +12 3250 78.8398 62.1117 161.876 -17.0418 -0.352526 23.1691 +13 3250 57.055 42.0837 161.198 -19.8231 -0.418194 25.8878 +9 3252 136.61 121.01 158.822 -16.2842 -0.483144 24.8434 +10 3252 118.947 102.424 156.076 -15.9492 -0.545442 23.4564 +11 3252 99.62 82.7844 154.547 -16.2699 -0.584084 23.0211 +12 3252 78.7966 61.4526 153.987 -16.4379 -0.584318 22.3463 +13 3252 56.3122 37.7781 153.273 -16.0341 -0.567486 20.9114 +14 3252 31.7153 12.8216 153.585 -16.4282 -0.547808 20.5134 +9 3270 269.852 229.849 235.675 -4.56155 0.843551 9.68871 +10 3270 234.797 189.749 240.305 -4.4686 0.804273 8.6035 +11 3270 191.297 141.496 247.238 -4.51138 0.802308 7.78251 +12 3270 136.449 80.2957 257.092 -4.5257 0.80581 6.90211 +9 3273 258.73 249.839 151.748 -21.1947 -1.27508 43.5904 +10 3273 251.788 241.014 148.394 -17.8371 -1.2195 35.9732 +9 3274 185.953 170.599 152.597 -14.8194 -0.708681 25.2423 +10 3274 169.573 152.467 149.434 -13.8166 -0.735444 22.6579 +9 3275 198.839 182.331 155.853 -13.364 -0.553193 23.4774 +10 3275 182.867 165.877 152.966 -13.49 -0.628773 22.8116 +11 3275 165.625 147.761 151.342 -13.3484 -0.646832 21.6954 +12 3275 146.352 127.785 150.408 -13.4012 -0.649383 20.875 +13 3275 125.855 106.009 149.474 -13.0914 -0.632766 19.5284 +14 3275 102.538 82.2427 149.686 -13.4193 -0.613175 19.0968 +9 3276 218.797 177.886 212.729 -5.13067 0.523554 9.47371 +10 3276 177.544 134.655 213.947 -5.41062 0.514651 9.03664 +11 3276 128.704 78.2727 218.859 -5.12166 0.490009 7.68521 +9 3278 188.547 172.139 161.19 -13.7827 -0.381838 23.6209 +10 3278 172 155.071 158.441 -13.8836 -0.457332 22.8941 +9 3282 221.237 205.239 148.997 -13.0384 -0.80102 24.2265 +10 3282 206.645 191.696 145.803 -14.4771 -0.971979 25.9255 +9 3284 189.567 141.46 224.271 -4.68954 0.574114 8.05654 +10 3284 136.054 81.5469 228.628 -4.66626 0.549636 7.11055 +9 3287 182.807 166.121 138.542 -13.7381 -1.10458 23.2279 +10 3287 166.567 150.609 135.036 -14.9113 -1.27297 24.2872 +11 3287 149.938 132.857 133.32 -14.4543 -1.24328 22.6911 +12 3287 130.707 112.795 131.735 -14.3596 -1.23305 21.6371 +13 3287 110.798 92.6621 131.179 -14.7719 -1.23431 21.3699 +14 3287 88.9329 70.1206 130.087 -14.8655 -1.22113 20.6022 +15 3287 66.1277 46.1193 130.431 -14.5892 -1.13891 19.3707 +9 3288 338.71 323.182 150.069 -9.36949 -0.788196 24.9601 +10 3288 328.897 312.755 146.933 -9.33949 -0.862554 24.0103 +11 3288 318.308 301.85 145 -9.50595 -0.909094 23.5498 +12 3288 307.035 289.415 143.664 -9.22294 -0.889913 21.9972 +9 3289 328.851 321.571 176.832 -20.7109 0.293526 53.2356 +10 3289 324.542 316.266 174.735 -18.4977 0.122071 46.828 +9 3295 338.681 322.62 134.278 -9.05946 -1.29018 24.1317 +10 3295 328.168 311.675 130.152 -9.16464 -1.39076 23.4997 +11 3295 317.856 299.262 127.578 -8.42702 -1.30798 20.8445 +9 3296 390.806 384.235 190.607 -17.8822 1.4512 58.9827 +10 3296 389.855 379.477 187.706 -11.3711 0.768669 37.3443 +9 3297 324.2 311.137 159.614 -11.7339 -0.544415 29.6696 +10 3297 316.279 303.45 157.564 -12.2797 -0.640188 30.2109 +11 3297 307.62 295.573 156.781 -13.463 -0.716655 32.1723 +12 3297 299.824 285.411 157.26 -11.543 -0.581131 26.8897 +9 3298 410.889 391.218 233.553 -5.42507 1.65749 19.703 +10 3298 402.568 381.783 234.19 -5.34912 1.58506 18.6462 +11 3298 393.14 372.401 236.108 -5.60528 1.63828 18.6879 +12 3298 383.365 361.261 238.913 -5.49686 1.60532 17.5344 +9 3300 554.845 548.558 127.296 -4.67452 -3.89222 61.6447 +10 3300 554.488 548.066 124.628 -4.60629 -4.03374 60.3511 +11 3300 554.2 547.879 122.995 -4.704 -4.23661 61.3108 +12 3300 553.741 547.248 121.775 -4.61785 -4.22571 59.6924 +13 3300 553.612 546.93 121.005 -4.49807 -4.16855 58.0101 +9 3307 435.99 420.481 206.312 -6.01152 1.1588 24.9903 +10 3307 430.045 414.263 205.649 -6.10982 1.11617 24.5577 +9 3311 431.749 413.573 235.577 -5.2548 1.85365 21.3235 +10 3311 423.756 404.822 236.245 -5.2712 1.79838 20.4699 +11 3311 415.946 395.485 238.181 -5.08278 1.71498 18.942 +12 3311 405.926 385.032 241.196 -5.23509 1.75697 18.5496 +13 3311 395.859 373.318 244.741 -5.09247 1.71307 17.1942 +14 3311 384.485 360.579 249.794 -5.0573 1.72881 16.2126 +15 3311 371.904 346.54 255.757 -5.03312 1.75574 15.2809 +16 3311 358.212 331.423 261.844 -5.03996 1.78441 14.4681 +17 3311 342.583 314.273 267.799 -5.06557 1.80148 13.6903 +18 3311 325.279 295.202 274.126 -5.07711 1.80867 12.8863 +9 3313 513.903 503.591 126.063 -4.98242 -2.43722 37.5826 +10 3313 511.927 501.469 122.834 -5.01446 -2.56909 37.0588 +9 3318 614.345 608.826 177.07 0.465774 0.410327 70.2187 +10 3318 614.95 609.302 174.935 0.512695 0.197892 68.6281 +9 3325 675.394 661.833 152.712 2.60761 -0.797805 28.5788 +10 3325 678.107 663.892 150.034 2.59029 -0.862309 27.2656 +11 3325 681.296 666.866 148.13 2.67041 -0.920348 26.8593 +12 3325 683.932 669.392 146.803 2.74756 -0.962417 26.6559 +13 3325 687.384 672.317 145.797 2.77442 -0.964568 25.7224 +9 3326 563.959 552.427 210.593 -2.12382 1.75769 33.6058 +10 3326 563.268 551.679 209.432 -2.14563 1.69539 33.4435 +9 3327 704.727 690.151 136.095 3.50692 -1.35456 26.5885 +10 3327 708.867 693.799 132.545 3.54022 -1.43698 25.722 +11 3327 713.377 697.709 130.033 3.5593 -1.46809 24.7374 +9 3328 704.727 690.151 136.095 3.50692 -1.35456 26.5885 +10 3328 708.867 693.799 132.545 3.54022 -1.43698 25.722 +11 3328 713.377 697.709 130.033 3.5593 -1.46809 24.7374 +9 3333 770.045 758.98 179.069 7.79096 0.301732 35.0278 +10 3333 774.847 764.482 177.022 8.56579 0.215987 37.3926 +9 3335 719.2 699.995 199.967 3.0665 0.758303 20.1804 +10 3335 725.147 705.266 199.036 3.12302 0.707398 19.4949 +11 3335 731.825 710.762 198.97 3.11792 0.665987 18.4 +12 3335 738.773 716.668 199.865 3.13982 0.656344 17.533 +13 3335 746.625 723.411 201.395 3.17153 0.660412 16.6955 +14 3335 755.512 730.746 204.135 3.1656 0.678458 15.6496 +9 3345 860.951 812.736 135.364 2.8007 -0.417666 8.0385 +10 3345 894.907 840.219 128.279 2.80272 -0.437823 7.08701 +9 3347 862.558 814.355 146.957 2.81932 -0.28859 8.04052 +10 3347 896.833 842.076 141.454 2.81804 -0.308019 7.07799 +9 3348 945.771 923.661 169.343 8.16796 -0.0852857 17.5291 +10 3348 965.156 941.778 166.941 8.17041 -0.135856 16.5785 +9 3362 896.071 847.42 227.035 3.16332 0.598206 7.96637 +10 3362 934.892 879.677 232.483 3.16491 0.580089 7.01928 +9 3367 962.932 927.39 195.014 5.34049 0.334909 10.9045 +10 3367 995.77 957.697 195.814 5.44895 0.323943 10.18 +9 3369 964.432 948.329 130.622 11.8378 -1.40878 24.0691 +10 3369 977.528 963.634 125.751 14.2258 -1.82103 27.895 +9 3370 1098.5 1070.96 135.929 9.53699 -0.720244 14.0739 +10 3370 1135 1105.84 131.253 9.677 -0.766149 13.2884 +11 3370 1178.1 1146.48 126.723 9.65897 -0.783724 12.2583 +12 3370 1227.28 1193.07 121.605 9.69953 -0.804721 11.3298 +9 3372 1013.8 974.456 186.511 5.51946 0.186469 9.85189 +10 3372 1056.35 1013.3 185.729 5.57585 0.160683 9.00473 +9 3375 1161.93 1134.93 134.046 10.9917 -0.772248 14.358 +10 3375 1203.66 1174.76 129.263 11.0444 -0.810366 13.4135 +9 3380 1121.75 1094.94 154.125 10.2639 -0.375309 14.4591 +10 3380 1160.03 1131.4 150.762 10.3284 -0.414517 13.5381 +9 3383 1124.03 1096.93 160.622 10.1967 -0.242436 14.3008 +10 3383 1161.47 1133 156.913 10.4142 -0.300792 13.615 +11 3383 1205.06 1174.88 153.584 10.5986 -0.342959 12.8417 +9 3405 299.522 263.068 287.802 -4.56841 1.69376 10.6319 +10 3405 271.116 231.66 296.668 -4.60762 1.68562 9.82312 +11 3405 237.222 193.371 307.927 -4.56096 1.65458 8.8385 +12 3405 194.769 146.429 323.636 -4.60908 1.67547 8.01761 +9 3409 530.108 492.323 292.181 -1.12951 1.69639 10.2576 +10 3409 522.46 481.748 301.183 -1.14915 1.69312 9.51972 +11 3409 514.811 468.724 314.214 -1.10431 1.64757 8.40965 +9 3410 439.937 391.733 324.714 -1.89016 1.69222 8.04034 +10 3410 419.452 365.275 342.28 -1.88488 1.67983 7.15391 +9 3413 495.544 459.92 285.23 -1.71917 1.69444 10.8796 +10 3413 485.433 446.4 294.514 -1.70819 1.67425 9.92958 +11 3413 474.337 431.836 305.434 -1.709 1.67561 9.11912 +9 3418 484.312 449.361 290.512 -1.92487 1.80824 11.089 +10 3418 475.383 433.684 298.54 -1.7284 1.61903 9.29454 +11 3418 462.455 420.472 311.526 -1.88208 1.77421 9.23152 +9 3420 545.307 499.278 310.467 -0.749802 1.60591 8.42016 +10 3420 538.869 486.918 323.528 -0.730898 1.55789 7.46032 +11 3420 529.71 472.057 342.76 -0.743964 1.58302 6.72261 +9 3421 659.849 618.116 301.801 0.647283 1.65969 9.28701 +10 3421 666.196 620.222 313.747 0.661739 1.64619 8.43045 +9 3423 622.602 567.955 341.636 0.128201 1.65903 7.09229 +10 3423 625.307 562.645 364.236 0.134992 1.64056 6.18514 +9 3424 622.602 567.955 341.636 0.128201 1.65903 7.09229 +10 3424 625.307 562.645 364.236 0.134992 1.64056 6.18514 +9 3431 618.368 591.94 255.065 0.179037 1.67091 14.665 +10 3431 619.518 591.779 258.298 0.192842 1.65455 13.972 +11 3431 621.261 591.12 263.292 0.208532 1.61172 12.8588 +9 3439 722.381 689.616 271.343 1.84961 1.61463 11.8289 +10 3439 733.032 697.396 277.661 1.86111 1.57976 10.8758 +9 3452 900.888 835.983 338.744 2.41104 1.3729 5.97146 +10 3452 955.186 878.098 366.641 2.40832 1.35031 5.02767 +9 3460 948.307 882.028 335.609 2.74536 1.31904 5.84767 +10 3460 1012.32 933.668 363.557 2.75051 1.30233 4.92743 +9 3463 965.364 899.157 330.038 2.88672 1.27527 5.85398 +10 3463 1031.93 952.811 360.637 2.86759 1.27492 4.89875 +10 3500 569.225 565.909 166.413 -6.53279 -1.04328 116.866 +11 3500 569.677 566.248 165.442 -6.2469 -1.161 113.018 +12 3500 569.784 566.299 164.877 -6.13214 -1.22981 111.238 +10 3517 480.714 453.526 260 -2.54559 1.72175 14.2554 +11 3517 472.726 443.287 265.084 -2.4967 1.68287 13.1654 +10 3527 134.849 118.237 92.1629 -15.3494 -2.60909 23.3304 +11 3527 116.082 97.6229 89.0649 -14.3601 -2.43824 20.9966 +10 3530 104.44 85.803 103.4 -14.558 -2.00173 20.7954 +11 3530 81.7424 62.9943 99.0752 -15.1224 -2.11383 20.6727 +10 3531 104.44 85.803 103.4 -14.558 -2.00173 20.7954 +11 3531 81.7424 62.9943 99.0752 -15.1224 -2.11383 20.6727 +10 3533 192.496 173.569 14.8661 -11.8361 -4.48363 20.4769 +11 3533 173.411 154.114 6.33775 -12.1404 -4.63505 20.0843 +10 3534 239.85 221.45 15.7714 -10.7928 -4.58567 21.0636 +11 3534 223.52 204.192 7.58224 -10.7284 -4.59307 20.0523 +10 3537 141.236 122.154 31.874 -13.1824 -3.96833 20.31 +11 3537 119.848 100.12 24.3159 -13.3342 -4.04448 19.6464 +10 3538 267.353 250.234 34.5862 -10.7374 -4.33843 22.6397 +11 3538 253.657 235.151 27.838 -10.3301 -4.20912 20.9428 +10 3550 255.692 238.11 14.9481 -10.811 -4.82418 22.0437 +11 3550 240.536 223.021 7.63947 -11.3175 -5.06695 22.1288 +10 3554 205.593 189.77 67.4364 -13.7135 -3.57862 24.4941 +11 3554 190.959 174.272 62.5257 -13.4747 -3.55144 23.2261 +12 3554 173.558 154.832 57.7661 -12.5062 -3.30118 20.6966 +10 3555 271.676 254.452 21.7926 -10.5373 -4.71101 22.5019 +11 3555 259.289 239.712 15.0128 -9.61072 -4.33084 19.7975 +10 3560 370.077 352.594 64.7868 -7.35778 -3.32023 22.1683 +11 3560 360.719 343.037 59.1371 -7.55968 -3.45467 21.92 +12 3560 350.071 329.981 54.0001 -6.93802 -3.17784 19.292 +13 3560 337.217 317.752 48.0922 -7.51541 -3.44286 19.9112 +14 3560 325.141 302.87 43.568 -6.85972 -3.11817 17.4023 +15 3560 311.261 288.797 38.6988 -7.1326 -3.20778 17.2527 +10 3565 333.727 317.93 79.1998 -9.37918 -3.18454 24.5345 +11 3565 323.638 305.411 74.0651 -8.42576 -2.91119 21.2629 +10 3568 364.094 346.662 92.0524 -7.56379 -2.48983 22.2335 +11 3568 354.189 336.103 87.822 -7.58413 -2.52533 21.4287 +10 3569 364.094 346.662 92.0524 -7.56379 -2.48983 22.2335 +11 3569 354.189 336.103 87.822 -7.58413 -2.52533 21.4287 +12 3569 343.184 323.718 84.0287 -7.35028 -2.45102 19.9099 +10 3571 343.609 326.484 84.74 -8.34208 -2.76388 22.6325 +11 3571 333.069 315.136 79.563 -8.28193 -2.79441 21.6127 +10 3572 343.609 326.484 84.74 -8.34208 -2.76388 22.6325 +11 3572 333.069 315.136 79.563 -8.28193 -2.79441 21.6127 +10 3573 312.572 295.606 95.7186 -9.40254 -2.44209 22.8437 +11 3573 300.946 283.271 91.3762 -9.37871 -2.4761 21.9274 +12 3573 287.923 269.72 87.6688 -9.49129 -2.51376 21.2921 +10 3574 349.987 333.581 98.8266 -8.49891 -2.4238 23.6245 +11 3574 339.78 322.364 94.515 -8.3202 -2.41604 22.2528 +12 3574 328.785 309.346 90.328 -7.75883 -2.28049 19.9387 +13 3574 315.597 292.948 88.5102 -6.97183 -2.00036 17.1125 +10 3576 405.423 387.331 35.823 -6.06078 -4.06843 21.4223 +11 3576 397.191 378.24 28.5656 -6.01965 -4.0899 20.4522 +12 3576 387.73 367.647 21.5206 -5.93302 -4.04755 19.2982 +13 3576 377.551 356.185 14.5721 -5.833 -3.97941 18.1404 +10 3579 345.822 328.959 124.337 -8.40121 -1.54548 22.9842 +11 3579 335.648 317.784 121.06 -8.23607 -1.55736 21.6955 +10 3580 497.225 479.788 32.6122 -3.46038 -4.32006 22.2265 +11 3580 493.189 474.993 25.6619 -3.43536 -4.34524 21.3004 +12 3580 488.298 469.144 18.9507 -3.40066 -4.31607 20.2348 +10 3581 497.225 479.788 32.6122 -3.46038 -4.32006 22.2265 +11 3581 493.189 474.993 25.6619 -3.43536 -4.34524 21.3004 +10 3583 448.22 430.644 64.2423 -4.93073 -3.31932 22.0512 +11 3583 441.975 423.924 58.5405 -4.98672 -3.40158 21.4705 +12 3583 434.551 415.642 52.7982 -4.97146 -3.41042 20.4967 +13 3583 426.679 407.011 46.9823 -4.99448 -3.43757 19.7053 +10 3589 477.16 459.709 25.862 -4.07521 -4.52437 22.2087 +11 3589 472.246 454.243 18.3238 -4.09676 -4.61044 21.5272 +12 3589 466.587 447.681 10.7274 -4.06204 -4.60626 20.5 +10 3590 520.682 503.747 41.4032 -2.8191 -4.16948 22.8864 +11 3590 517.904 499.853 34.8431 -2.72748 -4.10693 21.4715 +12 3590 514.228 495.176 28.5426 -2.68772 -4.06866 20.3427 +10 3591 440.862 421.936 52.6958 -4.78791 -3.41029 20.4784 +11 3591 433.572 414.796 46.6236 -5.0346 -3.61117 20.6416 +12 3591 426.006 405.974 41.1819 -4.92214 -3.53089 19.3486 +13 3591 418.135 396.702 35.5079 -4.7976 -3.44225 18.0836 +10 3593 426.573 410.317 112.039 -6.04655 -2.00957 23.8423 +11 3593 420.195 402.963 108.31 -5.90296 -2.012 22.4921 +10 3598 452.757 434.635 54.5159 -4.64782 -3.50769 21.3873 +11 3598 446.567 428.455 48.0203 -4.83397 -3.70227 21.3991 +12 3598 439.088 421.091 41.8377 -5.08816 -3.91052 21.5361 +10 3599 456.264 439.866 63.9101 -5.02174 -3.56884 23.6365 +11 3599 451.188 432.563 58.0813 -4.56734 -3.30998 20.8088 +12 3599 443.884 423.792 53.2229 -4.42924 -3.19827 19.2899 +13 3599 437.482 415.399 47.3433 -4.18572 -3.053 17.5511 +14 3599 428.107 406.545 43.1937 -4.52042 -3.23015 17.9753 +15 3599 419.428 397.04 38.1181 -4.56172 -3.23265 17.3115 +16 3599 410.905 386.198 32.6052 -4.3188 -3.04905 15.6865 +10 3601 503.872 486.963 106.559 -3.35738 -2.10599 22.9212 +11 3601 500.334 482.831 103.045 -3.35202 -2.14236 22.1433 +12 3601 495.973 477.652 99.7222 -3.33028 -2.14418 21.1551 +13 3601 491.633 472.602 96.0312 -3.3284 -2.16828 20.365 +14 3601 486.806 466.815 93.8868 -3.29831 -2.12181 19.3873 +15 3601 482.106 461.283 91.6219 -3.28772 -2.09542 18.6125 +16 3601 476.736 454.912 88.7018 -3.26919 -2.07124 17.7593 +10 3602 496.01 479.406 112.538 -3.67344 -1.9513 23.3425 +11 3602 492.379 475.006 109.139 -3.62291 -1.96992 22.3081 +10 3605 555.86 549.574 123.524 -4.58863 -4.21529 61.6561 +11 3605 555.673 549.395 121.721 -4.6105 -4.37497 61.7352 +10 3606 515.769 498.329 61.3783 -2.88881 -3.43353 22.2239 +11 3606 512.155 494.548 56.2163 -2.97155 -3.55832 22.0123 +12 3606 507.891 489.936 51.0971 -3.04153 -3.6425 21.5856 +13 3606 504.063 484.863 45.5445 -2.95146 -3.56171 20.1863 +14 3606 499.887 479.186 40.0487 -2.84588 -3.44615 18.7231 +15 3606 495.616 473.633 34.8052 -2.78421 -3.37322 17.6308 +16 3606 490.425 467.174 28.5776 -2.75222 -3.33305 16.6689 +17 3606 485.502 459.918 21.2054 -2.60472 -3.18401 15.1494 +10 3607 502.536 485.118 77.6897 -3.30036 -2.93466 22.2507 +11 3607 498.559 480.455 72.3687 -3.29352 -2.98152 21.4089 +10 3608 502.536 485.118 77.6897 -3.30036 -2.93466 22.2507 +11 3608 498.559 480.455 72.3687 -3.29352 -2.98152 21.4089 +10 3613 662.393 646.627 59.6078 1.80005 -3.85828 24.5827 +11 3613 665.206 648.945 54.6228 1.83817 -3.90551 23.8344 +12 3613 667.737 651.001 49.144 1.86727 -3.97057 23.1583 +13 3613 670.74 652.87 43.9213 1.83897 -3.87544 21.6879 +14 3613 674.031 655.003 39.562 1.81995 -3.76263 20.3679 +15 3613 678.002 659.025 34.4541 1.93732 -3.9175 20.4236 +10 3619 614.478 601.71 73.2471 0.206934 -4.19037 30.3544 +11 3619 616.319 603.626 68.8681 0.286061 -4.40076 30.536 +10 3623 693.4 678.091 88.0048 2.94157 -2.97694 25.3152 +11 3623 697.669 681.658 84.0087 2.95601 -2.98069 24.2071 +10 3628 728.274 712.475 59.3246 4.03619 -3.8599 24.5317 +11 3628 733.802 717.449 53.9311 4.08104 -3.90629 23.7006 +10 3632 746.034 731.152 87.1081 4.92585 -3.09487 26.0428 +11 3632 751.699 736.653 82.7134 5.07473 -3.21825 25.7607 +10 3633 829.665 813.18 99.5 7.17196 -2.39018 23.5107 +11 3633 839.881 822.459 95.259 7.1015 -2.39249 22.2472 +10 3634 829.665 813.18 99.5 7.17196 -2.39018 23.5107 +11 3634 839.881 822.459 95.259 7.1015 -2.39249 22.2472 +10 3637 709.09 694.017 31.9448 3.547 -5.02161 25.7136 +11 3637 713.634 698.486 25.3804 3.69063 -5.22962 25.5868 +12 3637 717.258 702.597 18.4066 3.94591 -5.65872 26.4361 +13 3637 722.176 705.092 11.859 3.54073 -5.06175 22.6854 +10 3639 815.901 799.78 57.1214 6.87544 -3.8563 24.0422 +11 3639 825.159 808.253 51.3333 6.85051 -3.86123 22.9263 +12 3639 834.585 816.997 45.1937 6.87239 -3.89881 22.0361 +13 3639 844.956 826.822 39.6296 6.97301 -3.94643 21.3737 +10 3642 795.601 780.774 124.912 6.74014 -1.73689 26.1408 +11 3642 804.059 787.776 121.935 6.41616 -1.67973 23.8021 +10 3644 739.321 723.974 49.3417 4.54163 -4.32289 25.2536 +11 3644 745.14 729.167 43.679 4.55949 -4.34408 24.2649 +12 3644 751.098 733.89 37.85 4.41809 -4.21411 22.5226 +13 3644 757.823 739.743 32.3886 4.40473 -4.17305 21.436 +14 3644 764.865 746.027 27.2239 4.42833 -4.15243 20.5736 +15 3644 772.943 753.485 21.9899 4.51028 -4.16467 19.9184 +10 3645 794.716 779.289 70.7632 6.44681 -3.5546 25.1225 +11 3645 802.65 786.706 65.5316 6.50517 -3.61567 24.3084 +12 3645 810.759 794.136 60.4306 6.5013 -3.6327 23.3148 +10 3648 697.179 682.251 102.221 3.15287 -2.54162 25.9635 +11 3648 701.237 685.672 98.2074 3.16389 -2.57614 24.9011 +10 3649 825.782 806.906 66.4444 6.15308 -3.02812 20.5329 +11 3649 835.633 818.542 60.6567 7.10525 -3.52624 22.6772 +12 3649 845.724 828.067 54.5668 7.18432 -3.59839 21.9498 +13 3649 856.072 838.675 50.1955 7.61134 -3.78722 22.2783 +10 3650 708.52 693.223 114.26 3.47508 -2.05759 25.3374 +11 3650 713.107 696.346 110.993 3.31846 -1.98251 23.1237 +12 3650 717.478 700.257 107.689 3.36625 -2.03267 22.5065 +10 3653 842.659 825.719 83.873 7.3915 -2.82156 22.8797 +11 3653 853.43 835.605 78.8434 7.34864 -2.83285 21.7423 +12 3653 864.599 846.237 73.7673 7.46075 -2.89861 21.1073 +13 3653 877.279 857.897 69.0828 7.41951 -2.87588 19.9965 +14 3653 891.036 870.606 64.9773 7.40081 -2.83638 18.9713 +15 3653 906.961 884.993 60.9525 7.27191 -2.73616 17.6427 +16 3653 924.455 901.333 55.5287 7.31522 -2.72553 16.7617 +17 3653 944.001 920.018 49.1208 7.49068 -2.77132 16.1607 +18 3653 965.921 940.236 42.8493 7.45246 -2.71874 15.0892 +10 3662 1032.14 1015.76 51.6636 13.8594 -3.97469 23.6643 +11 3662 1051.17 1033.93 42.9553 13.7641 -4.04869 22.4889 +10 3664 1091.75 1062.54 93.8699 8.86595 -1.45225 13.2667 +11 3664 1129.9 1098.76 86.5448 8.97426 -1.48857 12.4443 +12 3664 1173.68 1139.97 77.915 8.98815 -1.51265 11.4962 +13 3664 1225.37 1189.02 69.2863 9.10058 -1.53055 10.6631 +10 3666 1088.44 1059.33 103.387 8.83454 -1.28154 13.3111 +11 3666 1125.6 1094.82 96.9443 9.00579 -1.32475 12.592 +10 3672 1094.48 1065.83 75.3141 9.09378 -1.82919 13.5312 +11 3672 1132.06 1101.56 67.1564 9.20092 -1.86126 12.7058 +10 3673 1074.35 1055.13 31.8116 12.9871 -3.94098 20.1611 +11 3673 1098.62 1078.35 23.4891 12.9614 -3.95861 19.1229 +10 3679 1158.41 1128.86 115.14 9.97743 -1.04917 13.1167 +11 3679 1203.07 1171.34 109.544 10.0477 -1.07178 12.215 +10 3683 1137.97 1108.21 100.006 9.53716 -1.3148 13.0227 +11 3683 1181.56 1149.24 93.2614 9.50569 -1.32269 11.9907 +10 3688 127.483 111.615 166.111 -16.3188 -0.228258 24.4249 +11 3688 105.904 88.0879 165.671 -15.1852 -0.21658 21.7543 +10 3689 116.478 99.7881 137.504 -15.869 -1.13767 23.2215 +11 3689 96.6262 79.0644 134.324 -15.6887 -1.17849 22.0691 +12 3689 73.901 56.3821 132.519 -16.4239 -1.23673 22.1232 +10 3694 260.594 255.163 177.983 -34.5143 0.507238 71.3634 +11 3694 256.839 251.303 177.325 -34.2193 0.433714 70.0004 +10 3695 255.022 251.639 190.669 -56.2877 2.82837 114.554 +11 3695 252.98 249.098 189.356 -49.3361 2.28324 99.8317 +12 3695 250.14 246.43 189.458 -52.0344 2.40385 104.46 +13 3695 247.656 244.07 189.846 -54.2095 2.54529 108.079 +10 3699 169.917 153.459 150.757 -14.3486 -0.721177 23.5488 +11 3699 152.187 134.326 148.827 -13.7551 -0.722603 21.6996 +10 3700 191.793 175.29 166.262 -13.5983 -0.21457 23.4861 +11 3700 175.459 159.762 165.124 -14.855 -0.264518 24.6912 +10 3702 227.08 181.997 233.436 -4.55715 0.721815 8.59694 +11 3702 182.581 132.105 240.192 -4.54385 0.716599 7.67851 +12 3702 125.589 68.47 249.721 -4.55125 0.722853 6.78533 +10 3708 148.973 95.0959 239.592 -4.59204 0.665377 7.19372 +11 3708 82.7518 21.4261 247.85 -4.61429 0.656885 6.31993 +10 3712 318.685 285.088 214.347 -4.65042 0.663385 11.5358 +11 3712 294.611 258.169 216.894 -4.64225 0.649132 10.6353 +12 3712 265.635 225.853 220.997 -4.64386 0.650048 9.74261 +13 3712 231.005 187.584 226.221 -4.68306 0.660199 8.92608 +10 3714 343.61 326.877 145.291 -8.53774 -0.884838 23.1634 +11 3714 333.54 316.168 143.166 -8.53462 -0.917963 22.3102 +10 3718 359.943 331.861 217.919 -4.77469 0.862007 13.8016 +11 3718 343.307 313.373 220.177 -4.77775 0.849184 12.9476 +10 3723 489.314 482.35 166.944 -9.27515 -0.455868 55.6558 +11 3723 488.22 481.139 165.837 -9.20401 -0.532244 54.7314 +12 3723 486.636 479.522 165.286 -9.28145 -0.571462 54.4806 +13 3723 485.129 478.065 165.179 -9.46183 -0.583648 54.8666 +10 3726 430.045 414.263 205.649 -6.10982 1.11617 24.5577 +11 3726 423.889 407.763 206.023 -6.18437 1.10482 24.0333 +12 3726 417.078 400.39 207.064 -6.19536 1.10112 23.224 +13 3726 409.861 392.944 208.504 -6.34082 1.13196 22.9103 +14 3726 402.255 384.444 211.098 -6.25187 1.15337 21.7601 +15 3726 394.672 375.879 214.3 -6.14171 1.18456 20.6224 +16 3726 386.246 366.408 217.368 -6.04667 1.20531 19.5371 +10 3727 524.853 518.578 172.879 -7.25016 0.00213962 61.758 +11 3727 524.192 517.978 171.854 -7.37961 -0.0864333 62.3737 +10 3728 417.794 396.057 222.669 -4.73875 1.23099 17.8301 +11 3728 408.008 385.434 223.93 -4.79582 1.21532 17.1687 +12 3728 397.446 375.806 225.917 -5.26506 1.31713 17.9099 +10 3733 453.916 446.296 183.46 -10.9719 0.74763 50.864 +11 3733 451.628 444.258 182.686 -11.5106 0.716618 52.5884 +10 3734 641.415 631.655 133.476 1.75313 -2.16707 39.7082 +11 3734 642.749 632.908 131.429 1.81153 -2.26098 39.3819 +12 3734 644.032 634.019 129.932 1.84936 -2.30265 38.7083 +10 3737 682.441 667.303 146.189 2.58606 -0.946152 25.6023 +11 3737 685.972 670.309 144.137 2.6204 -0.984768 24.7434 +12 3737 689.532 673.271 142.3 2.64173 -1.00928 23.8344 +13 3737 693.742 676.822 140.746 2.67258 -1.01936 22.907 +10 3740 635.377 624.606 127.498 1.28754 -2.26193 35.9838 +11 3740 637.245 625.974 125.338 1.31946 -2.26459 34.3878 +12 3740 637.645 626.7 123.662 1.37831 -2.41406 35.4091 +10 3743 639.066 631.367 138.458 2.05858 -2.39969 50.3386 +11 3743 639.991 632.192 136.602 2.09603 -2.4969 49.6969 +12 3743 640.889 632.821 135.246 2.08569 -2.50363 48.0338 +13 3743 643.034 633.557 134.223 1.89736 -2.18963 40.8969 +10 3747 733.712 729.581 144.185 16.1428 -3.7277 93.8172 +11 3747 735.695 731.735 142.832 17.1105 -4.0726 97.8778 +12 3747 737.7 733.533 141.766 16.5169 -4.00713 93.0038 +10 3749 711.957 702.004 181.139 5.52585 0.447092 38.9373 +11 3749 715.159 705.211 180.545 5.702 0.415287 38.9605 +12 3749 718.974 707.298 180.387 5.03364 0.346539 33.1944 +10 3750 713.853 694.919 206.222 2.95885 0.946655 20.4703 +11 3750 719.408 700.086 206.951 3.05375 0.947872 20.0584 +10 3751 756.082 734.264 235.399 3.60724 1.53979 17.7635 +11 3751 765.423 741.71 238.058 3.53075 1.47705 16.3449 +12 3751 775.313 750.487 241.216 3.58638 1.47913 15.6118 +10 3753 807.875 788.652 219.875 5.54152 1.31391 20.1619 +11 3753 818.776 798.147 221.518 5.44771 1.26715 18.7879 +12 3753 830.043 808.66 222.927 5.5386 1.25785 18.1252 +13 3753 842.875 820.053 225.661 5.49131 1.24287 16.9821 +10 3782 984.451 962.353 160.644 9.11254 -0.296783 17.5385 +11 3782 1007.32 983.901 159.265 9.124 -0.311712 16.551 +10 3787 986.065 964.398 146.819 9.33397 -0.645447 17.8877 +11 3787 1008.94 984.902 145.086 8.92482 -0.620519 16.124 +10 3793 1169.98 1142.33 154.289 10.8876 -0.360676 14.0176 +11 3793 1214.93 1184.53 151.892 10.6963 -0.370368 12.7488 +10 3798 1140.87 1112.12 151.103 9.92842 -0.406452 13.4832 +11 3798 1182.98 1152.13 148.094 9.98282 -0.431045 12.5614 +10 3799 1126.45 1097.11 128.83 9.46339 -0.806003 13.2102 +11 3799 1167.82 1136.65 124.423 9.62189 -0.834733 12.436 +12 3799 1215.85 1182.15 118.844 9.66344 -0.860844 11.5002 +10 3800 1163.56 1135.72 133.335 10.6893 -0.762506 13.9219 +11 3800 1206.73 1176.11 128.189 10.4777 -0.783667 12.6598 +10 3802 1122.46 1091.94 145.553 9.02458 -0.48037 12.6955 +11 3802 1161.44 1132.33 142.087 10.1832 -0.567704 13.3137 +12 3802 1206.3 1174.54 137.557 10.0943 -0.597077 12.2054 +10 3809 301.303 254.872 322.766 -3.56617 1.7343 8.34735 +11 3809 264.303 211.869 340.165 -3.53697 1.71401 7.39176 +10 3815 500.076 459.688 296.93 -1.4561 1.65018 9.5963 +11 3815 488.867 444.754 309.529 -1.46961 1.66422 8.78583 +12 3815 476.41 425.914 324.88 -1.41636 1.61715 7.67527 +13 3815 459.863 403.015 345.409 -1.41448 1.63047 6.81781 +10 3816 510.958 469.375 307.583 -1.2737 1.74038 9.32058 +11 3816 504.22 458.365 321.292 -1.23398 1.73885 8.45228 +10 3822 553.935 510.958 305.589 -0.695237 1.65902 9.01828 +11 3822 548.943 501.135 319.162 -0.681073 1.64388 8.10701 +10 3831 576.079 545.618 265.914 -0.590402 1.64103 12.7237 +11 3831 574.272 541.631 272.073 -0.580709 1.6328 11.874 +10 3833 576.103 540.316 285.463 -0.502158 1.6902 10.8299 +11 3833 571.737 534.828 295.265 -0.550431 1.78148 10.5007 +10 3835 751.692 720.096 264.54 2.41633 1.5587 12.2665 +11 3835 765.035 730.289 271.483 2.40354 1.52473 11.1544 +12 3835 779.705 741.602 279.392 2.39858 1.50189 10.1717 +13 3835 798.214 755.784 290.605 2.38828 1.49067 9.13431 +14 3835 820.765 772.88 305.651 2.36919 1.48964 8.09378 +15 3835 848.651 794.933 323.635 2.39081 1.50774 7.21505 +16 3835 884.066 823.522 345.675 2.43542 1.53327 6.40148 +10 3836 721.862 688.442 269.793 1.80497 1.55804 11.5968 +11 3836 732.74 695.85 277.279 1.79363 1.52053 10.5063 +10 3837 752.681 717.564 273.97 2.1892 1.54668 11.0367 +11 3837 766.348 728.035 282.378 2.19821 1.53555 10.1162 +12 3837 782.97 740.522 292.338 2.1944 1.51199 9.1306 +13 3837 803.438 755.9 306.084 2.19069 1.5054 8.15285 +14 3837 828.873 775.547 323.869 2.20913 1.52116 7.268 +10 3840 802.197 752.927 306.569 2.10017 1.45779 7.86635 +11 3840 829.48 773.31 323.31 2.10311 1.43881 6.90009 +10 3843 739.093 705.787 269.268 2.08908 1.55494 11.6368 +11 3843 750.737 714.792 276.519 2.1097 1.54914 10.7824 +11 3899 833.794 816.71 96.9383 7.05002 -2.38681 22.6854 +12 3899 843.898 826.086 92.6202 7.06701 -2.41963 21.7596 +11 3900 829.469 812.275 28.9878 6.87019 -4.49452 22.5415 +12 3900 839.137 821.259 21.838 6.89788 -4.53742 21.6793 +11 3901 823.696 806.657 37.9844 6.75033 -4.25155 22.7453 +12 3901 833.135 815.336 31.4131 6.7474 -4.26862 21.7756 +13 3901 843.811 825.104 25.2523 6.72603 -4.23806 20.7174 +11 3905 1139.96 1108.32 109.759 9.00389 -1.07106 12.2485 +12 3905 1185.04 1150.92 102.874 9.05943 -1.10165 11.3588 +11 3906 123.184 105.383 145.494 -14.6759 -0.825552 21.7718 +12 3906 101.401 83.0309 144.306 -14.8591 -0.834769 21.0985 +13 3906 78.5281 58.6793 143.276 -14.3708 -0.800456 19.5264 +11 3911 603.208 597.988 178.463 -0.653617 0.577178 74.2484 +12 3911 603.447 598.323 178.069 -0.64075 0.546691 75.6396 +13 3911 603.974 599.296 178.264 -0.641281 0.621205 82.8476 +14 3911 604.946 599.623 179.306 -0.465627 0.651104 72.8188 +15 3911 605.676 600.199 181.097 -0.380878 0.808466 70.7641 +16 3911 607.097 601.774 181.967 -0.248534 0.919712 72.8213 +17 3911 608.293 603.188 182.81 -0.133265 1.04767 75.9254 +18 3911 609.632 604.074 183.45 0.00702769 1.02405 69.7306 +11 3926 394.194 358.281 283.946 -3.22128 1.66163 10.7922 +12 3926 375.15 335.932 294.04 -3.21054 1.6598 9.8824 +11 3929 786.552 738.511 309.625 1.979 1.52927 8.0677 +12 3929 810.161 755.445 326.359 1.96932 1.50697 7.08339 +13 3929 840.316 777.386 348.783 1.96966 1.50167 6.15881 +11 3933 838.416 783.608 312.916 2.24294 1.37269 7.0715 +12 3933 871.674 810.149 333.662 2.28843 1.40396 6.29948 +13 3933 917.742 845.338 361.864 2.28635 1.40223 5.35295 +11 3937 859.489 804.304 294.156 2.43273 1.18071 7.02319 +12 3937 895.916 834.386 309.949 2.49988 1.19683 6.29899 +11 3952 138.362 120.799 30.5354 -14.4112 -4.3527 22.0677 +12 3952 117.698 97.4998 24.327 -13.0807 -3.94996 19.1888 +11 3953 133.349 114.819 87.9623 -13.8042 -2.46081 20.9157 +12 3953 111.118 92.5374 83.7537 -14.4096 -2.57582 20.8591 +13 3953 88.5485 69.4539 80.1797 -14.6566 -2.60703 20.2977 +14 3953 66.0451 43.4818 76.3262 -12.9391 -2.29797 17.1772 +11 3956 101.681 80.848 77.66 -13.0951 -2.45447 18.604 +12 3956 75.2855 55.0515 71.7488 -14.1833 -2.68402 19.1546 +11 3966 268.844 250.217 49.8914 -9.82512 -3.54584 20.8068 +12 3966 253.476 234.39 44.1809 -10.0212 -3.62124 20.3062 +13 3966 237.711 217.595 38.0933 -9.92923 -3.59843 19.2668 +14 3966 220.07 198.883 32.5813 -9.87455 -3.55627 18.2928 +15 3966 201.804 179.4 27.616 -9.77617 -3.48216 17.2993 +16 3966 181.082 158.125 21.9222 -10.0259 -3.53162 16.8831 +11 3983 286.737 269.61 30.3627 -10.1241 -4.46871 22.6284 +12 3983 272.258 253.796 23.3093 -9.81373 -4.35098 20.993 +11 3984 285.382 267.646 55.6797 -9.81821 -3.5488 21.8529 +12 3984 271.389 253.988 50.3571 -10.4391 -3.78141 22.2735 +11 3987 312.418 294.789 90.7152 -9.05425 -2.50286 21.9861 +12 3987 300.007 281.23 87.0328 -8.8552 -2.45504 20.6406 +13 3987 286.383 267.058 83.1637 -8.98298 -2.49302 20.0558 +14 3987 272.128 250.766 80.3685 -8.48453 -2.3255 18.1427 +15 3987 255.565 235.806 76.8879 -9.62318 -2.6088 19.6147 +11 3989 345.403 327.042 102.016 -7.7278 -2.07234 21.1083 +12 3989 333.853 314.681 98.6169 -7.72483 -2.08 20.2163 +13 3989 321.638 301.375 95.2983 -7.63224 -2.05585 19.1266 +14 3989 308.094 286.879 92.7315 -7.63288 -2.02864 18.2688 +15 3989 294.089 271.647 90.1114 -7.55068 -1.98042 17.2698 +16 3989 278.212 255.117 87.1084 -7.70643 -1.99426 16.7814 +17 3989 261.033 236.84 82.7633 -7.73825 -2.00026 16.0201 +18 3989 242.657 216.29 77.5577 -7.47469 -1.94142 14.6995 +19 3989 221.102 193.695 71.2107 -7.61342 -1.99212 14.1415 +20 3989 196.255 166.954 64.0518 -7.57676 -1.99458 13.2273 +11 3996 375.102 356.084 96.7721 -6.62219 -2.14891 20.3796 +12 3996 364.565 345.541 92.6671 -6.91758 -2.26413 20.3731 +11 3997 390.565 371.932 98.1655 -6.3131 -2.15309 20.8002 +12 3997 381.036 362.058 94.496 -6.46813 -2.21785 20.4224 +11 3998 389.362 369.706 40.2149 -6.01729 -3.62461 19.7174 +12 3998 379.387 358.506 33.6587 -5.92097 -3.58067 18.5609 +11 4000 333.069 315.136 79.563 -8.28193 -2.79441 21.6127 +12 4000 321.334 302.101 75.7761 -8.04969 -2.71124 20.1515 +11 4001 411.681 393.72 93.9714 -5.91791 -2.35913 21.5789 +12 4001 403.371 384.604 90.3097 -5.90166 -2.36264 20.6523 +13 4001 394.522 375.37 86.6393 -6.0311 -2.41804 20.2368 +14 4001 385.086 364.601 83.8742 -5.88604 -2.33319 18.9199 +11 4002 299.294 280.889 78.2958 -9.05521 -2.75972 21.0583 +12 4002 285.622 266.66 74.2361 -9.17635 -2.7936 20.4394 +13 4002 271.763 252.074 69.6883 -9.21567 -2.81454 19.6848 +14 4002 256.15 236.834 66.2447 -9.82794 -2.96469 20.0652 +15 4002 241.351 220.137 61.4528 -9.3232 -2.82073 18.2697 +11 4008 501.025 482.964 70.8665 -3.22786 -3.03316 21.4589 +12 4008 496.545 477.728 65.7562 -3.22616 -3.05726 20.5973 +13 4008 491.928 472.379 60.8856 -3.23214 -3.07656 19.8257 +11 4010 502.031 485.12 115.415 -3.41536 -1.82441 22.9179 +12 4010 498.041 480.476 112.705 -3.4102 -1.83933 22.0645 +11 4013 505.208 486.993 42.4583 -3.0772 -3.84522 21.2773 +12 4013 500.792 481.591 36.2334 -3.04272 -3.82192 20.1848 +13 4013 496.603 476.967 30.2996 -3.08993 -3.89959 19.7377 +11 4014 457.277 439.857 113.003 -4.69558 -1.84549 22.2485 +12 4014 451.204 432.8 110.015 -4.6218 -1.83404 21.059 +13 4014 444.819 425.557 107.364 -4.59418 -1.82634 20.1218 +11 4017 528.969 511.312 65.2652 -2.45167 -3.27299 21.9501 +12 4017 525.773 507.285 60.508 -2.43429 -3.26407 20.9634 +13 4017 523.644 503.251 55.3674 -2.263 -3.09457 19.0051 +11 4021 424.726 405.373 46.3211 -5.13033 -3.51211 20.0273 +12 4021 416.354 396.105 39.7743 -5.12508 -3.53015 19.1399 +11 4024 492.949 475.071 32.3236 -3.50349 -4.22216 21.6782 +12 4024 487.979 469.396 25.6882 -3.51435 -4.2539 20.8564 +13 4024 483.34 463.481 18.7822 -3.41401 -4.16736 19.5163 +11 4025 477.15 457.331 35.1047 -3.58859 -3.73332 19.5553 +12 4025 470.926 451.293 28.4181 -3.79295 -3.95169 19.7409 +13 4025 464.66 445.178 21.5451 -3.99517 -4.17189 19.8943 +14 4025 458.286 437.561 17.0649 -3.92078 -4.03782 18.7012 +11 4026 423.99 405.401 69.5969 -5.36229 -2.98376 20.8499 +12 4026 415.652 396.713 65.9639 -5.49941 -3.03151 20.4636 +13 4026 407.312 387.606 61.9357 -5.51298 -3.02348 19.6681 +11 4035 616.784 606.642 111.87 0.382647 -3.23016 38.2179 +12 4035 617.327 607.297 109.786 0.41601 -3.3776 38.6416 +11 4036 637.8 627.984 116.684 1.54543 -3.07382 39.4853 +12 4036 638.887 628.853 114.734 1.57005 -3.11143 38.6273 +13 4036 640.309 629.9 113.321 1.58689 -3.07231 37.2365 +14 4036 641.605 630.911 112.948 1.60962 -3.00899 36.2419 +15 4036 643.591 632.554 112.799 1.65628 -2.92281 35.1167 +16 4036 645.534 634.223 112.179 1.70846 -2.88151 34.2665 +17 4036 647.928 636.231 110.936 1.76203 -2.84352 33.1358 +18 4036 650.278 638.379 110.071 1.83812 -2.83416 32.5715 +11 4041 566.981 561.003 98.2957 -3.82623 -6.69999 64.8391 +12 4041 566.647 560.788 96.65 -3.93404 -6.98612 66.1481 +13 4041 566.685 560.812 95.5812 -3.92126 -7.06739 65.992 +11 4048 661.788 646.092 97.758 1.78744 -2.57006 24.6936 +12 4048 664.729 648.525 94.4715 1.82882 -2.59828 23.918 +13 4048 668.406 651.338 92.0664 1.85194 -2.54245 22.7073 +11 4049 565.668 552.929 63.6593 -1.85063 -4.6041 30.423 +12 4049 565.115 552.666 59.933 -1.91774 -4.87246 31.1338 +11 4052 722.38 705.394 71.8962 3.56769 -3.19255 22.8169 +12 4052 727.585 710.057 66.99 3.61693 -3.24423 22.1117 +13 4052 733.267 715.174 62.3431 3.67282 -3.28102 21.4222 +14 4052 739.399 720.256 58.4845 3.64327 -3.20918 20.2461 +11 4054 727.267 710.814 85.3289 3.84274 -2.85738 23.5556 +12 4054 732.494 715.551 80.9006 3.89732 -2.91513 22.8744 +13 4054 738.583 720.612 76.8027 3.85652 -2.87098 21.5668 +14 4054 744.977 725.968 73.5708 3.82647 -2.80542 20.3883 +15 4054 752.086 732.658 70.6118 3.94071 -2.8269 19.9498 +11 4059 796.266 780.236 48.6011 6.25613 -4.16344 24.1771 +12 4059 804.15 787.412 42.6735 6.24478 -4.17775 23.1556 +13 4059 812.914 795.48 37.2077 6.26533 -4.17924 22.2305 +14 4059 822.211 803.952 32.5519 6.256 -4.12755 21.2269 +11 4060 733.802 717.449 53.9311 4.08104 -3.90629 23.7006 +12 4060 738.751 722.05 47.9131 4.15519 -4.01847 23.2068 +11 4061 833.794 816.71 96.9383 7.05002 -2.38681 22.6854 +12 4061 843.898 826.086 92.6202 7.06701 -2.41963 21.7596 +11 4064 728.446 712 37.7668 3.88313 -4.41228 23.5672 +12 4064 733.33 716.74 31.1429 4.00732 -4.58818 23.3612 +13 4064 739.111 721.799 25.1489 4.0197 -4.58294 22.3876 +11 4066 814.745 798.372 55.3832 6.73157 -3.85389 23.6717 +12 4066 823.633 806.472 49.775 6.70052 -3.85238 22.5842 +13 4066 833.432 815.533 44.7203 6.71845 -3.84531 21.6534 +11 4068 731.755 716.86 95.3044 4.4066 -2.79657 26.0199 +12 4068 736.54 720.328 91.5733 4.20719 -2.69303 23.9063 +11 4075 847.052 829.116 97.5068 7.11242 -2.25649 21.6086 +12 4075 858.009 839.344 93.4958 7.15018 -2.28386 20.7653 +13 4075 870.293 850.889 90.0375 7.21775 -2.29257 19.974 +14 4075 883.411 863.325 87.0663 7.32361 -2.29422 19.2961 +15 4075 898.303 877.387 84.0604 7.41517 -2.28029 18.5297 +11 4077 937.401 873.809 103.971 2.76924 -0.581851 6.09475 +12 4077 996.3 921.151 90.6933 2.76435 -0.587269 5.15741 +11 4078 835.278 818.431 106.119 7.19696 -2.12781 23.006 +12 4078 845.294 827.951 102.401 7.30116 -2.18206 22.3474 +13 4078 857.101 838.327 99.5574 7.08237 -2.09707 20.6438 +11 4079 945.366 882.115 116.287 2.85182 -0.480394 6.12763 +12 4079 1005.15 930.804 103.916 2.85808 -0.498063 5.21297 +13 4079 1091.17 1000.94 88.2987 2.86734 -0.503416 4.29581 +11 4092 1107.38 1077 75.9197 8.8027 -1.71405 12.7586 +12 4092 1147.8 1115.27 66.9227 8.88825 -1.74929 11.9151 +11 4095 1126.91 1096.26 78.0709 9.06686 -1.66112 12.6453 +12 4095 1169.77 1136.97 69.0498 9.17445 -1.69998 11.8165 +11 4097 1174.52 1142.05 86.7969 9.34685 -1.42376 11.9374 +12 4097 1223.87 1188.71 77.2516 9.38578 -1.46067 11.0241 +11 4103 1156.28 1124.75 114.298 9.3127 -0.997418 12.2904 +12 4103 1203.56 1169.37 107.942 9.33334 -1.01994 11.3373 +11 4105 1138.78 1107.31 114.721 9.03341 -0.992289 12.3162 +12 4105 1184.25 1150.43 108.4 9.12863 -1.02383 11.4613 +11 4108 1179.12 1147.99 101.967 9.82707 -1.22307 12.4492 +12 4108 1227.94 1193.95 94.2436 9.77262 -1.24232 11.4028 +11 4116 1176.76 1145.07 111.18 9.61233 -1.04517 12.2278 +12 4116 1226.37 1191.8 104.366 9.58616 -1.06441 11.2138 +11 4117 1113.68 1083.12 96.7737 8.85962 -1.33707 12.6806 +12 4117 1154.77 1122.32 88.9148 9.02624 -1.38966 11.9454 +13 4117 1203.8 1168.24 81.1679 8.97421 -1.38463 10.8966 +11 4118 1118.97 1097.21 41.2677 12.5749 -3.24822 17.8112 +12 4118 1148 1124.94 31.1852 12.545 -3.30072 16.811 +11 4138 164.92 147.326 145.72 -13.5751 -0.828425 22.029 +12 4138 145.763 127.602 143.928 -13.7172 -0.855509 21.3402 +13 4138 125.842 106.59 142.699 -13.4968 -0.841387 20.1325 +11 4140 201.249 153.189 230.723 -4.56353 0.646785 8.06435 +12 4140 149.705 95.656 238.331 -4.57014 0.650729 7.17081 +13 4140 83.8802 21.918 248.272 -4.55711 0.653803 6.25501 +11 4148 259.431 248.647 200.797 -17.4397 1.39181 35.9395 +12 4148 250.362 239.352 201.643 -17.5242 1.40456 35.2018 +11 4157 416.501 399.973 210.968 -6.27401 1.23864 23.4486 +12 4157 408.772 392.502 212.778 -6.62889 1.31808 23.8212 +13 4157 401.661 384.57 214.27 -6.53426 1.3017 22.678 +14 4157 393.795 375.848 217.045 -6.45801 1.32266 21.5962 +15 4157 385.612 366.961 220.441 -6.44972 1.3705 20.7804 +16 4157 376.886 357.28 223.83 -6.37452 1.39659 19.7679 +11 4159 302.115 265.966 222.787 -4.56841 0.741967 10.7215 +12 4159 274.051 234.789 226.909 -4.59017 0.739539 9.87153 +11 4160 454.92 437.787 133.946 -4.84799 -1.21979 22.6205 +12 4160 448.603 430.706 132.057 -4.83088 -1.22446 21.656 +13 4160 442.237 423.719 130.284 -4.85355 -1.23483 20.9298 +11 4162 431.238 415.588 218.421 -6.12052 1.56399 24.7653 +12 4162 425.08 409.074 219.876 -6.19103 1.57804 24.2144 +13 4162 418.532 401.999 221.844 -6.2066 1.59171 23.4432 +11 4166 446.864 437.834 205.238 -9.6783 1.92641 42.9222 +12 4166 443.521 434.377 205.648 -9.75378 1.92649 42.3862 +11 4167 417.284 394.979 227.901 -4.63041 1.32565 17.3762 +12 4167 408.257 383.466 229.453 -4.36172 1.22635 15.6339 +11 4170 508.368 491.749 222.796 -3.2708 1.61426 23.3222 +12 4170 503.811 487.74 224.657 -3.53462 1.7315 24.1172 +13 4170 500.829 483.479 226.524 -3.36625 1.6616 22.3386 +14 4170 496.504 479.325 229.904 -3.53493 1.78379 22.5605 +15 4170 492.581 475.252 233.95 -3.62589 1.89374 22.365 +16 4170 488.934 470.359 237.469 -3.48813 1.86849 20.8649 +17 4170 485.166 465.169 240.544 -3.34152 1.81833 19.3823 +18 4170 480.346 459.846 244.256 -3.3858 1.87096 18.9066 +11 4172 455.259 437.938 137.421 -4.78515 -1.09886 22.3762 +12 4172 449.125 431.132 135.63 -4.78962 -1.11128 21.5408 +13 4172 442.476 423.823 133.933 -4.81162 -1.12084 20.7786 +11 4174 511.984 506.75 184.965 -10.0144 1.24294 74.0531 +12 4174 511.379 505.208 184.775 -8.54559 1.03763 62.8028 +13 4174 510.969 504.683 185.17 -8.425 1.05247 61.6585 +14 4174 510.618 507.232 186.718 -15.6947 2.19913 114.455 +15 4174 510.802 503.919 188.663 -7.70728 1.23381 56.3107 +16 4174 510.913 504.181 190.406 -7.87013 1.40029 57.5655 +17 4174 510.863 503.955 191.274 -7.67522 1.43248 56.1109 +18 4174 510.763 503.626 192.312 -7.43623 1.46455 54.3087 +19 4174 510.647 503.434 192.693 -7.36666 1.47751 53.7377 +20 4174 510.501 503.1 192.852 -7.18949 1.45144 52.3681 +21 4174 510.318 502.9 192.506 -7.18582 1.42296 52.2448 +22 4174 510.092 502.383 192.688 -6.93069 1.38197 50.2753 +11 4177 664.866 645.109 230.699 1.50366 1.57267 19.6169 +12 4177 668.268 647.83 232.953 1.54294 1.57948 18.9628 +13 4177 672.278 650.559 236.174 1.55113 1.56602 17.8448 +14 4177 676.306 653.275 240.65 1.55674 1.58121 16.8286 +11 4178 690.349 674.079 158.738 2.66731 -0.46605 23.8219 +12 4178 693.238 676.971 157.146 2.76312 -0.518703 23.8258 +11 4180 774.161 759.394 144.946 5.98737 -1.01514 26.2458 +12 4180 784.557 764.219 143.202 4.62181 -0.783125 19.0563 +11 4182 766.501 749.607 209.026 4.99011 1.15014 22.942 +12 4182 773.508 756.623 209.748 5.21573 1.17373 22.9544 +11 4194 731.489 711.662 219.636 3.30325 1.26738 19.5475 +12 4194 738.363 717.75 221.473 3.35641 1.26693 18.802 +13 4194 745.826 724.203 224.004 3.38509 1.27065 17.9241 +14 4194 754.57 731.101 228.174 3.31885 1.2661 16.5138 +15 4194 764.495 739.662 232.996 3.35143 1.30095 15.6077 +16 4194 775.796 749.774 237.888 3.43155 1.34246 14.8944 +11 4196 836.594 819.773 132.042 7.25016 -1.3033 23.0417 +12 4196 846.916 829.067 129.371 7.14309 -1.30859 21.7142 +13 4196 858.259 839.773 127.458 7.22671 -1.31913 20.9664 +11 4210 1109.79 1078.76 132.66 8.66102 -0.69592 12.4928 +12 4210 1150.75 1117.37 128.016 8.70917 -0.721566 11.6114 +13 4210 1199.18 1163.46 124.003 8.86708 -0.734648 10.8509 +11 4219 1081.17 1051.34 174.576 8.49053 0.0309996 12.99 +12 4219 1117.18 1086.46 173.465 8.87557 0.0106772 12.6159 +11 4228 1159.44 1131.16 170.163 10.447 -0.0511269 13.7083 +12 4228 1203.3 1172.21 168.337 10.2611 -0.078063 12.4698 +11 4230 1144.91 1115.05 177.161 9.62802 0.0774572 12.9764 +12 4230 1188.1 1155.82 176.112 9.62634 0.0542135 12.0057 +11 4249 175.857 124.448 255.291 -4.53159 0.861353 7.53907 +12 4249 116.605 58.6296 267.024 -4.5673 0.872501 6.68516 +11 4257 280.098 234.829 316.181 -3.90933 1.70069 8.56163 +12 4257 240.929 190.93 332.971 -3.96021 1.72015 7.75152 +11 4260 335.767 293.744 308.681 -3.4997 1.73618 9.22292 +12 4260 305.979 259.759 323.743 -3.52807 1.75357 8.3854 +13 4260 269.012 216.794 342.741 -3.50312 1.74758 7.42226 +11 4264 512.65 459.519 333.21 -0.979735 1.62118 7.29462 +12 4264 499.79 438.642 355.065 -0.964281 1.60065 6.3384 +11 4273 649.636 617.733 266.556 0.674779 1.57769 12.1488 +12 4273 653.847 618.986 273.197 0.682405 1.54614 11.1178 +13 4273 657.97 621.159 281.826 0.706413 1.59013 10.5288 +11 4283 823.534 791.458 259.719 3.58325 1.45465 12.083 +12 4283 842 807.358 266.003 3.60419 1.44435 11.1881 +11 4285 818.065 763.012 302.167 2.03439 1.26171 7.04005 +12 4285 849.186 787.869 319.83 2.0992 1.28755 6.32087 +11 4286 812.152 757.696 322.058 1.99837 1.47173 7.1172 +12 4286 842.788 780.154 342.906 2.00017 1.45837 6.1879 +11 4287 786.779 733.752 330.878 1.7952 1.60075 7.30902 +12 4287 812.978 752.301 352.378 1.80077 1.58924 6.38743 +11 4288 789.53 753.682 271.665 2.69672 1.4806 10.8117 +12 4288 807.008 767.739 279.985 2.70082 1.4654 9.8696 +13 4288 828.307 784.958 290.985 2.71057 1.46379 8.94078 +14 4288 855.118 806.266 306.758 2.7 1.47232 7.93356 +11 4289 768.191 721.781 306.164 1.836 1.54293 8.35105 +12 4289 788.109 736.23 321.503 1.8487 1.53911 7.47079 +13 4289 814.019 755.014 341.903 1.8613 1.53895 6.56853 +11 4290 810.686 755.943 327.744 1.97351 1.51983 7.07993 +12 4290 840.865 778.056 349.282 1.97816 1.50884 6.17069 +11 4292 712.261 679.09 274.125 1.66306 1.63988 11.6839 +12 4292 722.047 685.559 282.218 1.65595 1.60995 10.6218 +12 4330 261.839 242.365 29.5601 -9.59124 -3.9525 19.9023 +13 4330 245.581 226.473 22.9134 -10.2321 -4.21511 20.2838 +12 4331 158.746 140.872 118.476 -13.5477 -1.63413 21.6834 +13 4331 139.901 121.671 115.293 -13.8388 -1.69608 21.2606 +14 4331 120.192 101.506 112.362 -14.0669 -1.73886 20.7406 +15 4331 98.5492 79.6049 110.923 -14.4893 -1.756 20.4586 +12 4333 550.832 531.274 33.5594 -1.61298 -3.82579 19.8174 +13 4333 548.728 528.768 27.2253 -1.63707 -3.91911 19.4178 +14 4333 546.697 525.885 21.2823 -1.62242 -3.91194 18.6223 +12 4344 1137.73 1105.42 95.7311 8.78105 -1.28219 11.9958 +13 4344 1184.12 1149.31 89.0563 8.86681 -1.2932 11.1351 +12 4345 1186.21 1162.57 39.3407 13.1018 -3.03348 16.3937 +13 4345 1223.9 1197.7 31.3715 12.5976 -2.90122 14.7958 +12 4351 700.699 691.652 176.848 5.41103 0.237129 42.8381 +13 4351 703.933 694.25 177.121 5.23517 0.236709 40.0256 +14 4351 707.92 696.991 178.316 4.83429 0.268448 35.4627 +15 4351 712.978 700.464 179.974 4.43891 0.305605 30.9695 +16 4351 718.439 703.935 181.092 4.03227 0.305077 26.7216 +12 4362 717.352 686.382 262.922 1.86959 1.56217 12.5146 +13 4362 726.685 693.097 270.235 1.87309 1.55732 11.5389 +14 4362 737.781 701.197 279.727 1.88262 1.56917 10.594 +15 4362 751.477 711.463 291.106 1.90508 1.5874 9.68581 +16 4362 767.93 723.577 303.866 1.918 1.58667 8.73843 +12 4363 728.381 694.211 272.189 1.86785 1.56153 11.3424 +13 4363 740.012 702.361 281.157 1.86112 1.54511 10.2939 +12 4368 57.8547 39.1904 122.285 -15.8778 -1.45536 20.7655 +13 4368 32.0247 12.094 119.888 -15.5652 -1.42748 19.4462 +12 4370 131.781 110.565 25.9885 -12.0964 -3.71835 18.2679 +13 4370 107.806 87.7895 18.3491 -13.4649 -4.14625 19.363 +14 4370 84.1094 61.172 11.4516 -12.305 -3.77974 16.897 +12 4372 78.4212 58.894 62.1167 -14.6104 -3.04613 19.8478 +13 4372 52.8208 32.2871 56.6816 -14.5639 -3.039 18.875 +14 4372 25.1003 4.96211 51.9464 -15.5894 -3.22499 19.2457 +12 4377 94.8039 76.5811 119.068 -15.1734 -1.58546 21.2687 +13 4377 71.5775 53.1588 116.534 -15.6894 -1.64249 21.0425 +12 4383 230.676 219.483 107.792 -18.1827 -3.12231 34.6267 +13 4383 220.913 207.883 105.47 -16.0219 -2.77789 29.7454 +12 4386 237.782 218.339 21.0681 -10.2712 -4.19342 19.9341 +13 4386 220.8 200.972 13.9525 -10.5319 -4.3048 19.5472 +12 4392 213.429 196.077 92.0532 -12.2627 -2.50129 22.3361 +13 4392 197.598 180.105 89.3251 -12.6495 -2.56481 22.1553 +12 4403 178.866 161.924 42.3284 -13.6555 -4.13843 22.877 +13 4403 162.059 144.62 37.0944 -13.7832 -4.18146 22.2237 +12 4409 282.149 262.975 58.1773 -9.17263 -3.21274 20.2144 +13 4409 267.152 246.961 52.8602 -9.10922 -3.19225 19.1954 +14 4409 250.996 229.829 48.1005 -9.09917 -3.16584 18.3103 +15 4409 234.49 212.175 43.1817 -9.02832 -3.12135 17.3682 +12 4410 313.567 294.09 62.2025 -8.16334 -3.05172 19.8997 +13 4410 300.097 278.999 56.7924 -7.87847 -2.95477 18.3694 +12 4411 318.26 299.648 91.5584 -8.40705 -2.34623 20.8239 +13 4411 305.65 286.229 87.9973 -8.40566 -2.34701 19.9566 +14 4411 291.893 271.525 85.1707 -8.37767 -2.31243 19.0288 +15 4411 277.347 255.827 82.6615 -8.29225 -2.25127 18.0101 +16 4411 261.6 238.751 79.2437 -8.1799 -2.20061 16.9621 +17 4411 243.926 220.199 74.6554 -8.27749 -2.22309 16.3347 +12 4413 335.13 314.316 19.7784 -7.08252 -3.95059 18.6215 +13 4413 322.123 300.638 12.4373 -7.18656 -4.01078 18.0401 +14 4413 307.73 285.107 5.56056 -7.16663 -3.97221 17.1322 +12 4414 290.821 272.018 97.2674 -9.10569 -2.15935 20.6128 +13 4414 276.883 257.808 93.9602 -9.36816 -2.22165 20.3185 +12 4418 329.782 311.357 69.0086 -8.15683 -3.02758 21.0362 +13 4418 318.357 296.383 65.2109 -7.11845 -2.63134 17.638 +12 4419 414.788 395.727 86.2072 -5.4887 -2.44173 20.3331 +13 4419 406.412 386.506 82.2736 -5.48187 -2.44428 19.4704 +12 4422 339.329 320.424 108.407 -7.67803 -1.83112 20.501 +13 4422 327.82 307.844 105.56 -7.57597 -1.80955 19.4021 +12 4424 355.814 336.078 54.0973 -6.906 -3.23212 19.6376 +13 4424 344.619 323.662 48.2248 -6.79079 -3.19442 18.494 +14 4424 331.751 309.477 42.5598 -6.69952 -3.14213 17.4003 +12 4431 510.698 492.854 23.5225 -2.97584 -4.49507 21.7192 +13 4431 507.153 488.038 16.7812 -2.87771 -4.38578 20.2758 +12 4432 438.649 420.445 98.8559 -5.04291 -2.1834 21.2899 +13 4432 431.79 412.692 95.9746 -4.99993 -2.16231 20.2939 +14 4432 424.057 404.129 92.9819 -5.00017 -2.15293 19.4489 +12 4433 482.005 464.043 105.921 -3.81447 -2.00161 21.5774 +13 4433 477.136 458.449 103.014 -3.80645 -2.00752 20.7404 +14 4433 471.81 452.174 100.987 -3.76824 -1.96598 19.7382 +15 4433 466.414 445.845 99.0759 -3.73834 -1.92676 18.8434 +12 4435 553.741 547.248 121.775 -4.61785 -4.22571 59.6924 +13 4435 553.612 546.93 121.005 -4.49807 -4.16855 58.0101 +12 4439 511.048 492.576 62.8981 -2.86454 -3.19733 20.9811 +13 4439 507.653 488.109 57.7875 -2.80083 -3.16253 19.831 +12 4442 481.274 461.771 15.1198 -3.53333 -4.34443 19.8731 +13 4442 476.208 456.115 8.33937 -3.56491 -4.398 19.289 +12 4447 462.275 444.653 106.935 -4.48948 -2.00931 21.9937 +13 4447 456.591 438.694 103.854 -4.59121 -2.07096 21.6563 +14 4447 450.19 431.384 101.636 -4.55196 -2.03414 20.6088 +15 4447 444.48 423.525 100.015 -4.2316 -1.86712 18.4957 +16 4447 437.488 414.769 97.7549 -4.06816 -1.77552 17.0588 +17 4447 429.727 406.06 94.2141 -4.08158 -1.78485 16.3764 +12 4450 454.631 435.314 65.1717 -4.3081 -2.99433 20.0639 +13 4450 447.826 428.296 60.2374 -4.44832 -3.09741 19.8452 +12 4456 678.094 661.294 114.101 2.19128 -1.87852 23.07 +13 4456 681.604 664.199 111.71 2.22345 -1.88703 22.2681 +14 4456 685.285 667.091 110.237 2.23572 -1.8487 21.3027 +15 4456 689.781 670.632 108.896 2.25036 -1.79413 20.2405 +12 4457 561.2 554.852 125.591 -4.09182 -3.99906 61.0514 +13 4457 561.16 554.825 124.913 -4.10403 -4.06512 61.1826 +14 4457 560.831 554.515 125.362 -4.1445 -4.0393 61.3688 +12 4460 645.238 634.73 123.167 1.82394 -2.5401 36.8863 +13 4460 646.836 636.237 121.961 1.88925 -2.57936 36.5692 +14 4460 648.28 637.59 121.78 1.94567 -2.56642 36.2568 +15 4460 650.488 639.591 121.951 2.0175 -2.50918 35.567 +12 4462 680.008 662.618 73.7201 2.17608 -3.06215 22.2876 +13 4462 683.602 665.236 69.554 2.16557 -3.02129 21.1033 +14 4462 687.514 668.182 66.0559 2.16604 -2.96747 20.0485 +15 4462 692.244 672.033 62.8202 2.19753 -2.92438 19.1764 +12 4463 767.124 749.752 11.9946 4.87213 -4.97402 22.3111 +13 4463 774.361 756.555 5.0992 4.97158 -5.06067 21.7667 +12 4465 804.671 787.948 47.9059 6.26713 -4.01343 23.1764 +13 4465 813.439 796.088 42.8883 6.31149 -4.02333 22.3366 +14 4465 822.798 804.619 38.2457 6.30056 -3.97726 21.3192 +15 4465 833.428 814.425 33.7947 6.32784 -3.93063 20.3949 +16 4465 845.027 824.937 27.9113 6.29571 -3.87533 19.2918 +12 4466 826.828 809.253 48.5975 6.64063 -3.7978 22.0532 +13 4466 836.86 818.778 43.3052 6.75255 -3.84859 21.4352 +14 4466 847.575 828.773 38.3692 6.79981 -3.84207 20.6135 +15 4466 859.591 840.121 33.5217 6.89791 -3.84392 19.9059 +12 4468 719.716 702.59 76.3149 3.45503 -3.02792 22.6308 +13 4468 724.795 707.656 72.4563 3.61169 -3.14664 22.6143 +12 4470 720.482 702.853 88.91 3.37972 -2.5577 21.9846 +13 4470 725.877 707.573 85.3441 3.41354 -2.56813 21.1748 +14 4470 731.806 712.879 82.5359 3.46946 -2.5633 20.4779 +15 4470 738.793 718.992 79.6799 3.50576 -2.52756 19.5733 +16 4470 746.284 725.398 75.8531 3.51624 -2.49464 18.5563 +12 4472 709.36 692.085 102.897 3.10327 -2.1753 22.436 +13 4472 714.284 696.368 100.08 3.13979 -2.18188 21.6328 +14 4472 719.517 700.667 98.082 3.1334 -2.13073 20.5612 +15 4472 725.835 706.162 96.0359 3.17482 -2.09745 19.701 +16 4472 732.624 711.961 92.9937 3.19916 -2.07602 18.7568 +17 4472 740.288 718.56 89.2125 3.23177 -2.06772 17.8373 +18 4472 748.669 726.018 86.1601 3.29893 -2.05592 17.111 +19 4472 758.131 734.247 81.3395 3.34141 -2.05819 16.2276 +12 4475 775.838 758.383 54.8278 5.11692 -3.63204 22.204 +13 4475 783.302 765.228 49.9075 5.16361 -3.65395 21.444 +14 4475 791.301 772.375 46.2124 5.15808 -3.59427 20.4783 +15 4475 800.407 780.78 42.1098 5.22314 -3.57822 19.7471 +16 4475 810.473 789.982 37.3056 5.26689 -3.55336 18.9149 +17 4475 821.972 800.393 30.8521 5.28726 -3.53462 17.9601 +12 4482 870.689 852.892 43.7951 7.8818 -3.89545 21.7786 +13 4482 883.206 864.347 38.0364 7.79411 -3.83992 20.5511 +14 4482 896.637 876.653 32.878 7.7161 -3.76228 19.3935 +12 4484 870.806 852.761 51.4338 7.77651 -3.6143 21.4779 +13 4484 883.38 864.583 45.9045 7.82491 -3.62781 20.6192 +14 4484 896.928 877.224 40.84 7.83418 -3.59894 19.6704 +12 4487 887.752 868.207 93.4122 7.64565 -2.18332 19.8302 +13 4487 899.311 881.07 89.9029 8.5326 -2.44274 21.2478 +14 4487 914.554 893.123 86.8444 7.64433 -2.15573 18.0845 +12 4496 852.934 835.109 81.0619 7.33394 -2.76609 21.7431 +13 4496 864.769 845.822 76.3774 7.23512 -2.73508 20.4554 +12 4501 852.098 830.984 114.89 6.17051 -1.47468 18.3569 +13 4501 865.245 843.441 112.402 6.2988 -1.48922 17.775 +12 4503 838.591 827.124 85.4548 10.7286 -4.09406 33.7992 +13 4503 847.217 831.484 82.6425 8.11407 -3.07999 24.6346 +12 4507 998.44 923.747 64.9275 2.79663 -0.776152 5.18893 +13 4507 1082.21 991.558 41.6165 2.80066 -0.777637 4.27542 +12 4520 1032.9 958.132 113.326 3.04124 -0.427638 5.18341 +13 4520 1125.41 1034.14 101.746 3.03604 -0.418509 4.24663 +12 4535 1169.42 1136.13 96.408 9.0329 -1.2334 11.6415 +13 4535 1220.61 1184.7 89.4106 9.14063 -1.24822 10.7934 +12 4536 1165.87 1132.48 116.228 8.95007 -0.911014 11.6083 +13 4536 1215.86 1179.99 111.194 9.07825 -0.92325 10.8037 +12 4538 54.681 36.9698 138.124 -16.8285 -1.05329 21.883 +13 4538 30.1915 12.0261 136.456 -17.1319 -1.07628 21.3359 +12 4548 69.8808 53.1552 137.391 -17.332 -1.13892 23.1725 +13 4548 47.0956 30.9697 135.471 -18.7355 -1.24523 24.0343 +12 4554 85.8913 67.9809 130.097 -15.7054 -1.28233 21.6397 +13 4554 63.0169 46.6701 128.121 -17.9592 -1.46991 23.7095 +12 4561 152.823 101.938 225.539 -4.82142 0.556154 7.61673 +13 4561 91.9423 34.2316 233.45 -4.81779 0.564009 6.71581 +12 4564 173.782 156.662 146.385 -13.6722 -0.830448 22.6377 +13 4564 155.852 139.561 145.345 -14.9593 -0.906995 23.79 +12 4565 139.797 121.808 164.387 -14.0269 -0.252835 21.5449 +13 4565 119.863 100.995 164.177 -13.9411 -0.24702 20.5413 +14 4565 96.7864 76.9634 164.979 -13.8947 -0.213388 19.5517 +12 4570 215.379 204.825 175.727 -20.0631 0.146241 36.7249 +13 4570 205.834 197.47 175.525 -25.9279 0.171512 46.3384 +12 4571 231.975 222.123 145.707 -20.5849 -1.48001 39.3363 +13 4571 223.668 213.753 144.406 -20.9066 -1.54124 39.091 +14 4571 215.57 205.141 145.278 -20.2916 -1.42024 37.1613 +12 4573 158.867 141.64 164.872 -14.053 -0.248879 22.4981 +13 4573 140.37 122.018 164.182 -13.7324 -0.25382 21.1183 +14 4573 119.406 99.8783 165.918 -13.4829 -0.190781 19.8477 +12 4576 208.247 197.428 144.837 -19.9254 -1.39105 35.8248 +13 4576 198.438 191.098 145.339 -30.086 -2.01357 52.8024 +12 4578 139.732 121.774 158.731 -14.0531 -0.42245 21.5821 +13 4578 119.34 100.518 159.04 -13.9905 -0.394243 20.5921 +14 4578 96.8592 77.2008 159.933 -14.0092 -0.353064 19.7155 +12 4581 415.312 398.825 189.518 -6.32833 0.542877 23.5068 +13 4581 407.982 391.029 190.467 -6.38706 0.55808 22.8622 +14 4581 400.577 382.437 191.978 -6.18831 0.566283 21.3659 +12 4582 297.594 261.422 221.601 -4.63261 0.723883 10.7147 +13 4582 269.599 230.014 226.399 -4.61308 0.726574 9.79089 +12 4584 315.456 298.062 154.693 -9.08251 -0.560861 22.2825 +13 4584 303.243 285.234 154.551 -9.1365 -0.545928 21.5213 +12 4585 315.456 298.062 154.693 -9.08251 -0.560861 22.2825 +13 4585 303.243 285.234 154.551 -9.1365 -0.545928 21.5213 +12 4592 524.852 519.145 150.653 -7.97208 -2.08939 67.9067 +13 4592 524.464 518.64 150.358 -7.84867 -2.07485 66.5502 +14 4592 523.802 517.732 150.968 -7.58855 -1.93671 63.8482 +15 4592 523.753 517.592 152.191 -7.48192 -1.80168 62.9145 +16 4592 523.612 517.457 152.839 -7.5001 -1.74656 62.9644 +17 4592 523.522 517.576 152.967 -7.77231 -1.79653 65.1812 +18 4592 523.47 517.554 153.23 -7.81672 -1.78178 65.5141 +12 4594 448.788 431.878 165.815 -5.10699 -0.223585 22.92 +13 4594 442.988 425.106 165.737 -5.00374 -0.213788 21.6747 +14 4594 436.39 417.796 166.398 -5.00234 -0.186486 20.8431 +15 4594 429.919 410.478 167.742 -4.96361 -0.141257 19.9367 +16 4594 422.677 402.383 168.606 -4.94654 -0.112434 19.0982 +12 4596 446.395 439.14 189.599 -12.0806 1.23976 53.4223 +13 4596 444.169 436.919 189.977 -12.2539 1.26868 53.459 +14 4596 441.876 434.358 191.329 -11.9812 1.3201 51.5549 +15 4596 440.039 432.293 193.235 -11.7548 1.41322 50.0327 +16 4596 438.098 430.307 194.852 -11.8218 1.51671 49.7479 +17 4596 436.189 428.463 195.744 -12.0535 1.59142 50.1647 +18 4596 434.222 426.131 196.568 -11.6395 1.57421 47.8981 +19 4596 432.197 423.982 196.674 -11.5962 1.55738 47.1752 +20 4596 429.996 421.568 196.681 -11.4452 1.51873 45.9901 +12 4603 424.042 402.994 235.257 -4.73425 1.59247 18.4131 +13 4603 415.227 393.292 238.467 -4.75894 1.60677 17.6695 +12 4604 433.691 415.798 143.445 -5.27975 -0.88289 21.6613 +13 4604 426.697 407.705 141.225 -5.17171 -0.894533 20.4066 +14 4604 419.246 399.088 140.767 -5.07124 -0.855028 19.2267 +12 4605 545.204 539.136 132.528 -5.6962 -3.56932 63.8649 +13 4605 544.895 538.757 131.997 -5.65828 -3.57513 63.1365 +14 4605 544.435 537.925 132.639 -5.37322 -3.31806 59.5324 +12 4607 558.967 554.277 166.161 -5.79382 -0.766464 82.6309 +13 4607 559.057 554.09 166.138 -5.46246 -0.726443 78.0427 +12 4609 660.704 647.15 196.608 2.02692 0.941401 28.5953 +13 4609 663.145 649.052 197.518 2.04249 0.940121 27.5025 +14 4609 665.52 651.127 199.584 2.08848 0.99756 26.9281 +15 4609 668.931 653.696 201.666 2.09334 1.01586 25.4401 +16 4609 672.212 656.582 203.671 2.15316 1.05907 24.7967 +17 4609 675.899 659.674 205.554 2.19625 1.08257 23.8873 +18 4609 679.848 662.847 207.364 2.22088 1.09042 22.7982 +19 4609 684.088 666.339 208.894 2.25558 1.09072 21.8371 +20 4609 688.597 669.993 209.884 2.28197 1.06913 20.832 +21 4609 693.196 673.949 210.68 2.33422 1.0557 20.1375 +22 4609 698.217 678.067 212.087 2.36342 1.04588 19.2347 +23 4609 703.789 682.64 214.143 2.39327 1.04866 18.3257 +24 4609 710.049 687.725 216.687 2.41789 1.05467 17.361 +12 4614 562.069 558.558 139.796 -7.26669 -5.05834 110.404 +13 4614 562.127 559.107 139.556 -8.43772 -5.92341 128.353 +14 4614 561.923 559.318 140.162 -9.82387 -6.74202 148.8 +15 4614 562.356 561.488 141.219 -29.2408 -19.5964 446.964 +12 4618 664.592 651.42 182.642 2.24429 0.399159 29.4249 +13 4618 667.299 653.508 182.979 2.24889 0.394372 28.1029 +14 4618 669.693 655.472 184.263 2.2714 0.430937 27.2545 +12 4619 561.593 549.469 209.902 -2.12513 1.64141 31.9678 +13 4619 560.682 548.452 211.083 -2.14679 1.67909 31.6913 +14 4619 560.069 547.121 213.211 -2.05306 1.67417 29.9324 +15 4619 559.602 545.982 215.914 -1.97028 1.69825 28.4567 +16 4619 559.213 545.686 218.163 -1.99922 1.79918 28.6517 +17 4619 559.055 545.126 219.988 -1.94764 1.81767 27.8251 +12 4620 560.086 554.519 181.075 -4.77371 0.793251 69.6221 +13 4620 561.059 555.414 180.069 -4.61462 0.686456 68.6518 +14 4620 559.971 554.038 182.492 -4.48928 0.872504 65.3213 +15 4620 560.47 554.517 183.962 -4.42879 1.00213 65.097 +16 4620 561.607 555.814 184.276 -4.4463 1.05909 66.9036 +12 4621 581.385 577.34 151.5 -3.74092 -2.83533 95.806 +13 4621 581.782 577.579 151.21 -3.55 -2.76619 92.2137 +14 4621 582.319 577.644 152.079 -3.12993 -2.38711 82.906 +15 4621 582.885 578.71 153.074 -3.43155 -2.54463 92.8243 +16 4621 583.561 579.237 153.76 -3.22929 -2.3717 89.625 +17 4621 584.387 580.02 153.533 -3.09611 -2.37646 88.7469 +18 4621 584.982 580.477 153.89 -2.93079 -2.26137 86.0413 +12 4623 739.373 735.117 134.209 16.3844 -4.87753 91.0684 +13 4623 741.397 737.174 133.739 16.7714 -4.97588 91.7885 +14 4623 743.435 739.067 134.378 16.4635 -4.7316 88.732 +15 4623 746.033 741.564 135.376 16.405 -4.50504 86.7335 +16 4623 748.812 744.122 135.419 15.9496 -4.28764 82.6427 +12 4625 746.606 724.282 199.218 3.29757 0.634361 17.3614 +13 4625 755.109 731.628 200.93 3.32949 0.642255 16.5053 +14 4625 764.531 739.497 203.635 3.32516 0.660454 15.4817 +12 4627 821.777 804.604 130.78 6.63805 -1.31606 22.5693 +13 4627 831.592 812.643 129.079 6.29403 -1.2409 20.4536 +12 4628 707.777 688.454 182.608 2.73029 0.271157 20.0575 +13 4628 712.714 693.427 182.899 2.87287 0.279768 20.095 +14 4628 717.533 697.966 184.215 2.96406 0.311888 19.8075 +12 4630 722.396 717.153 151.393 11.5594 -2.19856 73.9165 +13 4630 724.182 719.205 151.145 12.3694 -2.3427 77.8637 +14 4630 726.286 721.153 152.393 12.2156 -2.14133 75.5101 +12 4631 722.396 717.153 151.393 11.5594 -2.19856 73.9165 +13 4631 724.182 719.205 151.145 12.3694 -2.3427 77.8637 +12 4634 706.912 684.462 201.838 2.32931 0.693487 17.2638 +13 4634 713.293 689.501 203.84 2.34201 0.699566 16.2903 +12 4635 758.674 737.598 216.566 3.80035 1.11405 18.3892 +13 4635 767.436 745.129 218.857 3.80165 1.10775 17.3746 +14 4635 777.055 753.644 222.43 3.8431 1.1375 16.5553 +15 4635 788.408 763.648 226.717 3.87998 1.16851 15.6532 +16 4635 801.293 774.705 230.938 3.87349 1.17343 14.5768 +12 4639 846.916 829.067 129.371 7.14309 -1.30859 21.7142 +13 4639 858.259 839.773 127.458 7.22671 -1.31913 20.9664 +12 4640 951.958 880.994 141.197 2.59173 -0.239622 5.46156 +13 4640 1021.93 936.117 135.083 2.58116 -0.236419 4.51631 +12 4644 871.346 848.822 134.501 6.2432 -0.914649 17.2076 +13 4644 887.666 862.849 131.651 6.01941 -0.891818 15.6171 +14 4644 903.931 880.435 130.695 6.72983 -0.963823 16.4956 +15 4644 923.496 897.795 129.849 6.56132 -0.898806 15.0802 +16 4644 946.959 917.719 125.576 6.19822 -0.868517 13.2551 +12 4662 1025.06 951.773 183.623 3.04535 0.0789273 5.28839 +13 4662 1116.15 1023.83 186.922 2.94735 0.0818474 4.19791 +12 4664 1052.75 977.737 250.971 3.17352 0.559366 5.16664 +13 4664 1149.33 1058.2 268.458 3.18158 0.563524 4.25298 +12 4670 1156.58 1124.86 156.989 9.26401 -0.268683 12.2196 +13 4670 1204.37 1170.29 155.6 9.375 -0.271948 11.3725 +12 4676 1143.44 1112.78 174.136 9.35241 0.022452 12.6398 +13 4676 1187.44 1154.72 174.476 9.4848 0.0266223 11.8426 +12 4684 176.521 125.655 252.365 -4.57292 0.839646 7.6195 +13 4684 118.224 60.2915 263.237 -4.55562 0.838021 6.69005 +12 4694 587.788 559.711 257.628 -0.416496 1.62181 13.8037 +13 4694 587.721 556.099 264.038 -0.370968 1.54893 12.2567 +14 4694 585.934 553.126 271.903 -0.386799 1.62166 11.8132 +15 4694 585.67 550.162 281.048 -0.361394 1.63672 10.9152 +12 4696 557.433 523.104 273.165 -0.815616 1.56958 11.2899 +13 4696 553.45 516.996 282.227 -0.826774 1.61161 10.6318 +14 4696 547.841 507.922 293.556 -0.830483 1.62417 9.709 +12 4699 583.794 539.806 307.053 -0.31462 1.63872 8.81077 +13 4699 582.18 532.708 322.145 -0.29727 1.62093 7.83414 +14 4699 579.827 523.83 342.852 -0.2852 1.63068 6.92127 +12 4703 557.279 508.159 324.58 -0.571712 1.6592 7.89037 +13 4703 551.529 495.201 344.681 -0.553389 1.63857 6.8807 +12 4705 642.576 595.73 316.478 0.378578 1.64682 8.27327 +13 4705 648.309 596.2 334.215 0.399435 1.66335 7.43776 +12 4707 824.413 790.825 259.369 3.43599 1.38357 11.539 +13 4707 842.533 807.376 266.873 3.55956 1.4365 11.0242 +14 4707 864.857 826.83 276.602 3.60617 1.46547 10.1919 +15 4707 892.089 849.325 288.404 3.54883 1.45141 9.06316 +16 4707 924.917 877.68 301.594 3.58606 1.46396 8.20488 +17 4707 964.619 912.629 317.243 3.66842 1.4918 7.45481 +12 4708 800.196 760.468 283.414 2.57759 1.49488 9.75589 +13 4708 820.785 776.935 294.865 2.58746 1.49459 8.83863 +14 4708 846.018 796.895 309.922 2.58563 1.49881 7.88988 +15 4708 878.289 822.595 329.032 2.59179 1.50628 6.95895 +12 4710 793.824 739.912 329.569 1.83593 1.56143 7.18907 +13 4710 822.002 759.952 352.428 1.83905 1.55452 6.24612 +12 4712 777.125 728.235 313.14 1.84104 1.54132 7.92749 +13 4712 800.072 744.706 332.894 1.84834 1.5527 7.00034 +14 4712 830.157 765.714 358.544 1.83874 1.54778 6.01423 +12 4713 794.17 755.193 283.649 2.54417 1.52689 9.9437 +13 4713 814.097 771.11 295.193 2.55587 1.52873 9.01624 +12 4715 760.179 716.865 296.625 1.86789 1.53494 8.94806 +13 4715 778.629 730.039 311.12 1.86905 1.52852 7.97655 +14 4715 801.516 746.376 329.693 1.86997 1.52786 7.02894 +12 4723 918.004 855.978 314.8 2.67117 1.22927 6.24861 +13 4723 971.526 898.639 338.897 2.66755 1.22367 5.31744 +12 4724 849.186 787.869 319.83 2.0992 1.28755 6.32087 +13 4724 890.81 819.073 344.511 2.10595 1.28533 5.40273 +12 4732 890.13 831.874 300.887 2.58699 1.18052 6.65291 +13 4732 936.833 867.963 321.544 2.55257 1.15971 5.62763 +12 4736 1015.42 941.748 329.972 2.95904 1.1455 5.2605 +13 4736 1104.14 1011.98 363.585 2.88273 1.11171 4.2056 +13 4758 243.323 229.112 81.7998 -13.8427 -3.44159 27.2721 +14 4758 230.549 215.211 79.9411 -13.2729 -3.25381 25.2683 +13 4771 300.59 265.105 228.024 -4.677 0.835125 10.9222 +14 4771 273.593 234.205 234.448 -4.58165 0.839968 9.83977 +15 4771 241.719 199.198 242.634 -4.64681 0.881506 9.11495 +16 4771 202.755 155.639 251.871 -4.63787 0.900847 8.22606 +17 4771 154.537 102.56 261.873 -4.70238 0.919962 7.45666 +18 4771 93.1198 35.9179 276.847 -4.84959 0.976537 6.77555 +13 4776 748.003 737.171 161.053 6.86548 -0.585231 35.7814 +14 4776 752.216 741.712 162.558 7.29552 -0.526523 36.8998 +15 4776 757.053 746.458 163.977 7.47788 -0.450074 36.5818 +13 4777 920.065 896.236 174.793 6.99958 0.0437096 16.2653 +14 4777 938.637 914.155 175.696 7.22019 0.0623548 15.831 +13 4793 65.4851 44.7231 101.805 -14.0762 -1.83818 18.6675 +14 4793 37.9485 16.7876 99.3509 -14.5098 -1.86581 18.3156 +13 4800 111.337 91.0086 56.1106 -13.165 -3.08482 19.0658 +14 4800 86.885 66.012 51.0061 -13.4506 -3.13566 18.5682 +13 4805 68.1838 48.6669 81.9877 -14.8999 -2.50085 19.8584 +14 4805 41.6699 20.7337 78.5334 -14.57 -2.41993 18.5121 +13 4806 57.3718 38.9636 108.205 -16.1128 -1.88646 21.0545 +14 4806 32.1575 14.5594 106.946 -17.6241 -2.01173 22.0236 +13 4808 237.711 217.595 38.0933 -9.92923 -3.59843 19.2668 +14 4808 220.07 198.883 32.5813 -9.87455 -3.55627 18.2928 +15 4808 201.804 179.4 27.616 -9.77617 -3.48216 17.2993 +16 4808 181.082 158.125 21.9222 -10.0259 -3.53162 16.8831 +13 4810 265.796 246.245 59.6494 -9.44446 -3.11015 19.8233 +14 4810 250.156 229.263 55.1379 -9.24005 -3.02641 18.5503 +15 4810 233.53 211.532 50.7872 -9.18216 -2.98071 17.619 +13 4818 232.513 211.921 29.6689 -9.83506 -3.73491 18.8209 +14 4818 214.501 193.616 24.22 -10.1605 -3.82271 18.5572 +13 4822 231.659 217.105 103.834 -13.9476 -2.54739 26.6307 +14 4822 219.689 204.245 101.837 -13.5591 -2.46987 25.094 +13 4828 228.351 208.266 31.6998 -10.1949 -3.77496 19.2965 +14 4828 210.16 188.567 26.351 -9.93525 -3.64434 17.9486 +15 4828 190.279 168.144 21.4386 -10.1744 -3.6743 17.5091 +13 4830 236.651 220.251 55.9964 -12.2144 -3.82759 23.6335 +14 4830 223.475 202.15 51.421 -9.72506 -3.05877 18.1748 +15 4830 204.701 182.095 47.6358 -9.61979 -2.9753 17.1444 +13 4834 302.583 282.693 83.2794 -8.29019 -2.41905 19.4858 +14 4834 288.206 268.151 80.4465 -8.6073 -2.47509 19.326 +15 4834 273.697 253.069 77.6029 -8.74577 -2.48032 18.7887 +16 4834 257.891 235.239 73.7719 -8.33929 -2.34958 17.1102 +17 4834 240.754 216.272 68.3168 -8.09189 -2.29363 15.8311 +18 4834 220.814 195.466 62.6605 -8.23767 -2.33505 15.2897 +19 4834 198.706 173.102 55.5934 -8.61932 -2.46002 15.1372 +20 4834 174.002 145.67 47.2609 -8.25785 -2.38115 13.6798 +21 4834 145.943 116.089 37.4492 -8.3417 -2.4363 12.9824 +13 4835 305.65 286.229 87.9973 -8.40566 -2.34701 19.9566 +14 4835 291.893 271.525 85.1707 -8.37767 -2.31243 19.0288 +13 4836 405.332 383.731 88.5833 -5.07869 -2.09562 17.943 +14 4836 395.489 373.921 86.1037 -5.33133 -2.16048 17.9696 +15 4836 386.01 364.163 83.2508 -5.49628 -2.20302 17.74 +13 4839 328.086 308.855 125.445 -7.86186 -1.32419 20.1534 +14 4839 315.145 295.178 124.398 -7.92011 -1.30353 19.4103 +15 4839 302.435 281.11 123.519 -7.73609 -1.24268 18.1746 +13 4842 349.814 329.18 87.8448 -6.76164 -2.21295 18.783 +14 4842 337.056 316.137 84.5748 -6.997 -2.26673 18.5268 +15 4842 325.453 302.87 81.8253 -6.75745 -2.16511 17.1617 +13 4843 349.814 329.18 87.8448 -6.76164 -2.21295 18.783 +14 4843 337.056 316.137 84.5748 -6.997 -2.26673 18.5268 +15 4843 325.453 302.87 81.8253 -6.75745 -2.16511 17.1617 +16 4843 312.41 288.3 78.4824 -6.62003 -2.10246 16.0748 +17 4843 297.274 272.546 73.1769 -6.78349 -2.16519 15.6733 +18 4843 279.498 253.716 66.8422 -6.87653 -2.20866 15.0326 +13 4844 328.724 308.737 89.6559 -7.54748 -2.23596 19.3914 +14 4844 315.657 294.627 86.8423 -7.50687 -2.19692 18.4296 +15 4844 302.116 279.788 84.0514 -7.39636 -2.13638 17.3585 +16 4844 286.702 263.057 80.5353 -7.33464 -2.09728 16.3918 +17 4844 269.856 244.879 75.6698 -7.30559 -2.09002 15.5172 +18 4844 250.898 224.642 69.8297 -7.33765 -2.10772 14.7615 +19 4844 229.85 201.943 62.6561 -7.30866 -2.12109 13.8882 +20 4844 205.394 176.033 54.6479 -7.39408 -2.16255 13.2003 +21 4844 178.113 146.94 45.4008 -7.4345 -2.19622 12.4332 +22 4844 146.749 113.305 35.3246 -7.43324 -2.20887 11.5887 +23 4844 109.885 73.3703 25.2043 -7.3504 -2.17198 10.6141 +24 4844 66.0897 26.4219 12.5674 -7.35925 -2.17048 9.77051 +13 4849 282.136 263.06 70.1023 -9.2197 -2.89332 20.3173 +14 4849 267.372 247.59 66.4116 -9.29144 -2.89024 19.592 +15 4849 252.535 231.284 62.9378 -9.02416 -2.77825 18.2376 +13 4850 406.412 386.506 82.2736 -5.48187 -2.44428 19.4704 +14 4850 397.383 376.416 79.1158 -5.43576 -2.40149 18.4851 +13 4851 404.405 385.688 102.332 -5.88762 -2.02389 20.707 +14 4851 395.625 375.697 100.087 -5.76653 -1.96141 19.4488 +15 4851 386.682 365.731 98.0687 -5.71422 -1.91738 18.4991 +13 4852 308.561 288.311 71.6365 -7.98405 -2.68482 19.139 +14 4852 294.231 273.153 67.729 -8.03587 -2.67902 18.3878 +15 4852 279.314 256.843 63.7476 -7.89396 -2.60801 17.2472 +16 4852 262.505 238.975 59.6325 -7.92277 -2.58469 16.4717 +13 4853 382.395 360.769 53.3887 -5.64243 -2.96734 17.9219 +14 4853 371.164 348.179 48.2975 -5.57122 -2.91084 16.8621 +13 4856 391.507 372.177 110.504 -6.0594 -1.73263 20.0506 +14 4856 382.097 361.036 108.39 -5.80125 -1.64409 18.4023 +13 4857 291.293 272.606 121.396 -9.14864 -1.47917 20.7407 +14 4857 278.021 259.176 120.917 -9.44992 -1.48038 20.5662 +15 4857 264.742 244.972 121.034 -9.36882 -1.40797 19.6045 +16 4857 250.25 228.568 121.634 -8.90158 -1.26893 17.8755 +17 4857 233.716 211.433 120.04 -9.05984 -1.2731 17.3929 +18 4857 215.155 189.346 117.587 -8.20847 -1.15023 15.0169 +13 4864 548.187 541.213 111.341 -4.72684 -4.73771 55.5723 +14 4864 547.868 541.027 111.587 -4.84353 -4.81023 56.6501 +15 4864 547.861 541.01 112.015 -4.8374 -4.77 56.5713 +16 4864 547.83 540.967 111.982 -4.83098 -4.76394 56.4682 +13 4866 471.444 452.566 117.168 -3.92987 -1.58445 20.5303 +14 4866 466.124 446.748 115.977 -3.97654 -1.57684 20.0036 +15 4866 460.34 441.63 114.543 -4.284 -1.67407 20.715 +13 4868 475.266 455.428 30.4165 -3.63611 -3.85664 19.5364 +14 4868 469.626 448.642 25.0096 -3.58198 -3.78449 18.4698 +15 4868 463.848 441.972 19.2204 -3.57777 -3.77229 17.7165 +16 4868 457.58 434.303 12.3843 -3.50705 -3.70298 16.6501 +13 4871 444.423 424.523 58.8595 -4.45731 -3.07691 19.4756 +14 4871 437.343 416.083 54.4218 -4.35125 -2.99233 18.2305 +15 4871 429.837 407.459 49.9882 -4.31386 -2.94914 17.319 +16 4871 421.156 397.778 44.5932 -4.32888 -2.94702 16.5786 +13 4872 522.214 506.992 72.9821 -3.08219 -3.52423 25.4613 +14 4872 520.654 502.111 71.1348 -2.57541 -2.9466 20.9015 +13 4875 496.603 476.967 30.2996 -3.08993 -3.89959 19.7377 +14 4875 491.998 471.175 24.7215 -3.03267 -3.8213 18.6131 +15 4875 487.322 465.668 18.4338 -3.0322 -3.83054 17.8984 +13 4876 462.427 442.08 62.2272 -3.88408 -2.92039 19.0476 +14 4876 455.845 434.753 58.0961 -3.91473 -2.9226 18.3758 +15 4876 449.411 427.238 53.8304 -3.87953 -2.88331 17.479 +16 4876 442.212 418.581 48.6211 -3.80393 -2.8239 16.4011 +17 4876 434.502 409.613 42.0016 -3.77805 -2.82403 15.5721 +18 4876 426.209 398.912 34.7462 -3.60794 -2.71767 14.1983 +19 4876 416.204 386.302 25.8485 -3.47343 -2.6408 12.9617 +13 4877 462.427 442.08 62.2272 -3.88408 -2.92039 19.0476 +14 4877 455.845 434.753 58.0961 -3.91473 -2.9226 18.3758 +15 4877 449.411 427.238 53.8304 -3.87953 -2.88331 17.479 +16 4877 442.212 418.581 48.6211 -3.80393 -2.8239 16.4011 +13 4878 446.752 427.782 115.074 -4.61002 -1.63609 20.4309 +14 4878 439.882 419.781 113.611 -4.53429 -1.58314 19.2816 +15 4878 432.828 411.974 112.167 -4.55226 -1.56318 18.5854 +16 4878 425.195 403.171 110.037 -4.49648 -1.53204 17.5976 +17 4878 416.471 393.609 107.42 -4.53668 -1.53739 16.9528 +18 4878 407.429 383.129 104.315 -4.46799 -1.51502 15.9493 +19 4878 397.394 371.613 100.026 -4.42046 -1.51737 15.0333 +20 4878 385.319 357.889 94.8995 -4.39132 -1.52659 14.1299 +21 4878 372.076 343.336 88.5785 -4.43852 -1.5751 13.4854 +22 4878 356.746 325.507 82.082 -4.34714 -1.56083 12.4069 +23 4878 338.947 305.692 75.3819 -4.37108 -1.57442 11.6547 +24 4878 319.379 282.303 66.4926 -4.20405 -1.54093 10.4534 +25 4878 294.328 255.022 58.5471 -4.30794 -1.56211 9.86049 +26 4878 264.906 221.545 47.0699 -4.26954 -1.5582 8.93835 +13 4879 545.303 539.105 121.5 -5.56904 -4.45075 62.5347 +14 4879 544.913 538.47 121.913 -5.3897 -4.24704 60.1561 +15 4879 545.027 538.433 122.852 -5.25672 -4.07313 58.7758 +16 4879 544.998 538.351 122.911 -5.21703 -4.03575 58.3057 +17 4879 545.221 538.599 122.431 -5.21947 -4.09053 58.5347 +18 4879 545.503 538.781 122.141 -5.11828 -4.05213 57.653 +19 4879 545.777 539.033 121.127 -5.08 -4.11983 57.4678 +20 4879 545.843 539.001 119.839 -5.00232 -4.16215 56.647 +13 4880 545.303 539.105 121.5 -5.56904 -4.45075 62.5347 +14 4880 544.913 538.47 121.913 -5.3897 -4.24704 60.1561 +15 4880 545.027 538.433 122.852 -5.25672 -4.07313 58.7758 +16 4880 544.998 538.351 122.911 -5.21703 -4.03575 58.3057 +17 4880 545.221 538.599 122.431 -5.21947 -4.09053 58.5347 +18 4880 545.503 538.781 122.141 -5.11828 -4.05213 57.653 +19 4880 545.777 539.033 121.127 -5.08 -4.11983 57.4678 +20 4880 545.843 539.001 119.839 -5.00232 -4.16215 56.647 +13 4882 464.471 444.987 51.837 -3.99987 -3.33626 19.8917 +14 4882 458.158 437.843 47.3776 -4.0033 -3.31781 19.0787 +13 4885 484.066 464.228 49.1145 -3.39781 -3.35034 19.5362 +14 4885 478.889 458.008 44.3222 -3.36133 -3.30633 18.5607 +15 4885 473.438 451.534 39.4799 -3.33814 -3.27077 17.6945 +16 4885 467.224 444.64 33.7274 -3.38535 -3.30903 17.1613 +17 4885 461.382 437.299 25.8962 -3.30504 -3.27784 16.0936 +18 4885 454.392 428.665 18.2165 -3.23972 -3.22866 15.0649 +13 4891 584.957 580.124 76.7259 -2.73484 -10.6856 80.2064 +14 4891 585.382 580.304 75.9198 -2.55733 -10.2531 76.3196 +15 4891 587.267 580.75 74.9848 -1.83748 -8.06686 59.4727 +13 4894 611.795 602.257 106.398 0.125923 -3.74248 40.6334 +14 4894 611.991 602.355 105.809 0.135557 -3.73716 40.2193 +13 4896 690.015 672.616 119.175 2.48388 -1.6572 22.2757 +14 4896 694.027 675.988 117.812 2.51519 -1.63898 21.4852 +15 4896 699.163 679.991 117.005 2.51039 -1.56471 20.215 +16 4896 704.497 684.29 114.802 2.5237 -1.54319 19.1805 +17 4896 710.337 689.7 112.387 2.62314 -1.5739 18.7809 +18 4896 717.19 695.057 110.464 2.61219 -1.51421 17.5117 +13 4898 682.902 664.087 46.5169 2.09383 -3.60675 20.5989 +14 4898 685.576 666.673 42.251 2.16007 -3.71116 20.5029 +15 4898 689.535 670.145 38.9819 2.21546 -3.70848 19.9878 +16 4898 693.973 673.298 34.0292 2.19318 -3.60686 18.7466 +13 4900 596.088 590.081 79.4258 -1.20439 -8.35312 64.5104 +14 4900 595.978 590.444 79.0064 -1.31811 -9.1085 70.0298 +13 4902 564.547 559.41 83.0262 -4.70668 -9.3928 75.4473 +14 4902 564.527 559.667 82.2181 -4.97717 -10.0174 79.7471 +15 4902 564.993 559.72 81.5441 -4.53989 -9.30155 73.5015 +13 4903 690.208 672.393 82.9303 2.43173 -2.71139 21.7559 +14 4903 694.579 675.757 79.7012 2.42635 -2.65845 20.5917 +13 4908 663.287 647.817 62.1696 1.86547 -3.84305 25.0523 +14 4908 666.451 647.785 58.2572 1.63721 -3.29785 20.7643 +15 4908 670.647 650.244 54.8822 1.6083 -3.10595 18.9966 +13 4910 673.904 657.453 112.429 2.10103 -1.97307 23.5603 +14 4910 676.769 660.563 111.01 2.22766 -2.04981 23.9151 +15 4910 680.671 663.851 109.638 2.271 -2.01886 23.043 +16 4910 685.512 667.154 107.573 2.22236 -1.91012 21.1121 +13 4913 738.188 720.779 71.2976 3.96897 -3.13363 22.2638 +14 4913 744.557 726.094 67.8028 3.92742 -3.0562 20.9913 +13 4914 764.284 747.335 74.5733 4.90367 -3.1148 22.8676 +14 4914 771.272 753.71 71.5155 4.94602 -3.09946 22.0684 +13 4918 714.385 696.29 19.8664 3.11183 -4.54155 21.4194 +14 4918 719.456 700.662 13.9098 3.141 -4.54285 20.6226 +13 4920 752.807 735.169 47.592 4.36246 -3.81471 21.9736 +14 4920 759.657 741.381 43.0733 4.41148 -3.81435 21.2065 +15 4920 768.297 748.362 38.2433 4.27714 -3.62705 19.4416 +16 4920 776.767 756.259 31.9203 4.37955 -3.69138 18.8988 +13 4925 733.359 715.7 95.758 3.76567 -2.34506 21.9473 +14 4925 739.046 721.129 93.6443 3.88199 -2.37469 21.6315 +15 4925 744.727 727.591 92.4172 4.23707 -2.52144 22.6179 +13 4929 710.302 693.418 91.0378 3.20505 -2.60292 22.9552 +14 4929 714.862 696.602 88.4263 3.09755 -2.48348 21.2244 +15 4929 720.736 702.16 85.6573 3.21477 -2.52137 20.8639 +16 4929 727.143 707.468 82.3726 3.2103 -2.47036 19.6997 +17 4929 735.112 713.334 78.741 3.09677 -2.32131 17.7968 +13 4930 758.639 739.896 57.2851 4.27231 -3.31195 20.6777 +14 4930 766.775 746.641 52.3554 4.19432 -3.21476 19.2498 +15 4930 775.421 754.51 48.0821 4.26053 -3.20504 18.5343 +16 4930 784.677 763.14 42.7507 4.36768 -3.24496 17.9962 +17 4930 794.472 772.706 37.2738 4.5632 -3.34578 17.8058 +13 4935 883.38 864.583 45.9045 7.82491 -3.62781 20.6192 +14 4935 896.928 877.224 40.84 7.83418 -3.59894 19.6704 +13 4940 910.235 891.447 77.7172 8.59633 -2.71997 20.6288 +14 4940 925.281 905.383 74.1399 8.52315 -2.66486 19.4785 +15 4940 942.093 921.284 70.6161 8.58383 -2.63911 18.6254 +16 4940 960.726 938.716 65.2546 8.56991 -2.62587 17.6085 +13 4945 838.976 820.11 112.4 6.53214 -1.7213 20.5442 +14 4945 850.418 830.178 111.278 6.39219 -1.63418 19.149 +15 4945 863.136 842.633 110.025 6.64329 -1.64601 18.9031 +16 4945 876.748 856.368 106.584 7.0421 -1.74663 19.017 +17 4945 891.531 870.45 103.207 7.18476 -1.77464 18.3851 +18 4945 907.523 885.584 99.6998 7.2955 -1.79115 17.6665 +13 4946 859.196 840.352 35.252 7.11598 -3.92239 20.5677 +14 4946 871.664 851.769 29.481 7.0766 -3.87095 19.4809 +15 4946 885.68 864.762 23.7903 7.0907 -3.82792 18.5289 +16 4946 898.294 878.699 16.6569 7.91482 -4.28169 19.7788 +13 4956 973.246 958.86 61.7683 13.579 -4.14761 26.9401 +14 4956 987.084 972.164 58.695 13.5916 -4.10995 25.9768 +13 4963 978.822 957.695 104.665 9.38828 -1.73367 18.3447 +14 4963 997.68 976.898 102.066 10.0313 -1.82956 18.6487 +15 4963 1019.04 996.898 99.1132 9.93343 -1.78885 17.5035 +16 4963 1043.38 1019.83 95.1448 9.89162 -1.77184 16.4518 +13 4996 119.863 100.995 164.177 -13.9411 -0.24702 20.5413 +14 4996 96.7864 76.9634 164.979 -13.8947 -0.213388 19.5517 +13 5007 217.896 208.564 154.912 -22.5423 -1.03269 41.5284 +14 5007 209.575 199.453 156.107 -21.2264 -0.888717 38.2906 +13 5012 147.176 93.9158 244.833 -4.66336 0.725946 7.27705 +14 5012 81.8867 20.5293 256.354 -4.61948 0.730997 6.31666 +13 5014 268.573 228.521 245.082 -4.5731 0.968681 9.67682 +14 5014 234.06 190.213 253.897 -4.60007 0.992822 8.83922 +13 5016 177.999 169.943 193.041 -28.7771 1.34609 48.1132 +14 5016 169.965 161.834 194.626 -29.0394 1.43822 47.6645 +15 5016 162.742 154.324 196.888 -28.5112 1.53358 46.0411 +16 5016 155.007 146.49 198.936 -28.6685 1.64498 45.5071 +17 5016 147.282 138.474 199.775 -28.1926 1.64179 44.0039 +13 5017 161.419 112.039 226.827 -4.87483 0.587109 7.84882 +14 5017 103.462 48.6648 235.857 -4.96106 0.617586 7.07292 +13 5020 163.376 155.81 198.273 -31.6781 1.80469 51.2277 +14 5020 156.053 147.594 200.107 -28.7997 1.7307 45.821 +13 5024 300.577 282.678 138.593 -9.2726 -1.02819 21.6535 +14 5024 287.49 269.239 138.187 -9.47868 -1.02027 21.2353 +15 5024 274.281 254.113 138.053 -8.9298 -0.92688 19.2174 +16 5024 258.577 239.44 138.176 -9.85145 -0.973349 20.2523 +13 5025 325.954 306.656 139.559 -7.89415 -0.926753 20.084 +14 5025 313.098 292.922 138.899 -7.893 -0.904019 19.2102 +13 5026 360.695 332.694 201.817 -4.774 0.555593 13.8414 +14 5026 343.921 313.381 204.953 -4.67222 0.564571 12.6909 +13 5027 279.533 241.223 222.333 -4.62737 0.693759 10.1168 +14 5027 247.761 205.693 228.27 -4.61968 0.707586 9.21306 +15 5027 209.988 163.419 236.256 -4.60887 0.731315 8.32262 +16 5027 162.891 110.763 245.56 -4.60273 0.749202 7.43513 +13 5029 296.766 277.745 150.08 -8.83327 -0.643133 20.3762 +14 5029 283.107 265.167 150.541 -9.77427 -0.668073 21.6035 +15 5029 269.974 247.647 151.34 -8.1697 -0.517582 17.3587 +13 5033 405.924 388.33 197.579 -6.21695 0.754852 22.0284 +14 5033 397.754 379.764 199.858 -6.32426 0.806295 21.5443 +13 5036 444.846 436.935 200.915 -11.1839 1.9053 48.992 +14 5036 442.573 434.018 202.447 -10.4847 1.85808 45.3036 +13 5037 496.087 475.182 239.391 -2.91566 1.70965 18.5398 +14 5037 491.83 469.975 243.984 -2.89355 1.74824 17.734 +15 5037 486.494 463.314 249.45 -2.8517 1.77491 16.7197 +16 5037 481.177 456.718 254.948 -2.81954 1.80296 15.8464 +17 5037 474.569 448.519 260.552 -2.78349 1.80833 14.8781 +18 5037 467.455 439.521 266.566 -2.73265 1.80206 13.8751 +19 5037 459.414 429.164 272.791 -2.66614 1.77458 12.8124 +20 5037 449.824 417.083 279.658 -2.6206 1.75222 11.8375 +21 5037 438.46 403.767 287.249 -2.64909 1.77115 11.1714 +13 5038 538.976 514.567 246.594 -1.5533 1.62275 15.8785 +14 5038 535.486 509.577 252.095 -1.53566 1.6428 14.9587 +15 5038 532.182 504.541 258.411 -1.50367 1.66263 14.0216 +16 5038 528.372 498.926 265.113 -1.48103 1.683 13.1623 +13 5041 485.593 480.89 176.305 -14.1607 0.3942 82.4212 +14 5041 484.827 480.043 177.228 -14.0051 0.491158 81.0153 +13 5044 522.811 516.216 171.526 -7.06593 -0.108183 58.7714 +14 5044 521.985 515.254 172.55 -6.98843 -0.0242407 57.5788 +15 5044 521.687 514.988 174.141 -7.04657 0.103173 57.8605 +16 5044 521.318 514.654 175.161 -7.11313 0.186007 58.1631 +17 5044 521.226 514.495 175.671 -7.04974 0.2248 57.5845 +18 5044 521.035 514.116 176.28 -6.87254 0.265966 56.0164 +19 5044 520.83 513.813 176.244 -6.79234 0.259521 55.2344 +20 5044 520.567 513.061 175.728 -6.36849 0.205649 51.635 +21 5044 520.144 512.13 174.797 -5.99298 0.130212 48.3605 +22 5044 519.698 511.466 174.315 -5.86293 0.0953105 47.0764 +13 5046 496.629 489.81 164.992 -8.89641 -0.619385 56.8412 +14 5046 495.237 488.442 165.537 -9.03735 -0.578422 57.0388 +15 5046 494.167 487.71 166.308 -9.59823 -0.544528 60.0171 +16 5046 493.59 487.289 167.15 -9.88609 -0.486267 61.5091 +17 5046 493.168 486.564 167.405 -9.46676 -0.44318 58.6867 +18 5046 492.467 485.879 167.623 -9.5478 -0.42657 58.8346 +19 5046 491.827 485.07 167.268 -9.35878 -0.444016 57.3567 +20 5046 491.28 484.401 166.508 -9.23639 -0.495557 56.3444 +21 5046 490.117 483.232 165.506 -9.31969 -0.573375 56.299 +22 5046 489.297 482.037 164.653 -8.89791 -0.606784 53.3846 +23 5046 488.375 480.884 164.922 -8.6891 -0.568706 51.7355 +24 5046 487.614 479.85 164.907 -8.43658 -0.549816 49.9184 +25 5046 486.332 478.587 164.241 -8.5466 -0.597368 50.0431 +13 5048 559.691 555.109 133.028 -5.84625 -4.66898 84.5891 +14 5048 559.718 555.441 133.635 -6.25968 -4.92563 90.6201 +13 5051 661.376 646.66 208.362 1.89137 1.2961 26.3369 +14 5051 663.857 648.631 210.59 1.91548 1.33123 25.4538 +15 5051 667.022 651.302 213.355 1.96351 1.3839 24.6549 +16 5051 670.476 654.129 215.605 2.00177 1.40483 23.7105 +17 5051 673.771 657.364 217.712 2.10223 1.4686 23.6226 +18 5051 677.388 660.624 219.923 2.17337 1.5082 23.1196 +19 5051 680.765 663.624 222.118 2.23141 1.54381 22.6111 +20 5051 684.709 667.008 223.343 2.28046 1.53212 21.8956 +21 5051 688.429 670.647 224.493 2.38238 1.55982 21.7951 +22 5051 692.613 674.481 226.551 2.46044 1.59076 21.3754 +23 5051 697.441 678.563 229.088 2.50055 1.60005 20.5304 +24 5051 702.933 682.584 232.134 2.46475 1.56479 19.0461 +25 5051 708.177 686.391 235.03 2.43159 1.53305 17.7908 +26 5051 714.431 691.174 236.705 2.42209 1.47467 16.6644 +13 5052 560.682 548.452 211.083 -2.14679 1.67909 31.6913 +14 5052 560.069 547.121 213.211 -2.05306 1.67417 29.9324 +15 5052 559.602 545.982 215.914 -1.97028 1.69825 28.4567 +16 5052 559.213 545.686 218.163 -1.99922 1.79918 28.6517 +17 5052 559.055 545.126 219.988 -1.94764 1.81767 27.8251 +13 5053 567.927 551.247 226.894 -1.34064 1.74021 23.2351 +14 5053 566.514 549.308 230.698 -1.34381 1.80582 22.5254 +13 5056 737.922 714.319 204.312 2.92123 0.715917 16.4205 +14 5056 746.272 721.525 207.224 2.96744 0.746027 15.6615 +15 5056 755.996 729.269 210.721 2.94307 0.761046 14.5014 +16 5056 767.46 739.031 213.907 2.98338 0.77565 13.6327 +17 5056 780.13 749.676 217.414 3.00852 0.785956 12.7265 +13 5058 780.681 762.931 210.924 5.17833 1.15202 21.8345 +14 5058 788.954 770.742 213.726 5.29116 1.20548 21.2814 +15 5058 798.702 778.716 217.157 5.0834 1.19069 19.3921 +16 5058 808.787 788.971 219.665 5.40046 1.2689 19.5587 +13 5060 815.565 796.606 204.069 5.83647 0.88436 20.4423 +14 5060 825.685 806.19 206.584 5.95489 0.929353 19.8805 +15 5060 837.296 816.963 209.457 6.01628 0.966963 19.0613 +16 5060 850.449 830.737 212.742 6.56436 1.08698 19.6622 +17 5060 867.241 844.382 214.788 6.05505 0.985372 16.9548 +18 5060 887.874 859.005 218.145 5.17848 0.842712 13.4253 +19 5060 908.968 880.29 221.784 5.60802 0.916474 13.5146 +13 5062 857.668 838.967 173.772 7.12635 0.026379 20.7245 +14 5062 870.013 850.545 174.872 7.18618 0.0556747 19.908 +15 5062 883.99 863.742 176.372 7.28049 0.0933419 19.142 +13 5063 892.203 865.635 182.056 5.71436 0.18604 14.5877 +14 5063 912.965 883.946 183.943 5.61619 0.205258 13.356 +13 5064 860.844 837.737 183.83 5.84128 0.255154 16.7726 +14 5064 875.567 851.75 184.985 5.99944 0.2736 16.2733 +15 5064 892.798 867.828 186.827 6.09315 0.300595 15.522 +16 5064 912.489 885.648 188.097 6.06223 0.305052 14.4394 +13 5065 920.119 897.491 147.387 7.37222 -0.604555 17.1282 +14 5065 939.34 914.971 146.935 7.26909 -0.571321 15.9043 +13 5067 922.178 892.247 182.534 5.6105 0.173723 12.9493 +14 5067 947.63 914.891 184.833 5.54681 0.196548 11.8385 +13 5071 841.978 819.476 224.052 5.54816 1.22218 17.2241 +14 5071 856.213 832.257 228.128 5.53058 1.23939 16.1787 +15 5071 872.216 847.532 231.915 5.71567 1.28523 15.7014 +16 5071 891.291 863.907 237.296 5.52625 1.26405 14.1531 +17 5071 911.801 883.101 241.366 5.65687 1.2823 13.5046 +18 5071 935.703 904.21 247.53 5.56271 1.27368 12.3065 +19 5071 962.468 927.102 252.005 5.36001 1.20216 10.9588 +20 5071 994.953 958.102 259.293 5.61752 1.25994 10.5172 +21 5071 1032.28 992.049 266.474 5.64471 1.25014 9.63501 +22 5071 1076.37 1032.36 275.691 5.69711 1.25504 8.8058 +13 5100 188.255 137.39 334.373 -4.44906 1.70567 7.61959 +14 5100 132.71 74.0978 357.97 -4.37009 1.6965 6.61254 +13 5112 389.425 353.044 286.436 -3.25026 1.67702 10.6534 +14 5112 369.835 330.451 298.111 -3.26951 1.70834 9.84079 +15 5112 347.097 302.982 312.29 -3.1958 1.6978 8.78561 +13 5113 345.631 301.065 316.228 -3.18109 1.72807 8.69661 +14 5113 315.919 266.068 334.175 -3.164 1.73824 7.77464 +13 5132 676.63 636.997 294.101 0.90902 1.64327 9.77911 +14 5132 684.234 640.782 308.13 0.92313 1.67228 8.91966 +13 5134 792.703 747.573 300.934 2.17983 1.52445 8.58797 +14 5134 815.067 764.855 317.379 2.19842 1.54605 7.71862 +15 5134 844.103 786.998 338.114 2.20621 1.5545 6.78707 +13 5137 760.63 706.907 333.762 1.51047 1.60882 7.21425 +14 5137 783.748 722.369 358.339 1.52438 1.62323 6.31439 +13 5144 849.033 800.673 307.643 2.65993 1.49716 8.01443 +14 5144 881.013 825.9 326.266 2.64567 1.4952 7.03233 +15 5144 922.669 859.335 350.407 2.65559 1.50589 6.1196 +14 5204 436.749 415.034 56.4678 -4.27465 -2.87893 17.848 +15 5204 428.484 405.913 52.1401 -4.30913 -2.87269 17.1708 +16 5204 419.457 395.797 47.075 -4.31584 -2.85552 16.3808 +14 5205 501.041 486.478 114.963 -4.00262 -2.13528 26.6135 +15 5205 498.504 481.391 114.344 -3.48598 -1.83661 22.6488 +14 5211 275.865 267.6 174.148 -21.6869 0.0840685 46.893 +15 5211 270.802 262.821 175.982 -22.798 0.210482 48.5589 +14 5214 375.651 349.814 235.09 -4.86303 1.29391 15.001 +15 5214 362.294 334.832 239.85 -4.83644 1.31043 14.1131 +14 5215 281.332 262.864 142.346 -9.54666 -0.887353 20.9863 +15 5215 268.121 247.759 142.558 -9.00724 -0.799226 19.0343 +16 5215 252.187 231.769 142.474 -9.40132 -0.799208 18.9814 +17 5215 236.136 215.021 141.281 -9.49963 -0.803195 18.3554 +18 5215 218.58 195.765 139.788 -9.2054 -0.778526 16.9882 +19 5215 198.219 174.124 137.236 -9.16971 -0.794015 16.0847 +14 5217 445.806 435.318 208.678 -8.38677 1.83475 36.9542 +15 5217 442.825 432.858 210.935 -8.98574 2.05228 38.8856 +16 5217 439.894 429.621 212.93 -8.87135 2.09548 37.7273 +14 5218 530.158 513.533 225.957 -2.56548 1.71578 23.313 +15 5218 528.441 510.094 229.618 -2.37497 1.66191 21.125 +14 5221 860.335 841.088 172.302 6.99857 -0.0154186 20.1364 +15 5221 874.681 853.639 173.902 6.76811 0.026766 18.4197 +16 5221 889.387 867.498 174.435 6.86681 0.0387942 17.7061 +14 5229 79.6227 57.1281 70.723 -12.6544 -2.43879 17.2296 +15 5229 51.3508 27.8906 66.7517 -12.7809 -2.42934 16.5205 +14 5242 93.1045 71.1722 74.1878 -12.6487 -2.41647 17.6714 +15 5242 66.7638 48.4419 70.9492 -15.9134 -2.98759 21.1536 +14 5243 102.847 84.9798 90.0558 -15.2338 -2.48925 21.6923 +15 5243 81.5123 61.535 87.177 -14.1981 -2.30368 19.4007 +14 5252 180.17 161.648 87.837 -12.4528 -2.46559 20.9254 +15 5252 162.432 142.995 85.8746 -12.3563 -2.40366 19.9396 +14 5264 240.63 220.689 57.6191 -9.93816 -3.10418 19.4366 +15 5264 224.218 202.675 52.8477 -9.60807 -2.99223 17.9908 +16 5264 205.6 182.475 46.9065 -9.38304 -2.92547 16.7597 +17 5264 184.64 160.665 40.7682 -9.51995 -2.95927 16.1654 +14 5265 266.749 245.882 54.1812 -8.8246 -3.05487 18.5738 +15 5265 250.297 228.224 51.5769 -8.74304 -2.95141 17.5594 +14 5268 315.339 295.873 40.4545 -8.11847 -3.65333 19.9095 +15 5268 303.24 282.175 35.1913 -7.81094 -3.51031 18.3987 +14 5269 357.972 335.622 52.0228 -6.04653 -2.90401 17.3411 +15 5269 345.687 321.984 47.2718 -5.97961 -2.84582 16.3508 +16 5269 331.643 306.802 41.6538 -6.00964 -2.83706 15.6025 +17 5269 316.306 290.177 34.2118 -6.02848 -2.8501 14.8328 +18 5269 299.609 272.687 26.0499 -6.18408 -2.92902 14.396 +19 5269 281.252 251.254 15.7515 -5.87884 -2.81316 12.9202 +14 5272 299.032 278.789 84.1171 -8.23983 -2.35463 19.146 +15 5272 285.134 263.971 81.4742 -8.23449 -2.31938 18.3139 +14 5275 404.203 383.966 114.993 -5.45089 -1.53583 19.1522 +15 5275 395.313 374.075 113.79 -5.41855 -1.4938 18.2486 +16 5275 385.333 363.108 111.873 -5.41936 -1.47387 17.439 +17 5275 374.843 351.242 109.275 -5.34215 -1.44705 16.4222 +18 5275 363.147 337.85 106.117 -5.23223 -1.41708 15.3209 +19 5275 349.907 322.852 101.721 -5.15504 -1.41226 14.3252 +14 5276 404.203 383.966 114.993 -5.45089 -1.53583 19.1522 +15 5276 395.313 374.075 113.79 -5.41855 -1.4938 18.2486 +16 5276 385.333 363.108 111.873 -5.41936 -1.47387 17.439 +14 5283 312.021 289.859 20.7471 -7.21176 -3.68677 17.4887 +15 5283 298.112 274.02 13.0345 -6.94413 -3.56339 16.0876 +14 5285 414.275 392.699 53.8524 -4.86158 -2.96254 17.9626 +15 5285 405.372 382.631 49.2847 -4.823 -2.91877 17.0431 +16 5285 395.155 371.237 43.5043 -4.81501 -2.90489 16.2041 +17 5285 384.528 359.191 36.2391 -4.77073 -2.89628 15.2968 +18 5285 372.415 346.001 28.83 -4.82247 -2.92882 14.6729 +19 5285 359.125 330.863 19.1119 -4.75972 -2.922 13.7134 +14 5290 356.729 334.238 20.6882 -6.03847 -3.63425 17.2328 +15 5290 344.555 320.493 13.8735 -5.91594 -3.54907 16.1076 +14 5292 315.616 294.648 65.4904 -7.5304 -2.75049 18.4847 +15 5292 301.627 279.532 61.5383 -7.48644 -2.7063 17.542 +16 5292 286.699 263.055 56.3113 -7.33491 -2.64768 16.3923 +14 5294 371.287 350.017 95.8929 -6.01736 -1.94358 18.2218 +15 5294 360.328 338.002 93.5804 -5.99612 -1.9072 17.3591 +14 5306 472.555 452.925 106.638 -3.74883 -1.81188 19.7434 +15 5306 467.169 446.96 105.047 -3.78462 -1.80227 19.1779 +16 5306 461.393 439.906 102.691 -3.70405 -1.75402 18.0379 +17 5306 455.198 432.376 99.6024 -3.63307 -1.72406 16.9822 +18 5306 448.222 424.029 95.9486 -3.58207 -1.70749 16.0199 +14 5311 447.174 426.358 29.5062 -4.19027 -3.69902 18.6189 +15 5311 440.363 418.483 23.8974 -4.15369 -3.65681 17.7134 +16 5311 433.018 409.894 17.1562 -4.10101 -3.61681 16.7611 +17 5311 424.735 400.835 9.19604 -4.1539 -3.6782 16.2165 +14 5317 424.828 406.151 30.33 -5.31286 -4.09898 20.7514 +15 5317 418.251 400.538 24.6777 -5.80134 -4.49339 21.8804 +14 5320 551.814 546.09 85.7146 -5.41878 -8.17706 67.7083 +15 5320 552.204 546.16 86.1488 -5.09775 -7.70632 64.1299 +16 5320 552.799 546.305 86.2614 -4.69551 -7.16335 59.689 +14 5323 534.102 520.871 66.6706 -3.06347 -4.3109 29.2934 +15 5323 533.272 518.667 63.7359 -2.80577 -4.01323 26.5373 +16 5323 531.688 515.136 59.7963 -2.52705 -3.66893 23.4152 +17 5323 528.926 513.003 54.5144 -2.72 -3.99195 24.3396 +18 5323 526.164 511.245 48.7346 -3.00249 -4.46869 25.9777 +19 5323 523.746 508.334 42.513 -2.99074 -4.54261 25.1468 +14 5324 466.385 446.49 73.4241 -3.86565 -2.68457 19.4812 +15 5324 461.284 440.394 70.7227 -3.81262 -2.62612 18.553 +16 5324 455.05 432.904 67.0586 -3.74755 -2.56602 17.5006 +14 5325 485.28 464.855 83.7797 -3.26839 -2.34254 18.9755 +15 5325 480.105 458.538 80.0101 -3.22425 -2.31241 17.9709 +16 5325 474.337 451.686 76.2478 -3.20664 -2.29091 17.1105 +17 5325 468.13 444.486 70.7915 -3.21302 -2.31867 16.392 +14 5330 675.11 657.046 77.4731 1.94919 -2.83619 21.4552 +15 5330 679.134 660.374 74.6081 1.99219 -2.81318 20.6605 +14 5331 638.397 627.283 97.1118 1.39376 -3.66073 34.873 +15 5331 640.29 628.908 96.6658 1.45021 -3.59537 34.0498 +14 5344 621.417 608.363 73.1854 0.487919 -4.10098 29.6885 +15 5344 624.583 610.789 72.0739 0.585017 -3.92427 28.0959 +14 5346 675.828 657.479 92.1444 1.9399 -2.36262 21.1217 +15 5346 680.298 661.695 90.0874 2.04255 -2.38986 20.8341 +16 5346 685.485 665.625 87.5184 2.05358 -2.30808 19.5155 +17 5346 690.787 669.751 83.9599 2.0741 -2.26985 18.424 +14 5349 779.424 761.196 26.5316 5.00555 -4.3118 21.2621 +15 5349 788.04 768.979 21.4681 5.02971 -4.26617 20.3335 +16 5349 797.323 777.396 15.0537 5.06121 -4.25353 19.4492 +17 5349 807.952 787.057 7.87232 5.1001 -4.2412 18.5486 +14 5353 819.451 800.889 63.2103 6.07403 -3.17297 20.8805 +15 5353 830.062 810.595 59.671 6.08427 -3.12303 19.9092 +16 5353 841.797 821.131 55.1123 6.03631 -3.06034 18.7542 +14 5354 819.451 800.889 63.2103 6.07403 -3.17297 20.8805 +15 5354 830.062 810.595 59.671 6.08427 -3.12303 19.9092 +14 5355 708.846 690.42 103.888 2.89433 -2.01043 21.0337 +15 5355 714.454 695.112 102.244 2.91316 -1.961 20.0387 +16 5355 720.616 700.305 99.4362 2.93711 -1.94168 19.0825 +14 5363 727.41 708.419 32.2304 3.33337 -3.97748 20.4084 +15 5363 734.012 713.978 27.0723 3.3367 -3.90854 19.3451 +14 5366 876.999 857.021 33.2836 7.19088 -3.75275 19.4006 +15 5366 891.809 870.428 27.578 7.09099 -3.64978 18.1273 +14 5369 874.162 854.244 64.7879 7.13585 -2.91434 19.4585 +15 5369 888.607 867.508 60.7563 7.10396 -2.85377 18.3688 +16 5369 904.38 882.123 55.3181 7.11523 -2.83662 17.4137 +14 5374 910.413 891.554 39.8122 8.56904 -3.78936 20.5512 +15 5374 926.642 905.891 34.3744 8.20775 -3.58457 18.6771 +14 5381 1039.45 1022.44 20.9277 13.5773 -4.79829 22.7883 +15 5381 1058.69 1041.37 16.3787 13.9283 -4.85259 22.3762 +14 5382 1049.79 1032.89 26.1112 13.9906 -4.66354 22.9307 +15 5382 1070.22 1052.43 22.3309 13.9088 -4.54476 21.7854 +14 5384 1049.75 1032.73 36.9841 13.8957 -4.28909 22.7772 +15 5384 1070.01 1052.46 33.2031 14.0913 -4.27373 22.0812 +14 5386 977.106 962.461 41.4155 13.4815 -4.82113 26.4658 +15 5386 991.764 976.592 37.8643 13.5314 -4.77911 25.545 +16 5386 1007.31 991.681 32.9421 13.6702 -4.8086 24.7984 +14 5387 991.247 976.27 53.3341 13.6896 -4.28669 25.8786 +15 5387 1006.81 991.109 50.0507 13.5923 -4.20186 24.6883 +16 5387 1023.3 1007.06 45.8759 13.6815 -4.19884 23.8594 +17 5387 1041.32 1024.77 41.6088 14.0127 -4.25949 23.4171 +18 5387 1061.12 1043.78 37.3955 13.9867 -4.19574 22.3491 +14 5392 978.691 963.982 60.7853 13.4805 -4.09269 26.3502 +15 5392 993.35 978.172 58.0115 13.5821 -4.06419 25.5347 +16 5392 1008.99 993.215 53.7619 13.5985 -4.05442 24.5643 +14 5393 1010.13 988.083 104.086 9.75765 -1.67513 17.576 +15 5393 1033.87 1011.08 101.818 9.99923 -1.67403 17.0037 +14 5412 87.9632 67.9257 143.603 -13.9825 -0.784133 19.3424 +15 5412 63.3912 42.552 143.783 -14.078 -0.749331 18.5984 +14 5417 272.828 234.304 228.347 -4.69522 0.773771 10.0608 +15 5417 241.184 198.831 235.846 -4.67206 0.798916 9.15117 +16 5417 202.356 155.671 244.162 -4.68522 0.820455 8.3019 +17 5417 154.966 101.806 253.078 -4.59339 0.810614 7.2907 +18 5417 93.7007 34.2783 263.723 -4.66312 0.821412 6.52236 +14 5418 230.91 187.165 234.576 -4.64955 0.757908 8.85998 +15 5418 189.15 139.712 243.352 -4.56776 0.765963 7.83952 +16 5418 136.207 80.9079 253.924 -4.59789 0.78747 7.00864 +14 5440 403.533 385.831 220.381 -6.25187 1.44222 21.895 +15 5440 395.902 377.32 223.965 -6.17613 1.47746 20.8573 +16 5440 387.707 368.248 227.484 -6.12415 1.50804 19.9178 +14 5441 399.858 381.974 224.935 -6.29861 1.56431 21.6722 +15 5441 392.21 373.326 228.774 -6.1825 1.59066 20.5241 +16 5441 383.695 364.011 232.576 -6.16347 1.62972 19.6896 +17 5441 374.412 354.108 235.669 -6.2209 1.66178 19.0885 +18 5441 364.116 342.732 239.054 -6.16554 1.66293 18.125 +19 5441 352.908 330.471 242.099 -6.14423 1.65774 17.2736 +20 5441 340.282 316.556 245.219 -6.09652 1.63837 16.3358 +14 5442 324.58 291.202 228.205 -4.58627 0.890774 11.6119 +15 5442 302.056 265.589 234.583 -4.52934 0.90923 10.6278 +16 5442 275.252 235.795 241.302 -4.55111 0.931813 9.82267 +17 5442 243.34 199.897 248.231 -4.5281 0.931992 8.92142 +18 5442 204.405 156.273 256.973 -4.52146 0.938753 8.05226 +19 5442 156.226 102.304 266.005 -4.51592 0.927928 7.18766 +20 5442 93.785 32.4363 278.221 -4.51596 0.922561 6.31757 +14 5445 309.95 275.976 210.477 -4.73705 0.594842 11.4081 +15 5445 284.58 248.124 216.04 -4.78832 0.636314 10.6313 +14 5450 510.1 502.569 199.017 -7.09396 1.86608 51.4638 +15 5450 509.365 501.914 201.055 -7.22339 2.03313 52.0182 +16 5450 508.8 501.243 202.723 -7.16282 2.12336 51.2928 +14 5451 433.163 424.675 203.785 -11.1629 1.95739 45.6609 +15 5451 430.807 422.158 205.97 -11.1017 2.05674 44.812 +16 5451 428.462 419.571 207.826 -10.9417 2.11296 43.5945 +17 5451 425.942 417.082 208.934 -11.1329 2.18756 43.7475 +18 5451 423.231 414.239 210.047 -11.1307 2.22181 43.1026 +14 5452 506.54 490.359 224.886 -3.41994 1.72731 23.9529 +15 5452 503.865 486.708 229.175 -3.30907 1.76328 22.5898 +16 5452 500.58 483.023 232.16 -3.33424 1.81449 22.0756 +17 5452 497.317 479.084 235.05 -3.30676 1.83234 21.2571 +18 5452 493.619 474.44 238.955 -3.24721 1.85133 20.2085 +14 5454 517.781 514.19 154.906 -13.728 -2.68464 107.926 +15 5454 518.025 514.753 156.354 -15.0244 -2.70834 118.433 +16 5454 518.308 515.478 157.422 -17.32 -2.92914 136.951 +17 5454 518.796 516.277 157.875 -19.3616 -3.19526 153.917 +18 5454 519.271 516.976 158.413 -21.1346 -3.38026 168.897 +19 5454 519.901 517.855 158.344 -23.5419 -3.81003 189.457 +14 5459 617.661 611.697 174.47 0.729693 0.145585 64.9864 +15 5459 618.818 612.783 176.213 0.824073 0.298972 64.2181 +16 5459 620.146 613.958 177.067 0.919012 0.365749 62.6383 +17 5459 621.503 615.35 177.557 1.04275 0.410603 62.9956 +18 5459 622.898 616.55 178.353 1.12866 0.465307 61.0544 +19 5459 624.4 617.918 178.471 1.22986 0.465495 59.7953 +20 5459 625.671 619.072 177.881 1.31151 0.409207 58.7345 +21 5459 627.031 620.373 176.893 1.40951 0.325845 58.209 +22 5459 628.324 621.626 176.633 1.50484 0.30303 57.8653 +23 5459 629.795 622.948 176.667 1.58756 0.299166 56.6066 +24 5459 631.341 624.381 177.14 1.68106 0.330811 55.6858 +25 5459 632.6 625.549 176.796 1.75533 0.300342 54.9695 +26 5459 633.748 626.531 175.561 1.80031 0.201485 53.7022 +14 5461 618.415 608.114 202.655 0.461795 1.55398 37.6248 +15 5461 619.366 609.121 204.934 0.514148 1.68187 37.8284 +14 5462 570.27 555.342 219.357 -1.41373 1.6733 25.9627 +15 5462 570.394 554.77 222.634 -1.34646 1.71141 24.806 +16 5462 570.118 553.988 225.474 -1.3135 1.75238 24.0291 +17 5462 569.952 553.538 227.888 -1.29615 1.80096 23.6122 +14 5463 669.083 646.515 242.232 1.41676 1.6513 17.1737 +15 5463 673.887 649.048 247.708 1.39114 1.61879 15.6039 +16 5463 678.72 652.71 253.011 1.42832 1.65543 14.9015 +14 5469 618.309 612.491 186.755 0.807762 1.28325 66.6095 +15 5469 619.558 613.93 188.379 0.95438 1.48181 68.8707 +14 5471 667.969 648.655 231.586 1.62442 1.63338 20.0664 +15 5471 670.856 651.482 234.376 1.69946 1.70569 20.0047 +16 5471 674.14 654.324 237.932 1.75057 1.76406 19.5585 +14 5477 746.272 721.525 207.224 2.96744 0.746027 15.6615 +15 5477 755.996 729.269 210.721 2.94307 0.761046 14.5014 +16 5477 767.46 739.031 213.907 2.98338 0.77565 13.6327 +14 5480 741.607 737.448 141.999 17.0554 -3.98532 93.1949 +15 5480 744.087 739.737 143.043 16.6101 -3.68079 89.0881 +14 5482 753.022 748.569 142.342 17.3087 -3.68129 87.0533 +15 5482 755.81 751.288 143.529 17.3729 -3.48341 85.7103 +16 5482 758.512 754.017 143.825 17.8029 -3.46957 86.2388 +17 5482 761.596 757.091 144.08 18.1277 -3.43079 86.0308 +18 5482 764.635 760.001 144.604 17.9736 -3.27418 83.6277 +19 5482 767.953 763.037 144.688 17.3078 -3.07777 78.843 +20 5482 770.891 766.023 143.684 17.8021 -3.21875 79.6181 +21 5482 773.914 769.235 142.902 18.8701 -3.43892 82.8422 +14 5483 827.645 815.72 166.119 9.82383 -0.303403 32.5022 +15 5483 833.627 822.784 166.095 11.0998 -0.334816 35.7433 +16 5483 840.701 830.816 167.021 12.5607 -0.316988 39.2097 +14 5487 752.062 739.706 175.901 6.19498 0.132451 31.3673 +15 5487 756.674 744.736 177.284 6.61947 0.199349 32.4658 +16 5487 761.918 750.49 177.395 7.16117 0.21345 33.9138 +14 5489 739.722 716.492 218.144 3.00978 1.04725 16.6843 +15 5489 748.655 724.014 222.048 3.03218 1.07239 15.729 +16 5489 759.015 732.663 226.344 3.04647 1.09032 14.7077 +17 5489 770.244 742.255 230.729 3.08385 1.11073 13.8477 +18 5489 782.841 752.843 236.024 3.1028 1.13112 12.9199 +19 5489 798.079 765.362 242.056 3.09519 1.13619 11.8465 +14 5492 843.032 823.791 128.846 6.51788 -1.22857 20.1433 +15 5492 854.763 835.923 127.977 6.991 -1.27949 20.5717 +16 5492 868.673 847.571 126.902 6.59561 -1.16969 18.3664 +17 5492 882.824 861.243 124.841 6.8016 -1.19506 17.9592 +18 5492 897.654 876.566 122.377 7.33823 -1.28572 18.3787 +19 5492 917.082 893.72 120.854 7.07078 -1.19563 16.5901 +20 5492 937.801 911.822 117.548 6.78675 -1.14351 14.9186 +14 5493 872.721 853.097 132.218 7.20357 -1.11233 19.7508 +15 5493 886.82 866.361 131.554 7.27959 -1.08434 18.9443 +16 5493 902.213 880.831 129.902 7.35211 -1.07906 18.1266 +14 5498 875.567 851.75 184.985 5.99944 0.2736 16.2733 +15 5498 892.798 867.828 186.827 6.09315 0.300595 15.522 +14 5499 953.965 920.976 190.1 5.6079 0.280818 11.7487 +15 5499 984.713 948.621 192.864 5.58342 0.297808 10.7387 +16 5499 1021.22 981.409 194.987 5.55391 0.298609 9.73453 +14 5500 873.851 848.188 234.131 5.53197 1.2826 15.1027 +15 5500 891.986 864.942 239.597 5.60955 1.32565 14.3312 +16 5500 912.982 884.114 244.501 5.64576 1.33313 13.4256 +17 5500 937.814 906.714 249.975 5.66957 1.33202 12.4623 +14 5503 896.563 869.306 238.596 5.65596 1.29558 14.2193 +15 5503 918.686 889.552 244.19 5.69942 1.31523 13.3031 +16 5503 944.491 911.558 249.666 5.46276 1.25281 11.7683 +14 5507 993.566 970.3 155.556 8.86589 -0.399378 16.6588 +15 5507 1017.92 993.093 155.756 8.83504 -0.369917 15.6107 +14 5513 1012.67 989.282 133.021 9.25662 -0.914672 16.5685 +15 5513 1037.74 1013.39 132.144 9.44632 -0.898125 15.9183 +16 5513 1066 1039.91 130.063 9.39655 -0.880909 14.8538 +14 5520 981.571 958.636 145.293 8.71252 -0.645488 16.8984 +15 5520 1005.87 981.39 144.982 8.69466 -0.611485 15.8297 +16 5520 1031.35 1005.51 143.563 8.76556 -0.608712 14.9947 +17 5520 1061.01 1033.28 142.209 8.74528 -0.593639 13.9773 +18 5520 1092.42 1064.68 141.213 9.35121 -0.612765 13.9736 +14 5521 976.731 941.536 194.236 5.60385 0.32633 11.0123 +15 5521 1012.91 973.65 197.69 5.51898 0.339823 9.87274 +14 5531 175.387 123.639 256.641 -4.50675 0.869718 7.48963 +15 5531 117.608 58.661 269.737 -4.48286 0.882841 6.57494 +14 5535 390.941 354.975 286.467 -3.26503 1.69679 10.776 +15 5535 372.022 332.67 298.584 -3.24229 1.71617 9.84872 +14 5536 374.903 337.281 295.042 -3.35027 1.74451 10.3016 +15 5536 353.796 312.161 308.338 -3.29968 1.74792 9.30878 +16 5536 328.005 281.421 324.039 -3.24657 1.7433 8.31994 +17 5536 295.875 243.241 342.412 -3.20126 1.7304 7.36355 +14 5537 365.205 323.991 306.747 -3.18471 1.74504 9.40392 +15 5537 341.045 296.199 322.178 -3.21619 1.78856 8.64237 +16 5537 311.448 260.932 340.738 -3.16988 1.78515 7.67226 +14 5538 349.602 306.184 309.865 -3.21609 1.69504 8.92658 +15 5538 321.785 273.584 326.694 -3.20699 1.71441 8.04088 +16 5538 287.672 233.7 346.993 -3.20352 1.73308 7.18097 +14 5543 340.714 296.154 313.88 -3.24083 1.70001 8.69786 +15 5543 311.314 262.063 331.752 -3.25274 1.73298 7.86928 +14 5544 324.403 276.824 322.973 -3.2193 1.69478 8.14588 +15 5544 290.216 236.985 343.79 -3.2225 1.72492 7.28104 +14 5548 443.17 411.967 273.135 -2.86434 1.72632 12.4211 +15 5548 431.803 397.612 282.445 -2.7926 1.72171 11.3356 +14 5549 497.271 455.433 302.36 -1.44167 1.66272 9.2638 +15 5549 486.718 440.826 317.4 -1.43785 1.6919 8.4455 +16 5549 473.936 422.173 336.046 -1.40737 1.69345 7.48744 +14 5550 497.271 455.433 302.36 -1.44167 1.66272 9.2638 +15 5550 486.718 440.826 317.4 -1.43785 1.6919 8.4455 +16 5550 473.936 422.173 336.046 -1.40737 1.69345 7.48744 +17 5550 457.368 399.012 358.047 -1.40087 1.70465 6.64152 +14 5569 673.85 640.698 272.552 1.0417 1.6154 11.6911 +15 5569 679.111 645.999 282.675 1.12827 1.78151 11.7047 +14 5574 698.833 670.528 260.286 1.69418 1.65923 13.6929 +15 5574 706.471 674.924 268.068 1.65009 1.62117 12.2854 +14 5575 933.536 900.834 252.702 5.32154 1.31156 11.8518 +15 5575 962.613 927.206 260.815 5.35607 1.33443 10.9462 +14 5578 914.947 860.835 319.985 3.03148 1.46052 7.16245 +15 5578 959.922 899.585 342.769 3.11911 1.51267 6.4235 +14 5579 896.992 837.533 337.781 2.59665 1.48994 6.51834 +15 5579 945.191 875.872 365.691 2.6008 1.49429 5.59116 +14 5580 896.992 837.533 337.781 2.59665 1.48994 6.51834 +15 5580 945.191 875.872 365.691 2.6008 1.49429 5.59116 +14 5583 857.089 820.15 274.174 3.59947 1.47336 10.4923 +15 5583 882.823 841.615 285.4 3.56201 1.46704 9.40526 +14 5585 923.75 867.501 321.717 3.00034 1.42155 6.89027 +15 5585 971.439 908.206 345.217 3.07408 1.46418 6.12928 +14 5594 866.303 814.542 317.634 2.66437 1.50246 7.4878 +15 5594 902.976 843.994 338.613 2.67214 1.50957 6.57104 +15 5618 1065.53 1047.82 48.333 13.8278 -3.7762 21.8812 +16 5618 1087.25 1063.4 43.0985 10.7601 -2.92278 16.2528 +15 5626 1001.18 976.202 161.965 8.421 -0.23414 15.5151 +16 5626 1027.72 1000.87 161.798 8.36604 -0.221185 14.4356 +15 5631 348.896 304.654 317.955 -3.16475 1.7617 8.7603 +16 5631 320.642 271.052 335.851 -3.12952 1.76556 7.81561 +15 5634 691.838 662.906 257.15 1.52758 1.56502 13.3959 +16 5634 698.641 668.817 263.699 1.60441 1.63617 12.9952 +17 5634 706.707 673.899 271.378 1.59057 1.61312 11.8136 +18 5634 715.27 682.795 279.582 1.74851 1.76533 11.9346 +15 5635 738.93 701.892 281.634 1.87624 1.57763 10.4644 +16 5635 752.791 712.117 292.542 1.89158 1.58065 9.52895 +15 5641 69.6957 48.4648 81.1265 -13.6588 -2.32074 18.2552 +16 5641 42.5446 20.5991 78.1842 -13.8785 -2.31719 17.6607 +15 5642 116.559 95.5042 50.721 -12.5773 -3.11583 18.4077 +16 5642 92.5264 70.1825 45.8576 -12.4295 -3.05301 17.3459 +15 5644 65.6935 44.3525 62.3233 -13.689 -2.78205 18.161 +16 5644 38.0778 16.1492 58.2482 -13.9987 -2.80732 17.6744 +15 5645 65.6935 44.3525 62.3233 -13.689 -2.78205 18.161 +16 5645 38.0778 16.1492 58.2482 -13.9987 -2.80732 17.6744 +15 5665 246.309 224.325 89.301 -8.87566 -2.04153 17.63 +16 5665 228.072 206.752 86.1354 -9.61139 -2.18484 18.1788 +17 5665 210.363 185.251 81.9438 -8.53895 -1.9446 15.434 +18 5665 187.18 162.861 77.0498 -9.32959 -2.11614 15.9374 +15 5670 243.861 223.013 78.0814 -9.42227 -2.44183 18.5905 +16 5670 226.438 204.149 74.3578 -9.23308 -2.37372 17.3888 +17 5670 207.024 184.394 69.4138 -9.55458 -2.45526 17.1264 +18 5670 186.368 161.851 63.6817 -9.27199 -2.39193 15.8087 +19 5670 163.099 135.334 55.8815 -8.63743 -2.263 13.9592 +20 5670 133.957 106.694 48.2952 -9.37051 -2.45411 14.216 +21 5670 103.2 74.0267 38.8575 -9.32321 -2.46718 13.2851 +15 5671 235.999 219.155 114.051 -11.913 -1.87524 23.0101 +16 5671 221.638 202.858 113.066 -11.0954 -1.71005 20.6375 +15 5676 250.297 228.224 51.5769 -8.74304 -2.95141 17.5594 +16 5676 229.873 207.439 50.6965 -9.09125 -2.92495 17.2766 +17 5676 208.685 186.587 47.0724 -9.74414 -3.05741 17.5386 +18 5676 186.985 160.972 40.3958 -8.72591 -2.73518 14.8993 +19 5676 160.498 134.937 31.9058 -9.43676 -2.96195 15.1627 +20 5676 132.824 105.909 23.3777 -9.51432 -2.98314 14.3999 +15 5678 391.286 367.943 15.5854 -5.0228 -3.61899 16.6037 +16 5678 380.216 355.173 7.9064 -4.9191 -3.53791 15.476 +15 5680 291.626 268.883 30.1775 -7.50897 -3.36974 17.0413 +16 5680 275.157 251.79 22.9443 -7.68707 -3.44605 16.5864 +15 5685 302.433 280.407 90.8458 -7.48995 -1.99995 17.5963 +16 5685 287.235 264.116 87.9056 -7.48862 -1.97362 16.7636 +17 5685 270.884 246.37 83.5366 -7.42092 -1.95709 15.8101 +15 5687 313.948 290.198 25.221 -6.6859 -3.33905 16.3192 +16 5687 298.528 272.551 17.916 -6.4316 -3.20385 14.9202 +15 5688 399.356 376.208 24.7022 -4.87783 -3.43791 16.7435 +16 5688 388.931 364.296 18.1602 -4.81072 -3.37304 15.7329 +15 5693 278.013 257.58 93.3493 -8.71587 -2.09007 18.9682 +16 5693 262.755 240.513 90.4716 -8.37536 -1.98954 17.4252 +17 5693 245.973 221.328 86.2402 -7.92451 -1.88778 15.7262 +18 5693 226.328 201.892 81.8256 -8.42414 -2.00098 15.8608 +19 5693 206.083 179.213 75.5186 -8.06578 -1.94581 14.4241 +20 5693 180.659 153.067 69.2555 -8.34975 -2.01684 14.0468 +21 5693 153.855 120.159 61.713 -7.26444 -1.77171 11.5021 +15 5694 289.976 268.452 79.6051 -7.9755 -2.32711 18.0067 +16 5694 274.179 252.044 77.4515 -8.13853 -2.31509 17.5093 +17 5694 257.732 234.172 71.3484 -8.02132 -2.31423 16.4503 +18 5694 239.181 213.894 65.5658 -7.86764 -2.27903 15.327 +19 5694 218.273 190.355 58.6046 -7.52846 -2.19819 13.8826 +15 5696 318.664 295.787 64.4825 -6.83019 -2.54455 16.9417 +16 5696 303.826 279.059 59.7793 -6.63056 -2.4523 15.6483 +15 5697 284.386 262.69 112.421 -8.05064 -1.4962 17.8639 +16 5697 268.254 245.779 109.928 -8.15721 -1.50393 17.2448 +17 5697 251.368 227.267 106.078 -7.98326 -1.48828 16.0814 +15 5700 421.498 398.687 48.5137 -4.42847 -2.92796 16.9908 +16 5700 412.217 388.061 43.0197 -4.3882 -2.88706 16.0445 +17 5700 402.155 376.94 35.9481 -4.41836 -2.91653 15.371 +18 5700 391.585 364.397 28.2961 -4.30652 -2.85603 14.2554 +15 5705 482 459.996 52.192 -3.11401 -2.94563 17.6143 +16 5705 476.335 453.172 46.8779 -3.08935 -2.92128 16.7319 +15 5706 482 459.996 52.192 -3.11401 -2.94563 17.6143 +16 5706 476.335 453.172 46.8779 -3.08935 -2.92128 16.7319 +15 5709 511.677 504.04 100.256 -6.8842 -5.10595 50.747 +16 5709 510.878 502.585 99.5165 -6.39187 -4.75027 46.736 +15 5712 486.199 464.055 68.7739 -2.99237 -2.52468 17.5024 +16 5712 480.876 457.782 64.1747 -2.99314 -2.52785 16.7828 +15 5713 430.555 409.323 103.957 -4.52877 -1.74307 18.2547 +16 5713 422.37 400.392 101.572 -4.575 -1.74217 17.6347 +17 5713 413.913 390.899 98.1193 -4.56631 -1.74428 16.8404 +18 5713 404.642 379.952 94.3869 -4.4581 -1.7071 15.6975 +19 5713 394.057 372.646 89.391 -5.40634 -2.09385 18.1014 +15 5722 681.757 662.487 54.8505 2.01256 -3.28945 20.1135 +16 5722 686.456 666.206 49.9449 2.03975 -3.26026 19.1394 +17 5722 691.827 670.295 44.1131 2.05236 -3.21176 18.0006 +15 5725 679.349 660.522 106.481 1.99109 -1.89361 20.5852 +16 5725 683.744 663.921 104.241 2.01026 -1.85928 19.5523 +15 5726 604.155 593.055 109.916 -0.261554 -3.04586 34.9184 +16 5726 605.071 595.102 109.228 -0.241818 -3.42825 38.877 +17 5726 606.174 595.572 108.138 -0.171526 -3.27892 36.5576 +18 5726 607.342 596.57 107.089 -0.11054 -3.27932 35.9787 +19 5726 608.798 597.221 105.072 -0.0353414 -3.14499 33.4782 +20 5726 609.723 597.821 102.74 0.00739993 -3.16428 32.5635 +15 5728 683.047 664.019 114.305 2.07446 -1.65274 20.3679 +16 5728 687.732 667.695 112.439 2.09564 -1.61961 19.3429 +15 5729 683.047 664.019 114.305 2.07446 -1.65274 20.3679 +16 5729 687.732 667.695 112.439 2.09564 -1.61961 19.3429 +15 5736 567.382 549.6 30.9659 -1.27414 -4.28629 21.7969 +16 5736 566.208 547.033 25.9546 -1.21443 -4.11517 20.2128 +17 5736 566.059 546.296 20.5186 -1.18231 -4.14038 19.6109 +18 5736 565.706 546.07 14.2559 -1.19958 -4.33841 19.7375 +15 5739 617.541 606.994 118.082 0.406489 -2.78951 36.7478 +16 5739 618.981 608.033 117.677 0.462249 -2.70716 35.4008 +17 5739 620.292 609.344 116.792 0.526575 -2.75046 35.3996 +18 5739 621.742 610.576 116.01 0.586068 -2.73466 34.7119 +15 5741 566.996 560.839 95.8217 -3.71367 -6.72109 62.9544 +16 5741 567.826 561.167 95.8785 -3.36612 -6.20875 58.1983 +17 5741 568.609 561.747 95.3737 -3.20511 -6.06433 56.4742 +15 5742 569.469 563.6 123.893 -3.66919 -4.48108 66.038 +16 5742 569.922 563.903 124.256 -3.53782 -4.33756 64.3999 +17 5742 570.844 564.505 124.67 -3.28064 -4.08305 61.1419 +18 5742 571.605 564.934 124.947 -3.05608 -3.85755 58.0987 +19 5742 572.258 565.779 124.28 -3.09257 -4.02721 59.8212 +20 5742 572.742 566.214 123.157 -3.02987 -4.08978 59.3782 +21 5742 573.324 566.746 122.049 -2.95912 -4.1489 58.923 +22 5742 573.971 567.003 121.3 -2.7433 -3.97408 55.62 +23 5742 574.556 567.423 121.105 -2.63614 -3.89723 54.3392 +15 5745 671.114 652.957 104.08 1.82101 -2.03458 21.3457 +16 5745 675.47 656.737 101.337 1.88993 -2.05068 20.6896 +17 5745 679.737 660.555 99.7567 1.96517 -2.04694 20.2052 +18 5745 683.946 664.686 97.2873 2.07458 -2.1075 20.1231 +15 5748 750.389 730.824 56.677 3.86646 -3.18963 19.8098 +16 5748 758.148 737.799 51.4853 3.9223 -3.20377 19.0464 +15 5751 738.793 718.992 79.6799 3.50576 -2.52756 19.5733 +16 5751 746.284 725.398 75.8531 3.51624 -2.49464 18.5563 +15 5752 729.912 710.38 80.698 3.30982 -2.53437 19.8429 +16 5752 736.498 716.327 76.9871 3.38039 -2.55295 19.2146 +15 5754 719.213 699.67 109.339 3.0139 -1.74575 19.832 +16 5754 725.319 705.224 107.142 3.09434 -1.75654 19.2872 +15 5755 719.213 699.67 109.339 3.0139 -1.74575 19.832 +16 5755 725.319 705.224 107.142 3.09434 -1.75654 19.2872 +15 5756 759.239 739.566 33.125 4.08683 -3.81515 19.7008 +16 5756 767.716 746.925 27.1075 4.08615 -3.76553 18.6418 +17 5756 777.19 755.775 20.4794 4.20469 -3.82202 18.0984 +18 5756 788.452 765.176 12.7404 4.12844 -3.69506 16.6515 +15 5757 781.532 762.651 46.4065 4.89233 -3.5972 20.5264 +16 5757 791.115 771.065 41.233 4.86396 -3.52618 19.3303 +17 5757 802.071 780.547 35.0807 4.8044 -3.43834 18.007 +18 5757 814.075 791.025 28.5295 4.76592 -3.36326 16.8143 +15 5759 737.378 718.619 65.3728 3.65997 -3.07763 20.6606 +16 5759 744.836 724.564 60.6324 3.58449 -2.9736 19.119 +15 5763 715.804 696.636 68.0548 2.97729 -2.93678 20.2196 +16 5763 722.299 701.562 64.7998 2.92036 -2.79899 18.6904 +17 5763 729.727 708.285 60.6906 3.01037 -2.80986 18.0756 +18 5763 736.332 714.161 55.0451 3.07149 -2.85432 17.4817 +19 5763 745.068 721.463 48.7031 3.08372 -2.82526 16.4198 +20 5763 754.678 729.366 41.6169 3.07954 -2.78496 15.3116 +21 5763 766.489 738.458 31.4125 3.00716 -2.71037 13.8265 +15 5771 732.563 715.377 101.988 3.84457 -2.21497 22.5522 +16 5771 739.088 721.173 99.5983 3.88365 -2.19641 21.6337 +17 5771 747.363 728.255 96.2015 3.87386 -2.15481 20.2835 +18 5771 756.038 735.456 92.8427 3.82286 -2.08816 18.8309 +19 5771 765.637 743.016 88.391 3.70615 -2.00563 17.1334 +15 5774 896.819 875.732 36.9613 7.31756 -3.46169 18.3802 +16 5774 913.059 890.732 30.3605 7.30169 -3.42815 17.359 +17 5774 931.425 907.728 22.7813 7.29587 -3.40176 16.3554 +18 5774 951.848 926.906 15.2182 7.37151 -3.39483 15.539 +15 5775 896.672 875.633 46.9565 7.3303 -3.21429 18.4216 +16 5775 912.888 890.6 40.9482 7.3103 -3.17897 17.3893 +17 5775 931.423 907.874 34.2596 7.34163 -3.16131 16.4581 +18 5775 951.807 926.941 27.3002 7.39299 -3.14414 15.5861 +19 5775 974.812 948.431 18.7052 7.43694 -3.13864 14.6913 +20 5775 1000.37 972.028 7.73523 7.40616 -3.12911 13.6736 +15 5776 888.161 867.288 55.3501 7.16979 -3.02395 18.5687 +16 5776 903.843 881.779 49.7346 7.16422 -2.99729 17.5656 +15 5777 903.445 881.992 72.6787 7.35859 -2.50829 18.0666 +16 5777 920.371 897.496 67.9237 7.29847 -2.46397 16.9431 +17 5777 939.708 915.503 62.8177 7.32665 -2.44192 16.0124 +15 5780 868.032 852.966 26.0314 9.21487 -5.2344 25.7237 +16 5780 882.954 862.499 20.8568 7.17926 -3.9914 18.9474 +15 5782 842.676 823.21 104.398 6.43247 -1.88894 19.9096 +16 5782 855.106 834.634 101.752 6.44285 -1.86564 18.9323 +17 5782 869.142 847.597 98.739 6.4718 -1.84781 17.9891 +18 5782 884.424 861.802 95.7274 6.52654 -1.83133 17.1326 +19 5782 901.903 877.757 91.7145 6.50356 -1.80505 16.0515 +20 5782 920.857 895.103 85.9515 6.49259 -1.81248 15.0488 +21 5782 942.164 914.725 79.5698 6.5111 -1.82614 14.1249 +15 5784 884.778 864.175 125.399 7.1754 -1.23723 18.8116 +16 5784 900.04 878.408 123.401 7.21303 -1.22798 17.9168 +17 5784 917.194 894.574 121.287 7.30518 -1.22452 17.1338 +15 5785 883.314 862.804 94.7981 7.16942 -2.04422 18.8965 +16 5785 898.873 876.99 91.414 7.10184 -1.99913 17.7118 +15 5789 839.706 821.677 46.5238 6.85695 -3.76386 21.4974 +16 5789 852.086 832.625 41.82 6.69385 -3.61659 19.9148 +15 5790 859.507 839.195 80.9191 6.60997 -2.43126 19.0814 +16 5790 873.084 851.485 76.2961 6.55354 -2.40128 17.9438 +15 5795 970.065 950.144 67.194 9.72053 -2.84897 19.4553 +16 5795 988.193 968.299 62.3086 10.2234 -2.9848 19.482 +15 5796 894.347 872.076 108.849 6.86876 -1.54374 17.4027 +16 5796 910.805 888.088 105.938 7.12287 -1.5822 17.0605 +15 5797 880.762 862.52 40.5201 7.98561 -3.89659 21.2458 +16 5797 897.064 876.06 33.0676 7.35272 -3.57494 18.4528 +15 5799 1006.81 991.109 50.0507 13.5923 -4.20186 24.6883 +16 5799 1023.3 1007.06 45.8759 13.6815 -4.19884 23.8594 +17 5799 1041.32 1024.77 41.6088 14.0127 -4.25949 23.4171 +18 5799 1061.12 1043.78 37.3955 13.9867 -4.19574 22.3491 +19 5799 1083.06 1065.02 31.5672 14.0998 -4.20719 21.4857 +15 5802 1021.34 998.479 108.056 9.67484 -1.52244 16.9526 +16 5802 1046.41 1022.31 104.756 9.7373 -1.51789 16.083 +17 5802 1074.79 1049.4 101.316 9.84189 -1.51338 15.264 +18 5802 1106.75 1079.87 98.1856 9.9331 -1.49175 14.4152 +19 5802 1143.29 1114.59 93.7929 9.9904 -1.47986 13.5057 +20 5802 1184.97 1154.1 87.2413 10.0103 -1.48937 12.5523 +15 5805 1046.74 1022.33 112.847 9.61904 -1.3203 15.8756 +16 5805 1073 1048.34 109.584 10.0928 -1.37789 15.7137 +15 5807 1089.47 1071.67 112.292 14.4793 -1.82723 21.7695 +16 5807 1115.7 1093.9 108.573 12.4739 -1.58423 17.7826 +17 5807 1148.01 1124.65 105.346 12.3817 -1.55234 16.5917 +15 5811 1144.3 1123.66 18.9503 13.915 -4.00485 18.7757 +16 5811 1174.11 1152.61 10.6861 14.1052 -4.05172 18.0274 +15 5818 82.0981 61.1021 156.361 -13.4943 -0.421961 18.4595 +16 5818 55.9075 34.2491 157.126 -13.7311 -0.390065 17.8949 +15 5824 66.6216 46.6723 182.05 -14.6191 0.247612 19.428 +16 5824 41.0387 18.9615 184.15 -13.8324 0.274834 17.5554 +15 5839 172.569 164.493 178.915 -29.0639 0.403134 47.989 +16 5839 165.406 156.59 180.806 -27.0627 0.484495 43.9639 +17 5839 157.804 149.176 181.457 -28.1222 0.535571 44.9165 +18 5839 149.796 140.571 181.71 -26.7719 0.515682 42.015 +19 5839 141.068 131.807 181.115 -27.1709 0.479122 41.8468 +20 5839 132.227 122.479 180.968 -26.3013 0.447105 39.7571 +21 5839 122.381 112.034 179.854 -25.29 0.363398 37.4559 +15 5842 152.075 98.0911 244.912 -4.5521 0.716998 7.1795 +16 5842 88.6067 27.9801 256.99 -4.61563 0.745439 6.39281 +15 5844 189.391 179.508 141.041 -22.8359 -1.729 39.2151 +16 5844 180.872 170.13 142.099 -21.4353 -1.53784 36.0784 +17 5844 171.723 160.506 141.812 -20.9668 -1.48652 34.5525 +18 5844 161.629 149.963 140.764 -20.6248 -1.47755 33.2229 +19 5844 150.885 139.809 139.631 -22.246 -1.61133 34.995 +15 5845 162.742 154.324 196.888 -28.5112 1.53358 46.0411 +16 5845 155.007 146.49 198.936 -28.6685 1.64498 45.5071 +15 5846 277.372 257.692 155.598 -9.06666 -0.470982 19.6935 +16 5846 262.696 241.739 156.088 -8.89073 -0.42974 18.4943 +15 5847 277.372 257.692 155.598 -9.06666 -0.470982 19.6935 +16 5847 262.696 241.739 156.088 -8.89073 -0.42974 18.4943 +17 5847 246.497 224.948 155.401 -9.05024 -0.435055 17.9861 +18 5847 229.075 206.453 154.748 -9.03427 -0.42992 17.1323 +15 5848 162.935 154.197 188.937 -27.4553 0.988668 44.355 +16 5848 155.07 146.49 190.712 -28.4525 1.11795 45.1706 +17 5848 147.056 138.844 191.386 -30.2519 1.21218 47.1951 +18 5848 139.222 130.264 192.012 -28.2019 1.14872 43.2641 +19 5848 130.821 121.87 191.68 -28.7292 1.12978 43.2997 +20 5848 121.852 112.874 191.882 -29.1818 1.13851 43.173 +21 5848 112.835 103.358 191.319 -28.1541 1.0466 40.8964 +22 5848 103.085 93.2502 191.189 -27.661 1.00139 39.4066 +23 5848 92.6968 81.9551 192.29 -25.8463 0.971933 36.0813 +15 5860 391.784 373.442 234.101 -6.37763 1.79363 21.1305 +16 5860 383.363 363.319 238.336 -6.06164 1.7548 19.3359 +15 5861 320.693 286.366 239.398 -4.5202 1.04128 11.2907 +16 5861 297.07 259.752 246.502 -4.49798 1.0601 10.3858 +17 5861 269.426 228.658 253.561 -4.4815 1.06338 9.50678 +15 5864 404.319 386.241 228.803 -6.09839 1.66244 21.4393 +16 5864 396.769 377.848 232.541 -6.04077 1.69441 20.4833 +17 5864 388.366 368.629 235.718 -6.01973 1.71084 19.6365 +15 5865 325.426 292.591 208.337 -4.64822 0.580473 11.8039 +16 5865 303.041 268.229 212.237 -4.72971 0.607691 11.1336 +17 5865 279.236 240.059 216.024 -4.52896 0.591888 9.89279 +18 5865 248.111 204.448 220.332 -4.44659 0.584082 8.87646 +19 5865 210.142 163.983 225.896 -4.64794 0.617235 8.3964 +15 5874 432.631 411.663 138.442 -4.53235 -0.881542 18.4836 +16 5874 424.756 402.753 137.901 -4.51151 -0.853284 17.6146 +17 5874 416.241 393.322 136.548 -4.53074 -0.850903 16.9105 +15 5877 424.157 405.376 230.258 -5.30273 1.64181 20.6368 +16 5877 417.095 398.142 233.988 -5.45459 1.73259 20.4489 +15 5878 428.373 408.11 128.801 -4.80297 -1.16778 19.1269 +16 5878 420.627 399.31 127.791 -4.76062 -1.13548 18.181 +15 5879 492.534 485.371 156.096 -8.77515 -1.25658 54.1046 +16 5879 491.831 483.965 156.89 -8.03954 -1.09018 49.2729 +17 5879 491.598 482.995 157.191 -7.36518 -0.977929 45.0508 +18 5879 489.469 481.772 157.456 -8.38033 -1.07453 50.3516 +19 5879 488.821 481.322 156.879 -8.64746 -1.14413 51.6778 +20 5879 487.384 480.217 156.107 -9.15723 -1.25517 54.0802 +21 5879 486.288 478.584 154.915 -8.59522 -1.25085 50.3099 +15 5881 510.213 501.986 142.175 -6.48655 -2.00311 47.111 +16 5881 509.304 500.779 142.414 -6.31644 -1.91786 45.4596 +17 5881 508.581 500.16 141.832 -6.44129 -1.97889 46.0261 +18 5881 507.751 498.958 140.801 -6.21944 -1.95811 44.0784 +19 5881 506.931 498.088 139.946 -6.23342 -1.99876 43.8248 +20 5881 505.803 496.871 138.411 -6.23926 -2.07119 43.389 +21 5881 504.329 496.038 137.585 -6.81774 -2.28507 46.7475 +22 5881 503.219 495.098 137.055 -7.03379 -2.36792 47.7253 +23 5881 502.219 494.204 136.901 -7.19318 -2.40932 48.3524 +24 5881 501.127 492.471 137.834 -6.72828 -2.17299 44.7719 +25 5881 499.904 491.588 136.704 -7.08248 -2.33491 46.6032 +26 5881 498.642 489.561 135.146 -6.56121 -2.2306 42.6817 +15 5884 559.825 554.617 168.705 -5.12875 -0.42782 74.4076 +16 5884 559.806 555.051 169.384 -5.62058 -0.392032 81.5108 +15 5885 675.971 658.517 222.013 2.04379 1.51285 22.205 +16 5885 679.885 661.844 224.737 2.09394 1.54481 21.4838 +17 5885 684.385 665.831 227.369 2.16631 1.5783 20.8896 +15 5887 618.818 612.783 176.213 0.824073 0.298972 64.2181 +16 5887 620.146 613.958 177.067 0.919012 0.365749 62.6383 +15 5888 625.883 619.556 181.62 1.38583 0.744223 61.257 +16 5888 627.295 620.933 182.672 1.4973 0.828823 60.9132 +17 5888 629.061 622.396 183.002 1.57179 0.817869 58.1541 +18 5888 630.431 623.816 183.864 1.69491 0.894124 58.5941 +19 5888 632.074 625.261 184.034 1.7751 0.881422 56.8866 +20 5888 633.393 626.472 183.748 1.84977 0.845461 55.9991 +21 5888 635.062 628.192 182.9 1.99397 0.785434 56.414 +22 5888 636.329 629.519 182.782 2.1115 0.783096 56.9115 +23 5888 638.072 631.036 182.966 2.17698 0.77207 55.0911 +24 5888 639.653 632.615 183.514 2.29671 0.813575 55.0662 +25 5888 641.146 633.848 183.321 2.32485 0.770365 53.1071 +26 5888 642.399 635.03 182.138 2.39362 0.67666 52.5912 +15 5891 582.885 578.71 153.074 -3.43155 -2.54463 92.8243 +16 5891 583.561 579.237 153.76 -3.22929 -2.3717 89.625 +15 5892 704.266 685.561 127.673 2.71962 -1.29742 20.7199 +16 5892 709.879 690.058 126.31 2.71864 -1.26133 19.5535 +17 5892 715.991 695.483 124.673 2.78778 -1.26201 18.8994 +18 5892 723.214 701.221 122.862 2.77585 -1.22097 17.6225 +15 5893 758.788 754.519 133.377 18.7806 -4.96826 90.8067 +16 5893 761.826 756.972 133.756 16.8499 -4.32658 79.8453 +15 5894 746.628 734.382 171.663 6.01257 -0.0522266 31.6506 +16 5894 751.967 739.298 172.214 6.03782 -0.02715 30.5917 +17 5894 757.685 744.672 172.753 6.11419 -0.00418763 29.7829 +15 5895 720.038 714.726 172.728 11.1725 -0.0127564 72.9678 +16 5895 722.569 717.028 173.577 10.9566 0.0700904 69.9549 +15 5899 706.909 687.623 157.808 2.7114 -0.419068 20.0965 +16 5899 712.372 693.18 157.857 2.87763 -0.419749 20.1952 +17 5899 718.806 697.577 158.297 2.76431 -0.368345 18.2574 +18 5899 724.737 707.274 158.026 3.54272 -0.456089 22.1936 +15 5901 818.597 799.139 179.424 5.7707 0.181369 19.9188 +16 5901 830.289 809.709 180.017 5.76107 0.186961 18.8322 +15 5906 788.408 763.648 226.717 3.87998 1.16851 15.6532 +16 5906 801.293 774.705 230.938 3.87349 1.17343 14.5768 +17 5906 816.11 787.55 235.678 3.8848 1.18159 13.5707 +18 5906 833.943 802.058 241.193 3.78003 1.15126 12.1552 +19 5906 854.192 820.275 246.324 3.87432 1.16356 11.4272 +20 5906 876.952 840.906 251.673 3.9846 1.17454 10.7521 +15 5910 875.892 855.727 141.643 7.09423 -0.831352 19.2194 +16 5910 890.594 869.443 140.598 7.137 -0.819156 18.3237 +17 5910 907.311 884.838 139.477 7.11705 -0.797803 17.2467 +15 5911 891.408 871.31 170.47 7.5326 -0.0637266 19.2836 +16 5911 907.05 885.76 170.859 7.5058 -0.0503289 18.2047 +17 5911 924.692 902.142 171.307 7.50676 -0.0368494 17.1877 +18 5911 943.932 920.249 172.461 7.58402 -0.00890272 16.3654 +19 5911 965.572 940.608 172.819 7.66031 -0.000751119 15.5253 +20 5911 989.807 962.709 172.007 7.53764 -0.0167945 14.303 +21 5911 1016.81 988.102 171.168 7.62003 -0.0315437 13.5006 +15 5913 877.494 847.262 248.984 4.76067 1.35268 12.8203 +16 5913 899.711 866.901 255.402 4.75014 1.3514 11.8125 +17 5913 926.245 890.326 262.879 4.73589 1.34629 10.7903 +18 5913 956.407 917.509 272.015 4.78976 1.36935 9.964 +15 5914 851.954 832.595 134.346 6.72588 -1.0685 20.021 +16 5914 865.344 844.392 132.991 6.55769 -1.022 18.4985 +15 5920 1015.6 991.046 140.698 8.88212 -0.703409 15.7835 +16 5920 1042.32 1016.19 139.034 8.89732 -0.695334 14.8345 +15 5921 1079.03 1053.78 153.896 9.98542 -0.403222 15.3467 +16 5921 1110.89 1084.32 153.007 10.1366 -0.401301 14.5891 +15 5923 1068.92 1043.59 163.836 9.74337 -0.191276 15.3044 +16 5923 1100.22 1073.28 163.6 9.784 -0.184525 14.3878 +15 5926 1059.97 1034.71 155.403 9.58082 -0.371204 15.3481 +16 5926 1090.61 1064.15 154.383 9.7655 -0.374974 14.6476 +15 5929 1005.87 981.39 144.982 8.69466 -0.611485 15.8297 +16 5929 1031.35 1005.51 143.563 8.76556 -0.608712 14.9947 +17 5929 1061.01 1033.28 142.209 8.74528 -0.593639 13.9773 +18 5929 1092.42 1064.68 141.213 9.35121 -0.612765 13.9736 +15 5933 1027.81 1000.35 132.599 8.18022 -0.787314 14.1118 +16 5933 1053.53 1029.8 131.044 10.0492 -0.946364 16.3318 +17 5933 1081.23 1057.89 130.098 10.853 -0.983789 16.6022 +18 5933 1110.56 1088.95 130.276 12.4535 -1.05838 17.9356 +15 5939 1143.6 1110.5 175.888 8.66637 0.0492297 11.7091 +16 5939 1189.96 1153.38 178.35 8.52253 0.0806986 10.595 +15 5956 347.098 315.465 274.556 -4.45669 1.72693 12.252 +16 5956 328.03 293.783 283.876 -4.41574 1.74136 11.3172 +15 5961 333.386 286.817 319.672 -3.18545 1.69344 8.32241 +16 5961 301.48 250.089 338.761 -3.2201 1.73409 7.54165 +15 5973 719.739 688.298 266.112 1.88236 1.59325 12.327 +16 5973 729.478 695.932 273.875 1.92021 1.61762 11.5537 +15 5974 807.066 752.673 331.458 1.95046 1.56628 7.12549 +16 5974 837.245 775.104 355.24 1.96812 1.57655 6.23699 +15 5976 831.223 784.044 307.528 2.52375 1.53333 8.21505 +16 5976 860.574 807.266 324.945 2.5293 1.53251 7.27042 +17 5976 898.38 837.198 347.339 2.53571 1.5319 6.33477 +15 5979 807.424 754.56 325.368 2.01052 1.54971 7.33162 +16 5979 837.303 776.658 347.079 2.01717 1.54315 6.3908 +15 5980 807.424 754.56 325.368 2.01052 1.54971 7.33162 +16 5980 837.303 776.658 347.079 2.01717 1.54315 6.3908 +15 5984 922.517 867.924 325.27 3.07926 1.49966 7.09936 +16 5984 970.421 907.269 348.163 3.06936 1.49111 6.13713 +15 5985 895.361 838.66 331.313 2.70755 1.50117 6.83551 +16 5985 940.873 875.122 355.659 2.70665 1.49342 5.89457 +15 5988 922.818 875.724 300.147 3.57297 1.45188 8.22972 +16 5988 964.798 910.436 317.009 3.51014 1.42441 7.12958 +15 5990 850.373 793.927 332.098 2.29165 1.51541 6.86634 +16 5990 888.884 823.784 356.546 2.30475 1.51567 5.95353 +15 5995 1014.99 960.476 314.884 3.99487 1.39948 7.1096 +16 5995 1075.58 1013.8 335.608 4.05163 1.41499 6.27309 +16 6015 776.575 757.637 75.7055 4.73717 -2.75549 20.4654 +17 6015 785.824 766.701 70.9885 4.95094 -2.8612 20.2666 +16 6017 256.975 234.793 150.189 -8.53805 -0.54885 17.4725 +17 6017 238.71 216.364 149.984 -8.91442 -0.549747 17.3442 +16 6020 384.196 364.882 197.013 -6.26767 0.671904 20.067 +17 6020 374.846 354.886 198.167 -6.31654 0.681208 19.4178 +18 6020 365.137 343.476 199.648 -6.06113 0.664437 17.8925 +19 6020 353.739 332.385 200.606 -6.43499 0.698073 18.1498 +20 6020 341.261 317.471 201.549 -6.05777 0.64788 16.2912 +16 6021 290.596 251.981 217.414 -4.43687 0.619837 10.0368 +17 6021 260.941 219.591 222.261 -4.52858 0.641797 9.37285 +18 6021 226.369 182.385 227.747 -4.67966 0.670376 8.81168 +16 6023 777.631 749.316 210.414 3.18837 0.712531 13.6878 +17 6023 791.295 761.094 213.684 3.23232 0.726192 12.8332 +18 6023 807.339 774.076 217.429 3.19383 0.719821 11.6517 +19 6023 824.536 789.305 221.419 3.27769 0.740456 11.0011 +20 6023 845.611 807.049 225.094 3.28809 0.727679 10.0507 +16 6025 964.13 931.25 187.386 5.79255 0.237404 11.7876 +17 6025 994.86 960.196 188.916 5.97052 0.248892 11.1808 +16 6026 964.13 931.25 187.386 5.79255 0.237404 11.7876 +17 6026 994.86 960.196 188.916 5.97052 0.248892 11.1808 +18 6026 1031.44 992.441 191.066 5.81108 0.25086 9.93866 +19 6026 1076.63 1032.63 193.795 5.70238 0.255671 8.80919 +16 6053 276.021 253.343 102.273 -7.90016 -1.67179 17.0903 +17 6053 259.347 234.925 98.8011 -7.70284 -1.62878 15.87 +16 6055 261.6 238.751 79.2437 -8.1799 -2.20061 16.9621 +17 6055 243.926 220.199 74.6554 -8.27749 -2.22309 16.3347 +18 6055 224.736 199.337 69.2253 -8.13848 -2.1916 15.2595 +19 6055 203.099 176.365 62.415 -8.16684 -2.21901 14.4976 +20 6055 178.07 149.521 54.9103 -8.11851 -2.21912 13.5758 +21 6055 149.693 119.327 45.8087 -8.1349 -2.24739 12.7638 +22 6055 117.375 84.6576 35.7576 -8.08072 -2.25086 11.8463 +16 6063 352.662 327.932 24.4348 -5.57997 -3.22376 15.6722 +17 6063 338.767 313.033 15.9395 -5.6521 -3.27519 15.0603 +16 6064 352.662 327.932 24.4348 -5.57997 -3.22376 15.6722 +17 6064 338.767 313.033 15.9395 -5.6521 -3.27519 15.0603 +18 6064 323.774 296.606 6.63145 -5.65029 -3.2864 14.2656 +16 6066 346.996 321.291 45.4541 -5.48656 -2.66217 15.0774 +17 6066 331.988 304.933 38.4212 -5.51081 -2.66898 14.3252 +18 6066 315.774 287.436 30.274 -5.56868 -2.70259 13.6767 +19 6066 297.589 267.853 20.4187 -5.6355 -2.75362 13.034 +20 6066 275.967 244.09 9.22061 -5.62128 -2.75734 12.1584 +16 6070 369.675 346.461 87.4806 -5.55059 -1.97542 16.6954 +17 6070 357.811 333.049 82.8835 -5.46111 -1.9517 15.6521 +16 6071 390.188 367.915 90.7809 -5.29045 -1.97931 17.4009 +17 6071 379.844 356.303 86.8322 -5.24161 -1.96283 16.4639 +18 6071 368.153 343.524 82.0347 -5.26491 -1.98071 15.7363 +16 6076 312.015 288.011 51.0694 -6.65823 -2.72521 16.1461 +17 6076 296.955 269.538 44.571 -6.12437 -2.51325 14.136 +18 6076 277.256 250.636 35.7127 -6.70549 -2.76735 14.5598 +19 6076 257.363 230.203 26.1481 -6.96548 -2.90144 14.2701 +20 6076 235.021 207.017 15.5217 -7.18413 -3.01784 13.84 +16 6078 407.537 385.728 87.5978 -4.97566 -2.0998 17.771 +17 6078 398.451 375.696 83.5794 -4.98326 -2.10735 17.0321 +16 6080 373.305 351.196 55.6686 -5.73973 -2.84699 17.5296 +17 6080 362.598 339.405 49.6832 -5.71973 -2.85269 16.7111 +18 6080 350.221 325.515 43.1641 -5.63856 -2.81972 15.6877 +16 6081 377.022 353.85 71.5642 -5.39063 -2.34807 16.7265 +17 6081 365.607 341.008 66.6206 -5.327 -2.31974 15.7557 +18 6081 352.819 326.973 60.7383 -5.33563 -2.33002 14.9952 +16 6082 377.022 353.85 71.5642 -5.39063 -2.34807 16.7265 +17 6082 365.607 341.008 66.6206 -5.327 -2.31974 15.7557 +16 6083 300.558 277.437 90.3883 -7.17892 -1.9159 16.7632 +17 6083 284.886 260.803 85.9945 -7.24167 -1.93736 16.0935 +18 6083 267.895 242.158 82.3888 -7.131 -1.88813 15.0595 +16 6085 383.611 361.316 41.4004 -5.44371 -3.16708 17.3838 +17 6085 373.473 349.107 33.0803 -5.20445 -3.08127 15.9061 +18 6085 361.155 335.977 25.7422 -5.29943 -3.13847 15.3932 +16 6086 364.196 341.218 77.8266 -5.73577 -2.22142 16.8671 +17 6086 352.327 328.142 72.9596 -5.71326 -2.2187 16.0257 +16 6087 331.188 308.968 83.7944 -6.72925 -2.1529 17.4422 +17 6087 316.387 293.096 78.8176 -6.76106 -2.16865 16.6399 +18 6087 301.936 273.667 72.6932 -5.84532 -1.90321 13.7103 +19 6087 284.597 251.639 65.7517 -5.29639 -1.7456 11.7599 +16 6088 347.959 324.717 90.4136 -6.04611 -1.90536 16.6761 +17 6088 334.853 310.284 86.2575 -6.00596 -1.89327 15.7751 +18 6088 320.089 294.203 81.0297 -6.00666 -1.9054 14.9723 +19 6088 304.057 275.943 74.9112 -5.83688 -1.87128 13.7856 +20 6088 284.44 254.198 67.6593 -5.77476 -1.86846 12.8159 +16 6089 346.05 320.988 36.9158 -5.64766 -2.9135 15.4644 +17 6089 331.794 305.495 29.4369 -5.67327 -2.92925 14.7372 +18 6089 316.013 287.864 19.8856 -5.60155 -2.919 13.7687 +16 6090 323.872 300.07 48.491 -6.44728 -2.80658 16.2834 +17 6090 309.586 283.212 42.9203 -6.10954 -2.64635 14.6955 +18 6090 292.975 265.473 36.0442 -6.18315 -2.67201 14.0922 +16 6092 337.329 314.184 59.6313 -6.31783 -2.62764 16.7452 +17 6092 324.167 299.931 54.2476 -6.32549 -2.62881 15.9923 +16 6097 530.696 508.579 15.5546 -1.91534 -3.82032 17.5239 +17 6097 528.284 504.28 7.40231 -1.81877 -3.70246 16.1465 +16 6098 449.077 426.843 26.1405 -3.87709 -3.54445 17.4316 +17 6098 441.893 418.708 19.0978 -3.88461 -3.56233 16.7171 +16 6101 428.948 405.777 33.7056 -4.18685 -3.22568 16.7264 +17 6101 420.399 395.976 26.3639 -4.16026 -3.2218 15.869 +16 6104 485.862 462.913 48.1971 -2.89527 -2.91773 16.8884 +17 6104 481.178 456.746 42.2691 -2.82248 -2.87094 15.8632 +18 6104 475.676 449.77 35.6432 -2.77599 -2.845 14.9607 +16 6105 465.001 444.053 69.0287 -3.70669 -2.66225 18.5014 +17 6105 459.245 437.217 64.101 -3.66537 -2.65191 17.5945 +16 6109 554.329 536.814 58.2271 -1.69375 -3.51528 22.1275 +17 6109 553.281 535.196 50.6988 -1.67156 -3.6282 21.4308 +16 6112 511.459 502.546 114.421 -5.91223 -3.52158 43.4849 +17 6112 510.577 501.84 113.703 -6.08564 -3.6367 44.3615 +18 6112 509.824 500.981 112.992 -6.05875 -3.63652 43.8321 +19 6112 508.928 500.034 111.203 -6.0781 -3.72369 43.5806 +20 6112 507.92 499.141 109.418 -6.21876 -3.88129 44.147 +21 6112 507.008 497.91 107.115 -6.05462 -3.8812 42.5994 +16 6115 418.36 396.429 120.328 -4.68309 -1.28653 17.6728 +17 6115 409.297 386.455 117.781 -4.70943 -1.29512 16.9679 +16 6116 445.472 423.558 37.4807 -4.02211 -3.31827 17.6864 +17 6116 438.555 414.812 31.3485 -3.86869 -3.20134 16.3236 +16 6117 520.365 513.333 117.163 -6.81387 -4.25445 55.1207 +17 6117 520.249 513.084 117.042 -6.69592 -4.18444 54.0961 +18 6117 520.092 512.71 116.746 -6.51032 -4.08288 52.5047 +19 6117 519.956 512.376 115.874 -6.35017 -4.03815 51.1352 +20 6117 519.526 511.835 114.655 -6.28815 -4.06475 50.3938 +16 6119 531.688 515.136 59.7963 -2.52705 -3.66893 23.4152 +17 6119 528.926 513.003 54.5144 -2.72 -3.99195 24.3396 +18 6119 526.164 511.245 48.7346 -3.00249 -4.46869 25.9777 +19 6119 523.746 508.334 42.513 -2.99074 -4.54261 25.1468 +16 6122 642.185 630.739 95.5728 1.53113 -3.62686 33.8623 +17 6122 644.364 632.92 94.0077 1.63371 -3.70104 33.8689 +18 6122 646.831 634.889 92.5857 1.67648 -3.61042 32.4544 +19 6122 649.317 636.987 90.3854 1.73195 -3.59252 31.4318 +16 6124 597.147 590.861 120.063 -1.06079 -4.51149 61.6626 +17 6124 597.997 591.88 119.284 -1.01519 -4.70374 63.3551 +18 6124 598.965 592.549 119.37 -0.886993 -4.4779 60.4102 +19 6124 599.822 593.674 118.651 -0.850828 -4.73611 63.0456 +20 6124 600.7 594.08 117.237 -0.718918 -4.51302 58.5493 +16 6137 598.38 591.888 78.6895 -0.92483 -7.79025 59.693 +17 6137 599.422 592.811 77.8321 -0.823759 -7.72131 58.6309 +18 6137 600.518 593.228 77.0166 -0.666288 -7.06234 53.1707 +19 6137 601.795 593.808 75.3343 -0.52213 -6.55825 48.5238 +20 6137 602.51 594.029 72.9793 -0.446469 -6.32549 45.6981 +16 6145 759.851 739.325 60.0111 3.93299 -2.95298 18.8819 +17 6145 768.753 747.399 55.0087 4.00445 -2.96435 18.15 +18 6145 778.995 756.113 49.8749 3.97747 -2.8869 16.9379 +19 6145 789.813 765.856 43.7704 4.04155 -2.89425 16.1779 +20 6145 801.228 776.028 35.8778 4.08559 -2.91977 15.3802 +16 6146 708.518 688.375 96.9889 2.63897 -2.02313 19.2415 +17 6146 714.981 693.83 93.7064 2.67726 -2.01001 18.324 +18 6146 721.962 699.563 90.4039 2.6955 -1.97721 17.303 +16 6147 711.965 691.705 105.105 2.7151 -1.79624 19.1303 +17 6147 718.399 697.088 102.315 2.74327 -1.77793 18.1861 +18 6147 725.873 703.222 99.1723 2.75828 -1.74729 17.1106 +19 6147 734.13 710.057 95.1979 2.77953 -1.73273 16.0996 +20 6147 742.368 716.897 90.1069 2.80073 -1.74501 15.2161 +21 6147 751.997 725.335 84.0806 2.86968 -1.78851 14.5368 +16 6151 790.029 769.723 15.8251 4.77396 -4.15388 19.0868 +17 6151 800.456 779.197 8.4398 4.82356 -4.15441 18.2318 +16 6152 740.329 720.123 39.5198 3.4764 -3.54458 19.1815 +17 6152 748.349 727.032 33.0776 3.49729 -3.52215 18.1816 +16 6153 740.329 720.123 39.5198 3.4764 -3.54458 19.1815 +17 6153 748.349 727.032 33.0776 3.49729 -3.52215 18.1816 +16 6155 705.327 684.34 73.2912 2.45111 -2.54823 18.4672 +17 6155 711.458 689.97 69.0627 2.54726 -2.59458 18.037 +18 6155 717.528 695.664 64.4828 2.65262 -2.66251 17.727 +16 6156 801.661 781.677 29.7351 5.16344 -3.84685 19.394 +17 6156 812.355 791.67 23.4456 5.26637 -3.87997 18.7375 +18 6156 823.551 802.908 16.8024 5.5684 -4.06071 18.7755 +16 6160 869.491 848.445 20.3182 6.63412 -3.8931 18.4155 +17 6160 884.423 862.219 12.934 6.64933 -3.86868 17.455 +16 6168 854.216 834.188 73.3688 6.56164 -2.66817 19.3515 +17 6168 867.96 846.945 68.3057 6.60496 -2.67235 18.4432 +16 6170 903.948 882.017 117.996 7.21039 -1.34362 17.6724 +17 6170 921.705 898.573 115.771 7.24847 -1.32555 16.7552 +18 6170 941.227 916.822 113.884 7.29986 -1.29789 15.8807 +19 6170 963.271 937.409 110.973 7.34677 -1.2853 14.9867 +20 6170 987.704 959.982 106.534 7.32715 -1.28506 13.9809 +21 6170 1015.33 985.817 101.608 7.38626 -1.2969 13.1343 +22 6170 1046.48 1015.19 96.1025 7.50006 -1.31749 12.3857 +23 6170 1081.98 1048.44 89.6836 7.56466 -1.33176 11.5536 +24 6170 1123.45 1086.89 83.0919 7.54989 -1.31875 10.6005 +25 6170 1171.12 1132.13 74.6581 7.73663 -1.35285 9.94067 +16 6171 884.922 863.747 121.465 6.98515 -1.30358 18.3033 +17 6171 901.125 878.793 119.472 7.01286 -1.28396 17.3547 +18 6171 918.916 895.289 117.558 7.03312 -1.25714 16.4039 +19 6171 938.665 913.794 115.07 7.10772 -1.24796 15.5831 +20 6171 960.836 934.022 110.792 7.03705 -1.24327 14.4544 +21 6171 985.458 957.07 106.126 7.11267 -1.26261 13.6528 +22 6171 1013.26 982.873 101.01 7.13706 -1.27014 12.7562 +16 6172 879.587 858.774 125.589 6.96905 -1.21984 18.6219 +17 6172 895.426 873.346 123.7 6.95471 -1.19584 17.554 +16 6174 888.944 867.28 75.4452 6.92703 -2.41514 17.8897 +17 6174 905.687 882.878 70.3048 6.9739 -2.41507 16.9925 +18 6174 924.343 899.933 64.647 6.92691 -2.38112 15.8776 +19 6174 945.077 919.327 58.6996 6.999 -2.3813 15.0515 +20 6174 967.936 940.468 50.3673 7.00816 -2.39526 14.1099 +21 6174 993.896 964.737 41.2801 7.08017 -2.42383 13.292 +16 6175 905.128 882.943 76.728 7.15624 -2.32738 17.4697 +17 6175 923.082 899.677 71.8664 7.19531 -2.31765 16.5592 +16 6176 896.169 874.585 78.2408 7.13271 -2.35459 17.9565 +17 6176 913.296 890.315 74.0878 7.09938 -2.30851 16.8648 +16 6179 844.325 824.228 21.2783 6.27484 -4.05134 19.2854 +17 6179 857.295 836.319 14.7039 6.34389 -4.04982 18.4768 +16 6182 839.568 819.317 44.9764 6.10101 -3.39197 19.1389 +17 6182 852.432 831.367 38.5536 6.19325 -3.42466 18.3992 +18 6182 866.268 844.268 31.7065 6.26787 -3.4463 17.6173 +19 6182 879.91 859.067 25.1637 6.96744 -3.80625 18.5954 +16 6183 981.772 960.723 15.8279 9.49836 -4.00709 18.4126 +17 6183 1003.11 980.734 8.86004 9.44632 -3.93629 17.3188 +16 6185 1059.79 1035.64 106.719 10.0146 -1.47105 16.0493 +17 6185 1089.29 1063.61 103.318 10.0363 -1.45476 15.0952 +16 6190 1086.88 1064.1 106.94 11.2562 -1.55439 17.0153 +17 6190 1118.95 1093.13 102.856 10.5935 -1.45569 15.0053 +16 6191 1101.42 1081.96 39.0446 13.5769 -3.69357 19.9168 +17 6191 1126.55 1106.54 33.3084 13.8725 -3.74442 19.361 +18 6191 1153.92 1134.13 27.6816 14.7766 -3.94065 19.5859 +16 6193 1023.22 999.57 94.7153 9.39438 -1.77455 16.3863 +17 6193 1049.9 1024.76 90.5768 9.40792 -1.75785 15.4157 +16 6194 1060.22 1036.12 98.5301 10.0417 -1.65609 16.0774 +17 6194 1089.23 1064 94.7633 10.2151 -1.66303 15.366 +16 6209 60.2373 38.4433 177.958 -13.539 0.125795 17.7835 +17 6209 31.9519 9.57724 178.239 -13.8667 0.129277 17.322 +16 6215 73.6055 52.7692 168.872 -13.8166 -0.102654 18.6009 +17 6215 47.3906 25.576 168.778 -13.8426 -0.100358 17.7668 +16 6221 225.71 221.291 196.099 -46.6585 2.82553 87.7059 +17 6221 223.221 218.784 196.536 -46.7734 2.86711 87.3554 +16 6224 194.385 145.267 242.931 -4.54028 0.766347 7.89062 +17 6224 142.795 86.6024 251.978 -4.46185 0.756357 6.89725 +16 6229 159.72 149.136 152.322 -22.8302 -1.04206 36.6195 +17 6229 150 142.084 151.71 -31.1806 -1.43462 48.9556 +16 6231 213.995 167.669 244.852 -4.58659 0.834818 8.36627 +17 6231 168.423 116.933 253.809 -4.60205 0.844544 7.52727 +18 6231 110.386 52.5819 265.071 -4.63858 0.856927 6.70492 +16 6233 192.969 183.386 148.151 -23.3499 -1.38462 40.4423 +17 6233 184.669 173.52 148.077 -20.4711 -1.19376 34.7634 +16 6234 164.66 153.842 161.119 -22.0895 -0.582658 35.8248 +17 6234 154.59 144.226 161.494 -23.5804 -0.588761 37.3962 +16 6238 140.365 131.748 204.022 -29.2483 1.94295 44.9787 +17 6238 132.481 123.658 205.241 -29.044 1.97166 43.9264 +16 6239 160.996 150.204 137.746 -22.326 -1.74741 35.9126 +17 6239 150.981 140.54 136.634 -23.5927 -1.86342 37.1213 +18 6239 141.146 131.137 136.56 -25.1382 -1.9478 38.7226 +19 6239 131.545 121.154 135.266 -24.7083 -1.94292 37.2959 +16 6241 173.093 163.594 206.287 -24.6805 1.8905 40.8002 +17 6241 165.284 153.914 207.758 -20.9887 1.64897 34.0873 +18 6241 154.486 141.029 209.218 -18.1642 1.45146 28.8001 +16 6243 412.383 389.978 141.067 -4.72729 -0.762098 17.2988 +17 6243 402.9 380.018 139.995 -4.85121 -0.771335 16.9377 +16 6249 394.794 374.424 238.186 -5.66322 1.72275 19.0265 +17 6249 385.686 364.427 241.681 -5.65655 1.73903 18.2309 +16 6250 324.961 291.21 244.688 -4.52936 1.14323 11.4832 +17 6250 302.531 265.909 251.075 -4.50332 1.1473 10.5831 +16 6251 324.961 291.21 244.688 -4.52936 1.14323 11.4832 +17 6251 302.531 265.909 251.075 -4.50332 1.1473 10.5831 +16 6254 401.994 379.564 140.259 -4.97056 -0.780551 17.2787 +17 6254 392.039 369.234 139.118 -5.12365 -0.794634 16.9957 +18 6254 381.566 357.898 137.422 -5.17439 -0.804136 16.3755 +16 6255 325.386 294.675 215.779 -4.97029 0.750765 12.62 +17 6255 304.594 268.044 219.056 -4.48187 0.679007 10.604 +16 6257 438.185 429.164 206.393 -10.2042 1.99704 42.9626 +17 6257 435.995 426.848 207.381 -10.1927 2.02765 42.3729 +16 6258 429.892 418.306 213.342 -8.33042 1.87727 33.4546 +17 6258 425.938 414.535 214.765 -8.64935 1.97419 33.9875 +16 6259 519.466 512.957 140.842 -7.43586 -2.6421 59.5519 +17 6259 519.407 512.797 140.817 -7.32626 -2.60345 58.6358 +18 6259 519.22 512.53 140.811 -7.25353 -2.57282 57.9339 +19 6259 519.224 512.235 140.003 -6.94283 -2.52482 55.4548 +20 6259 518.779 511.671 139.007 -6.86077 -2.55799 54.5305 +16 6261 471.557 466.577 168.741 -14.8845 -0.443605 77.8227 +17 6261 471.66 466.06 169.404 -13.226 -0.330893 69.2032 +16 6267 510.913 504.181 190.406 -7.87013 1.40029 57.5655 +17 6267 510.863 503.955 191.274 -7.67522 1.43248 56.1109 +16 6268 645.701 634.379 205.98 1.71468 1.57161 34.2321 +17 6268 648.149 636.511 207.357 1.7811 1.59247 33.3021 +18 6268 650.391 638.369 208.98 1.82442 1.61414 32.2392 +16 6269 561.156 553.891 134.885 -3.57878 -2.80732 53.3481 +17 6269 561.892 554.329 134.615 -3.38529 -2.71574 51.2433 +16 6270 691.764 671.035 211.222 2.1302 0.994245 18.6976 +17 6270 698.489 675.5 214.036 2.07788 0.962249 16.8591 +16 6273 565.017 545.492 239.366 -1.22535 1.82973 19.8495 +17 6273 564.865 544.159 242.927 -1.15944 1.81781 18.7179 +18 6273 563.526 541.662 247.888 -1.13091 1.84339 17.7263 +16 6276 731.724 727.22 158.934 14.5713 -1.66032 86.0623 +17 6276 734.305 729.698 159.241 14.5434 -1.58702 84.1196 +18 6276 737.074 732.566 160.023 15.194 -1.52886 85.9749 +16 6278 729.199 700.867 204.948 2.26825 0.608479 13.6796 +17 6278 738.824 709.395 207.82 2.35937 0.638213 13.1696 +18 6278 750.26 718.142 211.165 2.35312 0.64072 12.0672 +16 6281 820.662 800.178 221.621 5.53583 1.27883 18.9212 +17 6281 832.438 811.134 224.66 5.61963 1.30624 18.1928 +18 6281 846.131 823.207 228.332 5.54338 1.29997 16.9072 +19 6281 860.836 836.898 231.772 5.63846 1.32207 16.1908 +20 6281 876.858 851.342 234.549 5.62706 1.29877 15.1895 +16 6282 768.931 764.372 131.953 18.7784 -4.81929 85.0172 +17 6282 772.117 767.369 131.997 18.3912 -4.62247 81.6324 +18 6282 775.138 770.488 132.532 19.1272 -4.65792 83.35 +16 6284 809.505 788.971 220.205 5.23042 1.23866 18.8748 +17 6284 821.13 799.696 223.217 5.30205 1.26211 18.082 +18 6284 834.592 811.541 227.453 5.24385 1.27231 16.8138 +16 6285 698.97 675.844 229.638 2.07669 1.31888 16.7586 +17 6285 705.374 680.922 233.25 2.10481 1.32675 15.8504 +16 6286 708.174 688.815 140.141 2.73629 -0.907683 20.0207 +17 6286 714.203 694.093 139.052 2.79517 -0.90291 19.2733 +16 6287 735.481 723.74 185.932 5.76098 0.598332 33.0106 +17 6287 740.374 729.088 186.774 6.22584 0.662513 34.34 +16 6290 699.726 675.914 239.117 2.03395 1.49474 16.2762 +17 6290 706.304 680.915 243.264 2.04676 1.48961 15.265 +18 6290 713.334 686.58 247.813 2.08358 1.50503 14.487 +19 6290 721.457 692.842 252.517 2.10051 1.49542 13.5445 +20 6290 730.189 700.194 256.658 2.16019 1.50072 12.921 +21 6290 740.068 708.068 261.341 2.19069 1.48532 12.1116 +22 6290 751.199 716.981 267.22 2.22345 1.48135 11.3267 +23 6290 764.162 727.301 274.35 2.25293 1.47904 10.5145 +24 6290 779.012 739.146 282.954 2.28317 1.48346 9.72188 +25 6290 796.456 752.332 292.563 2.2752 1.45729 8.7837 +26 6290 816.194 768.642 302.38 2.33416 1.46314 8.15055 +16 6292 881.069 860.04 136.313 6.93515 -0.933369 18.4302 +17 6292 896.845 874.837 135.102 7.01191 -0.921433 17.6109 +16 6293 883.167 862.444 159.493 7.09184 -0.346312 18.702 +17 6293 898.817 877.231 159.39 7.19797 -0.335037 17.9549 +18 6293 916.209 893.317 159.736 7.19519 -0.307803 16.93 +16 6302 924.14 900.213 175.595 7.06201 0.061537 16.1977 +17 6302 944.123 918.846 175.304 7.10954 0.0520707 15.3328 +16 6308 1082.69 1055.59 134.318 9.37849 -0.763877 14.3026 +17 6308 1116.53 1088.34 131.813 9.662 -0.782171 13.7514 +18 6308 1154.62 1125.66 129.821 10.1109 -0.798255 13.3845 +16 6310 1098.05 1071.5 165.88 9.88041 -0.141051 14.594 +17 6310 1133.85 1105.11 166.49 9.79842 -0.118934 13.4848 +16 6311 1098.05 1071.5 165.88 9.88041 -0.141051 14.594 +17 6311 1133.85 1105.11 166.49 9.79842 -0.118934 13.4848 +16 6343 140.228 85.0972 278.327 -4.57278 1.02765 7.03008 +17 6343 73.2623 9.85353 293.931 -4.5431 1.02567 6.11231 +16 6361 495.048 448.077 317.26 -1.30953 1.6514 8.25139 +17 6361 484.178 432.106 335.272 -1.29338 1.67543 7.44304 +16 6363 587.878 559.613 259.15 -0.412046 1.64001 13.7125 +17 6363 588.237 558.12 265.736 -0.380296 1.65659 12.8689 +18 6363 587.973 555.742 273.07 -0.359739 1.67013 12.0247 +16 6366 598.211 561.218 282.395 -0.164777 1.59057 10.477 +17 6366 597.516 558.369 292.237 -0.165247 1.6381 9.90045 +18 6366 598.305 556.027 304.559 -0.142992 1.67334 9.16729 +16 6373 819.441 792.37 254.647 4.16447 1.62294 14.3167 +17 6373 835.846 805.578 261.712 4.01578 1.57691 12.8047 +18 6373 854.96 822.448 271.535 4.0545 1.6304 11.9212 +19 6373 876.4 841.759 280.852 4.13774 1.67466 11.1885 +16 6388 860.574 807.266 324.945 2.5293 1.53251 7.27042 +17 6388 898.38 837.198 347.339 2.53571 1.5319 6.33477 +16 6394 903.014 869.004 259.642 4.63469 1.37069 11.3956 +17 6394 929.361 893.203 268.479 4.75091 1.42058 10.719 +18 6394 961.473 922.733 279.255 4.87947 1.4753 10.0045 +17 6407 598.365 591.531 57.4439 -0.879929 -9.07147 56.7143 +18 6407 599.562 592.536 56.2437 -0.764318 -8.91499 55.1624 +19 6407 600.661 593.662 54.2505 -0.682942 -9.10248 55.376 +20 6407 601.557 594.198 51.6822 -0.584053 -8.84394 52.6627 +17 6423 940.531 896.673 289.208 4.05351 1.42502 8.83689 +18 6423 980.119 931.049 303.696 4.05637 1.43227 7.89838 +19 6423 1029.62 973.785 320.935 4.04098 1.42453 6.94113 +17 6441 232.308 207.195 35.0494 -8.06897 -2.94749 15.4329 +18 6441 211.126 185.269 26.9045 -8.2771 -3.03197 14.9893 +17 6442 269.864 244.681 40.7347 -7.24558 -2.81806 15.3901 +18 6442 249.86 223.4 32.4343 -7.30191 -2.85053 14.6473 +17 6443 247.221 222.417 57.5981 -7.84668 -2.49594 15.6254 +18 6443 227.086 200.282 50.9165 -7.66467 -2.4436 14.4594 +19 6443 203.984 174.491 42.4089 -7.38669 -2.37578 13.1413 +20 6443 176.468 146.607 32.7879 -7.7905 -2.51953 12.9791 +17 6446 244.01 220.028 98.0273 -8.1877 -1.67599 16.1612 +18 6446 224.486 201.848 94.223 -9.13716 -1.86578 17.1209 +17 6460 274.745 252.145 65.7347 -7.95797 -2.54604 17.1497 +18 6460 258.015 233.437 59.2172 -7.68287 -2.48349 15.7689 +19 6460 239.296 208.536 50.3955 -6.46587 -2.13848 12.6001 +20 6460 212.363 182.204 42.2103 -7.0744 -2.32687 12.8512 +21 6460 184.554 151.61 31.8468 -6.92982 -2.29916 11.7649 +22 6460 151.143 117.79 20.2753 -7.38286 -2.4573 11.6205 +17 6462 270.264 246.197 95.407 -7.57288 -1.72857 16.1043 +18 6462 252.474 227.124 91.2142 -7.56665 -1.72995 15.2894 +19 6462 232.448 205.365 85.5404 -7.47944 -1.73174 14.3106 +17 6467 282.537 256.647 61.0464 -6.78494 -2.31974 14.9702 +18 6467 263.07 235.931 55.0766 -6.8579 -2.33111 14.2811 +17 6473 364.176 340.13 74.945 -5.48155 -2.18716 16.1182 +18 6473 350.874 324.593 70.1498 -5.28714 -2.09913 14.7472 +17 6477 380.769 357.159 113.937 -5.20513 -1.34041 16.4155 +18 6477 369.013 345.413 110.702 -5.47504 -1.41462 16.4228 +17 6480 499.744 475.775 13.4103 -2.46099 -3.57318 16.1699 +18 6480 494.85 468.794 4.84907 -2.36474 -3.46345 14.8746 +17 6486 506.952 487.75 108.052 -2.87037 -1.8128 20.1845 +18 6486 505.66 485.345 106.994 -2.74721 -1.74141 19.0783 +17 6487 553.918 546.976 121.994 -4.30535 -3.9354 55.8307 +18 6487 554.047 547.083 121.948 -4.28172 -3.92646 55.6531 +17 6488 553.918 546.976 121.994 -4.30535 -3.9354 55.8307 +18 6488 554.047 547.083 121.948 -4.28172 -3.92646 55.6531 +17 6490 419.669 397.944 81.1415 -4.69495 -2.26755 17.8397 +18 6490 411.331 387.525 76.3901 -4.4728 -2.1766 16.2807 +17 6491 454.059 431.491 92.9571 -3.70116 -1.90167 17.1737 +18 6491 447.09 423.295 88.98 -3.66767 -1.89341 16.2884 +19 6491 439.313 414.108 83.9472 -3.62812 -1.8947 15.3767 +20 6491 430.216 403.414 77.9547 -3.59428 -1.90191 14.4606 +17 6493 445.773 423.574 69.0385 -3.96315 -2.51203 17.4591 +18 6493 438.652 414.641 63.9323 -3.82331 -2.43665 16.1413 +19 6493 430.707 405.311 57.4089 -3.78294 -2.4418 15.2614 +20 6493 421.187 394.036 50.135 -3.7268 -2.4279 14.275 +17 6495 425.008 402.328 115.769 -4.37098 -1.35201 17.0891 +18 6495 416.584 392.542 113.026 -4.31154 -1.3367 16.1209 +17 6496 485.404 460.507 37.7111 -2.6787 -2.91575 15.5674 +18 6496 480.947 454.502 30.4236 -2.61234 -2.89301 14.6557 +17 6505 581.177 575.01 91.9551 -2.47232 -7.04692 62.8516 +18 6505 582.039 575.773 91.3358 -2.35922 -6.98833 61.8555 +19 6505 582.935 576.607 90.178 -2.26006 -7.018 61.2481 +20 6505 583.756 577.013 88.551 -2.05542 -6.71533 57.4756 +21 6505 584.404 577.534 86.0189 -1.96691 -6.78958 56.4165 +17 6506 631.321 619.939 98.0276 1.02703 -3.53141 34.0527 +18 6506 633.333 621.312 96.6251 1.06226 -3.40605 32.2397 +19 6506 635.485 623.32 94.5549 1.1448 -3.45746 31.861 +20 6506 637.354 624.766 91.8047 1.18605 -3.45857 30.7898 +17 6510 572.024 565.326 111.117 -3.01007 -4.95086 57.8621 +18 6510 572.649 566.138 110.673 -3.04514 -5.13001 59.5273 +17 6518 566.12 559.744 80.3825 -3.65977 -7.79073 60.7896 +18 6518 566.738 560.011 79.5627 -3.41909 -7.44891 57.6117 +19 6518 567.483 560.52 77.4744 -3.24593 -7.35797 55.6624 +20 6518 567.926 560.765 75.229 -3.12279 -7.32264 54.121 +21 6518 568.405 561.232 72.675 -3.08186 -7.50194 54.0326 +22 6518 568.845 561.46 70.6109 -2.9615 -7.43692 52.483 +17 6521 718.944 696.563 33.2818 2.62534 -3.34988 17.3177 +18 6521 726.928 702.813 26.2169 2.61433 -3.26628 16.0719 +17 6522 773.675 752.359 33.2736 4.13569 -3.51741 18.1827 +18 6522 783.844 761.37 26.4529 4.16549 -3.49906 17.2451 +17 6523 773.675 752.359 33.2736 4.13569 -3.51741 18.1827 +18 6523 783.844 761.37 26.4529 4.16549 -3.49906 17.2451 +17 6524 725.33 703.578 44.8272 2.85882 -3.16148 17.8176 +18 6524 732.485 710.155 38.6782 2.95697 -3.22758 17.3565 +19 6524 741 716.73 31.1917 2.90909 -3.13532 15.9693 +20 6524 750.718 723.833 21.9219 2.82024 -3.01551 14.4158 +21 6524 761.005 731.355 11.3591 2.74366 -2.92571 13.0717 +17 6525 718.445 696.153 58.046 2.62368 -2.76637 17.3859 +18 6525 725.937 702.45 52.623 2.66153 -2.74966 16.5014 +19 6525 734.165 709.526 45.7797 2.71647 -2.77027 15.7298 +17 6529 765.362 749.667 98.4819 5.3324 -2.54541 24.6949 +18 6529 775.263 755.717 95.8536 4.55386 -2.11613 19.8293 +19 6529 785.22 764.357 92.438 4.52274 -2.07047 18.5775 +17 6534 695.65 674.124 53.7391 2.14827 -2.97234 18.0049 +18 6534 701.718 678.754 49.9682 2.15569 -2.87442 16.8775 +17 6536 751.265 728.926 84.1796 3.4073 -2.13216 17.3493 +18 6536 760.598 737.469 80.1551 3.50773 -2.15285 16.7571 +17 6537 700.453 679.29 103.726 2.30704 -1.7546 18.314 +18 6537 706.427 684.269 100.934 2.34823 -1.74347 17.4912 +19 6537 713.381 690.091 97.1892 2.39458 -1.74517 16.6419 +17 6538 749.821 729.619 120.758 3.72934 -1.38515 19.1845 +18 6538 758.305 736.88 119.147 3.72915 -1.34647 18.0894 +19 6538 767.764 744.942 116.413 3.72361 -1.32844 16.9827 +20 6538 778.06 753.952 112.672 3.75439 -1.34094 16.0767 +17 6540 815.922 794.827 39.1622 5.25484 -3.40434 18.3733 +18 6540 828.527 805.853 33.091 5.18736 -3.31099 17.0932 +17 6541 763.321 741.089 43.754 3.71502 -3.11916 17.4329 +18 6541 773.17 750.31 37.7582 3.84453 -3.1745 16.9548 +19 6541 785.054 759.661 30.3538 3.71246 -3.01449 15.2636 +20 6541 797.455 770.28 21.1885 3.71412 -2.99797 14.2626 +17 6544 718.011 697.391 114.874 2.82517 -1.51037 18.796 +18 6544 725.165 703.345 113.526 2.84592 -1.46051 17.7624 +19 6544 732.755 709.972 110.172 2.90454 -1.47784 17.0114 +20 6544 741.131 716.86 105.71 2.91185 -1.48599 15.9685 +21 6544 749.867 724.363 100.369 2.95516 -1.52668 15.197 +22 6544 760.407 733.278 96.6348 2.98673 -1.50911 14.2862 +23 6544 772.134 742.606 91.4806 2.95743 -1.48028 13.1257 +24 6544 784.938 753.206 84.7331 2.96875 -1.49168 12.214 +25 6544 799.327 765.24 77.1367 2.99043 -1.50835 11.3703 +17 6546 937.052 913.119 32.014 7.34999 -3.1609 16.1936 +18 6546 958.048 932.826 24.9324 7.42149 -3.15017 15.366 +17 6552 886.95 864.9 48.6798 6.75765 -3.02507 17.5778 +18 6552 903.972 880.728 43.0698 6.80363 -2.9992 16.6741 +19 6552 922.995 898.152 35.9657 6.77711 -2.9598 15.6011 +20 6552 944.633 917.466 27.2336 6.62511 -2.87922 14.2663 +21 6552 968.39 938.702 17.0113 6.49234 -2.81967 13.0548 +17 6559 869.836 846.269 108.209 5.93238 -1.47342 16.4457 +18 6559 884.364 862.961 106.443 6.89677 -1.66672 18.1084 +19 6559 900.755 878.314 103.882 6.97016 -1.65093 17.271 +17 6562 933.187 909.862 75.3572 7.45284 -2.24526 16.6163 +18 6562 953.54 928.779 70.3602 7.4622 -2.22347 15.6528 +17 6564 926.179 902.82 59.8129 7.28072 -2.5994 16.5919 +18 6564 946.31 921.494 54.4023 7.28906 -2.56392 15.6179 +19 6564 969.007 942.604 47.6101 7.31275 -2.54801 14.6792 +20 6564 993.833 965.757 38.5725 7.35186 -2.56905 13.8043 +21 6564 1022.1 992.443 28.5534 7.47226 -2.61369 13.0691 +22 6564 1054.46 1022.03 17.058 7.36736 -2.57989 11.9483 +17 6566 973.935 950.756 53.9734 8.44428 -2.75502 16.7214 +18 6566 996.801 972.089 48.2888 8.41717 -2.70757 15.6835 +19 6566 1022.31 996.091 41.4733 8.45526 -2.69134 14.7807 +17 6569 1096.16 1069.31 112.917 9.73413 -1.19899 14.4338 +18 6569 1131.63 1102.95 110.244 9.77869 -1.17274 13.5149 +19 6569 1172.18 1141.98 106.354 10.0041 -1.18245 12.8297 +17 6574 1074.79 1049.4 101.316 9.84189 -1.51338 15.264 +18 6574 1106.75 1079.87 98.1856 9.9331 -1.49175 14.4152 +17 6576 999.422 977.594 32.6908 9.5942 -3.44931 17.7565 +18 6576 1022.54 999.241 25.7811 9.52087 -3.39062 16.6343 +19 6576 1048.67 1023.86 17.1712 9.50683 -3.3706 15.6216 +17 6578 1071.87 1046.3 91.919 9.71118 -1.7001 15.1564 +18 6578 1102.94 1076.57 88.1249 10.0513 -1.72614 14.6995 +19 6578 1138.6 1110.35 83.309 10.059 -1.70258 13.7191 +20 6578 1178.89 1148.75 76.003 10.1472 -1.72618 12.86 +17 6581 1132.88 1113.35 32.8054 14.3945 -3.85221 19.8468 +18 6581 1162.16 1141.86 26.7672 14.6208 -3.86519 19.0906 +17 6604 192.972 182.155 152.266 -20.6869 -1.02238 35.8301 +18 6604 183.667 174.178 151.259 -24.1082 -1.22242 40.8437 +17 6607 262.71 222.206 227.148 -4.59978 0.720031 9.56875 +18 6607 228.611 184.552 233.012 -4.64434 0.733415 8.79664 +19 6607 187.167 138.087 239.079 -4.62281 0.724792 7.89677 +20 6607 134.897 79.2655 247.093 -4.58312 0.716814 6.96683 +17 6609 165.133 114.154 247.674 -4.68282 0.788361 7.60268 +18 6609 107.29 49.3547 257.733 -4.65678 0.786952 6.68973 +17 6610 198.91 150.059 249.1 -4.51534 0.838371 7.93376 +18 6610 148.544 93.7982 258.645 -4.52337 0.841755 7.07954 +19 6610 84.089 22.0452 270.168 -4.54931 0.842505 6.24679 +17 6613 244.176 222.199 135.602 -8.93055 -0.910491 17.6355 +18 6613 225.953 203.587 133.771 -9.21261 -0.938616 17.3283 +17 6614 269.163 245.614 137.645 -7.76463 -0.803145 16.4587 +18 6614 251.328 226.413 135.666 -7.72319 -0.801756 15.5558 +19 6614 230.893 204.87 132.221 -7.81622 -0.838714 14.8936 +17 6623 291.892 254.209 236.223 -4.52819 0.903299 10.2852 +18 6623 263.478 222.388 242.55 -4.52407 0.911086 9.43216 +19 6623 229.359 184.246 249.141 -4.52698 0.908341 8.59122 +20 6623 187.117 136.617 257.437 -4.49341 0.899683 7.67481 +17 6627 409.31 386.463 144.135 -4.70816 -0.675231 16.9644 +18 6627 399.74 375.63 142.985 -4.67462 -0.665468 16.0753 +19 6627 389.246 362.989 141.035 -4.50702 -0.650939 14.7608 +17 6628 408.935 387.981 163.62 -5.14293 -0.236714 18.4964 +18 6628 399.82 377.639 163.567 -5.07918 -0.224902 17.4732 +17 6629 324.28 302.681 172.213 -7.0949 -0.0159436 17.9446 +18 6629 310.849 287.909 172.316 -6.99437 -0.0126022 16.895 +17 6633 340.215 309.504 250.606 -4.71094 1.35992 12.62 +18 6633 321 290.457 255.709 -5.07475 1.45713 12.6893 +17 6635 480.519 473.168 168.815 -9.42893 -0.295093 52.7224 +18 6635 479.513 471.925 169.149 -9.20512 -0.262221 51.0731 +19 6635 478.47 470.465 168.894 -8.79543 -0.265681 48.4117 +20 6635 477.203 468.921 168.138 -8.58423 -0.30584 46.7966 +21 6635 475.963 467.578 167.102 -8.55804 -0.368479 46.2209 +17 6638 521.027 502.359 232.926 -2.54743 1.72852 20.7615 +18 6638 518.239 498.733 235.99 -2.51477 1.73862 19.8696 +19 6638 515.711 494.671 238.812 -2.39604 1.68396 18.4215 +20 6638 511.833 490.192 241.265 -2.42569 1.69804 17.9094 +21 6638 509.29 485.834 244.17 -2.29617 1.63316 16.5233 +22 6638 504.353 481.495 247.049 -2.47224 1.7435 16.9554 +17 6639 484.659 475.228 144.749 -7.11378 -1.60076 41.0957 +18 6639 483.004 473.58 144.507 -7.21378 -1.6158 41.1283 +19 6639 481.437 472.158 143.951 -7.41642 -1.67309 41.7667 +20 6639 479.629 469.961 142.555 -7.21871 -1.68336 40.0874 +21 6639 477.879 468.212 140.874 -7.31638 -1.77685 40.0899 +22 6639 476.161 466.107 139.389 -7.12706 -1.78795 38.5494 +23 6639 474.244 463.95 138.747 -7.06112 -1.77981 37.6517 +24 6639 472.401 461.814 138.171 -6.95894 -1.75972 36.6084 +25 6639 469.938 459.359 137.026 -7.08908 -1.81912 36.6352 +26 6639 467.344 456.141 134.767 -6.81875 -1.82614 34.5953 +17 6642 521.383 514.232 200.836 -6.62264 2.10163 54.1926 +18 6642 521.03 513.83 201.912 -6.60511 2.168 53.8333 +19 6642 520.817 513.385 202.225 -6.41366 2.12276 52.1476 +20 6642 520.386 512.782 202.231 -6.29911 2.07515 50.9686 +21 6642 519.82 512.309 201.794 -6.41763 2.06962 51.6002 +22 6642 519.322 511.539 201.781 -6.22719 1.99625 49.7927 +23 6642 518.473 510.594 202.266 -6.20981 2.00513 49.1906 +17 6643 524.358 504.754 235.927 -2.33449 1.72818 19.7699 +18 6643 521.987 502.154 238.822 -2.37176 1.78663 19.5417 +19 6643 519.675 499.285 242.024 -2.36781 1.82215 19.0075 +20 6643 516.626 495.472 244.33 -2.35981 1.81495 18.3216 +17 6647 688.9 673.776 182.946 2.81777 0.358401 25.6252 +18 6647 693.154 678.434 184.179 3.05046 0.413246 26.3295 +17 6648 561.837 555.255 126.278 -3.89474 -3.80119 58.8864 +18 6648 562.35 555.657 126.176 -3.78906 -3.74645 57.9112 +19 6648 562.91 556.105 125.337 -3.68254 -3.75103 56.9585 +20 6648 563.276 556.22 124.023 -3.52372 -3.71764 54.9329 +21 6648 563.579 556.482 122.144 -3.47991 -3.83789 54.6078 +22 6648 563.881 556.727 120.918 -3.4294 -3.89924 54.1713 +23 6648 564.256 556.866 120.239 -3.29288 -3.82433 52.4453 +24 6648 564.669 557.158 119.776 -3.21069 -3.79625 51.606 +25 6648 564.71 557.179 118.437 -3.1987 -3.88109 51.4613 +26 6648 564.817 556.986 116.044 -3.06875 -3.89645 49.4885 +17 6649 675.899 659.674 205.554 2.19625 1.08257 23.8873 +18 6649 679.848 662.847 207.364 2.22088 1.09042 22.7982 +17 6650 630.112 622.259 156.665 1.40578 -1.10727 49.3512 +18 6650 631.23 623.69 156.232 1.54388 -1.18424 51.4047 +17 6653 680.042 664.521 188.49 2.43916 0.541094 24.9697 +18 6653 684.191 667.849 189.756 2.45302 0.555542 23.7158 +19 6653 688.474 671.504 190.519 2.49793 0.559154 22.8392 +17 6654 711.785 691.283 126.316 2.6783 -1.21928 18.9041 +18 6654 718.102 696.776 124.73 2.73392 -1.21213 18.1738 +17 6655 738.481 718.06 132.502 3.39116 -1.06141 18.9794 +18 6655 746.377 724.868 131.085 3.41693 -1.04315 18.02 +19 6655 755.032 732.404 128.995 3.45327 -1.04114 17.1281 +20 6655 764.425 740.846 125.957 3.52797 -1.06834 16.4372 +17 6656 709.732 689.906 148.938 2.7139 -0.64794 19.548 +18 6656 716.024 695.269 148.536 2.75538 -0.62937 18.6739 +19 6656 722.992 701.091 147.337 2.78205 -0.62582 17.6964 +17 6658 750.547 717.586 217.678 2.29757 0.730456 11.7583 +18 6658 762.063 727.51 222 2.37078 0.764009 11.2168 +19 6658 776.806 741.072 226.146 2.51405 0.801083 10.8461 +17 6660 780.458 767.054 161.291 6.84867 -0.463377 28.9152 +18 6660 786.641 773.556 161.445 7.26911 -0.468345 29.6187 +19 6660 793.317 780.251 161.507 7.55434 -0.466495 29.6626 +20 6660 802.048 787.588 161.324 7.15043 -0.428311 26.8032 +21 6660 810.016 794.003 160.314 6.72411 -0.420626 24.2032 +17 6661 766.845 756.342 177.574 8.04356 0.241386 36.8992 +18 6661 772.838 762.145 178.241 8.20186 0.270584 36.2444 +19 6661 780.357 767.881 178.725 7.35333 0.252762 31.0642 +20 6661 787.303 773.538 178.164 6.93605 0.207192 28.1564 +17 6663 791.295 761.094 213.684 3.23232 0.726192 12.8332 +18 6663 807.339 774.076 217.429 3.19383 0.719821 11.6517 +17 6671 932.894 909.418 128.243 7.39806 -1.02073 16.5091 +18 6671 952.782 928.997 126.858 7.75115 -1.03875 16.2948 +19 6671 975.003 949.4 124.678 7.66705 -1.01073 15.1379 +20 6671 999.876 972.707 120.681 7.71694 -1.03152 14.2655 +17 6676 916.919 893.967 178.196 7.19307 0.125025 16.886 +18 6676 935.883 911.902 179.449 7.30961 0.147727 16.1624 +19 6676 956.901 931.742 180.431 7.41597 0.161769 15.4053 +17 6679 847.732 839.714 148.646 15.9549 -1.62163 48.3347 +18 6679 853.429 845.66 148.884 16.8614 -1.65734 49.8878 +17 6684 1045.01 1004.02 189.186 5.70753 0.214063 9.45743 +18 6684 1092.58 1047.99 191.981 5.81834 0.230394 8.69144 +17 6693 1116.73 1088.69 180.23 9.71352 0.14127 13.8191 +18 6693 1155.73 1125.7 182.355 9.76952 0.169949 12.9063 +19 6693 1200.89 1169.09 183.881 9.98958 0.186279 12.1893 +17 6701 1120.8 1071.53 200.436 5.57359 0.300703 7.86627 +18 6701 1189.69 1134.76 205.815 5.67335 0.322341 7.05628 +17 6702 1115.1 1087.66 153.852 9.89559 -0.371944 14.1236 +18 6702 1154.41 1124.12 153.785 9.66225 -0.338165 12.7956 +19 6702 1199.5 1167.45 152.706 9.88701 -0.337669 12.0925 +17 6712 344.12 298.796 323.165 -3.1458 1.78139 8.55117 +18 6712 315.016 259.447 340.87 -2.84718 1.62411 6.97467 +17 6715 323.107 274.831 328.091 -3.18731 1.7273 8.02844 +18 6715 288.778 234.891 347.709 -3.19759 1.74298 7.19237 +17 6717 333.716 287.879 322.397 -3.23252 1.75245 8.45548 +18 6717 302.497 250.705 340.61 -3.18462 1.73984 7.48325 +17 6725 530.774 499.18 278.686 -1.33948 1.7993 12.2673 +18 6725 526.149 491.992 287.748 -1.31171 1.80683 11.3469 +19 6725 520.014 482.189 298.263 -1.27163 1.78092 10.2465 +20 6725 514.843 473.386 308.408 -1.22722 1.75634 9.34881 +21 6725 505.977 459.877 321.945 -1.20693 1.73719 8.40725 +17 6731 576.966 552.608 252.973 -0.718751 1.76682 15.9116 +18 6731 576.298 549.5 258.765 -0.666704 1.72203 14.4629 +17 6732 692.582 665.968 255.952 1.67567 1.6772 14.5631 +18 6732 699.886 671.243 262.501 1.69395 1.68121 13.5315 +17 6738 606.988 576.394 270.701 -0.0451467 1.71794 12.6683 +18 6738 611.087 574.952 280.58 0.0227081 1.60136 10.7257 +17 6739 584.415 541.378 303.719 -0.313835 1.63335 9.00568 +18 6739 583.077 536.046 318.31 -0.30245 1.66125 8.2407 +17 6750 867.766 830.067 277.6 3.6791 1.49249 10.281 +18 6750 893.876 852.408 288.932 3.68283 1.50359 9.34628 +19 6750 927.447 878.842 301.996 3.51313 1.42721 7.97407 +17 6757 1008.91 955.415 313.241 4.01004 1.40969 7.24527 +18 6757 1067.02 1006.55 334.167 4.06376 1.433 6.40969 +17 6758 1034.73 975.258 329.265 3.83988 1.41259 6.51641 +18 6758 1104.45 1035.15 356.114 3.83613 1.42055 5.59303 +18 6783 248.114 219.648 42.2626 -6.82032 -2.46421 13.6151 +19 6783 224.372 195.346 32.4497 -7.12847 -2.59839 13.3531 +18 6792 1130.03 1110.21 27.5287 14.1095 -3.93965 19.5603 +19 6792 1158.51 1138.28 21.8483 14.577 -4.00985 19.1599 +18 6800 1147.69 1117.53 138.167 9.58284 -0.617695 12.8488 +19 6800 1192.48 1160.05 136.226 9.65469 -0.606652 11.9506 +18 6825 191.945 166.744 66.7691 -8.90108 -2.26111 15.3789 +19 6825 168.707 141.886 59.7077 -8.82906 -2.26601 14.4504 +18 6843 229.624 203.358 34.8441 -7.76997 -2.82241 14.756 +19 6843 207.925 179.23 25.3222 -7.51828 -2.76168 13.5066 +18 6845 228.988 203.642 120.621 -8.06543 -1.10698 15.2915 +19 6845 207.26 180.742 116.608 -8.14893 -1.13931 14.6154 +18 6846 333.956 307.924 43.9796 -5.68676 -2.65918 14.8881 +19 6846 318.776 291.053 35.3133 -5.63395 -2.66486 13.9799 +20 6846 300.912 271.504 25.7334 -5.63763 -2.68725 13.1793 +18 6849 321.172 294.835 72.1082 -5.8817 -2.05473 14.7159 +19 6849 304.511 276.957 65.3241 -5.94676 -2.09624 14.066 +20 6849 285.388 255.887 57.5123 -5.90241 -2.10011 13.1375 +21 6849 263.177 231.553 48.3238 -5.88343 -2.11519 12.2556 +22 6849 237.946 204.249 38.0578 -5.92365 -2.1487 11.5016 +23 6849 208.936 171.869 27.4885 -5.80566 -2.10657 10.4562 +18 6853 338.468 312.312 48.9832 -5.56719 -2.54383 14.8176 +19 6853 323.134 295.443 40.8461 -5.55623 -2.56076 13.9968 +18 6854 338.468 312.312 48.9832 -5.56719 -2.54383 14.8176 +19 6854 323.134 295.443 40.8461 -5.55623 -2.56076 13.9968 +18 6864 398.109 376.099 59.6011 -5.16054 -2.76398 17.6094 +19 6864 387.708 365.677 52.6858 -5.40903 -2.92986 17.5921 +18 6865 308.025 281.563 48.0701 -6.12081 -2.53298 14.6464 +19 6865 291.868 263.454 39.5509 -6.00589 -2.52007 13.6405 +18 6867 437.334 412.384 32.0171 -3.70782 -3.03207 15.5339 +19 6867 428.824 402.084 22.974 -3.63053 -3.01073 14.494 +18 6871 513.675 505.171 123.113 -6.05679 -3.14203 45.5778 +19 6871 512.86 504.418 121.887 -6.15319 -3.24313 45.9128 +20 6871 511.986 503.415 120.523 -6.1147 -3.27945 45.2171 +18 6875 421.795 398.636 55.6933 -4.35507 -2.71746 16.7356 +19 6875 413.823 389.345 48.8461 -4.29535 -2.7213 15.8338 +18 6876 477.997 453.532 82.8026 -2.88849 -1.97711 15.8416 +19 6876 471.855 445.918 76.9093 -2.85179 -1.98697 14.9427 +18 6878 463.518 437.647 32.9036 -3.03224 -2.90577 14.9812 +19 6878 456.284 428.771 23.7363 -2.99248 -2.9113 14.087 +20 6878 447.388 418.087 13.1068 -2.97295 -2.92851 13.2273 +18 6881 464.906 440.951 80.2305 -3.24361 -2.07692 16.1792 +19 6881 458.216 432.488 74.5548 -3.1598 -2.05233 15.0645 +20 6881 450.171 422.749 68.0342 -3.12207 -2.05319 14.1334 +21 6881 441.056 411.78 60.1435 -3.09164 -2.06797 13.2385 +22 6881 430.654 399.447 51.7219 -3.07944 -2.08501 12.4196 +23 6881 418.645 385.057 42.7564 -3.05311 -2.08053 11.5389 +24 6881 405.052 369.454 32.832 -3.08585 -2.11283 10.8875 +25 6881 388.82 350.866 20.4292 -3.12398 -2.15717 10.2115 +18 6883 507.834 497.366 123.767 -5.22024 -2.51899 37.027 +19 6883 505.89 496.076 121.857 -5.67413 -2.79121 39.492 +18 6885 441.591 416.442 57.1645 -3.58758 -2.47097 15.4111 +19 6885 433.435 407.878 50.0929 -3.70168 -2.58012 15.1649 +18 6896 607.234 600.012 45.5688 -0.172907 -9.46631 53.6614 +19 6896 608.756 601.417 43.5972 -0.0588108 -9.46072 52.8116 +20 6896 609.856 602.395 40.7039 0.0213691 -9.5133 51.9425 +21 6896 611.035 603.565 37.6573 0.106106 -9.72109 51.8809 +22 6896 612.303 604.804 34.9467 0.196499 -9.8783 51.6837 +23 6896 613.391 605.95 32.6672 0.276614 -10.1202 52.0886 +18 6897 600.217 593.684 47.5741 -0.768198 -10.301 59.3277 +19 6897 601.68 594.868 45.0541 -0.621289 -10.0772 56.8942 +18 6899 590.416 583.366 73.9271 -1.45876 -7.53826 54.9814 +19 6899 591.064 584.191 71.5975 -1.44548 -7.91359 56.391 +20 6899 591.85 584.704 69.0258 -1.33107 -7.80403 54.2329 +18 6903 666.174 645.206 73.6862 1.45033 -2.54041 18.4839 +19 6903 671.378 648.133 69.3105 1.42851 -2.39271 16.6735 +18 6904 666.174 645.206 73.6862 1.45033 -2.54041 18.4839 +19 6904 671.378 648.133 69.3105 1.42851 -2.39271 16.6735 +18 6906 657.983 645.411 119.574 2.06892 -2.2764 30.8277 +19 6906 660.07 647.701 117.939 2.19349 -2.38475 31.3337 +18 6910 697.004 672.402 59.9808 1.9092 -2.46438 15.7535 +19 6910 703.184 677.364 54.1264 1.9477 -2.46992 15.0103 +20 6910 709.916 681.989 46.768 1.93027 -2.42513 13.878 +18 6915 746.911 724.912 114.176 3.35376 -1.43277 17.618 +19 6915 755.941 732.964 111.074 3.42211 -1.44429 16.8682 +20 6915 765.616 740.996 106.842 3.40482 -1.44025 15.7424 +21 6915 776.275 750.215 101.91 3.43643 -1.46233 14.8727 +22 6915 788.367 760.675 96.9246 3.46828 -1.47278 13.9954 +23 6915 801.631 772.178 91.638 3.50283 -1.48114 13.1587 +18 6916 825.76 804.969 43.4646 5.58566 -3.34284 18.6413 +19 6916 839.022 815.912 37.4925 5.33335 -3.14617 16.7705 +18 6920 735.281 712.802 93.2174 3.00415 -1.90293 17.2413 +19 6920 743.821 720.212 88.8728 3.05468 -1.91071 16.4162 +20 6920 752.907 727.869 83.2889 3.07526 -1.92145 15.4792 +18 6923 797.34 774.742 17.8986 4.46367 -3.6834 17.1515 +19 6923 810.371 785.987 10.311 4.42364 -3.58063 15.8946 +18 6929 937.442 912.542 47.9906 7.0733 -2.69364 15.5655 +19 6929 959.613 933.168 41.0222 7.11023 -2.67774 14.6557 +20 6929 984.137 955.596 31.9544 7.0498 -2.65183 13.5798 +18 6933 919.029 895.282 108.791 7.00007 -1.44908 16.3209 +19 6933 939.063 913.867 105.216 7.02441 -1.44191 15.3818 +20 6933 960.755 934.43 99.9813 7.16606 -1.48695 14.7228 +18 6937 942.245 917.185 43.2873 7.13073 -2.77711 15.4653 +19 6937 964.831 938.167 35.6919 7.15699 -2.76315 14.5355 +20 6937 989.632 961.09 25.7552 7.15301 -2.76842 13.5794 +18 6938 959.431 934.448 82.9769 7.52226 -1.93236 15.5131 +19 6938 982.661 956.377 77.8673 7.62482 -1.94118 14.7456 +18 6939 933.09 909.685 97.545 7.42501 -1.72834 16.5592 +19 6939 954.197 929.111 93.4113 7.37952 -1.70106 15.4498 +18 6940 969.117 942.664 108.872 7.30097 -1.29919 14.6511 +19 6940 992.336 966.647 105.776 8.00399 -1.40262 15.0876 +20 6940 1018.29 990.392 100.902 7.86971 -1.38536 13.8925 +21 6940 1048.12 1018.33 95.2068 7.90544 -1.39964 13.0062 +18 6942 913.03 886.479 46.2145 6.13946 -2.56202 14.5973 +19 6942 933.368 907.623 38.6606 6.75597 -2.79982 15.0542 +20 6942 954.851 927.65 29.8056 6.81867 -2.82486 14.2486 +18 6945 935.345 911.122 83.522 7.22428 -1.98093 16 +19 6945 956.511 930.735 78.4445 7.23027 -1.96744 15.0364 +18 6950 946.31 921.494 54.4023 7.28906 -2.56392 15.6179 +19 6950 969.007 942.604 47.6101 7.31275 -2.54801 14.6792 +20 6950 993.833 965.757 38.5725 7.35186 -2.56905 13.8043 +18 6951 938.206 913.559 70.8037 7.16264 -2.22412 15.7255 +19 6951 960.815 933.871 65.4661 7.00255 -2.14086 14.3844 +18 6952 948.637 924.023 99.482 7.39993 -1.60125 15.7466 +19 6952 972.098 945.358 95.5142 7.28266 -1.5536 14.4942 +18 6955 978.816 953.346 37.6979 7.78753 -2.85041 15.2171 +19 6955 1004.36 976.967 30.0494 7.7408 -2.79993 14.147 +20 6955 1032.55 1003.44 18.8448 7.80729 -2.84263 13.3178 +18 6956 985.529 960.895 48.0121 8.19816 -2.72222 15.7334 +19 6956 1010.86 984.349 40.4664 8.13143 -2.68254 14.6204 +18 6958 1103.25 1074.04 122.86 9.07671 -0.919148 13.2657 +19 6958 1142.04 1110.91 119.875 9.18597 -0.913946 12.4474 +18 6969 1137.9 1118.42 32.1704 14.5684 -3.87916 19.8954 +19 6969 1167.53 1146.65 25.616 14.3553 -3.7881 18.5635 +20 6969 1199.59 1177.83 15.8378 14.5623 -3.87522 17.8078 +18 6970 1134.14 1105.11 125.859 9.70384 -0.869315 13.3471 +19 6970 1176.22 1144.79 123.156 9.68575 -0.849467 12.3331 +20 6970 1224.84 1190.84 118.225 9.72066 -0.863063 11.3994 +18 6973 135.77 124.975 161.091 -23.5753 -0.585329 35.903 +19 6973 125.142 114.304 160.159 -24.0084 -0.629169 35.7604 +18 6975 138.947 129.867 200.334 -27.8397 1.62564 42.6836 +19 6975 130.119 121.329 200.057 -29.297 1.66231 44.0907 +18 6976 137.055 126.097 126.344 -23.1617 -2.27989 35.369 +19 6976 126.64 114.411 124.202 -21.2126 -2.13707 31.6941 +18 6978 112.023 100.917 176.249 -24.0652 0.164214 34.8998 +19 6978 100.208 89.5995 175.9 -25.791 0.154255 36.5351 +18 6980 127.666 116.4 140.724 -22.9748 -1.53186 34.4002 +19 6980 116.323 104.944 140.575 -23.2826 -1.52367 34.0593 +20 6980 104.309 92.7278 141.408 -23.4347 -1.45855 33.4666 +21 6980 91.6745 80.177 139.808 -24.195 -1.54388 33.7094 +18 6988 249.254 207.196 228.596 -4.60165 0.711907 9.21514 +19 6988 212.637 166.153 233.905 -4.58663 0.705473 8.33772 +20 6988 167.063 115.017 240.864 -4.56695 0.701917 7.44689 +21 6988 109.167 50.7131 248.917 -4.59828 0.698971 6.63045 +18 6993 239.445 216.691 144.215 -8.73747 -0.676085 17.0337 +19 6993 220.608 196.21 141.736 -8.56304 -0.685094 15.8852 +18 7006 368.835 347.503 233.538 -6.06134 1.52801 18.1681 +19 7006 357.924 335.538 236.132 -6.03813 1.51839 17.3137 +20 7006 345.793 322.167 238.927 -5.99678 1.50218 16.4043 +18 7008 409.587 385.32 141.8 -4.42642 -0.687374 15.9714 +19 7008 399.517 373.758 139.594 -4.38012 -0.69359 15.0466 +20 7008 388.173 360.827 137.995 -4.3486 -0.684723 14.1729 +21 7008 374.901 345.659 134.695 -4.31045 -0.700947 13.254 +22 7008 360.07 328.083 132.146 -4.18963 -0.683597 12.1166 +23 7008 342.164 308.347 128.962 -4.24727 -0.697179 11.4608 +24 7008 321.362 286.419 124.51 -4.43023 -0.743147 11.0916 +18 7011 285.619 248.576 219.751 -4.69728 0.680026 10.4626 +19 7011 256.982 214.996 223.497 -4.51072 0.647898 9.23103 +20 7011 220.568 174.84 227.932 -4.56927 0.646973 8.47552 +18 7014 361.185 339.312 209.057 -6.09938 0.889053 17.719 +19 7014 349.52 326.27 210.617 -6.00792 0.872482 16.6703 +20 7014 336.442 312.306 212.175 -6.07834 0.875114 16.0581 +21 7014 321.669 296.978 213.427 -6.26301 0.882665 15.6969 +22 7014 306.11 278.772 215.14 -5.96242 0.830876 14.1773 +23 7014 287.653 258.996 218.518 -6.03388 0.855932 13.5246 +24 7014 267.158 236.822 221.708 -6.06281 0.865046 12.7761 +25 7014 243.729 212.972 225.301 -6.38899 0.915951 12.6012 +18 7018 507.52 499.788 204.782 -7.08889 2.21807 50.1267 +19 7018 507.053 498.99 204.957 -6.82884 2.13869 48.0678 +20 7018 506.312 497.891 204.968 -6.58564 2.04841 46.0233 +21 7018 505.295 497.102 204.734 -6.83539 2.08998 47.303 +18 7019 531.943 527.924 129.081 -10.3751 -5.85118 96.4491 +19 7019 532.344 528.252 128.04 -10.1347 -5.88194 94.7043 +20 7019 532.464 528.554 126.626 -10.5918 -6.35113 99.1292 +21 7019 532.401 529.123 124.901 -12.6466 -7.85977 118.263 +18 7020 434.865 429.252 169.674 -16.7174 -0.304336 69.0475 +19 7020 434.28 425.471 171.559 -10.6882 -0.0789841 43.9981 +18 7021 574.661 572.184 149.316 -7.56653 -5.1034 156.443 +19 7021 575.765 573.179 149.08 -7.01824 -4.93738 149.846 +20 7021 576.705 574.084 148.352 -6.73161 -5.02042 147.84 +18 7024 581.648 569.896 214.273 -1.27579 1.89318 32.9803 +19 7024 582.028 569.631 215.349 -1.19287 1.84122 31.2629 +20 7024 582.518 569.787 216.062 -1.14089 1.823 30.4426 +21 7024 582.85 569.734 216.378 -1.09391 1.78253 29.5509 +18 7025 677.677 658.646 230.501 1.92257 1.62704 20.3648 +19 7025 682.168 662.045 233.16 1.93816 1.60976 19.2601 +20 7025 686.921 665.914 235.349 1.9781 1.59795 18.4493 +21 7025 691.945 670.038 237.409 2.02008 1.58287 17.692 +18 7027 558.028 551.663 150.794 -4.34873 -1.86162 60.891 +19 7027 558.412 552.077 150.33 -4.33628 -1.90959 61.1726 +20 7027 558.766 552.191 149.621 -4.14966 -1.89809 58.9477 +21 7027 559.018 552.496 148.389 -4.16267 -2.01501 59.4271 +22 7027 558.894 552.22 147.75 -4.07744 -2.02028 58.0679 +23 7027 559.583 552.235 147.613 -3.65386 -1.84542 52.7524 +24 7027 560.028 552.173 147.573 -3.38706 -1.72875 49.3401 +18 7029 770.663 756.914 173.834 6.29413 0.0382737 28.1896 +19 7029 777.107 763.1 173.997 6.42561 0.0438519 27.6717 +20 7029 784.161 769.487 173.403 6.39113 0.0201085 26.4112 +21 7029 791.563 776.413 172.636 6.45293 -0.00772477 25.582 +18 7030 716.716 696.1 180.167 2.79198 0.190546 18.7997 +19 7030 723.668 701.85 180.216 2.80927 0.181241 17.7637 +20 7030 730.995 707.914 180.436 2.82604 0.176444 16.7916 +21 7030 739.031 714.784 179.553 2.86819 0.148409 15.9843 +22 7030 747.961 722.274 179.415 2.8941 0.137204 15.0879 +23 7030 757.968 730.567 179.991 2.90932 0.139902 14.1447 +18 7032 769.745 740.269 213.087 2.91914 0.733185 13.149 +19 7032 783.079 751.481 216.705 2.94977 0.745445 12.2659 +18 7034 705.1 680.555 246.367 2.09086 1.60879 15.7905 +19 7034 712.295 686.265 250.757 2.12007 1.60762 14.8898 +20 7034 720.272 692.351 254.887 2.12988 1.57815 13.8809 +21 7034 729.012 699.57 259.387 2.17929 1.5787 13.1636 +22 7034 739.058 707.481 265.054 2.20291 1.56842 12.2741 +18 7037 705.312 680.933 239.83 2.10972 1.47569 15.8977 +19 7037 712.534 686.994 243.73 2.16571 1.49062 15.175 +20 7037 720.233 692.8 246.923 2.16704 1.45032 14.1281 +21 7037 728.985 699.931 250.554 2.20798 1.43655 13.34 +18 7042 780.503 775.214 148.377 17.3628 -2.48614 73.2869 +19 7042 782.599 779.367 148.395 28.7535 -4.06428 119.895 +20 7042 784.868 783.22 147.943 57.1336 -8.11845 235.151 +21 7042 789.493 785.562 146.572 24.5815 -3.5905 98.5722 +22 7042 793.536 785.53 145.79 12.343 -1.81573 48.408 +23 7042 796.722 790.77 145.308 16.8918 -2.4861 65.1204 +18 7045 712.801 692.761 144.229 2.76732 -0.767278 19.3403 +19 7045 719.746 698.48 142.792 2.78316 -0.759325 18.2251 +20 7045 727.635 703.98 140.13 2.6812 -0.743089 16.3843 +18 7048 863.516 851.758 171.894 11.6014 -0.0438371 32.9616 +19 7048 872.251 860.296 172.025 11.8033 -0.0372709 32.4202 +18 7049 960.073 928.989 192.026 6.05713 0.331303 12.4687 +19 7049 989.185 955.878 193.979 6.12245 0.340691 11.6367 +18 7051 939.13 914.771 126.641 7.26741 -1.01906 15.9107 +19 7051 960.87 935.102 124.305 7.32324 -1.01202 15.0408 +20 7051 984.802 957.285 120.433 7.32512 -1.02331 14.0852 +21 7051 1011.94 982.41 115.987 7.31966 -1.03447 13.1255 +18 7056 917.948 893.872 185.642 6.8805 0.285312 16.0983 +19 7056 939.973 912.041 186.899 6.35409 0.270099 13.8757 +18 7057 934.201 910.079 153.308 7.22911 -0.435255 16.0672 +19 7057 954.986 929.737 152.089 7.34856 -0.441759 15.3499 +20 7057 978.871 951.684 150.531 7.29661 -0.441051 14.2556 +21 7057 1005.5 976.31 148.482 7.28577 -0.448466 13.2771 +22 7057 1036.07 1004.23 146.694 7.19568 -0.441343 12.173 +23 7057 1070.69 1037.31 144.607 7.4213 -0.454593 11.6122 +18 7058 923.978 899.647 175.723 6.94135 0.0633274 15.9292 +19 7058 943.772 918.674 175.977 7.1529 0.0668356 15.4425 +20 7058 966.29 940.183 175.321 7.33955 0.0507601 14.8453 +21 7058 991.553 963.495 174.834 7.31305 0.0379133 13.8134 +22 7058 1020.01 989.125 175.19 7.13757 0.0406198 12.5471 +23 7058 1053.54 1019.96 175.26 7.10159 0.0384814 11.5413 +24 7058 1091.77 1055.98 175.597 7.23674 0.0411716 10.8285 +18 7063 1106.2 1058.87 200.38 5.63698 0.31243 8.18962 +19 7063 1168.4 1116.92 205.772 5.83068 0.343455 7.52818 +18 7064 1106.73 1077.38 136.331 9.09934 -0.66845 13.2059 +19 7064 1146.54 1114.99 134.286 9.14206 -0.656614 12.2841 +20 7064 1191.79 1157.94 130.118 9.23781 -0.678053 11.448 +18 7068 1095.91 1065.96 154.964 8.72313 -0.320873 12.9414 +19 7068 1135.12 1103.12 154.329 8.82269 -0.31098 12.1126 +20 7068 1181.37 1145.95 151.667 8.67289 -0.321351 10.9439 +18 7072 1163.82 1134.01 131.995 9.98836 -0.736313 13.0028 +19 7072 1209.07 1177.08 129.595 10.0681 -0.726483 12.1174 +18 7073 1119.01 1089.41 139.628 9.24517 -0.602966 13.094 +19 7073 1160 1128.26 137.747 9.31633 -0.594192 12.2122 +20 7073 1207.34 1173.18 133.803 9.40107 -0.614141 11.3474 +18 7075 1161.18 1131.8 145.227 10.0868 -0.505179 13.194 +19 7075 1205.78 1174.02 143.957 10.0849 -0.488782 12.2047 +18 7090 169.796 117.509 252.928 -4.51776 0.822612 7.41247 +19 7090 111.581 52.1476 263.355 -4.50065 0.817934 6.52114 +18 7094 389.932 352.596 292.861 -3.15976 1.72654 10.3807 +19 7094 371.321 330.682 303.267 -3.14896 1.72376 9.53704 +18 7097 365.85 324.306 306.646 -3.15112 1.7299 9.32935 +19 7097 341.544 296.068 320.319 -3.16574 1.74182 8.52265 +18 7100 279.748 239.928 305.16 -4.44893 1.78471 9.73306 +19 7100 248.075 204.311 318.095 -4.43681 1.78267 8.85605 +18 7102 546.474 517.311 267.558 -1.16198 1.74436 13.2901 +19 7102 543.268 512.526 274.341 -1.15828 1.77325 12.6072 +20 7102 539.485 506.046 281.896 -1.12562 1.75158 11.5903 +21 7102 535.345 499.387 290.154 -1.10865 1.75227 10.7787 +18 7103 419.346 382.719 295.269 -2.78958 1.79528 10.5817 +19 7103 403.96 362.625 306.285 -2.67178 1.73395 9.37644 +18 7109 690.228 661.236 265.349 1.4946 1.7137 13.3683 +19 7109 695.98 665.388 272.165 1.51745 1.7438 12.6694 +18 7114 737.276 704.575 269.959 2.09792 1.59508 11.8523 +19 7114 749.164 713.976 277.8 2.13105 1.60198 11.0141 +20 7114 763.168 724.525 286.313 2.13522 1.57712 10.0296 +21 7114 779.151 737.182 296.122 2.17054 1.57766 9.23469 +18 7117 755.265 714.88 294.237 1.938 1.61449 9.59704 +19 7117 771.12 727.156 306.26 1.97391 1.62992 8.81555 +18 7118 789.006 739.271 321.374 1.93806 1.60405 7.79277 +19 7118 814.094 757.919 340.505 1.95581 1.60312 6.89952 +18 7121 882.075 846.453 268.765 4.10941 1.44629 10.8805 +19 7121 908.039 869.877 277.787 4.20129 1.477 10.1561 +18 7122 899.77 860.147 280.22 3.93419 1.45549 9.78139 +19 7122 930.091 886.857 291.162 3.98235 1.46988 8.96453 +20 7122 967.943 919.249 303.561 3.95342 1.44187 7.95948 +21 7122 1014.07 959.811 319.051 4.00489 1.44746 7.14373 +22 7122 1073.23 1011.16 339.434 4.01251 1.44155 6.24403 +18 7123 945.045 900.605 291.921 4.05508 1.43919 8.72138 +19 7123 985.689 935.881 305.877 4.05635 1.43458 7.78139 +18 7124 963.156 913.511 309.257 3.82587 1.47586 7.80694 +19 7124 1010.75 954.616 327.441 3.83877 1.47915 6.90393 +18 7126 936.034 886.837 306.197 3.56455 1.45587 7.87796 +19 7126 978.083 922.743 323.986 3.577 1.46693 7.00346 +18 7128 1013.41 973.301 274.219 5.40799 1.35737 9.66207 +19 7128 1056.52 1012.56 285.246 5.46142 1.37332 8.81646 +18 7131 1041.62 998.729 280.874 5.41107 1.35283 9.03647 +19 7131 1090.94 1043.27 293.528 5.42469 1.35988 8.13102 +18 7139 1052.86 1006.27 276.506 5.11158 1.19519 8.31991 +19 7139 1103.79 1056.29 288.254 5.58924 1.30506 8.15988 +18 7140 1014.89 972.085 283.751 5.0867 1.39171 9.05501 +19 7140 1061.74 1014.14 296.464 5.10272 1.39489 8.14225 +20 7140 1120.02 1066.01 311.082 5.07732 1.3749 7.17685 +19 7153 1031.24 1004.08 48.4559 8.33941 -2.46015 14.2694 +20 7153 1061.17 1032.76 38.4323 8.53735 -2.54114 13.6401 +19 7155 1195.06 1173.4 19.2287 14.5226 -3.81049 17.8969 +20 7155 1231.61 1207.84 9.01888 14.0572 -3.70241 16.3056 +19 7159 344.971 322.392 232.229 -6.2946 1.41255 17.1655 +20 7159 332.066 308.214 234.828 -6.24924 1.39568 16.2493 +21 7159 317.74 292.489 237.203 -6.20785 1.3689 15.3492 +19 7162 985.054 957.555 149.175 7.33484 -0.462545 14.0944 +20 7162 1010.41 983.19 146.858 7.91078 -0.51303 14.2396 +21 7162 1039.46 1010.1 144.406 7.86553 -0.520487 13.2015 +22 7162 1072.48 1040.96 142.135 7.88967 -0.52356 12.2974 +19 7164 415.315 379.492 291.074 -2.91261 1.77266 10.8192 +20 7164 399.62 360.771 300.953 -2.90278 1.7712 9.97653 +21 7164 380.988 338.199 312.115 -2.86933 1.7482 9.05771 +19 7166 873.258 834.917 280.216 3.69437 1.50412 10.1086 +20 7166 900.578 858.056 290.079 3.67628 1.48084 9.11482 +19 7167 937.363 894.137 286.367 4.07348 1.41057 8.96624 +20 7167 974.447 926.778 297.589 4.11172 1.40557 8.13061 +21 7167 1020.17 967.653 311.163 4.19999 1.41473 7.38041 +19 7180 106.144 94.9636 121.758 -24.1859 -2.45485 34.6653 +20 7180 94.0145 82.9294 119.584 -24.9818 -2.58134 34.9637 +19 7183 273.322 245.336 41.8409 -6.45359 -2.51461 13.8489 +20 7183 252.272 222.877 31.8816 -6.5289 -2.57606 13.185 +21 7183 227.928 196.276 19.9747 -6.47652 -2.59446 12.2449 +19 7184 241.993 213.954 60.0703 -7.04134 -2.16056 13.8223 +20 7184 218.234 188.495 52.0166 -7.06818 -2.18259 13.0325 +19 7186 230.602 203.617 106.667 -7.5434 -1.31749 14.3627 +20 7186 207.058 178.866 101.839 -7.6689 -1.35305 13.7476 +21 7186 180.761 150.426 95.8826 -7.59306 -1.36299 12.7768 +22 7186 150.469 117.693 89.5618 -7.52385 -1.36504 11.825 +23 7186 115.128 80.2422 83.4225 -7.61299 -1.37702 11.1099 +24 7186 74.9029 36.2825 76.3923 -7.43626 -1.34164 10.0355 +19 7197 231.902 204.068 72.0599 -7.28807 -1.94514 13.9243 +20 7197 207.698 178.289 64.9022 -7.34001 -1.97174 13.1789 +19 7199 218.998 192.034 88.9964 -7.78046 -1.67055 14.3739 +20 7199 194.741 165.934 83.3459 -7.73495 -1.66902 13.4542 +21 7199 167.361 136.857 76.1065 -7.78686 -1.70367 12.7059 +22 7199 136.08 101.828 68.3268 -7.42546 -1.63927 11.3157 +19 7206 243.736 216.777 67.5829 -7.28878 -2.09746 14.3762 +20 7206 221.223 191.531 59.8616 -7.02526 -2.04411 13.0531 +19 7207 202.493 175.034 39.6107 -7.96279 -2.60643 14.1143 +20 7207 176.676 144.416 30.4536 -7.20797 -2.37112 12.0144 +19 7213 395.705 370.858 113.633 -4.62308 -1.28022 15.5981 +20 7213 383.977 357.444 109.647 -4.56688 -1.27962 14.6074 +21 7213 370.606 343.185 104.464 -4.68086 -1.3397 14.1342 +22 7213 355.844 325.159 99.0966 -4.44136 -1.29114 12.6307 +23 7213 338.768 305.805 94.1687 -4.41268 -1.28222 11.7578 +24 7213 318.386 283.197 88.3486 -4.4447 -1.28996 11.0141 +25 7213 295.345 257.159 80.9537 -4.41991 -1.29272 10.1495 +26 7213 268.316 226.579 71.1533 -4.39176 -1.30888 9.28611 +19 7221 377.029 351.839 106.723 -4.95838 -1.41016 15.3858 +20 7221 364.14 337.011 102.26 -4.85939 -1.39778 14.2867 +19 7229 478.027 451.566 63.5405 -2.67008 -2.21903 14.647 +20 7229 470.949 442.778 56.0103 -2.6429 -2.22788 13.7577 +21 7229 463.107 433.169 47.0767 -2.62765 -2.2567 12.9458 +19 7231 548.751 541.775 109.876 -4.68216 -4.84924 55.5572 +20 7231 548.896 541.661 108.274 -4.50325 -4.79407 53.5627 +21 7231 549.166 541.819 106.325 -4.41511 -4.86366 52.7489 +19 7234 429.896 404.764 29.928 -3.83982 -3.05467 15.421 +20 7234 420.246 393.92 19.8848 -3.86275 -3.12118 14.7222 +19 7239 554.455 549.579 61.9117 -6.0707 -12.2222 79.4895 +20 7239 554.331 549.076 59.4894 -5.64524 -11.5878 73.7534 +21 7239 555.975 548.754 57.6703 -3.98592 -8.56805 53.6723 +22 7239 556.133 548.744 55.0716 -3.88402 -8.56255 52.4544 +23 7239 556.302 549.091 53.4393 -3.96739 -8.89571 53.7504 +24 7239 556.757 549.382 51.9826 -3.84592 -8.80384 52.5542 +25 7239 556.846 549.414 49.8591 -3.80971 -8.88913 52.1472 +19 7242 422.811 397.299 109.997 -3.93188 -1.32341 15.1916 +20 7242 412.627 385.414 106.386 -3.8872 -1.312 14.2423 +21 7242 400.965 372.324 101.461 -3.91207 -1.33894 13.5321 +19 7253 685.471 663.897 96.0908 1.89004 -1.91123 17.9646 +20 7253 690.745 667.148 91.3236 1.84807 -1.85593 16.4248 +21 7253 696.925 672.435 85.5701 1.91625 -1.91447 15.8261 +19 7254 566.628 559.869 99.3583 -3.41197 -5.84108 57.3443 +20 7254 567.053 560.2 97.646 -3.33192 -5.89529 56.5587 +19 7256 676.32 663.555 125.579 2.80915 -1.98923 30.3606 +20 7256 679.544 666.8 123.328 2.9498 -2.08747 30.4121 +21 7256 682.612 671.006 120.882 3.38106 -2.40539 33.3944 +22 7256 686.002 673.573 118.887 3.30357 -2.33222 31.182 +23 7256 689.223 676.633 117.283 3.39868 -2.37081 30.7827 +24 7256 692.704 679.438 115.998 3.36639 -2.302 29.2138 +25 7256 695.78 682.128 113.624 3.39243 -2.33044 28.3895 +19 7260 569.557 562.882 93.0881 -3.21885 -6.41858 58.0605 +20 7260 570.106 563.35 91.324 -3.13669 -6.48195 57.365 +21 7260 570.69 563.68 89.1834 -2.97822 -6.41097 55.2853 +22 7260 571.144 563.958 87.3544 -2.87122 -6.39043 53.9293 +23 7260 571.687 564.594 86.1915 -2.86803 -6.56285 54.6412 +24 7260 572.202 565.083 84.9815 -2.8188 -6.63035 54.443 +25 7260 572.623 565.643 83.4267 -2.84246 -6.88196 55.5266 +26 7260 572.82 565.634 80.4724 -2.74635 -6.90569 53.9362 +19 7266 819.81 795.905 18.822 4.72432 -3.46108 16.2129 +20 7266 833.116 807.654 8.96318 4.71624 -3.45751 15.2219 +19 7270 701.29 677.785 87.0446 2.09627 -1.96095 16.4889 +20 7270 707.708 682.994 81.2803 2.1332 -1.9903 15.6822 +19 7272 700.365 677.267 108.775 2.11178 -1.49022 16.7802 +20 7272 706.662 682.053 104.382 2.11954 -1.49459 15.7496 +21 7272 713.884 687.555 99.3489 2.12836 -1.4996 14.7203 +22 7272 721.998 694.318 94.3371 2.18198 -1.52369 14.0021 +23 7272 730.868 701.467 88.9829 2.21624 -1.53227 13.182 +24 7272 740.76 709.321 83.1721 2.24164 -1.53227 12.3279 +25 7272 752.203 718.117 76.0522 2.24788 -1.52548 11.3705 +26 7272 764.859 727.847 66.4678 2.25385 -1.54398 10.4716 +19 7279 700.509 677.527 94.6244 2.12576 -1.82845 16.8644 +20 7279 707.572 682.505 88.9186 2.10031 -1.79866 15.4619 +19 7280 705.175 681.866 104.058 2.20346 -1.5854 16.6277 +20 7280 711.892 687.041 99.4343 2.21193 -1.58697 15.5961 +21 7280 719.404 693.177 94.094 2.24972 -1.61308 14.7778 +19 7281 705.175 681.866 104.058 2.20346 -1.5854 16.6277 +20 7281 711.892 687.041 99.4343 2.21193 -1.58697 15.5961 +19 7282 724.726 702.153 58.7723 2.74051 -2.71468 17.1697 +20 7282 732.693 708.668 51.2971 2.75294 -2.71767 16.1316 +19 7283 807.357 802.847 120.789 23.558 -6.20099 85.9365 +20 7283 811.034 806.041 119.512 21.6725 -5.73798 77.6153 +21 7283 814.415 809.781 117.98 23.7429 -6.35996 83.6266 +22 7283 818.062 813.214 116.707 23.1019 -6.22103 79.9459 +19 7285 729.603 705.587 78.174 2.68503 -2.11772 16.1388 +20 7285 737.874 712.54 72.332 2.72059 -2.13131 15.2984 +19 7287 716.569 692.235 40.587 2.3621 -2.91961 15.927 +20 7287 724.83 698.233 31.9687 2.32805 -2.84538 14.5725 +19 7288 716.569 692.235 40.587 2.3621 -2.91961 15.927 +20 7288 724.83 698.233 31.9687 2.32805 -2.84538 14.5725 +21 7288 732.398 705.685 21.5034 2.47003 -3.04334 14.5086 +19 7291 752.226 728.118 68.5242 3.17879 -2.3246 16.0768 +20 7291 762.256 735.903 61.0335 3.11248 -2.27929 14.7075 +19 7294 962.211 936.75 17.6346 7.43986 -3.27465 15.2222 +20 7294 984.526 959.609 7.20031 8.0834 -3.5711 15.5547 +19 7296 844.872 818.344 23.918 4.76469 -3.01571 14.6099 +20 7296 859.994 834.713 14.4493 5.32104 -3.36566 15.3307 +19 7297 948.611 922.021 36.3626 6.84937 -2.75734 14.5762 +20 7297 972.298 943.96 26.5077 6.87569 -2.77398 13.6767 +19 7298 926.251 900.948 47.8095 6.72308 -2.65458 15.3176 +20 7298 946.884 920.444 39.1321 6.8532 -2.71674 14.659 +21 7298 970.076 942.235 29.3506 6.95579 -2.76875 13.9213 +22 7298 996.69 966.483 18.9421 6.88408 -2.73691 12.8306 +19 7300 959.407 933.203 56.5697 7.1713 -2.38363 14.7903 +20 7300 983.564 955.536 48.1719 7.16774 -2.38951 13.8281 +21 7300 1011.12 981.344 38.7902 7.24348 -2.41827 13.0152 +19 7306 950.863 925.431 122.592 7.2087 -1.06159 15.2397 +20 7306 974.116 946.614 117.978 7.12021 -1.0718 14.0925 +19 7309 964.831 938.167 35.6919 7.15699 -2.76315 14.5355 +20 7309 989.632 961.09 25.7552 7.15301 -2.76842 13.5794 +19 7311 965.234 939.135 60.9877 7.32042 -2.30241 14.8505 +20 7311 990.061 961.995 52.5535 7.28247 -2.30245 13.8096 +19 7313 957.919 932.123 116.687 7.25384 -1.16957 15.0245 +20 7313 981.634 954.159 112.15 7.27434 -1.18682 14.1066 +21 7313 1008.37 979.317 107.257 7.37382 -1.21286 13.3409 +19 7315 954.018 927.938 64.0614 7.09472 -2.24077 14.8613 +20 7315 977.869 949.979 56.2243 7.09347 -2.24623 13.8965 +19 7318 1022.31 996.091 41.4733 8.45526 -2.69134 14.7807 +20 7318 1050.82 1022.56 31.9861 8.38766 -2.67768 13.7153 +19 7321 981.921 955.349 66.9613 7.52728 -2.14061 14.5858 +20 7321 1007.81 979.579 58.9885 7.57841 -2.16679 13.7304 +21 7321 1037.12 1007.28 50.3751 7.69764 -2.20506 12.9903 +22 7321 1069.9 1038.32 40.7492 7.8303 -2.24707 12.2732 +19 7330 975.003 949.4 124.678 7.66705 -1.01073 15.1379 +20 7330 999.876 972.707 120.681 7.71694 -1.03152 14.2655 +21 7330 1028.3 998.988 116.249 7.67362 -1.03731 13.2225 +19 7331 1106.1 1077.58 71.6067 9.35351 -1.90724 13.5919 +20 7331 1142.83 1113.33 63.9065 9.71074 -1.9839 13.139 +19 7332 978.39 952.716 103.901 7.71675 -1.44265 15.0962 +20 7332 1004.29 976.14 99.051 7.53222 -1.4083 13.7683 +19 7336 1158.28 1130.23 88.8856 10.5071 -1.60785 13.8162 +20 7336 1201.17 1170.42 81.77 10.334 -1.59102 12.6035 +19 7337 1158.28 1130.23 88.8856 10.5071 -1.60785 13.8162 +20 7337 1201.17 1170.42 81.77 10.334 -1.59102 12.6035 +19 7338 1151.76 1123.12 95.8508 10.167 -1.44391 13.5298 +20 7338 1194.17 1163.32 88.8773 10.1793 -1.46221 12.5634 +19 7339 1151.76 1123.12 95.8508 10.167 -1.44391 13.5298 +20 7339 1194.17 1163.32 88.8773 10.1793 -1.46221 12.5634 +19 7340 1151.76 1123.12 95.8508 10.167 -1.44391 13.5298 +20 7340 1194.17 1163.32 88.8773 10.1793 -1.46221 12.5634 +19 7344 1195.06 1173.4 19.2287 14.5226 -3.81049 17.8969 +20 7344 1231.61 1207.84 9.01888 14.0572 -3.70241 16.3056 +19 7348 1113.43 1085.08 81.234 9.54621 -1.7358 13.67 +20 7348 1152.08 1121.51 73.5166 9.53475 -1.74585 12.681 +19 7349 112.129 101.028 126.823 -24.0699 -2.22737 34.9141 +20 7349 99.8934 86.8388 125.243 -20.971 -1.95902 29.6888 +19 7350 112.129 101.028 126.823 -24.0699 -2.22737 34.9141 +20 7350 99.8934 86.8388 125.243 -20.971 -1.95902 29.6888 +19 7352 89.7224 78.1184 176.794 -24.0632 0.182392 33.3999 +20 7352 76.3186 64.4969 176.64 -24.2292 0.172026 32.785 +21 7352 62.6386 50.5449 175.62 -24.292 0.122847 32.0477 +19 7357 133.506 124.195 149.533 -27.4652 -1.34546 41.628 +20 7357 124.027 114.725 148.476 -28.0362 -1.40765 41.6639 +19 7358 129.426 119.29 171.546 -25.4448 -0.0693198 38.238 +20 7358 119.212 110.048 171.31 -28.7397 -0.0904703 42.29 +19 7360 134.117 123.029 160.351 -23.0313 -0.605693 34.9527 +20 7360 122.77 111.607 159.495 -23.4247 -0.642861 34.721 +21 7360 110.882 99.3852 157.783 -23.2996 -0.704172 33.7122 +22 7360 98.374 86.5797 156.719 -23.281 -0.734839 32.8612 +19 7363 131.545 121.154 135.266 -24.7083 -1.94292 37.2959 +20 7363 120.992 109.53 133.639 -22.8959 -1.83776 33.8137 +21 7363 109.083 97.7407 131.354 -23.7007 -1.9653 34.1693 +19 7367 237.337 211.182 127.849 -7.6442 -0.924252 14.818 +20 7367 215.189 186.725 124.7 -7.44211 -0.908714 13.6161 +19 7371 244.775 201.062 245.425 -4.48254 0.891766 8.86639 +20 7371 206.084 157.387 253.162 -4.45058 0.885845 7.95899 +21 7371 157.39 103.163 262.363 -4.47902 0.886644 7.14728 +19 7372 180.072 129.23 248.584 -4.53756 0.800089 7.6231 +20 7372 125.03 67.6987 258.453 -4.53967 0.801994 6.76025 +19 7375 182.915 134.326 233.525 -4.71648 0.670712 7.97649 +20 7375 130.987 75.778 240.787 -4.65626 0.66095 7.02018 +19 7382 147.232 136.017 163.102 -22.1453 -0.467122 34.5613 +20 7382 136.371 126.04 162.431 -24.6034 -0.541942 37.5164 +19 7386 387.974 362.964 133.997 -4.75912 -0.834549 15.4969 +20 7386 375.87 347.217 131.115 -4.38097 -0.782476 13.5267 +19 7388 368.96 346.722 234.676 -5.8115 1.49327 17.4282 +20 7388 357.534 333.922 237.573 -5.73331 1.4723 16.4142 +19 7389 368.96 346.722 234.676 -5.8115 1.49327 17.4282 +20 7389 357.534 333.922 237.573 -5.73331 1.4723 16.4142 +19 7390 368.96 346.722 234.676 -5.8115 1.49327 17.4282 +20 7390 357.534 333.922 237.573 -5.73331 1.4723 16.4142 +19 7391 381.933 357.27 245.635 -4.95761 1.58514 15.7148 +20 7391 369.261 344.409 249.523 -5.19381 1.65713 15.5953 +21 7391 355.966 330.721 252.823 -5.39569 1.70149 15.3521 +22 7391 342.025 315.564 256.831 -5.43081 1.70469 14.6469 +23 7391 326.623 298.638 262.271 -5.43075 1.71629 13.8494 +24 7391 309.295 278.694 268.483 -5.27074 1.67864 12.6656 +25 7391 289.146 254.92 274.866 -5.02869 1.60102 11.3241 +19 7392 364.425 341.058 248.974 -5.63503 1.7498 16.5864 +20 7392 351.95 327.176 252.785 -5.58544 1.73305 15.6443 +21 7392 337.689 311.801 256.546 -5.64103 1.73654 14.9712 +22 7392 321.982 293.356 261.381 -5.3963 1.66118 13.5394 +23 7392 303.299 272.911 267.783 -5.41356 1.67799 12.7541 +19 7394 279.205 240.406 234.893 -4.57366 0.858909 9.98948 +20 7394 248.549 205.759 240.525 -4.53183 0.849486 9.05758 +21 7394 211.252 164.327 246.494 -4.55939 0.842952 8.25939 +19 7395 369.338 347.707 241.927 -5.96551 1.71533 17.9182 +20 7395 358.459 335.787 245.044 -5.94921 1.71037 17.0951 +21 7395 346.234 322.52 247.943 -5.96453 1.70083 16.3434 +22 7395 332.673 307.261 251.792 -5.85268 1.66856 15.2515 +23 7395 317.489 290.647 257.033 -5.84479 1.68456 14.4391 +24 7395 300.263 271.463 262.785 -5.76862 1.67729 13.4573 +25 7395 280.576 250.023 268.518 -5.78388 1.68188 12.6854 +26 7395 257.932 225.247 273.951 -5.77885 1.66148 11.8582 +19 7396 370.943 345.606 127.768 -5.05872 -0.955825 15.2968 +20 7396 357.709 330.747 124.398 -5.01757 -0.965372 14.375 +21 7396 342.577 314.18 120.409 -5.05008 -0.992019 13.6482 +22 7396 325.575 294.752 116.189 -4.94901 -0.987498 12.5743 +23 7396 305.637 272.346 112.276 -4.90376 -0.977427 11.6419 +24 7396 282.865 247.831 107.24 -5.0089 -1.00599 11.0627 +19 7397 355.997 333.129 224.604 -5.95607 1.21558 16.9486 +20 7397 343.534 319.938 226.847 -6.0561 1.22916 16.4259 +21 7397 329.896 304.36 228.847 -5.88282 1.17783 15.1778 +19 7398 355.997 333.129 224.604 -5.95607 1.21558 16.9486 +20 7398 343.534 319.938 226.847 -6.0561 1.22916 16.4259 +21 7398 329.896 304.36 228.847 -5.88282 1.17783 15.1778 +22 7398 314.178 287.812 231.728 -6.0179 1.19945 14.7001 +23 7398 296.67 267.988 235.986 -5.85986 1.18235 13.5131 +24 7398 276.7 246.176 240.54 -5.85744 1.1911 12.6972 +19 7404 551.258 532.894 234.958 -1.70528 1.8165 21.1046 +20 7404 550.057 530.329 236.965 -1.62018 1.74565 19.6465 +21 7404 548.365 528.449 239.202 -1.65049 1.78948 19.4607 +19 7407 481.105 472.434 195.838 -7.95761 1.42381 44.6985 +20 7407 479.786 471.334 195.699 -8.24813 1.45201 45.8594 +21 7407 478.539 469.002 195.353 -7.37932 1.26716 40.6384 +19 7408 432.445 423.19 212.283 -10.2802 2.28853 41.8799 +20 7408 431.563 420.281 212.245 -8.47509 1.87556 34.3552 +19 7409 432.445 423.19 212.283 -10.2802 2.28853 41.8799 +20 7409 431.563 420.281 212.245 -8.47509 1.87556 34.3552 +19 7410 685.706 679.871 152.319 7.00986 -1.89036 66.4228 +20 7410 687.892 681.827 151.454 6.93783 -1.89542 63.906 +21 7410 690.455 683.973 149.88 6.70371 -1.90386 59.793 +22 7410 692.891 686.408 148.995 6.90431 -1.97681 59.7818 +19 7413 583.367 566.93 224.891 -0.855911 1.70049 23.5787 +20 7413 583.425 566.523 226.232 -0.830556 1.69637 22.9308 +19 7417 694.149 673.161 232.95 2.16497 1.53808 18.4669 +20 7417 699.169 677.378 234.708 2.20891 1.52472 17.7861 +19 7419 569.982 551.971 233.975 -1.18036 1.82288 21.5191 +20 7419 569.572 550.304 235.987 -1.11478 1.76004 20.1152 +21 7419 568.765 549.828 237.401 -1.15717 1.83092 20.467 +22 7419 569.458 549.024 242.214 -1.05417 1.8233 18.9675 +23 7419 569.408 547.549 248.47 -0.98662 1.85809 17.7302 +24 7419 568.423 545.101 256.512 -0.947453 1.92681 16.6185 +19 7422 586.584 582.209 153.821 -2.82052 -2.3365 88.5785 +20 7422 587.143 582.242 152.779 -2.45698 -2.20036 79.0846 +19 7427 805.075 800.2 137.374 21.5399 -3.9088 79.4915 +20 7427 808.473 803.636 136.276 22.0904 -4.0622 80.1305 +21 7427 811.904 807.215 134.83 23.1772 -4.35537 82.647 +22 7427 815.486 810.774 134.046 23.4726 -4.42351 82.2445 +23 7427 819.259 814.3 133.496 22.7152 -4.26334 78.1589 +24 7427 823.155 818.183 133.274 23.0742 -4.27575 77.9459 +25 7427 826.523 821.721 132.309 24.2668 -4.53483 80.7018 +19 7430 770.165 756.361 173.415 6.24958 0.0218481 28.0769 +20 7430 776.971 762.563 172.829 6.24125 -0.000916859 26.8996 +21 7430 784.121 769.221 172.057 6.29303 -0.0287413 26.0118 +22 7430 791.628 776.065 171.695 6.284 -0.0400099 24.9035 +23 7430 799.654 783.654 171.318 6.38203 -0.0515821 24.2241 +24 7430 808.402 791.608 171.562 6.36003 -0.0413397 23.0786 +25 7430 817.053 799.883 171.365 6.49112 -0.0465775 22.5721 +19 7431 813.607 800.216 179.478 8.18499 0.265723 28.9432 +20 7431 821.516 807.723 179.407 8.25449 0.255203 28.0998 +21 7431 830.145 815.493 179.017 8.08704 0.225933 26.4528 +19 7434 780.592 748.62 247.658 2.87352 1.25679 12.1226 +20 7434 795.727 760.131 253.725 2.80925 1.22034 10.8879 +19 7437 741.851 719.023 133.656 3.11283 -0.922341 16.9778 +20 7437 750.883 726.473 130.871 3.10987 -0.923861 15.8777 +19 7439 784.907 771.12 168.66 6.83175 -0.163396 28.112 +20 7439 791.427 777.435 168.128 6.9817 -0.181417 27.699 +21 7439 798.915 784.804 167.366 7.20763 -0.208877 27.4645 +22 7439 805.416 792.008 166.45 7.84667 -0.256572 28.9072 +19 7441 933.709 909.233 132.429 7.11376 -0.88716 15.8348 +20 7441 955.219 928.9 129.04 7.05473 -0.894226 14.7262 +21 7441 979.37 951.299 125.649 7.07653 -0.903292 13.807 +22 7441 1006.96 976.654 121.918 7.04296 -0.902709 12.7874 +23 7441 1037.95 1005.55 117.689 7.10333 -0.91473 11.9643 +24 7441 1073.64 1038.9 113.274 7.17591 -0.921275 11.157 +19 7444 938.295 913.67 140.45 7.17065 -0.706829 15.7387 +20 7444 959.921 933.414 137.631 7.0999 -0.713777 14.6216 +21 7444 984.326 956.214 134.53 7.16107 -0.732298 13.7872 +22 7444 1011.76 981.739 131.694 7.19703 -0.736533 12.9114 +23 7444 1043.2 1010.84 128.343 7.19966 -0.739018 11.9796 +19 7448 946.078 920.815 136.94 7.15504 -0.7636 15.3413 +20 7448 968.756 941.794 133.837 7.15596 -0.777304 14.3746 +19 7449 959.803 934.114 142.371 7.32361 -0.637399 15.0874 +20 7449 983.574 956.393 139.5 7.39109 -0.659116 14.2587 +21 7449 1010.38 981.14 136.511 7.36323 -0.667631 13.2549 +22 7449 1041.47 1009.71 133.638 7.30368 -0.663143 12.2013 +19 7450 878.973 873.663 145.582 27.255 -2.75897 72.9938 +20 7450 884.146 878.526 144.373 26.2443 -2.72215 68.9627 +19 7453 915.137 890.454 128.385 6.64989 -0.967723 15.7019 +20 7453 935.514 909.149 124.886 6.6407 -0.977264 14.6999 +19 7454 915.137 890.454 128.385 6.64989 -0.967723 15.7019 +20 7454 935.514 909.149 124.886 6.6407 -0.977264 14.6999 +21 7454 958.333 930.386 121.133 6.70353 -0.994099 13.8682 +22 7454 984.095 954.181 117.345 6.72531 -0.996743 12.9562 +23 7454 1013.07 980.818 112.934 6.72069 -0.997997 12.0176 +19 7456 966.085 940.698 156.361 7.54358 -0.348976 15.2667 +20 7456 990.407 963.068 154.455 7.48277 -0.361502 14.1765 +19 7457 971.505 938.197 192.49 5.83693 0.316658 11.6359 +20 7457 1003.2 967.319 193.197 5.89305 0.304555 10.8019 +21 7457 1040.25 1001.12 194.37 5.91259 0.295379 9.90534 +22 7457 1084.34 1041.62 196.378 5.96902 0.295748 9.0712 +23 7457 1137.8 1090.73 198.544 6.02821 0.293176 8.23407 +24 7457 1203.91 1151.2 202.023 6.05655 0.297242 7.35264 +19 7459 954.986 929.737 152.089 7.34856 -0.441759 15.3499 +20 7459 978.871 951.684 150.531 7.29661 -0.441051 14.2556 +21 7459 1005.5 976.31 148.482 7.28577 -0.448466 13.2771 +22 7459 1036.07 1004.23 146.694 7.19568 -0.441343 12.173 +23 7459 1070.69 1037.31 144.607 7.4213 -0.454593 11.6122 +24 7459 1111.26 1074.74 142.636 7.37938 -0.444471 10.613 +25 7459 1157.95 1118.88 139.922 7.54037 -0.452817 9.92119 +19 7466 1108.6 1073.98 142.366 7.74117 -0.472928 11.1925 +20 7466 1155.22 1117.44 138.562 7.75739 -0.487505 10.2577 +21 7466 1211.34 1169.65 134.236 7.75326 -0.497551 9.29616 +19 7468 984.806 959.551 138.929 7.981 -0.721532 15.3461 +20 7468 1010.86 982.704 135.884 7.65642 -0.705348 13.7663 +19 7473 976.389 950.114 179.976 7.49939 0.145608 14.751 +20 7473 1001.8 974.322 179.431 7.66857 0.128595 14.1067 +19 7481 1152.21 1120.22 164.897 9.11426 -0.133643 12.1189 +20 7481 1200.46 1164.99 163.946 8.9485 -0.134898 10.9268 +19 7493 215.419 168.022 261.924 -4.46678 1.00943 8.17717 +20 7493 169.161 115.912 272.292 -4.44255 1.00309 7.27856 +19 7495 202.103 151.438 334.633 -4.31986 1.71518 7.64975 +20 7495 150.775 94.012 355.182 -4.34148 1.72537 6.82793 +19 7496 182.306 131.25 262.519 -4.49514 0.943368 7.5913 +20 7496 127.111 69.4099 274.399 -4.49122 0.945309 6.71695 +19 7497 194.806 145.266 271.798 -4.49712 1.07283 7.82355 +20 7497 143.102 87.2124 284.101 -4.48311 1.06919 6.93468 +19 7498 242.815 198.077 309.75 -4.40336 1.64366 8.66321 +20 7498 202.471 152.731 325 -4.39619 1.64304 7.79196 +19 7499 336.137 312.26 252.082 -6.1512 1.78239 16.2325 +20 7499 322.055 296.531 255.914 -6.05051 1.74798 15.1847 +21 7499 305.518 279.601 260.355 -6.30172 1.81359 14.9549 +19 7501 380.664 342.08 298.649 -3.18659 1.75126 10.045 +20 7501 359.596 316.74 310.735 -3.13298 1.72816 9.04358 +21 7501 334.22 286.73 324.461 -3.11435 1.71482 8.16128 +22 7501 302.639 249.357 342.52 -3.09417 1.71046 7.27407 +19 7503 353.563 320.981 277.174 -4.22032 1.71981 11.8952 +20 7503 334.791 299.104 284.998 -4.13571 1.68795 10.8603 +19 7505 300.882 267.967 260.017 -5.03738 1.42244 11.775 +20 7505 277.732 239.767 265.026 -4.69484 1.30409 10.2086 +21 7505 248.994 205.172 270.149 -4.41971 1.19262 8.84439 +19 7519 656.673 611.933 313.538 0.56565 1.68904 8.66276 +20 7519 664.285 613.854 329.563 0.582897 1.66916 7.68531 +19 7521 617.546 570.593 316.78 0.0913689 1.64655 8.25459 +20 7521 619.578 567.476 332.263 0.103288 1.64343 7.43869 +19 7526 906.328 866.103 282.838 3.96297 1.46869 9.63521 +20 7526 938.728 893.814 293.411 3.93676 1.44183 8.62938 +21 7526 978.221 928.242 306.528 3.96221 1.43666 7.75475 +22 7526 1027.72 970.752 323.751 3.94256 1.42269 6.80281 +19 7527 961.572 915.468 297.84 4.10124 1.45618 8.4065 +20 7527 1005.48 953.788 311.497 4.11395 1.4406 7.49733 +21 7527 1060.68 1002.06 329.809 4.13327 1.43805 6.61085 +22 7527 1133.16 1064.11 354.578 4.07318 1.41367 5.61299 +19 7528 947.173 898.731 307.978 3.74358 1.4983 8.00066 +20 7528 991.579 936.909 324.056 3.75341 1.48558 7.08923 +21 7528 1047.97 985.465 345.257 3.76771 1.48165 6.20094 +19 7533 1013.85 975.364 270.117 5.64221 1.35737 10.0696 +20 7533 1055.14 1012.72 278.644 5.64283 1.33973 9.13756 +20 7556 381.83 354.418 83.7719 -4.46239 -1.74558 14.1386 +21 7556 368.646 339.238 76.9924 -4.40042 -1.75097 13.1793 +22 7556 354.499 321.099 69.8481 -4.10195 -1.65657 11.604 +23 7556 334.084 300.064 62.513 -4.34954 -1.7422 11.3925 +24 7556 313.8 275.462 54.0058 -4.14381 -1.66515 10.1093 +20 7557 321.736 292.223 44.8631 -5.2386 -2.32953 13.1325 +21 7557 302.723 271.36 34.4332 -5.25513 -2.37071 12.3576 +20 7558 400.618 372.635 78.8263 -4.01075 -1.80492 13.8504 +21 7558 387.816 357.925 71.0552 -3.98481 -1.82936 12.9663 +20 7562 612.654 601.496 81.3525 0.148977 -4.40474 34.7337 +21 7562 614.027 602.56 77.9354 0.209272 -4.44653 33.801 +22 7562 613.979 603.615 75.8533 0.229062 -5.02736 37.3959 +20 7564 721.703 697.026 79.7795 2.44102 -2.02594 15.7056 +21 7564 730.202 703.461 73.3718 2.42338 -1.99832 14.4937 +20 7569 310.42 287.256 243.548 -6.93684 1.63934 16.732 +21 7569 295.242 271.541 246.238 -7.12346 1.66311 16.3524 +22 7569 278.247 252.569 249.663 -6.93059 1.60673 15.0936 +20 7577 342.7 314.064 268.205 -5.00561 1.78855 13.5342 +21 7577 325.637 295.522 273.173 -5.0643 1.78939 12.87 +22 7577 306.83 273.807 279.293 -4.92423 1.73136 11.7366 +23 7577 284.736 249.788 287.982 -4.99257 1.76952 11.0901 +24 7577 259.244 221.192 297.956 -4.94516 1.76598 10.1855 +20 7584 940.726 894.273 299.747 3.82934 1.46729 8.34327 +21 7584 981.765 929.627 314.171 3.83465 1.45591 7.43364 +20 7586 1026.43 967.007 337.079 3.76822 1.48448 6.52219 +21 7586 1091.44 1024.41 361.925 3.86148 1.51508 5.7819 +20 7604 240.022 212.839 58.5846 -7.30217 -2.258 14.2578 +21 7604 215.332 187.181 49.3073 -7.52221 -2.35738 13.7676 +20 7605 198.521 170.044 70.3861 -7.75324 -1.93281 13.6101 +21 7605 171.888 140.951 62.5621 -7.59912 -1.91496 12.5278 +20 7608 188.028 159.642 106.028 -7.97648 -1.26453 13.6534 +21 7608 160.603 130.578 100.134 -8.03183 -1.30096 12.9083 +22 7608 129.675 98.2036 94.5783 -8.19054 -1.33599 12.315 +23 7608 94.6928 61.3039 89.6351 -8.28302 -1.3388 11.6079 +20 7620 225.628 196.283 70.1424 -7.02773 -1.8801 13.2075 +21 7620 199.771 169.056 62.1837 -7.16661 -1.93546 12.6187 +22 7620 170.62 137.423 53.477 -7.10226 -1.93158 11.6749 +23 7620 136.521 101.988 44.9852 -7.35782 -1.98892 11.2231 +24 7620 97.8975 60.5016 33.9361 -7.34946 -1.9954 10.3641 +20 7628 284.168 253.832 72.2818 -5.76148 -1.78077 12.7758 +21 7628 261.68 229.543 64.0086 -5.81465 -1.8193 12.0602 +20 7632 365.01 337.786 123.07 -4.82511 -0.982268 14.2364 +21 7632 350.404 321.25 118.716 -4.7748 -0.997471 13.2939 +20 7634 326.84 299.62 76.6356 -5.57909 -1.89874 14.2386 +21 7634 309.761 281.841 69.0374 -5.76776 -1.99731 13.8815 +22 7634 290.31 261.347 60.5422 -5.92086 -2.08295 13.3818 +20 7635 390.486 364.044 63.9502 -4.45044 -2.21236 14.6579 +21 7635 377.492 349.58 56.0214 -4.46587 -2.24832 13.8852 +20 7636 395.54 368.882 105.222 -4.31232 -1.36273 14.5384 +21 7636 383.314 354.115 99.823 -4.16208 -1.3435 13.2736 +20 7637 377.352 350.007 107.12 -4.5613 -1.29123 14.1733 +21 7637 363.11 334.504 101.612 -4.62777 -1.33776 13.5488 +20 7638 321.736 292.223 44.8631 -5.2386 -2.32953 13.1325 +21 7638 302.723 271.36 34.4332 -5.25513 -2.37071 12.3576 +20 7646 422.964 395.826 79.8119 -3.69337 -1.84163 14.2818 +21 7646 412.123 383.514 72.6569 -3.707 -1.88127 13.5474 +20 7647 543.999 536.798 89.1359 -4.89007 -6.24445 53.8187 +21 7647 543.986 536.897 87.118 -4.96877 -6.4966 54.6741 +20 7648 543.999 536.798 89.1359 -4.89007 -6.24445 53.8187 +21 7648 543.986 536.609 87.118 -4.77461 -6.24274 52.5377 +22 7648 543.794 536.403 86.4524 -4.77947 -6.2792 52.4375 +20 7653 431.716 404.554 85.5915 -3.51709 -1.72573 14.2694 +21 7653 421.457 392.509 79.1381 -3.49043 -1.73899 13.3889 +22 7653 409.751 378.879 72.2077 -3.47648 -1.75116 12.5541 +23 7653 396.199 363.349 65.129 -3.4888 -1.76149 11.7984 +24 7653 380.534 345.603 57.2085 -3.52186 -1.77835 11.0955 +20 7654 555.045 547.56 119.051 -3.91201 -3.86099 51.7786 +21 7654 554.664 547.648 117.854 -4.20266 -4.21068 55.2397 +22 7654 555.179 547.609 116.067 -3.8582 -4.02901 51.1925 +23 7654 555.016 547.812 115.706 -4.06689 -4.26111 53.8 +24 7654 555.291 548.081 115.027 -4.04257 -4.30768 53.7495 +25 7654 555.638 547.902 113.195 -3.74396 -4.14234 50.0992 +20 7658 545.165 526.95 44.6792 -1.89905 -3.77998 21.2787 +21 7658 543.589 524.453 37.6161 -1.85188 -3.7963 20.2545 +20 7659 546.125 539.771 68.9981 -5.36213 -8.77903 60.9922 +21 7659 546.173 539.868 66.0236 -5.39955 -9.10039 61.4645 +22 7659 546.358 539.925 63.5169 -5.2778 -9.13046 60.2537 +23 7659 546.649 539.978 62.2137 -5.06564 -8.90892 58.0993 +24 7659 547.159 540.169 61.2685 -4.79517 -8.57486 55.4471 +25 7659 547.069 540.068 59.3104 -4.79476 -8.71195 55.362 +26 7659 546.959 539.76 56.096 -4.67059 -8.7113 53.8338 +20 7662 445.029 417.495 49.8694 -3.2098 -2.39929 14.0764 +21 7662 434.89 406.657 40.4688 -3.32316 -2.51868 13.7276 +22 7662 424.15 394.214 31.8652 -3.32683 -2.52979 12.9467 +20 7667 636.121 624.147 99.3365 1.19158 -3.29803 32.3685 +21 7667 637.978 625.471 96.2393 1.22057 -3.29057 30.9898 +20 7668 636.121 624.147 99.3365 1.19158 -3.29803 32.3685 +21 7668 637.978 625.471 96.2393 1.22057 -3.29057 30.9898 +22 7668 640.672 627.259 93.2119 1.24594 -3.18937 28.8949 +23 7668 642.353 628.573 91.0285 1.2783 -3.18956 28.1256 +24 7668 644.384 630.698 88.8038 1.36682 -3.29887 28.3195 +25 7668 647.042 632.059 85.5059 1.34374 -3.13138 25.8667 +26 7668 649.334 633.854 80.9133 1.38018 -3.19038 25.0376 +20 7669 655.338 642.559 105.743 1.92431 -2.82103 30.3299 +21 7669 657.833 644.859 102.781 1.99862 -2.90116 29.873 +22 7669 660.477 647.111 100.197 2.04623 -2.91986 28.9963 +23 7669 663.265 649.438 98.0715 2.08634 -2.90513 28.0301 +24 7669 666.298 651.986 96.1086 2.12944 -2.88031 27.0798 +25 7669 669.039 654.337 93.2218 2.1731 -2.90937 26.3614 +26 7669 671.885 656.635 89.1667 2.19528 -2.9477 25.4146 +20 7670 573.822 568.206 107.9 -3.41823 -6.21275 69.0137 +21 7670 574.436 567.198 105.936 -2.60633 -4.96568 53.5424 +20 7672 593.056 584.445 57.0093 -1.02954 -7.22668 45.0113 +21 7672 595.654 584.962 52.0848 -0.698624 -6.06747 36.2502 +20 7673 591.85 584.704 69.0258 -1.33107 -7.80403 54.2329 +21 7673 592.805 585.612 66.3752 -1.25122 -7.95171 53.8836 +22 7673 593.658 586.281 64.0999 -1.15776 -7.91844 52.5355 +23 7673 594.407 586.784 62.2756 -1.06777 -7.79217 50.8449 +24 7673 595.499 587.601 60.6055 -0.956149 -7.63353 49.0686 +25 7673 596.038 588.068 58.3858 -0.911161 -7.71391 48.6238 +20 7674 679.253 655.905 79.54 1.60345 -2.1469 16.6006 +21 7674 684.428 660.201 73.4657 1.65995 -2.20358 15.9975 +22 7674 691.245 664.494 67.8129 1.64026 -2.10925 14.4886 +20 7677 610.92 601.604 49.1464 0.0784727 -7.13249 41.601 +21 7677 612.418 602.914 46.0887 0.161576 -7.16496 40.7824 +20 7678 625.061 613.144 112.088 0.698731 -2.73898 32.523 +21 7678 626.55 614.409 109.482 0.751744 -2.80386 31.9239 +22 7678 628.148 615.808 107.07 0.809165 -2.86357 31.4087 +23 7678 629.525 616.997 105.366 0.856064 -2.89371 30.9375 +20 7682 584.039 579.073 81.1241 -2.76046 -9.92202 78.0455 +21 7682 584.668 580.433 78.9111 -3.15711 -11.9152 91.516 +22 7682 586.185 580.527 76.7072 -2.21905 -9.12771 68.4993 +23 7682 586.824 580.099 75.3327 -1.81595 -7.78927 57.631 +24 7682 588.47 580.5 73.8935 -1.42138 -6.66967 48.6297 +25 7682 588.785 579.817 72.1049 -1.24439 -6.03482 43.2198 +20 7684 580.207 573.475 53.9662 -2.34222 -9.48675 57.5757 +21 7684 581.498 574.312 50.5791 -2.09749 -9.13964 53.9326 +20 7686 649.273 636.536 110.311 1.67481 -2.63763 30.4292 +21 7686 651.562 638.629 107.343 1.74449 -2.72081 29.9672 +22 7686 654.028 641.006 105.119 1.83427 -2.79398 29.7624 +20 7689 784.901 759.139 62.2492 3.6559 -2.30612 15.0442 +21 7689 797.653 770.161 54.4059 3.6751 -2.31432 14.0979 +22 7689 811.752 782.376 46.1009 3.69723 -2.31777 13.1938 +23 7689 827.409 795.872 36.8845 3.71055 -2.31592 12.2897 +24 7689 845.476 811.451 26.9107 3.72442 -2.30401 11.3909 +20 7693 760.188 735.212 99.3153 3.23948 -1.58155 15.5177 +21 7693 770.581 744.213 93.9452 3.28018 -1.60745 14.6985 +22 7693 782.013 754.369 88.6638 3.35098 -1.63591 14.0203 +20 7695 785.35 759.419 20.4874 3.64138 -3.15616 14.9461 +21 7695 797.67 770.659 10.1074 3.74088 -3.23648 14.3489 +20 7701 758.054 733.362 93.1594 3.23032 -1.73366 15.6962 +21 7701 768.28 741.992 87.5767 3.24318 -1.74249 14.7433 +22 7701 779.946 751.926 81.5822 3.26629 -1.74966 13.8318 +23 7701 792.06 763.205 75.4021 3.39728 -1.81408 13.4315 +24 7701 807.096 775.461 68.5254 3.35407 -1.77144 12.2513 +25 7701 823.751 789.186 60.8165 3.32863 -1.74111 11.213 +20 7702 770.147 746.373 101.136 3.62843 -1.62044 16.303 +21 7702 780.915 755.307 96.0248 3.59441 -1.6116 15.1352 +20 7709 828.754 807.323 63.6423 5.49391 -2.73729 18.0847 +21 7709 841.79 819.36 56.7962 5.56155 -2.7794 17.2797 +20 7711 738.871 714.405 116.857 2.83902 -1.22939 15.8412 +21 7711 747.742 722.141 112.847 2.89934 -1.25906 15.1393 +22 7711 757.582 730.276 108.919 2.91189 -1.25774 14.194 +23 7711 768.903 739.291 104.122 2.89046 -1.24679 13.0885 +24 7711 781.051 749.56 100.291 2.92519 -1.23773 12.3075 +20 7713 786.615 762.075 72.7817 3.87554 -2.19047 15.7936 +21 7713 798.395 771.876 66.3545 3.82497 -2.15721 14.6151 +22 7713 810.354 783.047 58.6194 3.94983 -2.24711 14.1934 +20 7715 701.274 676.374 63.6424 1.97853 -2.356 15.5656 +21 7715 706.506 682.09 55.5533 2.1328 -2.58057 15.8736 +22 7715 714.241 688.216 47.4206 2.16058 -2.58888 14.8922 +23 7715 722.04 695.725 39.1165 2.29593 -2.72981 14.7278 +20 7717 910.171 884.329 66.3411 6.24853 -2.21399 14.9979 +21 7717 930.734 903.362 58.6897 6.30279 -2.24038 14.1596 +20 7727 914.834 889.194 39.2289 6.39524 -2.79933 15.1156 +21 7727 935.192 908.658 30.2808 6.59213 -2.88627 14.6069 +22 7727 957.338 929.529 20.7923 6.71744 -2.93711 13.9367 +23 7727 982.659 952.642 9.8666 6.67668 -2.91669 12.9121 +20 7731 967.502 939.84 20.0822 6.95058 -2.96654 14.0109 +21 7731 994.108 964.041 8.47215 6.86996 -2.93668 12.8903 +20 7733 965.852 937.784 32.6642 6.81846 -2.68284 13.8082 +21 7733 991.943 962.134 22.24 6.89032 -2.71397 13.0017 +20 7741 924.801 900.357 64.4572 6.92744 -2.38202 15.8558 +21 7741 946.103 918.731 56.0941 6.60457 -2.29138 14.16 +20 7750 989.912 962.121 65.8509 7.35138 -2.06813 13.9457 +21 7750 1017.82 988.058 57.7464 7.36862 -2.07756 13.023 +22 7750 1049.25 1017.54 49.0259 7.44664 -2.09715 12.2199 +23 7750 1085.49 1051.32 38.9328 7.48235 -2.10544 11.3437 +24 7750 1127.79 1090.7 27.7186 7.50584 -2.10209 10.4505 +25 7750 1177.14 1136.89 13.793 7.57369 -2.12247 9.62804 +20 7752 1021.71 992.332 86.4128 7.53588 -1.58051 13.1928 +21 7752 1052.52 1021.78 79.3304 7.73861 -1.63386 12.6053 +22 7752 1086.3 1054.85 72.6681 8.14264 -1.71116 12.3238 +20 7757 1083.76 1045.82 87.2784 6.7136 -1.21154 10.2152 +21 7757 1130.87 1090.58 78.79 6.95118 -1.25426 9.62107 +20 7762 980.454 952.78 71.4941 7.19903 -1.96739 14.005 +21 7762 1007.41 978.06 63.6067 7.28018 -1.99907 13.2031 +22 7762 1038.04 1006.6 55.072 7.32098 -2.01242 12.3282 +23 7762 1073.15 1039.36 45.5398 7.37134 -2.02438 11.4729 +20 7765 1011.65 983.743 117.915 7.73985 -1.05753 13.889 +21 7765 1040.62 1011.62 114.104 7.98414 -1.08818 13.3644 +22 7765 1073.72 1042.4 110.087 7.96086 -1.07653 12.3752 +23 7765 1111.62 1077.97 105.735 8.0131 -1.07123 11.516 +20 7766 1001.75 973.79 56.7803 7.53381 -2.22971 13.8603 +21 7766 1030.42 1000.55 47.6953 7.56899 -2.25092 12.9765 +20 7776 107.04 95.4188 157.368 -23.2275 -0.715811 33.351 +21 7776 94.5872 82.7393 156.077 -23.3474 -0.760641 32.7125 +22 7776 81.3239 68.7486 154.858 -22.5633 -0.768679 30.8201 +23 7776 66.7935 53.9287 154.816 -22.6624 -0.753152 30.1268 +20 7777 132.227 122.479 180.968 -26.3013 0.447105 39.7571 +21 7777 122.381 112.034 179.854 -25.29 0.363398 37.4559 +22 7777 111.895 99.7651 179.323 -22.0378 0.286449 31.9515 +20 7782 68.1822 55.0439 131.222 -22.1338 -1.70211 29.4996 +21 7782 52.6267 41.7868 128.836 -27.5977 -2.18123 35.7544 +22 7782 37.8892 26.5263 127.247 -27.024 -2.15596 34.1086 +20 7785 77.927 65.8609 151.786 -23.667 -0.937878 32.1211 +21 7785 63.922 51.8751 149.768 -24.3289 -1.02936 32.172 +22 7785 49.0635 37.0712 148.289 -25.1053 -1.1003 32.3186 +20 7789 74.1594 58.2743 151.997 -18.1044 -0.705283 24.3986 +21 7789 54.8979 41.7472 150.251 -22.6556 -0.923253 29.4717 +20 7790 74.1594 58.2743 151.997 -18.1044 -0.705283 24.3986 +21 7790 54.8979 41.7472 150.251 -22.6556 -0.923253 29.4717 +20 7794 209.057 162.301 231.219 -4.60108 0.670516 8.28923 +21 7794 163.068 110.961 237.187 -4.60262 0.663172 7.43792 +20 7796 274.446 247.958 163.069 -6.79579 -0.19844 14.6321 +21 7796 254.194 225.175 162.944 -6.57784 -0.183437 13.3557 +20 7797 139.359 128.394 199.95 -23.0349 1.32743 35.3478 +21 7797 127.969 116.7 200.261 -22.9564 1.30642 34.3942 +20 7800 154.453 100.574 251.761 -4.53719 0.786666 7.19339 +21 7800 91.9192 29.8875 261.532 -4.4824 0.767887 6.24801 +20 7805 369.495 341.934 133.478 -4.67879 -0.767429 14.0626 +21 7805 354.84 325.764 129.625 -4.70568 -0.798613 13.3297 +22 7805 338.185 307.252 126.073 -4.7123 -0.812337 12.5292 +23 7805 319.499 285.978 122.679 -4.64791 -0.803995 11.5619 +20 7806 279.244 254.187 171.641 -7.08083 -0.0260103 15.4673 +21 7806 260.62 234.015 170.443 -7.04495 -0.0486742 14.5676 +20 7809 313.637 289.696 227.68 -6.63944 1.23011 16.1887 +21 7809 297.661 273.693 229.923 -6.98988 1.27897 16.1702 +20 7814 523.357 517.415 151.95 -7.79234 -1.88961 65.2241 +21 7814 523.174 517.306 150.64 -7.90762 -2.03343 66.049 +22 7814 523.104 517.129 149.787 -7.77235 -2.07368 64.8663 +23 7814 523.003 516.898 149.546 -7.61518 -2.05067 63.4805 +20 7816 533.742 514.752 234.956 -2.14457 1.75662 20.4094 +21 7816 531.452 511.792 236.731 -2.13409 1.74527 19.7142 +22 7816 528.853 508.273 239.255 -2.10651 1.73312 18.8327 +23 7816 526.2 504.449 242.689 -2.05854 1.72457 17.8182 +24 7816 523.34 500.641 246.51 -2.04027 1.74297 17.0743 +25 7816 519.542 495.345 250.085 -1.99832 1.71446 16.0176 +26 7816 515.555 489.424 252.841 -1.93243 1.64427 14.8325 +20 7819 467.683 446.59 242.743 -3.61296 1.77977 18.3744 +21 7819 461.885 440.272 245.147 -3.67032 1.79678 17.9332 +22 7819 455.564 432.77 248.411 -3.629 1.78053 17.0035 +20 7820 510.501 503.1 192.852 -7.18949 1.45144 52.3681 +21 7820 510.318 502.9 192.506 -7.18582 1.42296 52.2448 +22 7820 510.092 502.383 192.688 -6.93069 1.38197 50.2753 +23 7820 507.21 502.094 192.373 -10.7459 2.0493 75.756 +24 7820 506.911 499.557 193.27 -7.49789 1.4913 52.7043 +20 7823 659.747 645.665 215.364 1.91446 1.62159 27.5241 +21 7823 662.651 648.057 215.913 1.95417 1.58489 26.558 +22 7823 665.403 650.554 216.891 2.02001 1.5929 26.0997 +23 7823 668.895 653.154 218.511 2.02477 1.55801 24.6217 +24 7823 672.303 656.249 220.435 2.09939 1.59205 24.1425 +25 7823 675.64 658.906 221.995 2.12115 1.5774 23.161 +20 7826 679.922 673.302 146.124 5.70894 -2.16872 58.5422 +21 7826 682.496 675.3 144.867 5.44395 -2.08892 53.8548 +22 7826 684.705 677.347 143.933 5.48589 -2.11133 52.6745 +20 7827 562.598 557.101 169.609 -4.58919 -0.317066 70.5103 +21 7827 562.901 557.591 168.539 -4.71907 -0.436439 72.9778 +22 7827 563.457 557.914 168.031 -4.46725 -0.46739 69.9164 +23 7827 563.926 558.267 168.038 -4.33139 -0.457133 68.4867 +24 7827 564.585 558.927 168.298 -4.2697 -0.432546 68.5007 +25 7827 564.741 559.259 167.861 -4.39083 -0.489198 70.6893 +26 7827 565.225 559.55 166.419 -4.19701 -0.609148 68.3055 +20 7828 655.801 642.594 210.401 1.88073 1.52711 29.3463 +21 7828 658.241 645.047 210.618 1.98186 1.53737 29.374 +22 7828 660.938 647.148 211.345 2.00136 1.49934 28.1061 +23 7828 663.921 649.841 212.581 2.07386 1.51556 27.5261 +20 7830 563.829 557.239 185.524 -3.7277 1.03277 58.8155 +21 7830 564.182 557.441 184.739 -3.61609 0.947128 57.4985 +22 7830 564.448 557.584 184.565 -3.5305 0.916557 56.4687 +23 7830 564.917 557.966 185.012 -3.44987 0.939516 55.7591 +24 7830 565.021 558.069 186.028 -3.4413 1.01793 55.7508 +25 7830 565.59 558.883 185.84 -3.5215 1.04008 57.7879 +20 7835 695.993 693.224 163.131 16.7617 -1.88549 139.924 +21 7835 698.353 696.621 161.991 27.5409 -3.36939 223.797 +20 7836 732.823 709.81 168.996 2.87707 -0.0900457 16.8412 +21 7836 741.111 716.733 168.053 2.89867 -0.10578 15.8987 +22 7836 750.272 724.433 167.379 2.9252 -0.113823 14.9996 +23 7836 760.196 732.677 167.153 2.94036 -0.111284 14.0841 +20 7841 826.639 821.875 129.584 24.4772 -4.87904 81.3583 +21 7841 830.37 825.744 128.333 25.6347 -5.16853 83.7656 +22 7841 834.067 829.404 127.45 25.8629 -5.23047 83.1198 +23 7841 837.781 833.34 126.715 27.6011 -5.58002 87.2627 +24 7841 841.911 837.105 126.511 25.9645 -5.17863 80.629 +25 7841 845.634 840.772 125.529 26.0853 -5.22922 79.727 +20 7842 762.909 743.627 177.947 4.27197 0.14189 20.1003 +21 7842 768.715 747.259 177.23 3.9844 0.109542 18.0634 +20 7844 798.247 763.946 219.98 2.95484 0.737998 11.2993 +21 7844 815.727 778.588 223.926 2.98181 0.738659 10.4356 +20 7848 735.752 712.34 134.083 2.89519 -0.889502 16.5539 +21 7848 744.504 719.581 130.792 2.90841 -0.906548 15.5511 +22 7848 754.077 727.584 128.19 2.93009 -0.905552 14.6292 +20 7856 952.304 926.195 147.315 7.05134 -0.525427 14.8443 +21 7856 976.008 948.19 144.789 7.076 -0.541934 13.9327 +22 7856 1002.84 973.027 142.349 7.08503 -0.549543 12.9985 +23 7856 1033.44 1001.31 139.735 7.08611 -0.553664 12.0621 +20 7858 960.635 934.413 148.06 7.19167 -0.507905 14.7804 +21 7858 985.035 957.678 145.483 7.37219 -0.537405 14.1668 +22 7858 1012.65 982.759 143.166 7.24435 -0.533556 12.9676 +23 7858 1044.63 1011.78 140.45 7.11296 -0.52976 11.7963 +24 7858 1081.63 1046.23 137.935 7.16285 -0.52983 10.948 +25 7858 1125.63 1086.36 133.973 7.05838 -0.531785 9.86858 +20 7860 957.039 930.783 157.861 7.10874 -0.306729 14.7612 +21 7860 981.131 953.262 156.193 7.16189 -0.321134 13.9074 +22 7860 1008.55 978.078 155.042 7.03257 -0.313948 12.7176 +20 7861 951.95 924.905 179.746 6.80041 0.136883 14.3309 +21 7861 977.028 947.469 179.181 6.67756 0.114977 13.1116 +20 7863 863.334 835.695 190.686 4.93194 0.346551 14.0226 +21 7863 879.939 851.83 191.205 5.16688 0.350677 13.7884 +20 7873 985.388 949.283 199.184 5.59136 0.391727 10.7346 +21 7873 1021.06 981.934 201.062 5.64966 0.387276 9.90635 +20 7879 996.838 959.35 201.377 5.54914 0.408696 10.3386 +21 7879 1034.28 993.784 202.931 5.63383 0.398969 9.57109 +20 7889 1134.97 1094.9 138.818 7.04332 -0.456271 9.67251 +21 7889 1188.66 1146.96 135.128 7.45871 -0.485906 9.29319 +20 7898 275.988 235.029 305.173 -4.37458 1.73528 9.46251 +21 7898 243.772 198.629 317.328 -4.35242 1.71907 8.58541 +22 7898 203.835 153.949 333.708 -4.36862 1.73199 7.76913 +20 7899 192.16 141.386 320.5 -4.41582 1.562 7.63341 +21 7899 139.708 82.6526 338.549 -4.42347 1.55995 6.793 +20 7900 234.667 188.355 321.422 -4.34813 1.72314 8.36864 +21 7900 193.048 141.632 337.292 -4.35132 1.71789 7.53795 +22 7900 140.696 83.2872 358.03 -4.38699 1.73263 6.75117 +20 7922 418.538 383.608 289.384 -2.9375 1.79197 11.0957 +21 7922 403.551 365.701 298.182 -2.92356 1.77859 10.2397 +22 7922 385.981 344.367 309.329 -2.88591 1.7616 9.3135 +23 7922 364.689 319.351 323.602 -2.90116 1.78602 8.54859 +20 7927 693.817 662.742 271.98 1.45645 1.71346 12.4722 +21 7927 702.471 667.813 279.135 1.44001 1.6472 11.1828 +20 7933 616.4 573.078 300.943 0.0848188 1.58818 8.94633 +21 7933 618.915 572.945 310.773 0.109323 1.61153 8.43089 +20 7934 711.371 683.297 255.965 1.94802 1.59022 13.8056 +21 7934 719.782 690.073 260.304 1.99287 1.58112 13.0456 +20 7939 773.172 735.034 286.034 2.3044 1.59408 10.1625 +21 7939 789.867 748.26 295.963 2.32781 1.58937 9.31521 +22 7939 810.444 764.411 308.291 2.34406 1.58037 8.41936 +20 7942 716.602 683.961 275.631 1.76154 1.69135 11.874 +21 7942 726.134 690.658 282.601 1.76509 1.66172 10.925 +20 7950 839.409 802.747 261.292 3.36762 1.29575 10.5715 +21 7950 861.397 822.224 269.666 3.45328 1.32752 9.89399 +20 7953 1081.08 1036.4 253.712 5.66818 0.971997 8.67363 +21 7953 1136.9 1087.53 261.941 5.73842 0.969433 7.85169 +22 7953 1206.26 1151.04 273.402 5.8035 0.97792 7.0176 +20 7955 1076.85 1025.01 307.198 4.8418 1.39199 7.4761 +21 7955 1143.14 1083.04 325.095 4.76921 1.36075 6.44918 +20 7960 1037.08 996.349 271.886 5.63852 1.30614 9.51636 +21 7960 1083.28 1038.09 281.02 5.63096 1.28573 8.57668 +21 7980 610.223 593.904 224.554 0.0218327 1.70172 23.7498 +22 7980 611.181 594.392 226.257 0.0518846 1.7086 23.0853 +21 7992 1111.43 1064.54 259.663 5.74947 0.99449 8.26602 +22 7992 1174.82 1121.93 270.292 5.74127 0.989664 7.32856 +21 7997 111.383 79.6231 42.367 -8.42561 -2.20691 12.2033 +22 7997 76.6353 42.7882 32.2301 -8.45745 -2.23169 11.4507 +21 8011 133.144 103.675 80.9338 -8.68395 -1.67549 13.152 +22 8011 100.547 69.0151 73.8323 -8.67099 -1.68683 12.2914 +23 8011 62.6024 29.1796 67.1442 -8.79035 -1.6989 11.5961 +21 8028 182.71 152.712 125.436 -7.6432 -0.849076 12.9199 +22 8028 152.873 121.536 121.496 -7.82818 -0.880334 12.3681 +21 8029 164.775 133.939 43.2001 -7.74791 -2.2585 12.5688 +22 8029 133.526 99.2209 32.8046 -7.45383 -2.19292 11.298 +23 8029 95.5464 58.5469 23.101 -7.46232 -2.17408 10.4751 +21 8032 181.443 152.077 71.6878 -7.83094 -1.85049 13.1981 +22 8032 152.045 120.976 63.4732 -7.90977 -1.89104 12.4744 +21 8035 396.138 365.551 65.9448 -3.74807 -1.87752 12.6715 +22 8035 381.887 349.298 57.7997 -3.75256 -1.89636 11.8926 +21 8040 350.217 321.061 124.048 -4.77801 -0.899181 13.2933 +22 8040 333.361 307.061 120.172 -5.64103 -1.07598 14.7366 +21 8046 323.659 293.557 61.6795 -5.1017 -1.98384 12.8754 +22 8046 304.112 271.915 53.0942 -5.09575 -1.99795 12.0374 +21 8047 292.224 261.452 44.5097 -5.53929 -2.24033 12.5949 +22 8047 270.334 242.933 34.4135 -6.64992 -2.71389 14.1445 +21 8048 350.138 320.317 56.632 -4.6728 -2.09344 12.9966 +22 8048 334.071 302.445 47.8267 -4.67893 -2.12348 12.2547 +23 8048 313.521 279.67 39.4025 -4.69757 -2.11762 11.4494 +24 8048 291.917 256.677 28.5836 -4.8416 -2.19901 10.9979 +21 8049 366.262 337.185 112.169 -4.49456 -1.12107 13.3294 +22 8049 350.902 319.657 107.25 -4.44667 -1.12783 12.4042 +23 8049 333.259 299.354 102.814 -4.37742 -1.10964 11.4313 +24 8049 311.91 276.148 97.9829 -4.47072 -1.12457 10.8376 +25 8049 287.767 250.048 90.9123 -4.58267 -1.16694 10.2755 +26 8049 259.522 218.628 81.4718 -4.59779 -1.20032 9.47751 +21 8051 346.825 318.75 89.8423 -5.02668 -1.5882 13.8046 +22 8051 329.846 298.485 83.0733 -4.79093 -1.53776 12.3585 +23 8051 310.422 277.296 76.1488 -4.85057 -1.56809 11.6999 +21 8056 550.136 542.847 48.435 -4.37878 -9.16824 53.1689 +22 8056 549.504 542.989 44.0445 -4.9512 -10.6196 59.4866 +21 8060 417.969 389.527 87.1726 -3.61835 -1.61817 13.6269 +22 8060 406.488 376.484 80.7727 -3.63551 -1.6485 12.9174 +21 8065 483.015 472.206 68.1986 -6.28838 -5.20067 35.8556 +22 8065 480.908 470.096 65.5557 -6.39148 -5.33066 35.8465 +21 8067 426.95 398.879 90.056 -3.49425 -1.58435 13.8067 +22 8067 416.394 386.169 83.9295 -3.43293 -1.58036 12.8231 +21 8069 553.98 547.975 78.2941 -4.97176 -8.45869 64.5439 +22 8069 554.215 548.14 76.34 -4.89349 -8.53374 63.7981 +23 8069 554.413 548.29 74.99 -4.83796 -8.58557 63.3002 +24 8069 554.864 548.618 73.7123 -4.70334 -8.52539 62.0464 +25 8069 554.876 548.589 71.9697 -4.6721 -8.6194 61.6471 +26 8069 554.93 548.451 68.7078 -4.52848 -8.63324 59.8122 +21 8070 547.569 524.099 23.6789 -1.41873 -3.41409 16.5135 +22 8070 544.76 519.135 13.8719 -1.35833 -3.3326 15.125 +21 8077 693.38 668.023 45.721 1.77567 -2.69321 15.2852 +22 8077 699.184 672.701 37.025 1.81783 -2.75498 14.6348 +23 8077 707.142 676.758 28.9165 1.72513 -2.54462 12.7558 +21 8078 672.568 646.839 49.068 1.31545 -2.58431 15.0637 +22 8078 677.823 650.734 40.6246 1.35359 -2.62195 14.3072 +21 8083 603.487 596.313 39.8228 -0.454657 -9.96056 54.0243 +22 8083 604.341 597.143 37.545 -0.38942 -10.0971 53.8429 +21 8085 568.327 560.294 60.5429 -2.75737 -7.51062 48.2517 +22 8085 568.708 561.478 58.2283 -3.03484 -8.51553 53.6029 +23 8085 568.963 561.811 56.4005 -3.04942 -8.74738 54.1982 +24 8085 569.702 562.265 54.7058 -2.8788 -8.53359 52.1151 +25 8085 569.926 562.336 52.3256 -2.80493 -8.53007 51.0649 +21 8087 630.196 617.189 96.3919 0.852258 -3.1578 29.7987 +22 8087 631.884 618.02 93.6229 0.864978 -3.06981 27.956 +23 8087 633.711 619.314 91.2861 0.901075 -3.04317 26.9194 +24 8087 635.618 620.764 88.8717 0.9423 -3.03683 26.0911 +21 8092 651.562 638.629 107.343 1.74449 -2.72081 29.9672 +22 8092 654.028 641.006 105.119 1.83427 -2.79398 29.7624 +21 8099 697.887 673.169 72.6857 1.91942 -2.17672 15.6794 +22 8099 704.404 678.306 66.3355 1.95209 -2.19235 14.8506 +21 8101 770.581 744.213 93.9452 3.28018 -1.60745 14.6985 +22 8101 782.013 754.369 88.6638 3.35098 -1.63591 14.0203 +23 8101 794.985 765.161 82.9167 3.33964 -1.61983 12.9954 +21 8102 729.097 702.976 105.812 2.45813 -1.37864 14.8375 +22 8102 738.037 710.335 101.093 2.49127 -1.39149 13.9911 +21 8108 723.699 698.251 75.9068 2.4092 -2.04631 15.2298 +22 8108 732.651 705.319 69.8734 2.41905 -2.02381 14.1799 +21 8113 797.672 770.518 45.2149 3.72129 -2.525 14.2737 +22 8113 811.394 782.541 36.3054 3.75754 -2.54212 13.4328 +21 8114 728.873 702.518 86.4484 2.43174 -1.76103 14.7057 +22 8114 738.296 709.738 81.0624 2.42137 -1.72648 13.5711 +23 8114 749.435 718.174 75.3271 2.40345 -1.67578 12.398 +21 8115 741.466 715.153 97.5453 2.69277 -1.53737 14.7296 +22 8115 750.909 723.848 92.1269 2.8057 -1.60238 14.322 +23 8115 762.246 732.961 86.9089 2.80066 -1.57646 13.2349 +24 8115 774.573 742.469 81.1149 2.76096 -1.53495 12.0726 +25 8115 788.337 753.726 74.1028 2.77454 -1.53257 11.1979 +26 8115 804.744 766.757 64.454 2.76003 -1.53284 10.203 +21 8122 788.826 762.39 75.9324 3.64251 -1.96935 14.6609 +22 8122 799.942 774.453 69.6028 4.01217 -2.17595 15.2059 +23 8122 813.348 785.973 62.2229 3.99884 -2.17086 14.1584 +21 8123 788.826 762.39 75.9324 3.64251 -1.96935 14.6609 +22 8123 799.942 774.453 69.6028 4.01217 -2.17595 15.2059 +23 8123 813.348 785.973 62.2229 3.99884 -2.17086 14.1584 +21 8135 934.352 907.076 65.0924 6.39626 -2.12219 14.2095 +22 8135 957.902 928.714 57.624 6.41052 -2.12057 13.2784 +21 8136 965.869 938.176 43.6231 6.91106 -2.50659 13.9951 +22 8136 991.455 961.345 34.082 6.81269 -2.47557 12.8716 +23 8136 1021.19 988.686 23.6746 6.80179 -2.46502 11.9226 +24 8136 1054.95 1020.46 12.4817 6.93686 -2.49778 11.2379 +21 8140 974.94 946.293 23.4122 6.85129 -2.8022 13.5296 +22 8140 1002.14 971.242 12.8064 6.82393 -2.78196 12.5418 +21 8141 1019.9 990.146 33.9133 7.40912 -2.50874 13.0282 +22 8141 1051.43 1019.58 23.5773 7.45185 -2.51747 12.1683 +23 8141 1087.39 1053.11 11.6714 7.48829 -2.52598 11.3076 +21 8143 1041.4 1010.67 31.2524 7.54882 -2.47527 12.6128 +22 8143 1076.2 1043.01 20.1706 7.55104 -2.47066 11.6756 +21 8146 1004.43 974.639 81.031 7.11898 -1.65543 13.0082 +22 8146 1033.61 1003.58 73.7192 7.58633 -1.77355 12.9085 +23 8146 1066.63 1033.73 65.6379 7.46115 -1.75017 11.7782 +24 8146 1107.22 1070.42 56.7792 7.26467 -1.69443 10.5328 +25 8146 1153 1113.58 45.787 7.40487 -1.73139 9.83155 +26 8146 1206.09 1164.63 31.4748 7.72782 -1.8315 9.3472 +21 8153 1024.08 995.289 83.2518 7.73483 -1.67197 13.4638 +22 8153 1056.08 1024.76 76.5029 7.65975 -1.65285 12.3776 +23 8153 1093.44 1059.59 68.7413 7.67906 -1.65224 11.4506 +24 8153 1137.41 1099.82 59.6822 7.54329 -1.6173 10.3113 +25 8153 1186.94 1147.21 49.2404 7.80526 -1.67104 9.75395 +21 8169 127.9 115.816 186.645 -21.4104 0.61303 32.0733 +22 8169 115.618 103.927 186.901 -22.6953 0.64541 33.1528 +21 8172 105.199 95.6545 173.734 -28.3856 0.0495495 40.6083 +22 8172 94.9025 86.2225 173.317 -31.8486 0.0286804 44.6511 +21 8173 123.545 111.455 196.582 -21.5918 1.05414 32.0553 +22 8173 110.486 99.3416 199.481 -24.0541 1.28337 34.7764 +21 8180 260.62 234.015 170.443 -7.04495 -0.0486742 14.5676 +22 8180 239.705 211.107 169.673 -6.94672 -0.059746 13.5522 +21 8189 366.527 340.733 250.552 -5.06099 1.618 15.0256 +22 8189 352.268 326.01 254.433 -5.26326 1.66882 14.7601 +21 8192 329.38 303.904 200.405 -5.90744 0.580904 15.2133 +22 8192 312.408 285.1 202.191 -5.84502 0.577066 14.1928 +23 8192 296.274 266.237 203.907 -5.60241 0.555314 12.9031 +24 8192 274.89 245.303 208.036 -6.07585 0.638724 13.0994 +25 8192 252.039 219.997 210.242 -5.99335 0.626753 12.0956 +26 8192 225.827 191.506 211.442 -6.00572 0.603926 11.2926 +21 8195 374.415 363.283 221.803 -11.347 2.36208 34.8182 +22 8195 368.081 362.036 222.966 -21.455 4.45238 64.1076 +23 8195 363.724 358.44 226.043 -24.9882 5.4065 73.3415 +24 8195 363.763 353.256 230.76 -12.5651 2.96014 36.8849 +21 8199 525.679 505.085 241.897 -2.18781 1.80082 18.8196 +22 8199 523.068 501.048 244.859 -2.10981 1.75645 17.6007 +23 8199 520.091 497.029 248.927 -2.08379 1.77181 16.8052 +24 8199 516.343 492.312 253.249 -2.08357 1.79698 16.1279 +21 8203 576.044 572.242 167.539 -4.73594 -0.750976 101.958 +22 8203 576.687 572.939 166.806 -4.71102 -0.866782 103.405 +23 8203 577.5 573.742 166.996 -4.58227 -0.837253 103.13 +21 8205 616.594 607.05 205.443 0.395923 1.83431 40.6121 +22 8205 617.658 608.152 205.845 0.457649 1.86426 40.7732 +23 8205 619.031 609.228 206.811 0.519002 1.86068 39.5369 +24 8205 620.592 610.77 207.942 0.603345 1.9188 39.4573 +21 8206 564.627 551.925 217.246 -1.90023 1.87736 30.5143 +22 8206 564.729 551.036 218.166 -1.75859 1.77749 28.3042 +23 8206 564.534 550.839 219.78 -1.76591 1.84047 28.2992 +21 8208 627.031 620.373 176.893 1.40951 0.325845 58.209 +22 8208 628.324 621.626 176.633 1.50484 0.30303 57.8653 +23 8208 629.795 622.948 176.667 1.58756 0.299166 56.6066 +24 8208 631.341 624.381 177.14 1.68106 0.330811 55.6858 +21 8209 613.549 607.539 182.429 0.356604 0.855903 64.4967 +22 8209 611.523 605.554 182.402 0.17673 0.859144 64.9226 +21 8210 627.868 621.275 190.95 1.49161 1.4743 58.7845 +22 8210 629.244 622.295 190.799 1.52171 1.38725 55.7792 +21 8217 738.409 714.074 142.906 2.84405 -0.661026 15.9262 +22 8217 747.451 721.565 140.759 2.86135 -0.665989 14.9724 +23 8217 757.428 729.837 138.56 2.87875 -0.667651 14.0471 +24 8217 768.586 739.388 136.774 2.92553 -0.663743 13.2737 +21 8218 793.933 778.954 181.261 6.61151 0.301485 25.8738 +22 8218 801.933 786.301 181.434 6.61038 0.294818 24.7936 +23 8218 810.544 794.322 182.154 6.65533 0.307951 23.8927 +24 8218 819.941 802.765 182.607 6.57928 0.305013 22.5647 +25 8218 830.021 811.707 182.765 6.46607 0.290696 21.1624 +26 8218 840.705 821.209 181.664 6.36864 0.242745 19.8802 +21 8227 707.273 683.575 227.821 2.21482 1.24591 16.3547 +22 8227 713.995 689.518 229.826 2.2919 1.25028 15.8346 +23 8227 721.417 695.628 232.739 2.32987 1.24733 15.0288 +21 8228 723.454 696.841 233.005 2.29881 1.21406 14.5633 +22 8228 732.536 703.823 236.529 2.30059 1.19121 13.4982 +21 8229 768.939 730.407 236.354 2.22177 0.885196 10.0583 +22 8229 786.113 744.157 241.485 2.26038 0.87867 9.23769 +21 8230 839.108 834.195 130.096 25.0986 -4.67512 78.892 +22 8230 843.082 838.194 129.23 25.6593 -4.79333 79.2821 +21 8231 839.108 834.195 130.096 25.0986 -4.67512 78.892 +22 8231 843.082 838.194 129.23 25.6593 -4.79333 79.2821 +23 8231 847.045 842.402 128.73 27.4726 -5.10432 83.4683 +24 8231 851.154 846.455 128.418 27.6173 -5.07955 82.4806 +21 8235 874.289 845.33 181.264 4.91026 0.155986 13.3832 +22 8235 892.346 866.614 181.364 5.90307 0.177652 15.0618 +21 8242 939.165 907.863 194.266 5.65606 0.367432 12.3816 +22 8242 966.06 932.304 195.878 5.67297 0.366378 11.4818 +21 8246 977.569 949.472 139.165 7.0354 -0.644042 13.7939 +22 8246 1004.65 974.77 136.409 7.10195 -0.655121 12.9699 +23 8246 1034.99 1003.49 132.837 7.25445 -0.682373 12.3037 +21 8247 1040.32 1002.19 187.215 6.06698 0.202258 10.1623 +22 8247 1082.59 1041.64 188.29 6.20484 0.202475 9.46459 +23 8247 1134.38 1088.59 188.963 6.15539 0.18893 8.46252 +21 8251 1046.43 1017.2 151.461 8.02824 -0.393137 13.2595 +22 8251 1079.73 1048.48 149.801 8.08036 -0.396191 12.4003 +21 8253 1007.28 978.127 128.85 7.32897 -0.810884 13.2962 +22 8253 1037.24 1006.17 125.056 7.39379 -0.826332 12.474 +23 8253 1071.81 1038.42 120.81 7.43704 -0.837333 11.6087 +21 8254 1049.77 1020.48 127.993 8.07495 -0.822912 13.2355 +22 8254 1083.41 1052.58 124.514 8.25647 -0.842277 12.5722 +23 8254 1121.61 1088.16 120.117 8.22051 -0.846638 11.5835 +24 8254 1166.54 1130.6 115.957 8.32454 -0.850374 10.7839 +25 8254 1219.38 1180.11 111.13 8.34201 -0.844345 9.87021 +21 8269 189.203 138.985 252.272 -4.49632 0.849487 7.71789 +22 8269 136.783 80.1281 261.809 -4.48244 0.843392 6.84097 +21 8273 248.994 205.172 270.149 -4.41971 1.19262 8.84439 +22 8273 211.764 167.005 278.372 -4.77384 1.26629 8.65899 +21 8274 324.643 300.099 255.141 -6.23552 1.8009 15.7912 +22 8274 308.868 281.882 259.835 -5.98524 1.73136 14.3622 +23 8274 290.789 262.022 265.981 -5.95234 1.73894 13.4731 +21 8275 411.02 376.275 282.157 -3.06941 1.68982 11.1549 +22 8275 395.243 358.146 291.144 -3.10324 1.71281 10.4477 +23 8275 377.336 336.71 302.322 -3.07048 1.71184 9.54024 +24 8275 356.037 311.226 315.397 -3.039 1.70867 8.64914 +25 8275 329.9 281.197 330.417 -3.0844 1.73778 7.95795 +21 8279 394.495 356.227 297.179 -3.01879 1.74512 10.128 +22 8279 375.4 333.793 308.631 -3.02302 1.7529 9.31512 +23 8279 352.805 306.759 323.13 -2.9952 1.75306 8.41718 +24 8279 325.06 273.771 340.761 -2.97954 1.75847 7.55661 +21 8283 345.626 299.672 324.441 -3.08514 1.77191 8.4341 +22 8283 316.289 264.714 341.899 -3.05437 1.76058 7.51471 +21 8289 427.877 392.801 284.924 -2.78226 1.71623 11.0495 +22 8289 413.47 375.907 294.229 -2.80408 1.73567 10.318 +21 8293 554.724 516.593 290.71 -0.77246 1.66022 10.1642 +22 8293 551.363 509.68 301.338 -0.749953 1.65573 9.29819 +21 8294 554.724 516.593 290.71 -0.77246 1.66022 10.1642 +22 8294 551.363 509.68 301.338 -0.749953 1.65573 9.29819 +23 8294 547.154 499.713 315.09 -0.706584 1.61048 8.16963 +21 8295 463.816 439.222 253.549 -3.18314 1.76244 15.7589 +22 8295 456.543 431.559 257.678 -3.28983 1.8237 15.513 +21 8297 649.631 614.883 279.087 0.619455 1.64221 11.1539 +22 8297 654.337 616.757 287.843 0.640039 1.64362 10.3135 +23 8297 661.43 621.069 298.539 0.690329 1.67269 9.60263 +24 8297 667.421 622.368 311.397 0.689856 1.65176 8.60246 +25 8297 675.569 625.892 326.637 0.713756 1.66285 7.80195 +21 8298 636.118 590.322 314.036 0.311514 1.65598 8.46322 +22 8298 640.213 589.715 329.406 0.326065 1.66527 7.67513 +21 8299 616.09 589.454 255.711 0.1317 1.67096 14.551 +22 8299 617.223 587.825 260.938 0.140033 1.60944 13.1837 +23 8299 619.871 590.662 266.935 0.189636 1.73016 13.2691 +21 8304 784.629 741.986 303.335 2.20527 1.64362 9.08889 +22 8304 802.735 757.171 315.825 2.27734 1.68547 8.50618 +21 8305 700.979 673.519 259.299 1.78829 1.69098 14.1142 +22 8305 708.98 679.073 264.731 1.78568 1.65019 12.9594 +23 8305 717.457 685.407 272.336 1.80832 1.66726 12.0926 +24 8305 727.5 692.806 281.091 1.82603 1.67579 11.1713 +25 8305 738.003 699.853 291.826 1.80851 1.67515 10.1594 +21 8308 890.616 850.818 275.065 3.79342 1.37954 9.73861 +22 8308 920.545 876.452 285.03 3.78852 1.36656 8.78999 +21 8311 892.902 851.071 252.425 3.63841 1.02177 9.26529 +22 8311 924.897 878.047 260.518 3.61543 1.00508 8.27261 +23 8311 964.18 911.994 270.869 3.65014 1.00887 7.42685 +24 8311 1014.12 954.561 284.351 3.64862 1.00556 6.50735 +25 8311 1078.78 1009.75 300.177 3.65098 0.99069 5.61421 +21 8313 881.312 839.125 292.36 3.46012 1.52162 9.18707 +22 8313 911.557 865.138 304.695 3.49461 1.52562 8.34939 +21 8314 904.731 864.294 257.241 3.92102 1.12099 9.58483 +22 8314 937.288 892.364 264.81 3.91867 1.09953 8.62749 +21 8315 904.731 864.294 257.241 3.92102 1.12099 9.58483 +22 8315 937.288 892.364 264.81 3.91867 1.09953 8.62749 +21 8316 1099.88 1054.07 259.577 5.74896 1.01681 8.45988 +22 8316 1160.26 1108.87 268.119 5.75648 0.995807 7.54229 +21 8317 1100 1053.88 281.804 5.71313 1.26917 8.40526 +22 8317 1160.16 1108.94 294.043 5.77463 1.27102 7.56744 +21 8318 1004.86 953.09 309.892 4.10144 1.42183 7.4863 +22 8318 1059.72 1000.73 327.913 4.09864 1.41178 6.56946 +21 8321 976.444 929.181 299.045 4.16969 1.43418 8.20036 +22 8321 1022.88 969.42 314.064 4.15299 1.41886 7.24991 +23 8321 1081.43 1021.78 333.375 4.24862 1.44528 6.4965 +21 8322 976.211 923.949 317.896 3.76849 1.49076 7.41605 +22 8322 1028.34 968.238 337.131 3.74263 1.46813 6.44832 +23 8322 1096.71 1026.93 362.371 3.75003 1.45888 5.55433 +22 8336 510.325 501.361 116.997 -5.94621 -3.34698 43.2352 +23 8336 509.282 500.247 116.189 -5.9622 -3.36913 42.9005 +22 8343 509.883 485.821 250.236 -2.22513 1.72744 16.1073 +23 8343 506.913 481.754 255.932 -2.19152 1.77373 15.405 +24 8343 501.482 475.943 260.327 -2.27322 1.83984 15.1763 +25 8343 496.102 468.275 264.427 -2.19003 1.76762 13.9276 +22 8346 912.028 884.132 178.467 5.82408 0.108085 13.8933 +23 8346 935.293 904.118 177.463 5.61231 0.0794055 12.4319 +22 8361 96.593 65.6225 39.0154 -8.89686 -2.32129 12.5143 +23 8361 59.5675 26.2641 30.0413 -8.87081 -2.30342 11.6377 +22 8366 74.8142 45.763 64.4625 -9.88735 -2.00414 13.3411 +23 8366 37.4603 5.73587 56.6805 -9.68666 -1.96703 12.2169 +22 8368 117.375 84.6576 35.7576 -8.08072 -2.25086 11.8463 +23 8368 79.9366 44.9309 25.8696 -8.12688 -2.25543 11.0718 +22 8370 135.746 101.375 44.7853 -7.40477 -2.00146 11.2762 +23 8370 96.6992 60.6263 34.7567 -7.63683 -2.05636 10.7442 +24 8370 52.9994 14.5462 23.0676 -7.77456 -2.09236 10.0791 +22 8383 229.194 194.91 52.3158 -5.95946 -1.88856 11.3049 +23 8383 198.862 161.869 42.8708 -5.96346 -1.8874 10.477 +24 8383 163.539 123.079 31.2062 -5.92136 -1.88052 9.57913 +25 8383 120.387 76.3998 16.6639 -5.97358 -1.90733 8.81114 +22 8385 142.616 110.091 62.8959 -7.71144 -1.81593 11.916 +23 8385 107.26 73.0681 54.9378 -7.8911 -1.85246 11.3353 +22 8393 163.142 129.663 39.1275 -7.16239 -2.14553 11.5765 +23 8393 127.762 89.2263 28.1049 -6.71578 -2.01766 10.0575 +22 8399 309.781 277.861 43.3644 -5.04461 -2.17903 12.1419 +23 8399 287.988 253.659 33.9288 -5.03161 -2.17376 11.2899 +24 8399 263.093 225.939 22.9368 -5.00888 -2.16736 10.4313 +25 8399 233.419 192.833 9.08467 -4.97825 -2.1675 9.5496 +22 8401 396.844 366.251 50.2175 -3.73484 -2.15325 12.6687 +23 8401 382.772 349.725 42.7261 -3.68625 -2.11513 11.728 +24 8401 366.411 330.545 31.8822 -3.64156 -2.11129 10.8063 +22 8403 298.021 265.275 62.8201 -5.11031 -1.80494 11.8357 +23 8403 274.504 240.029 54.7923 -5.22058 -1.83955 11.2424 +24 8403 248.048 211.043 45.4633 -5.24758 -1.84916 10.4736 +25 8403 217.164 176.771 33.3014 -5.21803 -1.85575 9.59493 +26 8403 179.679 134.488 17.9261 -5.10966 -1.84151 8.57637 +22 8404 384.018 352.096 63.0336 -3.79521 -1.84796 12.1414 +23 8404 368.046 333.467 55.0886 -3.75166 -1.82936 11.2083 +24 8404 349.613 312.309 45.6498 -3.74302 -1.83164 10.3896 +22 8405 280.527 248.402 78.1821 -5.50164 -1.58297 12.0646 +23 8405 256.39 221.063 71.3096 -5.37011 -1.54403 10.9713 +24 8405 227.702 189.211 63.2835 -5.32889 -1.52908 10.0692 +25 8405 192.735 151.685 52.7247 -5.45422 -1.57191 9.44144 +22 8407 385.785 355.292 100.053 -3.94196 -1.28244 12.7104 +23 8407 370.659 338.181 95.2349 -3.95112 -1.28372 11.9333 +24 8407 354.159 318.959 89.9922 -3.89746 -1.26448 11.0108 +25 8407 332.957 294.966 83.0562 -3.91083 -1.26964 10.2017 +22 8408 375.67 346.728 110.047 -4.34075 -1.16563 13.391 +23 8408 360.075 329.793 105.928 -4.42549 -1.18717 12.799 +22 8409 375.67 346.728 110.047 -4.34075 -1.16563 13.391 +23 8409 360.075 329.793 105.928 -4.42549 -1.18717 12.799 +22 8413 316.143 284.138 56.7624 -4.92447 -1.94839 12.1097 +23 8413 294.815 260.303 48.1282 -4.89879 -1.94128 11.2303 +24 8413 270.165 232.788 38.0762 -4.87741 -1.93688 10.3692 +25 8413 240.763 199.804 25.1938 -4.83662 -1.9365 9.46267 +22 8416 408.435 377.932 63.2807 -3.54183 -1.9296 12.7064 +23 8416 394.912 362.087 55.6222 -3.51248 -1.91838 11.8072 +24 8416 379.67 344.344 46.779 -3.49566 -1.91707 10.9716 +25 8416 361.368 323.23 35.7454 -3.49554 -1.93105 10.1622 +26 8416 339.679 298.27 21.7539 -3.50085 -1.96005 9.35967 +22 8417 295.961 263.783 82.3343 -5.23493 -1.51106 12.0447 +23 8417 272.903 238.211 76.0914 -5.21255 -1.49821 11.1718 +22 8420 399.734 368.491 32.49 -3.60739 -2.41319 12.4049 +23 8420 385.62 353.82 22.7112 -3.78259 -2.53608 12.1876 +22 8427 479.953 469.138 73.2114 -6.4374 -4.94914 35.838 +23 8427 477.692 466.955 70.9219 -6.59706 -5.09948 36.0972 +24 8427 475.753 464.693 69.0118 -6.49862 -5.04333 35.0431 +25 8427 473.307 461.915 66.1795 -6.42491 -5.03017 34.0236 +26 8427 470.571 458.951 61.7887 -6.42496 -5.13416 33.3542 +22 8428 424.392 393.637 74.3647 -3.23401 -1.72015 12.6019 +23 8428 411.66 378.618 67.3358 -3.21718 -1.71537 11.7298 +24 8428 397.697 361.847 59.4154 -3.17442 -1.69969 10.8111 +25 8428 380.547 342.379 49.4538 -3.22294 -1.73664 10.1544 +26 8428 360.099 317.981 36.8369 -3.18144 -1.73467 9.20199 +22 8434 505.993 497.621 88.1378 -6.64446 -5.4351 46.2914 +23 8434 505.087 496.589 86.5993 -6.60366 -5.45212 45.6081 +24 8434 504.279 495.719 84.8615 -6.6065 -5.52166 45.2776 +22 8437 528.542 518.472 59.4001 -4.32155 -6.05174 38.4875 +23 8437 528 518.347 55.7046 -4.53865 -6.51917 40.1524 +22 8443 653.458 640.544 63.0843 1.82599 -4.56598 30.0131 +23 8443 655.783 642.544 59.6679 1.87552 -4.59255 29.2765 +24 8443 658.701 644.963 56.2251 1.92151 -4.56038 28.2133 +25 8443 661.455 647.085 52.1539 1.93989 -4.51183 26.9714 +26 8443 663.758 649.48 46.7374 2.03891 -4.74436 27.1434 +22 8444 641.514 628.244 85.5024 1.29349 -3.5359 29.207 +23 8444 643.657 629.984 82.7904 1.33952 -3.53809 28.3451 +24 8444 646.084 631.829 80.1892 1.37635 -3.49187 27.1896 +25 8444 648.221 633.603 76.9298 1.42063 -3.52472 26.5128 +26 8444 650.445 635.216 72.1965 1.44212 -3.55036 25.4499 +22 8445 612.04 599.352 97.1997 0.105033 -3.20276 30.5457 +23 8445 613.24 600.092 94.8226 0.15037 -3.18777 29.4766 +24 8445 614.798 600.856 92.6361 0.201837 -3.09058 27.7989 +25 8445 615.889 601.426 89.824 0.235074 -3.08366 26.7973 +26 8445 616.922 601.714 85.6815 0.260039 -3.07895 25.4849 +22 8447 603.22 595.859 46.1224 -0.462577 -9.24744 52.6496 +23 8447 604.227 596.708 44.143 -0.380896 -9.19458 51.5436 +22 8449 628.289 617.074 57.6759 0.897038 -5.51634 34.5574 +23 8449 630.385 617.915 54.8202 0.897115 -5.08467 31.0824 +22 8452 620.612 606.493 90.8842 0.42049 -3.11847 27.4503 +23 8452 622.408 607.539 88.404 0.464172 -3.05091 26.0669 +22 8460 767.459 739.814 32.208 3.068 -2.73276 14.0195 +23 8460 779.551 749.833 22.1151 3.07256 -2.72457 13.0416 +22 8461 797.58 769.206 38.0056 3.55938 -2.55279 13.6593 +23 8461 811.281 781.811 28.4607 3.67684 -2.6319 13.1517 +22 8465 775.314 746.579 61.3783 3.09846 -2.08382 13.4877 +23 8465 788.253 757.292 53.7821 3.10012 -2.06575 12.5178 +22 8470 757.925 729.683 65.7749 2.82187 -2.03662 13.7235 +23 8470 769.52 739.188 58.4732 2.83269 -2.02553 12.7774 +22 8473 734.337 705.629 31.4497 2.33465 -2.64573 13.5003 +23 8473 744.561 713.182 21.9233 2.31096 -2.58363 12.3513 +22 8478 959.876 930.732 33.9973 6.45657 -2.55922 13.2984 +23 8478 986.286 954.683 23.0952 6.40328 -2.54548 12.2641 +22 8482 965.183 940.632 107.399 7.78066 -1.43209 15.7864 +23 8482 992.032 962.067 102.438 6.85628 -1.26228 12.9344 +22 8500 1080.03 1047.25 41.5047 7.70982 -2.15249 11.8242 +23 8500 1119.77 1084.79 30.7886 7.83495 -2.18159 11.0801 +24 8500 1166.82 1128.61 18.8358 7.8333 -2.16499 10.1424 +22 8504 1070.96 1039.18 98.1242 7.80011 -1.26334 12.1979 +23 8504 1109.33 1075.12 91.9221 7.848 -1.27089 11.3305 +24 8504 1154.57 1117.1 85.8273 7.81208 -1.24742 10.3424 +25 8504 1207.36 1166.75 77.6295 7.90567 -1.2593 9.54198 +22 8507 1051.43 1019.58 23.5773 7.45185 -2.51747 12.1683 +23 8507 1087.39 1053.11 11.6714 7.48829 -2.52598 11.3076 +22 8508 983.432 953.926 28.1576 6.80617 -2.63413 13.1352 +23 8508 1011.7 979.586 16.8903 6.72598 -2.60855 12.068 +22 8518 984.095 954.181 117.345 6.72531 -0.996743 12.9562 +23 8518 1013.07 980.818 112.934 6.72069 -0.997997 12.0176 +22 8521 1049.85 1017.87 33.5587 7.39551 -2.33973 12.1196 +23 8521 1086.21 1051.7 22.3478 7.41923 -2.34266 11.2309 +22 8538 125.93 114.193 175.711 -22.1345 0.130749 33.023 +23 8538 113.728 101.283 177.264 -21.3996 0.190343 31.1409 +22 8542 49.2692 36.9311 127.193 -24.3928 -1.98788 31.4129 +23 8542 33.7275 21.3997 126.736 -25.0904 -2.00947 31.4392 +22 8553 241.366 212.692 152.402 -6.89754 -0.383141 13.5169 +23 8553 217.33 186.623 151.565 -6.86108 -0.372396 12.6215 +22 8562 338.185 307.252 126.073 -4.7123 -0.812337 12.5292 +23 8562 319.499 285.978 122.679 -4.64791 -0.803995 11.5619 +22 8566 330.278 304.265 243.609 -5.76706 1.46107 14.8995 +23 8566 314.581 286.838 249.027 -5.71122 1.47482 13.97 +22 8568 317.052 290.79 245.132 -5.98291 1.47836 14.7582 +23 8568 300.112 272.188 250.142 -5.95256 1.48672 13.8796 +24 8568 281.093 251.326 255.538 -5.92714 1.49203 13.0201 +25 8568 259.122 227.258 260.688 -5.90754 1.48067 12.1634 +22 8569 534.26 527.953 141.419 -6.41305 -2.67723 61.4514 +23 8569 534.182 527.813 141.204 -6.35763 -2.66949 60.8572 +22 8573 480.014 470.89 205.807 -7.62713 1.94012 42.4813 +23 8573 478.455 469.24 206.902 -7.64231 1.9847 42.0598 +22 8576 474.548 450.846 250.617 -3.05971 1.76231 16.3519 +23 8576 468.603 443.659 255.522 -3.03539 1.78019 15.5378 +24 8576 461.762 435.138 260.634 -2.98195 1.77104 14.5577 +25 8576 453.357 425.005 265.971 -2.95929 1.76414 13.6698 +26 8576 444.304 413.526 270.527 -2.88415 1.70466 12.5928 +22 8577 480.58 470.466 127.223 -6.85034 -2.42353 38.3223 +23 8577 478.647 468.175 126.296 -6.71495 -2.38814 37.0103 +24 8577 476.995 465.956 125.914 -6.45047 -2.28408 35.1094 +25 8577 474.757 463.408 124.594 -6.37988 -2.28404 34.1488 +26 8577 472.186 460.553 121.836 -6.34351 -2.35585 33.3185 +22 8578 578.249 575.709 146.623 -6.62064 -5.54664 152.571 +23 8578 579.156 576.72 146.571 -6.70516 -5.79647 159.128 +24 8578 580.26 577.821 146.738 -6.45433 -5.75302 158.945 +22 8581 593.98 576.818 226.206 -0.487605 1.66987 22.5834 +23 8581 594.698 577.035 228.44 -0.451939 1.69041 21.9424 +22 8583 562.868 556.394 129.58 -3.87396 -3.59046 59.8657 +23 8583 563.275 557.08 128.984 -4.01344 -3.80405 62.5661 +24 8583 563.459 557.925 128.699 -4.4751 -4.28624 70.0414 +22 8586 583.463 565.729 229.153 -0.790487 1.70533 21.8559 +23 8586 583.91 565.264 231.663 -0.738877 1.69413 20.7855 +24 8586 583.999 564.57 234.523 -0.70664 1.7049 19.9478 +22 8587 637.776 630.123 152.393 1.98038 -1.43607 50.6409 +23 8587 639.095 631.562 151.672 2.10605 -1.51042 51.4501 +24 8587 640.791 632.781 151.522 2.09421 -1.43038 48.3815 +25 8587 642.124 634.249 150.281 2.22127 -1.53969 49.2166 +26 8587 643.361 635.353 147.949 2.26732 -1.67056 48.3988 +22 8590 810.604 805.82 138.238 22.5754 -3.88708 81.022 +23 8590 814.317 809.361 137.665 22.1914 -3.81373 78.1993 +22 8596 698.217 678.067 212.087 2.36342 1.04588 19.2347 +23 8596 703.789 682.64 214.143 2.39327 1.04866 18.3257 +24 8596 710.049 687.725 216.687 2.41789 1.05467 17.361 +25 8596 716.216 693.113 218.451 2.47976 1.06012 16.7757 +26 8596 722.856 698.5 220.021 2.49861 1.04021 15.9126 +22 8600 718.259 697.51 214.963 2.81394 1.09008 18.6786 +23 8600 725.098 703.201 217.164 2.8343 1.08698 17.7002 +24 8600 732.701 709.633 219.787 2.86746 1.09287 16.8017 +25 8600 740.428 716.023 222.08 2.88043 1.08347 15.8811 +26 8600 748.6 723.194 223.468 2.9397 1.07011 15.2553 +22 8608 802.419 786.763 177.345 6.61723 0.154102 24.7568 +23 8608 811.246 794.603 177.264 6.50925 0.142327 23.2869 +22 8610 744.117 715.878 134.974 2.55943 -0.720516 13.7244 +23 8610 751.926 727.577 132.726 3.1407 -0.885253 15.9176 +22 8621 913.315 884.705 190.634 5.70289 0.333807 13.5466 +23 8621 936.386 905.63 191.908 5.70788 0.332778 12.6013 +24 8621 962.668 929.303 193.45 5.68472 0.331574 11.6161 +25 8621 992.198 956.309 194.511 5.72692 0.324131 10.7992 +22 8629 948.843 935.834 172.272 14.0092 -0.0240359 29.7926 +23 8629 961.3 948.192 171.459 14.4136 -0.0571521 29.567 +22 8632 1081.12 1049.8 133.041 8.08805 -0.682858 12.3756 +23 8632 1119.42 1085.96 129.436 8.18614 -0.697113 11.5848 +24 8632 1164.61 1128.06 126.16 8.15616 -0.686141 10.6026 +22 8633 1030.1 999.068 138.353 7.28047 -0.597299 12.4915 +23 8633 1063.29 1030.42 135.257 7.41478 -0.614393 11.7912 +24 8633 1101.59 1066.65 132.16 7.56374 -0.62556 11.0917 +25 8633 1145.98 1108.36 128.044 7.66064 -0.639943 10.3044 +26 8633 1199.28 1157.01 121.8 7.49416 -0.648792 9.16931 +22 8634 1072.95 1031.05 192.239 5.93964 0.248476 9.24842 +23 8634 1123.73 1077.91 193.81 6.02706 0.245645 8.45776 +22 8635 990.079 955.053 193.86 5.83565 0.322154 11.0655 +23 8635 1025.09 986.769 194.877 5.825 0.308722 10.1147 +22 8639 1003.3 968.16 186.315 6.01868 0.205758 11.0293 +23 8639 1038.69 1001.12 187.065 6.13442 0.203144 10.3143 +24 8639 1080.29 1039.61 188.954 6.2157 0.212592 9.5275 +25 8639 1129.58 1084.58 189.95 6.20778 0.204088 8.61342 +22 8642 1037.09 1005.89 180.182 7.35998 0.126158 12.4214 +23 8642 1071.92 1038.12 180.325 7.34845 0.118744 11.4676 +24 8642 1110.67 1076.04 180.781 7.77295 0.122952 11.1921 +25 8642 1158.18 1118.15 182.339 7.36158 0.12727 9.68183 +26 8642 1212.64 1171.17 181.406 7.8116 0.110767 9.34599 +22 8643 1048.32 1017.51 150.743 7.64964 -0.385495 12.5798 +23 8643 1083.28 1050.14 148.689 7.67862 -0.391688 11.6954 +22 8645 1059.46 1028.48 149.296 7.80012 -0.408438 12.5095 +23 8645 1096.03 1063.11 147.377 7.93878 -0.415762 11.7749 +24 8645 1138.93 1102.68 145.652 7.84321 -0.403027 10.6903 +25 8645 1187.49 1149.32 143.067 8.13278 -0.419167 10.1537 +22 8669 329.806 298.281 273.514 -4.76668 1.71513 12.2942 +23 8669 310.238 276.045 281.636 -4.70219 1.70892 11.335 +24 8669 287.23 250.648 290.717 -4.73297 1.73067 10.5948 +25 8669 260.008 220.599 300.725 -4.76433 1.74286 9.83446 +22 8673 365.903 323.259 313.034 -3.06915 1.76574 9.08865 +23 8673 341.738 294.656 328.319 -3.05552 1.77367 8.23188 +24 8673 311.792 259.302 347.128 -3.04716 1.7834 7.38376 +22 8674 355.14 310.916 313.999 -3.09022 1.71438 8.76392 +23 8674 328.703 280.245 329.817 -3.11329 1.73993 7.99824 +22 8678 310.536 284.074 252.234 -6.06978 1.61132 14.6463 +23 8678 292.988 264.866 257.779 -6.04686 1.62217 13.7822 +24 8678 273.363 243.266 263.819 -6.00024 1.62349 12.8776 +25 8678 250.365 218.297 269.901 -6.01665 1.62557 12.086 +26 8678 224.043 189.378 275.835 -5.97373 1.59572 11.1805 +22 8681 510.091 465.805 312.427 -1.20649 1.69293 8.75177 +23 8681 500.829 451.127 328.267 -1.17509 1.67961 7.79793 +24 8681 489.14 433.242 347.981 -1.15718 1.6829 6.93368 +22 8685 481.612 433.271 322.81 -1.42173 1.66628 8.01758 +23 8685 467.646 413.7 341.666 -1.41306 1.6809 7.1845 +24 8685 450.003 388.429 365.389 -1.39192 1.67961 6.29446 +22 8691 624.463 580.103 308.296 0.180471 1.64004 8.73696 +23 8691 627.806 579.727 323.242 0.203856 1.68016 8.06117 +22 8692 660.14 609.74 327.482 0.539075 1.64797 7.68989 +23 8692 667.62 611.314 347.236 0.553893 1.66357 6.88334 +22 8700 774.964 732.871 255.204 2.11072 1.05086 9.20749 +23 8700 793.875 747.368 263.81 2.12882 1.05053 8.33366 +24 8700 816.931 764.965 275.067 2.14353 1.05654 7.45827 +22 8701 722.805 683.403 298.093 1.54381 1.7073 9.83625 +23 8701 735.045 691.367 310.943 1.54323 1.69823 8.8735 +22 8709 1094.09 1048.91 278.671 5.76075 1.25809 8.57853 +23 8709 1151.84 1101.82 289.592 5.82366 1.25368 7.74876 +24 8709 1224.39 1167.96 305.162 5.85202 1.25932 6.86766 +22 8719 1109.11 1062.59 274.073 5.76867 1.16885 8.33213 +23 8719 1171.38 1120.16 285.693 5.89155 1.18328 7.56641 +22 8732 1120.99 1073.42 276.796 5.77532 1.17377 8.14799 +23 8732 1185.94 1132.66 289.131 5.81141 1.17238 7.27499 +23 8736 332.007 298.97 81.0159 -4.51281 -1.49322 11.7317 +24 8736 311.831 275.971 73.6207 -4.45961 -1.4864 10.8078 +25 8736 287.337 248.493 64.8704 -4.45584 -1.49325 9.97776 +26 8736 258.102 215.208 52.9831 -4.40124 -1.50112 9.03568 +23 8740 575.573 568.104 103.618 -2.44418 -4.97927 51.8911 +24 8740 576.074 568.628 102.412 -2.41571 -5.08184 52.0536 +25 8740 576.505 568.849 101.042 -2.31924 -5.03863 50.6264 +26 8740 576.817 569.187 98.5612 -2.30487 -5.22986 50.7928 +23 8751 366.231 324.113 308.996 -3.10326 1.73628 9.20205 +24 8751 342.037 295.801 323.81 -3.10792 1.75372 8.38242 +23 8758 139 103.907 30.0152 -7.20259 -2.18635 11.0442 +24 8758 99.0178 63.4794 18.3116 -7.71666 -2.33585 10.9058 +23 8765 119.926 86.2234 90.4503 -7.80376 -1.31335 11.4998 +24 8765 81.3864 42.8228 84.3087 -7.35689 -1.23334 10.0503 +23 8767 113.609 78.933 36.7234 -7.68254 -2.10874 11.177 +24 8767 73.6673 34.9215 24.7109 -7.42932 -2.05378 10.003 +23 8768 100.612 65.9033 70.0185 -7.87636 -1.59146 11.1664 +24 8768 59.3967 22.2207 61.3988 -7.94921 -1.6104 10.4254 +23 8772 97.5793 62.4202 59.3199 -7.8219 -1.73454 11.0235 +24 8772 55.1546 17.7405 49.7601 -7.95953 -1.76725 10.359 +23 8773 97.5793 62.4202 59.3199 -7.8219 -1.73454 11.0235 +24 8773 55.1546 17.7405 49.7601 -7.95953 -1.76725 10.359 +23 8781 205.474 167.915 46.0077 -5.77902 -1.81409 10.3191 +24 8781 170.351 130.089 34.9251 -5.85953 -1.84013 9.62613 +25 8781 128.742 84.024 20.2212 -5.77558 -1.83343 8.66712 +23 8783 200.444 163.153 34.0581 -5.893 -1.99925 10.3932 +24 8783 164.977 124.262 21.997 -5.86538 -1.99026 9.51925 +25 8783 121.464 77.0857 6.56448 -5.90793 -2.01277 8.73352 +23 8785 248.652 212.929 82.1541 -5.42686 -1.36383 10.8495 +24 8785 219.313 180.909 74.7861 -5.45836 -1.37167 10.0921 +25 8785 184.253 142.81 65.112 -5.51239 -1.39644 9.35185 +26 8785 142.176 95.7072 52.2726 -5.4027 -1.39385 8.34058 +23 8788 206.46 169.062 39.4343 -5.78978 -1.91633 10.3636 +24 8788 171.449 131.118 27.3828 -5.835 -1.93747 9.60985 +23 8790 398.33 365.845 33.6245 -3.49284 -2.30227 11.9312 +24 8790 382.992 352.796 23.1377 -4.0304 -2.6633 12.8354 +23 8791 280.984 246.245 34.6332 -5.08072 -2.13729 11.157 +24 8791 254.742 217.428 23.3171 -5.1077 -2.15263 10.3868 +23 8792 382.772 349.725 42.7261 -3.68625 -2.11513 11.728 +24 8792 366.411 330.545 31.8822 -3.64156 -2.11129 10.8063 +23 8793 389.971 357.294 49.7582 -3.60956 -2.02344 11.8606 +24 8793 374.2 339.147 40.5397 -3.60661 -2.02757 11.0568 +25 8793 355.928 317.757 28.7458 -3.56915 -2.02792 10.1536 +26 8793 333.765 292.072 14.0131 -3.55316 -2.0464 9.29583 +23 8794 372.897 339.278 51.789 -3.78133 -1.93434 11.5285 +24 8794 355.201 318.91 42.1756 -3.7649 -1.93424 10.6799 +25 8794 334.281 294.219 30.6993 -3.69095 -1.90602 9.67441 +23 8796 366.551 331.751 60.7469 -3.75092 -1.73041 11.1372 +24 8796 347.832 310.437 51.9002 -3.75945 -1.73738 10.3642 +25 8796 325.57 285.316 40.7348 -3.7896 -1.76302 9.62831 +26 8796 299.134 257.111 26.122 -3.968 -1.87559 9.22302 +23 8798 413.042 379.966 73.6972 -3.19142 -1.6103 11.7177 +24 8798 399.014 363.128 66.2675 -3.15147 -1.5954 10.8001 +25 8798 381.98 343.544 56.835 -3.18053 -1.62142 10.0838 +26 8798 362.045 319.406 44.5861 -3.11806 -1.61586 9.08958 +23 8802 309.687 276.855 92.4811 -4.90606 -1.31494 11.8047 +24 8802 288.119 253.14 86.5741 -4.93619 -1.32495 11.0803 +25 8802 262.101 224.725 78.6047 -4.99341 -1.35448 10.3694 +26 8802 231.977 190.98 68.0783 -4.94724 -1.37281 9.45388 +23 8803 318.824 285.849 114.638 -4.73598 -0.948321 11.7536 +24 8803 297.236 261.168 110.077 -4.65136 -0.934925 10.7457 +23 8808 329.645 296.438 90.9464 -4.5278 -1.32491 11.6713 +24 8808 308.439 272.65 84.9223 -4.51947 -1.31975 10.8294 +23 8812 356.825 321.711 54.8936 -3.86613 -1.80447 11.0375 +24 8812 336.266 299.31 45.3344 -3.9722 -1.85344 10.4872 +23 8814 417.571 383.67 48.8877 -3.04201 -1.96422 11.4326 +24 8814 404.075 367.187 39.7824 -2.9922 -1.93775 10.5068 +23 8817 526.032 518.743 116.613 -6.15552 -4.14466 53.1734 +24 8817 525.912 518.466 116.001 -6.03445 -4.10143 52.0527 +25 8817 525.377 517.807 114.804 -5.97331 -4.11905 51.1983 +26 8817 524.858 517.07 112.405 -5.84226 -4.16945 49.7678 +23 8819 487.77 476.896 65.0954 -6.01653 -5.32337 35.6446 +24 8819 486.303 475.339 63.1593 -6.03868 -5.37424 35.3501 +23 8823 499.502 490.333 63.989 -6.44725 -6.37741 42.2684 +24 8823 498.164 488.635 62.2482 -6.27926 -6.23477 40.6725 +25 8823 496.471 487.706 59.397 -6.9307 -6.95331 44.22 +26 8823 495.577 486.008 55.8239 -6.3986 -6.56967 40.5047 +23 8827 517.919 509.882 110.784 -6.12443 -4.14823 48.2215 +24 8827 517.461 509.081 110.031 -5.904 -4.02728 46.2543 +23 8830 618.915 605.113 84.2025 0.364103 -3.45011 28.0805 +24 8830 620.567 606.23 81.6706 0.412407 -3.41611 27.0318 +25 8830 621.899 607.078 78.4168 0.447221 -3.42262 26.1502 +26 8830 623.13 607.954 73.8188 0.48034 -3.50528 25.5383 +23 8833 612.856 605.612 13.8579 0.244447 -11.7911 53.509 +24 8833 614.307 606.907 11.4278 0.344597 -11.7174 52.3739 +25 8833 615.334 607.875 8.35151 0.415855 -11.8459 51.9582 +23 8837 563.318 556.137 49.8958 -3.45905 -9.19775 53.9738 +24 8837 563.618 556.196 47.2119 -3.32495 -9.09314 52.2201 +25 8837 563.994 556.195 43.4754 -3.13852 -8.91148 49.6988 +26 8837 564.114 557.957 39.5602 -3.96462 -11.6284 62.9463 +23 8839 659.336 645.058 77.7919 1.87267 -3.57636 27.1452 +24 8839 662.381 647.244 75.0053 1.87439 -3.47218 25.6039 +25 8839 665.322 649.564 71.4236 1.90086 -3.4576 24.5961 +23 8841 604.281 595.977 113.219 -0.341406 -3.85755 46.6731 +24 8841 605.568 596.622 112.291 -0.239681 -3.63661 43.3262 +25 8841 606.311 597.43 111.163 -0.196437 -3.73099 43.6379 +23 8847 594.194 586.446 49.7486 -1.0651 -8.53375 50.0175 +24 8847 595.255 587.418 47.8392 -0.980462 -8.56892 49.4565 +25 8847 595.74 587.943 45.5279 -0.952053 -8.77202 49.7097 +26 8847 596.017 588.193 41.9758 -0.929661 -8.98488 49.5341 +23 8851 797.187 766.528 28.3181 3.28726 -2.53229 12.6415 +24 8851 812.297 779.532 18.4169 3.32368 -2.53185 11.8289 +23 8856 734.359 705.471 95.2715 2.32055 -1.44258 13.4164 +24 8856 744.628 713.7 89.9628 2.34578 -1.43959 12.5311 +25 8856 755.958 722.602 83.3107 2.35756 -1.44198 11.6194 +23 8857 740.307 711.024 100.074 2.39836 -1.33504 13.2355 +24 8857 750.888 719.437 94.9315 2.41377 -1.33085 12.3232 +25 8857 762.856 729.103 88.9383 2.43959 -1.33545 11.4827 +23 8862 788.053 758.033 45.4533 3.19377 -2.27957 12.9104 +24 8862 803.306 770.042 36.4166 3.12867 -2.20323 11.6516 +25 8862 818.578 784.419 25.0559 3.28686 -2.32416 11.3464 +23 8865 749.182 718.922 58.8431 2.47841 -2.02378 12.8078 +24 8865 760.932 728.325 50.6868 2.49363 -2.01251 11.8862 +25 8865 774.017 738.772 40.8912 2.50644 -2.0112 10.9967 +23 8870 737.169 707.599 82.9748 2.31807 -1.63269 13.107 +24 8870 747.616 715.823 76.6398 2.33249 -1.62555 12.1904 +25 8870 759.451 725.183 68.99 2.34954 -1.62806 11.3101 +26 8870 772.865 735.976 58.8782 2.37791 -1.65961 10.5064 +23 8871 737.169 707.599 82.9748 2.31807 -1.63269 13.107 +24 8871 747.616 715.823 76.6398 2.33249 -1.62555 12.1904 +23 8880 803.5 775.056 104.599 3.66249 -1.28897 13.6259 +24 8880 818.654 787.903 100.439 3.65241 -1.26493 12.6036 +25 8880 834.262 802.336 95.0053 3.78058 -1.30979 12.1397 +23 8881 798.113 768.549 36.3075 3.42583 -2.48091 13.1096 +24 8881 815.142 780.351 25.8364 3.17408 -2.26987 11.1401 +23 8882 743.356 714.82 123.19 2.51857 -0.934862 13.5821 +24 8882 754.529 725.196 120.236 2.6547 -0.963548 13.2129 +23 8889 870.641 864.364 87.9806 22.3422 -7.26308 61.746 +24 8889 875.947 869.569 86.8664 22.4318 -7.24079 60.7588 +23 8899 840.641 815.101 49.5028 4.85999 -2.59425 15.175 +24 8899 856.499 829.3 41.9999 4.87683 -2.58424 14.2497 +23 8902 879.159 873.879 65.6525 27.427 -10.9059 73.4038 +24 8902 883.891 878.049 64.2763 25.2239 -9.98336 66.343 +23 8909 1062.48 1028 22.8323 7.05516 -2.33688 11.2394 +24 8909 1102.18 1064.84 10.1258 7.08639 -2.34087 10.3794 +23 8910 1088.16 1054.98 78.3888 7.74776 -1.52923 11.6805 +24 8910 1130.57 1093.79 70.4607 7.60888 -1.49535 10.5373 +25 8910 1178.15 1139.15 61.0376 7.8321 -1.54023 9.93889 +23 8911 1064.81 1031.74 80.1722 7.39452 -1.50539 11.7197 +24 8911 1103.97 1068.44 72.6641 7.47551 -1.51487 10.9097 +25 8911 1148.52 1110.4 63.2581 7.59365 -1.54413 10.166 +23 8912 1029.83 997.735 97.6453 7.03471 -1.2589 12.0776 +24 8912 1064.89 1030.13 92.1808 7.03757 -1.24689 11.1522 +25 8912 1105.19 1067.69 85.012 7.09888 -1.25815 10.3345 +23 8913 1029.83 997.735 97.6453 7.03471 -1.2589 12.0776 +24 8913 1064.89 1030.13 92.1808 7.03757 -1.24689 11.1522 +25 8913 1105.19 1067.69 85.012 7.09888 -1.25815 10.3345 +26 8913 1154.22 1111.9 74.5844 6.91265 -1.2472 9.15746 +23 8917 987.718 956.406 112.938 6.48733 -1.02786 12.378 +24 8917 1018.54 984.873 108.652 6.5245 -1.0242 11.5106 +25 8917 1053.47 1017.17 102.874 6.56815 -1.03542 10.6759 +23 8918 1076.35 1042.86 113.762 7.48645 -0.947723 11.5721 +24 8918 1117.26 1080.69 109.119 7.45738 -0.936162 10.5982 +25 8918 1164.81 1124.96 103.131 7.4852 -0.939928 9.72691 +23 8919 1022.08 990.041 121.933 6.91618 -0.853728 12.097 +24 8919 1056.56 1022.24 118.046 6.99482 -0.857645 11.2907 +25 8919 1094.63 1058.65 113.64 7.24172 -0.884017 10.772 +23 8922 1005 972.698 22.1672 6.5748 -2.50537 11.9965 +24 8922 1038.09 1003.04 10.6711 6.56831 -2.48587 11.0594 +23 8925 980.413 948.375 41.4097 6.21768 -2.20378 12.0972 +24 8925 1010.62 976.296 31.5462 6.27566 -2.21111 11.2902 +23 8928 995.121 963.819 111.793 6.61642 -1.04783 12.3819 +24 8928 1026.65 992.697 107.742 6.59771 -1.02995 11.4134 +23 8929 995.121 963.819 111.793 6.61642 -1.04783 12.3819 +24 8929 1026.65 992.697 107.742 6.59771 -1.02995 11.4134 +23 8931 1078.04 1044.15 106.483 7.42625 -1.0521 11.4376 +24 8931 1119.04 1082.63 101.188 7.51492 -1.05707 10.6427 +25 8931 1166.69 1127.06 94.3015 7.55151 -1.06472 9.77988 +26 8931 1224.45 1180.49 85.0143 7.51281 -1.07323 8.8158 +23 8932 1056.22 1023.1 123.354 7.24406 -0.802805 11.7021 +24 8932 1094.46 1058.76 119.54 7.29596 -0.802172 10.8564 +25 8932 1137.93 1100.03 114.603 7.4876 -0.825481 10.2249 +26 8932 1190.23 1146.71 107.141 7.16827 -0.811216 8.90731 +23 8933 992.767 961.469 65.4686 6.57682 -1.84301 12.3834 +24 8933 1023.73 989.931 57.4664 6.58247 -1.83388 11.4675 +23 8935 1099.55 1066.49 27.1798 7.96214 -2.36714 11.7247 +24 8935 1144.95 1106.76 13.3215 7.52892 -2.24341 10.1466 +23 8942 1116.65 1081.69 87.1883 7.79132 -1.31624 11.0863 +24 8942 1162.89 1125.28 80.2008 7.90338 -1.3234 10.306 +25 8942 1217.28 1176.1 71.2618 7.92712 -1.32517 9.41176 +23 8943 1135.03 1100.53 88.873 8.18053 -1.30741 11.2329 +24 8943 1182.73 1145.14 81.8574 8.19054 -1.30032 10.3106 +23 8953 1121.68 1087.24 81.3728 7.9877 -1.42686 11.254 +24 8953 1167.44 1130.82 73.3666 8.18308 -1.45929 10.5835 +23 8957 72.7436 62.9926 190.952 -29.5715 0.996964 39.7472 +24 8957 61.9262 51.7761 191.762 -28.9811 1.00062 38.1842 +25 8957 49.7189 39.4233 191.982 -29.2085 0.997971 37.6447 +23 8970 161.865 135.956 229.046 -9.28167 1.16498 14.959 +24 8970 135.766 108.079 233.085 -9.19214 1.16854 13.9987 +25 8970 105.935 76.4923 236.5 -9.18797 1.16114 13.1635 +26 8970 71.9046 40.5884 239.321 -9.22209 1.14008 12.3761 +23 8972 175.691 149.145 242.26 -8.77936 1.40443 14.6004 +24 8972 149.17 122.044 248.188 -9.11659 1.49176 14.2878 +23 8975 153.594 128.083 220.209 -9.60054 0.99708 15.1923 +24 8975 127.646 100.107 223.112 -9.39961 0.980272 14.0734 +25 8975 97.657 69.7349 224.96 -9.84772 1.00239 13.8806 +26 8975 64.3161 32.1031 226.657 -9.09189 0.897166 12.0316 +23 8976 155.15 127.055 241.593 -8.68789 1.31422 13.7951 +24 8976 127.072 99.9403 246.579 -9.55218 1.45959 14.2849 +25 8976 96.635 67.1583 250.453 -9.34696 1.41407 13.1485 +26 8976 61.3971 30.5051 254.135 -9.53143 1.41332 12.5461 +23 8980 306.735 279.133 242.917 -5.89318 1.36347 14.0416 +24 8980 288.444 258.882 247.322 -5.83483 1.35312 13.1107 +23 8983 298.67 264.48 129.928 -4.88429 -0.6744 11.3358 +24 8983 274.668 238.721 126.585 -5.00413 -0.691385 10.7816 +25 8983 245.102 206.352 125.355 -5.05205 -0.658427 10.0018 +23 8984 472.808 463.918 166.35 -8.26249 -0.392946 43.5953 +24 8984 471.633 462.623 166.587 -8.2228 -0.373648 43.0161 +25 8984 469.769 460.444 165.883 -8.0525 -0.40153 41.5636 +26 8984 467.293 458 163.884 -8.22298 -0.518467 41.7048 +23 8985 458.805 449.684 197.852 -8.87742 1.47206 42.4891 +24 8985 456.937 447.82 198.714 -8.99201 1.5236 42.5106 +25 8985 454.695 445.355 199.004 -8.90712 1.50403 41.4996 +26 8985 452.332 442.589 198.165 -8.66837 1.39546 39.7802 +23 8986 419.594 409.815 210.681 -10.4349 2.07786 39.6345 +24 8986 416.729 406.183 211.851 -9.82213 1.98638 36.7527 +23 8989 517.588 510.15 136.037 -6.64184 -2.65876 52.1068 +24 8989 517.268 509.698 135.662 -6.54844 -2.63891 51.196 +23 8990 484.822 475.736 154.552 -7.37445 -1.08202 42.6572 +24 8990 483.568 473.699 154.628 -6.85745 -0.992017 39.2718 +25 8990 481.892 471.08 154.062 -6.34226 -0.933571 35.8446 +26 8990 478.168 467.04 151.65 -6.34254 -1.02356 34.8301 +23 8994 503.486 495.033 205.754 -6.74078 2.09073 45.8525 +24 8994 502.733 494.002 206.707 -6.5725 2.08282 44.3927 +25 8994 501.539 492.523 206.928 -6.43505 2.02991 42.984 +26 8994 500.109 490.98 206.253 -6.44004 1.96523 42.4553 +23 8997 546.064 540.219 130.298 -5.83481 -3.91066 66.3049 +24 8997 546.539 540.81 130.169 -5.90834 -4.00182 67.6462 +25 8997 547.116 540.689 129.335 -5.2188 -3.6372 60.3041 +26 8997 546.813 540.411 127.259 -5.2645 -3.82548 60.5381 +23 8999 554.957 539.153 229.586 -1.8559 1.92827 24.5245 +24 8999 554.057 538.389 232.201 -1.90286 2.03466 24.7374 +23 9000 674.71 660.651 211.569 2.48919 1.47918 27.5675 +24 9000 678.286 663.64 213.202 2.52055 1.47976 26.4623 +25 9000 681.544 666.533 214.356 2.57592 1.48515 25.8199 +26 9000 684.95 669.356 214.371 2.59682 1.43003 24.8531 +23 9001 618.084 601.197 224.352 0.27117 1.63809 22.9511 +24 9001 620.17 602.265 226.76 0.318318 1.6172 21.6462 +23 9003 672.784 660.065 205.05 2.67 1.35963 30.4706 +24 9003 676.174 662.915 206.372 2.69862 1.35784 29.2299 +25 9003 679.066 665.256 206.9 2.70347 1.32424 28.0644 +26 9003 681.875 667.932 206.335 2.78603 1.28987 27.7979 +23 9004 583.419 569.547 218.817 -1.01217 1.77976 27.9389 +24 9004 583.719 569.349 220.639 -0.96596 1.78625 26.972 +25 9004 583.91 568.89 221.962 -0.917249 1.7562 25.8034 +26 9004 583.766 568.583 222.123 -0.912524 1.74306 25.5271 +23 9005 619.546 609.772 183.55 0.548825 0.587824 39.6537 +24 9005 621.206 611.242 184.047 0.627843 0.603353 38.8956 +23 9009 802.405 787.554 154.347 6.97517 -0.669389 26.0978 +24 9009 810.189 794.981 154.019 7.08619 -0.665247 25.4845 +23 9010 697.541 692.488 155.78 9.35253 -1.81495 76.7003 +24 9010 699.829 694.599 155.794 9.27185 -1.75229 74.1115 +23 9019 703.728 679.304 243.999 2.07097 1.56464 15.8681 +24 9019 710.246 684.763 248.193 2.12236 1.58808 15.2093 +23 9023 746.242 717.642 228.922 2.56706 1.05302 13.5513 +24 9023 757.218 727.024 232.556 2.62685 1.0621 12.8361 +23 9026 739.962 716.546 185.643 2.99138 0.293384 16.5518 +24 9026 747.592 723.986 187.381 3.14089 0.330556 16.4184 +23 9030 885.913 877.115 138.163 16.8718 -2.1179 44.0509 +24 9030 893.237 884.26 137.701 16.974 -2.10337 43.1736 +23 9032 867.65 853.867 166.462 10.0588 -0.249141 28.1212 +24 9032 877.63 863.311 166.47 10.0561 -0.239475 27.067 +25 9032 887.775 873.007 166.001 10.1193 -0.249259 26.2438 +23 9033 867.65 853.867 166.462 10.0588 -0.249141 28.1212 +24 9033 877.63 863.311 166.47 10.0561 -0.239475 27.067 +25 9033 887.775 873.007 166.001 10.1193 -0.249259 26.2438 +26 9033 898.98 883.148 164.547 9.81905 -0.281839 24.4793 +23 9035 888.565 842.253 213.256 3.23603 0.468602 8.36869 +24 9035 922.626 869.839 218.149 3.18569 0.460908 7.34219 +23 9039 863.983 850.408 178.94 10.0673 0.240823 28.5506 +24 9039 873.839 859.238 179.674 9.72228 0.250894 26.5438 +25 9039 883.707 869.062 179.822 10.0555 0.255593 26.4655 +26 9039 895.109 879.175 178.722 9.62637 0.197823 24.3243 +23 9040 867.369 860.762 127.714 20.9592 -3.66977 58.6591 +24 9040 872.6 866.181 127.054 22.0128 -3.83286 60.3826 +23 9044 861.816 816.035 236.033 2.95971 0.741269 8.46574 +24 9044 893.274 840.989 245.006 2.91478 0.741259 7.41282 +25 9044 933.31 872.55 256.064 2.86217 0.735633 6.37887 +26 9044 986.625 914.164 269.59 2.7952 0.717104 5.34878 +23 9045 858.463 854.785 135.481 36.3494 -5.4578 105.372 +24 9045 863.889 857.448 135.198 21.2112 -3.14049 60.1766 +25 9045 867.429 860.39 134.004 19.6775 -2.96458 55.0591 +23 9047 954.973 902.099 242.405 3.50912 0.706586 7.33023 +24 9047 1003.51 943.371 252.228 3.51893 0.709012 6.44514 +25 9047 1065.47 996.626 264.215 3.55726 0.712851 5.62984 +23 9049 871.532 849.23 160.463 6.30979 -0.298456 17.3787 +24 9049 887.61 864.945 160.723 6.58969 -0.287494 17.1001 +25 9049 904.17 880.465 161.1 6.67557 -0.266322 16.3493 +23 9050 1049.97 1017.36 145.766 7.25449 -0.446204 11.8853 +24 9050 1087.37 1052.13 143.798 7.28314 -0.442893 10.9982 +25 9050 1130.56 1092.49 140.706 7.35114 -0.453595 10.1806 +26 9050 1181.7 1140.06 136.09 7.38036 -0.474246 9.30758 +23 9051 1066.25 1033.21 152.913 7.42405 -0.324157 11.7294 +24 9051 1105.08 1069.88 151.177 7.56107 -0.33076 11.0098 +25 9051 1150.23 1112.05 148.977 7.60579 -0.335891 10.1501 +23 9052 1084.4 1050.94 178.204 7.62222 0.0858714 11.5822 +24 9052 1125.29 1089.39 178.917 7.71705 0.0907169 10.7967 +25 9052 1173.2 1134.18 179.247 7.75967 0.0880147 9.93348 +26 9052 1230.55 1187.24 178.315 7.70218 0.0677378 8.94931 +23 9054 1093.13 1048.04 192.953 5.76081 0.239444 8.59579 +24 9054 1148.89 1099.99 195.904 5.92525 0.253236 7.92708 +25 9054 1218.58 1163.38 198.603 5.92693 0.250587 7.02198 +23 9055 1106.49 1059.74 199.675 5.70973 0.308176 8.2904 +24 9055 1167.16 1115.45 203.132 5.79233 0.314526 7.49527 +23 9057 1036.7 1005.36 152.165 7.32099 -0.354588 12.3667 +24 9057 1071.74 1037.58 150.58 7.26734 -0.350235 11.3456 +25 9057 1112.08 1075.03 148.258 7.28518 -0.356566 10.4602 +23 9059 1082.66 1049.56 170.398 7.67665 -0.0398466 11.7078 +24 9059 1123.81 1088.01 170.642 7.71575 -0.0331875 10.8259 +23 9060 1050.91 1018.21 158.092 7.25048 -0.242509 11.8534 +24 9060 1088.37 1052.92 157.261 7.25501 -0.236269 10.9327 +23 9061 998.322 961.215 197.118 5.62769 0.351242 10.4449 +24 9061 1036.01 995.315 199.538 5.62824 0.352167 9.52265 +25 9061 1079.74 1035.49 202.1 5.70739 0.355005 8.7586 +26 9061 1133.38 1084.04 203.425 5.70235 0.332795 7.8547 +23 9062 1116.36 1083.28 134.88 8.22969 -0.616635 11.7167 +24 9062 1160.64 1124.95 131.878 8.29529 -0.616807 10.8612 +25 9062 1212.99 1173.66 127.964 8.24135 -0.613082 9.85437 +23 9063 1154.6 1106.99 196.39 6.15017 0.265582 8.1418 +24 9063 1223.56 1170.41 199.699 6.20454 0.271268 7.29116 +23 9070 1123.92 1075.76 205.293 5.73711 0.361821 8.0479 +24 9070 1189.38 1135.52 209.608 5.78207 0.366511 7.19524 +23 9071 1132.8 1083.89 207.343 5.74662 0.378788 7.92449 +24 9071 1200.56 1145.77 212.065 5.79474 0.384465 7.07468 +23 9072 1148.59 1097.57 237.95 5.67433 0.685261 7.59553 +24 9072 1221.58 1164.57 247.13 5.76569 0.699735 6.79738 +23 9073 1115.43 1067.68 206.928 5.69092 0.383323 8.11707 +24 9073 1179.32 1125.37 211.673 5.67232 0.386464 7.1833 +23 9075 1126.35 1085.15 170.957 6.73742 -0.0247363 9.40674 +24 9075 1178.02 1135.54 168.932 7.18757 -0.0495884 9.12307 +23 9076 240.21 212.503 266.448 -7.16056 1.8145 13.9884 +24 9076 217.789 188.087 272.965 -7.08517 1.81051 13.049 +25 9076 191.547 160.064 279.605 -7.13198 1.82135 12.3106 +26 9076 161.729 128.211 285.802 -7.1769 1.81009 11.5633 +23 9078 264.272 233.034 274.104 -5.93732 1.74103 12.4071 +24 9078 240.095 205.745 282.326 -5.77746 1.71186 11.283 +23 9087 184.116 155.989 257.184 -8.12475 1.61046 13.7793 +24 9087 157.525 128.379 262.998 -8.33086 1.66132 13.2977 +25 9087 128.335 98.6406 268.776 -8.70502 1.73516 13.0521 +23 9088 184.116 155.989 257.184 -8.12475 1.61046 13.7793 +24 9088 157.525 128.379 262.998 -8.33086 1.66132 13.2977 +25 9088 128.335 98.6406 268.776 -8.70502 1.73516 13.0521 +26 9088 95.282 62.354 274.17 -8.38936 1.65275 11.7704 +23 9091 332.358 306.115 254.835 -5.6739 1.67803 14.7688 +24 9091 316.4 288.325 260.736 -5.60895 1.68143 13.805 +25 9091 298.019 268.109 266.617 -5.59476 1.68384 12.9577 +26 9091 277.086 245.164 271.889 -5.59454 1.66646 12.1413 +23 9096 345.95 302.118 312.201 -3.23043 1.70765 8.84218 +24 9096 318.849 270.979 327.677 -3.26203 1.73725 8.09631 +25 9096 286.216 232.142 345.525 -3.21194 1.71524 7.16743 +23 9098 371.892 326.94 320.191 -2.84004 1.76061 8.6221 +24 9098 347.122 297.193 336.872 -2.82335 1.76454 7.76247 +25 9098 316.242 259.768 356.804 -2.78986 1.74963 6.86284 +23 9101 370.339 323.45 329.062 -2.74042 1.78946 8.26568 +24 9101 344.062 291.053 348.117 -2.69033 1.77597 7.31148 +23 9104 530.571 496.218 283.815 -1.23508 1.73502 11.2821 +24 9104 525.869 488.071 293.241 -1.18932 1.71083 10.2538 +25 9104 519.794 479.214 304.187 -1.1882 1.73843 9.55087 +26 9104 511.427 465.817 316.19 -1.1557 1.68806 8.49753 +23 9111 645.413 617.556 260.493 0.691348 1.68988 13.9128 +24 9111 649.693 619.369 266.44 0.710914 1.65775 12.7811 +25 9111 653.463 621.005 273.25 0.726556 1.66143 11.9405 +23 9114 665.036 620.612 309.954 0.670799 1.65775 8.72451 +24 9114 672.78 623.038 325.757 0.682704 1.65116 7.79173 +25 9114 681.551 626.513 344.421 0.702606 1.67441 7.04186 +23 9115 659.717 610.903 322.72 0.551941 1.64914 7.93988 +24 9115 667.18 612.474 341.337 0.565768 1.65431 7.08466 +23 9118 637.797 610.252 263.268 0.550656 1.76315 14.0706 +24 9118 640.955 609.525 270.129 0.536556 1.66247 12.3314 +23 9121 746.817 709.005 288.08 1.94985 1.63687 10.25 +24 9121 761.296 719.873 299.296 1.96764 1.63964 9.35655 +25 9121 777.971 732.389 311.917 1.98462 1.63877 8.50283 +23 9124 740.198 705.773 273.603 2.03845 1.57205 11.2587 +24 9124 752.774 715.453 282.224 2.06126 1.57414 10.3849 +25 9124 767.165 726.452 291.641 2.07937 1.56721 9.5196 +23 9125 806.717 758.053 287.201 2.17623 1.26217 7.96435 +24 9125 832.591 777.706 301.595 2.18278 1.25997 7.06161 +23 9126 824.281 772.422 268.283 2.22409 0.988462 7.47372 +24 9126 856.09 794.956 281.287 2.16613 0.952737 6.33975 +23 9129 860.347 813.796 263.186 2.89383 1.04234 8.32579 +24 9129 891.703 839.169 276.09 2.88485 1.05556 7.37753 +23 9131 1078.78 1033.61 286.418 5.58025 1.35058 8.58101 +24 9131 1134.08 1083.95 299.985 5.6204 1.36224 7.73144 +25 9131 1203.71 1146.98 316.429 5.62538 1.35935 6.83146 +23 9141 1159.3 1108.42 295.086 5.80461 1.29063 7.61863 +24 9141 1233.67 1176.09 310.81 5.82247 1.28701 6.73136 +24 9149 694.436 679.79 97.6685 3.11294 -2.75752 26.4633 +25 9149 698.43 683.236 94.8587 3.14185 -2.75738 25.5086 +26 9149 702.248 686.504 90.6377 3.16226 -2.80496 24.6166 +24 9152 813.742 782.878 111.083 3.55355 -1.07505 12.5575 +25 9152 829.895 797.238 107.604 3.62416 -1.07325 11.8681 +24 9159 226.986 198.786 255.037 -7.28728 1.56543 13.7439 +25 9159 200.961 169.358 260.351 -6.94502 1.4872 12.2641 +26 9159 171.901 138.284 264.564 -6.9931 1.46538 11.529 +24 9162 391.535 345.629 322.994 -2.55116 1.75682 8.4429 +25 9162 367.812 316.455 340.298 -2.5285 1.75134 7.54674 +24 9164 622.253 580.32 301.792 0.1626 1.6517 9.24288 +25 9164 625.058 578.433 314.906 0.178557 1.63654 8.31262 +26 9164 627.635 577.68 329.213 0.194366 1.68128 7.75847 +24 9168 959.791 899.609 259.936 3.12595 0.777238 6.43999 +25 9168 1016.02 946.144 273.298 3.1244 0.772094 5.54629 +26 9168 1092.61 1009.47 290.12 3.121 0.757664 4.6619 +24 9186 155.915 114.979 31.8958 -5.95252 -1.84959 9.4677 +25 9186 111.738 67.4923 17.3333 -6.04359 -1.88803 8.75953 +24 9194 277.283 240.678 28.0587 -4.87591 -2.12477 10.588 +25 9194 249.026 208.906 14.2394 -4.82704 -2.12363 9.6604 +24 9195 193.065 153.489 30.74 -5.65292 -1.92886 9.79316 +25 9195 154.048 108.552 15.8365 -5.37802 -1.85383 8.51887 +24 9197 322.293 285.012 60.3647 -4.13896 -1.62076 10.396 +25 9197 297.25 257.404 49.3824 -4.21011 -1.66447 9.72675 +26 9197 268.128 224.134 36.2179 -4.16877 -1.66828 8.80974 +24 9198 311.831 275.971 73.6207 -4.45961 -1.4864 10.8078 +25 9198 287.337 248.493 64.8704 -4.45584 -1.49325 9.97776 +24 9203 346.351 309.122 39.3172 -3.7977 -1.92674 10.4107 +25 9203 324.125 281.511 27.226 -3.5979 -1.83564 9.09497 +24 9205 323.69 289.892 119.288 -4.54326 -0.851314 11.4673 +25 9205 300.81 266.699 114.945 -4.86192 -0.911901 11.3621 +26 9205 277.031 236.295 108.566 -4.38478 -0.847709 9.51433 +24 9212 507.559 497.562 62.7201 -5.48097 -5.918 38.7715 +25 9212 506.128 496.387 60.924 -5.7039 -6.17256 39.7903 +26 9212 504.132 494.858 58.0436 -6.10696 -6.65045 41.7954 +24 9213 507.559 497.562 62.7201 -5.48097 -5.918 38.7715 +25 9213 506.128 496.387 60.924 -5.7039 -6.17256 39.7903 +26 9213 504.132 494.858 58.0436 -6.10696 -6.65045 41.7954 +24 9218 482.561 472.656 74.0724 -6.88714 -5.35694 39.1291 +25 9218 481.469 470.195 71.8171 -6.10286 -4.8139 34.3777 +26 9218 479.155 467.609 67.912 -6.06652 -4.88201 33.5666 +24 9219 549.598 542.01 103.06 -4.24506 -4.94112 51.0821 +25 9219 549.359 541.726 101.481 -4.23665 -5.0229 50.7786 +26 9219 549.184 541.393 98.8415 -4.16302 -5.1033 49.7514 +24 9221 498.517 488.798 112.629 -6.13757 -3.32875 39.8809 +25 9221 496.749 487.134 111.708 -6.30231 -3.41602 40.3098 +26 9221 495.226 485.77 108.881 -6.49431 -3.63378 40.9845 +24 9223 625.261 616.816 14.7882 0.998692 -10.0535 45.8923 +25 9223 626.55 617.017 11.7271 0.957336 -9.07885 40.6557 +24 9224 570.128 562.76 41.3882 -2.87451 -9.58375 52.5995 +25 9224 570.392 562.6 39.0327 -2.7002 -9.22557 49.7424 +24 9226 628.959 615.077 94.1538 0.750662 -3.04532 27.92 +25 9226 630.59 616.18 91.2432 0.783954 -3.04217 26.8965 +26 9226 632.216 617.355 87.1303 0.818932 -3.09848 26.0799 +24 9227 692.704 679.438 115.998 3.36639 -2.302 29.2138 +25 9227 695.78 682.128 113.624 3.39243 -2.33044 28.3895 +24 9229 606.674 599.12 32.4244 -0.205124 -9.98485 51.3029 +25 9229 607.374 599.915 30.0985 -0.157375 -10.2807 51.9624 +26 9229 608.607 600.461 25.3029 -0.0627917 -9.729 47.5757 +24 9232 690.84 676.103 106.581 2.96256 -2.41556 26.2989 +25 9232 694.572 679.36 103.916 3.002 -2.43436 25.4794 +26 9232 698.487 682.744 100.219 3.0343 -2.47838 24.6196 +24 9236 761.449 728.734 31.3702 2.49392 -2.32307 11.8472 +25 9236 774.584 738.98 19.8785 2.48975 -2.30797 10.886 +24 9239 798.872 766.305 59.9149 3.12248 -1.86279 11.9009 +25 9239 814.439 779.491 51.0772 3.14898 -1.8717 11.09 +26 9239 833.273 795.338 39.6683 3.16768 -1.88584 10.2166 +24 9244 802.109 771.331 124.83 3.36045 -0.838127 12.5925 +25 9244 817.785 784.584 121.375 3.36879 -0.832858 11.6734 +24 9248 760.932 728.325 50.6868 2.49363 -2.01251 11.8862 +25 9248 774.017 738.772 40.8912 2.50644 -2.0112 10.9967 +24 9249 787.995 755.001 64.2377 2.90496 -1.76829 11.7467 +25 9249 803.246 767.817 55.4929 2.93653 -1.77934 10.9394 +24 9250 787.995 755.001 64.2377 2.90496 -1.76829 11.7467 +25 9250 803.246 767.817 55.4929 2.93653 -1.77934 10.9394 +26 9250 821.547 782.714 43.3743 2.93227 -1.791 9.98051 +24 9251 828.105 797.977 96.8149 3.89639 -1.35568 12.8641 +25 9251 845.251 812.8 91.0448 3.90133 -1.35416 11.9434 +24 9252 770.324 737.816 48.8306 2.65645 -2.04934 11.9226 +25 9252 783.684 748.956 38.6429 2.69325 -2.0759 11.1603 +26 9252 799.93 762.2 26.5052 2.71026 -2.08353 10.2724 +24 9254 718.684 689.312 67.6851 1.99566 -1.92332 13.1954 +25 9254 727.277 695.89 59.9467 2.01459 -1.93226 12.3482 +24 9255 773.846 742.982 101.97 2.85921 -1.23366 12.5575 +25 9255 787.695 754.213 96.4002 2.85785 -1.22655 11.5757 +26 9255 802.81 766.869 88.765 2.88818 -1.25673 10.7836 +24 9259 737.019 707.062 93.0607 2.28541 -1.43073 12.9375 +25 9259 746.881 714.585 87.0922 2.28394 -1.42639 12.0006 +26 9259 758.363 723.176 78.831 2.27159 -1.43532 11.0147 +24 9260 776.571 746.377 121.936 2.97118 -0.905849 12.8363 +25 9260 789.935 757.577 117.812 2.99431 -0.913725 11.9778 +26 9260 805.642 770.263 111.555 2.97714 -0.930711 10.9552 +24 9266 842.005 812.489 91.0631 4.23029 -1.48852 13.1313 +25 9266 859.78 828.114 84.8872 4.24447 -1.49217 12.2394 +26 9266 880.222 845.871 76.5551 4.23233 -1.50582 11.2826 +24 9279 1019.05 985.236 47.4614 6.50553 -1.99211 11.4631 +25 9279 1054.19 1017.69 36.7717 6.542 -2.00221 10.6162 +26 9279 1095.24 1055.48 23.1559 6.56237 -2.02268 9.74922 +24 9281 1037.35 1003.26 58.3623 6.74065 -1.80402 11.3691 +25 9281 1073.58 1037.19 48.8004 6.85001 -1.83132 10.6516 +24 9287 1017.15 985.222 93.7542 6.85676 -1.33066 12.1381 +25 9287 1050.17 1015.75 86.3012 6.87647 -1.35079 11.2608 +26 9287 1088.35 1051.35 76.6606 6.95089 -1.39649 10.4749 +24 9294 1015.98 982.398 101.085 6.50019 -1.14784 11.54 +25 9294 1050.5 1014.21 94.8967 6.5275 -1.15405 10.6813 +24 9295 1015.98 982.398 101.085 6.50019 -1.14784 11.54 +25 9295 1050.5 1014.21 94.8967 6.5275 -1.15405 10.6813 +24 9296 1079.4 1044.57 124.995 7.24579 -0.738072 11.1273 +25 9296 1121.68 1083.49 120.477 7.20406 -0.736791 10.15 +24 9301 1039.62 1007.18 94.5803 7.12084 -1.29603 11.947 +25 9301 1076 1040.32 87.9308 7.02285 -1.27863 10.8637 +24 9309 1127.9 1091.55 105.618 7.65975 -0.993588 10.6626 +25 9309 1175.78 1136.52 98.5927 7.7485 -1.01624 9.87402 +24 9311 1151.9 1116.02 113.076 8.11942 -0.894941 10.8022 +25 9311 1202.95 1163.74 107.547 8.12867 -0.894621 9.88413 +24 9312 1123.27 1086.96 114.032 7.59955 -0.870189 10.6741 +25 9312 1171.31 1132.04 108.418 7.6844 -0.881445 9.87021 +24 9319 1154.57 1117.1 85.8273 7.81208 -1.24742 10.3424 +25 9319 1207.36 1166.75 77.6295 7.90567 -1.2593 9.54198 +24 9328 99.2054 86.9231 164.711 -22.3196 -0.356122 31.5554 +25 9328 84.3119 71.1675 164.267 -21.4643 -0.350921 29.4858 +24 9351 267.158 236.822 221.708 -6.06281 0.865046 12.7761 +25 9351 243.729 212.972 225.301 -6.38899 0.915951 12.6012 +24 9352 189.072 159.47 242.349 -7.63007 1.26104 13.0929 +25 9352 160.229 130.872 247.126 -8.22136 1.35895 13.2019 +24 9355 326.318 319.696 186.79 -22.9782 1.13058 58.5352 +25 9355 323.243 315.746 185.899 -20.5143 0.934693 51.6976 +24 9356 405.326 394.935 213.507 -10.5585 2.10168 37.3021 +25 9356 401.442 390.933 214.114 -10.6374 2.1089 36.8797 +26 9356 397.382 386.575 213.629 -10.5462 2.02673 35.8639 +24 9359 489.8 479.851 145.109 -6.46582 -1.49797 38.956 +25 9359 487.94 477.958 144.216 -6.54485 -1.54114 38.8289 +26 9359 485.948 475.644 142.075 -6.44396 -1.60452 37.6144 +24 9360 476.865 467.413 208.709 -7.54094 2.03764 41.0046 +25 9360 474.92 465.14 208.75 -7.39438 1.97139 39.6268 +24 9363 531.421 517.928 220.221 -3.11064 1.88563 28.7239 +25 9363 529.818 516.312 221.14 -3.17134 1.92036 28.696 +26 9363 528.11 514.087 221.409 -3.11999 1.85994 27.6391 +24 9364 545.596 538.921 196.296 -5.14735 1.88644 58.0647 +25 9364 545.49 538.775 196.278 -5.12538 1.87388 57.7211 +26 9364 545.2 538.134 195.332 -4.89248 1.70878 54.8503 +24 9365 518.677 510.18 175.049 -5.74507 0.138758 45.6116 +25 9365 517.614 509.379 174.706 -5.99735 0.120802 47.0642 +26 9365 516.309 507.981 173.11 -6.01432 0.0164836 46.5367 +24 9367 506.911 499.557 193.27 -7.49789 1.4913 52.7043 +25 9367 505.897 500.366 193.422 -10.0669 1.99744 70.0707 +24 9370 593.653 578.709 221.701 -0.571768 1.75583 25.9361 +25 9370 593.947 578.61 223.094 -0.546831 1.75964 25.2716 +24 9372 613.979 595.836 231.186 0.130844 1.72705 21.3626 +25 9372 615.135 596.201 233.435 0.15817 1.71867 20.4697 +24 9373 694.77 674.596 185.387 2.2688 0.333692 19.2115 +25 9373 699.394 679.219 185.046 2.39187 0.324603 19.2111 +26 9373 705.516 683.357 183.237 2.32602 0.251698 17.4902 +24 9375 588.53 583.174 149.916 -2.10895 -2.30038 72.3616 +25 9375 589.099 583.335 149.163 -1.90663 -2.20768 67.2379 +26 9375 589.783 584.015 147.539 -1.8416 -2.35741 67.191 +24 9376 588.53 583.174 149.916 -2.10895 -2.30038 72.3616 +25 9376 589.099 583.335 149.163 -1.90663 -2.20768 67.2379 +26 9376 589.783 584.015 147.539 -1.8416 -2.35741 67.191 +24 9378 817.016 800.065 172.437 6.57414 -0.0132111 22.865 +25 9378 825.805 808.729 172.021 6.80223 -0.0261886 22.6967 +24 9381 719.838 692.18 246.249 2.14175 1.42543 14.0132 +25 9381 727.667 698.902 250.176 2.20554 1.4439 13.4739 +24 9386 780.017 752.035 148.812 3.27209 -0.461499 13.8505 +25 9386 791.724 762.234 145.75 3.31804 -0.493694 13.1425 +24 9390 713.776 693.259 192.261 2.72844 0.50808 18.8903 +25 9390 720.051 697.116 192.834 2.58778 0.467944 16.8989 +24 9391 906.987 900.311 140.297 23.9301 -2.61946 58.0525 +25 9391 912.554 906.106 139.718 25.241 -2.7604 60.1077 +24 9397 851.154 846.455 128.418 27.6173 -5.07955 82.4806 +25 9397 854.837 850.254 127.662 28.7451 -5.29618 84.5598 +26 9397 858.65 854.045 125.704 29.0561 -5.49995 84.1664 +24 9400 836.54 819.52 168.008 7.16351 -0.152943 22.7718 +25 9400 847.161 829.531 167.479 7.23932 -0.163773 21.984 +26 9400 858.157 839.304 165.82 7.08291 -0.200412 20.5577 +24 9402 896.481 852.779 199.517 3.5266 0.32772 8.86853 +25 9402 928.406 880.586 202.55 3.58155 0.333567 8.10491 +26 9402 969.865 913.525 205.868 3.43516 0.314752 6.87916 +24 9403 898.136 848.98 211.149 3.15341 0.418472 7.88457 +25 9403 934.159 880.292 215.28 3.23683 0.423057 7.19499 +26 9403 977.839 917.281 218.944 3.26665 0.408819 6.40006 +24 9404 878.756 827.244 219.632 2.80711 0.487785 7.52402 +25 9404 915.055 855.316 225.165 2.74692 0.470364 6.48785 +26 9404 961.461 893.097 230.91 2.76495 0.456153 5.66924 +24 9413 1088.12 1052.65 154.129 7.24672 -0.283546 10.926 +25 9413 1131.57 1093.03 152.12 7.27483 -0.28895 10.0555 +24 9415 1008.79 949.565 246.23 3.62064 0.665445 6.54358 +25 9415 1071.27 1002.95 256.136 3.63027 0.654823 5.67325 +24 9423 1162.98 1127.14 146.108 8.29334 -0.400804 10.8126 +25 9423 1213.74 1175.67 144.405 8.52509 -0.401423 10.181 +24 9425 1154.68 1118.22 137.145 8.02935 -0.525974 10.6278 +25 9425 1206.02 1166.47 133.927 8.10082 -0.528693 9.79956 +24 9426 1138.93 1102.68 145.652 7.84321 -0.403027 10.6903 +25 9426 1187.49 1149.32 143.067 8.13278 -0.419167 10.1537 +24 9431 1141.11 1105.89 179.345 8.107 0.0990045 11.0046 +25 9431 1186.11 1149.89 178.524 8.55234 0.0841123 10.7031 +24 9432 113.037 84.2076 255.569 -9.25106 1.54112 13.4435 +25 9432 80.0081 49.5585 260.929 -9.34161 1.55369 12.7284 +26 9432 42.6837 10.2502 265.695 -9.38836 1.53759 11.9498 +24 9438 272.311 242.179 259.622 -6.01196 1.54677 12.8625 +25 9438 249.279 217.166 265.733 -6.02645 1.55359 12.0692 +24 9439 251.717 221.353 271.296 -6.33025 1.74144 12.7641 +25 9439 226.978 194.479 277.982 -6.32337 1.73758 11.9257 +24 9440 251.717 221.353 271.296 -6.33025 1.74144 12.7641 +25 9440 226.978 194.479 277.982 -6.32337 1.73758 11.9257 +24 9441 208.747 177.623 278.923 -6.91725 1.83055 12.4524 +25 9441 180.301 146.416 286.544 -6.80466 1.80224 11.4379 +24 9442 231.128 194.389 295.049 -5.53296 1.78659 10.5494 +25 9442 198.73 158.999 305.572 -5.55417 1.79427 9.75477 +24 9450 295.231 258.025 295.361 -4.53809 1.76868 10.4171 +25 9450 268.066 227.746 305.951 -4.54943 1.77314 9.61246 +26 9450 236.186 191.911 317.069 -4.52979 1.74963 8.75374 +24 9451 381.693 337.817 316.194 -2.78968 1.75485 8.83349 +25 9451 358.181 309.577 331.154 -2.77811 1.74945 7.97409 +24 9456 376.264 330.356 319.857 -2.72974 1.72004 8.44256 +25 9456 350.954 300.397 336.189 -2.74759 1.73538 7.66608 +24 9464 733.39 704.18 255.992 2.27712 1.52883 13.2683 +25 9464 743.426 711.84 261.458 2.27648 1.50677 12.2701 +24 9468 748.592 710.933 287.86 1.98309 1.6404 10.2917 +25 9468 762.441 721.315 298.053 1.99682 1.63525 9.42416 +24 9471 763.654 724.772 290.915 2.1288 1.631 9.96798 +25 9471 778.876 736.796 301.363 2.16134 1.64043 9.21049 +26 9471 797.38 750.773 313.005 2.16464 1.61524 8.31573 +24 9474 824.378 771.704 306.051 2.19067 1.35831 7.35807 +25 9474 854.163 794.667 323.276 2.20835 1.35805 6.51426 +24 9476 943.983 883.279 256.882 2.95924 0.743543 6.38474 +25 9476 997.52 927.496 269.836 2.97602 0.743939 5.53486 +26 9476 1069.59 986.734 286.296 2.98247 0.735472 4.67791 +24 9480 882.139 823.005 343.337 2.476 1.54859 6.55413 +25 9480 924.487 856.638 369.15 2.49322 1.55403 5.71228 +24 9481 857.26 797.889 255.9 2.24105 0.751351 6.52805 +25 9481 897.241 827.698 268.934 2.22207 0.742127 5.57322 +24 9485 959.791 899.609 259.936 3.12595 0.777238 6.43999 +25 9485 1016.02 946.144 273.298 3.1244 0.772094 5.54629 +26 9485 1092.61 1009.47 290.12 3.121 0.757664 4.6619 +24 9490 1093.55 1046.88 289.668 5.5698 1.3443 8.30348 +25 9490 1152.36 1100.72 303.296 5.64643 1.35692 7.50577 +24 9496 1006.28 947.854 303.281 3.64749 1.19917 6.63395 +25 9496 1067.78 1000.62 324.006 3.66495 1.20895 5.77104 +25 9514 605.801 597.97 39.5034 -0.257756 -9.14612 49.4881 +26 9514 606.641 598.241 35.7882 -0.186577 -8.76434 46.137 +25 9518 361.8 343.561 236.798 -7.29666 1.88317 21.2497 +26 9518 354.087 334.607 239.888 -7.04414 1.84834 19.895 +25 9521 1137.72 1099.18 145.11 7.36291 -0.386778 10.0588 +26 9521 1189.66 1147.79 141.002 7.4421 -0.408629 9.25656 +25 9523 385.661 346.389 299.758 -3.06238 1.73574 9.86887 +26 9523 365.564 322.596 310.185 -3.0502 1.71679 9.02 +25 9527 431.97 404.448 262.136 -3.46611 1.74256 14.0826 +26 9527 421.788 392.871 266.194 -3.48799 1.73385 13.4031 +25 9528 615.586 589.223 258.417 0.122792 1.74341 14.7018 +26 9528 617.163 588.737 263.065 0.143682 1.70467 13.6344 +25 9532 908.289 840.145 305.686 2.35478 1.04707 5.68762 +26 9532 964.2 882.829 327.959 2.34107 1.02388 4.76305 +25 9548 265.969 226.675 99.3738 -4.69686 -1.00447 9.86337 +26 9548 234.726 190.969 90.9633 -4.60126 -1.00525 8.85724 +25 9552 209.873 169.305 100.157 -5.2921 -0.962556 9.55361 +26 9552 171.743 128.059 92.0125 -5.38349 -0.994046 8.87219 +25 9554 155.767 115.451 73.7156 -6.04608 -1.32087 9.61338 +26 9554 113.411 70.0676 63.5948 -6.14879 -1.35405 8.94204 +25 9555 232.076 191.97 41.7339 -5.05576 -1.75613 9.66379 +26 9555 196.811 151.446 26.7146 -4.88722 -1.73039 8.5435 +25 9558 362.984 324.508 42.7963 -3.44236 -1.81569 10.0732 +26 9558 341.621 299.478 29.2055 -3.41506 -1.8309 9.1965 +25 9559 304.217 265.292 74.537 -4.21366 -1.35675 9.95707 +26 9559 276.035 234.042 64.1938 -4.26617 -1.38989 9.22933 +25 9560 337.04 299.062 84.7901 -3.8544 -1.24554 10.2051 +26 9560 313.432 272.92 75.3974 -3.92632 -1.29217 9.56679 +25 9563 295.773 257.82 89.1942 -4.44107 -1.18405 10.212 +26 9563 267.988 226.188 79.8266 -4.38937 -1.19545 9.27214 +25 9564 332.081 293.723 89.8222 -3.88568 -1.16274 10.1041 +26 9564 307.818 265.876 80.0158 -3.86442 -1.18898 9.24077 +25 9566 293.992 255.518 98.8299 -4.40569 -1.03347 10.0735 +26 9566 266.139 223.729 90.34 -4.34963 -1.04509 9.13871 +25 9567 350.048 311.611 38.6236 -3.62665 -1.87585 10.0834 +26 9567 327.719 281.89 25.0815 -3.30341 -1.73202 8.45704 +25 9572 291.011 251.956 117.739 -4.38125 -0.758043 9.92389 +26 9572 261.948 220.372 111.805 -4.491 -0.788729 9.32199 +25 9579 504.66 495.789 50.2082 -6.35172 -7.42631 43.6897 +26 9579 503.088 494.256 46.5506 -6.47481 -7.68089 43.8789 +25 9580 505.303 496.6 55.3746 -6.43471 -7.25082 44.5333 +26 9580 503.825 494.845 51.8175 -6.32441 -7.23971 43.1582 +25 9586 523.28 515.062 98.881 -5.63986 -4.83543 47.165 +26 9586 522.33 514.187 96.2475 -5.75408 -5.05336 47.5963 +25 9587 452.92 441.863 118.874 -7.60899 -2.62216 35.0499 +26 9587 449.766 438.558 115.552 -7.6579 -2.74612 34.5789 +25 9588 549.359 541.726 101.481 -4.23665 -5.0229 50.7786 +26 9588 549.184 541.393 98.8415 -4.16302 -5.1033 49.7514 +25 9589 507.196 497.665 114.207 -5.76926 -3.30535 40.6661 +26 9589 505.986 494.862 111.55 -5.00119 -2.96015 34.8404 +25 9592 603.232 595.698 20.4713 -0.451157 -10.8649 51.4455 +26 9592 603.887 596.165 16.2026 -0.394557 -10.8969 50.1914 +25 9594 598.064 590.258 26.4085 -0.791107 -10.078 49.6545 +26 9594 598.343 590.669 22.1217 -0.785146 -10.5512 50.5072 +25 9595 615.858 608.099 27.3764 0.436028 -10.071 49.9502 +26 9595 616.784 608.923 23.3014 0.493665 -10.2192 49.3041 +25 9596 655.82 640.658 26.6337 1.63884 -5.18 25.5612 +26 9596 658.265 643.321 20.3206 1.75066 -5.48264 25.9349 +25 9598 633.163 619.355 46.5832 0.918201 -4.91209 28.0687 +26 9598 635.168 620.618 41.8698 0.945451 -4.83589 26.6389 +25 9600 583.763 575.751 40.7319 -1.72958 -8.85834 48.3767 +26 9600 583.914 576.219 36.7215 -1.79004 -9.50206 50.3634 +25 9601 625.855 609.327 82.6791 0.529616 -2.93071 23.4501 +26 9601 626.948 609.843 77.8986 0.546072 -2.98198 22.6591 +25 9602 569.955 562.309 65.1523 -2.78243 -7.56668 50.6923 +26 9602 570.129 562.37 62.096 -2.73005 -7.66851 49.9569 +25 9604 677.964 662.99 104.231 2.45391 -2.46176 25.8842 +26 9604 681.041 665.102 100.467 2.40902 -2.43952 24.3167 +25 9606 662.674 652.793 123.43 2.8875 -2.68683 39.2253 +26 9606 664.526 654.289 120.407 2.88406 -2.75182 37.8584 +25 9608 621.657 607.436 64.5543 0.456958 -4.09089 27.2552 +26 9608 622.49 607.634 59.3606 0.467525 -4.10334 26.0871 +25 9613 814.439 779.491 51.0772 3.14898 -1.8717 11.09 +26 9613 833.273 795.338 39.6683 3.16768 -1.88584 10.2166 +25 9614 799.033 763.962 59.5681 2.90195 -1.73506 11.0509 +26 9614 816.135 778.11 48.4308 2.91813 -1.75763 10.1926 +25 9615 832.785 798.59 70.9513 3.50654 -1.60074 11.3343 +26 9615 852.329 815.459 61.1208 3.53686 -1.62782 10.5119 +25 9618 774.35 741.528 109.159 2.69688 -1.04239 11.8083 +26 9618 788.413 752.842 102.72 2.70081 -1.05906 10.8957 +25 9620 800.74 766.577 121.972 3.00596 -0.800025 11.3448 +26 9620 816.38 781.403 116.316 3.17621 -0.86827 11.0809 +25 9622 728.896 697.449 43.2024 2.03838 -2.21456 12.3245 +26 9622 739.42 704.378 31.7928 1.99059 -2.16227 11.0601 +25 9624 771.847 737.571 84.4219 2.54325 -1.38584 11.3074 +26 9624 786.237 748.993 75.526 2.54812 -1.4037 10.4063 +25 9626 820.049 783.79 34.8822 3.1182 -2.04391 10.6888 +26 9626 839.459 800.069 21.7591 3.13511 -2.06046 9.83951 +25 9630 818.247 782.466 46.1956 3.1329 -1.90144 10.832 +26 9630 837.845 798.435 32.4013 3.11153 -1.91437 9.83456 +25 9632 725.68 694.472 79.2089 1.99871 -1.61186 12.4194 +26 9632 733.746 701.894 70.3136 2.09425 -1.72921 12.1678 +25 9639 696.112 671.738 65.1298 1.90743 -2.37401 15.9012 +26 9639 700.961 680.596 59.3206 2.41082 -2.99458 19.0314 +25 9652 926.016 916.861 93.5372 18.5673 -4.6537 42.3343 +26 9652 932.37 922.898 88.5975 18.3058 -4.77798 40.9167 +25 9673 1087.19 1048.38 103.507 6.61203 -0.960005 9.98864 +26 9673 1136.18 1090.89 96.0759 6.24651 -0.910707 8.55855 +25 9681 1131.2 1093.06 87.6072 7.34729 -1.2007 10.1629 +26 9681 1182.2 1140.75 78.1433 7.42087 -1.22736 9.35042 +25 9690 1162.68 1124.2 122.173 7.72253 -0.707595 10.074 +26 9690 1218.32 1175.53 115.58 7.64225 -0.719011 9.05808 +25 9699 96.8181 66.7475 245.652 -9.15909 1.3004 12.8888 +26 9699 62.0669 29.7548 248.979 -9.10141 1.26549 11.9947 +25 9708 168.818 134.174 159.266 -6.83353 -0.210672 11.1872 +26 9708 133.357 95.4471 156.629 -6.74727 -0.229884 10.2234 +25 9711 259.346 226.975 227.13 -5.8114 0.900645 11.9731 +26 9711 233.261 198.281 229.877 -5.77841 0.875635 11.0799 +25 9712 238.874 206.437 244.621 -6.13863 1.18848 11.9488 +26 9712 211.521 176.727 248.646 -6.14502 1.1701 11.1393 +25 9726 285.534 269.971 243.007 -11.1839 2.42134 24.9041 +26 9726 275.477 258.12 244.169 -10.339 2.20702 22.3297 +25 9728 431.314 422.373 198.194 -10.7084 1.52237 43.3475 +26 9728 428.489 419.324 197.314 -10.6119 1.43354 42.2867 +25 9731 448.721 437.906 135.88 -7.98848 -1.83641 35.8371 +26 9731 445.556 434.418 133.379 -7.90924 -1.90373 34.7969 +25 9732 580.863 575.269 127.849 -2.75539 -4.32138 69.2818 +26 9732 581.576 575.431 125.608 -2.44614 -4.12996 63.0719 +25 9734 579.007 575.196 166.919 -4.30584 -0.836488 101.69 +26 9734 579.449 575.431 165.327 -4.02534 -1.00627 96.4594 +25 9735 572.032 558.365 221.246 -1.47494 1.90193 28.3586 +26 9735 571.82 557.41 221.359 -1.40672 1.80802 26.8955 +25 9737 641.108 621.46 230.556 0.862508 1.57753 19.7263 +26 9737 643.312 623.141 231.589 0.898845 1.56415 19.2149 +25 9743 615.762 609.846 183.061 0.563154 0.926759 65.51 +26 9743 617.468 613.042 181.588 0.959683 1.05982 87.5502 +25 9749 713.062 690.425 250.812 2.45592 1.84978 17.1207 +26 9749 720.13 693.046 254.026 2.19291 1.60985 14.3099 +25 9760 758.197 733.225 205.292 3.19728 0.697755 15.5207 +26 9760 767.387 741.758 205.785 3.30779 0.690168 15.1221 +25 9762 738.727 710.22 239.02 2.43391 1.24677 13.596 +26 9762 748.517 718.031 241.204 2.44836 1.20429 12.7131 +25 9763 754.705 732.121 188.609 3.45235 0.374743 17.1621 +26 9763 761.982 740.926 186.912 3.88852 0.35864 18.4075 +25 9765 882.36 868.164 141.565 10.3219 -1.18389 27.3006 +26 9765 892.332 877.646 139.123 10.3423 -1.23369 26.3898 +25 9767 835.926 818.799 162.684 7.09947 -0.318973 22.6293 +26 9767 846.203 828.358 160.85 7.12312 -0.36134 21.7187 +25 9791 1019.42 981.512 187.77 5.80828 0.211386 10.2253 +26 9791 1058.71 1017.44 187.782 5.84678 0.194321 9.39263 +25 9800 1146.57 1108.47 155.845 7.57165 -0.239826 10.1735 +26 9800 1199.89 1157.99 152.836 7.56896 -0.256661 9.2513 +25 9801 1176.39 1137.96 162.48 7.92279 -0.145007 10.0853 +26 9801 1234.02 1191.06 160.1 7.80823 -0.159472 9.02204 +25 9802 1154.19 1115.66 171.278 7.59383 -0.0219808 10.0605 +26 9802 1208.64 1166.48 169.428 7.63334 -0.0436528 9.19371 +25 9813 1171.14 1132.47 144.377 7.801 -0.395582 10.0229 +26 9813 1227.57 1185.3 140.186 7.85473 -0.415204 9.17058 +25 9821 104.814 74.1446 270.95 -8.84023 1.71807 12.6372 +26 9821 69.7365 37.2654 276.47 -8.92997 1.71405 11.936 +25 9826 176.456 135.716 312.375 -5.71048 1.83959 9.51349 +26 9826 134.774 90.3549 324.379 -5.74154 1.83238 8.72549 +25 9829 194.997 143.189 341.327 -4.29822 1.74674 7.48098 +26 9829 143.36 85.0604 361.472 -4.29536 1.73784 6.64794 +25 9833 275.817 244.233 259.628 -5.67596 1.47577 12.2712 +26 9833 251.75 218.293 264.311 -5.74461 1.46834 11.5842 +25 9835 141.494 108.961 287.503 -7.72823 1.89297 11.9133 +26 9835 106.14 70.7041 294.45 -7.63098 1.84319 10.9373 +25 9838 238.044 205.953 256.259 -6.21848 1.39605 12.0772 +26 9838 210.894 176.03 261.12 -6.14219 1.3599 11.1166 +25 9841 330.17 301.096 261.811 -5.16177 1.64349 13.3305 +26 9841 312.076 280.97 266.726 -5.13697 1.62099 12.4596 +25 9842 336.181 306.039 266.139 -4.87174 1.66239 12.8582 +26 9842 317.813 285.247 271.154 -4.81213 1.62138 11.9012 +25 9843 278.378 240.427 293.05 -4.68748 1.70123 10.2125 +26 9843 249.596 208.165 302.194 -4.66693 1.67689 9.35475 +25 9844 279.932 240.166 298.634 -4.4526 1.69903 9.74652 +26 9844 249.392 206.355 309.042 -4.49533 1.69979 9.00567 +25 9845 385.661 346.389 299.758 -3.06238 1.73574 9.86887 +26 9845 365.564 322.596 310.185 -3.0502 1.71679 9.02 +25 9847 325.886 275.149 339.284 -3.00327 1.76201 7.63897 +26 9847 292.086 234.85 358.303 -2.97945 1.74042 6.77155 +25 9854 345.638 315.592 269.366 -4.71835 1.72542 12.8995 +26 9854 327.311 295.274 274.298 -4.73242 1.7009 12.0979 +25 9859 540.4 515.563 253.729 -1.49572 1.74909 15.6048 +26 9859 537.412 510.903 256.795 -1.4619 1.70088 14.6203 +25 9862 632.417 587.793 309.791 0.275147 1.64833 8.68528 +26 9862 636.051 586.186 322.877 0.28537 1.61605 7.77241 +25 9866 602.745 552.242 330.347 -0.0724834 1.67512 7.67441 +26 9866 603.558 546.102 348.864 -0.0561072 1.64551 6.74563 +25 9883 840.323 782.748 280.133 2.15291 1.00086 6.73158 +26 9883 875.803 809.235 294.44 2.14837 0.981103 5.82224 +25 9884 840.323 782.748 280.133 2.15291 1.00086 6.73158 +26 9884 875.803 809.235 294.44 2.14837 0.981103 5.82224 +25 9889 910.731 841.986 281.457 2.35324 0.848585 5.63782 +26 9889 966.193 884.935 299.069 2.35749 0.834331 4.76965 +25 9897 1027.81 957.746 273.305 3.20645 0.770086 5.53152 +26 9897 1105.84 1022.96 289.994 3.21647 0.759204 4.67639 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/example.graph b/examples/Data/example.graph new file mode 100644 index 000000000..28034c69d --- /dev/null +++ b/examples/Data/example.graph @@ -0,0 +1,611 @@ +VERTEX2 0 -0.13824042322 0.342115061624 -0.21557075232 +VERTEX2 1 0.612650361503 0.369015313751 -0.0563461272597 +VERTEX2 2 1.45479903751 0.32013063469 0.00237213120454 +VERTEX2 3 2.15898096669 0.470294509791 0.2252884021 +VERTEX2 4 2.88516818219 0.975843235486 0.663228096686 +VERTEX2 5 3.54878752013 1.42348114163 0.514657357344 +VERTEX2 6 4.32268502365 1.77291535029 0.359562734992 +VERTEX2 7 5.08813168428 2.06549657048 0.478125988701 +VERTEX2 8 5.82496111116 2.35969982503 0.422228187736 +VERTEX2 9 6.60694009323 2.69135662887 0.387034318241 +VERTEX2 10 7.23925137037 3.104611283 0.512008508154 +VERTEX2 11 7.88977565307 3.52369876229 0.510071235528 +VERTEX2 12 8.46649417534 4.12269969397 0.748925805491 +VERTEX2 13 9.02278033295 4.72424791132 0.856233672115 +VERTEX2 14 9.51752434143 5.39695844275 0.935937098771 +VERTEX2 15 10.0446733918 5.98414466425 0.827804203493 +VERTEX2 16 10.7598348236 6.44960011929 0.66804473602 +VERTEX2 17 11.5972376522 6.80537766408 0.434941288594 +VERTEX2 18 12.2250075039 7.20442152894 0.60418193616 +VERTEX2 19 12.8678138507 7.70255061643 0.721822794329 +VERTEX2 20 13.5570195199 8.15843137362 0.593196573979 +VERTEX2 21 14.105649437 8.68489938394 0.640245465981 +VERTEX2 22 14.8224385492 9.03493116691 0.389518546051 +VERTEX2 23 15.5843623557 9.40302979333 0.425220242351 +VERTEX2 24 16.2288322902 9.91680608172 0.666877924504 +VERTEX2 25 16.7734636078 10.4312050251 0.681531027672 +VERTEX2 26 17.4387968671 11.005129183 0.768715640688 +VERTEX2 27 17.7890621789 11.6956218678 1.10988383528 +VERTEX2 28 18.1363236735 12.3803438454 1.15258075093 +VERTEX2 29 18.5588734995 13.1408718358 1.04155126412 +VERTEX2 30 18.9922514403 13.8160705369 0.971438456359 +VERTEX2 31 19.4325629424 14.4733850988 0.934520345955 +VERTEX2 32 19.9599388848 15.0464180472 0.877139653946 +VERTEX2 33 20.5469053533 15.5710340353 0.832297735476 +VERTEX2 34 21.2487400511 16.0027088196 0.400422858988 +VERTEX2 35 22.0354445454 16.279918955 0.319643226898 +VERTEX2 36 22.791287229 16.5499150181 0.433961446308 +VERTEX2 37 23.5369676303 16.8796783232 0.412377133313 +VERTEX2 38 24.3284326258 17.0889935946 0.247486633995 +VERTEX2 39 25.022695509 17.4036693591 0.418515661559 +VERTEX2 40 25.833691896 17.5333774597 0.242076471575 +VERTEX2 41 26.509920511 17.8164161072 0.330656267986 +VERTEX2 42 27.2102127101 18.1210604608 0.510746644634 +VERTEX2 43 27.9408557181 18.4814891494 0.453985699035 +VERTEX2 44 28.6169766716 18.8182098691 0.458777942952 +VERTEX2 45 29.4313889637 19.1357097768 0.315177512361 +VERTEX2 46 30.0878533291 19.5935012258 0.599592761269 +VERTEX2 47 30.6308494244 20.2191621501 0.791897780929 +VERTEX2 48 31.2734501775 20.7120615592 0.660037247468 +VERTEX2 49 31.9206533665 21.0772297685 0.5072035147 +VERTEX2 50 32.6763238236 21.4307681859 0.454485923064 +VERTEX2 51 33.3148481476 21.8561680514 0.60984431497 +VERTEX2 52 34.1013046603 22.2191493052 0.390376111344 +VERTEX2 53 34.8953983726 22.3514742253 0.21440693077 +VERTEX2 54 35.5398222802 22.7545971294 0.615814590831 +VERTEX2 55 36.0796597873 23.3482683055 0.770181973449 +VERTEX2 56 36.7331436274 23.8425596089 0.686311813947 +VERTEX2 57 37.3595434784 24.3051907322 0.642633326683 +VERTEX2 58 37.9821262299 24.7824436801 0.670645829824 +VERTEX2 59 38.5783823068 25.3597188555 0.700563120761 +VERTEX2 60 39.1778265015 25.9111323369 0.739828088912 +VERTEX2 61 39.7774314984 26.468354909 0.760112883167 +VERTEX2 62 40.5142302821 26.7603415627 0.360997494201 +VERTEX2 63 41.3046572615 26.9763392108 0.294108606273 +VERTEX2 64 42.0961911474 26.9894909267 0.0261721941131 +VERTEX2 65 42.8993485692 27.0228858541 -0.0101699718322 +VERTEX2 66 43.7802018787 26.9183386714 -0.14998582283 +VERTEX2 67 44.4852457598 26.6914007663 -0.229610091357 +VERTEX2 68 45.2817862376 26.3996944287 -0.403989633144 +VERTEX2 69 45.9356734923 26.0051290697 -0.524619871446 +VERTEX2 70 46.6446168067 25.600148756 -0.514124183817 +VERTEX2 71 47.3746747907 25.2783070597 -0.393217999666 +VERTEX2 72 48.0468975618 24.858529404 -0.611511747817 +VERTEX2 73 48.5985868491 24.2739248983 -0.750544536918 +VERTEX2 74 49.0527438314 23.5710791408 -0.961680491481 +VERTEX2 75 49.2855884713 22.8045393649 -1.26366594654 +VERTEX2 76 49.5531551426 22.07091907 -1.20968280224 +VERTEX2 77 49.7661651916 21.2825192392 -1.31976079475 +VERTEX2 78 50.0808782733 20.5442674319 -1.12044697254 +VERTEX2 79 50.2411613948 19.8192859683 -1.32310987107 +VERTEX2 80 50.593374374 19.0401532836 -1.19010897017 +VERTEX2 81 50.7996996995 18.2237817778 -1.25581427155 +VERTEX2 82 51.1212445439 17.5292614731 -1.12361470203 +VERTEX2 83 51.4506022502 16.8176851053 -1.26886160199 +VERTEX2 84 51.6718980908 16.0314246481 -1.20207903627 +VERTEX2 85 51.7763413724 15.2475638806 -1.37580476659 +VERTEX2 86 51.7436299376 14.470393643 -1.57551900737 +VERTEX2 87 51.7823620936 13.662469339 -1.58332101723 +VERTEX2 88 51.7876820152 12.8254876297 -1.54396226933 +VERTEX2 89 51.8506699031 12.0601624148 -1.49704318637 +VERTEX2 90 52.1025342746 11.3090918983 -1.27677489091 +VERTEX2 91 52.3751696328 10.5860629809 -1.18997203951 +VERTEX2 92 52.7492358918 9.85554108611 -1.06464614342 +VERTEX2 93 53.0454987108 9.0309169672 -1.09735731166 +VERTEX2 94 53.5294752309 8.30487726603 -0.996640361599 +EDGE2 0 1 0.717448855412 0.179994080198 0.13818539933 1 0 1 1 0 0 +EDGE2 1 2 0.837626285811 -0.00455175621601 0.0472991985156 1 0 1 1 0 0 +EDGE2 2 3 0.730277063669 0.138122839345 0.195071775287 1 0 1 1 0 0 +EDGE2 3 4 0.820088167497 0.330077088561 0.419082044433 1 0 1 1 0 0 +EDGE2 4 5 0.751370583006 -0.0273254868576 -0.228659037893 1 0 1 1 0 0 +EDGE2 5 6 0.840179304794 -0.0492096503989 -0.165641208116 1 0 1 1 0 0 +EDGE2 6 7 0.834845292082 0.0123885559434 0.125976751144 1 0 1 1 0 0 +EDGE2 7 8 0.787371504945 -0.0559773501633 -0.0755976318713 1 0 1 1 0 0 +EDGE2 8 9 0.927708591397 -0.0476716890116 -0.00287962007188 1 0 1 1 0 0 +EDGE2 9 10 0.730378261921 0.17317279657 0.138282893502 1 0 1 1 0 0 +EDGE2 10 11 0.779303803898 0.0853449755561 0.0323688320359 1 0 1 1 0 0 +EDGE2 11 12 0.78273752447 0.300201637472 0.246750324389 1 0 1 1 0 0 +EDGE2 12 13 0.791566966819 0.0845024659404 0.0706094824868 1 0 1 1 0 0 +EDGE2 13 14 0.839568888481 0.0868682543031 0.0707684617219 1 0 1 1 0 0 +EDGE2 14 15 0.773151053081 -0.0593185180517 -0.155366269405 1 0 1 1 0 0 +EDGE2 15 16 0.865064493339 -0.175806171924 -0.17949133873 1 0 1 1 0 0 +EDGE2 16 17 0.911877312319 -0.185936696416 -0.268755813818 1 0 1 1 0 0 +EDGE2 17 18 0.770300068296 0.126048087534 0.188926402795 1 0 1 1 0 0 +EDGE2 18 19 0.836050157131 0.0586909108092 0.103845037354 1 0 1 1 0 0 +EDGE2 19 20 0.802346917562 -0.147928636285 -0.093306893258 1 0 1 1 0 0 +EDGE2 20 21 0.757849343112 0.0715772513539 0.124155654615 1 0 1 1 0 0 +EDGE2 21 22 0.775750933534 -0.196756273535 -0.298936959752 1 0 1 1 0 0 +EDGE2 22 23 0.871271438269 0.0573046191775 0.0353456305698 1 0 1 1 0 0 +EDGE2 23 24 0.811030742162 0.182063773111 0.250823572639 1 0 1 1 0 0 +EDGE2 24 25 0.746714037369 0.0325617212022 -0.0276665993655 1 0 1 1 0 0 +EDGE2 25 26 0.86122739728 -0.00477108497939 0.0654936733039 1 0 1 1 0 0 +EDGE2 26 27 0.743470468243 0.258017697 0.326840047412 1 0 1 1 0 0 +EDGE2 27 28 0.767611305804 -0.0194473809016 0.015974781367 1 0 1 1 0 0 +EDGE2 28 29 0.862923844436 -0.072552727637 -0.101230904939 1 0 1 1 0 0 +EDGE2 29 30 0.798343874527 -0.0100123616381 -0.0690217895568 1 0 1 1 0 0 +EDGE2 30 31 0.797880458664 0.010391602905 -0.0148972103321 1 0 1 1 0 0 +EDGE2 31 32 0.7909503515 -0.129294597268 -0.0650424809131 1 0 1 1 0 0 +EDGE2 32 33 0.842504611493 -0.175416599555 -0.0602555708183 1 0 1 1 0 0 +EDGE2 33 34 0.850215628436 -0.25776734023 -0.430013888881 1 0 1 1 0 0 +EDGE2 34 35 0.878503147997 -0.0904880193607 -0.110294282873 1 0 1 1 0 0 +EDGE2 35 36 0.856359797661 -0.00248016167379 0.151938705998 1 0 1 1 0 0 +EDGE2 36 37 0.832014541489 -0.0130179735184 0.0190247158611 1 0 1 1 0 0 +EDGE2 37 38 0.79003682341 -0.11167056714 -0.209191335194 1 0 1 1 0 0 +EDGE2 38 39 0.773095034914 0.115088515991 0.198916260227 1 0 1 1 0 0 +EDGE2 39 40 0.868778586384 -0.268010831047 -0.216977740006 1 0 1 1 0 0 +EDGE2 40 41 0.747080875885 0.111312520032 0.12949742181 1 0 1 1 0 0 +EDGE2 41 42 0.778805446629 0.021318220948 0.192566907397 1 0 1 1 0 0 +EDGE2 42 43 0.805554382015 0.0232777384249 -0.0694087339945 1 0 1 1 0 0 +EDGE2 43 44 0.813443633444 0.0640947959252 0.0147897258654 1 0 1 1 0 0 +EDGE2 44 45 0.880420396037 -0.0605322428822 -0.144031989178 1 0 1 1 0 0 +EDGE2 45 46 0.827332486742 0.280288429131 0.328067436679 1 0 1 1 0 0 +EDGE2 46 47 0.815610897482 0.224126154957 0.19211589295 1 0 1 1 0 0 +EDGE2 47 48 0.829375613726 -0.13990131371 -0.15863308512 1 0 1 1 0 0 +EDGE2 48 49 0.756790221176 -0.0537543626573 -0.14995378239 1 0 1 1 0 0 +EDGE2 49 50 0.864033920652 -0.060820449151 -0.0470197844462 1 0 1 1 0 0 +EDGE2 50 51 0.747576670836 0.115572803882 0.111904734712 1 0 1 1 0 0 +EDGE2 51 52 0.801571192348 -0.200227517424 -0.271734247998 1 0 1 1 0 0 +EDGE2 52 53 0.783342882846 -0.216604931502 -0.232376474041 1 0 1 1 0 0 +EDGE2 53 54 0.716633103688 0.208120785595 0.398955080153 1 0 1 1 0 0 +EDGE2 54 55 0.773727687761 0.144824498948 0.159143610152 1 0 1 1 0 0 +EDGE2 55 56 0.779100726172 -0.140449927137 -0.0179275725938 1 0 1 1 0 0 +EDGE2 56 57 0.77536053616 -0.0727835270276 -0.0370113971051 1 0 1 1 0 0 +EDGE2 57 58 0.792809168417 -0.00330191812217 0.0632619937894 1 0 1 1 0 0 +EDGE2 58 59 0.789336249422 0.0499678920653 0.04511737545 1 0 1 1 0 0 +EDGE2 59 60 0.799312335356 0.0154078296169 0.0686385071901 1 0 1 1 0 0 +EDGE2 60 61 0.841385096251 -0.0451402806057 -0.00137586137994 1 0 1 1 0 0 +EDGE2 61 62 0.73727689023 -0.335159174575 -0.434654147977 1 0 1 1 0 0 +EDGE2 62 63 0.849739889254 -0.101852726335 -0.0546134930344 1 0 1 1 0 0 +EDGE2 63 64 0.732343387025 -0.152861749502 -0.277235132206 1 0 1 1 0 0 +EDGE2 64 65 0.778127849356 0.0424893245594 -0.103498695967 1 0 1 1 0 0 +EDGE2 65 66 0.847762865635 -0.152071812994 -0.150846679463 1 0 1 1 0 0 +EDGE2 66 67 0.803448897426 -0.0786018488252 -0.100750096392 1 0 1 1 0 0 +EDGE2 67 68 0.869574260331 -0.067393723035 -0.227113129725 1 0 1 1 0 0 +EDGE2 68 69 0.700122812394 -0.127175450528 -0.145967973471 1 0 1 1 0 0 +EDGE2 69 70 0.741569767586 0.0209821877481 0.0347431035841 1 0 1 1 0 0 +EDGE2 70 71 0.782413802829 0.0140327998855 0.120620056225 1 0 1 1 0 0 +EDGE2 71 72 0.726382907259 -0.174488223666 -0.216565330734 1 0 1 1 0 0 +EDGE2 72 73 0.786270332597 -0.222893898151 -0.0947849029055 1 0 1 1 0 0 +EDGE2 73 74 0.872600785936 -0.157300465738 -0.187369985951 1 0 1 1 0 0 +EDGE2 74 75 0.745108268557 -0.24332540853 -0.256205853911 1 0 1 1 0 0 +EDGE2 75 76 0.741656734669 0.0584297856637 0.0684660276348 1 0 1 1 0 0 +EDGE2 76 77 0.83107553466 -0.068222280325 -0.101097480556 1 0 1 1 0 0 +EDGE2 77 78 0.838396530029 0.105042823302 0.218131052621 1 0 1 1 0 0 +EDGE2 78 79 0.76082044773 -0.162843454224 -0.195114595262 1 0 1 1 0 0 +EDGE2 79 80 0.8724369566 0.157719970278 0.155580359369 1 0 1 1 0 0 +EDGE2 80 81 0.89087135963 -0.0673911030734 -0.043743726621 1 0 1 1 0 0 +EDGE2 81 82 0.771001809797 0.114512192599 0.150286338457 1 0 1 1 0 0 +EDGE2 82 83 0.812780357241 0.00395510362595 -0.215353852667 1 0 1 1 0 0 +EDGE2 83 84 0.812252387954 -0.0274735142136 0.0152810139298 1 0 1 1 0 0 +EDGE2 84 85 0.728059940228 -0.211739661884 -0.148376056446 1 0 1 1 0 0 +EDGE2 85 86 0.743100348032 -0.205518475255 -0.220672724526 1 0 1 1 0 0 +EDGE2 86 87 0.800837885496 0.0270216423016 -0.0121669543509 1 0 1 1 0 0 +EDGE2 87 88 0.84523698212 0.025403746229 0.0393784439646 1 0 1 1 0 0 +EDGE2 88 89 0.776634574418 0.0577931763852 0.0735885911249 1 0 1 1 0 0 +EDGE2 89 90 0.795529423553 0.237162491279 0.23536520899 1 0 1 1 0 0 +EDGE2 90 91 0.805787421901 0.0521263906349 0.0421550276299 1 0 1 1 0 0 +EDGE2 91 92 0.821073980711 0.0501285496699 0.101339417467 1 0 1 1 0 0 +EDGE2 92 93 0.852950616989 -0.144711794646 -0.0130042276003 1 0 1 1 0 0 +EDGE2 93 94 0.86189702426 0.0935919937033 0.0835356089409 1 0 1 1 0 0 +BR 0 144 0.185182458717 9.13212526936 0.0349 0.1 +BR 1 144 -0.0129226894449 8.31812366009 0.0349 0.1 +BR 2 137 -0.00718256171569 9.4510095689 0.0349 0.1 +BR 2 144 -0.0402886026913 7.40183795114 0.0349 0.1 +BR 3 110 -0.0749913933297 9.38512144583 0.0349 0.1 +BR 3 137 -0.214302812649 8.91847706309 0.0349 0.1 +BR 3 144 -0.331046619669 6.88216766504 0.0349 0.1 +BR 4 110 -0.528773048781 8.70707069137 0.0349 0.1 +BR 4 137 -0.721109439101 8.1019911191 0.0349 0.1 +BR 4 144 -0.823882810817 6.3429714463 0.0349 0.1 +BR 5 110 -0.440317029226 7.90152610245 0.0349 0.1 +BR 5 137 -0.695335598589 7.36947399552 0.0349 0.1 +BR 5 144 -0.836258509529 5.68573435009 0.0349 0.1 +BR 6 110 -0.300578669402 7.30263189677 0.0349 0.1 +BR 6 137 -0.615732878739 6.58070581163 0.0349 0.1 +BR 6 144 -0.748502380201 4.97181349627 0.0349 0.1 +BR 7 110 -0.457809242486 6.4057096724 0.0349 0.1 +BR 7 137 -0.799831219908 6.09478184977 0.0349 0.1 +BR 7 144 -0.964230560912 4.56454858228 0.0349 0.1 +BR 8 110 -0.467348208232 5.49325886324 0.0349 0.1 +BR 8 137 -0.807694275092 5.51772540214 0.0349 0.1 +BR 8 144 -1.13536530576 3.81666726517 0.0349 0.1 +BR 9 110 -0.518981300619 5.25851673305 0.0349 0.1 +BR 9 137 -0.854409841336 5.08562424167 0.0349 0.1 +BR 9 144 -1.28402784294 3.64150184656 0.0349 0.1 +BR 10 110 -0.790651006069 4.290875248 0.0349 0.1 +BR 10 137 -1.18130413181 4.71464967115 0.0349 0.1 +BR 10 144 -1.5646244434 3.61089756748 0.0349 0.1 +BR 11 110 -0.880642022432 3.98236035001 0.0349 0.1 +BR 11 137 -1.29691369659 4.50238497278 0.0349 0.1 +BR 11 144 -1.82713910938 3.78383778763 0.0349 0.1 +BR 12 110 -1.32187002351 3.62433679399 0.0349 0.1 +BR 12 137 -1.7145607617 4.46822989525 0.0349 0.1 +BR 12 144 -2.21545709717 4.24105066636 0.0349 0.1 +BR 13 110 -1.71296518505 3.57549906761 0.0349 0.1 +BR 13 137 -1.98866377754 4.79459486414 0.0349 0.1 +BR 13 144 -2.46140779298 4.93843797616 0.0349 0.1 +BR 14 110 -1.99056042177 3.82339476594 0.0349 0.1 +BR 14 137 -2.22640434465 5.305250162 0.0349 0.1 +BR 14 144 -2.55677091106 5.46170314439 0.0349 0.1 +BR 15 110 -2.04880614871 4.10480923415 0.0349 0.1 +BR 15 137 -2.23779804266 5.87635629681 0.0349 0.1 +BR 15 144 -2.6151098223 6.3515317913 0.0349 0.1 +BR 16 110 -2.06003060806 4.42557132946 0.0349 0.1 +BR 16 117 -1.35214243919 10.0761482514 0.0349 0.1 +BR 16 137 -2.21401914815 6.16051869558 0.0349 0.1 +BR 16 144 -2.53705251945 6.83886701303 0.0349 0.1 +BR 17 110 -2.05946000954 4.70286658969 0.0349 0.1 +BR 17 117 -1.24383519856 9.61361367685 0.0349 0.1 +BR 17 137 -2.10879624347 6.45383801752 0.0349 0.1 +BR 17 144 -2.37194735825 7.43285240943 0.0349 0.1 +BR 18 110 -2.24565367321 5.05455899365 0.0349 0.1 +BR 18 117 -1.4566998731 9.45407941567 0.0349 0.1 +BR 18 137 -2.36776538577 7.09802331697 0.0349 0.1 +BR 18 144 -2.63414325206 8.05544152173 0.0349 0.1 +BR 19 110 -2.53165374141 5.63229552339 0.0349 0.1 +BR 19 117 -1.69653853719 9.45427424857 0.0349 0.1 +BR 19 137 -2.50848481788 7.55177276066 0.0349 0.1 +BR 19 144 -2.79987374438 8.77345763541 0.0349 0.1 +BR 20 110 -2.47990354001 6.35010296373 0.0349 0.1 +BR 20 117 -1.62650378923 9.39686061139 0.0349 0.1 +BR 20 137 -2.54701526227 8.32866970212 0.0349 0.1 +BR 20 144 -2.63947313054 9.56517009268 0.0349 0.1 +BR 21 110 -2.55850203983 6.96898661248 0.0349 0.1 +BR 21 117 -1.72847175528 9.84266033626 0.0349 0.1 +BR 21 130 0.664621658612 9.5759865835 0.0349 0.1 +BR 21 137 -2.57262324612 9.07025812037 0.0349 0.1 +BR 22 110 -2.46140069173 7.76173665587 0.0349 0.1 +BR 22 117 -1.50767608255 9.8291133283 0.0349 0.1 +BR 22 130 0.823885118652 8.81501192048 0.0349 0.1 +BR 22 137 -2.38946943302 9.59604468387 0.0349 0.1 +BR 23 110 -2.49582690441 8.28781200224 0.0349 0.1 +BR 23 117 -1.72519040254 9.80915204869 0.0349 0.1 +BR 23 130 0.931240309024 8.39880397639 0.0349 0.1 +BR 24 110 -2.75856723917 9.10160958405 0.0349 0.1 +BR 24 130 0.78416776229 7.76276053788 0.0349 0.1 +BR 25 110 -2.80692285652 9.76642515575 0.0349 0.1 +BR 25 130 0.775233070078 7.11275145442 0.0349 0.1 +BR 26 130 0.790834643547 6.33736770408 0.0349 0.1 +BR 27 130 0.534243817656 5.91578829565 0.0349 0.1 +BR 28 112 0.0414364252573 9.90330083232 0.0349 0.1 +BR 28 130 0.508210275456 5.21523105568 0.0349 0.1 +BR 28 146 -0.845262619975 9.96746671173 0.0349 0.1 +BR 29 112 0.183098888443 8.97611974568 0.0349 0.1 +BR 29 130 0.714643071872 4.52800551501 0.0349 0.1 +BR 29 146 -0.759652310647 9.34738787399 0.0349 0.1 +BR 30 112 0.220803493857 8.38735907801 0.0349 0.1 +BR 30 130 0.986350911973 3.98277990705 0.0349 0.1 +BR 30 146 -0.778277445645 8.57965070765 0.0349 0.1 +BR 31 112 0.299031878039 7.66323555915 0.0349 0.1 +BR 31 130 1.24857419325 3.67126201123 0.0349 0.1 +BR 31 146 -0.801974563814 8.07274519519 0.0349 0.1 +BR 32 112 0.423997675694 6.73235131609 0.0349 0.1 +BR 32 130 1.46838088131 3.46892248338 0.0349 0.1 +BR 32 146 -0.79908260713 7.4588636461 0.0349 0.1 +BR 33 112 0.476958671405 6.18741823661 0.0349 0.1 +BR 33 130 1.75701275846 3.59510992657 0.0349 0.1 +BR 33 146 -0.831662121031 7.04303707355 0.0349 0.1 +BR 34 112 1.11053185407 5.73111181601 0.0349 0.1 +BR 34 130 2.32852970858 4.06426280442 0.0349 0.1 +BR 34 146 -0.46502078765 6.39400757176 0.0349 0.1 +BR 35 112 1.29539336024 5.39706444208 0.0349 0.1 +BR 35 129 -0.286317245678 9.78983149537 0.0349 0.1 +BR 35 130 2.56479344603 4.74998169538 0.0349 0.1 +BR 35 146 -0.532333579717 5.60699182585 0.0349 0.1 +BR 36 112 1.32829018039 5.23245230162 0.0349 0.1 +BR 36 129 -0.460072777958 8.93159378784 0.0349 0.1 +BR 36 130 -3.72946554068 5.24707372009 0.0349 0.1 +BR 36 146 -0.651976626401 5.00329187599 0.0349 0.1 +BR 37 112 1.47981669566 4.97207303698 0.0349 0.1 +BR 37 129 -0.3297608179 8.28473488253 0.0349 0.1 +BR 37 130 -3.64959871445 6.0920051131 0.0349 0.1 +BR 37 146 -0.761130816352 4.33535233295 0.0349 0.1 +BR 38 112 1.79010072399 5.11134982 0.0349 0.1 +BR 38 129 -0.239172851184 7.30972395375 0.0349 0.1 +BR 38 130 -3.51623581001 7.035350049 0.0349 0.1 +BR 38 132 0.0344695438909 9.16065906572 0.0349 0.1 +BR 38 146 -0.729682501329 3.69383136681 0.0349 0.1 +BR 39 112 1.80724225657 5.0712041146 0.0349 0.1 +BR 39 129 -0.466822552134 6.71909069076 0.0349 0.1 +BR 39 130 -3.58201828036 7.74976854347 0.0349 0.1 +BR 39 132 -0.145489919023 8.26408270817 0.0349 0.1 +BR 39 136 -0.373174247759 10.0594690013 0.0349 0.1 +BR 39 146 -1.03884588422 3.05919083504 0.0349 0.1 +BR 40 112 2.09018812193 5.6349471547 0.0349 0.1 +BR 40 129 -0.347661923995 6.08661605953 0.0349 0.1 +BR 40 130 -3.40788452199 8.33216602696 0.0349 0.1 +BR 40 132 0.0183763853089 7.65498891306 0.0349 0.1 +BR 40 136 -0.205928280437 9.23372153865 0.0349 0.1 +BR 40 146 -1.15729572346 2.758937753 0.0349 0.1 +BR 41 112 2.11156675384 6.17957324232 0.0349 0.1 +BR 41 129 -0.513471163104 5.47917944802 0.0349 0.1 +BR 41 130 -3.45321447468 8.96911724514 0.0349 0.1 +BR 41 132 -0.00417850025153 6.7854687031 0.0349 0.1 +BR 41 136 -0.306724739524 8.47672248547 0.0349 0.1 +BR 41 146 -1.48971635217 2.63763674624 0.0349 0.1 +BR 42 112 2.03992029635 6.31576122552 0.0349 0.1 +BR 42 129 -0.830261802361 4.91295992246 0.0349 0.1 +BR 42 130 -3.55865937637 9.89982911214 0.0349 0.1 +BR 42 132 -0.236186305191 6.2509710589 0.0349 0.1 +BR 42 136 -0.594332746928 7.68658045685 0.0349 0.1 +BR 42 146 -1.89947156813 2.90103368108 0.0349 0.1 +BR 43 112 2.20405052469 6.82505384798 0.0349 0.1 +BR 43 129 -0.86677535825 4.24973929099 0.0349 0.1 +BR 43 132 -0.170572630907 5.21697313753 0.0349 0.1 +BR 43 136 -0.59926860855 6.96617850118 0.0349 0.1 +BR 43 146 -2.18328873694 3.15420328364 0.0349 0.1 +BR 44 112 2.28288455017 7.21970860023 0.0349 0.1 +BR 44 129 -1.0660796602 3.60369990665 0.0349 0.1 +BR 44 132 -0.269529469754 4.78179932008 0.0349 0.1 +BR 44 136 -0.552094085176 6.39602268905 0.0349 0.1 +BR 44 146 -2.34040228059 3.39346775306 0.0349 0.1 +BR 45 112 2.53707604246 8.03041958241 0.0349 0.1 +BR 45 129 -1.17710675346 3.31741261854 0.0349 0.1 +BR 45 132 -0.169178567894 3.72737707244 0.0349 0.1 +BR 45 136 -0.58982083798 5.65573127607 0.0349 0.1 +BR 45 146 -2.31254599631 4.073315509 0.0349 0.1 +BR 46 112 2.30336072906 8.53878391819 0.0349 0.1 +BR 46 129 -1.56469510909 3.27257795455 0.0349 0.1 +BR 46 132 -0.596947941988 3.01003728934 0.0349 0.1 +BR 46 136 -0.972903852928 5.11198354755 0.0349 0.1 +BR 46 145 -0.379034045173 9.44743347682 0.0349 0.1 +BR 46 146 -2.71640793524 4.69101880432 0.0349 0.1 +BR 47 112 -4.09979829598 8.93000904485 0.0349 0.1 +BR 47 129 -2.08829636192 3.6048789119 0.0349 0.1 +BR 47 132 -0.992144225485 2.55259283291 0.0349 0.1 +BR 47 136 -1.37087445362 4.9788870276 0.0349 0.1 +BR 47 138 0.471079307943 9.48838419239 0.0349 0.1 +BR 47 145 -0.585304896045 8.55966650601 0.0349 0.1 +BR 47 146 -2.86951126121 5.46138428744 0.0349 0.1 +BR 48 112 -3.87787490571 9.29627530206 0.0349 0.1 +BR 48 129 -2.08519281032 3.93461289407 0.0349 0.1 +BR 48 132 -1.1882653081 2.02386021289 0.0349 0.1 +BR 48 136 -1.37524100074 4.78257071668 0.0349 0.1 +BR 48 138 0.596766880921 8.85284436333 0.0349 0.1 +BR 48 145 -0.641491507579 7.95203729796 0.0349 0.1 +BR 48 146 -2.75763166267 6.362323849 0.0349 0.1 +BR 49 211 0.739516646502 9.8712550054 0.0349 0.1 +BR 49 129 -2.14750043042 4.41467137273 0.0349 0.1 +BR 49 132 -1.32001186912 1.81101852014 0.0349 0.1 +BR 49 136 -1.3132413823 4.29282959482 0.0349 0.1 +BR 49 138 0.852323239846 8.31832913318 0.0349 0.1 +BR 49 145 -0.425206869031 7.30184295026 0.0349 0.1 +BR 49 146 -2.81219083584 7.1999192447 0.0349 0.1 +BR 50 211 0.835145641247 9.39883397423 0.0349 0.1 +BR 50 129 -2.29739481979 4.84591520301 0.0349 0.1 +BR 50 132 -1.69740609702 1.88108819843 0.0349 0.1 +BR 50 136 -1.41813064673 4.22649063304 0.0349 0.1 +BR 50 138 1.00506413746 7.80362591487 0.0349 0.1 +BR 50 145 -0.455209251406 6.50387636211 0.0349 0.1 +BR 50 146 -2.73782469254 7.87670364149 0.0349 0.1 +BR 51 211 0.702762892786 8.87516504348 0.0349 0.1 +BR 51 129 -2.47535256165 5.23986867221 0.0349 0.1 +BR 51 132 -2.30239380502 2.18778407787 0.0349 0.1 +BR 51 133 -0.721507862233 9.98554796724 0.0349 0.1 +BR 51 136 -1.81775933595 4.26750754492 0.0349 0.1 +BR 51 138 0.972975632993 7.33609223589 0.0349 0.1 +BR 51 145 -0.655168730304 5.97764397657 0.0349 0.1 +BR 51 146 -2.9008185124 8.52711403391 0.0349 0.1 +BR 52 211 1.02160299745 8.39990010785 0.0349 0.1 +BR 52 129 -2.38078665638 5.89398424924 0.0349 0.1 +BR 52 132 -2.32150260829 2.7642509002 0.0349 0.1 +BR 52 133 -0.593338340282 9.09248006087 0.0349 0.1 +BR 52 136 -1.70907208704 4.52511614196 0.0349 0.1 +BR 52 138 1.31486182491 7.00604753829 0.0349 0.1 +BR 52 145 -0.623641599141 5.23461904841 0.0349 0.1 +BR 52 146 -2.72475360758 9.52193132649 0.0349 0.1 +BR 53 211 1.31559744632 8.11139198603 0.0349 0.1 +BR 53 214 0.237146993035 9.72602918909 0.0349 0.1 +BR 53 129 -2.29755087534 6.31115337961 0.0349 0.1 +BR 53 132 -2.35974179857 3.19960631018 0.0349 0.1 +BR 53 133 -0.394598671292 8.38412703631 0.0349 0.1 +BR 53 136 -1.80773002423 4.40929640292 0.0349 0.1 +BR 53 138 1.54926467893 6.88525427648 0.0349 0.1 +BR 53 145 -0.474177899207 4.53003713639 0.0349 0.1 +BR 54 211 0.984732803445 7.42786510356 0.0349 0.1 +BR 54 214 -0.11180491587 9.02509825398 0.0349 0.1 +BR 54 129 -2.74232381524 6.87541946089 0.0349 0.1 +BR 54 132 -2.90610674415 3.90683353197 0.0349 0.1 +BR 54 133 -0.946269617578 7.87816492515 0.0349 0.1 +BR 54 136 -2.26079857458 5.05238790003 0.0349 0.1 +BR 54 138 1.23881048754 6.66133430521 0.0349 0.1 +BR 54 145 -0.947227352968 3.83527710037 0.0349 0.1 +BR 55 211 0.898485222553 7.20091899213 0.0349 0.1 +BR 55 214 -0.331475822555 8.15612623956 0.0349 0.1 +BR 55 129 -2.94211283394 7.71377937916 0.0349 0.1 +BR 55 132 -2.96263902277 4.72504746653 0.0349 0.1 +BR 55 133 -1.19619007418 7.57872766791 0.0349 0.1 +BR 55 136 -2.50797826148 5.6165181032 0.0349 0.1 +BR 55 138 1.15570916703 6.30471479324 0.0349 0.1 +BR 55 145 -1.34211765445 3.61160861965 0.0349 0.1 +BR 56 211 1.15825542961 6.7888627078 0.0349 0.1 +BR 56 214 -0.219470357269 7.60748335035 0.0349 0.1 +BR 56 129 -2.8680390372 8.7065246753 0.0349 0.1 +BR 56 132 -2.98769597419 5.64491656469 0.0349 0.1 +BR 56 133 -1.18165204481 7.28168467592 0.0349 0.1 +BR 56 136 -2.50662065879 6.33607011113 0.0349 0.1 +BR 56 138 1.38983018292 6.2829567225 0.0349 0.1 +BR 56 145 -1.48728342633 3.55073682465 0.0349 0.1 +BR 57 211 1.31121936211 6.4499882023 0.0349 0.1 +BR 57 214 -0.23903049767 6.70522585497 0.0349 0.1 +BR 57 129 -2.9344494194 9.42282481723 0.0349 0.1 +BR 57 132 -2.92810125756 6.33396803893 0.0349 0.1 +BR 57 133 -1.20821854839 7.04533813918 0.0349 0.1 +BR 57 136 -2.58342247807 6.79285980736 0.0349 0.1 +BR 57 138 1.60454813339 6.18478768582 0.0349 0.1 +BR 57 141 0.855478263576 9.81268967389 0.0349 0.1 +BR 57 145 -1.64743462419 3.55197042884 0.0349 0.1 +BR 58 211 1.3697376327 6.28814896116 0.0349 0.1 +BR 58 214 -0.240573643222 6.00770973914 0.0349 0.1 +BR 58 132 -3.04782555269 7.20609442047 0.0349 0.1 +BR 58 133 -1.38654094358 6.89172239496 0.0349 0.1 +BR 58 136 -2.71931807774 7.43484636746 0.0349 0.1 +BR 58 138 1.67863856935 6.1507384544 0.0349 0.1 +BR 58 141 0.976143688736 9.46697440494 0.0349 0.1 +BR 58 145 -1.83870327644 3.65503744995 0.0349 0.1 +BR 59 211 1.48699429679 6.08115940992 0.0349 0.1 +BR 59 214 -0.415570760211 5.13438758848 0.0349 0.1 +BR 59 132 -3.02827764182 7.96286566655 0.0349 0.1 +BR 59 133 -1.53145859942 6.77610181098 0.0349 0.1 +BR 59 136 -2.74531072749 8.32929527587 0.0349 0.1 +BR 59 138 1.72057247223 6.26065897831 0.0349 0.1 +BR 59 141 1.03071332211 8.88769595496 0.0349 0.1 +BR 59 145 -2.08753542039 4.10672697789 0.0349 0.1 +BR 60 211 1.59739021193 6.15588728463 0.0349 0.1 +BR 60 214 -0.511168179873 4.33010644987 0.0349 0.1 +BR 60 132 -3.09344355595 8.61019942961 0.0349 0.1 +BR 60 133 -1.7654808189 6.71410728498 0.0349 0.1 +BR 60 136 -2.77389441808 9.0499972807 0.0349 0.1 +BR 60 138 1.8820286755 6.37121288506 0.0349 0.1 +BR 60 141 1.07152819217 8.35085378616 0.0349 0.1 +BR 60 145 -2.26379347264 4.5992746157 0.0349 0.1 +BR 61 211 1.65733486617 6.06862058524 0.0349 0.1 +BR 61 214 -0.592403718182 3.79555195012 0.0349 0.1 +BR 61 116 -1.11564212635 9.76016152567 0.0349 0.1 +BR 61 132 -3.08611036748 9.40173514366 0.0349 0.1 +BR 61 133 -1.83574223151 6.77780820625 0.0349 0.1 +BR 61 136 -2.81345972719 9.87046005411 0.0349 0.1 +BR 61 138 2.01635034865 6.58454580038 0.0349 0.1 +BR 61 141 1.05738477029 7.90059102737 0.0349 0.1 +BR 61 145 -2.46764482041 5.23886327349 0.0349 0.1 +BR 62 211 2.19981530481 6.55940364295 0.0349 0.1 +BR 62 214 -0.330629210924 2.89895419258 0.0349 0.1 +BR 62 116 -0.712532191251 9.34490097865 0.0349 0.1 +BR 62 133 -1.50791588512 7.01329261316 0.0349 0.1 +BR 62 138 2.42398978932 7.32781104937 0.0349 0.1 +BR 62 141 1.56493435286 7.93355916389 0.0349 0.1 +BR 62 145 -2.2278542462 5.49873142521 0.0349 0.1 +BR 63 211 2.32173832925 7.0194270853 0.0349 0.1 +BR 63 214 -0.386580845638 2.43330741085 0.0349 0.1 +BR 63 116 -0.729079668132 8.53447098505 0.0349 0.1 +BR 63 133 -1.57833951194 6.88281488712 0.0349 0.1 +BR 63 138 2.57564520733 7.78656203108 0.0349 0.1 +BR 63 141 1.81747758419 8.07098244115 0.0349 0.1 +BR 63 145 -2.23878875365 5.92539391826 0.0349 0.1 +BR 64 211 2.64430253079 7.83864538862 0.0349 0.1 +BR 64 214 -0.0994208312564 1.44204544545 0.0349 0.1 +BR 64 116 -0.55500504894 7.72325595942 0.0349 0.1 +BR 64 133 -1.4536518654 6.65517115162 0.0349 0.1 +BR 64 138 2.8401061616 8.57033338472 0.0349 0.1 +BR 64 141 2.1957214779 8.46409667869 0.0349 0.1 +BR 64 145 -2.02665785317 6.30435908086 0.0349 0.1 +BR 65 211 2.77723756274 8.49481575652 0.0349 0.1 +BR 65 214 -0.222004642925 0.769067027532 0.0349 0.1 +BR 65 116 -0.476406751958 6.944593788 0.0349 0.1 +BR 65 133 -1.5055349911 6.5435294725 0.0349 0.1 +BR 65 138 2.89207363594 9.52197266067 0.0349 0.1 +BR 65 139 0.690529531955 9.88828227669 0.0349 0.1 +BR 65 141 2.20677044598 8.87273441824 0.0349 0.1 +BR 65 145 -2.16442898949 6.62783981315 0.0349 0.1 +BR 66 211 2.92708006505 9.25699933973 0.0349 0.1 +BR 66 214 -2.70729617971 0.089927286145 0.0349 0.1 +BR 66 116 -0.437916662456 6.37909317223 0.0349 0.1 +BR 66 133 -1.53242050643 6.44340702808 0.0349 0.1 +BR 66 139 0.911600005332 9.29148527033 0.0349 0.1 +BR 66 141 2.43759073241 9.53382144492 0.0349 0.1 +BR 66 145 -2.09539296277 7.1168381771 0.0349 0.1 +BR 67 214 -3.07507169223 0.880638010099 0.0349 0.1 +BR 67 116 -0.364201036385 5.70130017619 0.0349 0.1 +BR 67 133 -1.5796828657 6.40788347591 0.0349 0.1 +BR 67 139 1.09811562801 8.94633439107 0.0349 0.1 +BR 67 145 -2.09672822137 7.34322150374 0.0349 0.1 +BR 68 214 3.25749632058 1.71825216935 0.0349 0.1 +BR 68 116 -0.250579061157 4.98724463734 0.0349 0.1 +BR 68 133 -1.49770874602 6.29144792573 0.0349 0.1 +BR 68 139 1.35862501974 8.66611776892 0.0349 0.1 +BR 68 145 -2.0380754896 7.71319884521 0.0349 0.1 +BR 69 214 3.36924028033 2.37881667021 0.0349 0.1 +BR 69 114 0.965203878623 9.96554579176 0.0349 0.1 +BR 69 116 -0.177465967368 4.16576217975 0.0349 0.1 +BR 69 133 -1.58615525394 6.17247552536 0.0349 0.1 +BR 69 139 1.6044244742 8.66323549571 0.0349 0.1 +BR 69 145 -2.05356692956 8.23087471484 0.0349 0.1 +BR 70 214 3.26447815983 3.50520447752 0.0349 0.1 +BR 70 114 1.04557241854 9.48035082217 0.0349 0.1 +BR 70 116 -0.174044759473 3.30434496879 0.0349 0.1 +BR 70 133 -1.71878170033 6.12453562279 0.0349 0.1 +BR 70 139 1.6988840667 8.90097770891 0.0349 0.1 +BR 70 145 -2.09118659226 8.57946955435 0.0349 0.1 +BR 71 214 3.17116978801 4.13326733054 0.0349 0.1 +BR 71 114 0.971598066455 8.94056084471 0.0349 0.1 +BR 71 116 -0.442084127811 2.65553820347 0.0349 0.1 +BR 71 131 1.51291549191 9.93983683031 0.0349 0.1 +BR 71 133 -1.92850538371 6.61503232087 0.0349 0.1 +BR 71 139 1.62178936432 8.9275013656 0.0349 0.1 +BR 71 145 -2.26077765156 8.81810560523 0.0349 0.1 +BR 72 214 3.3483118075 5.07146259456 0.0349 0.1 +BR 72 114 1.25024033184 8.65447650965 0.0349 0.1 +BR 72 116 -0.29484144987 1.7807736885 0.0349 0.1 +BR 72 133 -1.85932117232 6.54581267011 0.0349 0.1 +BR 72 139 1.90675845297 9.03288373875 0.0349 0.1 +BR 72 145 -2.11133037157 9.64278665008 0.0349 0.1 +BR 73 214 3.42031481088 5.68604714096 0.0349 0.1 +BR 73 114 1.49448393979 8.76928636352 0.0349 0.1 +BR 73 116 -0.311282829508 0.986563086856 0.0349 0.1 +BR 73 133 -1.81885055957 6.86219220059 0.0349 0.1 +BR 73 139 2.19840475652 9.39629377331 0.0349 0.1 +BR 73 145 -2.08434312084 10.019522072 0.0349 0.1 +BR 74 214 3.53214111622 6.47416976793 0.0349 0.1 +BR 74 219 1.125245923 9.70485712932 0.0349 0.1 +BR 74 114 1.78271170313 8.74159061945 0.0349 0.1 +BR 74 116 -0.496879055986 0.212551914458 0.0349 0.1 +BR 74 133 -1.69837838721 6.62504018219 0.0349 0.1 +BR 75 214 3.80548992485 6.97643942878 0.0349 0.1 +BR 75 219 1.44648023525 9.61002619118 0.0349 0.1 +BR 75 114 2.17495579726 9.36616344671 0.0349 0.1 +BR 75 116 3.15139437828 0.640676998818 0.0349 0.1 +BR 75 133 -1.47800625615 6.55213863832 0.0349 0.1 +BR 76 214 3.64481450915 7.68409243587 0.0349 0.1 +BR 76 219 1.55416548399 9.58187707528 0.0349 0.1 +BR 76 114 2.22336594529 9.69979828032 0.0349 0.1 +BR 76 116 3.12835380769 1.52693080051 0.0349 0.1 +BR 76 133 -1.74190482626 6.46408688569 0.0349 0.1 +BR 77 214 3.78271717671 8.33092440218 0.0349 0.1 +BR 77 219 1.67410135616 9.71669336385 0.0349 0.1 +BR 77 116 3.18266207552 2.40071229786 0.0349 0.1 +BR 77 133 -1.70540467651 6.66269006969 0.0349 0.1 +BR 78 214 3.42981856843 8.9840154373 0.0349 0.1 +BR 78 219 1.55521791221 9.65971453808 0.0349 0.1 +BR 78 116 3.08079550878 3.13311875201 0.0349 0.1 +BR 78 133 -1.9629815922 7.01715815731 0.0349 0.1 +BR 79 214 3.64301348008 9.64604876625 0.0349 0.1 +BR 79 219 1.84313214295 9.8736833446 0.0349 0.1 +BR 79 116 3.23976285086 3.82731244384 0.0349 0.1 +BR 79 133 -1.92693348218 7.07982856181 0.0349 0.1 +BR 80 219 1.82267971334 10.0181195912 0.0349 0.1 +BR 80 116 3.0932606444 4.56053898399 0.0349 0.1 +BR 80 133 -2.16850666747 7.82134702265 0.0349 0.1 +BR 81 116 3.10963701499 5.36017902545 0.0349 0.1 +BR 81 133 4.14615729787 7.91335159223 0.0349 0.1 +BR 82 116 3.02427035132 6.3165782418 0.0349 0.1 +BR 82 118 0.386637063745 9.30518727853 0.0349 0.1 +BR 82 133 3.96654040143 8.46139182575 0.0349 0.1 +BR 83 116 3.17577034597 6.95212398542 0.0349 0.1 +BR 83 118 0.54486099103 8.70615519965 0.0349 0.1 +BR 83 133 3.97631817437 9.0707544279 0.0349 0.1 +BR 84 116 3.08672783226 7.73113294416 0.0349 0.1 +BR 84 118 0.50758642684 7.92961801618 0.0349 0.1 +BR 84 133 3.83740508413 9.53430891219 0.0349 0.1 +BR 85 116 3.2851042494 8.61085233676 0.0349 0.1 +BR 85 118 0.800702749373 7.297783814 0.0349 0.1 +BR 86 116 3.46202134229 9.40431553868 0.0349 0.1 +BR 86 118 1.02219323662 6.98093561867 0.0349 0.1 +BR 86 125 0.894103907508 9.78156008486 0.0349 0.1 +BR 87 118 1.17775566595 6.57332518044 0.0349 0.1 +BR 87 125 0.953764386986 9.11980772782 0.0349 0.1 +BR 88 118 1.23977118944 6.39248070013 0.0349 0.1 +BR 88 125 0.988718137509 8.638143389 0.0349 0.1 +BR 89 118 1.32805006899 6.07271098982 0.0349 0.1 +BR 89 125 1.03116673027 8.19879638653 0.0349 0.1 +BR 90 118 1.27747987129 5.7243455139 0.0349 0.1 +BR 90 125 0.89663965971 7.9292423614 0.0349 0.1 +BR 91 118 1.23616540573 5.42052023942 0.0349 0.1 +BR 91 125 0.901333443965 7.46153346919 0.0349 0.1 +BR 92 118 1.27418747645 5.10370611594 0.0349 0.1 +BR 92 125 0.814247104386 6.78352263469 0.0349 0.1 +BR 93 118 1.52925418993 5.08780303591 0.0349 0.1 +BR 93 122 0.0350305409562 9.72894928235 0.0349 0.1 +BR 93 125 0.990434800962 6.40937952378 0.0349 0.1 +BR 94 118 1.57085863582 5.16163930514 0.0349 0.1 +BR 94 122 -0.0746183892492 8.89244084523 0.0349 0.1 +BR 94 125 0.977283745835 5.68611237558 0.0349 0.1 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/Data/w10000-odom.graph b/examples/Data/w10000-odom.graph new file mode 100644 index 000000000..56c385cce --- /dev/null +++ b/examples/Data/w10000-odom.graph @@ -0,0 +1,80186 @@ +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 +VERTEX2 100 -1.07148 -0.0252992 1.35446 +VERTEX2 101 -2.03273 0.228716 2.89508 +VERTEX2 102 -3.03517 0.481399 2.90001 +VERTEX2 103 -4.07831 0.666658 2.88897 +VERTEX2 104 -4.97053 0.927183 2.90999 +VERTEX2 105 -5.95187 1.14752 2.89351 +VERTEX2 106 -5.79719 1.99354 1.32631 +VERTEX2 107 -5.53203 2.9937 1.27327 +VERTEX2 108 -5.18084 3.98453 1.25315 +VERTEX2 109 -4.91489 4.88054 1.23434 +VERTEX2 110 -4.57738 5.85163 1.20528 +VERTEX2 111 -5.51058 6.17551 2.78307 +VERTEX2 112 -6.45034 6.57273 2.79211 +VERTEX2 113 -7.38619 6.90802 2.79463 +VERTEX2 114 -8.36923 7.34601 2.79528 +VERTEX2 115 -9.26885 7.79083 2.77514 +VERTEX2 116 -8.90116 8.77833 1.20582 +VERTEX2 117 -8.51372 9.71101 1.25156 +VERTEX2 118 -8.15017 10.6798 1.22892 +VERTEX2 119 -7.88586 11.5802 1.27389 +VERTEX2 120 -7.64723 12.5462 1.28499 +VERTEX2 121 -8.65477 12.914 2.85116 +VERTEX2 122 -9.64587 13.2092 2.84568 +VERTEX2 123 -10.6661 13.5209 2.85179 +VERTEX2 124 -11.6149 13.7381 2.84877 +VERTEX2 125 -12.5932 13.9995 2.81969 +VERTEX2 126 -12.3159 15.0016 1.24736 +VERTEX2 127 -11.9441 15.9773 1.23889 +VERTEX2 128 -11.6362 16.8814 1.24381 +VERTEX2 129 -11.3895 17.865 1.24911 +VERTEX2 130 -11.1087 18.8247 1.26057 +VERTEX2 131 -11.9256 19.1785 2.85408 +VERTEX2 132 -12.9026 19.352 2.84362 +VERTEX2 133 -13.8659 19.7619 2.79681 +VERTEX2 134 -14.8086 20.1455 2.81274 +VERTEX2 135 -15.7621 20.4734 2.77939 +VERTEX2 136 -15.3236 21.3872 1.2034 +VERTEX2 137 -14.9643 22.3399 1.1969 +VERTEX2 138 -14.6499 23.2974 1.21387 +VERTEX2 139 -14.2421 24.289 1.2444 +VERTEX2 140 -13.9185 25.2302 1.22456 +VERTEX2 141 -14.8985 25.5809 2.79194 +VERTEX2 142 -15.8303 25.9001 2.78248 +VERTEX2 143 -16.7861 26.2595 2.79595 +VERTEX2 144 -17.7704 26.5561 2.80504 +VERTEX2 145 -18.7187 26.8958 2.82832 +VERTEX2 146 -19.0239 25.9966 -1.88734 +VERTEX2 147 -19.3603 25.069 -1.90573 +VERTEX2 148 -19.6805 24.1352 -1.88936 +VERTEX2 149 -20.0969 23.1646 -1.90023 +VERTEX2 150 -20.3997 22.2406 -1.88261 +VERTEX2 151 -21.25 22.551 2.85369 +VERTEX2 152 -22.2785 22.9044 2.86125 +VERTEX2 153 -23.2205 23.2216 2.89262 +VERTEX2 154 -24.181 23.3376 2.86869 +VERTEX2 155 -25.1643 23.665 2.83199 +VERTEX2 156 -24.8169 24.6326 1.23778 +VERTEX2 157 -24.4129 25.6799 1.25887 +VERTEX2 158 -24.1549 26.6661 1.27352 +VERTEX2 159 -23.7919 27.572 1.25285 +VERTEX2 160 -23.4097 28.5401 1.26524 +VERTEX2 161 -24.373 28.8287 2.85514 +VERTEX2 162 -25.322 29.1378 2.84571 +VERTEX2 163 -26.2798 29.4546 2.83014 +VERTEX2 164 -27.1809 29.7961 2.85348 +VERTEX2 165 -28.0934 30.0373 2.85997 +VERTEX2 166 -27.8789 31.0095 1.30777 +VERTEX2 167 -27.6131 31.993 1.31028 +VERTEX2 168 -27.3978 32.9505 1.28446 +VERTEX2 169 -27.2392 33.9482 1.28867 +VERTEX2 170 -27.012 34.8715 1.28123 +VERTEX2 171 -26.0722 34.5849 -0.276286 +VERTEX2 172 -25.1495 34.3415 -0.294066 +VERTEX2 173 -24.2029 34.0333 -0.318192 +VERTEX2 174 -23.2781 33.7646 -0.303061 +VERTEX2 175 -22.381 33.4325 -0.305577 +VERTEX2 176 -22.0966 34.4303 1.28507 +VERTEX2 177 -21.751 35.3871 1.32406 +VERTEX2 178 -21.5548 36.3964 1.29875 +VERTEX2 179 -21.3227 37.3181 1.30108 +VERTEX2 180 -21.1306 38.3562 1.28034 +VERTEX2 181 -22.0873 38.7165 2.854 +VERTEX2 182 -23.0256 38.9093 2.89201 +VERTEX2 183 -24.083 39.1834 2.8999 +VERTEX2 184 -24.995 39.4452 2.89616 +VERTEX2 185 -26.0653 39.7412 2.87677 +VERTEX2 186 -26.3053 38.8001 -1.84742 +VERTEX2 187 -26.5494 37.8211 -1.81656 +VERTEX2 188 -26.732 36.8951 -1.81289 +VERTEX2 189 -27.0311 35.8802 -1.80985 +VERTEX2 190 -27.3215 34.9177 -1.81162 +VERTEX2 191 -26.3781 34.6588 -0.225313 +VERTEX2 192 -25.3852 34.4304 -0.231752 +VERTEX2 193 -24.4088 34.2154 -0.249897 +VERTEX2 194 -23.4685 33.9799 -0.256 +VERTEX2 195 -22.5273 33.7573 -0.211831 +VERTEX2 196 -22.348 34.7571 1.41032 +VERTEX2 197 -22.1829 35.7678 1.39322 +VERTEX2 198 -21.9718 36.7004 1.37121 +VERTEX2 199 -21.7402 37.6626 1.36259 +VERTEX2 200 -21.4603 38.6756 1.35672 +VERTEX2 201 -22.4102 38.8271 2.94661 +VERTEX2 202 -23.4372 38.9585 2.93555 +VERTEX2 203 -24.3272 39.2563 2.89147 +VERTEX2 204 -25.2789 39.4651 2.88153 +VERTEX2 205 -26.2813 39.7413 2.90132 +VERTEX2 206 -26.0078 40.6895 1.34433 +VERTEX2 207 -25.7555 41.7375 1.34567 +VERTEX2 208 -25.5341 42.7266 1.34725 +VERTEX2 209 -25.2228 43.6814 1.31399 +VERTEX2 210 -24.9768 44.7091 1.33749 +VERTEX2 211 -25.8715 44.925 2.88943 +VERTEX2 212 -26.928 45.1303 2.88763 +VERTEX2 213 -27.9305 45.4822 2.88563 +VERTEX2 214 -28.8075 45.6985 2.88182 +VERTEX2 215 -29.8143 45.9419 2.89667 +VERTEX2 216 -30.054 45.0006 -1.80906 +VERTEX2 217 -30.2532 44.0192 -1.80513 +VERTEX2 218 -30.4332 43.0942 -1.79445 +VERTEX2 219 -30.6871 42.0851 -1.76101 +VERTEX2 220 -30.9337 41.1196 -1.77042 +VERTEX2 221 -30.0609 41.0607 -0.162306 +VERTEX2 222 -29.0737 40.9459 -0.179675 +VERTEX2 223 -28.1398 40.7795 -0.185669 +VERTEX2 224 -27.1318 40.6651 -0.210762 +VERTEX2 225 -26.2021 40.5598 -0.215218 +VERTEX2 226 -26.0074 41.474 1.36486 +VERTEX2 227 -25.7507 42.4446 1.38225 +VERTEX2 228 -25.5538 43.399 1.36897 +VERTEX2 229 -25.2516 44.414 1.35733 +VERTEX2 230 -24.9514 45.4053 1.36018 +VERTEX2 231 -24.0443 45.2364 -0.235616 +VERTEX2 232 -23.0857 44.9845 -0.253387 +VERTEX2 233 -22.0878 44.7297 -0.26546 +VERTEX2 234 -21.0676 44.501 -0.287583 +VERTEX2 235 -20.0664 44.2083 -0.326104 +VERTEX2 236 -19.7829 45.2151 1.23532 +VERTEX2 237 -19.4417 46.1221 1.24974 +VERTEX2 238 -19.1661 46.9965 1.22106 +VERTEX2 239 -18.9263 47.9163 1.20355 +VERTEX2 240 -18.5067 48.8172 1.19158 +VERTEX2 241 -19.4189 49.2207 2.73705 +VERTEX2 242 -20.2899 49.6403 2.76965 +VERTEX2 243 -21.3168 50.123 2.77272 +VERTEX2 244 -22.2974 50.5509 2.78988 +VERTEX2 245 -23.2547 50.8764 2.74502 +VERTEX2 246 -23.6524 49.9889 -1.95326 +VERTEX2 247 -24.0379 48.9702 -1.98637 +VERTEX2 248 -24.4585 48.0876 -1.99167 +VERTEX2 249 -24.84 47.2183 -1.99873 +VERTEX2 250 -25.1821 46.3191 -1.97351 +VERTEX2 251 -24.2757 45.9373 -0.376597 +VERTEX2 252 -23.3974 45.5526 -0.379423 +VERTEX2 253 -22.4914 45.2354 -0.371224 +VERTEX2 254 -21.5175 44.9762 -0.388135 +VERTEX2 255 -20.603 44.6158 -0.415691 +VERTEX2 256 -21.0113 43.7242 -1.99609 +VERTEX2 257 -21.4442 42.8264 -1.98491 +VERTEX2 258 -21.8294 41.8567 -1.95626 +VERTEX2 259 -22.2017 40.9184 -1.96824 +VERTEX2 260 -22.6315 39.9435 -1.94643 +VERTEX2 261 -21.6486 39.5893 -0.363441 +VERTEX2 262 -20.7395 39.2552 -0.365742 +VERTEX2 263 -19.8349 38.8461 -0.35389 +VERTEX2 264 -18.9332 38.5655 -0.375271 +VERTEX2 265 -17.9559 38.1493 -0.370244 +VERTEX2 266 -18.3904 37.2921 -1.91684 +VERTEX2 267 -18.721 36.3405 -1.9177 +VERTEX2 268 -19.138 35.4179 -1.92784 +VERTEX2 269 -19.4322 34.4343 -1.92139 +VERTEX2 270 -19.7713 33.5669 -1.90555 +VERTEX2 271 -18.8606 33.1904 -0.29815 +VERTEX2 272 -17.88 32.9234 -0.298845 +VERTEX2 273 -16.9331 32.6438 -0.274779 +VERTEX2 274 -15.9628 32.407 -0.247858 +VERTEX2 275 -15.0836 32.2157 -0.252306 +VERTEX2 276 -14.7753 33.2536 1.31744 +VERTEX2 277 -14.5327 34.1976 1.32878 +VERTEX2 278 -14.3113 35.095 1.34461 +VERTEX2 279 -14.0304 36.0671 1.34851 +VERTEX2 280 -13.7678 37.075 1.36982 +VERTEX2 281 -14.7563 37.2461 2.92596 +VERTEX2 282 -15.7296 37.4685 2.916 +VERTEX2 283 -16.7 37.746 2.88261 +VERTEX2 284 -17.744 37.9982 2.87691 +VERTEX2 285 -18.7522 38.2356 2.85674 +VERTEX2 286 -19.0352 37.3433 -1.86137 +VERTEX2 287 -19.3624 36.4026 -1.83748 +VERTEX2 288 -19.6776 35.4624 -1.85277 +VERTEX2 289 -20.0675 34.5059 -1.87227 +VERTEX2 290 -20.3325 33.4871 -1.87521 +VERTEX2 291 -19.3884 33.2176 -0.339053 +VERTEX2 292 -18.4374 32.924 -0.336411 +VERTEX2 293 -17.4745 32.5773 -0.325113 +VERTEX2 294 -16.5439 32.2316 -0.303294 +VERTEX2 295 -15.6398 31.8362 -0.318577 +VERTEX2 296 -15.3277 32.7585 1.26981 +VERTEX2 297 -15.0473 33.704 1.28355 +VERTEX2 298 -14.7905 34.7517 1.28236 +VERTEX2 299 -14.5228 35.751 1.28641 +VERTEX2 300 -14.2213 36.699 1.28485 +VERTEX2 301 -13.2077 36.3092 -0.318856 +VERTEX2 302 -12.3042 36.0075 -0.312494 +VERTEX2 303 -11.4225 35.687 -0.319939 +VERTEX2 304 -10.5137 35.4147 -0.313426 +VERTEX2 305 -9.45538 35.1233 -0.321963 +VERTEX2 306 -9.7909 34.2226 -1.92684 +VERTEX2 307 -10.1565 33.3304 -1.91452 +VERTEX2 308 -10.5241 32.3545 -1.91797 +VERTEX2 309 -10.8732 31.3376 -1.92723 +VERTEX2 310 -11.1837 30.4706 -1.89662 +VERTEX2 311 -12.1179 30.7944 2.82715 +VERTEX2 312 -13.0638 31.1527 2.86071 +VERTEX2 313 -14.0315 31.4904 2.82928 +VERTEX2 314 -15.0417 31.7356 2.8523 +VERTEX2 315 -16.0322 31.9509 2.84906 +VERTEX2 316 -16.3984 30.9912 -1.89255 +VERTEX2 317 -16.7651 30.0772 -1.90822 +VERTEX2 318 -17.0457 29.103 -1.89048 +VERTEX2 319 -17.3979 28.1649 -1.87927 +VERTEX2 320 -17.6834 27.1439 -1.8939 +VERTEX2 321 -18.6401 27.5299 2.77126 +VERTEX2 322 -19.6147 27.8401 2.78246 +VERTEX2 323 -20.5004 28.2085 2.77971 +VERTEX2 324 -21.4133 28.578 2.78845 +VERTEX2 325 -22.2835 28.9053 2.77508 +VERTEX2 326 -22.5504 27.9067 -1.91959 +VERTEX2 327 -22.8123 26.9518 -1.91532 +VERTEX2 328 -23.174 26.0094 -1.9084 +VERTEX2 329 -23.5476 25.0236 -1.92869 +VERTEX2 330 -23.7985 24.1215 -1.9256 +VERTEX2 331 -22.8583 23.7922 -0.345008 +VERTEX2 332 -21.8583 23.4649 -0.358998 +VERTEX2 333 -20.8569 23.1006 -0.371323 +VERTEX2 334 -19.9834 22.7196 -0.369225 +VERTEX2 335 -19.0585 22.319 -0.376194 +VERTEX2 336 -18.634 23.2053 1.19002 +VERTEX2 337 -18.2617 24.1418 1.19986 +VERTEX2 338 -17.9894 25.0752 1.23256 +VERTEX2 339 -17.6828 26.0077 1.24314 +VERTEX2 340 -17.3351 26.9921 1.21103 +VERTEX2 341 -18.2116 27.3619 2.7653 +VERTEX2 342 -19.144 27.7007 2.78166 +VERTEX2 343 -20.0757 28.065 2.77345 +VERTEX2 344 -20.9293 28.4635 2.81324 +VERTEX2 345 -21.8963 28.8299 2.82458 +VERTEX2 346 -22.1786 27.8751 -1.93268 +VERTEX2 347 -22.5127 26.9779 -1.94886 +VERTEX2 348 -22.828 26.0345 -1.96537 +VERTEX2 349 -23.2289 25.1817 -1.9617 +VERTEX2 350 -23.6294 24.2901 -1.97133 +VERTEX2 351 -24.5391 24.5992 2.73979 +VERTEX2 352 -25.4309 25.013 2.74053 +VERTEX2 353 -26.3734 25.328 2.71417 +VERTEX2 354 -27.2588 25.7573 2.75051 +VERTEX2 355 -28.2459 26.1965 2.76734 +VERTEX2 356 -28.6742 25.2946 -1.95286 +VERTEX2 357 -29.0163 24.3446 -1.93904 +VERTEX2 358 -29.3925 23.384 -1.95777 +VERTEX2 359 -29.7684 22.4639 -1.96179 +VERTEX2 360 -30.1419 21.4981 -1.99236 +VERTEX2 361 -29.2053 21.0274 -0.419895 +VERTEX2 362 -28.3587 20.6403 -0.387469 +VERTEX2 363 -27.4761 20.3164 -0.376801 +VERTEX2 364 -26.4702 20.0618 -0.381542 +VERTEX2 365 -25.5156 19.7201 -0.388107 +VERTEX2 366 -25.09 20.5839 1.19436 +VERTEX2 367 -24.769 21.6187 1.19079 +VERTEX2 368 -24.3914 22.5497 1.22208 +VERTEX2 369 -24.0584 23.5108 1.25873 +VERTEX2 370 -23.7005 24.4922 1.28808 +VERTEX2 371 -24.6986 24.8846 2.88144 +VERTEX2 372 -25.6465 25.2082 2.8878 +VERTEX2 373 -26.6076 25.4374 2.91634 +VERTEX2 374 -27.6151 25.6313 2.91156 +VERTEX2 375 -28.5505 25.8482 2.92837 +VERTEX2 376 -28.3029 26.7594 1.36296 +VERTEX2 377 -28.1199 27.7541 1.34903 +VERTEX2 378 -27.8674 28.7941 1.33028 +VERTEX2 379 -27.6428 29.7534 1.35401 +VERTEX2 380 -27.3438 30.6897 1.34736 +VERTEX2 381 -26.3313 30.4266 -0.242469 +VERTEX2 382 -25.369 30.2281 -0.257587 +VERTEX2 383 -24.3704 30.04 -0.245353 +VERTEX2 384 -23.3959 29.8264 -0.227806 +VERTEX2 385 -22.4431 29.6227 -0.204447 +VERTEX2 386 -22.1877 30.5583 1.39411 +VERTEX2 387 -21.9428 31.5497 1.38656 +VERTEX2 388 -21.7985 32.6262 1.42117 +VERTEX2 389 -21.62 33.6429 1.43928 +VERTEX2 390 -21.4424 34.6363 1.42607 +VERTEX2 391 -20.4783 34.4613 -0.163793 +VERTEX2 392 -19.515 34.4065 -0.185647 +VERTEX2 393 -18.5137 34.232 -0.172033 +VERTEX2 394 -17.4763 34.0636 -0.174621 +VERTEX2 395 -16.4323 33.9721 -0.18919 +VERTEX2 396 -16.249 34.9471 1.39622 +VERTEX2 397 -16.0593 35.9076 1.40199 +VERTEX2 398 -15.8523 36.858 1.40067 +VERTEX2 399 -15.7188 37.8348 1.43222 +VERTEX2 400 -15.6876 38.7977 1.47882 +VERTEX2 401 -16.7085 38.8344 3.0652 +VERTEX2 402 -17.6405 38.8762 3.07312 +VERTEX2 403 -18.6831 38.9395 3.03995 +VERTEX2 404 -19.636 39.0568 3.07563 +VERTEX2 405 -20.6096 39.0536 3.10228 +VERTEX2 406 -20.6611 38.0146 -1.59817 +VERTEX2 407 -20.6602 36.9905 -1.61391 +VERTEX2 408 -20.666 36.0257 -1.61759 +VERTEX2 409 -20.7377 35.0383 -1.62027 +VERTEX2 410 -20.7528 34.0078 -1.62894 +VERTEX2 411 -19.7475 33.9495 -0.0521872 +VERTEX2 412 -18.7921 33.8745 -0.056291 +VERTEX2 413 -17.8845 33.8383 -0.0692387 +VERTEX2 414 -16.9345 33.7772 -0.0626386 +VERTEX2 415 -15.893 33.714 -0.0308337 +VERTEX2 416 -15.9293 32.6855 -1.59268 +VERTEX2 417 -15.9728 31.6386 -1.58004 +VERTEX2 418 -15.9688 30.6634 -1.57192 +VERTEX2 419 -15.9158 29.656 -1.57184 +VERTEX2 420 -15.9716 28.6282 -1.60697 +VERTEX2 421 -17.015 28.6097 3.11305 +VERTEX2 422 -18.0815 28.6471 -3.12371 +VERTEX2 423 -19.1056 28.7267 -3.12006 +VERTEX2 424 -20.1002 28.5618 -3.12378 +VERTEX2 425 -21.1118 28.5738 3.13581 +VERTEX2 426 -21.002 29.557 1.57956 +VERTEX2 427 -21.0645 30.5216 1.58428 +VERTEX2 428 -21.0061 31.5983 1.59068 +VERTEX2 429 -21.0978 32.6637 1.5728 +VERTEX2 430 -21.0999 33.7164 1.56708 +VERTEX2 431 -20.1415 33.7711 -0.00796042 +VERTEX2 432 -19.1367 33.8244 -0.0269536 +VERTEX2 433 -18.1687 33.9017 -0.0206863 +VERTEX2 434 -17.2404 33.8303 -0.00308791 +VERTEX2 435 -16.1908 33.7664 0.0044507 +VERTEX2 436 -16.1697 34.7566 1.57882 +VERTEX2 437 -16.1593 35.6998 1.59318 +VERTEX2 438 -16.1701 36.6987 1.59227 +VERTEX2 439 -16.2103 37.6566 1.59269 +VERTEX2 440 -16.2563 38.6675 1.60529 +VERTEX2 441 -17.2887 38.6577 -3.12015 +VERTEX2 442 -18.2946 38.6139 -3.11699 +VERTEX2 443 -19.3174 38.5031 -3.08179 +VERTEX2 444 -20.2516 38.4505 -3.08456 +VERTEX2 445 -21.2156 38.3987 -3.07697 +VERTEX2 446 -21.2076 37.3547 -1.4834 +VERTEX2 447 -21.0911 36.3677 -1.49234 +VERTEX2 448 -21.0205 35.3987 -1.48586 +VERTEX2 449 -20.8273 34.3143 -1.49041 +VERTEX2 450 -20.6989 33.3054 -1.47538 +VERTEX2 451 -19.6942 33.3338 0.0712095 +VERTEX2 452 -18.7357 33.4346 0.0769025 +VERTEX2 453 -17.8039 33.5266 0.0628561 +VERTEX2 454 -16.8361 33.484 0.0566204 +VERTEX2 455 -15.727 33.5384 0.0505723 +VERTEX2 456 -15.7124 34.5607 1.58273 +VERTEX2 457 -15.7464 35.5518 1.58792 +VERTEX2 458 -15.754 36.5886 1.56447 +VERTEX2 459 -15.6649 37.5279 1.5594 +VERTEX2 460 -15.7398 38.5341 1.58711 +VERTEX2 461 -16.8077 38.5603 -3.11573 +VERTEX2 462 -17.7759 38.4898 -3.07059 +VERTEX2 463 -18.8834 38.4116 -3.07478 +VERTEX2 464 -19.8479 38.3587 -3.09401 +VERTEX2 465 -20.8661 38.2304 -3.10684 +VERTEX2 466 -20.8075 37.2047 -1.52683 +VERTEX2 467 -20.779 36.2848 -1.55015 +VERTEX2 468 -20.6945 35.2877 -1.56995 +VERTEX2 469 -20.6358 34.2614 -1.56458 +VERTEX2 470 -20.6463 33.2925 -1.59838 +VERTEX2 471 -19.5773 33.3107 -0.0447117 +VERTEX2 472 -18.539 33.3718 -0.0347506 +VERTEX2 473 -17.5573 33.3363 -0.026354 +VERTEX2 474 -16.5009 33.4361 -0.0462468 +VERTEX2 475 -15.4892 33.3726 -0.0265261 +VERTEX2 476 -15.4475 34.4479 1.56715 +VERTEX2 477 -15.4307 35.4387 1.56971 +VERTEX2 478 -15.4559 36.4302 1.5765 +VERTEX2 479 -15.4588 37.4202 1.57899 +VERTEX2 480 -15.5089 38.4834 1.57828 +VERTEX2 481 -16.5774 38.4369 3.12989 +VERTEX2 482 -17.5579 38.5364 3.12642 +VERTEX2 483 -18.6101 38.5232 3.13081 +VERTEX2 484 -19.6845 38.5496 3.11261 +VERTEX2 485 -20.6666 38.5573 3.13313 +VERTEX2 486 -20.627 39.5345 1.57895 +VERTEX2 487 -20.6097 40.4498 1.58324 +VERTEX2 488 -20.6518 41.3839 1.60197 +VERTEX2 489 -20.7194 42.4555 1.60489 +VERTEX2 490 -20.7839 43.4675 1.62853 +VERTEX2 491 -21.7812 43.3464 -3.06077 +VERTEX2 492 -22.7651 43.3524 -3.07233 +VERTEX2 493 -23.7137 43.2676 -3.08112 +VERTEX2 494 -24.7108 43.1861 -3.1228 +VERTEX2 495 -25.7169 43.1162 -3.12734 +VERTEX2 496 -25.619 42.0863 -1.55635 +VERTEX2 497 -25.7084 41.0983 -1.57379 +VERTEX2 498 -25.7233 39.9648 -1.59447 +VERTEX2 499 -25.6885 38.8444 -1.62745 +VERTEX2 500 -25.8082 37.826 -1.59967 +VERTEX2 501 -26.8249 37.8904 3.10413 +VERTEX2 502 -27.8383 37.8749 3.1207 +VERTEX2 503 -28.9027 37.8553 3.11469 +VERTEX2 504 -29.9196 37.8782 3.12054 +VERTEX2 505 -30.9371 37.9088 3.11621 +VERTEX2 506 -30.9629 36.9776 -1.58487 +VERTEX2 507 -30.9939 35.9428 -1.57237 +VERTEX2 508 -30.9699 34.8807 -1.55654 +VERTEX2 509 -30.9624 33.8153 -1.5756 +VERTEX2 510 -30.9054 32.7995 -1.56046 +VERTEX2 511 -31.9238 32.8201 3.1276 +VERTEX2 512 -32.92 32.8315 3.13714 +VERTEX2 513 -33.9926 32.8478 3.12515 +VERTEX2 514 -34.9629 32.8578 -3.10501 +VERTEX2 515 -35.9359 32.8872 -3.10831 +VERTEX2 516 -35.8714 31.9253 -1.54071 +VERTEX2 517 -35.8734 30.9232 -1.5386 +VERTEX2 518 -35.8466 29.8972 -1.5636 +VERTEX2 519 -35.9587 28.8379 -1.55838 +VERTEX2 520 -35.927 27.815 -1.56138 +VERTEX2 521 -36.975 27.893 -3.12172 +VERTEX2 522 -38.0207 27.8224 -3.11362 +VERTEX2 523 -38.966 27.787 -3.1181 +VERTEX2 524 -39.9962 27.9022 -3.10857 +VERTEX2 525 -40.9606 27.96 -3.10061 +VERTEX2 526 -40.8989 26.968 -1.53518 +VERTEX2 527 -40.8216 25.9807 -1.51264 +VERTEX2 528 -40.7048 24.9999 -1.49511 +VERTEX2 529 -40.5554 23.9958 -1.45133 +VERTEX2 530 -40.4688 22.9643 -1.46467 +VERTEX2 531 -39.5134 23.1017 0.111118 +VERTEX2 532 -38.606 23.2063 0.0906616 +VERTEX2 533 -37.5833 23.3372 0.109496 +VERTEX2 534 -36.5849 23.4548 0.131992 +VERTEX2 535 -35.6826 23.6008 0.105104 +VERTEX2 536 -35.804 24.5184 1.65318 +VERTEX2 537 -35.9447 25.5368 1.65844 +VERTEX2 538 -35.9628 26.5835 1.68707 +VERTEX2 539 -36.1223 27.6562 1.72951 +VERTEX2 540 -36.3303 28.712 1.72896 +VERTEX2 541 -35.3277 28.824 0.163767 +VERTEX2 542 -34.341 28.9517 0.206348 +VERTEX2 543 -33.428 29.1756 0.185649 +VERTEX2 544 -32.5554 29.4219 0.181183 +VERTEX2 545 -31.5665 29.6919 0.205359 +VERTEX2 546 -31.4265 28.7439 -1.36439 +VERTEX2 547 -31.2645 27.7504 -1.35927 +VERTEX2 548 -31.0016 26.6924 -1.33592 +VERTEX2 549 -30.7484 25.695 -1.33819 +VERTEX2 550 -30.5453 24.7153 -1.35332 +VERTEX2 551 -31.6392 24.5421 -2.94047 +VERTEX2 552 -32.5928 24.2634 -2.93748 +VERTEX2 553 -33.5375 23.9883 -2.95063 +VERTEX2 554 -34.5053 23.7055 -2.95621 +VERTEX2 555 -35.5168 23.5134 -2.93892 +VERTEX2 556 -35.3024 22.5561 -1.38119 +VERTEX2 557 -35.1096 21.6194 -1.36074 +VERTEX2 558 -34.8436 20.5562 -1.3806 +VERTEX2 559 -34.5976 19.5913 -1.40553 +VERTEX2 560 -34.4969 18.5549 -1.43055 +VERTEX2 561 -35.4984 18.4339 -3.00045 +VERTEX2 562 -36.4775 18.3044 -2.9826 +VERTEX2 563 -37.4226 18.1251 -3.00977 +VERTEX2 564 -38.4417 18.0143 -3.00536 +VERTEX2 565 -39.4207 17.8236 -3.02269 +VERTEX2 566 -39.356 16.8019 -1.44369 +VERTEX2 567 -39.2731 15.8434 -1.40812 +VERTEX2 568 -39.1723 14.848 -1.39642 +VERTEX2 569 -38.9924 13.7904 -1.35397 +VERTEX2 570 -38.7902 12.8783 -1.35036 +VERTEX2 571 -39.7912 12.7865 -2.89684 +VERTEX2 572 -40.8111 12.6045 -2.89672 +VERTEX2 573 -41.8832 12.3676 -2.92148 +VERTEX2 574 -42.7849 12.1571 -2.91922 +VERTEX2 575 -43.6555 11.9582 -2.90483 +VERTEX2 576 -43.3581 10.988 -1.32562 +VERTEX2 577 -43.1881 10.0829 -1.31886 +VERTEX2 578 -42.9614 9.145 -1.31429 +VERTEX2 579 -42.6528 8.17221 -1.25377 +VERTEX2 580 -42.3244 7.21948 -1.23804 +VERTEX2 581 -43.3202 6.93211 -2.8157 +VERTEX2 582 -44.2591 6.69289 -2.83828 +VERTEX2 583 -45.1786 6.43882 -2.82063 +VERTEX2 584 -46.2132 6.08163 -2.85554 +VERTEX2 585 -47.1453 5.90572 -2.85541 +VERTEX2 586 -46.907 4.82954 -1.32687 +VERTEX2 587 -46.6772 3.86996 -1.29134 +VERTEX2 588 -46.3498 2.90769 -1.29197 +VERTEX2 589 -46.0623 1.94628 -1.32324 +VERTEX2 590 -45.7736 1.02674 -1.33422 +VERTEX2 591 -46.6854 0.763833 -2.91134 +VERTEX2 592 -47.6583 0.468389 -2.89787 +VERTEX2 593 -48.5857 0.284282 -2.89852 +VERTEX2 594 -49.5594 0.12518 -2.9448 +VERTEX2 595 -50.4984 -0.0739373 -2.93749 +VERTEX2 596 -50.3568 -1.03602 -1.37384 +VERTEX2 597 -50.2183 -2.06684 -1.37834 +VERTEX2 598 -50.0039 -3.05411 -1.39443 +VERTEX2 599 -49.8883 -4.06061 -1.40454 +VERTEX2 600 -49.6528 -5.01397 -1.40687 +VERTEX2 601 -48.6774 -4.86862 0.133456 +VERTEX2 602 -47.7752 -4.75667 0.142568 +VERTEX2 603 -46.76 -4.60527 0.0958657 +VERTEX2 604 -45.8175 -4.48571 0.12711 +VERTEX2 605 -44.6973 -4.30745 0.155031 +VERTEX2 606 -44.5693 -5.26432 -1.41126 +VERTEX2 607 -44.3542 -6.22993 -1.40932 +VERTEX2 608 -44.2066 -7.21197 -1.41567 +VERTEX2 609 -44.1165 -8.10264 -1.41239 +VERTEX2 610 -43.9601 -9.09737 -1.43514 +VERTEX2 611 -44.9516 -9.26971 -3.04093 +VERTEX2 612 -46.0113 -9.30883 -3.06309 +VERTEX2 613 -46.8852 -9.36808 -3.06266 +VERTEX2 614 -47.8935 -9.49085 -3.06295 +VERTEX2 615 -48.8586 -9.59517 -3.05772 +VERTEX2 616 -48.7866 -10.5949 -1.47851 +VERTEX2 617 -48.6953 -11.6065 -1.48143 +VERTEX2 618 -48.5654 -12.5841 -1.50002 +VERTEX2 619 -48.495 -13.4789 -1.49079 +VERTEX2 620 -48.3229 -14.5342 -1.49641 +VERTEX2 621 -49.3584 -14.5726 -3.07087 +VERTEX2 622 -50.3368 -14.6909 -3.08496 +VERTEX2 623 -51.3678 -14.6928 -3.11971 +VERTEX2 624 -52.3266 -14.6801 -3.10734 +VERTEX2 625 -53.314 -14.7485 -3.12081 +VERTEX2 626 -53.2913 -13.7338 1.55877 +VERTEX2 627 -53.2373 -12.7794 1.55096 +VERTEX2 628 -53.2567 -11.7593 1.56609 +VERTEX2 629 -53.2344 -10.7285 1.55205 +VERTEX2 630 -53.2076 -9.73736 1.55954 +VERTEX2 631 -54.1981 -9.65468 3.12434 +VERTEX2 632 -55.173 -9.69023 3.12313 +VERTEX2 633 -56.1151 -9.66489 3.1189 +VERTEX2 634 -57.099 -9.69483 3.10769 +VERTEX2 635 -58.0125 -9.76834 3.10907 +VERTEX2 636 -58.0476 -10.7582 -1.63549 +VERTEX2 637 -58.066 -11.7669 -1.64131 +VERTEX2 638 -58.1335 -12.7881 -1.59849 +VERTEX2 639 -58.1527 -13.7578 -1.56366 +VERTEX2 640 -58.123 -14.7728 -1.54041 +VERTEX2 641 -57.1544 -14.769 0.0180519 +VERTEX2 642 -56.1871 -14.7816 -0.000877353 +VERTEX2 643 -55.213 -14.8962 -0.0289206 +VERTEX2 644 -54.2373 -14.9259 -0.0434696 +VERTEX2 645 -53.2881 -15.0225 -0.0563827 +VERTEX2 646 -53.2514 -14.0714 1.49912 +VERTEX2 647 -53.1507 -13.1166 1.51586 +VERTEX2 648 -53.1326 -12.1812 1.53013 +VERTEX2 649 -53.0836 -11.2239 1.50189 +VERTEX2 650 -53.1576 -10.2684 1.46791 +VERTEX2 651 -54.166 -10.1743 3.01388 +VERTEX2 652 -55.1265 -10.0717 3.01446 +VERTEX2 653 -56.1456 -9.94837 2.99837 +VERTEX2 654 -57.1764 -9.83205 3.03798 +VERTEX2 655 -58.2464 -9.77103 3.04202 +VERTEX2 656 -58.3473 -10.6876 -1.69677 +VERTEX2 657 -58.4882 -11.6211 -1.69785 +VERTEX2 658 -58.6966 -12.5952 -1.69994 +VERTEX2 659 -58.8265 -13.5349 -1.68784 +VERTEX2 660 -58.9994 -14.5065 -1.66331 +VERTEX2 661 -60.0154 -14.4319 3.06632 +VERTEX2 662 -60.9796 -14.3369 3.11079 +VERTEX2 663 -62.0147 -14.3206 3.08177 +VERTEX2 664 -63.0222 -14.2972 3.14141 +VERTEX2 665 -64.0002 -14.3727 3.13898 +VERTEX2 666 -63.9774 -15.4207 -1.54213 +VERTEX2 667 -64.0195 -16.3328 -1.53643 +VERTEX2 668 -64.0644 -17.3227 -1.50278 +VERTEX2 669 -63.9104 -18.3057 -1.53483 +VERTEX2 670 -63.8654 -19.3377 -1.50421 +VERTEX2 671 -62.9445 -19.3485 0.0935826 +VERTEX2 672 -61.9917 -19.1549 0.0930683 +VERTEX2 673 -60.9557 -19.1136 0.120736 +VERTEX2 674 -60.0189 -18.8668 0.139983 +VERTEX2 675 -59.0639 -18.8051 0.131913 +VERTEX2 676 -58.9131 -19.8087 -1.42163 +VERTEX2 677 -58.7475 -20.73 -1.38146 +VERTEX2 678 -58.4682 -21.7642 -1.40073 +VERTEX2 679 -58.3532 -22.785 -1.41669 +VERTEX2 680 -58.209 -23.8232 -1.43306 +VERTEX2 681 -57.1974 -23.6097 0.142638 +VERTEX2 682 -56.2229 -23.5334 0.148882 +VERTEX2 683 -55.18 -23.3441 0.173444 +VERTEX2 684 -54.2083 -23.2107 0.168107 +VERTEX2 685 -53.1447 -23.1096 0.16971 +VERTEX2 686 -52.9543 -24.0955 -1.38573 +VERTEX2 687 -52.7515 -25.0997 -1.36215 +VERTEX2 688 -52.4995 -26.0897 -1.36311 +VERTEX2 689 -52.284 -27.0376 -1.38193 +VERTEX2 690 -52.0978 -28.0231 -1.36593 +VERTEX2 691 -51.1215 -27.7246 0.188524 +VERTEX2 692 -50.1045 -27.5182 0.182094 +VERTEX2 693 -49.1512 -27.3974 0.173912 +VERTEX2 694 -48.1163 -27.2849 0.185823 +VERTEX2 695 -47.2155 -27.0169 0.15977 +VERTEX2 696 -47.1406 -28.0547 -1.43179 +VERTEX2 697 -46.9913 -29.0582 -1.39038 +VERTEX2 698 -46.7801 -30.0848 -1.37639 +VERTEX2 699 -46.6245 -31.0673 -1.37251 +VERTEX2 700 -46.3665 -31.9277 -1.3556 +VERTEX2 701 -47.3876 -32.0831 -2.90824 +VERTEX2 702 -48.4226 -32.3542 -2.94082 +VERTEX2 703 -49.4123 -32.5772 -2.93052 +VERTEX2 704 -50.3365 -32.814 -2.94132 +VERTEX2 705 -51.2611 -33.0185 -2.96166 +VERTEX2 706 -51.1798 -34.0665 -1.38618 +VERTEX2 707 -50.9465 -35.122 -1.36089 +VERTEX2 708 -50.7667 -36.0061 -1.34414 +VERTEX2 709 -50.5097 -37.0147 -1.34478 +VERTEX2 710 -50.2854 -37.9703 -1.36655 +VERTEX2 711 -49.3142 -37.7843 0.203534 +VERTEX2 712 -48.4129 -37.6341 0.193037 +VERTEX2 713 -47.4127 -37.4806 0.133577 +VERTEX2 714 -46.4512 -37.3979 0.109727 +VERTEX2 715 -45.4808 -37.2902 0.0824423 +VERTEX2 716 -45.3962 -38.3382 -1.48105 +VERTEX2 717 -45.2954 -39.3581 -1.47503 +VERTEX2 718 -45.1678 -40.3227 -1.44086 +VERTEX2 719 -45.0369 -41.2922 -1.42559 +VERTEX2 720 -44.8889 -42.2358 -1.45315 +VERTEX2 721 -45.8506 -42.2693 -3.03368 +VERTEX2 722 -46.8411 -42.3338 -3.04579 +VERTEX2 723 -47.7928 -42.4122 -3.06063 +VERTEX2 724 -48.761 -42.5297 -3.02213 +VERTEX2 725 -49.6967 -42.5947 -3.01838 +VERTEX2 726 -49.886 -41.5765 1.6912 +VERTEX2 727 -49.9789 -40.5749 1.68992 +VERTEX2 728 -50.205 -39.5732 1.68282 +VERTEX2 729 -50.28 -38.5962 1.68821 +VERTEX2 730 -50.3821 -37.6855 1.67733 +VERTEX2 731 -49.4115 -37.5508 0.159167 +VERTEX2 732 -48.5278 -37.3818 0.162956 +VERTEX2 733 -47.5244 -37.2027 0.169578 +VERTEX2 734 -46.5208 -37.0035 0.16225 +VERTEX2 735 -45.513 -36.8342 0.132502 +VERTEX2 736 -45.639 -35.781 1.72963 +VERTEX2 737 -45.6825 -34.7923 1.71095 +VERTEX2 738 -45.7812 -33.7404 1.71413 +VERTEX2 739 -45.9814 -32.7149 1.69935 +VERTEX2 740 -46.0593 -31.7922 1.69307 +VERTEX2 741 -45.0466 -31.6887 0.094065 +VERTEX2 742 -44.0813 -31.5333 0.0389496 +VERTEX2 743 -43.0685 -31.563 0.0446127 +VERTEX2 744 -42.0541 -31.4992 0.0405451 +VERTEX2 745 -41.0079 -31.4467 0.0440895 +VERTEX2 746 -41.005 -30.4539 1.58707 +VERTEX2 747 -41.0307 -29.4307 1.61307 +VERTEX2 748 -41.0555 -28.481 1.5931 +VERTEX2 749 -41.1619 -27.543 1.548 +VERTEX2 750 -41.2201 -26.5007 1.5765 +VERTEX2 751 -42.1706 -26.4798 -3.10908 +VERTEX2 752 -43.1754 -26.4553 -3.10302 +VERTEX2 753 -44.2126 -26.508 -3.0898 +VERTEX2 754 -45.2818 -26.5448 -3.11839 +VERTEX2 755 -46.2725 -26.4569 -3.085 +VERTEX2 756 -46.2189 -27.4485 -1.53947 +VERTEX2 757 -46.2638 -28.4456 -1.54449 +VERTEX2 758 -46.2667 -29.4466 -1.52489 +VERTEX2 759 -46.2721 -30.5047 -1.53177 +VERTEX2 760 -46.1916 -31.3934 -1.5403 +VERTEX2 761 -45.1691 -31.3175 0.0347229 +VERTEX2 762 -44.1604 -31.2652 0.0248278 +VERTEX2 763 -43.1477 -31.2965 -0.0129862 +VERTEX2 764 -42.1521 -31.3015 0.0122871 +VERTEX2 765 -41.0612 -31.3234 0.0371727 +VERTEX2 766 -41.1252 -30.2236 1.59303 +VERTEX2 767 -41.1681 -29.179 1.59011 +VERTEX2 768 -41.205 -28.214 1.61905 +VERTEX2 769 -41.2801 -27.2255 1.60797 +VERTEX2 770 -41.3161 -26.2791 1.59926 +VERTEX2 771 -42.2907 -26.3925 -3.09105 +VERTEX2 772 -43.2732 -26.5085 -3.10097 +VERTEX2 773 -44.3234 -26.5203 -3.062 +VERTEX2 774 -45.3136 -26.533 -3.03961 +VERTEX2 775 -46.3421 -26.6032 -3.04092 +VERTEX2 776 -46.3298 -27.616 -1.4592 +VERTEX2 777 -46.2615 -28.5199 -1.461 +VERTEX2 778 -46.1695 -29.5608 -1.47333 +VERTEX2 779 -46.0825 -30.6383 -1.47862 +VERTEX2 780 -46.0067 -31.6322 -1.46551 +VERTEX2 781 -45.0551 -31.534 0.127203 +VERTEX2 782 -44.076 -31.4013 0.155961 +VERTEX2 783 -43.1381 -31.2801 0.150139 +VERTEX2 784 -42.1365 -31.1664 0.149846 +VERTEX2 785 -41.1566 -31.0267 0.171919 +VERTEX2 786 -41.3107 -30.0084 1.75913 +VERTEX2 787 -41.5974 -29.0046 1.71928 +VERTEX2 788 -41.6788 -28.0393 1.72657 +VERTEX2 789 -41.8546 -27.0481 1.73702 +VERTEX2 790 -41.8953 -26.0893 1.72976 +VERTEX2 791 -42.9275 -26.2676 -3.00694 +VERTEX2 792 -43.9022 -26.4284 -2.99154 +VERTEX2 793 -44.8209 -26.6187 -2.99442 +VERTEX2 794 -45.7858 -26.821 -2.98035 +VERTEX2 795 -46.8778 -27.0908 -2.9758 +VERTEX2 796 -46.6883 -28.0147 -1.37381 +VERTEX2 797 -46.4991 -29.0196 -1.40055 +VERTEX2 798 -46.2546 -30.0195 -1.40083 +VERTEX2 799 -46.1811 -31.0212 -1.40848 +VERTEX2 800 -45.9708 -31.9988 -1.40855 +VERTEX2 801 -44.9869 -31.8942 0.155184 +VERTEX2 802 -43.9435 -31.8109 0.189965 +VERTEX2 803 -43.012 -31.6843 0.150502 +VERTEX2 804 -42.0569 -31.5254 0.142 +VERTEX2 805 -41.002 -31.3111 0.153426 +VERTEX2 806 -41.1163 -30.2605 1.71703 +VERTEX2 807 -41.2694 -29.3126 1.712 +VERTEX2 808 -41.3943 -28.3957 1.7574 +VERTEX2 809 -41.5982 -27.4213 1.78392 +VERTEX2 810 -41.8814 -26.4592 1.7908 +VERTEX2 811 -42.932 -26.7759 -2.91207 +VERTEX2 812 -43.8105 -27.0144 -2.94899 +VERTEX2 813 -44.7905 -27.285 -2.97308 +VERTEX2 814 -45.7227 -27.5146 -2.97724 +VERTEX2 815 -46.5868 -27.6841 -3.01087 +VERTEX2 816 -46.5012 -28.7057 -1.477 +VERTEX2 817 -46.4221 -29.6554 -1.49557 +VERTEX2 818 -46.3566 -30.6613 -1.52859 +VERTEX2 819 -46.2271 -31.5902 -1.52562 +VERTEX2 820 -46.0777 -32.5591 -1.4942 +VERTEX2 821 -47.1264 -32.6673 -3.06739 +VERTEX2 822 -48.0976 -32.8121 -3.06231 +VERTEX2 823 -49.0597 -32.9891 -3.03795 +VERTEX2 824 -50.0501 -33.0877 -3.02583 +VERTEX2 825 -51.1178 -33.2044 -3.04899 +VERTEX2 826 -51.2845 -32.174 1.67099 +VERTEX2 827 -51.4472 -31.1992 1.6698 +VERTEX2 828 -51.4847 -30.2989 1.67924 +VERTEX2 829 -51.6615 -29.3071 1.68417 +VERTEX2 830 -51.776 -28.3511 1.66148 +VERTEX2 831 -52.7624 -28.4482 -3.02897 +VERTEX2 832 -53.8126 -28.5665 -3.02928 +VERTEX2 833 -54.7231 -28.6884 -3.00696 +VERTEX2 834 -55.6937 -28.8093 -2.99203 +VERTEX2 835 -56.5269 -28.9746 -2.97884 +VERTEX2 836 -56.3315 -29.9749 -1.38032 +VERTEX2 837 -56.0916 -30.9434 -1.341 +VERTEX2 838 -55.7339 -31.9449 -1.32891 +VERTEX2 839 -55.5442 -32.9801 -1.30645 +VERTEX2 840 -55.2559 -33.9229 -1.26322 +VERTEX2 841 -54.2583 -33.6433 0.29552 +VERTEX2 842 -53.2823 -33.4276 0.327012 +VERTEX2 843 -52.4101 -33.0488 0.315976 +VERTEX2 844 -51.4488 -32.7657 0.327028 +VERTEX2 845 -50.5321 -32.3643 0.324415 +VERTEX2 846 -50.8846 -31.4565 1.86898 +VERTEX2 847 -51.2763 -30.5007 1.88715 +VERTEX2 848 -51.5753 -29.6683 1.92473 +VERTEX2 849 -51.9599 -28.7394 1.91815 +VERTEX2 850 -52.3484 -27.8238 1.94135 +VERTEX2 851 -53.2403 -28.2363 -2.77481 +VERTEX2 852 -54.1741 -28.5632 -2.78717 +VERTEX2 853 -55.0933 -28.96 -2.77415 +VERTEX2 854 -56.0365 -29.4079 -2.74879 +VERTEX2 855 -56.8865 -29.8152 -2.8045 +VERTEX2 856 -56.5049 -30.7189 -1.23077 +VERTEX2 857 -56.1333 -31.6822 -1.21244 +VERTEX2 858 -55.7032 -32.5808 -1.20847 +VERTEX2 859 -55.261 -33.4879 -1.20951 +VERTEX2 860 -54.905 -34.4286 -1.23304 +VERTEX2 861 -53.8712 -34.0987 0.340213 +VERTEX2 862 -52.8867 -33.7226 0.341676 +VERTEX2 863 -51.9358 -33.3584 0.347405 +VERTEX2 864 -50.9128 -33.0302 0.339396 +VERTEX2 865 -49.899 -32.6635 0.320644 +VERTEX2 866 -50.1671 -31.7161 1.88259 +VERTEX2 867 -50.5278 -30.7579 1.87517 +VERTEX2 868 -50.8432 -29.7431 1.87007 +VERTEX2 869 -51.1271 -28.784 1.84815 +VERTEX2 870 -51.51 -27.7791 1.84275 +VERTEX2 871 -50.5276 -27.5106 0.250131 +VERTEX2 872 -49.5089 -27.2804 0.242901 +VERTEX2 873 -48.5517 -26.9564 0.219053 +VERTEX2 874 -47.5772 -26.6977 0.219029 +VERTEX2 875 -46.6059 -26.4966 0.220207 +VERTEX2 876 -46.7725 -25.4971 1.81126 +VERTEX2 877 -47.137 -24.5477 1.8023 +VERTEX2 878 -47.3933 -23.4987 1.78102 +VERTEX2 879 -47.634 -22.5737 1.76535 +VERTEX2 880 -47.8153 -21.636 1.77965 +VERTEX2 881 -48.7405 -21.9137 -2.93829 +VERTEX2 882 -49.7024 -22.1984 -2.90625 +VERTEX2 883 -50.5948 -22.4132 -2.89522 +VERTEX2 884 -51.6221 -22.688 -2.89545 +VERTEX2 885 -52.6071 -22.9121 -2.85769 +VERTEX2 886 -52.3215 -23.878 -1.28161 +VERTEX2 887 -51.946 -24.8252 -1.33027 +VERTEX2 888 -51.7001 -25.8161 -1.33884 +VERTEX2 889 -51.4615 -26.8116 -1.33 +VERTEX2 890 -51.2125 -27.8176 -1.34481 +VERTEX2 891 -52.1894 -28.0153 -2.93216 +VERTEX2 892 -53.148 -28.2006 -2.90732 +VERTEX2 893 -54.053 -28.3511 -2.89383 +VERTEX2 894 -54.9714 -28.5697 -2.88408 +VERTEX2 895 -55.983 -28.7746 -2.90354 +VERTEX2 896 -55.8191 -29.7559 -1.3359 +VERTEX2 897 -55.5912 -30.7189 -1.31434 +VERTEX2 898 -55.2653 -31.6732 -1.32846 +VERTEX2 899 -55.063 -32.6865 -1.30001 +VERTEX2 900 -54.7675 -33.6292 -1.28876 +VERTEX2 901 -53.8611 -33.4391 0.30405 +VERTEX2 902 -52.8953 -33.1895 0.32786 +VERTEX2 903 -51.9618 -32.8179 0.327422 +VERTEX2 904 -51.0337 -32.5871 0.36942 +VERTEX2 905 -50.1608 -32.3126 0.349641 +VERTEX2 906 -50.4731 -31.3731 1.9654 +VERTEX2 907 -50.8221 -30.3556 1.93471 +VERTEX2 908 -51.1331 -29.4476 1.9654 +VERTEX2 909 -51.4183 -28.586 1.9888 +VERTEX2 910 -51.9007 -27.6836 1.99086 +VERTEX2 911 -52.8118 -27.9945 -2.73149 +VERTEX2 912 -53.7042 -28.3872 -2.73903 +VERTEX2 913 -54.583 -28.7241 -2.69694 +VERTEX2 914 -55.5442 -29.0981 -2.70508 +VERTEX2 915 -56.4394 -29.6253 -2.70068 +VERTEX2 916 -56.9223 -28.6658 1.99252 +VERTEX2 917 -57.309 -27.7307 1.98645 +VERTEX2 918 -57.6338 -26.8664 2.00072 +VERTEX2 919 -58.067 -26.0449 2.02427 +VERTEX2 920 -58.5419 -25.1523 2.03954 +VERTEX2 921 -59.3396 -25.6365 -2.68091 +VERTEX2 922 -60.3083 -26.1804 -2.69283 +VERTEX2 923 -61.301 -26.7159 -2.66454 +VERTEX2 924 -62.1897 -27.1857 -2.66943 +VERTEX2 925 -63.0443 -27.6561 -2.6462 +VERTEX2 926 -63.5231 -26.6979 2.06409 +VERTEX2 927 -64.0393 -25.7912 2.06991 +VERTEX2 928 -64.5686 -24.9607 2.06524 +VERTEX2 929 -65.0379 -24.059 2.05544 +VERTEX2 930 -65.5938 -23.1703 2.05223 +VERTEX2 931 -66.4811 -23.6486 -2.64201 +VERTEX2 932 -67.3221 -24.1764 -2.64057 +VERTEX2 933 -68.0905 -24.6127 -2.64591 +VERTEX2 934 -69.0279 -25.0944 -2.6407 +VERTEX2 935 -69.9223 -25.452 -2.64975 +VERTEX2 936 -69.3964 -26.3278 -1.07183 +VERTEX2 937 -68.8552 -27.1891 -1.09627 +VERTEX2 938 -68.4252 -28.0524 -1.0887 +VERTEX2 939 -67.9263 -28.9949 -1.05686 +VERTEX2 940 -67.42 -29.9425 -1.07197 +VERTEX2 941 -68.2736 -30.4658 -2.62982 +VERTEX2 942 -69.1234 -30.9983 -2.64423 +VERTEX2 943 -69.9064 -31.4245 -2.67178 +VERTEX2 944 -70.7599 -31.8603 -2.68683 +VERTEX2 945 -71.6039 -32.3026 -2.67054 +VERTEX2 946 -72.0936 -31.343 2.01316 +VERTEX2 947 -72.4988 -30.4651 2.00223 +VERTEX2 948 -72.9205 -29.5832 2.00777 +VERTEX2 949 -73.2877 -28.6726 1.95489 +VERTEX2 950 -73.6219 -27.7939 1.92139 +VERTEX2 951 -72.721 -27.4954 0.360975 +VERTEX2 952 -71.8368 -27.1807 0.334102 +VERTEX2 953 -70.8957 -26.8733 0.32018 +VERTEX2 954 -69.9494 -26.5969 0.32757 +VERTEX2 955 -68.9972 -26.3267 0.332126 +VERTEX2 956 -69.4289 -25.4182 1.85416 +VERTEX2 957 -69.6799 -24.4795 1.84126 +VERTEX2 958 -69.8788 -23.5483 1.83443 +VERTEX2 959 -70.1015 -22.5639 1.86715 +VERTEX2 960 -70.358 -21.6797 1.82345 +VERTEX2 961 -71.4076 -21.8737 -2.87252 +VERTEX2 962 -72.3761 -22.1929 -2.88627 +VERTEX2 963 -73.2231 -22.438 -2.89079 +VERTEX2 964 -74.2253 -22.6906 -2.89218 +VERTEX2 965 -75.2259 -22.9362 -2.89184 +VERTEX2 966 -74.9121 -23.8615 -1.29509 +VERTEX2 967 -74.6317 -24.8703 -1.30344 +VERTEX2 968 -74.3479 -25.9801 -1.31919 +VERTEX2 969 -74.0064 -26.9517 -1.33442 +VERTEX2 970 -73.7711 -27.879 -1.30531 +VERTEX2 971 -72.8199 -27.5631 0.262946 +VERTEX2 972 -71.8602 -27.3013 0.237186 +VERTEX2 973 -70.9132 -27.2044 0.227828 +VERTEX2 974 -69.9519 -27.0204 0.245565 +VERTEX2 975 -68.9437 -26.8069 0.249194 +VERTEX2 976 -68.732 -27.8165 -1.31728 +VERTEX2 977 -68.5235 -28.7061 -1.33715 +VERTEX2 978 -68.2036 -29.7195 -1.34792 +VERTEX2 979 -67.9145 -30.7449 -1.3309 +VERTEX2 980 -67.6726 -31.7537 -1.32802 +VERTEX2 981 -68.6558 -31.9681 -2.89633 +VERTEX2 982 -69.5619 -32.1256 -2.92181 +VERTEX2 983 -70.6161 -32.38 -2.90058 +VERTEX2 984 -71.5484 -32.5918 -2.86564 +VERTEX2 985 -72.5572 -32.8465 -2.86607 +VERTEX2 986 -72.2227 -33.8353 -1.33771 +VERTEX2 987 -71.922 -34.918 -1.33253 +VERTEX2 988 -71.7014 -35.9253 -1.31295 +VERTEX2 989 -71.4851 -36.9227 -1.30575 +VERTEX2 990 -71.1527 -37.8053 -1.29358 +VERTEX2 991 -70.2153 -37.5577 0.29858 +VERTEX2 992 -69.335 -37.2099 0.324074 +VERTEX2 993 -68.3613 -36.8264 0.325066 +VERTEX2 994 -67.4976 -36.4817 0.319894 +VERTEX2 995 -66.5278 -36.1947 0.323151 +VERTEX2 996 -66.8433 -35.2587 1.88798 +VERTEX2 997 -67.1525 -34.3661 1.8819 +VERTEX2 998 -67.43 -33.4202 1.88487 +VERTEX2 999 -67.7902 -32.3936 1.92548 +VERTEX2 1000 -68.2118 -31.492 1.93779 +VERTEX2 1001 -69.1293 -31.7804 -2.78079 +VERTEX2 1002 -70.1009 -32.1389 -2.74391 +VERTEX2 1003 -71.0562 -32.5691 -2.71405 +VERTEX2 1004 -72.0053 -33.0595 -2.6817 +VERTEX2 1005 -72.9229 -33.4796 -2.66883 +VERTEX2 1006 -72.4757 -34.3573 -1.11183 +VERTEX2 1007 -72.0996 -35.3383 -1.13358 +VERTEX2 1008 -71.6563 -36.3299 -1.14123 +VERTEX2 1009 -71.1694 -37.3516 -1.15245 +VERTEX2 1010 -70.8062 -38.2239 -1.12579 +VERTEX2 1011 -69.8612 -37.7023 0.43034 +VERTEX2 1012 -68.9889 -37.3075 0.460718 +VERTEX2 1013 -68.164 -36.8883 0.477054 +VERTEX2 1014 -67.2459 -36.4386 0.46958 +VERTEX2 1015 -66.3378 -35.9507 0.466449 +VERTEX2 1016 -66.788 -35.1013 2.06204 +VERTEX2 1017 -67.3573 -34.1699 2.00398 +VERTEX2 1018 -67.7263 -33.2593 1.99771 +VERTEX2 1019 -68.257 -32.3084 1.97909 +VERTEX2 1020 -68.5907 -31.4067 1.99991 +VERTEX2 1021 -69.6152 -31.748 -2.73462 +VERTEX2 1022 -70.4249 -32.0491 -2.71972 +VERTEX2 1023 -71.3476 -32.384 -2.72608 +VERTEX2 1024 -72.2842 -32.7249 -2.71989 +VERTEX2 1025 -73.2314 -33.1525 -2.70637 +VERTEX2 1026 -72.7277 -34.075 -1.13556 +VERTEX2 1027 -72.3546 -34.9537 -1.12843 +VERTEX2 1028 -71.9767 -35.9051 -1.12659 +VERTEX2 1029 -71.4882 -36.8391 -1.1462 +VERTEX2 1030 -71.1322 -37.7194 -1.18759 +VERTEX2 1031 -72.0361 -38.1538 -2.78182 +VERTEX2 1032 -72.9318 -38.4659 -2.78114 +VERTEX2 1033 -73.7602 -38.858 -2.76675 +VERTEX2 1034 -74.6869 -39.2583 -2.74717 +VERTEX2 1035 -75.5924 -39.6767 -2.75678 +VERTEX2 1036 -75.2208 -40.4949 -1.17713 +VERTEX2 1037 -74.7484 -41.4087 -1.22111 +VERTEX2 1038 -74.3712 -42.3864 -1.20953 +VERTEX2 1039 -73.9414 -43.2482 -1.22315 +VERTEX2 1040 -73.5299 -44.1987 -1.22857 +VERTEX2 1041 -72.5303 -43.8927 0.320224 +VERTEX2 1042 -71.6161 -43.6171 0.318519 +VERTEX2 1043 -70.5745 -43.3179 0.293971 +VERTEX2 1044 -69.5797 -43.0416 0.31503 +VERTEX2 1045 -68.6391 -42.7046 0.313206 +VERTEX2 1046 -68.904 -41.7668 1.88263 +VERTEX2 1047 -69.2657 -40.8279 1.89802 +VERTEX2 1048 -69.5325 -39.9065 1.9216 +VERTEX2 1049 -69.9021 -38.9655 1.92552 +VERTEX2 1050 -70.322 -38.06 1.90189 +VERTEX2 1051 -69.3663 -37.7577 0.355856 +VERTEX2 1052 -68.5275 -37.3496 0.30476 +VERTEX2 1053 -67.5722 -37.0566 0.318286 +VERTEX2 1054 -66.6777 -36.7488 0.326713 +VERTEX2 1055 -65.6753 -36.4191 0.276532 +VERTEX2 1056 -65.9381 -35.3569 1.85059 +VERTEX2 1057 -66.2145 -34.3614 1.85674 +VERTEX2 1058 -66.502 -33.353 1.8594 +VERTEX2 1059 -66.7508 -32.3769 1.85506 +VERTEX2 1060 -66.9734 -31.4677 1.86348 +VERTEX2 1061 -67.9614 -31.7351 -2.87445 +VERTEX2 1062 -68.9979 -32.0085 -2.86096 +VERTEX2 1063 -69.9315 -32.1955 -2.86146 +VERTEX2 1064 -70.7672 -32.4756 -2.82432 +VERTEX2 1065 -71.6886 -32.7413 -2.82302 +VERTEX2 1066 -71.3673 -33.7353 -1.25541 +VERTEX2 1067 -71.0718 -34.6274 -1.22219 +VERTEX2 1068 -70.77 -35.6248 -1.2282 +VERTEX2 1069 -70.4846 -36.644 -1.26684 +VERTEX2 1070 -70.2047 -37.5394 -1.24929 +VERTEX2 1071 -69.2384 -37.1939 0.308796 +VERTEX2 1072 -68.2025 -36.9306 0.3239 +VERTEX2 1073 -67.1681 -36.5755 0.340437 +VERTEX2 1074 -66.2321 -36.3249 0.352661 +VERTEX2 1075 -65.2885 -35.9877 0.32145 +VERTEX2 1076 -65.0449 -36.972 -1.2467 +VERTEX2 1077 -64.7625 -37.9683 -1.26488 +VERTEX2 1078 -64.4423 -39.0097 -1.26848 +VERTEX2 1079 -64.1742 -39.9412 -1.26505 +VERTEX2 1080 -63.9125 -40.9622 -1.27631 +VERTEX2 1081 -64.7932 -41.1999 -2.8343 +VERTEX2 1082 -65.73 -41.5446 -2.85085 +VERTEX2 1083 -66.7594 -41.8731 -2.86273 +VERTEX2 1084 -67.7751 -42.0815 -2.87523 +VERTEX2 1085 -68.7534 -42.3512 -2.87753 +VERTEX2 1086 -68.4119 -43.2988 -1.30745 +VERTEX2 1087 -68.1767 -44.2725 -1.31227 +VERTEX2 1088 -67.9307 -45.2725 -1.26847 +VERTEX2 1089 -67.6688 -46.2258 -1.26237 +VERTEX2 1090 -67.2788 -47.1752 -1.25009 +VERTEX2 1091 -66.3971 -46.9392 0.336955 +VERTEX2 1092 -65.3899 -46.6712 0.344183 +VERTEX2 1093 -64.4247 -46.3714 0.380699 +VERTEX2 1094 -63.476 -45.9463 0.383932 +VERTEX2 1095 -62.6852 -45.5909 0.398846 +VERTEX2 1096 -62.2836 -46.5308 -1.15326 +VERTEX2 1097 -61.9461 -47.4809 -1.17981 +VERTEX2 1098 -61.5708 -48.4421 -1.19314 +VERTEX2 1099 -61.1138 -49.3424 -1.20079 +VERTEX2 1100 -60.736 -50.2028 -1.1914 +VERTEX2 1101 -59.8419 -49.8569 0.356392 +VERTEX2 1102 -58.9534 -49.5911 0.348887 +VERTEX2 1103 -58.0005 -49.2577 0.306343 +VERTEX2 1104 -56.9998 -48.8046 0.307769 +VERTEX2 1105 -56.0179 -48.4597 0.328204 +VERTEX2 1106 -56.3913 -47.564 1.90112 +VERTEX2 1107 -56.7129 -46.6582 1.90751 +VERTEX2 1108 -56.9924 -45.7642 1.87922 +VERTEX2 1109 -57.368 -44.7052 1.87292 +VERTEX2 1110 -57.667 -43.7303 1.85427 +VERTEX2 1111 -58.5803 -44.007 -2.84876 +VERTEX2 1112 -59.5112 -44.2867 -2.84334 +VERTEX2 1113 -60.3542 -44.5975 -2.8587 +VERTEX2 1114 -61.4497 -44.9022 -2.88554 +VERTEX2 1115 -62.434 -45.2033 -2.89191 +VERTEX2 1116 -62.119 -46.1446 -1.3367 +VERTEX2 1117 -61.8966 -47.2003 -1.36173 +VERTEX2 1118 -61.7103 -48.1477 -1.38419 +VERTEX2 1119 -61.4432 -49.1577 -1.39962 +VERTEX2 1120 -61.2952 -50.2074 -1.37249 +VERTEX2 1121 -60.2119 -50.0389 0.237857 +VERTEX2 1122 -59.2444 -49.8317 0.24237 +VERTEX2 1123 -58.3256 -49.6583 0.246544 +VERTEX2 1124 -57.3425 -49.3613 0.239502 +VERTEX2 1125 -56.4132 -49.1585 0.243942 +VERTEX2 1126 -56.6601 -48.1326 1.7982 +VERTEX2 1127 -56.7755 -47.143 1.8235 +VERTEX2 1128 -57.0455 -46.2765 1.83011 +VERTEX2 1129 -57.3665 -45.2678 1.833 +VERTEX2 1130 -57.5953 -44.1994 1.8086 +VERTEX2 1131 -58.6126 -44.3212 -2.88066 +VERTEX2 1132 -59.5319 -44.5578 -2.86868 +VERTEX2 1133 -60.4052 -44.7799 -2.85541 +VERTEX2 1134 -61.3604 -45.0873 -2.83751 +VERTEX2 1135 -62.3461 -45.4606 -2.86256 +VERTEX2 1136 -62.019 -46.4159 -1.25003 +VERTEX2 1137 -61.766 -47.3667 -1.25545 +VERTEX2 1138 -61.4145 -48.3352 -1.24698 +VERTEX2 1139 -61.1085 -49.3066 -1.22113 +VERTEX2 1140 -60.7862 -50.1874 -1.20595 +VERTEX2 1141 -59.857 -49.7839 0.382092 +VERTEX2 1142 -58.9417 -49.3804 0.367539 +VERTEX2 1143 -57.9582 -49.0592 0.346868 +VERTEX2 1144 -57.0103 -48.8788 0.330614 +VERTEX2 1145 -56.1076 -48.57 0.340901 +VERTEX2 1146 -56.4065 -47.6269 1.91681 +VERTEX2 1147 -56.7297 -46.7269 1.92 +VERTEX2 1148 -57.0014 -45.8217 1.93393 +VERTEX2 1149 -57.4211 -44.8632 1.93289 +VERTEX2 1150 -57.7777 -43.9303 1.93536 +VERTEX2 1151 -56.8074 -43.4954 0.364824 +VERTEX2 1152 -55.9307 -43.1175 0.368146 +VERTEX2 1153 -54.9686 -42.7324 0.356064 +VERTEX2 1154 -54.0238 -42.4132 0.343608 +VERTEX2 1155 -53.1421 -42.1283 0.332853 +VERTEX2 1156 -53.4284 -41.2094 1.91395 +VERTEX2 1157 -53.7371 -40.2601 1.93637 +VERTEX2 1158 -54.154 -39.346 1.8987 +VERTEX2 1159 -54.4407 -38.3675 1.85868 +VERTEX2 1160 -54.7634 -37.4898 1.86876 +VERTEX2 1161 -55.7444 -37.787 -2.79808 +VERTEX2 1162 -56.7058 -38.1263 -2.81976 +VERTEX2 1163 -57.6173 -38.4497 -2.8369 +VERTEX2 1164 -58.6303 -38.7217 -2.80633 +VERTEX2 1165 -59.6086 -39.0791 -2.7948 +VERTEX2 1166 -59.2318 -40.0782 -1.22388 +VERTEX2 1167 -58.9647 -41.0762 -1.21337 +VERTEX2 1168 -58.6317 -42.0238 -1.2026 +VERTEX2 1169 -58.2993 -43.0172 -1.19114 +VERTEX2 1170 -57.9237 -44.0533 -1.16662 +VERTEX2 1171 -57.0472 -43.7138 0.432378 +VERTEX2 1172 -56.124 -43.3698 0.447107 +VERTEX2 1173 -55.2617 -42.9281 0.497175 +VERTEX2 1174 -54.4076 -42.4757 0.480033 +VERTEX2 1175 -53.5351 -41.9402 0.472773 +VERTEX2 1176 -54.0432 -41.0466 2.05881 +VERTEX2 1177 -54.566 -40.2215 2.07713 +VERTEX2 1178 -54.9695 -39.3495 2.05942 +VERTEX2 1179 -55.358 -38.4757 2.08006 +VERTEX2 1180 -55.9008 -37.6467 2.12208 +VERTEX2 1181 -56.826 -38.0866 -2.56997 +VERTEX2 1182 -57.5772 -38.6267 -2.55339 +VERTEX2 1183 -58.4107 -39.2228 -2.52783 +VERTEX2 1184 -59.1656 -39.7765 -2.51529 +VERTEX2 1185 -59.9415 -40.3791 -2.48129 +VERTEX2 1186 -59.3077 -41.1339 -0.9239 +VERTEX2 1187 -58.6858 -41.8659 -0.933771 +VERTEX2 1188 -58.0483 -42.6595 -0.944587 +VERTEX2 1189 -57.503 -43.5579 -0.932869 +VERTEX2 1190 -56.8702 -44.3506 -0.898817 +VERTEX2 1191 -56.1364 -43.6662 0.641224 +VERTEX2 1192 -55.3373 -43.0694 0.661821 +VERTEX2 1193 -54.4995 -42.4876 0.610478 +VERTEX2 1194 -53.6291 -41.8977 0.599757 +VERTEX2 1195 -52.7505 -41.3168 0.611304 +VERTEX2 1196 -53.3787 -40.4967 2.17768 +VERTEX2 1197 -53.9724 -39.701 2.15122 +VERTEX2 1198 -54.5223 -38.8679 2.14446 +VERTEX2 1199 -55.0996 -37.96 2.12693 +VERTEX2 1200 -55.6093 -37.1192 2.13177 +VERTEX2 1201 -54.892 -36.5794 0.592166 +VERTEX2 1202 -54.0735 -35.9631 0.592285 +VERTEX2 1203 -53.265 -35.4193 0.609963 +VERTEX2 1204 -52.5183 -34.8898 0.63631 +VERTEX2 1205 -51.7407 -34.3325 0.660933 +VERTEX2 1206 -51.0577 -35.0484 -0.945359 +VERTEX2 1207 -50.6093 -35.9368 -0.942812 +VERTEX2 1208 -50.1348 -36.7192 -0.924604 +VERTEX2 1209 -49.54 -37.5664 -0.91972 +VERTEX2 1210 -49.0741 -38.302 -0.925063 +VERTEX2 1211 -48.2928 -37.6549 0.637767 +VERTEX2 1212 -47.4862 -36.9983 0.615316 +VERTEX2 1213 -46.5801 -36.4337 0.608442 +VERTEX2 1214 -45.7682 -35.8818 0.60027 +VERTEX2 1215 -44.8918 -35.3659 0.597418 +VERTEX2 1216 -44.3404 -36.2041 -0.971341 +VERTEX2 1217 -43.7334 -37.0834 -0.981005 +VERTEX2 1218 -43.1335 -37.8841 -0.988384 +VERTEX2 1219 -42.5621 -38.7319 -0.98408 +VERTEX2 1220 -41.9695 -39.5394 -0.98083 +VERTEX2 1221 -41.1116 -38.9091 0.606953 +VERTEX2 1222 -40.1986 -38.3506 0.609054 +VERTEX2 1223 -39.4024 -37.7754 0.632375 +VERTEX2 1224 -38.5662 -37.1576 0.62243 +VERTEX2 1225 -37.7982 -36.5172 0.59237 +VERTEX2 1226 -38.3231 -35.6653 2.16972 +VERTEX2 1227 -38.8669 -34.8359 2.16156 +VERTEX2 1228 -39.3228 -34.0637 2.19683 +VERTEX2 1229 -39.9213 -33.2469 2.20187 +VERTEX2 1230 -40.5481 -32.4161 2.17292 +VERTEX2 1231 -39.7331 -31.8105 0.622303 +VERTEX2 1232 -38.8702 -31.1918 0.623522 +VERTEX2 1233 -37.953 -30.6286 0.627637 +VERTEX2 1234 -37.1664 -30.0267 0.612099 +VERTEX2 1235 -36.2841 -29.4417 0.623933 +VERTEX2 1236 -36.8233 -28.6947 2.22018 +VERTEX2 1237 -37.4652 -27.872 2.23635 +VERTEX2 1238 -38.0906 -27.1259 2.2715 +VERTEX2 1239 -38.6968 -26.3537 2.2873 +VERTEX2 1240 -39.375 -25.6316 2.27491 +VERTEX2 1241 -40.1946 -26.2037 -2.47202 +VERTEX2 1242 -40.9571 -26.8904 -2.46032 +VERTEX2 1243 -41.7078 -27.5478 -2.49322 +VERTEX2 1244 -42.4937 -28.1335 -2.48242 +VERTEX2 1245 -43.3623 -28.7023 -2.4647 +VERTEX2 1246 -42.7619 -29.4712 -0.86189 +VERTEX2 1247 -42.1385 -30.2059 -0.861816 +VERTEX2 1248 -41.4565 -31.0072 -0.867068 +VERTEX2 1249 -40.9099 -31.777 -0.862701 +VERTEX2 1250 -40.2722 -32.5266 -0.88709 +VERTEX2 1251 -39.4372 -31.9076 0.681901 +VERTEX2 1252 -38.7291 -31.1889 0.674571 +VERTEX2 1253 -37.9686 -30.5851 0.683954 +VERTEX2 1254 -37.2005 -29.9652 0.680384 +VERTEX2 1255 -36.4156 -29.4314 0.693144 +VERTEX2 1256 -35.8501 -30.1535 -0.863649 +VERTEX2 1257 -35.15 -30.9415 -0.864044 +VERTEX2 1258 -34.5728 -31.6936 -0.830776 +VERTEX2 1259 -33.8489 -32.4044 -0.82408 +VERTEX2 1260 -33.1563 -33.0753 -0.828641 +VERTEX2 1261 -32.434 -32.4337 0.729054 +VERTEX2 1262 -31.6934 -31.7995 0.752871 +VERTEX2 1263 -30.9765 -31.0971 0.792926 +VERTEX2 1264 -30.2322 -30.3589 0.779345 +VERTEX2 1265 -29.6492 -29.6053 0.736366 +VERTEX2 1266 -28.9223 -30.3174 -0.828678 +VERTEX2 1267 -28.172 -30.9983 -0.826349 +VERTEX2 1268 -27.4772 -31.6027 -0.820236 +VERTEX2 1269 -26.7291 -32.3766 -0.804396 +VERTEX2 1270 -26.0122 -33.0445 -0.779936 +VERTEX2 1271 -26.7546 -33.6706 -2.34071 +VERTEX2 1272 -27.3487 -34.4327 -2.36522 +VERTEX2 1273 -28.1361 -35.257 -2.3661 +VERTEX2 1274 -28.9212 -35.9455 -2.33347 +VERTEX2 1275 -29.7219 -36.5321 -2.3363 +VERTEX2 1276 -28.932 -37.2507 -0.740404 +VERTEX2 1277 -28.1685 -37.8793 -0.745064 +VERTEX2 1278 -27.4685 -38.5322 -0.723292 +VERTEX2 1279 -26.7037 -39.1173 -0.704755 +VERTEX2 1280 -25.9075 -39.6978 -0.707003 +VERTEX2 1281 -25.2264 -38.903 0.814425 +VERTEX2 1282 -24.5525 -38.1833 0.819191 +VERTEX2 1283 -23.9043 -37.4894 0.783622 +VERTEX2 1284 -23.2961 -36.7471 0.774321 +VERTEX2 1285 -22.536 -36.049 0.803584 +VERTEX2 1286 -23.1955 -35.3076 2.34407 +VERTEX2 1287 -23.9494 -34.5375 2.33801 +VERTEX2 1288 -24.6235 -33.8367 2.31559 +VERTEX2 1289 -25.3685 -33.1634 2.34086 +VERTEX2 1290 -26.109 -32.5178 2.33233 +VERTEX2 1291 -26.8842 -33.2222 -2.38898 +VERTEX2 1292 -27.6096 -33.8825 -2.41284 +VERTEX2 1293 -28.3221 -34.6222 -2.38239 +VERTEX2 1294 -29.1132 -35.2986 -2.3552 +VERTEX2 1295 -29.8034 -35.9757 -2.35904 +VERTEX2 1296 -29.0164 -36.7433 -0.748253 +VERTEX2 1297 -28.1227 -37.4383 -0.74295 +VERTEX2 1298 -27.3874 -38.1449 -0.726088 +VERTEX2 1299 -26.5478 -38.821 -0.744004 +VERTEX2 1300 -25.8308 -39.4313 -0.764297 +VERTEX2 1301 -25.1668 -38.728 0.81196 +VERTEX2 1302 -24.3909 -38.0661 0.81174 +VERTEX2 1303 -23.5938 -37.2268 0.830066 +VERTEX2 1304 -22.9882 -36.5108 0.826044 +VERTEX2 1305 -22.2847 -35.8559 0.814159 +VERTEX2 1306 -21.6155 -36.5207 -0.754931 +VERTEX2 1307 -20.9004 -37.2402 -0.733467 +VERTEX2 1308 -20.1927 -37.9807 -0.759942 +VERTEX2 1309 -19.5461 -38.7251 -0.749418 +VERTEX2 1310 -18.7585 -39.3998 -0.757656 +VERTEX2 1311 -17.9758 -38.6106 0.826296 +VERTEX2 1312 -17.2783 -37.8995 0.845671 +VERTEX2 1313 -16.6419 -37.1701 0.824692 +VERTEX2 1314 -15.9188 -36.3583 0.839361 +VERTEX2 1315 -15.237 -35.5191 0.843957 +VERTEX2 1316 -15.9723 -34.8469 2.38902 +VERTEX2 1317 -16.6972 -34.1338 2.39541 +VERTEX2 1318 -17.3577 -33.4953 2.41536 +VERTEX2 1319 -18.0835 -32.8337 2.42393 +VERTEX2 1320 -18.812 -32.229 2.45079 +VERTEX2 1321 -18.2877 -31.503 0.888732 +VERTEX2 1322 -17.6863 -30.6689 0.905204 +VERTEX2 1323 -17.0702 -29.8927 0.925658 +VERTEX2 1324 -16.4141 -29.1341 0.964666 +VERTEX2 1325 -15.8348 -28.2892 1.02052 +VERTEX2 1326 -15.0037 -28.7927 -0.537892 +VERTEX2 1327 -14.151 -29.363 -0.534629 +VERTEX2 1328 -13.3573 -29.896 -0.523997 +VERTEX2 1329 -12.4572 -30.5087 -0.553651 +VERTEX2 1330 -11.5583 -31.049 -0.577327 +VERTEX2 1331 -11.0235 -30.2357 0.990317 +VERTEX2 1332 -10.5025 -29.4464 0.96308 +VERTEX2 1333 -9.7875 -28.5262 0.96657 +VERTEX2 1334 -9.20977 -27.7106 0.994843 +VERTEX2 1335 -8.67005 -26.7651 1.01095 +VERTEX2 1336 -9.37241 -26.3081 2.5732 +VERTEX2 1337 -10.2156 -25.82 2.55209 +VERTEX2 1338 -11.1465 -25.2981 2.57129 +VERTEX2 1339 -12.0091 -24.7591 2.55987 +VERTEX2 1340 -12.9083 -24.1966 2.57185 +VERTEX2 1341 -13.4303 -25.0633 -2.11957 +VERTEX2 1342 -13.9598 -25.8772 -2.13438 +VERTEX2 1343 -14.529 -26.7806 -2.16371 +VERTEX2 1344 -15.1269 -27.5758 -2.13985 +VERTEX2 1345 -15.7284 -28.4206 -2.15257 +VERTEX2 1346 -14.8849 -28.833 -0.580397 +VERTEX2 1347 -14.0964 -29.354 -0.605642 +VERTEX2 1348 -13.211 -29.8712 -0.605463 +VERTEX2 1349 -12.3011 -30.4378 -0.632246 +VERTEX2 1350 -11.4894 -30.9982 -0.633634 +VERTEX2 1351 -11.024 -30.2265 0.931627 +VERTEX2 1352 -10.4232 -29.4145 0.949176 +VERTEX2 1353 -9.75056 -28.6363 0.953141 +VERTEX2 1354 -9.18295 -27.8027 0.965247 +VERTEX2 1355 -8.62333 -26.9226 0.944851 +VERTEX2 1356 -9.43601 -26.2733 2.53837 +VERTEX2 1357 -10.2913 -25.6777 2.53915 +VERTEX2 1358 -11.1106 -25.0105 2.55001 +VERTEX2 1359 -12.0151 -24.4696 2.53658 +VERTEX2 1360 -12.8363 -23.9444 2.54198 +VERTEX2 1361 -13.3029 -24.7032 -2.14954 +VERTEX2 1362 -13.8095 -25.5446 -2.171 +VERTEX2 1363 -14.3771 -26.3955 -2.15573 +VERTEX2 1364 -14.9217 -27.2505 -2.1466 +VERTEX2 1365 -15.4032 -28.0788 -2.14292 +VERTEX2 1366 -16.1653 -27.5388 2.59905 +VERTEX2 1367 -17.0073 -26.992 2.63818 +VERTEX2 1368 -17.7674 -26.4618 2.62429 +VERTEX2 1369 -18.538 -25.8999 2.65135 +VERTEX2 1370 -19.3942 -25.4277 2.63125 +VERTEX2 1371 -19.8509 -26.3032 -2.10198 +VERTEX2 1372 -20.3968 -27.1963 -2.10269 +VERTEX2 1373 -20.9059 -28.0671 -2.08996 +VERTEX2 1374 -21.3735 -28.9683 -2.07067 +VERTEX2 1375 -21.7892 -29.8257 -2.0608 +VERTEX2 1376 -22.7527 -29.3094 2.62433 +VERTEX2 1377 -23.618 -28.7428 2.64989 +VERTEX2 1378 -24.4839 -28.2311 2.65901 +VERTEX2 1379 -25.3343 -27.7454 2.68627 +VERTEX2 1380 -26.192 -27.2692 2.72015 +VERTEX2 1381 -25.821 -26.353 1.19113 +VERTEX2 1382 -25.4373 -25.3019 1.18287 +VERTEX2 1383 -24.9894 -24.2444 1.1578 +VERTEX2 1384 -24.5872 -23.3185 1.16071 +VERTEX2 1385 -24.1332 -22.3832 1.16049 +VERTEX2 1386 -25.0835 -22.0569 2.70611 +VERTEX2 1387 -26.0278 -21.5248 2.70727 +VERTEX2 1388 -26.9867 -21.1336 2.71529 +VERTEX2 1389 -27.9696 -20.7066 2.7281 +VERTEX2 1390 -28.8983 -20.3487 2.71083 +VERTEX2 1391 -28.588 -19.358 1.12194 +VERTEX2 1392 -28.0955 -18.4906 1.14292 +VERTEX2 1393 -27.6195 -17.6717 1.10852 +VERTEX2 1394 -27.1987 -16.8437 1.10376 +VERTEX2 1395 -26.8096 -15.8871 1.08926 +VERTEX2 1396 -27.7014 -15.4428 2.65165 +VERTEX2 1397 -28.5598 -15.0463 2.64906 +VERTEX2 1398 -29.4118 -14.538 2.6681 +VERTEX2 1399 -30.2706 -14.0662 2.6693 +VERTEX2 1400 -31.1648 -13.7289 2.69181 +VERTEX2 1401 -31.619 -14.6582 -2.0054 +VERTEX2 1402 -32.0672 -15.6671 -2.01124 +VERTEX2 1403 -32.5065 -16.5122 -2.0126 +VERTEX2 1404 -32.9218 -17.4637 -2.00979 +VERTEX2 1405 -33.3278 -18.4566 -1.98085 +VERTEX2 1406 -32.4294 -18.8553 -0.412657 +VERTEX2 1407 -31.5116 -19.3188 -0.434308 +VERTEX2 1408 -30.5465 -19.6907 -0.437888 +VERTEX2 1409 -29.6331 -20.1218 -0.435707 +VERTEX2 1410 -28.6691 -20.5494 -0.427158 +VERTEX2 1411 -28.2253 -19.5724 1.17926 +VERTEX2 1412 -27.8805 -18.7407 1.16518 +VERTEX2 1413 -27.4324 -17.8128 1.14956 +VERTEX2 1414 -27.0687 -16.8788 1.19523 +VERTEX2 1415 -26.6894 -15.9821 1.20943 +VERTEX2 1416 -27.5496 -15.5895 2.79866 +VERTEX2 1417 -28.5376 -15.269 2.78191 +VERTEX2 1418 -29.4676 -14.8618 2.77575 +VERTEX2 1419 -30.2972 -14.585 2.758 +VERTEX2 1420 -31.1746 -14.148 2.73954 +VERTEX2 1421 -31.6523 -15.0643 -1.98461 +VERTEX2 1422 -32.0506 -16.0156 -1.99676 +VERTEX2 1423 -32.473 -16.9615 -2.00008 +VERTEX2 1424 -32.9505 -17.8955 -2.00641 +VERTEX2 1425 -33.4189 -18.8644 -2.00977 +VERTEX2 1426 -32.5414 -19.2472 -0.427204 +VERTEX2 1427 -31.6705 -19.6343 -0.427739 +VERTEX2 1428 -30.7804 -20.0138 -0.411771 +VERTEX2 1429 -29.8665 -20.391 -0.434422 +VERTEX2 1430 -28.9607 -20.8062 -0.472329 +VERTEX2 1431 -28.5585 -19.805 1.12298 +VERTEX2 1432 -28.1447 -18.9166 1.11982 +VERTEX2 1433 -27.7469 -18.0178 1.09218 +VERTEX2 1434 -27.2992 -17.0809 1.09351 +VERTEX2 1435 -26.8943 -16.2782 1.07703 +VERTEX2 1436 -27.7376 -15.7739 2.65756 +VERTEX2 1437 -28.5974 -15.3145 2.67854 +VERTEX2 1438 -29.5194 -14.8761 2.68898 +VERTEX2 1439 -30.4729 -14.5562 2.70533 +VERTEX2 1440 -31.4306 -14.0929 2.69588 +VERTEX2 1441 -31.8591 -14.9723 -2.05323 +VERTEX2 1442 -32.2743 -15.9043 -2.03621 +VERTEX2 1443 -32.7225 -16.7076 -2.03623 +VERTEX2 1444 -33.1741 -17.693 -2.02667 +VERTEX2 1445 -33.6231 -18.6939 -2.03657 +VERTEX2 1446 -32.6366 -19.1418 -0.464116 +VERTEX2 1447 -31.7346 -19.584 -0.476614 +VERTEX2 1448 -30.8717 -19.9828 -0.486075 +VERTEX2 1449 -30.0348 -20.4463 -0.477968 +VERTEX2 1450 -29.0873 -20.8745 -0.47028 +VERTEX2 1451 -28.7265 -19.9237 1.10079 +VERTEX2 1452 -28.3065 -18.9389 1.1315 +VERTEX2 1453 -27.8637 -17.9892 1.06736 +VERTEX2 1454 -27.4021 -17.1211 1.05133 +VERTEX2 1455 -26.8952 -16.2503 1.05889 +VERTEX2 1456 -26.0142 -16.772 -0.504983 +VERTEX2 1457 -25.1147 -17.3263 -0.507164 +VERTEX2 1458 -24.203 -17.8031 -0.486641 +VERTEX2 1459 -23.2919 -18.2742 -0.451697 +VERTEX2 1460 -22.3281 -18.7046 -0.451939 +VERTEX2 1461 -22.7848 -19.5627 -2.06949 +VERTEX2 1462 -23.2416 -20.4426 -2.06815 +VERTEX2 1463 -23.7188 -21.3262 -2.08126 +VERTEX2 1464 -24.2817 -22.1778 -2.10129 +VERTEX2 1465 -24.8738 -23.0527 -2.08691 +VERTEX2 1466 -24.0955 -23.539 -0.509802 +VERTEX2 1467 -23.2256 -24.0124 -0.532877 +VERTEX2 1468 -22.4608 -24.5677 -0.535807 +VERTEX2 1469 -21.6211 -25.0792 -0.54113 +VERTEX2 1470 -20.7916 -25.5454 -0.53395 +VERTEX2 1471 -20.2522 -24.6911 1.03089 +VERTEX2 1472 -19.817 -23.9484 1.02622 +VERTEX2 1473 -19.3017 -23.1178 1.02424 +VERTEX2 1474 -18.7989 -22.2513 1.03233 +VERTEX2 1475 -18.2406 -21.3755 1.02766 +VERTEX2 1476 -17.3927 -21.8696 -0.529257 +VERTEX2 1477 -16.5787 -22.2972 -0.541957 +VERTEX2 1478 -15.6465 -22.8236 -0.55104 +VERTEX2 1479 -14.823 -23.3218 -0.565452 +VERTEX2 1480 -14.0524 -23.7876 -0.570463 +VERTEX2 1481 -14.6225 -24.6611 -2.18055 +VERTEX2 1482 -15.1677 -25.4643 -2.18225 +VERTEX2 1483 -15.7529 -26.2527 -2.14476 +VERTEX2 1484 -16.2721 -27.0061 -2.11664 +VERTEX2 1485 -16.782 -27.8592 -2.14319 +VERTEX2 1486 -15.9724 -28.5073 -0.556809 +VERTEX2 1487 -15.0895 -28.96 -0.532002 +VERTEX2 1488 -14.209 -29.4872 -0.548555 +VERTEX2 1489 -13.3993 -30.0493 -0.557544 +VERTEX2 1490 -12.4753 -30.4972 -0.544532 +VERTEX2 1491 -12.0788 -29.6562 1.03367 +VERTEX2 1492 -11.55 -28.8163 1.04732 +VERTEX2 1493 -11.081 -28.0152 1.04203 +VERTEX2 1494 -10.6549 -27.1705 1.04417 +VERTEX2 1495 -10.1942 -26.3062 1.06779 +VERTEX2 1496 -11.1017 -25.7899 2.65957 +VERTEX2 1497 -11.978 -25.3415 2.65721 +VERTEX2 1498 -12.9553 -24.9239 2.67568 +VERTEX2 1499 -13.8519 -24.3618 2.64413 +VERTEX2 1500 -14.6693 -23.7757 2.63745 +VERTEX2 1501 -15.1184 -24.6764 -2.06485 +VERTEX2 1502 -15.523 -25.5761 -2.05649 +VERTEX2 1503 -16.0528 -26.356 -2.05085 +VERTEX2 1504 -16.6034 -27.2082 -2.06186 +VERTEX2 1505 -17.1074 -27.9787 -2.06486 +VERTEX2 1506 -17.9041 -27.5209 2.59848 +VERTEX2 1507 -18.7439 -26.9691 2.62276 +VERTEX2 1508 -19.642 -26.4653 2.62205 +VERTEX2 1509 -20.4807 -25.9286 2.61678 +VERTEX2 1510 -21.3586 -25.4227 2.60363 +VERTEX2 1511 -21.9256 -26.2698 -2.09532 +VERTEX2 1512 -22.3674 -27.0911 -2.13303 +VERTEX2 1513 -22.8914 -27.8329 -2.09564 +VERTEX2 1514 -23.3769 -28.6652 -2.1101 +VERTEX2 1515 -23.973 -29.5743 -2.10863 +VERTEX2 1516 -23.1615 -30.1472 -0.511021 +VERTEX2 1517 -22.221 -30.704 -0.541271 +VERTEX2 1518 -21.3686 -31.1661 -0.583211 +VERTEX2 1519 -20.6011 -31.7876 -0.591002 +VERTEX2 1520 -19.8147 -32.3844 -0.601869 +VERTEX2 1521 -19.2706 -31.4836 0.962637 +VERTEX2 1522 -18.7391 -30.6027 0.964911 +VERTEX2 1523 -18.1879 -29.7703 0.941715 +VERTEX2 1524 -17.473 -29.0403 0.962902 +VERTEX2 1525 -16.9047 -28.279 0.940806 +VERTEX2 1526 -17.8072 -27.721 2.52642 +VERTEX2 1527 -18.6255 -27.1699 2.53147 +VERTEX2 1528 -19.4711 -26.6193 2.50533 +VERTEX2 1529 -20.2129 -26.0197 2.50606 +VERTEX2 1530 -21.0224 -25.3489 2.48555 +VERTEX2 1531 -21.6874 -26.2331 -2.20528 +VERTEX2 1532 -22.3565 -27.0208 -2.22694 +VERTEX2 1533 -22.8486 -27.8008 -2.25106 +VERTEX2 1534 -23.5657 -28.6336 -2.23293 +VERTEX2 1535 -24.1249 -29.4019 -2.2369 +VERTEX2 1536 -24.9519 -28.7039 2.4519 +VERTEX2 1537 -25.6431 -28.0743 2.44882 +VERTEX2 1538 -26.4027 -27.476 2.46036 +VERTEX2 1539 -27.2089 -26.8451 2.46499 +VERTEX2 1540 -27.9719 -26.1833 2.47508 +VERTEX2 1541 -28.6051 -26.9181 -2.23498 +VERTEX2 1542 -29.2086 -27.7013 -2.24166 +VERTEX2 1543 -29.8204 -28.4475 -2.2869 +VERTEX2 1544 -30.4718 -29.246 -2.28276 +VERTEX2 1545 -31.092 -29.9666 -2.29163 +VERTEX2 1546 -31.8246 -29.3071 2.37406 +VERTEX2 1547 -32.5802 -28.6611 2.36775 +VERTEX2 1548 -33.2751 -28.0311 2.37066 +VERTEX2 1549 -33.8784 -27.3433 2.36581 +VERTEX2 1550 -34.5422 -26.6034 2.39958 +VERTEX2 1551 -33.894 -25.8878 0.833562 +VERTEX2 1552 -33.3004 -25.1196 0.865997 +VERTEX2 1553 -32.7287 -24.3043 0.881112 +VERTEX2 1554 -32.0421 -23.5629 0.88629 +VERTEX2 1555 -31.4305 -22.803 0.874433 +VERTEX2 1556 -30.6938 -23.4495 -0.66741 +VERTEX2 1557 -29.9013 -24.0216 -0.669915 +VERTEX2 1558 -29.1628 -24.6761 -0.655215 +VERTEX2 1559 -28.3325 -25.2747 -0.639965 +VERTEX2 1560 -27.4924 -25.8257 -0.648412 +VERTEX2 1561 -28.0777 -26.5402 -2.22116 +VERTEX2 1562 -28.7324 -27.3009 -2.20002 +VERTEX2 1563 -29.3926 -28.0456 -2.18446 +VERTEX2 1564 -29.9602 -28.9167 -2.21832 +VERTEX2 1565 -30.6 -29.7495 -2.24973 +VERTEX2 1566 -29.7964 -30.3691 -0.642141 +VERTEX2 1567 -29.041 -30.9663 -0.662329 +VERTEX2 1568 -28.231 -31.5846 -0.663769 +VERTEX2 1569 -27.5072 -32.1604 -0.651372 +VERTEX2 1570 -26.6541 -32.8057 -0.649388 +VERTEX2 1571 -26.0358 -31.9783 0.872722 +VERTEX2 1572 -25.3413 -31.2457 0.850443 +VERTEX2 1573 -24.7405 -30.4628 0.839486 +VERTEX2 1574 -24.0705 -29.6772 0.867456 +VERTEX2 1575 -23.3994 -28.8044 0.878039 +VERTEX2 1576 -24.1733 -28.1536 2.48073 +VERTEX2 1577 -24.9085 -27.5253 2.45149 +VERTEX2 1578 -25.6758 -26.8572 2.46051 +VERTEX2 1579 -26.5238 -26.2078 2.49038 +VERTEX2 1580 -27.4003 -25.5086 2.47998 +VERTEX2 1581 -28.0538 -26.3761 -2.22448 +VERTEX2 1582 -28.6128 -27.1797 -2.22119 +VERTEX2 1583 -29.1845 -27.9312 -2.20076 +VERTEX2 1584 -29.8164 -28.8066 -2.20599 +VERTEX2 1585 -30.4106 -29.5732 -2.21362 +VERTEX2 1586 -29.6088 -30.1042 -0.62272 +VERTEX2 1587 -28.7953 -30.6401 -0.606951 +VERTEX2 1588 -27.9789 -31.1556 -0.611924 +VERTEX2 1589 -27.2266 -31.7636 -0.630514 +VERTEX2 1590 -26.504 -32.3464 -0.658434 +VERTEX2 1591 -25.899 -31.5176 0.922411 +VERTEX2 1592 -25.3131 -30.7407 0.910111 +VERTEX2 1593 -24.6743 -30.0012 0.861931 +VERTEX2 1594 -23.9599 -29.2452 0.836514 +VERTEX2 1595 -23.2705 -28.5065 0.877315 +VERTEX2 1596 -22.5079 -29.0998 -0.657393 +VERTEX2 1597 -21.7194 -29.7079 -0.670279 +VERTEX2 1598 -20.9233 -30.3259 -0.665283 +VERTEX2 1599 -20.0859 -30.9211 -0.674022 +VERTEX2 1600 -19.3147 -31.5289 -0.676165 +VERTEX2 1601 -19.9258 -32.2753 -2.2916 +VERTEX2 1602 -20.4978 -32.9897 -2.26716 +VERTEX2 1603 -21.1577 -33.7299 -2.25482 +VERTEX2 1604 -21.8865 -34.5245 -2.26037 +VERTEX2 1605 -22.5042 -35.2723 -2.24992 +VERTEX2 1606 -21.7507 -35.9088 -0.715588 +VERTEX2 1607 -20.983 -36.5533 -0.742358 +VERTEX2 1608 -20.2872 -37.2357 -0.768375 +VERTEX2 1609 -19.5997 -37.9168 -0.760076 +VERTEX2 1610 -18.8594 -38.6566 -0.767909 +VERTEX2 1611 -18.1667 -38.0338 0.778842 +VERTEX2 1612 -17.4583 -37.2752 0.769236 +VERTEX2 1613 -16.7499 -36.5717 0.766831 +VERTEX2 1614 -15.996 -35.8935 0.748963 +VERTEX2 1615 -15.2298 -35.2739 0.774015 +VERTEX2 1616 -15.9032 -34.5294 2.3414 +VERTEX2 1617 -16.6679 -33.8179 2.36259 +VERTEX2 1618 -17.3281 -33.0576 2.34754 +VERTEX2 1619 -17.9786 -32.2486 2.30063 +VERTEX2 1620 -18.623 -31.5399 2.27667 +VERTEX2 1621 -19.3851 -32.1397 -2.46207 +VERTEX2 1622 -20.2324 -32.7057 -2.47638 +VERTEX2 1623 -20.9672 -33.3009 -2.44523 +VERTEX2 1624 -21.7515 -33.9535 -2.45193 +VERTEX2 1625 -22.5509 -34.5662 -2.45261 +VERTEX2 1626 -21.8989 -35.3378 -0.914747 +VERTEX2 1627 -21.3078 -36.055 -0.905745 +VERTEX2 1628 -20.8115 -36.8798 -0.860012 +VERTEX2 1629 -20.2198 -37.5732 -0.816855 +VERTEX2 1630 -19.5974 -38.2789 -0.824681 +VERTEX2 1631 -18.8249 -37.596 0.733355 +VERTEX2 1632 -18.1394 -36.9731 0.710239 +VERTEX2 1633 -17.4197 -36.2853 0.71942 +VERTEX2 1634 -16.6919 -35.6207 0.697404 +VERTEX2 1635 -15.9001 -34.9385 0.672703 +VERTEX2 1636 -16.4624 -34.1698 2.21386 +VERTEX2 1637 -17.0241 -33.3844 2.20507 +VERTEX2 1638 -17.6646 -32.57 2.20861 +VERTEX2 1639 -18.2182 -31.7753 2.26398 +VERTEX2 1640 -18.8405 -31.0022 2.25059 +VERTEX2 1641 -18.0732 -30.3744 0.663339 +VERTEX2 1642 -17.2762 -29.7538 0.675169 +VERTEX2 1643 -16.5969 -29.1681 0.660773 +VERTEX2 1644 -15.7763 -28.5318 0.636745 +VERTEX2 1645 -14.9898 -27.9624 0.633073 +VERTEX2 1646 -15.5958 -27.1882 2.21031 +VERTEX2 1647 -16.0918 -26.3883 2.1963 +VERTEX2 1648 -16.7133 -25.5154 2.17641 +VERTEX2 1649 -17.2368 -24.6799 2.17854 +VERTEX2 1650 -17.8103 -23.8701 2.1535 +VERTEX2 1651 -18.5527 -24.4763 -2.5608 +VERTEX2 1652 -19.4678 -25.0361 -2.56476 +VERTEX2 1653 -20.2199 -25.5949 -2.59009 +VERTEX2 1654 -21.0612 -26.0641 -2.59479 +VERTEX2 1655 -21.9585 -26.5584 -2.58492 +VERTEX2 1656 -22.4384 -25.7511 2.14912 +VERTEX2 1657 -23.0565 -24.9519 2.13862 +VERTEX2 1658 -23.5791 -24.0198 2.14819 +VERTEX2 1659 -24.2171 -23.1173 2.153 +VERTEX2 1660 -24.8058 -22.3054 2.16006 +VERTEX2 1661 -23.9864 -21.7604 0.602754 +VERTEX2 1662 -23.1527 -21.2465 0.593894 +VERTEX2 1663 -22.3229 -20.6835 0.619583 +VERTEX2 1664 -21.5463 -20.058 0.61978 +VERTEX2 1665 -20.6553 -19.4997 0.598611 +VERTEX2 1666 -20.178 -20.2885 -0.942069 +VERTEX2 1667 -19.5612 -21.1269 -0.930847 +VERTEX2 1668 -18.9527 -21.8871 -0.961611 +VERTEX2 1669 -18.2864 -22.6249 -0.972137 +VERTEX2 1670 -17.7399 -23.4531 -0.96491 +VERTEX2 1671 -16.844 -22.8458 0.610148 +VERTEX2 1672 -16.0647 -22.3337 0.59458 +VERTEX2 1673 -15.2241 -21.7987 0.577687 +VERTEX2 1674 -14.3603 -21.2426 0.563901 +VERTEX2 1675 -13.5391 -20.805 0.543428 +VERTEX2 1676 -13.0162 -21.594 -1.01687 +VERTEX2 1677 -12.4792 -22.3764 -0.992476 +VERTEX2 1678 -11.9576 -23.2345 -0.97087 +VERTEX2 1679 -11.4475 -24.0722 -1.00076 +VERTEX2 1680 -10.8703 -24.8126 -0.985758 +VERTEX2 1681 -10.0485 -24.3565 0.586257 +VERTEX2 1682 -9.25135 -23.8477 0.562049 +VERTEX2 1683 -8.35518 -23.2866 0.559723 +VERTEX2 1684 -7.49595 -22.7646 0.552896 +VERTEX2 1685 -6.58338 -22.2384 0.580383 +VERTEX2 1686 -7.23252 -21.3922 2.16862 +VERTEX2 1687 -7.8635 -20.4812 2.18594 +VERTEX2 1688 -8.46835 -19.6784 2.19382 +VERTEX2 1689 -8.98709 -18.9027 2.2202 +VERTEX2 1690 -9.63098 -18.0651 2.20316 +VERTEX2 1691 -10.3788 -18.6556 -2.52477 +VERTEX2 1692 -11.2275 -19.2346 -2.50655 +VERTEX2 1693 -12.0857 -19.8503 -2.53474 +VERTEX2 1694 -13.0506 -20.3156 -2.57509 +VERTEX2 1695 -13.8355 -20.9631 -2.5797 +VERTEX2 1696 -14.4878 -20.0436 2.14141 +VERTEX2 1697 -15.0257 -19.2155 2.13764 +VERTEX2 1698 -15.6003 -18.377 2.16083 +VERTEX2 1699 -16.1804 -17.5047 2.16672 +VERTEX2 1700 -16.6717 -16.7529 2.16532 +VERTEX2 1701 -17.4428 -17.3773 -2.53916 +VERTEX2 1702 -18.2266 -17.9367 -2.51755 +VERTEX2 1703 -18.9687 -18.5548 -2.50203 +VERTEX2 1704 -19.7341 -19.1513 -2.52578 +VERTEX2 1705 -20.5675 -19.7049 -2.55297 +VERTEX2 1706 -20.0082 -20.5441 -0.973669 +VERTEX2 1707 -19.4632 -21.3999 -0.976789 +VERTEX2 1708 -18.9687 -22.2588 -0.948183 +VERTEX2 1709 -18.4008 -23.1242 -0.956514 +VERTEX2 1710 -17.8453 -23.9237 -0.938451 +VERTEX2 1711 -17.0529 -23.3249 0.675645 +VERTEX2 1712 -16.2447 -22.7508 0.658153 +VERTEX2 1713 -15.505 -22.0796 0.661226 +VERTEX2 1714 -14.7396 -21.598 0.655037 +VERTEX2 1715 -13.9138 -20.883 0.650172 +VERTEX2 1716 -14.4975 -20.1127 2.23312 +VERTEX2 1717 -15.099 -19.3079 2.21558 +VERTEX2 1718 -15.7136 -18.5109 2.2319 +VERTEX2 1719 -16.3677 -17.6507 2.22509 +VERTEX2 1720 -16.9701 -16.8139 2.24219 +VERTEX2 1721 -16.1485 -16.2412 0.667641 +VERTEX2 1722 -15.3431 -15.6389 0.679137 +VERTEX2 1723 -14.4662 -14.9411 0.693538 +VERTEX2 1724 -13.6612 -14.2605 0.686488 +VERTEX2 1725 -12.9106 -13.5991 0.684916 +VERTEX2 1726 -13.5467 -12.8343 2.25902 +VERTEX2 1727 -14.0811 -12.0452 2.25049 +VERTEX2 1728 -14.8079 -11.2551 2.26568 +VERTEX2 1729 -15.3962 -10.4767 2.28856 +VERTEX2 1730 -16.0629 -9.71665 2.25339 +VERTEX2 1731 -16.8698 -10.3596 -2.47206 +VERTEX2 1732 -17.7391 -10.9637 -2.47164 +VERTEX2 1733 -18.4727 -11.5822 -2.50706 +VERTEX2 1734 -19.2867 -12.1524 -2.51149 +VERTEX2 1735 -20.0526 -12.7985 -2.52841 +VERTEX2 1736 -19.551 -13.5558 -0.930125 +VERTEX2 1737 -19.002 -14.3453 -0.915415 +VERTEX2 1738 -18.4249 -15.1608 -0.91936 +VERTEX2 1739 -17.9807 -15.9723 -0.914759 +VERTEX2 1740 -17.4091 -16.7807 -0.895096 +VERTEX2 1741 -16.6178 -16.0911 0.660765 +VERTEX2 1742 -15.8022 -15.4237 0.676256 +VERTEX2 1743 -14.9588 -14.82 0.661067 +VERTEX2 1744 -14.1886 -14.2455 0.683942 +VERTEX2 1745 -13.3996 -13.632 0.655339 +VERTEX2 1746 -14.0416 -12.8826 2.2462 +VERTEX2 1747 -14.6952 -12.1306 2.2589 +VERTEX2 1748 -15.2971 -11.3301 2.27246 +VERTEX2 1749 -15.9586 -10.5695 2.2843 +VERTEX2 1750 -16.503 -9.86706 2.29471 +VERTEX2 1751 -17.2159 -10.5495 -2.4195 +VERTEX2 1752 -17.9587 -11.1469 -2.37475 +VERTEX2 1753 -18.7394 -11.858 -2.36551 +VERTEX2 1754 -19.3946 -12.632 -2.32213 +VERTEX2 1755 -20.0682 -13.3416 -2.34833 +VERTEX2 1756 -20.7278 -12.7104 2.35263 +VERTEX2 1757 -21.4582 -12.0858 2.34171 +VERTEX2 1758 -22.0784 -11.3772 2.34851 +VERTEX2 1759 -22.8428 -10.7184 2.34153 +VERTEX2 1760 -23.5942 -10.023 2.32496 +VERTEX2 1761 -22.8634 -9.43922 0.757747 +VERTEX2 1762 -22.175 -8.7351 0.759375 +VERTEX2 1763 -21.4512 -8.04677 0.782241 +VERTEX2 1764 -20.8051 -7.38493 0.807942 +VERTEX2 1765 -20.1107 -6.60881 0.834204 +VERTEX2 1766 -20.8593 -5.93672 2.40424 +VERTEX2 1767 -21.6709 -5.16399 2.40269 +VERTEX2 1768 -22.4316 -4.45161 2.4176 +VERTEX2 1769 -23.1248 -3.7317 2.38587 +VERTEX2 1770 -23.8206 -3.05635 2.38259 +VERTEX2 1771 -24.5179 -3.74033 -2.30307 +VERTEX2 1772 -25.2316 -4.51238 -2.29041 +VERTEX2 1773 -25.8257 -5.2511 -2.28644 +VERTEX2 1774 -26.508 -6.10307 -2.28916 +VERTEX2 1775 -27.2067 -6.79967 -2.28438 +VERTEX2 1776 -27.964 -6.11537 2.44275 +VERTEX2 1777 -28.6821 -5.44792 2.45539 +VERTEX2 1778 -29.5099 -4.93471 2.47161 +VERTEX2 1779 -30.217 -4.33934 2.43731 +VERTEX2 1780 -30.9445 -3.70293 2.42717 +VERTEX2 1781 -31.6164 -4.44551 -2.29717 +VERTEX2 1782 -32.2448 -5.17655 -2.27517 +VERTEX2 1783 -32.9011 -6.02045 -2.29664 +VERTEX2 1784 -33.4878 -6.66286 -2.2831 +VERTEX2 1785 -34.1656 -7.33022 -2.28505 +VERTEX2 1786 -33.3625 -7.91847 -0.705387 +VERTEX2 1787 -32.4999 -8.66044 -0.72003 +VERTEX2 1788 -31.7289 -9.3466 -0.723926 +VERTEX2 1789 -31.0124 -10.0163 -0.704773 +VERTEX2 1790 -30.2731 -10.7243 -0.719416 +VERTEX2 1791 -30.9196 -11.4516 -2.2598 +VERTEX2 1792 -31.558 -12.1126 -2.29062 +VERTEX2 1793 -32.2043 -12.8838 -2.23317 +VERTEX2 1794 -32.8319 -13.6726 -2.22285 +VERTEX2 1795 -33.4642 -14.5132 -2.24698 +VERTEX2 1796 -32.8405 -15.1128 -0.663123 +VERTEX2 1797 -32.1401 -15.6907 -0.644203 +VERTEX2 1798 -31.3014 -16.3307 -0.626446 +VERTEX2 1799 -30.4211 -16.9382 -0.643502 +VERTEX2 1800 -29.5906 -17.5858 -0.63234 +VERTEX2 1801 -30.169 -18.4499 -2.16765 +VERTEX2 1802 -30.7202 -19.2605 -2.17873 +VERTEX2 1803 -31.3494 -20.0929 -2.18441 +VERTEX2 1804 -31.9708 -20.9043 -2.17644 +VERTEX2 1805 -32.5991 -21.7425 -2.17669 +VERTEX2 1806 -33.4744 -21.0709 2.54616 +VERTEX2 1807 -34.2706 -20.4703 2.56136 +VERTEX2 1808 -35.1602 -19.9477 2.52252 +VERTEX2 1809 -35.9995 -19.3564 2.50991 +VERTEX2 1810 -36.7421 -18.7435 2.53438 +VERTEX2 1811 -37.238 -19.6449 -2.18429 +VERTEX2 1812 -37.7459 -20.4719 -2.19798 +VERTEX2 1813 -38.3067 -21.2784 -2.19815 +VERTEX2 1814 -38.8187 -22.1487 -2.24134 +VERTEX2 1815 -39.4068 -22.9349 -2.22056 +VERTEX2 1816 -38.6124 -23.6454 -0.664463 +VERTEX2 1817 -37.8392 -24.2817 -0.658319 +VERTEX2 1818 -37.0801 -24.9533 -0.693318 +VERTEX2 1819 -36.3927 -25.597 -0.709208 +VERTEX2 1820 -35.6096 -26.3093 -0.709403 +VERTEX2 1821 -34.9287 -25.4568 0.839573 +VERTEX2 1822 -34.2897 -24.7218 0.866981 +VERTEX2 1823 -33.6319 -24.0229 0.851138 +VERTEX2 1824 -32.9353 -23.2493 0.864251 +VERTEX2 1825 -32.3401 -22.4029 0.854936 +VERTEX2 1826 -31.6269 -23.1045 -0.742174 +VERTEX2 1827 -30.9065 -23.7908 -0.703742 +VERTEX2 1828 -30.2304 -24.4652 -0.70505 +VERTEX2 1829 -29.5172 -25.0944 -0.690895 +VERTEX2 1830 -28.7202 -25.6739 -0.69509 +VERTEX2 1831 -28.0683 -24.9075 0.87385 +VERTEX2 1832 -27.3618 -24.0274 0.851411 +VERTEX2 1833 -26.7534 -23.1752 0.877753 +VERTEX2 1834 -26.1168 -22.4537 0.872158 +VERTEX2 1835 -25.4737 -21.6048 0.850915 +VERTEX2 1836 -24.7339 -22.3031 -0.746107 +VERTEX2 1837 -23.9539 -23.0222 -0.756831 +VERTEX2 1838 -23.1544 -23.5938 -0.753258 +VERTEX2 1839 -22.4785 -24.2729 -0.778708 +VERTEX2 1840 -21.7353 -25.0101 -0.794935 +VERTEX2 1841 -22.4349 -25.7353 -2.34079 +VERTEX2 1842 -23.1048 -26.4846 -2.31866 +VERTEX2 1843 -23.8108 -27.2455 -2.32043 +VERTEX2 1844 -24.4294 -27.9666 -2.33145 +VERTEX2 1845 -25.1336 -28.6697 -2.2968 +VERTEX2 1846 -24.3631 -29.2553 -0.755048 +VERTEX2 1847 -23.6716 -29.9192 -0.729415 +VERTEX2 1848 -22.9447 -30.6094 -0.764501 +VERTEX2 1849 -22.1923 -31.3508 -0.769519 +VERTEX2 1850 -21.5055 -32.0934 -0.747277 +VERTEX2 1851 -20.841 -31.4067 0.848889 +VERTEX2 1852 -20.2445 -30.6137 0.816513 +VERTEX2 1853 -19.5109 -29.923 0.844809 +VERTEX2 1854 -18.9394 -29.1714 0.834745 +VERTEX2 1855 -18.2581 -28.3943 0.834602 +VERTEX2 1856 -18.9836 -27.7939 2.42344 +VERTEX2 1857 -19.7667 -27.0741 2.41655 +VERTEX2 1858 -20.5171 -26.3608 2.43385 +VERTEX2 1859 -21.3295 -25.7395 2.45777 +VERTEX2 1860 -22.0859 -25.0961 2.45902 +VERTEX2 1861 -21.4474 -24.2468 0.92125 +VERTEX2 1862 -20.8823 -23.3626 0.920754 +VERTEX2 1863 -20.2738 -22.5851 0.916575 +VERTEX2 1864 -19.6971 -21.7952 0.922186 +VERTEX2 1865 -19.1229 -21.0017 0.88612 +VERTEX2 1866 -18.3613 -21.5821 -0.681138 +VERTEX2 1867 -17.5309 -22.2074 -0.683587 +VERTEX2 1868 -16.7544 -22.7751 -0.668663 +VERTEX2 1869 -16.0565 -23.4456 -0.664723 +VERTEX2 1870 -15.2976 -24.166 -0.644358 +VERTEX2 1871 -14.6298 -23.4312 0.894134 +VERTEX2 1872 -14.0019 -22.6454 0.903438 +VERTEX2 1873 -13.3178 -21.8346 0.872143 +VERTEX2 1874 -12.6238 -21.0724 0.891546 +VERTEX2 1875 -11.9735 -20.3243 0.922297 +VERTEX2 1876 -11.1254 -20.8839 -0.655517 +VERTEX2 1877 -10.3169 -21.4727 -0.651187 +VERTEX2 1878 -9.51188 -22.0804 -0.657657 +VERTEX2 1879 -8.84359 -22.6942 -0.665846 +VERTEX2 1880 -8.10102 -23.3644 -0.674962 +VERTEX2 1881 -7.43126 -22.5407 0.905754 +VERTEX2 1882 -6.80605 -21.6995 0.92617 +VERTEX2 1883 -6.25111 -20.8428 0.939438 +VERTEX2 1884 -5.63712 -20.0496 0.967216 +VERTEX2 1885 -5.18374 -19.1843 0.954024 +VERTEX2 1886 -5.97115 -18.5591 2.54765 +VERTEX2 1887 -6.8875 -18.0187 2.54123 +VERTEX2 1888 -7.72945 -17.5093 2.55233 +VERTEX2 1889 -8.47027 -16.9862 2.55204 +VERTEX2 1890 -9.31132 -16.4367 2.53902 +VERTEX2 1891 -9.89189 -17.2297 -2.19112 +VERTEX2 1892 -10.4662 -18.0129 -2.24815 +VERTEX2 1893 -11.0081 -18.7643 -2.24066 +VERTEX2 1894 -11.6504 -19.5551 -2.25858 +VERTEX2 1895 -12.2863 -20.2679 -2.239 +VERTEX2 1896 -11.5309 -20.9287 -0.688747 +VERTEX2 1897 -10.7389 -21.5586 -0.684495 +VERTEX2 1898 -9.82752 -22.2294 -0.699466 +VERTEX2 1899 -9.21607 -22.8117 -0.697494 +VERTEX2 1900 -8.38509 -23.4905 -0.689835 +VERTEX2 1901 -9.03764 -24.2543 -2.28702 +VERTEX2 1902 -9.56793 -25.0483 -2.26542 +VERTEX2 1903 -10.1992 -25.8617 -2.27163 +VERTEX2 1904 -10.8866 -26.5881 -2.25425 +VERTEX2 1905 -11.5429 -27.3106 -2.23615 +VERTEX2 1906 -10.8075 -27.9262 -0.673796 +VERTEX2 1907 -10.0694 -28.5589 -0.67199 +VERTEX2 1908 -9.29066 -29.204 -0.650459 +VERTEX2 1909 -8.55544 -29.9619 -0.640557 +VERTEX2 1910 -7.76286 -30.5342 -0.659004 +VERTEX2 1911 -7.20392 -29.6879 0.886798 +VERTEX2 1912 -6.57237 -28.9385 0.899406 +VERTEX2 1913 -5.94055 -28.2132 0.8792 +VERTEX2 1914 -5.23984 -27.4192 0.845003 +VERTEX2 1915 -4.5127 -26.7287 0.851558 +VERTEX2 1916 -5.25632 -26.1209 2.43231 +VERTEX2 1917 -5.95843 -25.4283 2.4516 +VERTEX2 1918 -6.75075 -24.8129 2.46554 +VERTEX2 1919 -7.56078 -24.2147 2.48491 +VERTEX2 1920 -8.33813 -23.6062 2.4721 +VERTEX2 1921 -8.97827 -24.4295 -2.22521 +VERTEX2 1922 -9.67589 -25.2943 -2.25164 +VERTEX2 1923 -10.3549 -26.1418 -2.20484 +VERTEX2 1924 -10.9758 -26.9469 -2.21266 +VERTEX2 1925 -11.5534 -27.8312 -2.20524 +VERTEX2 1926 -12.3699 -27.1988 2.50337 +VERTEX2 1927 -13.1703 -26.5279 2.52521 +VERTEX2 1928 -13.9322 -25.963 2.49802 +VERTEX2 1929 -14.7458 -25.3019 2.48766 +VERTEX2 1930 -15.5021 -24.6226 2.47359 +VERTEX2 1931 -14.8719 -23.7581 0.886118 +VERTEX2 1932 -14.1714 -23.0336 0.914319 +VERTEX2 1933 -13.5548 -22.2228 0.913861 +VERTEX2 1934 -12.8986 -21.3576 0.897881 +VERTEX2 1935 -12.2928 -20.6572 0.914581 +VERTEX2 1936 -13.1066 -20.104 2.49444 +VERTEX2 1937 -13.8839 -19.5216 2.52327 +VERTEX2 1938 -14.6985 -18.8737 2.50889 +VERTEX2 1939 -15.4575 -18.2398 2.52894 +VERTEX2 1940 -16.3181 -17.661 2.5463 +VERTEX2 1941 -15.7812 -16.8345 0.981567 +VERTEX2 1942 -15.1941 -15.9873 0.957347 +VERTEX2 1943 -14.7031 -15.1471 0.959161 +VERTEX2 1944 -14.1569 -14.3644 0.95625 +VERTEX2 1945 -13.5081 -13.5671 0.951562 +VERTEX2 1946 -14.3623 -12.9972 2.53324 +VERTEX2 1947 -15.1804 -12.4028 2.54022 +VERTEX2 1948 -16.064 -11.8726 2.54158 +VERTEX2 1949 -16.9386 -11.2522 2.55587 +VERTEX2 1950 -17.7688 -10.6514 2.53888 +VERTEX2 1951 -17.3142 -9.87535 0.970884 +VERTEX2 1952 -16.6391 -8.99717 0.994887 +VERTEX2 1953 -16.052 -8.09752 1.00324 +VERTEX2 1954 -15.499 -7.27829 0.997625 +VERTEX2 1955 -14.9966 -6.49352 1.03828 +VERTEX2 1956 -14.2189 -7.04072 -0.50216 +VERTEX2 1957 -13.3922 -7.48257 -0.520827 +VERTEX2 1958 -12.4671 -7.93988 -0.523926 +VERTEX2 1959 -11.5817 -8.50353 -0.52112 +VERTEX2 1960 -10.7845 -9.03765 -0.533408 +VERTEX2 1961 -10.3059 -8.16529 1.05085 +VERTEX2 1962 -9.81536 -7.35889 1.01406 +VERTEX2 1963 -9.23654 -6.61124 1.00625 +VERTEX2 1964 -8.67337 -5.75492 0.986425 +VERTEX2 1965 -8.10533 -4.91027 0.988049 +VERTEX2 1966 -8.92669 -4.34179 2.53427 +VERTEX2 1967 -9.73585 -3.84462 2.52935 +VERTEX2 1968 -10.4496 -3.20576 2.50325 +VERTEX2 1969 -11.2098 -2.54368 2.54105 +VERTEX2 1970 -12.0563 -1.94925 2.57745 +VERTEX2 1971 -12.6186 -2.74792 -2.12953 +VERTEX2 1972 -13.0917 -3.55547 -2.10329 +VERTEX2 1973 -13.5965 -4.43365 -2.09657 +VERTEX2 1974 -14.1772 -5.30425 -2.0769 +VERTEX2 1975 -14.6373 -6.12375 -2.10567 +VERTEX2 1976 -13.7124 -6.68705 -0.523687 +VERTEX2 1977 -12.8486 -7.21467 -0.513915 +VERTEX2 1978 -11.919 -7.78269 -0.517946 +VERTEX2 1979 -11.073 -8.25196 -0.515317 +VERTEX2 1980 -10.1634 -8.79642 -0.523002 +VERTEX2 1981 -9.67838 -7.9292 1.05418 +VERTEX2 1982 -9.16931 -7.04277 1.04088 +VERTEX2 1983 -8.64161 -6.18388 1.0101 +VERTEX2 1984 -8.1284 -5.27824 0.972486 +VERTEX2 1985 -7.60564 -4.4466 0.939375 +VERTEX2 1986 -8.37477 -3.82735 2.53172 +VERTEX2 1987 -9.24637 -3.21042 2.51859 +VERTEX2 1988 -10.1239 -2.53201 2.51686 +VERTEX2 1989 -10.9978 -1.90917 2.53711 +VERTEX2 1990 -11.7904 -1.32458 2.53019 +VERTEX2 1991 -11.2019 -0.547537 0.935565 +VERTEX2 1992 -10.6479 0.367869 0.903784 +VERTEX2 1993 -10.0651 1.2105 0.939412 +VERTEX2 1994 -9.58936 2.04685 0.940499 +VERTEX2 1995 -9.06279 2.90147 0.945863 +VERTEX2 1996 -9.89438 3.54285 2.51696 +VERTEX2 1997 -10.7308 4.25377 2.50641 +VERTEX2 1998 -11.5248 4.89639 2.5291 +VERTEX2 1999 -12.3735 5.49513 2.54814 +VERTEX2 2000 -13.1858 6.05181 2.56837 +VERTEX2 2001 -13.7254 5.20243 -2.13803 +VERTEX2 2002 -14.303 4.34929 -2.12789 +VERTEX2 2003 -14.8358 3.54221 -2.11683 +VERTEX2 2004 -15.3174 2.61479 -2.1364 +VERTEX2 2005 -15.8708 1.75571 -2.11438 +VERTEX2 2006 -16.7312 2.33768 2.64292 +VERTEX2 2007 -17.756 2.81636 2.63161 +VERTEX2 2008 -18.5427 3.38114 2.63185 +VERTEX2 2009 -19.3776 3.85182 2.64118 +VERTEX2 2010 -20.2769 4.31245 2.63063 +VERTEX2 2011 -20.8093 3.41714 -2.05642 +VERTEX2 2012 -21.2706 2.48159 -2.06253 +VERTEX2 2013 -21.785 1.61342 -2.06938 +VERTEX2 2014 -22.3067 0.708392 -2.0648 +VERTEX2 2015 -22.7477 -0.205162 -2.04491 +VERTEX2 2016 -23.6065 0.220195 2.64611 +VERTEX2 2017 -24.4118 0.646133 2.65944 +VERTEX2 2018 -25.3491 1.1358 2.63823 +VERTEX2 2019 -26.2181 1.62761 2.62657 +VERTEX2 2020 -27.1521 2.02316 2.62949 +VERTEX2 2021 -27.7253 1.15037 -2.0559 +VERTEX2 2022 -28.2086 0.227182 -2.07296 +VERTEX2 2023 -28.6903 -0.652161 -2.09523 +VERTEX2 2024 -29.0654 -1.42402 -2.16137 +VERTEX2 2025 -29.6166 -2.28225 -2.18079 +VERTEX2 2026 -28.6674 -2.86207 -0.588607 +VERTEX2 2027 -27.8149 -3.435 -0.616415 +VERTEX2 2028 -26.9482 -4.00403 -0.615424 +VERTEX2 2029 -26.036 -4.57714 -0.62106 +VERTEX2 2030 -25.2044 -5.19623 -0.607567 +VERTEX2 2031 -25.8372 -5.99281 -2.16588 +VERTEX2 2032 -26.4207 -6.86355 -2.17939 +VERTEX2 2033 -26.9598 -7.73235 -2.13798 +VERTEX2 2034 -27.502 -8.46839 -2.12125 +VERTEX2 2035 -27.971 -9.27159 -2.12391 +VERTEX2 2036 -28.7577 -8.79364 2.57767 +VERTEX2 2037 -29.6329 -8.25547 2.56932 +VERTEX2 2038 -30.5034 -7.7022 2.55739 +VERTEX2 2039 -31.3124 -7.15419 2.53878 +VERTEX2 2040 -32.1247 -6.57191 2.54189 +VERTEX2 2041 -32.6112 -7.42001 -2.13348 +VERTEX2 2042 -33.1577 -8.33656 -2.15162 +VERTEX2 2043 -33.7306 -9.21045 -2.11544 +VERTEX2 2044 -34.2267 -10.0978 -2.10724 +VERTEX2 2045 -34.7069 -11.003 -2.10261 +VERTEX2 2046 -33.7354 -11.517 -0.534625 +VERTEX2 2047 -32.7904 -11.9902 -0.556246 +VERTEX2 2048 -31.9486 -12.5884 -0.588572 +VERTEX2 2049 -31.2023 -13.1683 -0.606238 +VERTEX2 2050 -30.4003 -13.7656 -0.606872 +VERTEX2 2051 -29.8986 -12.9785 0.987095 +VERTEX2 2052 -29.355 -12.1568 1.00284 +VERTEX2 2053 -28.8506 -11.3303 1.049 +VERTEX2 2054 -28.3425 -10.4988 1.04881 +VERTEX2 2055 -27.7883 -9.58358 1.05609 +VERTEX2 2056 -26.9352 -10.1118 -0.481473 +VERTEX2 2057 -26.0783 -10.6248 -0.487299 +VERTEX2 2058 -25.2562 -11.1446 -0.500472 +VERTEX2 2059 -24.3735 -11.5983 -0.528523 +VERTEX2 2060 -23.5693 -12.184 -0.545103 +VERTEX2 2061 -22.9831 -11.3448 1.00278 +VERTEX2 2062 -22.3528 -10.5443 0.997694 +VERTEX2 2063 -21.7934 -9.68397 0.969025 +VERTEX2 2064 -21.2668 -8.85816 0.970404 +VERTEX2 2065 -20.7295 -8.12832 0.949282 +VERTEX2 2066 -21.5472 -7.53264 2.4971 +VERTEX2 2067 -22.3832 -6.92191 2.52433 +VERTEX2 2068 -23.1194 -6.29834 2.51284 +VERTEX2 2069 -23.9581 -5.66369 2.53207 +VERTEX2 2070 -24.8043 -5.02537 2.53625 +VERTEX2 2071 -24.2609 -4.23558 0.962738 +VERTEX2 2072 -23.6213 -3.49659 0.970915 +VERTEX2 2073 -23.11 -2.73717 0.974565 +VERTEX2 2074 -22.5917 -1.82451 0.985269 +VERTEX2 2075 -22.0662 -1.00574 0.983252 +VERTEX2 2076 -22.7727 -0.469014 2.55678 +VERTEX2 2077 -23.683 0.0589224 2.57231 +VERTEX2 2078 -24.5088 0.503269 2.54792 +VERTEX2 2079 -25.3691 1.08725 2.53073 +VERTEX2 2080 -26.1567 1.66746 2.55723 +VERTEX2 2081 -25.5762 2.49301 0.957204 +VERTEX2 2082 -25.015 3.35093 0.96005 +VERTEX2 2083 -24.5735 4.19608 0.953901 +VERTEX2 2084 -23.9056 5.01438 0.965834 +VERTEX2 2085 -23.406 5.782 0.98094 +VERTEX2 2086 -24.2753 6.28793 2.56502 +VERTEX2 2087 -25.1378 6.82137 2.53164 +VERTEX2 2088 -25.8501 7.4199 2.52859 +VERTEX2 2089 -26.6978 8.07985 2.5427 +VERTEX2 2090 -27.5519 8.62362 2.53009 +VERTEX2 2091 -28.1088 7.70734 -2.20413 +VERTEX2 2092 -28.6905 6.90155 -2.19502 +VERTEX2 2093 -29.1875 6.06336 -2.20768 +VERTEX2 2094 -29.6536 5.2986 -2.21744 +VERTEX2 2095 -30.333 4.49178 -2.21156 +VERTEX2 2096 -29.3937 3.89549 -0.626496 +VERTEX2 2097 -28.5772 3.32012 -0.635275 +VERTEX2 2098 -27.726 2.70237 -0.619608 +VERTEX2 2099 -26.9067 2.08766 -0.605263 +VERTEX2 2100 -26.0629 1.48325 -0.600737 +VERTEX2 2101 -26.6391 0.704716 -2.18615 +VERTEX2 2102 -27.1682 -0.130507 -2.21152 +VERTEX2 2103 -27.6473 -1.0611 -2.19987 +VERTEX2 2104 -28.2201 -1.79037 -2.21438 +VERTEX2 2105 -28.8641 -2.68801 -2.22821 +VERTEX2 2106 -28.0551 -3.32534 -0.663399 +VERTEX2 2107 -27.3101 -3.97092 -0.624348 +VERTEX2 2108 -26.4342 -4.54411 -0.654327 +VERTEX2 2109 -25.6517 -5.14787 -0.6677 +VERTEX2 2110 -24.8888 -5.72625 -0.653872 +VERTEX2 2111 -25.5439 -6.45124 -2.24218 +VERTEX2 2112 -26.1975 -7.27307 -2.20786 +VERTEX2 2113 -26.8211 -8.18751 -2.19779 +VERTEX2 2114 -27.4536 -8.98686 -2.22102 +VERTEX2 2115 -28.0369 -9.87707 -2.24284 +VERTEX2 2116 -27.1609 -10.4543 -0.685432 +VERTEX2 2117 -26.3717 -11.1443 -0.721439 +VERTEX2 2118 -25.5635 -11.906 -0.718893 +VERTEX2 2119 -24.8135 -12.5356 -0.710716 +VERTEX2 2120 -23.9764 -13.2468 -0.73881 +VERTEX2 2121 -23.3059 -12.4772 0.843023 +VERTEX2 2122 -22.6118 -11.7645 0.846578 +VERTEX2 2123 -21.9392 -10.9583 0.868428 +VERTEX2 2124 -21.3477 -10.1932 0.873793 +VERTEX2 2125 -20.7556 -9.3369 0.858069 +VERTEX2 2126 -21.4612 -8.66028 2.44629 +VERTEX2 2127 -22.1667 -8.06307 2.45537 +VERTEX2 2128 -22.8807 -7.38723 2.45954 +VERTEX2 2129 -23.6776 -6.80166 2.47321 +VERTEX2 2130 -24.5002 -6.20744 2.49398 +VERTEX2 2131 -25.1418 -6.96574 -2.21875 +VERTEX2 2132 -25.6689 -7.68038 -2.20986 +VERTEX2 2133 -26.2608 -8.43573 -2.22144 +VERTEX2 2134 -26.8168 -9.30165 -2.21022 +VERTEX2 2135 -27.5304 -10.0437 -2.20374 +VERTEX2 2136 -26.7704 -10.7377 -0.636977 +VERTEX2 2137 -26.039 -11.4077 -0.65251 +VERTEX2 2138 -25.1794 -11.9859 -0.642455 +VERTEX2 2139 -24.3208 -12.6492 -0.621864 +VERTEX2 2140 -23.4488 -13.2009 -0.615664 +VERTEX2 2141 -22.8822 -12.3145 0.951564 +VERTEX2 2142 -22.244 -11.4794 0.961323 +VERTEX2 2143 -21.7157 -10.653 0.938636 +VERTEX2 2144 -21.081 -9.79632 0.958144 +VERTEX2 2145 -20.4894 -9.00313 0.920603 +VERTEX2 2146 -21.3927 -8.36448 2.48162 +VERTEX2 2147 -22.1786 -7.66541 2.47875 +VERTEX2 2148 -23.0015 -7.10452 2.51599 +VERTEX2 2149 -23.8125 -6.53038 2.5057 +VERTEX2 2150 -24.562 -5.98111 2.51526 +VERTEX2 2151 -25.1892 -6.75962 -2.18565 +VERTEX2 2152 -25.6882 -7.58118 -2.20649 +VERTEX2 2153 -26.3974 -8.36855 -2.20635 +VERTEX2 2154 -26.9587 -9.12922 -2.17593 +VERTEX2 2155 -27.5366 -9.94961 -2.18439 +VERTEX2 2156 -26.6838 -10.516 -0.607257 +VERTEX2 2157 -25.7623 -11.0583 -0.604699 +VERTEX2 2158 -24.8792 -11.6515 -0.626468 +VERTEX2 2159 -24.0912 -12.2041 -0.630329 +VERTEX2 2160 -23.3286 -12.8397 -0.628378 +VERTEX2 2161 -23.9658 -13.6198 -2.19345 +VERTEX2 2162 -24.4868 -14.4062 -2.20956 +VERTEX2 2163 -25.0733 -15.1925 -2.22215 +VERTEX2 2164 -25.7098 -15.9446 -2.22048 +VERTEX2 2165 -26.3042 -16.6879 -2.24152 +VERTEX2 2166 -25.5009 -17.3489 -0.653259 +VERTEX2 2167 -24.7159 -17.8276 -0.655044 +VERTEX2 2168 -23.9684 -18.4093 -0.674743 +VERTEX2 2169 -23.204 -19.111 -0.673918 +VERTEX2 2170 -22.4332 -19.7771 -0.670034 +VERTEX2 2171 -21.863 -18.9192 0.879588 +VERTEX2 2172 -21.2026 -18.104 0.874673 +VERTEX2 2173 -20.5809 -17.2586 0.914196 +VERTEX2 2174 -19.8904 -16.4094 0.915505 +VERTEX2 2175 -19.4149 -15.5275 0.932563 +VERTEX2 2176 -20.249 -14.9853 2.55042 +VERTEX2 2177 -21.0522 -14.3575 2.53571 +VERTEX2 2178 -21.8388 -13.8141 2.5139 +VERTEX2 2179 -22.6623 -13.2553 2.49682 +VERTEX2 2180 -23.4326 -12.6347 2.53839 +VERTEX2 2181 -23.9894 -13.5079 -2.16712 +VERTEX2 2182 -24.6176 -14.2683 -2.13606 +VERTEX2 2183 -25.1897 -15.0004 -2.15797 +VERTEX2 2184 -25.6321 -15.7831 -2.14273 +VERTEX2 2185 -26.181 -16.6671 -2.17722 +VERTEX2 2186 -27.0013 -16.088 2.53197 +VERTEX2 2187 -27.7709 -15.5447 2.53494 +VERTEX2 2188 -28.5741 -14.9675 2.53602 +VERTEX2 2189 -29.3081 -14.32 2.50663 +VERTEX2 2190 -30.154 -13.7639 2.4766 +VERTEX2 2191 -30.6543 -14.5978 -2.22116 +VERTEX2 2192 -31.2886 -15.391 -2.21063 +VERTEX2 2193 -31.8007 -16.1688 -2.19769 +VERTEX2 2194 -32.3317 -16.9836 -2.17219 +VERTEX2 2195 -32.9376 -17.75 -2.18386 +VERTEX2 2196 -33.7844 -17.2085 2.52065 +VERTEX2 2197 -34.6497 -16.5663 2.51936 +VERTEX2 2198 -35.4348 -15.9605 2.53905 +VERTEX2 2199 -36.1693 -15.4125 2.55635 +VERTEX2 2200 -37.0325 -14.9048 2.56901 +VERTEX2 2201 -36.4435 -14.1046 1.03327 +VERTEX2 2202 -35.9213 -13.1721 1.02941 +VERTEX2 2203 -35.3895 -12.2847 1.02558 +VERTEX2 2204 -34.9545 -11.3824 1.04973 +VERTEX2 2205 -34.4925 -10.6416 1.06115 +VERTEX2 2206 -35.3675 -10.183 2.60082 +VERTEX2 2207 -36.2565 -9.62341 2.60892 +VERTEX2 2208 -37.1225 -9.08297 2.5513 +VERTEX2 2209 -37.9327 -8.56056 2.5388 +VERTEX2 2210 -38.7484 -7.95265 2.52645 +VERTEX2 2211 -39.3102 -8.80905 -2.17795 +VERTEX2 2212 -39.8796 -9.64383 -2.17619 +VERTEX2 2213 -40.4735 -10.4379 -2.13187 +VERTEX2 2214 -41.041 -11.2786 -2.12226 +VERTEX2 2215 -41.5158 -12.0566 -2.11717 +VERTEX2 2216 -40.781 -12.5638 -0.512498 +VERTEX2 2217 -39.9317 -13.0609 -0.524896 +VERTEX2 2218 -39.1071 -13.5879 -0.499367 +VERTEX2 2219 -38.3063 -14.0355 -0.503208 +VERTEX2 2220 -37.4806 -14.4758 -0.501131 +VERTEX2 2221 -37.9239 -15.2852 -2.08402 +VERTEX2 2222 -38.4773 -16.1905 -2.05655 +VERTEX2 2223 -38.9962 -17.1532 -2.07652 +VERTEX2 2224 -39.4514 -17.9958 -2.05771 +VERTEX2 2225 -39.8788 -18.879 -2.04049 +VERTEX2 2226 -38.9521 -19.3226 -0.497408 +VERTEX2 2227 -38.0803 -19.7753 -0.459916 +VERTEX2 2228 -37.1701 -20.232 -0.456251 +VERTEX2 2229 -36.2538 -20.6137 -0.435612 +VERTEX2 2230 -35.3352 -21.0428 -0.431071 +VERTEX2 2231 -35.7111 -22.0294 -1.97421 +VERTEX2 2232 -36.2346 -22.983 -1.99973 +VERTEX2 2233 -36.6503 -23.8879 -1.99935 +VERTEX2 2234 -37.0321 -24.7392 -1.9945 +VERTEX2 2235 -37.3942 -25.7124 -2.00447 +VERTEX2 2236 -36.4421 -26.0936 -0.435866 +VERTEX2 2237 -35.55 -26.501 -0.441485 +VERTEX2 2238 -34.6831 -26.8881 -0.418416 +VERTEX2 2239 -33.7655 -27.2646 -0.409625 +VERTEX2 2240 -32.8315 -27.6445 -0.387139 +VERTEX2 2241 -32.512 -26.7598 1.2072 +VERTEX2 2242 -32.1095 -25.8618 1.21865 +VERTEX2 2243 -31.7325 -24.9363 1.21474 +VERTEX2 2244 -31.4823 -24.0091 1.19711 +VERTEX2 2245 -31.1358 -23.0297 1.1934 +VERTEX2 2246 -32.1219 -22.7172 2.76142 +VERTEX2 2247 -33.0688 -22.2976 2.74747 +VERTEX2 2248 -33.9768 -21.9563 2.74634 +VERTEX2 2249 -34.9101 -21.5646 2.72761 +VERTEX2 2250 -35.7966 -21.1516 2.72037 +VERTEX2 2251 -36.2454 -22.0484 -1.97143 +VERTEX2 2252 -36.6175 -22.9107 -1.9614 +VERTEX2 2253 -37.0174 -23.8998 -1.95746 +VERTEX2 2254 -37.3406 -24.821 -1.93136 +VERTEX2 2255 -37.7077 -25.63 -1.91047 +VERTEX2 2256 -38.5678 -25.3125 2.81307 +VERTEX2 2257 -39.4402 -24.9817 2.80715 +VERTEX2 2258 -40.3626 -24.6784 2.81993 +VERTEX2 2259 -41.2252 -24.3846 2.82848 +VERTEX2 2260 -42.1342 -24.1117 2.82969 +VERTEX2 2261 -41.8758 -23.1873 1.26742 +VERTEX2 2262 -41.6054 -22.1488 1.26115 +VERTEX2 2263 -41.2861 -21.2409 1.25011 +VERTEX2 2264 -41.0156 -20.281 1.19773 +VERTEX2 2265 -40.667 -19.4155 1.20909 +VERTEX2 2266 -39.715 -19.7785 -0.372112 +VERTEX2 2267 -38.7845 -20.1383 -0.352734 +VERTEX2 2268 -37.847 -20.3997 -0.388552 +VERTEX2 2269 -36.9708 -20.7717 -0.385009 +VERTEX2 2270 -36.0478 -21.2278 -0.383865 +VERTEX2 2271 -36.4142 -22.0456 -1.96685 +VERTEX2 2272 -36.7618 -23.0732 -1.93711 +VERTEX2 2273 -37.0612 -24.0331 -1.93075 +VERTEX2 2274 -37.544 -24.9229 -1.93567 +VERTEX2 2275 -37.9336 -25.8534 -1.92962 +VERTEX2 2276 -37.0026 -26.2414 -0.372766 +VERTEX2 2277 -36.0369 -26.6698 -0.360565 +VERTEX2 2278 -35.015 -27.0449 -0.336394 +VERTEX2 2279 -34.1497 -27.3216 -0.339998 +VERTEX2 2280 -33.2014 -27.6523 -0.319565 +VERTEX2 2281 -33.5277 -28.7016 -1.91669 +VERTEX2 2282 -33.8475 -29.6743 -1.84037 +VERTEX2 2283 -34.0536 -30.6509 -1.84725 +VERTEX2 2284 -34.4019 -31.5602 -1.87424 +VERTEX2 2285 -34.718 -32.5281 -1.87137 +VERTEX2 2286 -33.7819 -32.8437 -0.308141 +VERTEX2 2287 -32.7798 -33.13 -0.298199 +VERTEX2 2288 -31.8827 -33.3868 -0.323123 +VERTEX2 2289 -30.8996 -33.6619 -0.330815 +VERTEX2 2290 -30.017 -34.0523 -0.344846 +VERTEX2 2291 -29.6917 -33.1115 1.21449 +VERTEX2 2292 -29.3558 -32.1726 1.19236 +VERTEX2 2293 -29.0412 -31.1717 1.24183 +VERTEX2 2294 -28.8044 -30.2805 1.2222 +VERTEX2 2295 -28.4341 -29.2729 1.2082 +VERTEX2 2296 -27.4503 -29.6487 -0.355111 +VERTEX2 2297 -26.5215 -29.9691 -0.3395 +VERTEX2 2298 -25.5891 -30.2204 -0.356269 +VERTEX2 2299 -24.5751 -30.5563 -0.366286 +VERTEX2 2300 -23.6683 -30.8981 -0.385414 +VERTEX2 2301 -23.3999 -30.004 1.19367 +VERTEX2 2302 -23.0173 -29.0969 1.16718 +VERTEX2 2303 -22.6358 -28.1247 1.16355 +VERTEX2 2304 -22.2515 -27.2197 1.17386 +VERTEX2 2305 -21.8756 -26.393 1.17452 +VERTEX2 2306 -20.9509 -26.7247 -0.35336 +VERTEX2 2307 -20.0106 -27.0473 -0.378832 +VERTEX2 2308 -19.0683 -27.5058 -0.382466 +VERTEX2 2309 -18.0705 -27.802 -0.401091 +VERTEX2 2310 -17.0876 -28.2221 -0.451426 +VERTEX2 2311 -16.5943 -27.4158 1.10528 +VERTEX2 2312 -16.2118 -26.4637 1.11467 +VERTEX2 2313 -15.7059 -25.6516 1.11652 +VERTEX2 2314 -15.2734 -24.7502 1.13692 +VERTEX2 2315 -14.8031 -23.8919 1.11878 +VERTEX2 2316 -13.8245 -24.3139 -0.45076 +VERTEX2 2317 -12.8472 -24.7878 -0.456486 +VERTEX2 2318 -11.9863 -25.2511 -0.452594 +VERTEX2 2319 -11.069 -25.7242 -0.478989 +VERTEX2 2320 -10.1818 -26.2064 -0.471158 +VERTEX2 2321 -9.68834 -25.3479 1.09159 +VERTEX2 2322 -9.29535 -24.4975 1.11634 +VERTEX2 2323 -8.89155 -23.6023 1.10694 +VERTEX2 2324 -8.49713 -22.6783 1.07153 +VERTEX2 2325 -8.04387 -21.8401 1.02528 +VERTEX2 2326 -8.83289 -21.2797 2.59188 +VERTEX2 2327 -9.72456 -20.8289 2.5701 +VERTEX2 2328 -10.5205 -20.2305 2.58728 +VERTEX2 2329 -11.3982 -19.6921 2.59312 +VERTEX2 2330 -12.2359 -19.1236 2.60946 +VERTEX2 2331 -12.7798 -19.9478 -2.10877 +VERTEX2 2332 -13.3223 -20.8657 -2.1221 +VERTEX2 2333 -13.887 -21.6555 -2.11644 +VERTEX2 2334 -14.464 -22.4477 -2.10716 +VERTEX2 2335 -14.9601 -23.3144 -2.12529 +VERTEX2 2336 -14.0838 -23.8282 -0.570339 +VERTEX2 2337 -13.2978 -24.3679 -0.554771 +VERTEX2 2338 -12.3715 -24.8486 -0.553468 +VERTEX2 2339 -11.5362 -25.3581 -0.552068 +VERTEX2 2340 -10.6397 -25.9214 -0.575576 +VERTEX2 2341 -10.1158 -25.0409 1.00289 +VERTEX2 2342 -9.51028 -24.1688 1.03 +VERTEX2 2343 -8.98458 -23.3574 1.04997 +VERTEX2 2344 -8.40522 -22.4467 1.06041 +VERTEX2 2345 -7.86278 -21.4712 1.05563 +VERTEX2 2346 -8.76203 -21.0752 2.6037 +VERTEX2 2347 -9.56329 -20.5418 2.62576 +VERTEX2 2348 -10.4473 -20.0065 2.6287 +VERTEX2 2349 -11.357 -19.5296 2.62521 +VERTEX2 2350 -12.2439 -19.0943 2.65625 +VERTEX2 2351 -12.7505 -19.9998 -2.01738 +VERTEX2 2352 -13.169 -20.9537 -2.00239 +VERTEX2 2353 -13.5909 -21.8865 -1.97365 +VERTEX2 2354 -13.9482 -22.8126 -1.99133 +VERTEX2 2355 -14.3289 -23.7914 -2.01507 +VERTEX2 2356 -13.4189 -24.2655 -0.421258 +VERTEX2 2357 -12.4875 -24.666 -0.424967 +VERTEX2 2358 -11.5601 -25.1885 -0.439404 +VERTEX2 2359 -10.6944 -25.5704 -0.43627 +VERTEX2 2360 -9.75193 -25.9761 -0.439088 +VERTEX2 2361 -9.31848 -24.9976 1.11305 +VERTEX2 2362 -8.84573 -24.1326 1.1176 +VERTEX2 2363 -8.41144 -23.2164 1.1093 +VERTEX2 2364 -8.03092 -22.3069 1.09651 +VERTEX2 2365 -7.56054 -21.3758 1.07655 +VERTEX2 2366 -8.43766 -20.9353 2.65537 +VERTEX2 2367 -9.32789 -20.5327 2.6764 +VERTEX2 2368 -10.1997 -20.0642 2.63471 +VERTEX2 2369 -11.0622 -19.5972 2.65018 +VERTEX2 2370 -11.9216 -19.1081 2.64713 +VERTEX2 2371 -12.3199 -19.9991 -2.10022 +VERTEX2 2372 -12.7155 -20.9256 -2.12139 +VERTEX2 2373 -13.2757 -21.6853 -2.10506 +VERTEX2 2374 -13.857 -22.5994 -2.16328 +VERTEX2 2375 -14.3854 -23.3855 -2.16031 +VERTEX2 2376 -15.1792 -22.8311 2.53554 +VERTEX2 2377 -15.9528 -22.2613 2.54789 +VERTEX2 2378 -16.754 -21.5979 2.5628 +VERTEX2 2379 -17.5198 -21.0529 2.51825 +VERTEX2 2380 -18.3446 -20.482 2.5204 +VERTEX2 2381 -18.9648 -21.4231 -2.17414 +VERTEX2 2382 -19.5172 -22.3 -2.17344 +VERTEX2 2383 -20.1083 -23.178 -2.21344 +VERTEX2 2384 -20.7071 -24.0157 -2.19119 +VERTEX2 2385 -21.2197 -24.8152 -2.20018 +VERTEX2 2386 -20.4134 -25.3802 -0.616646 +VERTEX2 2387 -19.5312 -25.9444 -0.662074 +VERTEX2 2388 -18.7791 -26.579 -0.629692 +VERTEX2 2389 -17.9768 -27.1977 -0.612873 +VERTEX2 2390 -17.2249 -27.7359 -0.619769 +VERTEX2 2391 -16.6275 -26.8813 0.99477 +VERTEX2 2392 -16.1142 -26.0338 1.00881 +VERTEX2 2393 -15.5605 -25.2138 1.01179 +VERTEX2 2394 -14.9678 -24.4266 0.983231 +VERTEX2 2395 -14.3873 -23.5127 0.979656 +VERTEX2 2396 -15.2127 -22.9787 2.5639 +VERTEX2 2397 -16.0107 -22.43 2.59215 +VERTEX2 2398 -16.8217 -21.929 2.61083 +VERTEX2 2399 -17.6443 -21.3857 2.59251 +VERTEX2 2400 -18.4827 -20.9233 2.57175 +VERTEX2 2401 -19.0407 -21.7484 -2.12268 +VERTEX2 2402 -19.5708 -22.5553 -2.15062 +VERTEX2 2403 -20.0582 -23.4187 -2.12693 +VERTEX2 2404 -20.6605 -24.2957 -2.13112 +VERTEX2 2405 -21.1341 -25.1221 -2.13948 +VERTEX2 2406 -21.9925 -24.5713 2.57396 +VERTEX2 2407 -22.8641 -24.0865 2.57712 +VERTEX2 2408 -23.6683 -23.5462 2.59267 +VERTEX2 2409 -24.5336 -23.0902 2.6045 +VERTEX2 2410 -25.405 -22.6415 2.55225 +VERTEX2 2411 -25.9143 -23.3661 -2.14748 +VERTEX2 2412 -26.4315 -24.167 -2.1677 +VERTEX2 2413 -27.0319 -24.9714 -2.16657 +VERTEX2 2414 -27.6065 -25.7748 -2.15258 +VERTEX2 2415 -28.0883 -26.5872 -2.17344 +VERTEX2 2416 -27.2247 -27.1466 -0.620395 +VERTEX2 2417 -26.4797 -27.796 -0.598217 +VERTEX2 2418 -25.6084 -28.292 -0.58629 +VERTEX2 2419 -24.7388 -28.8608 -0.58783 +VERTEX2 2420 -23.9883 -29.4851 -0.567712 +VERTEX2 2421 -23.5397 -28.6226 0.991672 +VERTEX2 2422 -22.9749 -27.822 0.990172 +VERTEX2 2423 -22.4503 -27.0441 1.01418 +VERTEX2 2424 -21.876 -26.2313 1.02697 +VERTEX2 2425 -21.3437 -25.391 1.03747 +VERTEX2 2426 -22.1908 -24.824 2.58869 +VERTEX2 2427 -23.071 -24.3492 2.59435 +VERTEX2 2428 -23.9809 -23.8076 2.59421 +VERTEX2 2429 -24.823 -23.3505 2.60617 +VERTEX2 2430 -25.6464 -22.8732 2.61576 +VERTEX2 2431 -26.0975 -23.7416 -2.10175 +VERTEX2 2432 -26.6436 -24.5503 -2.10552 +VERTEX2 2433 -27.1422 -25.4722 -2.09374 +VERTEX2 2434 -27.6508 -26.3413 -2.09784 +VERTEX2 2435 -28.1259 -27.1989 -2.11277 +VERTEX2 2436 -27.3061 -27.6844 -0.560213 +VERTEX2 2437 -26.4484 -28.2073 -0.565251 +VERTEX2 2438 -25.6338 -28.7248 -0.528987 +VERTEX2 2439 -24.8567 -29.185 -0.512503 +VERTEX2 2440 -24.0686 -29.6356 -0.512995 +VERTEX2 2441 -24.5434 -30.4599 -2.10883 +VERTEX2 2442 -25.0641 -31.3473 -2.15061 +VERTEX2 2443 -25.6155 -32.1275 -2.13686 +VERTEX2 2444 -26.0502 -32.9739 -2.14633 +VERTEX2 2445 -26.5055 -33.7926 -2.15372 +VERTEX2 2446 -27.342 -33.2311 2.56079 +VERTEX2 2447 -28.1285 -32.6676 2.57321 +VERTEX2 2448 -28.9924 -32.1105 2.57337 +VERTEX2 2449 -29.7763 -31.5591 2.60126 +VERTEX2 2450 -30.6846 -30.9454 2.60809 +VERTEX2 2451 -30.2266 -30.0577 1.05633 +VERTEX2 2452 -29.657 -29.1622 1.07866 +VERTEX2 2453 -29.1833 -28.2876 1.08763 +VERTEX2 2454 -28.7217 -27.4084 1.10875 +VERTEX2 2455 -28.2672 -26.565 1.10379 +VERTEX2 2456 -29.239 -26.0387 2.71738 +VERTEX2 2457 -30.1939 -25.6119 2.73684 +VERTEX2 2458 -31.2061 -25.2156 2.79259 +VERTEX2 2459 -32.1548 -24.7615 2.80345 +VERTEX2 2460 -33.0812 -24.4187 2.80202 +VERTEX2 2461 -33.4531 -25.3385 -1.89814 +VERTEX2 2462 -33.791 -26.2718 -1.89486 +VERTEX2 2463 -34.1956 -27.1443 -1.90619 +VERTEX2 2464 -34.4357 -28.0297 -1.92497 +VERTEX2 2465 -34.7219 -28.9175 -1.91876 +VERTEX2 2466 -33.695 -29.2361 -0.353491 +VERTEX2 2467 -32.7103 -29.6075 -0.391096 +VERTEX2 2468 -31.7583 -29.9897 -0.378117 +VERTEX2 2469 -30.8519 -30.2957 -0.381076 +VERTEX2 2470 -29.9163 -30.7149 -0.390999 +VERTEX2 2471 -30.2902 -31.6154 -1.9381 +VERTEX2 2472 -30.6188 -32.5348 -1.94721 +VERTEX2 2473 -30.9833 -33.5063 -1.94006 +VERTEX2 2474 -31.4296 -34.4417 -1.91612 +VERTEX2 2475 -31.7388 -35.3817 -1.93224 +VERTEX2 2476 -30.7554 -35.7818 -0.347614 +VERTEX2 2477 -29.8016 -36.1616 -0.370215 +VERTEX2 2478 -28.8712 -36.5138 -0.362155 +VERTEX2 2479 -27.997 -36.848 -0.383551 +VERTEX2 2480 -27.0368 -37.2706 -0.36755 +VERTEX2 2481 -26.6498 -36.3555 1.22138 +VERTEX2 2482 -26.2698 -35.4834 1.20491 +VERTEX2 2483 -25.8836 -34.5515 1.2003 +VERTEX2 2484 -25.5038 -33.6074 1.22036 +VERTEX2 2485 -25.1692 -32.6677 1.26118 +VERTEX2 2486 -26.08 -32.2727 2.84137 +VERTEX2 2487 -27.1318 -32.0088 2.82205 +VERTEX2 2488 -28.007 -31.6899 2.83196 +VERTEX2 2489 -28.9196 -31.3178 2.82458 +VERTEX2 2490 -29.8873 -30.9801 2.82505 +VERTEX2 2491 -29.4602 -29.9773 1.25633 +VERTEX2 2492 -29.1304 -29.0982 1.24568 +VERTEX2 2493 -28.7452 -28.1753 1.25039 +VERTEX2 2494 -28.3885 -27.2255 1.24078 +VERTEX2 2495 -28.077 -26.3271 1.25654 +VERTEX2 2496 -27.1167 -26.5908 -0.31735 +VERTEX2 2497 -26.1466 -26.9299 -0.342127 +VERTEX2 2498 -25.2583 -27.2878 -0.348879 +VERTEX2 2499 -24.2968 -27.5356 -0.355607 +VERTEX2 2500 -23.2773 -27.8961 -0.381776 +VERTEX2 2501 -23.6333 -28.8156 -1.94389 +VERTEX2 2502 -24.034 -29.7916 -1.94874 +VERTEX2 2503 -24.4693 -30.7072 -1.95834 +VERTEX2 2504 -24.8448 -31.6432 -1.9963 +VERTEX2 2505 -25.2186 -32.5584 -1.9928 +VERTEX2 2506 -24.3207 -32.9687 -0.426081 +VERTEX2 2507 -23.4171 -33.3201 -0.42228 +VERTEX2 2508 -22.5321 -33.7405 -0.430997 +VERTEX2 2509 -21.6394 -34.1332 -0.41702 +VERTEX2 2510 -20.7447 -34.5519 -0.394973 +VERTEX2 2511 -20.2902 -33.6572 1.18093 +VERTEX2 2512 -19.9085 -32.756 1.17389 +VERTEX2 2513 -19.5004 -31.8605 1.20777 +VERTEX2 2514 -19.1714 -30.7936 1.2051 +VERTEX2 2515 -18.8558 -29.8982 1.19398 +VERTEX2 2516 -19.7746 -29.4994 2.75333 +VERTEX2 2517 -20.7694 -29.1249 2.75461 +VERTEX2 2518 -21.7721 -28.7545 2.7657 +VERTEX2 2519 -22.8013 -28.4467 2.77482 +VERTEX2 2520 -23.7657 -28.0375 2.75922 +VERTEX2 2521 -23.3587 -27.1222 1.18116 +VERTEX2 2522 -23.0541 -26.2512 1.19699 +VERTEX2 2523 -22.6705 -25.2859 1.18692 +VERTEX2 2524 -22.3468 -24.3286 1.18626 +VERTEX2 2525 -21.9796 -23.4182 1.19207 +VERTEX2 2526 -22.9261 -23.0209 2.78514 +VERTEX2 2527 -23.8444 -22.6995 2.79842 +VERTEX2 2528 -24.7161 -22.264 2.77681 +VERTEX2 2529 -25.7252 -21.8951 2.79095 +VERTEX2 2530 -26.715 -21.5836 2.77701 +VERTEX2 2531 -27.0719 -22.5343 -1.90485 +VERTEX2 2532 -27.3692 -23.4605 -1.89295 +VERTEX2 2533 -27.7318 -24.3987 -1.88327 +VERTEX2 2534 -27.9819 -25.3675 -1.87838 +VERTEX2 2535 -28.3241 -26.4076 -1.92167 +VERTEX2 2536 -27.256 -26.7828 -0.343817 +VERTEX2 2537 -26.303 -27.0463 -0.308177 +VERTEX2 2538 -25.3712 -27.3905 -0.295279 +VERTEX2 2539 -24.3506 -27.6686 -0.291842 +VERTEX2 2540 -23.4788 -27.9164 -0.299395 +VERTEX2 2541 -23.1549 -26.9929 1.25184 +VERTEX2 2542 -22.8039 -26.0171 1.25908 +VERTEX2 2543 -22.5819 -24.9926 1.26449 +VERTEX2 2544 -22.2733 -24.048 1.23244 +VERTEX2 2545 -21.9417 -23.0649 1.21465 +VERTEX2 2546 -22.9331 -22.797 2.79961 +VERTEX2 2547 -23.8736 -22.4165 2.81528 +VERTEX2 2548 -24.8036 -22.1505 2.8264 +VERTEX2 2549 -25.7154 -21.7523 2.83877 +VERTEX2 2550 -26.698 -21.5224 2.81014 +VERTEX2 2551 -26.9713 -22.469 -1.9054 +VERTEX2 2552 -27.2941 -23.4711 -1.92259 +VERTEX2 2553 -27.6028 -24.3908 -1.91862 +VERTEX2 2554 -28.061 -25.3385 -1.92855 +VERTEX2 2555 -28.4327 -26.35 -1.91635 +VERTEX2 2556 -27.5402 -26.6885 -0.345991 +VERTEX2 2557 -26.5367 -27.1207 -0.336904 +VERTEX2 2558 -25.6581 -27.3617 -0.31612 +VERTEX2 2559 -24.7705 -27.7002 -0.349702 +VERTEX2 2560 -23.8092 -27.9968 -0.359288 +VERTEX2 2561 -23.4138 -27.1153 1.21405 +VERTEX2 2562 -23.1105 -26.211 1.23518 +VERTEX2 2563 -22.8615 -25.297 1.22502 +VERTEX2 2564 -22.5183 -24.323 1.23576 +VERTEX2 2565 -22.1852 -23.3676 1.26185 +VERTEX2 2566 -23.114 -23.023 2.82806 +VERTEX2 2567 -24.0706 -22.8022 2.83913 +VERTEX2 2568 -24.9935 -22.5557 2.8474 +VERTEX2 2569 -25.8756 -22.2741 2.88136 +VERTEX2 2570 -26.9139 -22.0806 2.86748 +VERTEX2 2571 -27.0952 -23.0106 -1.869 +VERTEX2 2572 -27.4316 -24.0166 -1.88607 +VERTEX2 2573 -27.7542 -25.0163 -1.88487 +VERTEX2 2574 -28.0682 -25.9408 -1.81692 +VERTEX2 2575 -28.3871 -26.9564 -1.84229 +VERTEX2 2576 -27.4262 -27.1508 -0.264573 +VERTEX2 2577 -26.3957 -27.5128 -0.246965 +VERTEX2 2578 -25.4172 -27.7944 -0.246542 +VERTEX2 2579 -24.3751 -28.038 -0.242891 +VERTEX2 2580 -23.2739 -28.219 -0.297315 +VERTEX2 2581 -22.962 -27.2715 1.24824 +VERTEX2 2582 -22.6668 -26.3124 1.22476 +VERTEX2 2583 -22.2452 -25.3272 1.27213 +VERTEX2 2584 -21.9641 -24.3802 1.30025 +VERTEX2 2585 -21.7194 -23.4281 1.30056 +VERTEX2 2586 -22.6295 -23.1857 2.87724 +VERTEX2 2587 -23.5972 -22.9308 2.89775 +VERTEX2 2588 -24.543 -22.7198 2.88521 +VERTEX2 2589 -25.4064 -22.5207 2.87612 +VERTEX2 2590 -26.3416 -22.2 2.8634 +VERTEX2 2591 -26.58 -23.1729 -1.84178 +VERTEX2 2592 -26.8356 -24.1881 -1.85741 +VERTEX2 2593 -27.0815 -25.2401 -1.85518 +VERTEX2 2594 -27.4368 -26.1103 -1.89494 +VERTEX2 2595 -27.728 -27.0412 -1.88667 +VERTEX2 2596 -26.7972 -27.3669 -0.333168 +VERTEX2 2597 -25.816 -27.7036 -0.361839 +VERTEX2 2598 -24.8415 -28.0816 -0.378019 +VERTEX2 2599 -23.8742 -28.4311 -0.385182 +VERTEX2 2600 -22.826 -28.8795 -0.365727 +VERTEX2 2601 -23.2468 -29.8362 -1.94721 +VERTEX2 2602 -23.6099 -30.8218 -1.94975 +VERTEX2 2603 -24.0542 -31.7343 -1.94374 +VERTEX2 2604 -24.3723 -32.7065 -1.96492 +VERTEX2 2605 -24.6995 -33.5767 -1.98512 +VERTEX2 2606 -23.741 -34.0259 -0.442919 +VERTEX2 2607 -22.7988 -34.4959 -0.443727 +VERTEX2 2608 -21.823 -34.926 -0.456324 +VERTEX2 2609 -20.8962 -35.3297 -0.445513 +VERTEX2 2610 -19.994 -35.7102 -0.399951 +VERTEX2 2611 -20.3751 -36.6333 -1.98945 +VERTEX2 2612 -20.777 -37.4894 -1.96655 +VERTEX2 2613 -21.2143 -38.3526 -1.96677 +VERTEX2 2614 -21.6148 -39.2974 -1.97026 +VERTEX2 2615 -21.9669 -40.2353 -1.97713 +VERTEX2 2616 -21.0271 -40.6894 -0.375224 +VERTEX2 2617 -20.1178 -41.1404 -0.389164 +VERTEX2 2618 -19.2545 -41.5972 -0.403961 +VERTEX2 2619 -18.3653 -41.9871 -0.414622 +VERTEX2 2620 -17.4261 -42.3506 -0.39385 +VERTEX2 2621 -16.9975 -41.5478 1.18698 +VERTEX2 2622 -16.6039 -40.5925 1.24024 +VERTEX2 2623 -16.2074 -39.7299 1.23187 +VERTEX2 2624 -15.8867 -38.7996 1.26161 +VERTEX2 2625 -15.5748 -37.8758 1.25961 +VERTEX2 2626 -16.5181 -37.5456 2.8458 +VERTEX2 2627 -17.4839 -37.2355 2.83471 +VERTEX2 2628 -18.411 -36.9925 2.85624 +VERTEX2 2629 -19.3177 -36.7236 2.84137 +VERTEX2 2630 -20.2838 -36.4414 2.84131 +VERTEX2 2631 -19.8906 -35.4809 1.26002 +VERTEX2 2632 -19.5462 -34.5051 1.23442 +VERTEX2 2633 -19.2501 -33.5618 1.24463 +VERTEX2 2634 -18.9182 -32.6291 1.26563 +VERTEX2 2635 -18.6296 -31.6173 1.29806 +VERTEX2 2636 -19.6106 -31.305 2.84472 +VERTEX2 2637 -20.4287 -30.9515 2.86267 +VERTEX2 2638 -21.4389 -30.7761 2.84948 +VERTEX2 2639 -22.4406 -30.4389 2.86605 +VERTEX2 2640 -23.5275 -30.0406 2.8445 +VERTEX2 2641 -23.8453 -30.9887 -1.89355 +VERTEX2 2642 -24.1873 -31.8797 -1.87544 +VERTEX2 2643 -24.4768 -32.8567 -1.85868 +VERTEX2 2644 -24.8023 -33.8572 -1.82986 +VERTEX2 2645 -25.0081 -34.7402 -1.85974 +VERTEX2 2646 -24.0622 -35.085 -0.314366 +VERTEX2 2647 -22.9886 -35.4407 -0.297729 +VERTEX2 2648 -22.0521 -35.6785 -0.274254 +VERTEX2 2649 -21.1344 -35.8976 -0.249412 +VERTEX2 2650 -20.1474 -36.1297 -0.251985 +VERTEX2 2651 -19.8581 -35.2829 1.314 +VERTEX2 2652 -19.5833 -34.2911 1.31175 +VERTEX2 2653 -19.4026 -33.2923 1.30644 +VERTEX2 2654 -19.1143 -32.3097 1.31368 +VERTEX2 2655 -18.7673 -31.3691 1.34603 +VERTEX2 2656 -19.7473 -31.1537 2.93506 +VERTEX2 2657 -20.7553 -30.8698 2.91615 +VERTEX2 2658 -21.6891 -30.6294 2.92108 +VERTEX2 2659 -22.6131 -30.308 2.90762 +VERTEX2 2660 -23.609 -30.0863 2.90561 +VERTEX2 2661 -23.8214 -31.1361 -1.8263 +VERTEX2 2662 -24.0621 -32.0801 -1.84721 +VERTEX2 2663 -24.3889 -33.0325 -1.83052 +VERTEX2 2664 -24.6034 -34.005 -1.85546 +VERTEX2 2665 -24.8502 -34.9255 -1.84298 +VERTEX2 2666 -23.911 -35.2049 -0.237531 +VERTEX2 2667 -22.9235 -35.4246 -0.238358 +VERTEX2 2668 -21.9367 -35.5324 -0.265313 +VERTEX2 2669 -21.0397 -35.7657 -0.271456 +VERTEX2 2670 -20.0646 -36.0396 -0.281029 +VERTEX2 2671 -20.2769 -36.9697 -1.86172 +VERTEX2 2672 -20.6311 -38.0099 -1.88022 +VERTEX2 2673 -20.9016 -38.9321 -1.85936 +VERTEX2 2674 -21.1395 -39.9375 -1.84357 +VERTEX2 2675 -21.3719 -40.8039 -1.81956 +VERTEX2 2676 -20.4649 -41.0601 -0.253828 +VERTEX2 2677 -19.4911 -41.3312 -0.290256 +VERTEX2 2678 -18.5243 -41.5768 -0.282263 +VERTEX2 2679 -17.5054 -41.8684 -0.283837 +VERTEX2 2680 -16.4948 -42.1093 -0.228867 +VERTEX2 2681 -16.171 -41.0962 1.35947 +VERTEX2 2682 -15.9159 -40.2189 1.40057 +VERTEX2 2683 -15.7401 -39.2364 1.38602 +VERTEX2 2684 -15.5852 -38.2321 1.37356 +VERTEX2 2685 -15.4171 -37.2725 1.40373 +VERTEX2 2686 -16.3484 -37.137 2.95481 +VERTEX2 2687 -17.3781 -36.8634 2.94015 +VERTEX2 2688 -18.3328 -36.5428 2.92516 +VERTEX2 2689 -19.2736 -36.3575 2.9255 +VERTEX2 2690 -20.2444 -36.0416 2.91847 +VERTEX2 2691 -20.4433 -37.004 -1.81588 +VERTEX2 2692 -20.6966 -37.9454 -1.8281 +VERTEX2 2693 -20.9617 -38.8488 -1.83455 +VERTEX2 2694 -21.2969 -39.834 -1.82745 +VERTEX2 2695 -21.5856 -40.8325 -1.82373 +VERTEX2 2696 -20.6447 -41.1118 -0.25309 +VERTEX2 2697 -19.6519 -41.361 -0.274745 +VERTEX2 2698 -18.5768 -41.6496 -0.271284 +VERTEX2 2699 -17.6562 -41.9283 -0.271901 +VERTEX2 2700 -16.6722 -42.2576 -0.306082 +VERTEX2 2701 -16.9155 -43.2245 -1.89859 +VERTEX2 2702 -17.254 -44.1562 -1.87924 +VERTEX2 2703 -17.5631 -45.1295 -1.90958 +VERTEX2 2704 -17.967 -46.1753 -1.89687 +VERTEX2 2705 -18.2978 -47.1382 -1.9271 +VERTEX2 2706 -19.236 -46.7538 2.77481 +VERTEX2 2707 -20.2102 -46.4267 2.80841 +VERTEX2 2708 -21.093 -46.0472 2.85498 +VERTEX2 2709 -22.1015 -45.7857 2.85108 +VERTEX2 2710 -23.0543 -45.4733 2.80853 +VERTEX2 2711 -23.2846 -46.4498 -1.92918 +VERTEX2 2712 -23.5789 -47.3374 -1.91299 +VERTEX2 2713 -23.8966 -48.2338 -1.95576 +VERTEX2 2714 -24.3438 -49.1778 -1.9226 +VERTEX2 2715 -24.6762 -50.1188 -1.92983 +VERTEX2 2716 -23.6955 -50.4448 -0.35722 +VERTEX2 2717 -22.8584 -50.7635 -0.338034 +VERTEX2 2718 -21.9235 -51.1599 -0.326066 +VERTEX2 2719 -20.9953 -51.4883 -0.368125 +VERTEX2 2720 -20.0045 -51.9621 -0.343661 +VERTEX2 2721 -20.3006 -52.8663 -1.90866 +VERTEX2 2722 -20.6225 -53.8257 -1.9222 +VERTEX2 2723 -20.8982 -54.7618 -1.8961 +VERTEX2 2724 -21.1873 -55.6086 -1.86639 +VERTEX2 2725 -21.472 -56.4822 -1.86321 +VERTEX2 2726 -20.4905 -56.8745 -0.302995 +VERTEX2 2727 -19.5742 -57.1757 -0.294271 +VERTEX2 2728 -18.6411 -57.5033 -0.287681 +VERTEX2 2729 -17.6628 -57.685 -0.321528 +VERTEX2 2730 -16.6583 -58.1409 -0.317124 +VERTEX2 2731 -16.2938 -57.1446 1.23961 +VERTEX2 2732 -15.9701 -56.1873 1.25709 +VERTEX2 2733 -15.6853 -55.2065 1.27766 +VERTEX2 2734 -15.33 -54.3545 1.22795 +VERTEX2 2735 -15.0398 -53.3882 1.22483 +VERTEX2 2736 -16.0365 -53.0406 2.80397 +VERTEX2 2737 -17.0013 -52.6643 2.78287 +VERTEX2 2738 -17.9536 -52.2645 2.78344 +VERTEX2 2739 -18.8781 -51.8587 2.76804 +VERTEX2 2740 -19.7991 -51.5307 2.73988 +VERTEX2 2741 -19.4603 -50.5494 1.20325 +VERTEX2 2742 -19.1216 -49.644 1.2083 +VERTEX2 2743 -18.7745 -48.7045 1.1964 +VERTEX2 2744 -18.4268 -47.6655 1.18606 +VERTEX2 2745 -18.0506 -46.6832 1.15879 +VERTEX2 2746 -17.167 -47.0991 -0.413825 +VERTEX2 2747 -16.2117 -47.5408 -0.396105 +VERTEX2 2748 -15.3021 -47.9956 -0.356049 +VERTEX2 2749 -14.3924 -48.3484 -0.388069 +VERTEX2 2750 -13.445 -48.6694 -0.377877 +VERTEX2 2751 -13.0307 -47.6515 1.21848 +VERTEX2 2752 -12.7047 -46.7542 1.21813 +VERTEX2 2753 -12.3148 -45.7457 1.2197 +VERTEX2 2754 -11.8852 -44.81 1.21972 +VERTEX2 2755 -11.5049 -43.8524 1.20932 +VERTEX2 2756 -12.3426 -43.5119 2.75327 +VERTEX2 2757 -13.3058 -43.1812 2.72148 +VERTEX2 2758 -14.1969 -42.738 2.71583 +VERTEX2 2759 -15.0525 -42.3579 2.69824 +VERTEX2 2760 -15.8249 -41.9627 2.68529 +VERTEX2 2761 -15.3919 -40.9845 1.11909 +VERTEX2 2762 -14.9419 -40.0517 1.12024 +VERTEX2 2763 -14.5139 -39.1142 1.11826 +VERTEX2 2764 -14.1066 -38.1923 1.13843 +VERTEX2 2765 -13.6643 -37.2608 1.15693 +VERTEX2 2766 -14.6502 -36.8331 2.69319 +VERTEX2 2767 -15.5288 -36.3611 2.70272 +VERTEX2 2768 -16.5283 -35.9277 2.7235 +VERTEX2 2769 -17.5553 -35.4737 2.68674 +VERTEX2 2770 -18.4509 -35.0542 2.65867 +VERTEX2 2771 -18.9758 -36.0164 -2.07243 +VERTEX2 2772 -19.4256 -36.9606 -2.05742 +VERTEX2 2773 -19.9622 -37.8479 -2.04533 +VERTEX2 2774 -20.4422 -38.7586 -2.04936 +VERTEX2 2775 -20.8487 -39.5947 -2.01794 +VERTEX2 2776 -19.8941 -40.0543 -0.44766 +VERTEX2 2777 -18.9525 -40.6139 -0.48371 +VERTEX2 2778 -18.1232 -41.0985 -0.490695 +VERTEX2 2779 -17.273 -41.6595 -0.502014 +VERTEX2 2780 -16.3951 -42.1209 -0.503078 +VERTEX2 2781 -15.942 -41.2803 1.08697 +VERTEX2 2782 -15.4405 -40.3834 1.09071 +VERTEX2 2783 -14.9173 -39.431 1.11059 +VERTEX2 2784 -14.4195 -38.5663 1.12837 +VERTEX2 2785 -14.0537 -37.6721 1.14486 +VERTEX2 2786 -13.2197 -38.0277 -0.431162 +VERTEX2 2787 -12.2501 -38.3429 -0.413892 +VERTEX2 2788 -11.3425 -38.7468 -0.399285 +VERTEX2 2789 -10.3831 -39.1453 -0.405403 +VERTEX2 2790 -9.47242 -39.5279 -0.408892 +VERTEX2 2791 -9.00384 -38.5621 1.12635 +VERTEX2 2792 -8.55766 -37.5854 1.11233 +VERTEX2 2793 -8.19206 -36.6531 1.12757 +VERTEX2 2794 -7.84855 -35.7634 1.12001 +VERTEX2 2795 -7.36983 -34.9048 1.12414 +VERTEX2 2796 -8.19268 -34.51 2.647 +VERTEX2 2797 -9.01833 -34.0265 2.62912 +VERTEX2 2798 -9.89652 -33.5341 2.593 +VERTEX2 2799 -10.7056 -33.0901 2.59153 +VERTEX2 2800 -11.6006 -32.5646 2.61292 +VERTEX2 2801 -12.1325 -33.4021 -2.08799 +VERTEX2 2802 -12.6975 -34.2679 -2.10236 +VERTEX2 2803 -13.2602 -35.1766 -2.09351 +VERTEX2 2804 -13.7975 -36.0526 -2.10839 +VERTEX2 2805 -14.3218 -36.9233 -2.1258 +VERTEX2 2806 -13.4483 -37.4872 -0.54242 +VERTEX2 2807 -12.5686 -38.0181 -0.547472 +VERTEX2 2808 -11.6836 -38.5052 -0.517194 +VERTEX2 2809 -10.7981 -39.1133 -0.49285 +VERTEX2 2810 -9.96589 -39.7 -0.485632 +VERTEX2 2811 -9.46133 -38.7988 1.08424 +VERTEX2 2812 -8.98675 -37.9395 1.10024 +VERTEX2 2813 -8.51415 -37.0579 1.13235 +VERTEX2 2814 -8.0854 -36.1765 1.12997 +VERTEX2 2815 -7.63846 -35.2818 1.06993 +VERTEX2 2816 -8.51232 -34.8418 2.58461 +VERTEX2 2817 -9.33375 -34.3041 2.59928 +VERTEX2 2818 -10.1841 -33.8515 2.61685 +VERTEX2 2819 -11.0461 -33.3913 2.61353 +VERTEX2 2820 -11.8786 -32.879 2.6209 +VERTEX2 2821 -11.3704 -31.9603 1.04345 +VERTEX2 2822 -10.8405 -31.0632 1.0718 +VERTEX2 2823 -10.3001 -30.1553 1.05044 +VERTEX2 2824 -9.87264 -29.2969 1.04452 +VERTEX2 2825 -9.32978 -28.3496 1.07696 +VERTEX2 2826 -10.3087 -27.8687 2.63978 +VERTEX2 2827 -11.2607 -27.4008 2.60738 +VERTEX2 2828 -12.1828 -26.8459 2.60036 +VERTEX2 2829 -13.0717 -26.3102 2.58649 +VERTEX2 2830 -13.8965 -25.8033 2.56936 +VERTEX2 2831 -14.4396 -26.6634 -2.10133 +VERTEX2 2832 -14.927 -27.52 -2.07808 +VERTEX2 2833 -15.4598 -28.3386 -2.09913 +VERTEX2 2834 -15.9532 -29.2309 -2.08913 +VERTEX2 2835 -16.4207 -30.1693 -2.08939 +VERTEX2 2836 -15.6017 -30.694 -0.547913 +VERTEX2 2837 -14.7882 -31.247 -0.547135 +VERTEX2 2838 -13.8276 -31.6968 -0.548037 +VERTEX2 2839 -12.9855 -32.2829 -0.539558 +VERTEX2 2840 -12.0891 -32.7565 -0.543648 +VERTEX2 2841 -12.5504 -33.6681 -2.10692 +VERTEX2 2842 -13.0603 -34.5298 -2.14022 +VERTEX2 2843 -13.6356 -35.4267 -2.15085 +VERTEX2 2844 -14.1828 -36.2071 -2.12461 +VERTEX2 2845 -14.6023 -37.0382 -2.14033 +VERTEX2 2846 -15.4404 -36.4183 2.5603 +VERTEX2 2847 -16.2035 -35.8765 2.59562 +VERTEX2 2848 -17.0783 -35.3311 2.62218 +VERTEX2 2849 -17.9036 -34.9216 2.62009 +VERTEX2 2850 -18.6716 -34.4158 2.64902 +VERTEX2 2851 -19.2373 -35.3173 -2.05159 +VERTEX2 2852 -19.7629 -36.1834 -2.07561 +VERTEX2 2853 -20.295 -37.0219 -2.08729 +VERTEX2 2854 -20.7719 -37.8428 -2.1076 +VERTEX2 2855 -21.2972 -38.7807 -2.10346 +VERTEX2 2856 -20.4316 -39.3212 -0.563636 +VERTEX2 2857 -19.6121 -39.8162 -0.590462 +VERTEX2 2858 -18.7547 -40.4003 -0.583574 +VERTEX2 2859 -17.9243 -40.9735 -0.549948 +VERTEX2 2860 -16.9402 -41.3892 -0.561515 +VERTEX2 2861 -17.4505 -42.2829 -2.09646 +VERTEX2 2862 -17.9621 -43.112 -2.08566 +VERTEX2 2863 -18.526 -44.0735 -2.09503 +VERTEX2 2864 -19.0736 -45.0047 -2.08363 +VERTEX2 2865 -19.5933 -45.8919 -2.10339 +VERTEX2 2866 -18.7058 -46.294 -0.560232 +VERTEX2 2867 -17.7671 -46.7814 -0.555401 +VERTEX2 2868 -16.976 -47.3055 -0.600293 +VERTEX2 2869 -16.2088 -47.8898 -0.596974 +VERTEX2 2870 -15.3713 -48.4501 -0.589764 +VERTEX2 2871 -14.8726 -47.5898 0.971941 +VERTEX2 2872 -14.2755 -46.8279 0.981412 +VERTEX2 2873 -13.7507 -46.1151 1.0109 +VERTEX2 2874 -13.2589 -45.3608 1.00549 +VERTEX2 2875 -12.7714 -44.437 1.00782 +VERTEX2 2876 -13.5987 -43.8573 2.57402 +VERTEX2 2877 -14.4272 -43.3102 2.59091 +VERTEX2 2878 -15.1792 -42.8382 2.60641 +VERTEX2 2879 -16.037 -42.3699 2.60057 +VERTEX2 2880 -16.9673 -41.818 2.62547 +VERTEX2 2881 -17.4771 -42.6754 -2.07564 +VERTEX2 2882 -17.9132 -43.5648 -2.08394 +VERTEX2 2883 -18.3798 -44.3486 -2.09708 +VERTEX2 2884 -18.9139 -45.1395 -2.08617 +VERTEX2 2885 -19.3338 -46.0442 -2.11983 +VERTEX2 2886 -18.3099 -46.5148 -0.579694 +VERTEX2 2887 -17.5143 -47.0774 -0.580585 +VERTEX2 2888 -16.6376 -47.6341 -0.571391 +VERTEX2 2889 -15.8098 -48.179 -0.542218 +VERTEX2 2890 -14.9257 -48.6465 -0.524414 +VERTEX2 2891 -15.4518 -49.5229 -2.10206 +VERTEX2 2892 -15.9513 -50.4021 -2.10846 +VERTEX2 2893 -16.5156 -51.2364 -2.07595 +VERTEX2 2894 -17.0032 -52.0913 -2.0482 +VERTEX2 2895 -17.4216 -52.9832 -2.01853 +VERTEX2 2896 -16.4599 -53.3903 -0.464055 +VERTEX2 2897 -15.6257 -53.8473 -0.500543 +VERTEX2 2898 -14.8067 -54.4 -0.457741 +VERTEX2 2899 -13.8106 -54.8992 -0.447225 +VERTEX2 2900 -12.8767 -55.4054 -0.45621 +VERTEX2 2901 -12.4499 -54.4975 1.13101 +VERTEX2 2902 -12.0409 -53.5444 1.14 +VERTEX2 2903 -11.5313 -52.6763 1.11054 +VERTEX2 2904 -11.0504 -51.7974 1.1103 +VERTEX2 2905 -10.6138 -50.9608 1.15274 +VERTEX2 2906 -9.67524 -51.3668 -0.407568 +VERTEX2 2907 -8.82028 -51.8208 -0.435599 +VERTEX2 2908 -7.93593 -52.2294 -0.467912 +VERTEX2 2909 -7.01943 -52.6859 -0.475681 +VERTEX2 2910 -6.18984 -53.0876 -0.497638 +VERTEX2 2911 -5.76569 -52.1687 1.12654 +VERTEX2 2912 -5.38265 -51.3065 1.11279 +VERTEX2 2913 -4.9448 -50.4061 1.07604 +VERTEX2 2914 -4.48191 -49.5403 1.06928 +VERTEX2 2915 -3.93707 -48.6624 1.06929 +VERTEX2 2916 -4.78151 -48.2852 2.6308 +VERTEX2 2917 -5.56239 -47.7985 2.65777 +VERTEX2 2918 -6.50971 -47.3409 2.64266 +VERTEX2 2919 -7.40246 -46.9535 2.64894 +VERTEX2 2920 -8.29168 -46.4751 2.64919 +VERTEX2 2921 -8.7822 -47.3049 -2.08451 +VERTEX2 2922 -9.35829 -48.1045 -2.0851 +VERTEX2 2923 -9.82392 -48.9884 -2.099 +VERTEX2 2924 -10.3061 -49.7909 -2.0727 +VERTEX2 2925 -10.7881 -50.7096 -2.06642 +VERTEX2 2926 -11.615 -50.1368 2.63086 +VERTEX2 2927 -12.5119 -49.6317 2.61999 +VERTEX2 2928 -13.3992 -49.0904 2.61763 +VERTEX2 2929 -14.2755 -48.5216 2.59164 +VERTEX2 2930 -15.1581 -47.9799 2.57516 +VERTEX2 2931 -15.57 -48.7904 -2.1603 +VERTEX2 2932 -16.123 -49.566 -2.17813 +VERTEX2 2933 -16.7234 -50.3688 -2.18366 +VERTEX2 2934 -17.3287 -51.1357 -2.18991 +VERTEX2 2935 -17.9015 -51.9854 -2.21984 +VERTEX2 2936 -17.1286 -52.6775 -0.648309 +VERTEX2 2937 -16.2315 -53.3151 -0.626341 +VERTEX2 2938 -15.4279 -53.9321 -0.613473 +VERTEX2 2939 -14.5283 -54.4835 -0.633401 +VERTEX2 2940 -13.6371 -55.0509 -0.613156 +VERTEX2 2941 -13.1444 -54.2499 0.950969 +VERTEX2 2942 -12.502 -53.4135 0.947186 +VERTEX2 2943 -11.836 -52.6034 0.936511 +VERTEX2 2944 -11.1493 -51.789 0.892796 +VERTEX2 2945 -10.5661 -51.1869 0.886057 +VERTEX2 2946 -11.3536 -50.4927 2.46297 +VERTEX2 2947 -12.1024 -49.8785 2.46994 +VERTEX2 2948 -12.9769 -49.2409 2.47783 +VERTEX2 2949 -13.8254 -48.6827 2.47727 +VERTEX2 2950 -14.6011 -48.116 2.4882 +VERTEX2 2951 -13.8918 -47.3925 0.916217 +VERTEX2 2952 -13.3599 -46.5148 0.896132 +VERTEX2 2953 -12.7069 -45.7356 0.91466 +VERTEX2 2954 -12.0618 -44.9053 0.914272 +VERTEX2 2955 -11.4972 -44.0934 0.927937 +VERTEX2 2956 -12.2314 -43.4843 2.49062 +VERTEX2 2957 -12.9299 -42.9327 2.47768 +VERTEX2 2958 -13.7813 -42.2914 2.44872 +VERTEX2 2959 -14.5551 -41.6801 2.45589 +VERTEX2 2960 -15.3189 -41.1437 2.45425 +VERTEX2 2961 -15.8891 -41.8977 -2.2934 +VERTEX2 2962 -16.509 -42.6174 -2.30341 +VERTEX2 2963 -17.1698 -43.4099 -2.29876 +VERTEX2 2964 -17.8296 -44.1723 -2.29126 +VERTEX2 2965 -18.5023 -44.9691 -2.27897 +VERTEX2 2966 -19.2733 -44.3108 2.45186 +VERTEX2 2967 -20.0994 -43.5932 2.44675 +VERTEX2 2968 -20.9418 -42.9371 2.41812 +VERTEX2 2969 -21.6409 -42.3125 2.41158 +VERTEX2 2970 -22.3726 -41.68 2.39635 +VERTEX2 2971 -21.8044 -40.9145 0.818375 +VERTEX2 2972 -21.1529 -40.1643 0.801654 +VERTEX2 2973 -20.3897 -39.4411 0.763369 +VERTEX2 2974 -19.6448 -38.6641 0.74845 +VERTEX2 2975 -18.8929 -37.9462 0.755358 +VERTEX2 2976 -19.5809 -37.1468 2.33072 +VERTEX2 2977 -20.3402 -36.4783 2.35982 +VERTEX2 2978 -21.069 -35.7544 2.33622 +VERTEX2 2979 -21.6935 -34.9637 2.32539 +VERTEX2 2980 -22.3082 -34.1754 2.32529 +VERTEX2 2981 -21.5618 -33.5843 0.740005 +VERTEX2 2982 -20.7859 -32.9032 0.736726 +VERTEX2 2983 -20.0365 -32.1847 0.716998 +VERTEX2 2984 -19.2582 -31.5418 0.717721 +VERTEX2 2985 -18.5055 -30.9612 0.740479 +VERTEX2 2986 -19.0947 -30.1827 2.30833 +VERTEX2 2987 -19.7557 -29.547 2.31076 +VERTEX2 2988 -20.356 -28.8128 2.29521 +VERTEX2 2989 -20.9934 -28.1337 2.28454 +VERTEX2 2990 -21.6472 -27.4156 2.26719 +VERTEX2 2991 -22.3561 -28.0443 -2.39666 +VERTEX2 2992 -23.092 -28.7186 -2.42085 +VERTEX2 2993 -23.8699 -29.3098 -2.4349 +VERTEX2 2994 -24.6479 -29.9718 -2.43987 +VERTEX2 2995 -25.3535 -30.63 -2.44865 +VERTEX2 2996 -24.7219 -31.4043 -0.865583 +VERTEX2 2997 -24.1074 -32.1396 -0.818497 +VERTEX2 2998 -23.4882 -32.9184 -0.82693 +VERTEX2 2999 -22.8453 -33.6667 -0.802909 +VERTEX2 3000 -22.0588 -34.4285 -0.780887 +VERTEX2 3001 -22.8692 -35.0764 -2.35161 +VERTEX2 3002 -23.6305 -35.7631 -2.34271 +VERTEX2 3003 -24.3 -36.4938 -2.29908 +VERTEX2 3004 -25.048 -37.2423 -2.31012 +VERTEX2 3005 -25.7236 -38.069 -2.32393 +VERTEX2 3006 -24.9533 -38.7115 -0.784098 +VERTEX2 3007 -24.2847 -39.4937 -0.750434 +VERTEX2 3008 -23.5825 -40.2378 -0.766631 +VERTEX2 3009 -22.8395 -40.957 -0.759088 +VERTEX2 3010 -22.0231 -41.5906 -0.793118 +VERTEX2 3011 -22.8199 -42.2844 -2.39466 +VERTEX2 3012 -23.5841 -42.9609 -2.40444 +VERTEX2 3013 -24.3151 -43.6012 -2.41025 +VERTEX2 3014 -25.0562 -44.1497 -2.41625 +VERTEX2 3015 -25.7728 -44.775 -2.42222 +VERTEX2 3016 -26.5017 -44.1103 2.31559 +VERTEX2 3017 -27.1492 -43.3612 2.32182 +VERTEX2 3018 -27.917 -42.6186 2.22664 +VERTEX2 3019 -28.6179 -41.7215 2.21911 +VERTEX2 3020 -29.2598 -40.9673 2.21657 +VERTEX2 3021 -30.0509 -41.6163 -2.51534 +VERTEX2 3022 -30.9178 -42.172 -2.55063 +VERTEX2 3023 -31.7269 -42.8365 -2.53303 +VERTEX2 3024 -32.5272 -43.5409 -2.5481 +VERTEX2 3025 -33.2919 -44.131 -2.55268 +VERTEX2 3026 -33.8597 -43.2816 2.16897 +VERTEX2 3027 -34.4778 -42.464 2.17806 +VERTEX2 3028 -35.1008 -41.6205 2.17464 +VERTEX2 3029 -35.6483 -40.7593 2.20449 +VERTEX2 3030 -36.3133 -39.927 2.22323 +VERTEX2 3031 -37.0836 -40.5492 -2.50432 +VERTEX2 3032 -37.8472 -41.0856 -2.49308 +VERTEX2 3033 -38.633 -41.6634 -2.47639 +VERTEX2 3034 -39.3572 -42.2777 -2.48224 +VERTEX2 3035 -40.1965 -42.8762 -2.463 +VERTEX2 3036 -39.4713 -43.6648 -0.900686 +VERTEX2 3037 -38.8841 -44.451 -0.919767 +VERTEX2 3038 -38.2929 -45.2029 -0.906573 +VERTEX2 3039 -37.4998 -46.0215 -0.909308 +VERTEX2 3040 -36.9126 -46.8608 -0.92324 +VERTEX2 3041 -36.0822 -46.3066 0.615279 +VERTEX2 3042 -35.3291 -45.7347 0.6259 +VERTEX2 3043 -34.5502 -45.2153 0.596301 +VERTEX2 3044 -33.7418 -44.7395 0.587871 +VERTEX2 3045 -32.9105 -44.1913 0.59495 +VERTEX2 3046 -33.4942 -43.398 2.13865 +VERTEX2 3047 -34.062 -42.5567 2.13146 +VERTEX2 3048 -34.6029 -41.7075 2.11685 +VERTEX2 3049 -35.1098 -40.8901 2.10202 +VERTEX2 3050 -35.6059 -39.9908 2.08872 +VERTEX2 3051 -36.5208 -40.5492 -2.60385 +VERTEX2 3052 -37.4022 -41.0575 -2.61552 +VERTEX2 3053 -38.2836 -41.5095 -2.61255 +VERTEX2 3054 -39.14 -41.9884 -2.60291 +VERTEX2 3055 -40.06 -42.464 -2.58753 +VERTEX2 3056 -40.6184 -41.5739 2.14611 +VERTEX2 3057 -41.1297 -40.6519 2.12424 +VERTEX2 3058 -41.6578 -39.8365 2.12804 +VERTEX2 3059 -42.1498 -39.1148 2.10892 +VERTEX2 3060 -42.6602 -38.2722 2.12632 +VERTEX2 3061 -41.7885 -37.7348 0.56346 +VERTEX2 3062 -41.0222 -37.1912 0.546774 +VERTEX2 3063 -40.1803 -36.7134 0.538004 +VERTEX2 3064 -39.251 -36.1502 0.547315 +VERTEX2 3065 -38.3826 -35.6443 0.538066 +VERTEX2 3066 -38.819 -34.918 2.13981 +VERTEX2 3067 -39.3469 -34.0315 2.14865 +VERTEX2 3068 -39.9409 -33.1405 2.15203 +VERTEX2 3069 -40.4856 -32.2196 2.16017 +VERTEX2 3070 -41.0148 -31.452 2.15055 +VERTEX2 3071 -41.888 -31.9782 -2.55482 +VERTEX2 3072 -42.7751 -32.5084 -2.54844 +VERTEX2 3073 -43.5742 -33.0178 -2.54241 +VERTEX2 3074 -44.3311 -33.5593 -2.5243 +VERTEX2 3075 -45.1031 -34.1968 -2.51756 +VERTEX2 3076 -44.5376 -35.0396 -0.91238 +VERTEX2 3077 -44.0082 -35.7736 -0.935902 +VERTEX2 3078 -43.3909 -36.5504 -0.963174 +VERTEX2 3079 -42.7627 -37.4391 -0.953475 +VERTEX2 3080 -42.137 -38.2343 -0.948785 +VERTEX2 3081 -41.2774 -37.6348 0.636727 +VERTEX2 3082 -40.4316 -37.0324 0.627797 +VERTEX2 3083 -39.6821 -36.3832 0.637235 +VERTEX2 3084 -38.8724 -35.7136 0.632375 +VERTEX2 3085 -38.0913 -35.0979 0.618928 +VERTEX2 3086 -37.5273 -35.9416 -0.948382 +VERTEX2 3087 -36.9238 -36.7913 -0.972878 +VERTEX2 3088 -36.3786 -37.6533 -0.948408 +VERTEX2 3089 -35.8456 -38.5087 -0.956107 +VERTEX2 3090 -35.2872 -39.3517 -0.966738 +VERTEX2 3091 -34.3769 -38.7069 0.623481 +VERTEX2 3092 -33.5119 -38.0102 0.627482 +VERTEX2 3093 -32.6671 -37.4857 0.62422 +VERTEX2 3094 -31.8998 -36.9107 0.605798 +VERTEX2 3095 -31.1601 -36.362 0.609098 +VERTEX2 3096 -31.7607 -35.5335 2.20613 +VERTEX2 3097 -32.3727 -34.7732 2.18114 +VERTEX2 3098 -32.9353 -34.0377 2.14911 +VERTEX2 3099 -33.408 -33.2104 2.15881 +VERTEX2 3100 -34.0367 -32.3543 2.16281 +VERTEX2 3101 -34.8425 -32.8817 -2.56332 +VERTEX2 3102 -35.8069 -33.3701 -2.57927 +VERTEX2 3103 -36.6654 -33.851 -2.57985 +VERTEX2 3104 -37.4283 -34.376 -2.579 +VERTEX2 3105 -38.3799 -35.025 -2.6173 +VERTEX2 3106 -37.9263 -35.9395 -1.07337 +VERTEX2 3107 -37.4415 -36.8088 -1.04993 +VERTEX2 3108 -36.9927 -37.6488 -1.02898 +VERTEX2 3109 -36.4496 -38.5393 -0.998291 +VERTEX2 3110 -35.8209 -39.3731 -0.979385 +VERTEX2 3111 -34.9817 -38.7452 0.633569 +VERTEX2 3112 -34.1258 -38.1803 0.638656 +VERTEX2 3113 -33.3473 -37.5713 0.609397 +VERTEX2 3114 -32.5973 -36.9879 0.616801 +VERTEX2 3115 -31.7884 -36.4205 0.600285 +VERTEX2 3116 -32.3061 -35.595 2.15014 +VERTEX2 3117 -32.7246 -34.7489 2.15388 +VERTEX2 3118 -33.2944 -33.8911 2.16313 +VERTEX2 3119 -33.9245 -33.065 2.17388 +VERTEX2 3120 -34.5004 -32.1955 2.21501 +VERTEX2 3121 -35.3227 -32.8342 -2.55308 +VERTEX2 3122 -36.1921 -33.4151 -2.53031 +VERTEX2 3123 -37.0183 -33.8957 -2.52599 +VERTEX2 3124 -37.862 -34.4259 -2.56594 +VERTEX2 3125 -38.6841 -34.8363 -2.55967 +VERTEX2 3126 -38.1431 -35.6342 -0.974434 +VERTEX2 3127 -37.5806 -36.4239 -0.953324 +VERTEX2 3128 -36.9774 -37.2735 -0.951489 +VERTEX2 3129 -36.4612 -37.9916 -0.923694 +VERTEX2 3130 -35.8563 -38.7838 -0.906454 +VERTEX2 3131 -35.1071 -38.1398 0.676924 +VERTEX2 3132 -34.3528 -37.535 0.647965 +VERTEX2 3133 -33.5758 -36.8596 0.638478 +VERTEX2 3134 -32.8081 -36.3184 0.645615 +VERTEX2 3135 -31.9729 -35.784 0.646626 +VERTEX2 3136 -32.6012 -35.0075 2.22424 +VERTEX2 3137 -33.2163 -34.1776 2.19726 +VERTEX2 3138 -33.8343 -33.3073 2.23088 +VERTEX2 3139 -34.5068 -32.5803 2.21074 +VERTEX2 3140 -35.0617 -31.8393 2.19529 +VERTEX2 3141 -35.8239 -32.4935 -2.50763 +VERTEX2 3142 -36.6172 -33.0881 -2.51121 +VERTEX2 3143 -37.4694 -33.7423 -2.49767 +VERTEX2 3144 -38.3593 -34.397 -2.49967 +VERTEX2 3145 -39.13 -34.9852 -2.49403 +VERTEX2 3146 -39.7525 -34.2347 2.22456 +VERTEX2 3147 -40.3202 -33.3507 2.23639 +VERTEX2 3148 -40.9386 -32.4925 2.22582 +VERTEX2 3149 -41.492 -31.6676 2.2397 +VERTEX2 3150 -42.107 -30.873 2.23323 +VERTEX2 3151 -42.9631 -31.5054 -2.47453 +VERTEX2 3152 -43.7568 -32.1241 -2.44627 +VERTEX2 3153 -44.5098 -32.6537 -2.4234 +VERTEX2 3154 -45.2223 -33.3121 -2.40659 +VERTEX2 3155 -45.9711 -33.9434 -2.4194 +VERTEX2 3156 -45.3296 -34.7285 -0.848681 +VERTEX2 3157 -44.6314 -35.4763 -0.84216 +VERTEX2 3158 -43.9605 -36.1745 -0.853905 +VERTEX2 3159 -43.3439 -36.8749 -0.84289 +VERTEX2 3160 -42.6056 -37.6794 -0.860842 +VERTEX2 3161 -41.8723 -37.1105 0.745135 +VERTEX2 3162 -41.1261 -36.3679 0.764883 +VERTEX2 3163 -40.4175 -35.6774 0.773105 +VERTEX2 3164 -39.6093 -34.9596 0.75295 +VERTEX2 3165 -38.9105 -34.2061 0.742011 +VERTEX2 3166 -38.2741 -34.9727 -0.845552 +VERTEX2 3167 -37.6231 -35.7488 -0.836643 +VERTEX2 3168 -36.9722 -36.5054 -0.848792 +VERTEX2 3169 -36.3407 -37.2956 -0.858397 +VERTEX2 3170 -35.6733 -38.1023 -0.881387 +VERTEX2 3171 -34.871 -37.4155 0.704852 +VERTEX2 3172 -34.0989 -36.7587 0.697499 +VERTEX2 3173 -33.2613 -36.1041 0.675136 +VERTEX2 3174 -32.4305 -35.5358 0.677451 +VERTEX2 3175 -31.648 -34.9173 0.678384 +VERTEX2 3176 -31.0653 -35.7046 -0.924754 +VERTEX2 3177 -30.4709 -36.4325 -0.93365 +VERTEX2 3178 -29.8986 -37.2862 -0.916638 +VERTEX2 3179 -29.2741 -37.9844 -0.8902 +VERTEX2 3180 -28.616 -38.7911 -0.92877 +VERTEX2 3181 -27.8933 -38.1852 0.660684 +VERTEX2 3182 -27.1459 -37.583 0.645166 +VERTEX2 3183 -26.2806 -37.0629 0.668061 +VERTEX2 3184 -25.5026 -36.4162 0.670448 +VERTEX2 3185 -24.763 -35.7238 0.656008 +VERTEX2 3186 -25.2656 -34.908 2.22413 +VERTEX2 3187 -25.8578 -34.1087 2.2577 +VERTEX2 3188 -26.4487 -33.2878 2.26341 +VERTEX2 3189 -27.1252 -32.4845 2.25624 +VERTEX2 3190 -27.8172 -31.8087 2.24745 +VERTEX2 3191 -27.0598 -31.2289 0.658198 +VERTEX2 3192 -26.2987 -30.5701 0.621981 +VERTEX2 3193 -25.4837 -29.8815 0.679671 +VERTEX2 3194 -24.6765 -29.2899 0.712244 +VERTEX2 3195 -23.968 -28.6296 0.729297 +VERTEX2 3196 -24.7104 -27.9969 2.31263 +VERTEX2 3197 -25.3597 -27.2955 2.32108 +VERTEX2 3198 -26.0435 -26.5913 2.36615 +VERTEX2 3199 -26.7149 -25.9001 2.35993 +VERTEX2 3200 -27.4784 -25.2331 2.39516 +VERTEX2 3201 -28.1657 -25.995 -2.30351 +VERTEX2 3202 -28.9521 -26.7799 -2.35827 +VERTEX2 3203 -29.6467 -27.4882 -2.33904 +VERTEX2 3204 -30.3537 -28.1969 -2.33993 +VERTEX2 3205 -31.034 -28.9224 -2.3029 +VERTEX2 3206 -30.2792 -29.6108 -0.698967 +VERTEX2 3207 -29.5514 -30.2953 -0.677585 +VERTEX2 3208 -28.7559 -30.8549 -0.691351 +VERTEX2 3209 -28.0415 -31.4511 -0.69625 +VERTEX2 3210 -27.2789 -32.079 -0.71834 +VERTEX2 3211 -26.6234 -31.3791 0.85186 +VERTEX2 3212 -25.9102 -30.5869 0.868106 +VERTEX2 3213 -25.1811 -29.8467 0.859066 +VERTEX2 3214 -24.522 -29.0614 0.862275 +VERTEX2 3215 -23.8712 -28.3237 0.879383 +VERTEX2 3216 -24.6723 -27.6734 2.44498 +VERTEX2 3217 -25.4047 -26.9811 2.4132 +VERTEX2 3218 -26.1628 -26.2334 2.42133 +VERTEX2 3219 -26.8679 -25.5364 2.40751 +VERTEX2 3220 -27.5789 -24.8061 2.42346 +VERTEX2 3221 -28.2725 -25.5299 -2.24888 +VERTEX2 3222 -28.8571 -26.2757 -2.25986 +VERTEX2 3223 -29.4991 -27.0055 -2.23933 +VERTEX2 3224 -30.0706 -27.8171 -2.25229 +VERTEX2 3225 -30.749 -28.4689 -2.23464 +VERTEX2 3226 -29.9379 -29.1417 -0.683048 +VERTEX2 3227 -29.2097 -29.8001 -0.678036 +VERTEX2 3228 -28.4744 -30.3664 -0.693831 +VERTEX2 3229 -27.651 -31.0986 -0.677988 +VERTEX2 3230 -26.8578 -31.6696 -0.700298 +VERTEX2 3231 -26.1934 -30.9214 0.861185 +VERTEX2 3232 -25.5637 -30.1687 0.861242 +VERTEX2 3233 -24.8682 -29.5003 0.838461 +VERTEX2 3234 -24.1659 -28.7436 0.854245 +VERTEX2 3235 -23.5014 -27.9966 0.838183 +VERTEX2 3236 -22.7307 -28.6127 -0.765355 +VERTEX2 3237 -22.0013 -29.2093 -0.763768 +VERTEX2 3238 -21.2957 -30.0023 -0.761024 +VERTEX2 3239 -20.5967 -30.6715 -0.755088 +VERTEX2 3240 -19.8717 -31.3132 -0.747084 +VERTEX2 3241 -19.3035 -30.4984 0.775386 +VERTEX2 3242 -18.4877 -29.7705 0.739188 +VERTEX2 3243 -17.7817 -29.1477 0.755286 +VERTEX2 3244 -17.0542 -28.4756 0.751336 +VERTEX2 3245 -16.2692 -27.7731 0.762471 +VERTEX2 3246 -16.9636 -27.1113 2.32367 +VERTEX2 3247 -17.6283 -26.38 2.32584 +VERTEX2 3248 -18.3534 -25.633 2.34384 +VERTEX2 3249 -19.0794 -24.9021 2.32761 +VERTEX2 3250 -19.7731 -24.144 2.33675 +VERTEX2 3251 -20.5401 -24.7472 -2.3603 +VERTEX2 3252 -21.1354 -25.4428 -2.37927 +VERTEX2 3253 -22.0075 -26.1437 -2.38545 +VERTEX2 3254 -22.77 -26.8794 -2.40122 +VERTEX2 3255 -23.5213 -27.5646 -2.40551 +VERTEX2 3256 -22.8458 -28.3092 -0.81064 +VERTEX2 3257 -22.1409 -29.0258 -0.836625 +VERTEX2 3258 -21.4925 -29.7232 -0.799573 +VERTEX2 3259 -20.7924 -30.4844 -0.808 +VERTEX2 3260 -20.1387 -31.2898 -0.849119 +VERTEX2 3261 -20.827 -31.921 -2.42816 +VERTEX2 3262 -21.6286 -32.5595 -2.44259 +VERTEX2 3263 -22.2721 -33.1882 -2.46923 +VERTEX2 3264 -23.0623 -33.7822 -2.48135 +VERTEX2 3265 -23.8832 -34.4115 -2.5193 +VERTEX2 3266 -23.3558 -35.17 -0.968726 +VERTEX2 3267 -22.8026 -35.9866 -0.963983 +VERTEX2 3268 -22.2324 -36.8648 -0.909305 +VERTEX2 3269 -21.6172 -37.6045 -0.898894 +VERTEX2 3270 -20.9601 -38.3168 -0.906137 +VERTEX2 3271 -20.2343 -37.7023 0.664923 +VERTEX2 3272 -19.4414 -37.0826 0.69231 +VERTEX2 3273 -18.646 -36.4788 0.707477 +VERTEX2 3274 -17.8809 -35.8093 0.705924 +VERTEX2 3275 -17.0956 -35.1496 0.705123 +VERTEX2 3276 -17.7399 -34.36 2.28304 +VERTEX2 3277 -18.3623 -33.6433 2.2846 +VERTEX2 3278 -19.0419 -32.9342 2.28016 +VERTEX2 3279 -19.743 -32.1681 2.29648 +VERTEX2 3280 -20.4533 -31.3391 2.31 +VERTEX2 3281 -21.2096 -32.0738 -2.40781 +VERTEX2 3282 -21.9788 -32.7615 -2.41174 +VERTEX2 3283 -22.6766 -33.4501 -2.40066 +VERTEX2 3284 -23.4049 -34.1549 -2.40602 +VERTEX2 3285 -24.2045 -34.7762 -2.365 +VERTEX2 3286 -23.5159 -35.5748 -0.749741 +VERTEX2 3287 -22.7611 -36.2541 -0.755739 +VERTEX2 3288 -22.1086 -36.9365 -0.799153 +VERTEX2 3289 -21.4456 -37.6161 -0.795331 +VERTEX2 3290 -20.7344 -38.2697 -0.819607 +VERTEX2 3291 -20.035 -37.5421 0.722556 +VERTEX2 3292 -19.3153 -36.862 0.700014 +VERTEX2 3293 -18.4336 -36.239 0.707114 +VERTEX2 3294 -17.7482 -35.5887 0.692952 +VERTEX2 3295 -16.9208 -34.9598 0.688099 +VERTEX2 3296 -17.497 -34.1771 2.26955 +VERTEX2 3297 -18.1681 -33.4124 2.26564 +VERTEX2 3298 -18.873 -32.5927 2.25174 +VERTEX2 3299 -19.4539 -31.8683 2.2829 +VERTEX2 3300 -20.1174 -31.1274 2.29611 +VERTEX2 3301 -19.3628 -30.425 0.76482 +VERTEX2 3302 -18.6393 -29.7646 0.755035 +VERTEX2 3303 -17.9916 -29.0364 0.731377 +VERTEX2 3304 -17.202 -28.3951 0.759366 +VERTEX2 3305 -16.4469 -27.6866 0.7446 +VERTEX2 3306 -17.1749 -26.8612 2.36394 +VERTEX2 3307 -17.9211 -26.153 2.38772 +VERTEX2 3308 -18.6425 -25.5196 2.41524 +VERTEX2 3309 -19.4166 -24.9462 2.4105 +VERTEX2 3310 -20.0867 -24.2524 2.40222 +VERTEX2 3311 -19.4213 -23.465 0.849383 +VERTEX2 3312 -18.8028 -22.6091 0.866433 +VERTEX2 3313 -18.2734 -21.9601 0.884437 +VERTEX2 3314 -17.5737 -21.2954 0.899373 +VERTEX2 3315 -16.9942 -20.4941 0.866239 +VERTEX2 3316 -17.6527 -19.8772 2.45771 +VERTEX2 3317 -18.3647 -19.2831 2.42643 +VERTEX2 3318 -19.1994 -18.5623 2.45427 +VERTEX2 3319 -19.957 -17.8781 2.45317 +VERTEX2 3320 -20.757 -17.2062 2.49261 +VERTEX2 3321 -21.3545 -17.9781 -2.22785 +VERTEX2 3322 -21.9812 -18.7723 -2.23591 +VERTEX2 3323 -22.5798 -19.5727 -2.18967 +VERTEX2 3324 -23.1881 -20.4245 -2.16494 +VERTEX2 3325 -23.6732 -21.2413 -2.14631 +VERTEX2 3326 -24.4609 -20.6872 2.5782 +VERTEX2 3327 -25.3559 -20.1879 2.57273 +VERTEX2 3328 -26.1735 -19.6623 2.57952 +VERTEX2 3329 -26.9721 -19.1386 2.60854 +VERTEX2 3330 -27.9074 -18.7655 2.62467 +VERTEX2 3331 -28.3865 -19.6181 -2.07807 +VERTEX2 3332 -28.8085 -20.5733 -2.07559 +VERTEX2 3333 -29.3529 -21.3734 -2.12258 +VERTEX2 3334 -29.9317 -22.2287 -2.15031 +VERTEX2 3335 -30.4618 -23.1345 -2.11263 +VERTEX2 3336 -29.605 -23.6243 -0.537053 +VERTEX2 3337 -28.7514 -24.1715 -0.547308 +VERTEX2 3338 -27.9227 -24.6529 -0.571046 +VERTEX2 3339 -27.0326 -25.1552 -0.579911 +VERTEX2 3340 -26.1637 -25.6818 -0.562082 +VERTEX2 3341 -25.7031 -24.8684 1.00929 +VERTEX2 3342 -25.0915 -24.0717 0.964733 +VERTEX2 3343 -24.5378 -23.0902 0.945094 +VERTEX2 3344 -23.9507 -22.2853 0.927192 +VERTEX2 3345 -23.3968 -21.4474 0.960168 +VERTEX2 3346 -24.1711 -20.8668 2.53617 +VERTEX2 3347 -24.9825 -20.2381 2.52172 +VERTEX2 3348 -25.7688 -19.6113 2.53326 +VERTEX2 3349 -26.5946 -19.101 2.50838 +VERTEX2 3350 -27.3591 -18.411 2.49599 +VERTEX2 3351 -27.9484 -19.1885 -2.19805 +VERTEX2 3352 -28.4895 -20.0883 -2.24264 +VERTEX2 3353 -29.1032 -20.868 -2.2472 +VERTEX2 3354 -29.7169 -21.6428 -2.22847 +VERTEX2 3355 -30.3433 -22.4778 -2.22651 +VERTEX2 3356 -29.499 -23.1418 -0.69337 +VERTEX2 3357 -28.7228 -23.7907 -0.701177 +VERTEX2 3358 -27.9165 -24.4173 -0.739212 +VERTEX2 3359 -27.2477 -25.0795 -0.768568 +VERTEX2 3360 -26.4751 -25.7699 -0.801348 +VERTEX2 3361 -27.2193 -26.485 -2.37177 +VERTEX2 3362 -27.9053 -27.183 -2.34487 +VERTEX2 3363 -28.6187 -27.9012 -2.34916 +VERTEX2 3364 -29.2732 -28.4909 -2.35594 +VERTEX2 3365 -29.9613 -29.1547 -2.38305 +VERTEX2 3366 -29.2443 -29.8762 -0.809506 +VERTEX2 3367 -28.5667 -30.6184 -0.797388 +VERTEX2 3368 -27.8873 -31.3654 -0.75821 +VERTEX2 3369 -27.0895 -32.0357 -0.790594 +VERTEX2 3370 -26.3837 -32.7519 -0.7835 +VERTEX2 3371 -27.0379 -33.4485 -2.35153 +VERTEX2 3372 -27.7147 -34.1306 -2.34641 +VERTEX2 3373 -28.479 -34.8094 -2.36429 +VERTEX2 3374 -29.2237 -35.4669 -2.30921 +VERTEX2 3375 -29.8945 -36.1357 -2.27985 +VERTEX2 3376 -30.5697 -35.4926 2.41319 +VERTEX2 3377 -31.3583 -34.755 2.40652 +VERTEX2 3378 -32.003 -34.118 2.41713 +VERTEX2 3379 -32.7357 -33.3973 2.41639 +VERTEX2 3380 -33.4822 -32.5952 2.39529 +VERTEX2 3381 -34.1756 -33.2785 -2.31585 +VERTEX2 3382 -34.8506 -34.0314 -2.30342 +VERTEX2 3383 -35.5405 -34.8447 -2.28709 +VERTEX2 3384 -36.1165 -35.6343 -2.29434 +VERTEX2 3385 -36.7832 -36.1816 -2.28301 +VERTEX2 3386 -37.5381 -35.4767 2.43986 +VERTEX2 3387 -38.33 -34.7912 2.4277 +VERTEX2 3388 -39.0731 -34.2294 2.44723 +VERTEX2 3389 -39.7666 -33.62 2.41835 +VERTEX2 3390 -40.4525 -32.9733 2.42841 +VERTEX2 3391 -39.7667 -32.166 0.814477 +VERTEX2 3392 -39.089 -31.4541 0.7917 +VERTEX2 3393 -38.3506 -30.7286 0.776895 +VERTEX2 3394 -37.6604 -30.0491 0.768927 +VERTEX2 3395 -36.9114 -29.406 0.74592 +VERTEX2 3396 -37.5673 -28.7153 2.31318 +VERTEX2 3397 -38.2886 -28.0361 2.33636 +VERTEX2 3398 -39.0274 -27.3615 2.35091 +VERTEX2 3399 -39.7462 -26.5256 2.33636 +VERTEX2 3400 -40.5469 -25.7683 2.32208 +VERTEX2 3401 -41.2476 -26.4669 -2.38296 +VERTEX2 3402 -41.9837 -27.156 -2.40357 +VERTEX2 3403 -42.6347 -27.8143 -2.40258 +VERTEX2 3404 -43.4975 -28.523 -2.40648 +VERTEX2 3405 -44.2297 -29.2297 -2.37475 +VERTEX2 3406 -43.3955 -29.8992 -0.816952 +VERTEX2 3407 -42.6392 -30.633 -0.799875 +VERTEX2 3408 -41.8432 -31.2846 -0.78677 +VERTEX2 3409 -41.1504 -32.0515 -0.784428 +VERTEX2 3410 -40.4395 -32.7594 -0.797671 +VERTEX2 3411 -39.7296 -32.1434 0.786507 +VERTEX2 3412 -39.0368 -31.4823 0.760096 +VERTEX2 3413 -38.3643 -30.7169 0.760428 +VERTEX2 3414 -37.5978 -30.0769 0.772823 +VERTEX2 3415 -36.9107 -29.3343 0.772118 +VERTEX2 3416 -36.2056 -30.0539 -0.857863 +VERTEX2 3417 -35.5538 -30.8236 -0.837387 +VERTEX2 3418 -34.8776 -31.5909 -0.834493 +VERTEX2 3419 -34.237 -32.4112 -0.843917 +VERTEX2 3420 -33.5212 -33.1281 -0.866362 +VERTEX2 3421 -32.799 -32.4117 0.698661 +VERTEX2 3422 -32.0681 -31.7862 0.70358 +VERTEX2 3423 -31.2835 -31.2012 0.682445 +VERTEX2 3424 -30.5211 -30.5846 0.696647 +VERTEX2 3425 -29.7049 -29.9152 0.687744 +VERTEX2 3426 -30.3609 -29.2122 2.26662 +VERTEX2 3427 -31.0189 -28.448 2.23999 +VERTEX2 3428 -31.6444 -27.6145 2.2143 +VERTEX2 3429 -32.2198 -26.6828 2.2388 +VERTEX2 3430 -32.8145 -25.9198 2.27101 +VERTEX2 3431 -33.6048 -26.6042 -2.42504 +VERTEX2 3432 -34.4103 -27.2419 -2.4567 +VERTEX2 3433 -35.167 -27.8717 -2.46572 +VERTEX2 3434 -35.9526 -28.5252 -2.48864 +VERTEX2 3435 -36.7676 -29.0854 -2.52613 +VERTEX2 3436 -36.2479 -29.8716 -0.978204 +VERTEX2 3437 -35.6774 -30.7102 -0.986583 +VERTEX2 3438 -35.129 -31.58 -0.997788 +VERTEX2 3439 -34.6155 -32.4015 -1.00883 +VERTEX2 3440 -34.0114 -33.3158 -1.01124 +VERTEX2 3441 -33.2333 -32.7865 0.560475 +VERTEX2 3442 -32.3517 -32.2172 0.560392 +VERTEX2 3443 -31.4999 -31.6832 0.549941 +VERTEX2 3444 -30.6549 -31.1247 0.544182 +VERTEX2 3445 -29.7496 -30.6291 0.591273 +VERTEX2 3446 -30.3384 -29.8261 2.14696 +VERTEX2 3447 -30.8261 -29.0208 2.19562 +VERTEX2 3448 -31.429 -28.2261 2.16333 +VERTEX2 3449 -31.9427 -27.4424 2.16412 +VERTEX2 3450 -32.5055 -26.5355 2.17858 +VERTEX2 3451 -31.619 -25.9749 0.591103 +VERTEX2 3452 -30.8883 -25.4534 0.579761 +VERTEX2 3453 -30.0984 -24.9425 0.580302 +VERTEX2 3454 -29.1831 -24.3688 0.554457 +VERTEX2 3455 -28.3302 -23.9489 0.558815 +VERTEX2 3456 -27.8229 -24.8158 -1.02786 +VERTEX2 3457 -27.3516 -25.7264 -1.04562 +VERTEX2 3458 -26.8315 -26.6911 -1.04278 +VERTEX2 3459 -26.2386 -27.6438 -1.02088 +VERTEX2 3460 -25.7536 -28.5332 -1.01781 +VERTEX2 3461 -26.5489 -29.0936 -2.59909 +VERTEX2 3462 -27.3401 -29.6138 -2.61871 +VERTEX2 3463 -28.1463 -30.1636 -2.61543 +VERTEX2 3464 -29.0046 -30.6799 -2.62524 +VERTEX2 3465 -29.8461 -31.1798 -2.62576 +VERTEX2 3466 -29.445 -31.9913 -1.03125 +VERTEX2 3467 -29.0045 -32.8564 -1.03233 +VERTEX2 3468 -28.4134 -33.6997 -1.0665 +VERTEX2 3469 -27.9216 -34.6107 -1.05348 +VERTEX2 3470 -27.4255 -35.5243 -1.07277 +VERTEX2 3471 -28.351 -36.0338 -2.61608 +VERTEX2 3472 -29.1337 -36.4862 -2.63849 +VERTEX2 3473 -29.9988 -36.9397 -2.63066 +VERTEX2 3474 -30.8614 -37.4605 -2.6539 +VERTEX2 3475 -31.7997 -38.0759 -2.65371 +VERTEX2 3476 -32.175 -37.1719 2.08338 +VERTEX2 3477 -32.6914 -36.2471 2.11137 +VERTEX2 3478 -33.1593 -35.3824 2.12215 +VERTEX2 3479 -33.6321 -34.5895 2.12374 +VERTEX2 3480 -34.1338 -33.7639 2.12056 +VERTEX2 3481 -34.9523 -34.2868 -2.55531 +VERTEX2 3482 -35.8827 -34.8399 -2.55956 +VERTEX2 3483 -36.7988 -35.3996 -2.58851 +VERTEX2 3484 -37.5839 -35.914 -2.5744 +VERTEX2 3485 -38.4566 -36.5001 -2.5988 +VERTEX2 3486 -37.9495 -37.3414 -1.01709 +VERTEX2 3487 -37.4619 -38.2011 -1.04391 +VERTEX2 3488 -36.9133 -39.1434 -1.0433 +VERTEX2 3489 -36.4442 -40.1003 -1.02827 +VERTEX2 3490 -35.9094 -40.9675 -1.04787 +VERTEX2 3491 -35.031 -40.4319 0.503302 +VERTEX2 3492 -34.162 -39.9328 0.495939 +VERTEX2 3493 -33.2152 -39.4586 0.523036 +VERTEX2 3494 -32.3648 -38.8964 0.503896 +VERTEX2 3495 -31.4631 -38.3788 0.482098 +VERTEX2 3496 -31.0649 -39.2388 -1.08513 +VERTEX2 3497 -30.512 -40.0251 -1.05959 +VERTEX2 3498 -30.0192 -40.8977 -1.06535 +VERTEX2 3499 -29.493 -41.6977 -1.071 +VERTEX2 3500 -29.0341 -42.5508 -1.06255 +VERTEX2 3501 -30.0233 -43.0076 -2.58722 +VERTEX2 3502 -30.8462 -43.5177 -2.582 +VERTEX2 3503 -31.7877 -44.0794 -2.58976 +VERTEX2 3504 -32.7092 -44.5229 -2.59062 +VERTEX2 3505 -33.4653 -45.0117 -2.61018 +VERTEX2 3506 -32.9131 -45.9149 -1.04321 +VERTEX2 3507 -32.3908 -46.8072 -1.05136 +VERTEX2 3508 -31.9682 -47.685 -1.06493 +VERTEX2 3509 -31.4742 -48.6175 -1.08109 +VERTEX2 3510 -31.0399 -49.5038 -1.09449 +VERTEX2 3511 -30.0105 -48.9675 0.486233 +VERTEX2 3512 -29.168 -48.453 0.47294 +VERTEX2 3513 -28.2849 -48.0489 0.471923 +VERTEX2 3514 -27.4367 -47.6732 0.449334 +VERTEX2 3515 -26.676 -47.1934 0.445164 +VERTEX2 3516 -26.2085 -48.0934 -1.11936 +VERTEX2 3517 -25.8071 -49.016 -1.12805 +VERTEX2 3518 -25.2616 -49.8681 -1.10478 +VERTEX2 3519 -24.8068 -50.7439 -1.10466 +VERTEX2 3520 -24.3139 -51.6024 -1.11695 +VERTEX2 3521 -25.2501 -52.0711 -2.72999 +VERTEX2 3522 -26.1461 -52.5299 -2.74277 +VERTEX2 3523 -27.0848 -52.8801 -2.71841 +VERTEX2 3524 -27.9529 -53.2124 -2.66026 +VERTEX2 3525 -28.8695 -53.5832 -2.61776 +VERTEX2 3526 -28.4088 -54.38 -1.03263 +VERTEX2 3527 -27.9232 -55.2307 -1.04367 +VERTEX2 3528 -27.4283 -56.1189 -1.02067 +VERTEX2 3529 -26.9083 -56.8851 -1.02243 +VERTEX2 3530 -26.3249 -57.7412 -1.01927 +VERTEX2 3531 -27.182 -58.3362 -2.59819 +VERTEX2 3532 -28.038 -58.8486 -2.59993 +VERTEX2 3533 -28.8965 -59.3972 -2.56867 +VERTEX2 3534 -29.7212 -60.0434 -2.57748 +VERTEX2 3535 -30.642 -60.5649 -2.57894 +VERTEX2 3536 -30.0985 -61.4687 -1.01501 +VERTEX2 3537 -29.5748 -62.3496 -1.0215 +VERTEX2 3538 -29.0252 -63.1634 -1.01897 +VERTEX2 3539 -28.5229 -64.048 -0.987639 +VERTEX2 3540 -27.9396 -64.8491 -0.980498 +VERTEX2 3541 -27.1238 -64.2955 0.584693 +VERTEX2 3542 -26.343 -63.8485 0.571065 +VERTEX2 3543 -25.5301 -63.3565 0.570801 +VERTEX2 3544 -24.732 -62.7826 0.568064 +VERTEX2 3545 -23.8477 -62.2982 0.560865 +VERTEX2 3546 -23.3074 -63.0829 -1.02311 +VERTEX2 3547 -22.757 -63.9685 -1.07441 +VERTEX2 3548 -22.2679 -64.8599 -1.0817 +VERTEX2 3549 -21.8664 -65.7882 -1.06163 +VERTEX2 3550 -21.3318 -66.7048 -1.0479 +VERTEX2 3551 -20.5513 -66.2514 0.520326 +VERTEX2 3552 -19.6954 -65.7 0.515088 +VERTEX2 3553 -18.8346 -65.2006 0.49412 +VERTEX2 3554 -17.9437 -64.6731 0.484435 +VERTEX2 3555 -17.0709 -64.2889 0.511897 +VERTEX2 3556 -16.6054 -65.1267 -1.05098 +VERTEX2 3557 -16.1314 -66.0195 -1.05056 +VERTEX2 3558 -15.6258 -66.8915 -1.07183 +VERTEX2 3559 -15.1683 -67.8221 -1.11162 +VERTEX2 3560 -14.713 -68.7373 -1.05917 +VERTEX2 3561 -13.7635 -68.1254 0.495773 +VERTEX2 3562 -12.8771 -67.6061 0.490564 +VERTEX2 3563 -11.9627 -67.0728 0.506436 +VERTEX2 3564 -11.1239 -66.7119 0.506557 +VERTEX2 3565 -10.1972 -66.1444 0.504897 +VERTEX2 3566 -10.6864 -65.298 2.04472 +VERTEX2 3567 -11.1241 -64.3431 2.0415 +VERTEX2 3568 -11.6478 -63.4579 2.06351 +VERTEX2 3569 -12.1292 -62.6443 2.0809 +VERTEX2 3570 -12.6647 -61.8031 2.08192 +VERTEX2 3571 -11.8016 -61.2483 0.511334 +VERTEX2 3572 -10.9515 -60.8326 0.504032 +VERTEX2 3573 -10.0979 -60.3607 0.465894 +VERTEX2 3574 -9.16939 -59.9329 0.448307 +VERTEX2 3575 -8.22911 -59.4905 0.472666 +VERTEX2 3576 -8.63734 -58.568 2.06238 +VERTEX2 3577 -9.11939 -57.6713 2.03285 +VERTEX2 3578 -9.56268 -56.8421 2.05266 +VERTEX2 3579 -9.98075 -56.0089 2.04614 +VERTEX2 3580 -10.4662 -55.1205 2.06138 +VERTEX2 3581 -11.4255 -55.408 -2.58148 +VERTEX2 3582 -12.2675 -55.9728 -2.61083 +VERTEX2 3583 -13.1021 -56.5422 -2.56164 +VERTEX2 3584 -13.9522 -57.0508 -2.55716 +VERTEX2 3585 -14.8499 -57.6571 -2.56324 +VERTEX2 3586 -14.3471 -58.4976 -1.01993 +VERTEX2 3587 -13.884 -59.3368 -1.03149 +VERTEX2 3588 -13.3192 -60.1198 -1.02635 +VERTEX2 3589 -12.7883 -60.9044 -1.00174 +VERTEX2 3590 -12.2231 -61.739 -1.02374 +VERTEX2 3591 -11.3913 -61.2775 0.584694 +VERTEX2 3592 -10.5075 -60.724 0.612878 +VERTEX2 3593 -9.68051 -60.1315 0.63144 +VERTEX2 3594 -8.86118 -59.5659 0.639426 +VERTEX2 3595 -8.10936 -59.0305 0.63025 +VERTEX2 3596 -7.53152 -59.8469 -0.898749 +VERTEX2 3597 -6.86991 -60.6005 -0.885277 +VERTEX2 3598 -6.27699 -61.3676 -0.902913 +VERTEX2 3599 -5.56136 -62.074 -0.904822 +VERTEX2 3600 -4.92284 -62.834 -0.883778 +VERTEX2 3601 -4.09914 -62.2517 0.700943 +VERTEX2 3602 -3.31274 -61.6156 0.68462 +VERTEX2 3603 -2.60227 -60.9657 0.666217 +VERTEX2 3604 -1.75485 -60.3468 0.682593 +VERTEX2 3605 -0.887085 -59.7575 0.652787 +VERTEX2 3606 -0.20737 -60.5392 -0.902163 +VERTEX2 3607 0.364382 -61.3775 -0.89352 +VERTEX2 3608 1.00042 -62.1913 -0.887525 +VERTEX2 3609 1.65391 -62.9668 -0.911938 +VERTEX2 3610 2.29061 -63.7196 -0.927356 +VERTEX2 3611 3.15342 -63.1393 0.634465 +VERTEX2 3612 4.02556 -62.4626 0.606671 +VERTEX2 3613 4.86727 -61.9794 0.617403 +VERTEX2 3614 5.65656 -61.351 0.611493 +VERTEX2 3615 6.41616 -60.7496 0.605174 +VERTEX2 3616 6.9735 -61.6423 -0.95242 +VERTEX2 3617 7.57965 -62.507 -0.96699 +VERTEX2 3618 8.1299 -63.2813 -0.95671 +VERTEX2 3619 8.65247 -63.9802 -0.946907 +VERTEX2 3620 9.21899 -64.8061 -0.921747 +VERTEX2 3621 8.43589 -65.4326 -2.46968 +VERTEX2 3622 7.66371 -66.0101 -2.50379 +VERTEX2 3623 6.86427 -66.6621 -2.50937 +VERTEX2 3624 6.07567 -67.2607 -2.47574 +VERTEX2 3625 5.20228 -67.9049 -2.47625 +VERTEX2 3626 4.57841 -67.1408 2.21156 +VERTEX2 3627 3.88392 -66.378 2.20795 +VERTEX2 3628 3.28159 -65.6319 2.23271 +VERTEX2 3629 2.70138 -64.8604 2.24036 +VERTEX2 3630 2.03278 -64.047 2.22597 +VERTEX2 3631 1.24268 -64.6276 -2.49519 +VERTEX2 3632 0.492973 -65.1992 -2.50666 +VERTEX2 3633 -0.367872 -65.8175 -2.48323 +VERTEX2 3634 -1.12589 -66.51 -2.42377 +VERTEX2 3635 -1.96649 -67.1346 -2.42738 +VERTEX2 3636 -2.63716 -66.3634 2.28813 +VERTEX2 3637 -3.3139 -65.6957 2.30185 +VERTEX2 3638 -4.03088 -64.9623 2.30602 +VERTEX2 3639 -4.76092 -64.1766 2.32134 +VERTEX2 3640 -5.40785 -63.4812 2.30604 +VERTEX2 3641 -6.17246 -64.1466 -2.41433 +VERTEX2 3642 -6.90151 -64.6938 -2.42875 +VERTEX2 3643 -7.6031 -65.3214 -2.43087 +VERTEX2 3644 -8.39167 -65.9116 -2.40078 +VERTEX2 3645 -9.09285 -66.6112 -2.38858 +VERTEX2 3646 -8.46075 -67.3264 -0.820151 +VERTEX2 3647 -7.72413 -68.0398 -0.809661 +VERTEX2 3648 -6.95657 -68.7536 -0.85032 +VERTEX2 3649 -6.32861 -69.5295 -0.875768 +VERTEX2 3650 -5.60911 -70.2586 -0.890709 +VERTEX2 3651 -4.84498 -69.6623 0.677092 +VERTEX2 3652 -4.13558 -69.0331 0.708735 +VERTEX2 3653 -3.3911 -68.3822 0.703453 +VERTEX2 3654 -2.6354 -67.6146 0.709527 +VERTEX2 3655 -1.92646 -66.9226 0.714665 +VERTEX2 3656 -2.6115 -66.1262 2.29511 +VERTEX2 3657 -3.27193 -65.3519 2.2407 +VERTEX2 3658 -3.85391 -64.6214 2.23851 +VERTEX2 3659 -4.53897 -63.8277 2.21635 +VERTEX2 3660 -5.19433 -63.0018 2.22557 +VERTEX2 3661 -6.03075 -63.5822 -2.48341 +VERTEX2 3662 -6.84393 -64.2354 -2.46287 +VERTEX2 3663 -7.5489 -64.8514 -2.48207 +VERTEX2 3664 -8.38936 -65.3778 -2.46679 +VERTEX2 3665 -9.21023 -66.0118 -2.4739 +VERTEX2 3666 -8.55468 -66.8899 -0.917499 +VERTEX2 3667 -7.83952 -67.6539 -0.904467 +VERTEX2 3668 -7.2085 -68.4506 -0.913709 +VERTEX2 3669 -6.62685 -69.3153 -0.935356 +VERTEX2 3670 -6.00726 -70.2155 -0.93413 +VERTEX2 3671 -5.23727 -69.7015 0.630879 +VERTEX2 3672 -4.49231 -69.1076 0.634921 +VERTEX2 3673 -3.59823 -68.5703 0.623512 +VERTEX2 3674 -2.81227 -68.0693 0.621737 +VERTEX2 3675 -2.07453 -67.486 0.616697 +VERTEX2 3676 -2.72045 -66.6217 2.17704 +VERTEX2 3677 -3.26724 -65.7424 2.17226 +VERTEX2 3678 -3.8583 -64.9536 2.15512 +VERTEX2 3679 -4.42546 -64.0737 2.14867 +VERTEX2 3680 -4.98105 -63.2373 2.15638 +VERTEX2 3681 -5.7986 -63.8418 -2.56133 +VERTEX2 3682 -6.61032 -64.3411 -2.54976 +VERTEX2 3683 -7.482 -64.9289 -2.56998 +VERTEX2 3684 -8.27423 -65.4261 -2.60355 +VERTEX2 3685 -9.16308 -65.813 -2.5866 +VERTEX2 3686 -9.69613 -64.9459 2.14077 +VERTEX2 3687 -10.22 -64.1234 2.14339 +VERTEX2 3688 -10.757 -63.2352 2.14406 +VERTEX2 3689 -11.2946 -62.3368 2.1451 +VERTEX2 3690 -11.8401 -61.4664 2.138 +VERTEX2 3691 -12.7144 -62.0029 -2.55913 +VERTEX2 3692 -13.5889 -62.5641 -2.5282 +VERTEX2 3693 -14.4273 -63.1325 -2.50349 +VERTEX2 3694 -15.186 -63.7598 -2.51232 +VERTEX2 3695 -16.0359 -64.2682 -2.52048 +VERTEX2 3696 -15.4641 -65.0513 -0.918937 +VERTEX2 3697 -14.9751 -65.8727 -0.905703 +VERTEX2 3698 -14.3151 -66.691 -0.928576 +VERTEX2 3699 -13.7949 -67.5749 -0.913049 +VERTEX2 3700 -13.2511 -68.3934 -0.923553 +VERTEX2 3701 -14.1503 -69.0782 -2.48474 +VERTEX2 3702 -14.931 -69.7524 -2.53698 +VERTEX2 3703 -15.8425 -70.3009 -2.52749 +VERTEX2 3704 -16.6157 -70.8602 -2.50701 +VERTEX2 3705 -17.3267 -71.4279 -2.52692 +VERTEX2 3706 -16.7375 -72.2725 -0.996792 +VERTEX2 3707 -16.1922 -73.0511 -1.03366 +VERTEX2 3708 -15.6979 -73.9845 -1.02309 +VERTEX2 3709 -15.1304 -74.8491 -1.01191 +VERTEX2 3710 -14.6348 -75.6993 -0.983427 +VERTEX2 3711 -13.813 -75.1496 0.62572 +VERTEX2 3712 -13.0749 -74.4971 0.629215 +VERTEX2 3713 -12.3055 -73.9263 0.651685 +VERTEX2 3714 -11.4542 -73.3338 0.652071 +VERTEX2 3715 -10.7338 -72.7205 0.625755 +VERTEX2 3716 -11.3543 -71.8981 2.19917 +VERTEX2 3717 -11.8916 -71.0315 2.23214 +VERTEX2 3718 -12.4413 -70.2258 2.25874 +VERTEX2 3719 -13.0916 -69.5043 2.27056 +VERTEX2 3720 -13.7679 -68.7041 2.2846 +VERTEX2 3721 -13.0021 -67.9419 0.704194 +VERTEX2 3722 -12.3286 -67.2148 0.702807 +VERTEX2 3723 -11.5246 -66.625 0.72134 +VERTEX2 3724 -10.693 -65.9327 0.7454 +VERTEX2 3725 -9.96196 -65.3242 0.706813 +VERTEX2 3726 -10.6006 -64.5717 2.30132 +VERTEX2 3727 -11.3609 -63.8235 2.26766 +VERTEX2 3728 -11.9418 -62.9954 2.25287 +VERTEX2 3729 -12.6128 -62.226 2.25978 +VERTEX2 3730 -13.1665 -61.5167 2.26123 +VERTEX2 3731 -12.4324 -60.9066 0.676199 +VERTEX2 3732 -11.6445 -60.2155 0.689919 +VERTEX2 3733 -10.8818 -59.5848 0.703366 +VERTEX2 3734 -10.1623 -58.9094 0.75441 +VERTEX2 3735 -9.41567 -58.259 0.745174 +VERTEX2 3736 -10.0715 -57.587 2.32684 +VERTEX2 3737 -10.7179 -56.8903 2.31512 +VERTEX2 3738 -11.4902 -56.2631 2.28932 +VERTEX2 3739 -12.1462 -55.5206 2.31512 +VERTEX2 3740 -12.8551 -54.7994 2.30885 +VERTEX2 3741 -13.5549 -55.4805 -2.39524 +VERTEX2 3742 -14.2556 -56.1488 -2.39316 +VERTEX2 3743 -14.9615 -56.8181 -2.38357 +VERTEX2 3744 -15.6181 -57.5764 -2.36302 +VERTEX2 3745 -16.3816 -58.2381 -2.36044 +VERTEX2 3746 -15.7884 -58.9477 -0.80699 +VERTEX2 3747 -15.1109 -59.7003 -0.817834 +VERTEX2 3748 -14.496 -60.4608 -0.787239 +VERTEX2 3749 -13.8001 -61.0631 -0.781152 +VERTEX2 3750 -13.0738 -61.6803 -0.786878 +VERTEX2 3751 -12.3569 -60.9384 0.799736 +VERTEX2 3752 -11.6072 -60.2227 0.77668 +VERTEX2 3753 -10.8084 -59.5798 0.793409 +VERTEX2 3754 -10.1246 -58.9197 0.786001 +VERTEX2 3755 -9.47792 -58.2049 0.813018 +VERTEX2 3756 -8.74569 -58.91 -0.778021 +VERTEX2 3757 -8.07223 -59.6468 -0.805991 +VERTEX2 3758 -7.4252 -60.3961 -0.823365 +VERTEX2 3759 -6.86358 -61.1419 -0.840175 +VERTEX2 3760 -6.08587 -61.9763 -0.834647 +VERTEX2 3761 -6.86721 -62.7421 -2.38585 +VERTEX2 3762 -7.64513 -63.407 -2.42049 +VERTEX2 3763 -8.35857 -64.0444 -2.43974 +VERTEX2 3764 -9.20243 -64.6376 -2.4579 +VERTEX2 3765 -9.93776 -65.314 -2.45447 +VERTEX2 3766 -10.5851 -64.6105 2.26963 +VERTEX2 3767 -11.2103 -63.7451 2.27756 +VERTEX2 3768 -11.8558 -63.0231 2.23932 +VERTEX2 3769 -12.474 -62.2395 2.28606 +VERTEX2 3770 -13.1398 -61.4687 2.24276 +VERTEX2 3771 -14.0496 -62.1573 -2.49716 +VERTEX2 3772 -14.8436 -62.8233 -2.50445 +VERTEX2 3773 -15.5589 -63.378 -2.47423 +VERTEX2 3774 -16.2873 -63.9467 -2.48313 +VERTEX2 3775 -17.0156 -64.4441 -2.46192 +VERTEX2 3776 -16.3763 -65.2499 -0.887162 +VERTEX2 3777 -15.7904 -66.0911 -0.872404 +VERTEX2 3778 -15.0977 -66.9498 -0.882512 +VERTEX2 3779 -14.4763 -67.7386 -0.877044 +VERTEX2 3780 -13.794 -68.5305 -0.867254 +VERTEX2 3781 -14.4757 -69.1777 -2.45115 +VERTEX2 3782 -15.2381 -69.7854 -2.45331 +VERTEX2 3783 -15.9682 -70.4935 -2.45009 +VERTEX2 3784 -16.7765 -71.1082 -2.4222 +VERTEX2 3785 -17.575 -71.8191 -2.42139 +VERTEX2 3786 -16.9362 -72.563 -0.903453 +VERTEX2 3787 -16.331 -73.3589 -0.895358 +VERTEX2 3788 -15.6723 -74.189 -0.913082 +VERTEX2 3789 -15.0402 -74.9643 -0.914733 +VERTEX2 3790 -14.4137 -75.7544 -0.902806 +VERTEX2 3791 -13.5584 -75.1214 0.670368 +VERTEX2 3792 -12.726 -74.453 0.659451 +VERTEX2 3793 -11.9326 -73.7867 0.688193 +VERTEX2 3794 -11.2077 -73.0202 0.666427 +VERTEX2 3795 -10.4756 -72.5078 0.692238 +VERTEX2 3796 -9.77422 -73.3066 -0.865418 +VERTEX2 3797 -9.24238 -74.079 -0.882343 +VERTEX2 3798 -8.68443 -74.8887 -0.897124 +VERTEX2 3799 -8.04958 -75.6475 -0.881265 +VERTEX2 3800 -7.42199 -76.4425 -0.903152 +VERTEX2 3801 -6.68009 -75.8561 0.671282 +VERTEX2 3802 -5.84873 -75.1505 0.689135 +VERTEX2 3803 -5.07681 -74.5111 0.686075 +VERTEX2 3804 -4.34527 -73.8815 0.667336 +VERTEX2 3805 -3.58575 -73.3295 0.677886 +VERTEX2 3806 -4.23139 -72.6095 2.20604 +VERTEX2 3807 -4.78686 -71.7912 2.25537 +VERTEX2 3808 -5.42118 -71.0271 2.26445 +VERTEX2 3809 -6.12105 -70.2791 2.26086 +VERTEX2 3810 -6.79975 -69.4963 2.24323 +VERTEX2 3811 -5.97586 -68.8055 0.673767 +VERTEX2 3812 -5.27781 -68.1557 0.679409 +VERTEX2 3813 -4.43355 -67.584 0.676367 +VERTEX2 3814 -3.61636 -66.97 0.668188 +VERTEX2 3815 -2.78245 -66.3501 0.687119 +VERTEX2 3816 -3.36077 -65.5761 2.23803 +VERTEX2 3817 -3.96996 -64.7965 2.23545 +VERTEX2 3818 -4.67706 -64.0161 2.22232 +VERTEX2 3819 -5.24576 -63.2465 2.23924 +VERTEX2 3820 -5.93029 -62.4919 2.24089 +VERTEX2 3821 -6.67523 -63.0938 -2.5291 +VERTEX2 3822 -7.53791 -63.6265 -2.51602 +VERTEX2 3823 -8.31946 -64.1913 -2.47565 +VERTEX2 3824 -9.08914 -64.8521 -2.44008 +VERTEX2 3825 -9.87591 -65.4737 -2.42941 +VERTEX2 3826 -9.20948 -66.2818 -0.875175 +VERTEX2 3827 -8.61902 -67.0668 -0.872143 +VERTEX2 3828 -7.96984 -67.823 -0.875092 +VERTEX2 3829 -7.27859 -68.6216 -0.905575 +VERTEX2 3830 -6.69393 -69.4246 -0.875576 +VERTEX2 3831 -7.42294 -70.1673 -2.44353 +VERTEX2 3832 -8.23989 -70.7729 -2.43465 +VERTEX2 3833 -8.977 -71.445 -2.44118 +VERTEX2 3834 -9.74719 -72.1417 -2.4629 +VERTEX2 3835 -10.5392 -72.8599 -2.48764 +VERTEX2 3836 -9.90263 -73.7569 -0.913461 +VERTEX2 3837 -9.25324 -74.4984 -0.917176 +VERTEX2 3838 -8.66237 -75.2604 -0.905843 +VERTEX2 3839 -7.94197 -76.0125 -0.916912 +VERTEX2 3840 -7.32912 -76.7806 -0.90132 +VERTEX2 3841 -8.07863 -77.4204 -2.45597 +VERTEX2 3842 -8.79679 -78.0411 -2.47235 +VERTEX2 3843 -9.52965 -78.678 -2.47019 +VERTEX2 3844 -10.3546 -79.2362 -2.48852 +VERTEX2 3845 -11.1536 -79.7734 -2.51669 +VERTEX2 3846 -10.5542 -80.5726 -0.937391 +VERTEX2 3847 -9.95772 -81.3675 -0.925315 +VERTEX2 3848 -9.40204 -82.2102 -0.9532 +VERTEX2 3849 -8.81863 -82.9993 -0.944451 +VERTEX2 3850 -8.20746 -83.8361 -0.957512 +VERTEX2 3851 -7.37516 -83.2876 0.61306 +VERTEX2 3852 -6.67261 -82.6584 0.615763 +VERTEX2 3853 -5.90046 -81.9931 0.580251 +VERTEX2 3854 -5.00203 -81.4447 0.586448 +VERTEX2 3855 -4.19838 -80.8928 0.605017 +VERTEX2 3856 -3.59225 -81.6849 -0.962632 +VERTEX2 3857 -2.98793 -82.5104 -0.970011 +VERTEX2 3858 -2.48214 -83.3386 -0.974685 +VERTEX2 3859 -1.88006 -84.2263 -0.949535 +VERTEX2 3860 -1.418 -85.0496 -0.970402 +VERTEX2 3861 -0.682755 -84.4796 0.60532 +VERTEX2 3862 0.110004 -83.8491 0.579704 +VERTEX2 3863 0.956662 -83.2432 0.58469 +VERTEX2 3864 1.84295 -82.7166 0.609857 +VERTEX2 3865 2.67429 -82.0535 0.618373 +VERTEX2 3866 2.0874 -81.2206 2.1601 +VERTEX2 3867 1.5006 -80.428 2.18177 +VERTEX2 3868 0.940155 -79.608 2.19402 +VERTEX2 3869 0.417151 -78.8629 2.22061 +VERTEX2 3870 -0.117896 -78.0601 2.20188 +VERTEX2 3871 -0.919274 -78.6169 -2.49635 +VERTEX2 3872 -1.68427 -79.1786 -2.48083 +VERTEX2 3873 -2.46634 -79.7105 -2.4773 +VERTEX2 3874 -3.23581 -80.2912 -2.45965 +VERTEX2 3875 -3.99693 -80.9275 -2.45612 +VERTEX2 3876 -3.39362 -81.7474 -0.892957 +VERTEX2 3877 -2.81487 -82.5924 -0.921916 +VERTEX2 3878 -2.15573 -83.3753 -0.945758 +VERTEX2 3879 -1.60091 -84.2615 -0.946362 +VERTEX2 3880 -0.987231 -85.0648 -0.953333 +VERTEX2 3881 -1.6989 -85.6118 -2.53959 +VERTEX2 3882 -2.50089 -86.1414 -2.51134 +VERTEX2 3883 -3.3563 -86.7079 -2.48408 +VERTEX2 3884 -4.15381 -87.3265 -2.44675 +VERTEX2 3885 -4.89891 -87.9482 -2.49276 +VERTEX2 3886 -4.29257 -88.8272 -0.901978 +VERTEX2 3887 -3.67461 -89.632 -0.906942 +VERTEX2 3888 -3.03574 -90.3579 -0.902191 +VERTEX2 3889 -2.47001 -91.1689 -0.913474 +VERTEX2 3890 -1.88143 -91.9182 -0.93737 +VERTEX2 3891 -2.68112 -92.4647 -2.46335 +VERTEX2 3892 -3.43995 -93.1125 -2.46539 +VERTEX2 3893 -4.29267 -93.7621 -2.47327 +VERTEX2 3894 -5.12522 -94.3584 -2.47861 +VERTEX2 3895 -5.96316 -94.9677 -2.4809 +VERTEX2 3896 -5.3539 -95.734 -0.878204 +VERTEX2 3897 -4.67401 -96.5391 -0.894994 +VERTEX2 3898 -4.03742 -97.3209 -0.903392 +VERTEX2 3899 -3.40508 -98.1112 -0.926326 +VERTEX2 3900 -2.71852 -98.925 -0.958402 +VERTEX2 3901 -1.88891 -98.3861 0.618374 +VERTEX2 3902 -1.05469 -97.8451 0.633383 +VERTEX2 3903 -0.247498 -97.1859 0.626089 +VERTEX2 3904 0.569451 -96.5648 0.638391 +VERTEX2 3905 1.39516 -95.9556 0.644303 +VERTEX2 3906 1.98228 -96.831 -0.931413 +VERTEX2 3907 2.59903 -97.6478 -0.940871 +VERTEX2 3908 3.13024 -98.4818 -0.921571 +VERTEX2 3909 3.82424 -99.2221 -0.922453 +VERTEX2 3910 4.50013 -100.033 -0.907473 +VERTEX2 3911 5.31397 -99.339 0.628642 +VERTEX2 3912 6.04441 -98.7931 0.622459 +VERTEX2 3913 6.84031 -98.2833 0.612244 +VERTEX2 3914 7.72935 -97.8493 0.641332 +VERTEX2 3915 8.45306 -97.3259 0.673871 +VERTEX2 3916 7.76135 -96.4754 2.24803 +VERTEX2 3917 7.1229 -95.7206 2.2183 +VERTEX2 3918 6.49876 -94.9162 2.21717 +VERTEX2 3919 5.92581 -94.1163 2.2205 +VERTEX2 3920 5.34878 -93.3359 2.20967 +VERTEX2 3921 4.50785 -94.0289 -2.49505 +VERTEX2 3922 3.64601 -94.5767 -2.4721 +VERTEX2 3923 2.81413 -95.1113 -2.48868 +VERTEX2 3924 2.08649 -95.7182 -2.48501 +VERTEX2 3925 1.25686 -96.3221 -2.48908 +VERTEX2 3926 1.89718 -97.0592 -0.93708 +VERTEX2 3927 2.52483 -97.6925 -0.926969 +VERTEX2 3928 3.10668 -98.4005 -0.897007 +VERTEX2 3929 3.68634 -99.1788 -0.883064 +VERTEX2 3930 4.32838 -100.003 -0.853714 +VERTEX2 3931 5.12134 -99.3019 0.698283 +VERTEX2 3932 5.9475 -98.7079 0.713086 +VERTEX2 3933 6.67132 -98.0082 0.685894 +VERTEX2 3934 7.5273 -97.3526 0.659775 +VERTEX2 3935 8.32202 -96.7432 0.667728 +VERTEX2 3936 7.74615 -95.8917 2.24262 +VERTEX2 3937 7.10775 -95.0972 2.24805 +VERTEX2 3938 6.48238 -94.3233 2.24803 +VERTEX2 3939 5.95336 -93.6188 2.24954 +VERTEX2 3940 5.37268 -92.753 2.21288 +VERTEX2 3941 4.5164 -93.3466 -2.48777 +VERTEX2 3942 3.73364 -93.9713 -2.47696 +VERTEX2 3943 2.92893 -94.5989 -2.47078 +VERTEX2 3944 2.14342 -95.2362 -2.44645 +VERTEX2 3945 1.32127 -95.8467 -2.44114 +VERTEX2 3946 1.96365 -96.6379 -0.880897 +VERTEX2 3947 2.50593 -97.3854 -0.875679 +VERTEX2 3948 3.23037 -98.0444 -0.889863 +VERTEX2 3949 3.90709 -98.8465 -0.897562 +VERTEX2 3950 4.53814 -99.6659 -0.906848 +VERTEX2 3951 3.71925 -100.287 -2.46129 +VERTEX2 3952 2.92444 -100.835 -2.51523 +VERTEX2 3953 2.17175 -101.368 -2.54766 +VERTEX2 3954 1.36194 -101.917 -2.52049 +VERTEX2 3955 0.565552 -102.478 -2.52471 +VERTEX2 3956 1.1278 -103.368 -0.94905 +VERTEX2 3957 1.76398 -104.191 -0.938164 +VERTEX2 3958 2.31701 -105.086 -0.962281 +VERTEX2 3959 2.7919 -105.975 -0.933018 +VERTEX2 3960 3.33168 -106.779 -0.881925 +VERTEX2 3961 4.10216 -106.167 0.687561 +VERTEX2 3962 4.93768 -105.511 0.723628 +VERTEX2 3963 5.68452 -104.827 0.691407 +VERTEX2 3964 6.56205 -104.146 0.719913 +VERTEX2 3965 7.37194 -103.401 0.719343 +VERTEX2 3966 6.72946 -102.631 2.25952 +VERTEX2 3967 6.0074 -101.847 2.26282 +VERTEX2 3968 5.34747 -101.074 2.24893 +VERTEX2 3969 4.77616 -100.315 2.22899 +VERTEX2 3970 4.12852 -99.5516 2.22466 +VERTEX2 3971 4.96869 -98.9596 0.621348 +VERTEX2 3972 5.75831 -98.3993 0.583546 +VERTEX2 3973 6.57081 -97.8276 0.590802 +VERTEX2 3974 7.40801 -97.1567 0.587971 +VERTEX2 3975 8.27648 -96.571 0.579419 +VERTEX2 3976 8.82609 -97.3877 -1.0039 +VERTEX2 3977 9.42479 -98.3177 -1.02136 +VERTEX2 3978 9.84828 -99.1066 -1.05113 +VERTEX2 3979 10.3262 -100.006 -1.03301 +VERTEX2 3980 10.7717 -100.822 -1.04246 +VERTEX2 3981 11.6321 -100.381 0.509295 +VERTEX2 3982 12.5118 -99.9496 0.541504 +VERTEX2 3983 13.3761 -99.521 0.522883 +VERTEX2 3984 14.3181 -99.0588 0.520121 +VERTEX2 3985 15.1504 -98.5308 0.488724 +VERTEX2 3986 14.7656 -97.6955 2.06761 +VERTEX2 3987 14.3332 -96.8451 2.07632 +VERTEX2 3988 13.8803 -95.9173 2.07534 +VERTEX2 3989 13.4501 -95.0738 2.06665 +VERTEX2 3990 13.0001 -94.213 2.07567 +VERTEX2 3991 12.1518 -94.6956 -2.62979 +VERTEX2 3992 11.3437 -95.1661 -2.64212 +VERTEX2 3993 10.5543 -95.6568 -2.65371 +VERTEX2 3994 9.8271 -96.1552 -2.64845 +VERTEX2 3995 8.96308 -96.5443 -2.66863 +VERTEX2 3996 9.42234 -97.4286 -1.11612 +VERTEX2 3997 9.89278 -98.4181 -1.11663 +VERTEX2 3998 10.2175 -99.3838 -1.1116 +VERTEX2 3999 10.6058 -100.28 -1.139 +VERTEX2 4000 11.0339 -101.207 -1.13454 +VERTEX2 4001 11.8953 -100.835 0.430658 +VERTEX2 4002 12.791 -100.468 0.432513 +VERTEX2 4003 13.6369 -100.004 0.448537 +VERTEX2 4004 14.5412 -99.5044 0.453174 +VERTEX2 4005 15.4216 -99.0446 0.426668 +VERTEX2 4006 14.9919 -98.0867 2.04058 +VERTEX2 4007 14.5356 -97.1678 2.02742 +VERTEX2 4008 14.1734 -96.2414 2.05906 +VERTEX2 4009 13.6344 -95.3699 2.05555 +VERTEX2 4010 13.2023 -94.5747 2.04922 +VERTEX2 4011 12.3913 -95.015 -2.6654 +VERTEX2 4012 11.5327 -95.5075 -2.65629 +VERTEX2 4013 10.6005 -95.9643 -2.65951 +VERTEX2 4014 9.70228 -96.4672 -2.64621 +VERTEX2 4015 8.86813 -96.8247 -2.62974 +VERTEX2 4016 9.36165 -97.618 -1.04637 +VERTEX2 4017 9.82283 -98.4884 -1.03831 +VERTEX2 4018 10.2534 -99.4255 -1.0307 +VERTEX2 4019 10.7021 -100.275 -1.01242 +VERTEX2 4020 11.2768 -101.165 -1.02943 +VERTEX2 4021 10.355 -101.65 -2.60263 +VERTEX2 4022 9.51348 -102.129 -2.61594 +VERTEX2 4023 8.66693 -102.644 -2.6363 +VERTEX2 4024 7.80305 -103.134 -2.65097 +VERTEX2 4025 7.04621 -103.646 -2.63963 +VERTEX2 4026 7.54727 -104.538 -1.07005 +VERTEX2 4027 8.07505 -105.435 -1.07445 +VERTEX2 4028 8.50372 -106.289 -1.08665 +VERTEX2 4029 8.98092 -107.155 -1.10985 +VERTEX2 4030 9.35698 -108.052 -1.10619 +VERTEX2 4031 8.50786 -108.499 -2.70922 +VERTEX2 4032 7.69726 -108.925 -2.70755 +VERTEX2 4033 6.84555 -109.33 -2.73785 +VERTEX2 4034 5.90808 -109.774 -2.71015 +VERTEX2 4035 4.92201 -110.225 -2.7231 +VERTEX2 4036 4.56094 -109.277 1.9785 +VERTEX2 4037 4.1382 -108.303 1.9531 +VERTEX2 4038 3.79681 -107.337 1.91479 +VERTEX2 4039 3.51696 -106.394 1.89619 +VERTEX2 4040 3.17829 -105.509 1.92189 +VERTEX2 4041 2.22045 -105.937 -2.78066 +VERTEX2 4042 1.33372 -106.18 -2.76153 +VERTEX2 4043 0.387854 -106.556 -2.74155 +VERTEX2 4044 -0.505439 -107.042 -2.74851 +VERTEX2 4045 -1.38735 -107.462 -2.73527 +VERTEX2 4046 -1.71378 -106.592 1.98285 +VERTEX2 4047 -2.01682 -105.71 1.95052 +VERTEX2 4048 -2.39973 -104.721 1.94823 +VERTEX2 4049 -2.75669 -103.757 1.94322 +VERTEX2 4050 -3.12144 -102.819 1.93552 +VERTEX2 4051 -4.04926 -103.102 -2.7778 +VERTEX2 4052 -4.93811 -103.442 -2.7547 +VERTEX2 4053 -5.94705 -103.81 -2.77334 +VERTEX2 4054 -6.87527 -104.192 -2.77125 +VERTEX2 4055 -7.88181 -104.584 -2.7573 +VERTEX2 4056 -7.60849 -105.528 -1.17792 +VERTEX2 4057 -7.20554 -106.362 -1.20114 +VERTEX2 4058 -6.81187 -107.352 -1.21341 +VERTEX2 4059 -6.53421 -108.323 -1.20721 +VERTEX2 4060 -6.29073 -109.274 -1.18904 +VERTEX2 4061 -5.42436 -108.827 0.40619 +VERTEX2 4062 -4.56549 -108.438 0.409479 +VERTEX2 4063 -3.7187 -107.982 0.422998 +VERTEX2 4064 -2.7768 -107.518 0.398341 +VERTEX2 4065 -1.81723 -107.165 0.387552 +VERTEX2 4066 -2.16271 -106.236 1.97739 +VERTEX2 4067 -2.56246 -105.265 1.95592 +VERTEX2 4068 -2.97051 -104.277 1.942 +VERTEX2 4069 -3.31736 -103.265 1.92981 +VERTEX2 4070 -3.65831 -102.404 1.94928 +VERTEX2 4071 -2.69073 -102.104 0.350189 +VERTEX2 4072 -1.69154 -101.675 0.364174 +VERTEX2 4073 -0.691775 -101.288 0.359036 +VERTEX2 4074 0.271095 -100.924 0.341739 +VERTEX2 4075 1.16552 -100.591 0.345762 +VERTEX2 4076 1.52102 -101.572 -1.19775 +VERTEX2 4077 1.92212 -102.466 -1.20274 +VERTEX2 4078 2.24903 -103.347 -1.24286 +VERTEX2 4079 2.60309 -104.356 -1.2417 +VERTEX2 4080 2.91977 -105.3 -1.21401 +VERTEX2 4081 3.84454 -104.837 0.356036 +VERTEX2 4082 4.74313 -104.467 0.353114 +VERTEX2 4083 5.62309 -104.146 0.34398 +VERTEX2 4084 6.57166 -103.809 0.342925 +VERTEX2 4085 7.61886 -103.493 0.365769 +VERTEX2 4086 7.95999 -104.354 -1.18374 +VERTEX2 4087 8.37428 -105.273 -1.17848 +VERTEX2 4088 8.76004 -106.271 -1.17638 +VERTEX2 4089 9.15481 -107.269 -1.17639 +VERTEX2 4090 9.53933 -108.173 -1.19088 +VERTEX2 4091 10.5598 -107.777 0.376915 +VERTEX2 4092 11.4415 -107.358 0.389259 +VERTEX2 4093 12.3714 -106.962 0.400535 +VERTEX2 4094 13.2375 -106.645 0.403786 +VERTEX2 4095 14.1693 -106.263 0.386722 +VERTEX2 4096 13.8004 -105.365 1.93096 +VERTEX2 4097 13.4568 -104.424 1.92292 +VERTEX2 4098 13.0691 -103.57 1.90976 +VERTEX2 4099 12.7206 -102.626 1.92753 +VERTEX2 4100 12.3975 -101.703 1.94955 +VERTEX2 4101 11.4926 -102.044 -2.7665 +VERTEX2 4102 10.6202 -102.427 -2.7664 +VERTEX2 4103 9.69202 -102.873 -2.7687 +VERTEX2 4104 8.7677 -103.253 -2.78921 +VERTEX2 4105 7.81826 -103.536 -2.78212 +VERTEX2 4106 7.50902 -102.552 1.94601 +VERTEX2 4107 7.22704 -101.706 1.96265 +VERTEX2 4108 6.78395 -100.822 1.92919 +VERTEX2 4109 6.50309 -99.8415 1.9126 +VERTEX2 4110 6.12623 -98.8253 1.92333 +VERTEX2 4111 7.01612 -98.606 0.35978 +VERTEX2 4112 7.96185 -98.2406 0.360472 +VERTEX2 4113 8.87712 -97.8584 0.298596 +VERTEX2 4114 9.80047 -97.4886 0.314341 +VERTEX2 4115 10.7435 -97.1815 0.34131 +VERTEX2 4116 10.3212 -96.2656 1.92396 +VERTEX2 4117 10.0207 -95.3113 1.9448 +VERTEX2 4118 9.66054 -94.3484 1.94777 +VERTEX2 4119 9.27958 -93.5031 1.92184 +VERTEX2 4120 8.9267 -92.5689 1.88138 +VERTEX2 4121 7.95338 -92.8476 -2.8342 +VERTEX2 4122 6.98013 -93.1357 -2.84174 +VERTEX2 4123 6.02088 -93.481 -2.85729 +VERTEX2 4124 5.03468 -93.8117 -2.83446 +VERTEX2 4125 4.12256 -94.1583 -2.81515 +VERTEX2 4126 3.7838 -93.1248 1.90093 +VERTEX2 4127 3.49481 -92.1522 1.91696 +VERTEX2 4128 3.12572 -91.1592 1.90169 +VERTEX2 4129 2.79332 -90.2332 1.89061 +VERTEX2 4130 2.48851 -89.2993 1.88503 +VERTEX2 4131 1.45711 -89.5845 -2.83774 +VERTEX2 4132 0.539588 -89.8362 -2.84523 +VERTEX2 4133 -0.462595 -90.0025 -2.84558 +VERTEX2 4134 -1.34282 -90.3335 -2.82937 +VERTEX2 4135 -2.27482 -90.5564 -2.84277 +VERTEX2 4136 -2.64892 -89.5789 1.88109 +VERTEX2 4137 -2.94114 -88.6716 1.90093 +VERTEX2 4138 -3.21515 -87.7194 1.90456 +VERTEX2 4139 -3.63571 -86.7247 1.87293 +VERTEX2 4140 -3.90362 -85.8036 1.85623 +VERTEX2 4141 -2.93822 -85.4822 0.255328 +VERTEX2 4142 -1.9937 -85.241 0.275381 +VERTEX2 4143 -1.06742 -84.9037 0.261421 +VERTEX2 4144 -0.181589 -84.6248 0.267461 +VERTEX2 4145 0.781101 -84.411 0.277872 +VERTEX2 4146 1.01002 -85.4218 -1.27925 +VERTEX2 4147 1.21656 -86.4577 -1.26198 +VERTEX2 4148 1.54079 -87.3843 -1.26489 +VERTEX2 4149 1.88811 -88.3919 -1.26779 +VERTEX2 4150 2.28226 -89.2906 -1.29672 +VERTEX2 4151 1.26334 -89.5865 -2.8679 +VERTEX2 4152 0.268039 -89.9413 -2.853 +VERTEX2 4153 -0.659405 -90.1659 -2.84753 +VERTEX2 4154 -1.57347 -90.4237 -2.86009 +VERTEX2 4155 -2.54624 -90.6656 -2.8646 +VERTEX2 4156 -2.26263 -91.6154 -1.3193 +VERTEX2 4157 -2.03087 -92.5199 -1.28035 +VERTEX2 4158 -1.7797 -93.4808 -1.29457 +VERTEX2 4159 -1.48088 -94.5122 -1.31922 +VERTEX2 4160 -1.2508 -95.5048 -1.3121 +VERTEX2 4161 -0.287675 -95.1736 0.245953 +VERTEX2 4162 0.698767 -94.9522 0.267939 +VERTEX2 4163 1.59581 -94.6859 0.230845 +VERTEX2 4164 2.63523 -94.4851 0.271077 +VERTEX2 4165 3.62383 -94.1381 0.255817 +VERTEX2 4166 3.36166 -93.1744 1.84578 +VERTEX2 4167 3.10274 -92.2963 1.86683 +VERTEX2 4168 2.87062 -91.3438 1.86218 +VERTEX2 4169 2.50534 -90.4217 1.85713 +VERTEX2 4170 2.13188 -89.4959 1.8578 +VERTEX2 4171 3.20948 -89.1494 0.297032 +VERTEX2 4172 4.0675 -88.8733 0.306087 +VERTEX2 4173 4.93121 -88.6059 0.286942 +VERTEX2 4174 5.82418 -88.3343 0.288789 +VERTEX2 4175 6.82635 -88.07 0.264336 +VERTEX2 4176 6.53347 -87.1218 1.86856 +VERTEX2 4177 6.17539 -86.1929 1.88209 +VERTEX2 4178 5.88312 -85.2585 1.93205 +VERTEX2 4179 5.48653 -84.2461 1.92602 +VERTEX2 4180 5.12127 -83.3023 1.94795 +VERTEX2 4181 4.11038 -83.6455 -2.79509 +VERTEX2 4182 3.17313 -84.0254 -2.7625 +VERTEX2 4183 2.23544 -84.3163 -2.76059 +VERTEX2 4184 1.32836 -84.688 -2.77507 +VERTEX2 4185 0.391999 -85.0536 -2.8107 +VERTEX2 4186 0.0284533 -84.0971 1.90995 +VERTEX2 4187 -0.262683 -83.1211 1.90747 +VERTEX2 4188 -0.606494 -82.1306 1.91284 +VERTEX2 4189 -1.06829 -81.1547 1.91877 +VERTEX2 4190 -1.49932 -80.2437 1.89069 +VERTEX2 4191 -2.47445 -80.5176 -2.82767 +VERTEX2 4192 -3.39951 -80.8151 -2.81371 +VERTEX2 4193 -4.26647 -81.0065 -2.79349 +VERTEX2 4194 -5.21659 -81.3236 -2.79363 +VERTEX2 4195 -6.18188 -81.6565 -2.77693 +VERTEX2 4196 -5.83488 -82.6112 -1.19102 +VERTEX2 4197 -5.42829 -83.6037 -1.22829 +VERTEX2 4198 -4.97925 -84.5635 -1.23469 +VERTEX2 4199 -4.58494 -85.5392 -1.23309 +VERTEX2 4200 -4.16462 -86.4532 -1.24124 +VERTEX2 4201 -3.18134 -86.1421 0.342265 +VERTEX2 4202 -2.27613 -85.8109 0.341304 +VERTEX2 4203 -1.3256 -85.4109 0.349184 +VERTEX2 4204 -0.27409 -85.0539 0.30881 +VERTEX2 4205 0.583239 -84.7872 0.322863 +VERTEX2 4206 0.921009 -85.7598 -1.27498 +VERTEX2 4207 1.19309 -86.6705 -1.26059 +VERTEX2 4208 1.49643 -87.6377 -1.24723 +VERTEX2 4209 1.83848 -88.6708 -1.23531 +VERTEX2 4210 2.22941 -89.678 -1.22875 +VERTEX2 4211 3.18019 -89.2378 0.330905 +VERTEX2 4212 4.10321 -88.988 0.336744 +VERTEX2 4213 5.0511 -88.6316 0.347583 +VERTEX2 4214 6.04039 -88.2664 0.386671 +VERTEX2 4215 7.01561 -87.8396 0.372637 +VERTEX2 4216 6.65123 -86.9028 1.93534 +VERTEX2 4217 6.29185 -85.9455 1.98571 +VERTEX2 4218 5.88124 -85.0931 1.96825 +VERTEX2 4219 5.51546 -84.2145 1.96125 +VERTEX2 4220 5.04763 -83.2833 1.96945 +VERTEX2 4221 4.173 -83.649 -2.72829 +VERTEX2 4222 3.23736 -84.1651 -2.76005 +VERTEX2 4223 2.30434 -84.5172 -2.7605 +VERTEX2 4224 1.35043 -84.9193 -2.766 +VERTEX2 4225 0.338076 -85.228 -2.74087 +VERTEX2 4226 0.68751 -86.1425 -1.16568 +VERTEX2 4227 1.15072 -87.0688 -1.16512 +VERTEX2 4228 1.56438 -88.0697 -1.20349 +VERTEX2 4229 1.97942 -88.9305 -1.20714 +VERTEX2 4230 2.36055 -89.8642 -1.17086 +VERTEX2 4231 3.31547 -89.3928 0.396534 +VERTEX2 4232 4.2045 -88.9506 0.393159 +VERTEX2 4233 5.14622 -88.5171 0.386902 +VERTEX2 4234 6.14593 -88.2724 0.381238 +VERTEX2 4235 7.03815 -87.868 0.398789 +VERTEX2 4236 7.42003 -88.7306 -1.16705 +VERTEX2 4237 7.85541 -89.5992 -1.14692 +VERTEX2 4238 8.18492 -90.564 -1.12838 +VERTEX2 4239 8.62829 -91.4815 -1.13673 +VERTEX2 4240 8.9182 -92.3665 -1.12436 +VERTEX2 4241 8.01872 -92.83 -2.68906 +VERTEX2 4242 7.09856 -93.3654 -2.69496 +VERTEX2 4243 6.16999 -93.7917 -2.69646 +VERTEX2 4244 5.27527 -94.1683 -2.69211 +VERTEX2 4245 4.46189 -94.5888 -2.65189 +VERTEX2 4246 4.97802 -95.4385 -1.09414 +VERTEX2 4247 5.41531 -96.2824 -1.08629 +VERTEX2 4248 5.84042 -97.2755 -1.08282 +VERTEX2 4249 6.31441 -98.1396 -1.05641 +VERTEX2 4250 6.77359 -99.009 -1.04221 +VERTEX2 4251 7.62738 -98.4536 0.51917 +VERTEX2 4252 8.51587 -97.9754 0.531314 +VERTEX2 4253 9.44534 -97.4974 0.490924 +VERTEX2 4254 10.307 -97.0585 0.513768 +VERTEX2 4255 11.2764 -96.5335 0.505003 +VERTEX2 4256 10.7473 -95.6467 2.08322 +VERTEX2 4257 10.3125 -94.7615 2.12454 +VERTEX2 4258 9.77026 -93.943 2.12318 +VERTEX2 4259 9.33255 -93.187 2.0905 +VERTEX2 4260 8.86877 -92.3883 2.1128 +VERTEX2 4261 7.95877 -92.899 -2.59764 +VERTEX2 4262 7.13528 -93.4641 -2.58635 +VERTEX2 4263 6.25819 -93.8698 -2.58432 +VERTEX2 4264 5.41901 -94.314 -2.57417 +VERTEX2 4265 4.52308 -94.8564 -2.59694 +VERTEX2 4266 5.08588 -95.711 -1.01907 +VERTEX2 4267 5.65196 -96.5783 -1.00825 +VERTEX2 4268 6.30734 -97.362 -0.990779 +VERTEX2 4269 6.88218 -98.1717 -0.971306 +VERTEX2 4270 7.52206 -99.0718 -0.965925 +VERTEX2 4271 8.24205 -98.5042 0.613853 +VERTEX2 4272 9.04074 -97.9306 0.611217 +VERTEX2 4273 9.91454 -97.3771 0.611853 +VERTEX2 4274 10.7415 -96.869 0.599664 +VERTEX2 4275 11.6195 -96.3191 0.62716 +VERTEX2 4276 11.02 -95.4573 2.23003 +VERTEX2 4277 10.3875 -94.6222 2.192 +VERTEX2 4278 9.79038 -93.7801 2.18081 +VERTEX2 4279 9.21522 -92.9891 2.20362 +VERTEX2 4280 8.60146 -92.2721 2.19445 +VERTEX2 4281 9.40156 -91.5961 0.658475 +VERTEX2 4282 10.0776 -90.925 0.669435 +VERTEX2 4283 10.8513 -90.2995 0.688447 +VERTEX2 4284 11.65 -89.7585 0.72952 +VERTEX2 4285 12.4083 -89.2457 0.713624 +VERTEX2 4286 11.7723 -88.4673 2.24493 +VERTEX2 4287 11.1503 -87.7263 2.26755 +VERTEX2 4288 10.6002 -86.8848 2.27298 +VERTEX2 4289 10.0284 -86.0893 2.27107 +VERTEX2 4290 9.37908 -85.3867 2.26399 +VERTEX2 4291 8.58902 -85.9747 -2.45311 +VERTEX2 4292 7.88861 -86.5958 -2.4419 +VERTEX2 4293 7.10913 -87.2899 -2.4248 +VERTEX2 4294 6.30882 -87.8874 -2.40631 +VERTEX2 4295 5.62478 -88.5979 -2.41427 +VERTEX2 4296 4.96851 -87.8709 2.30197 +VERTEX2 4297 4.32276 -87.1904 2.32085 +VERTEX2 4298 3.68978 -86.4505 2.33235 +VERTEX2 4299 3.01675 -85.7685 2.34585 +VERTEX2 4300 2.35887 -84.9908 2.33641 +VERTEX2 4301 1.62969 -85.7082 -2.38363 +VERTEX2 4302 0.89503 -86.478 -2.35728 +VERTEX2 4303 0.18775 -87.1592 -2.37732 +VERTEX2 4304 -0.485212 -87.9028 -2.3314 +VERTEX2 4305 -1.21608 -88.5651 -2.30511 +VERTEX2 4306 -0.462514 -89.3208 -0.751247 +VERTEX2 4307 0.403964 -90.0105 -0.747236 +VERTEX2 4308 1.08535 -90.6308 -0.77963 +VERTEX2 4309 1.8261 -91.3146 -0.767918 +VERTEX2 4310 2.62011 -91.9461 -0.756759 +VERTEX2 4311 3.22076 -91.2945 0.824923 +VERTEX2 4312 3.90869 -90.5421 0.847942 +VERTEX2 4313 4.56863 -89.7051 0.82879 +VERTEX2 4314 5.25626 -88.9943 0.818239 +VERTEX2 4315 5.8431 -88.2353 0.82193 +VERTEX2 4316 5.10848 -87.5259 2.40099 +VERTEX2 4317 4.37199 -86.8011 2.42479 +VERTEX2 4318 3.63545 -86.1376 2.43298 +VERTEX2 4319 2.80227 -85.4457 2.4381 +VERTEX2 4320 2.06158 -84.8426 2.44721 +VERTEX2 4321 1.30198 -85.5888 -2.24846 +VERTEX2 4322 0.727359 -86.3837 -2.28933 +VERTEX2 4323 0.109017 -87.0932 -2.28406 +VERTEX2 4324 -0.564139 -87.9046 -2.31827 +VERTEX2 4325 -1.26637 -88.6867 -2.34668 +VERTEX2 4326 -2.05515 -87.9253 2.37013 +VERTEX2 4327 -2.74888 -87.1727 2.36642 +VERTEX2 4328 -3.5697 -86.5601 2.35255 +VERTEX2 4329 -4.30114 -85.8399 2.36078 +VERTEX2 4330 -5.01063 -85.0407 2.38937 +VERTEX2 4331 -5.71463 -85.748 -2.3396 +VERTEX2 4332 -6.41131 -86.4935 -2.35302 +VERTEX2 4333 -7.06696 -87.1583 -2.3414 +VERTEX2 4334 -7.84341 -87.8378 -2.32662 +VERTEX2 4335 -8.59485 -88.6093 -2.33525 +VERTEX2 4336 -9.24856 -87.8728 2.39153 +VERTEX2 4337 -9.83217 -87.2025 2.41207 +VERTEX2 4338 -10.6296 -86.5197 2.42239 +VERTEX2 4339 -11.4633 -85.7246 2.4121 +VERTEX2 4340 -12.2561 -85.0453 2.42276 +VERTEX2 4341 -12.8987 -85.8523 -2.27369 +VERTEX2 4342 -13.4473 -86.4706 -2.25223 +VERTEX2 4343 -14.0267 -87.2492 -2.23834 +VERTEX2 4344 -14.5577 -88.0308 -2.24772 +VERTEX2 4345 -15.127 -88.8191 -2.25392 +VERTEX2 4346 -15.8565 -88.1958 2.48235 +VERTEX2 4347 -16.686 -87.5854 2.46426 +VERTEX2 4348 -17.4979 -87.0893 2.48645 +VERTEX2 4349 -18.2754 -86.486 2.48658 +VERTEX2 4350 -19.0217 -85.9422 2.46921 +VERTEX2 4351 -19.6487 -86.7947 -2.21498 +VERTEX2 4352 -20.334 -87.5726 -2.22773 +VERTEX2 4353 -20.9657 -88.332 -2.21283 +VERTEX2 4354 -21.5936 -89.1862 -2.20099 +VERTEX2 4355 -22.2981 -89.9134 -2.19149 +VERTEX2 4356 -23.0541 -89.403 2.55096 +VERTEX2 4357 -23.9333 -88.8433 2.52375 +VERTEX2 4358 -24.8204 -88.3087 2.50389 +VERTEX2 4359 -25.6103 -87.647 2.4996 +VERTEX2 4360 -26.3355 -87.0564 2.48105 +VERTEX2 4361 -25.7077 -86.3193 0.929429 +VERTEX2 4362 -25.136 -85.493 0.883106 +VERTEX2 4363 -24.4458 -84.7713 0.889992 +VERTEX2 4364 -23.8026 -84.0007 0.900489 +VERTEX2 4365 -23.1109 -83.1484 0.899093 +VERTEX2 4366 -23.9679 -82.5619 2.46642 +VERTEX2 4367 -24.7243 -81.9263 2.44996 +VERTEX2 4368 -25.5471 -81.246 2.44544 +VERTEX2 4369 -26.2885 -80.5392 2.42306 +VERTEX2 4370 -27.041 -79.909 2.41211 +VERTEX2 4371 -27.728 -80.6118 -2.29117 +VERTEX2 4372 -28.386 -81.3526 -2.28625 +VERTEX2 4373 -29.1451 -82.1677 -2.24683 +VERTEX2 4374 -29.8031 -83.0342 -2.23712 +VERTEX2 4375 -30.4423 -83.7003 -2.22648 +VERTEX2 4376 -31.1632 -83.1297 2.50247 +VERTEX2 4377 -31.9739 -82.5583 2.51233 +VERTEX2 4378 -32.7923 -81.8852 2.52998 +VERTEX2 4379 -33.6472 -81.345 2.50102 +VERTEX2 4380 -34.5276 -80.7915 2.49164 +VERTEX2 4381 -33.9439 -80.0165 0.882741 +VERTEX2 4382 -33.3345 -79.2049 0.876718 +VERTEX2 4383 -32.7233 -78.4807 0.909036 +VERTEX2 4384 -32.1509 -77.7265 0.874825 +VERTEX2 4385 -31.4408 -76.9431 0.837321 +VERTEX2 4386 -30.6713 -77.7285 -0.754688 +VERTEX2 4387 -29.9842 -78.457 -0.734021 +VERTEX2 4388 -29.1688 -79.1786 -0.696043 +VERTEX2 4389 -28.3825 -79.7228 -0.678586 +VERTEX2 4390 -27.4683 -80.4443 -0.68881 +VERTEX2 4391 -28.1011 -81.26 -2.27404 +VERTEX2 4392 -28.7587 -81.9953 -2.28221 +VERTEX2 4393 -29.4152 -82.7701 -2.30103 +VERTEX2 4394 -30.0295 -83.4412 -2.29654 +VERTEX2 4395 -30.6438 -84.1743 -2.29001 +VERTEX2 4396 -31.3691 -83.5564 2.41231 +VERTEX2 4397 -32.0733 -82.9044 2.41075 +VERTEX2 4398 -32.7996 -82.2719 2.40232 +VERTEX2 4399 -33.4681 -81.5871 2.39213 +VERTEX2 4400 -34.1906 -80.8955 2.38138 +VERTEX2 4401 -34.821 -81.5795 -2.32454 +VERTEX2 4402 -35.4117 -82.291 -2.34623 +VERTEX2 4403 -36.193 -83.0053 -2.32109 +VERTEX2 4404 -36.9463 -83.719 -2.35975 +VERTEX2 4405 -37.6289 -84.536 -2.36403 +VERTEX2 4406 -36.8903 -85.2766 -0.78333 +VERTEX2 4407 -36.2034 -86.0543 -0.809139 +VERTEX2 4408 -35.558 -86.7535 -0.801363 +VERTEX2 4409 -34.9376 -87.4975 -0.778788 +VERTEX2 4410 -34.2025 -88.1883 -0.757113 +VERTEX2 4411 -33.4872 -87.4905 0.853393 +VERTEX2 4412 -32.7637 -86.6054 0.86628 +VERTEX2 4413 -32.1735 -85.882 0.860267 +VERTEX2 4414 -31.5111 -85.097 0.874001 +VERTEX2 4415 -30.8915 -84.3057 0.875594 +VERTEX2 4416 -31.5659 -83.6311 2.45972 +VERTEX2 4417 -32.369 -83.0899 2.48185 +VERTEX2 4418 -33.2184 -82.6183 2.50677 +VERTEX2 4419 -34.0402 -82.0229 2.47857 +VERTEX2 4420 -34.8646 -81.409 2.49854 +VERTEX2 4421 -35.4548 -82.1907 -2.21126 +VERTEX2 4422 -36.0803 -82.9734 -2.2038 +VERTEX2 4423 -36.7219 -83.8545 -2.20445 +VERTEX2 4424 -37.2561 -84.7594 -2.19964 +VERTEX2 4425 -37.7739 -85.5244 -2.24439 +VERTEX2 4426 -36.9607 -86.1485 -0.667296 +VERTEX2 4427 -36.198 -86.7599 -0.651894 +VERTEX2 4428 -35.4394 -87.3129 -0.659286 +VERTEX2 4429 -34.6431 -87.934 -0.705557 +VERTEX2 4430 -33.8762 -88.5981 -0.733869 +VERTEX2 4431 -33.1988 -87.8646 0.86895 +VERTEX2 4432 -32.5464 -87.1383 0.889119 +VERTEX2 4433 -31.8964 -86.4221 0.888804 +VERTEX2 4434 -31.3156 -85.6033 0.912915 +VERTEX2 4435 -30.7111 -84.8058 0.960829 +VERTEX2 4436 -29.9011 -85.4549 -0.61827 +VERTEX2 4437 -29.1028 -86.0122 -0.657102 +VERTEX2 4438 -28.366 -86.5642 -0.675631 +VERTEX2 4439 -27.6508 -87.1536 -0.660583 +VERTEX2 4440 -26.8169 -87.7239 -0.626031 +VERTEX2 4441 -26.1922 -86.845 0.949637 +VERTEX2 4442 -25.6282 -86.077 0.982729 +VERTEX2 4443 -25.0624 -85.2538 0.973405 +VERTEX2 4444 -24.4665 -84.3658 0.955661 +VERTEX2 4445 -23.8254 -83.5533 0.932448 +VERTEX2 4446 -23.0373 -84.1331 -0.627916 +VERTEX2 4447 -22.2069 -84.7 -0.638808 +VERTEX2 4448 -21.4235 -85.2074 -0.676238 +VERTEX2 4449 -20.6463 -85.8148 -0.648836 +VERTEX2 4450 -19.8714 -86.4137 -0.645543 +VERTEX2 4451 -20.4372 -87.1496 -2.2565 +VERTEX2 4452 -21.0244 -87.8806 -2.27524 +VERTEX2 4453 -21.676 -88.7181 -2.2501 +VERTEX2 4454 -22.2917 -89.5528 -2.25354 +VERTEX2 4455 -22.9411 -90.3666 -2.24594 +VERTEX2 4456 -22.1057 -90.94 -0.671131 +VERTEX2 4457 -21.3782 -91.5657 -0.700522 +VERTEX2 4458 -20.6756 -92.2474 -0.718426 +VERTEX2 4459 -19.9266 -92.9952 -0.694664 +VERTEX2 4460 -19.1453 -93.6324 -0.685634 +VERTEX2 4461 -18.4888 -92.8716 0.891202 +VERTEX2 4462 -17.9032 -92.0658 0.884984 +VERTEX2 4463 -17.3114 -91.3184 0.885472 +VERTEX2 4464 -16.612 -90.5106 0.844376 +VERTEX2 4465 -15.9585 -89.776 0.846947 +VERTEX2 4466 -16.7882 -89.1362 2.4145 +VERTEX2 4467 -17.6244 -88.4992 2.45267 +VERTEX2 4468 -18.3253 -87.8937 2.44814 +VERTEX2 4469 -19.0911 -87.2282 2.44502 +VERTEX2 4470 -19.9093 -86.5802 2.41475 +VERTEX2 4471 -19.1785 -85.7612 0.848357 +VERTEX2 4472 -18.536 -84.9885 0.866611 +VERTEX2 4473 -17.9044 -84.1825 0.851944 +VERTEX2 4474 -17.1702 -83.4962 0.874874 +VERTEX2 4475 -16.5514 -82.6481 0.900679 +VERTEX2 4476 -17.3041 -82.0512 2.4753 +VERTEX2 4477 -18.0929 -81.4199 2.48019 +VERTEX2 4478 -18.8407 -80.7553 2.41496 +VERTEX2 4479 -19.5926 -80.057 2.41239 +VERTEX2 4480 -20.3524 -79.3377 2.44073 +VERTEX2 4481 -21.0267 -80.0357 -2.24404 +VERTEX2 4482 -21.702 -80.7936 -2.25694 +VERTEX2 4483 -22.3518 -81.5841 -2.28341 +VERTEX2 4484 -22.9831 -82.2936 -2.3281 +VERTEX2 4485 -23.6108 -83.0155 -2.31269 +VERTEX2 4486 -22.8831 -83.7177 -0.731144 +VERTEX2 4487 -22.123 -84.4521 -0.733046 +VERTEX2 4488 -21.3828 -85.1336 -0.762781 +VERTEX2 4489 -20.5874 -85.7406 -0.767872 +VERTEX2 4490 -19.9267 -86.5296 -0.754326 +VERTEX2 4491 -19.2601 -85.8061 0.788398 +VERTEX2 4492 -18.4964 -85.0614 0.783814 +VERTEX2 4493 -17.8372 -84.3895 0.785605 +VERTEX2 4494 -17.0443 -83.7015 0.763778 +VERTEX2 4495 -16.3756 -82.9965 0.731184 +VERTEX2 4496 -15.6813 -83.7187 -0.840228 +VERTEX2 4497 -15.0338 -84.5237 -0.834691 +VERTEX2 4498 -14.4394 -85.2566 -0.829752 +VERTEX2 4499 -13.7896 -86.0582 -0.845836 +VERTEX2 4500 -13.1752 -86.8999 -0.842329 +VERTEX2 4501 -12.4178 -86.1555 0.725955 +VERTEX2 4502 -11.6068 -85.5296 0.737093 +VERTEX2 4503 -10.8475 -84.8579 0.74376 +VERTEX2 4504 -10.1545 -84.0743 0.758851 +VERTEX2 4505 -9.44265 -83.4179 0.746445 +VERTEX2 4506 -8.76199 -84.1969 -0.827657 +VERTEX2 4507 -8.09574 -84.9174 -0.819086 +VERTEX2 4508 -7.48481 -85.6927 -0.856849 +VERTEX2 4509 -6.8467 -86.456 -0.836673 +VERTEX2 4510 -6.30098 -87.1256 -0.852309 +VERTEX2 4511 -5.46384 -86.4435 0.697375 +VERTEX2 4512 -4.66831 -85.8281 0.706946 +VERTEX2 4513 -3.84537 -85.1985 0.681985 +VERTEX2 4514 -3.10259 -84.5965 0.682802 +VERTEX2 4515 -2.3751 -83.9193 0.700893 +VERTEX2 4516 -1.70433 -84.7274 -0.841533 +VERTEX2 4517 -1.12295 -85.51 -0.884854 +VERTEX2 4518 -0.544769 -86.2382 -0.858699 +VERTEX2 4519 0.0824264 -86.9886 -0.870519 +VERTEX2 4520 0.731336 -87.7728 -0.892907 +VERTEX2 4521 1.55816 -87.1204 0.679078 +VERTEX2 4522 2.33454 -86.5235 0.716889 +VERTEX2 4523 3.06102 -85.8896 0.685068 +VERTEX2 4524 3.79424 -85.2264 0.695751 +VERTEX2 4525 4.57751 -84.5995 0.639292 +VERTEX2 4526 3.92726 -83.7977 2.18447 +VERTEX2 4527 3.38379 -82.9252 2.17486 +VERTEX2 4528 2.82601 -82.1096 2.15452 +VERTEX2 4529 2.27309 -81.2597 2.1669 +VERTEX2 4530 1.75381 -80.5234 2.1772 +VERTEX2 4531 0.927351 -81.1598 -2.53054 +VERTEX2 4532 0.130743 -81.6842 -2.5539 +VERTEX2 4533 -0.715718 -82.3209 -2.56492 +VERTEX2 4534 -1.54744 -82.8071 -2.54899 +VERTEX2 4535 -2.31324 -83.3792 -2.5413 +VERTEX2 4536 -2.89855 -82.3762 2.16221 +VERTEX2 4537 -3.47839 -81.4749 2.12722 +VERTEX2 4538 -3.98716 -80.655 2.11293 +VERTEX2 4539 -4.49994 -79.8067 2.09354 +VERTEX2 4540 -4.96523 -79.0444 2.12367 +VERTEX2 4541 -4.19679 -78.5371 0.584331 +VERTEX2 4542 -3.46732 -77.977 0.553321 +VERTEX2 4543 -2.62207 -77.4658 0.602283 +VERTEX2 4544 -1.78578 -76.9461 0.606245 +VERTEX2 4545 -0.93947 -76.3551 0.638649 +VERTEX2 4546 -0.264753 -77.1137 -0.909252 +VERTEX2 4547 0.292116 -77.949 -0.897573 +VERTEX2 4548 0.894728 -78.771 -0.890128 +VERTEX2 4549 1.54349 -79.5354 -0.877406 +VERTEX2 4550 2.1873 -80.2603 -0.889359 +VERTEX2 4551 2.96231 -79.7069 0.67384 +VERTEX2 4552 3.77783 -79.0339 0.663122 +VERTEX2 4553 4.51526 -78.4837 0.661175 +VERTEX2 4554 5.30474 -77.9054 0.657046 +VERTEX2 4555 6.17931 -77.2552 0.641877 +VERTEX2 4556 5.64363 -76.3852 2.19992 +VERTEX2 4557 5.12521 -75.6291 2.19172 +VERTEX2 4558 4.61508 -74.7973 2.18288 +VERTEX2 4559 3.97906 -74.0987 2.16264 +VERTEX2 4560 3.38282 -73.2845 2.17069 +VERTEX2 4561 4.15522 -72.7005 0.600738 +VERTEX2 4562 4.9692 -72.0952 0.601081 +VERTEX2 4563 5.84279 -71.6241 0.619497 +VERTEX2 4564 6.71578 -71.018 0.563748 +VERTEX2 4565 7.59933 -70.4636 0.518723 +VERTEX2 4566 7.08161 -69.6054 2.08534 +VERTEX2 4567 6.61062 -68.736 2.07305 +VERTEX2 4568 6.07694 -67.8982 2.04921 +VERTEX2 4569 5.58968 -66.9754 2.03158 +VERTEX2 4570 5.13362 -66.0713 2.06391 +VERTEX2 4571 6.0895 -65.5258 0.502978 +VERTEX2 4572 6.93286 -65.0568 0.498812 +VERTEX2 4573 7.81205 -64.5499 0.506541 +VERTEX2 4574 8.84211 -64.1457 0.512971 +VERTEX2 4575 9.70149 -63.6385 0.491431 +VERTEX2 4576 9.28143 -62.7869 2.04309 +VERTEX2 4577 8.83192 -61.974 2.02953 +VERTEX2 4578 8.38138 -61.0625 1.99308 +VERTEX2 4579 7.89798 -60.1395 1.998 +VERTEX2 4580 7.43134 -59.2112 1.95176 +VERTEX2 4581 6.46858 -59.5543 -2.74253 +VERTEX2 4582 5.58059 -59.9543 -2.73008 +VERTEX2 4583 4.69768 -60.3711 -2.6992 +VERTEX2 4584 3.82068 -60.6714 -2.69089 +VERTEX2 4585 2.90371 -61.1851 -2.67772 +VERTEX2 4586 2.39628 -60.3054 2.01744 +VERTEX2 4587 1.87578 -59.4554 1.99571 +VERTEX2 4588 1.41844 -58.4666 1.96094 +VERTEX2 4589 0.993352 -57.5218 1.93309 +VERTEX2 4590 0.675446 -56.4727 1.92149 +VERTEX2 4591 -0.16024 -56.7913 -2.77123 +VERTEX2 4592 -1.11711 -57.2123 -2.75393 +VERTEX2 4593 -2.13043 -57.6608 -2.75768 +VERTEX2 4594 -2.97284 -57.9603 -2.77372 +VERTEX2 4595 -3.90578 -58.2854 -2.76705 +VERTEX2 4596 -4.29221 -57.4706 1.90668 +VERTEX2 4597 -4.61886 -56.585 1.89944 +VERTEX2 4598 -5.0126 -55.6382 1.91289 +VERTEX2 4599 -5.3695 -54.6343 1.90099 +VERTEX2 4600 -5.69238 -53.7316 1.93618 +VERTEX2 4601 -4.71613 -53.4057 0.385605 +VERTEX2 4602 -3.75691 -53.0574 0.370093 +VERTEX2 4603 -2.84302 -52.7619 0.382025 +VERTEX2 4604 -1.87573 -52.5004 0.367617 +VERTEX2 4605 -0.977609 -52.1337 0.404191 +VERTEX2 4606 -1.41656 -51.2672 1.95543 +VERTEX2 4607 -1.78541 -50.3929 1.94483 +VERTEX2 4608 -2.15439 -49.5345 1.96078 +VERTEX2 4609 -2.56918 -48.5546 1.93573 +VERTEX2 4610 -2.9886 -47.6302 1.95354 +VERTEX2 4611 -3.83921 -48.0021 -2.76442 +VERTEX2 4612 -4.81848 -48.4525 -2.75438 +VERTEX2 4613 -5.8616 -48.8571 -2.76066 +VERTEX2 4614 -6.72558 -49.253 -2.7615 +VERTEX2 4615 -7.71275 -49.5686 -2.73956 +VERTEX2 4616 -7.27194 -50.5351 -1.18605 +VERTEX2 4617 -6.99526 -51.4742 -1.17441 +VERTEX2 4618 -6.49719 -52.3786 -1.14518 +VERTEX2 4619 -6.21371 -53.3982 -1.16007 +VERTEX2 4620 -5.84352 -54.3833 -1.15768 +VERTEX2 4621 -4.89847 -54.0185 0.436467 +VERTEX2 4622 -3.99105 -53.5821 0.430282 +VERTEX2 4623 -3.05184 -53.1625 0.42224 +VERTEX2 4624 -2.1167 -52.7544 0.426447 +VERTEX2 4625 -1.2584 -52.2731 0.401427 +VERTEX2 4626 -0.858725 -53.2118 -1.18909 +VERTEX2 4627 -0.469725 -54.1355 -1.18166 +VERTEX2 4628 -0.0816834 -55.0376 -1.1496 +VERTEX2 4629 0.309221 -55.9694 -1.142 +VERTEX2 4630 0.671203 -56.8424 -1.12314 +VERTEX2 4631 -0.296558 -57.263 -2.70041 +VERTEX2 4632 -1.25238 -57.6645 -2.68943 +VERTEX2 4633 -2.11817 -58.0963 -2.69178 +VERTEX2 4634 -3.01174 -58.656 -2.68904 +VERTEX2 4635 -3.9144 -59.111 -2.69954 +VERTEX2 4636 -3.51493 -59.9935 -1.1483 +VERTEX2 4637 -2.97555 -60.9252 -1.18528 +VERTEX2 4638 -2.56582 -61.8597 -1.20914 +VERTEX2 4639 -2.18361 -62.7722 -1.17114 +VERTEX2 4640 -1.73034 -63.804 -1.15689 +VERTEX2 4641 -0.909525 -63.462 0.414082 +VERTEX2 4642 -0.04002 -63.0987 0.390082 +VERTEX2 4643 0.887549 -62.6675 0.414766 +VERTEX2 4644 1.7798 -62.2152 0.421196 +VERTEX2 4645 2.74545 -61.7821 0.426104 +VERTEX2 4646 2.32959 -60.8933 2.03886 +VERTEX2 4647 1.90849 -59.986 2.03219 +VERTEX2 4648 1.45972 -58.9989 2.02045 +VERTEX2 4649 1.05339 -58.1347 2.005 +VERTEX2 4650 0.703692 -57.3257 2.00976 +VERTEX2 4651 -0.239886 -57.7882 -2.7159 +VERTEX2 4652 -1.2038 -58.1971 -2.70411 +VERTEX2 4653 -2.16989 -58.6247 -2.70869 +VERTEX2 4654 -3.06354 -59.0183 -2.70637 +VERTEX2 4655 -3.91195 -59.4154 -2.68448 +VERTEX2 4656 -3.62848 -60.282 -1.0932 +VERTEX2 4657 -3.0935 -61.1895 -1.10202 +VERTEX2 4658 -2.69546 -62.1105 -1.11488 +VERTEX2 4659 -2.29465 -62.9886 -1.1056 +VERTEX2 4660 -1.94673 -63.9662 -1.13359 +VERTEX2 4661 -1.03186 -63.6483 0.438671 +VERTEX2 4662 -0.245867 -63.196 0.445162 +VERTEX2 4663 0.749226 -62.8264 0.452546 +VERTEX2 4664 1.70221 -62.3752 0.467176 +VERTEX2 4665 2.57127 -61.9144 0.431775 +VERTEX2 4666 2.98338 -62.8286 -1.13456 +VERTEX2 4667 3.42339 -63.7427 -1.14293 +VERTEX2 4668 3.85253 -64.5892 -1.08924 +VERTEX2 4669 4.3217 -65.436 -1.07383 +VERTEX2 4670 4.78402 -66.3795 -1.05524 +VERTEX2 4671 5.62355 -65.8151 0.52958 +VERTEX2 4672 6.4842 -65.2995 0.544705 +VERTEX2 4673 7.41305 -64.8096 0.554843 +VERTEX2 4674 8.30044 -64.3197 0.550927 +VERTEX2 4675 9.11053 -63.7371 0.520576 +VERTEX2 4676 8.56385 -62.8893 2.08083 +VERTEX2 4677 8.1226 -61.993 2.10643 +VERTEX2 4678 7.60934 -61.1674 2.12334 +VERTEX2 4679 7.00699 -60.3809 2.11486 +VERTEX2 4680 6.50064 -59.5698 2.10874 +VERTEX2 4681 5.61198 -60.0808 -2.58517 +VERTEX2 4682 4.76397 -60.6674 -2.58208 +VERTEX2 4683 3.92567 -61.1387 -2.59254 +VERTEX2 4684 3.07833 -61.6221 -2.61705 +VERTEX2 4685 2.25405 -62.1226 -2.61103 +VERTEX2 4686 2.62805 -62.963 -1.037 +VERTEX2 4687 3.15716 -63.8296 -1.02195 +VERTEX2 4688 3.72116 -64.7134 -1.03469 +VERTEX2 4689 4.27108 -65.6426 -1.04093 +VERTEX2 4690 4.75841 -66.5534 -1.01918 +VERTEX2 4691 5.49935 -65.9898 0.554139 +VERTEX2 4692 6.3196 -65.4473 0.571166 +VERTEX2 4693 7.21672 -64.9016 0.535356 +VERTEX2 4694 8.14301 -64.4705 0.537786 +VERTEX2 4695 8.95996 -63.8646 0.563509 +VERTEX2 4696 8.35403 -63.0158 2.14957 +VERTEX2 4697 7.7547 -62.1122 2.13501 +VERTEX2 4698 7.28118 -61.3217 2.10564 +VERTEX2 4699 6.77312 -60.5619 2.10465 +VERTEX2 4700 6.19015 -59.7586 2.10337 +VERTEX2 4701 5.29959 -60.2797 -2.61252 +VERTEX2 4702 4.49123 -60.8251 -2.62773 +VERTEX2 4703 3.56332 -61.3688 -2.63495 +VERTEX2 4704 2.67247 -61.9215 -2.64297 +VERTEX2 4705 1.79411 -62.4124 -2.62452 +VERTEX2 4706 1.27678 -61.6332 2.07761 +VERTEX2 4707 0.698814 -60.6849 2.11911 +VERTEX2 4708 0.201039 -59.8621 2.10618 +VERTEX2 4709 -0.261157 -58.9968 2.11423 +VERTEX2 4710 -0.779909 -58.1206 2.14341 +VERTEX2 4711 0.0479509 -57.6472 0.595683 +VERTEX2 4712 0.899512 -57.1176 0.624674 +VERTEX2 4713 1.73052 -56.4797 0.596791 +VERTEX2 4714 2.58559 -55.8811 0.592237 +VERTEX2 4715 3.513 -55.292 0.587109 +VERTEX2 4716 2.95882 -54.5077 2.15108 +VERTEX2 4717 2.3639 -53.6557 2.15476 +VERTEX2 4718 1.82969 -52.7473 2.17347 +VERTEX2 4719 1.31028 -51.8695 2.1875 +VERTEX2 4720 0.635333 -51.1004 2.2158 +VERTEX2 4721 1.43785 -50.5294 0.645777 +VERTEX2 4722 2.35269 -49.9218 0.626871 +VERTEX2 4723 3.20017 -49.3471 0.612349 +VERTEX2 4724 4.03635 -48.8068 0.617581 +VERTEX2 4725 4.77278 -48.2046 0.593099 +VERTEX2 4726 4.22959 -47.3837 2.15867 +VERTEX2 4727 3.6987 -46.527 2.19207 +VERTEX2 4728 3.13249 -45.6757 2.20497 +VERTEX2 4729 2.58012 -44.8136 2.19131 +VERTEX2 4730 2.00264 -44.0223 2.1977 +VERTEX2 4731 1.19752 -44.6038 -2.51277 +VERTEX2 4732 0.375092 -45.1516 -2.53075 +VERTEX2 4733 -0.36446 -45.6968 -2.53352 +VERTEX2 4734 -1.21002 -46.3134 -2.54622 +VERTEX2 4735 -2.02643 -46.8075 -2.55997 +VERTEX2 4736 -2.55473 -46.002 2.16764 +VERTEX2 4737 -3.11306 -45.1966 2.13837 +VERTEX2 4738 -3.70263 -44.3496 2.16416 +VERTEX2 4739 -4.30107 -43.5139 2.17585 +VERTEX2 4740 -4.86705 -42.6886 2.21817 +VERTEX2 4741 -5.63988 -43.3227 -2.50503 +VERTEX2 4742 -6.50902 -43.8631 -2.5172 +VERTEX2 4743 -7.34817 -44.4365 -2.53151 +VERTEX2 4744 -8.16539 -44.9684 -2.52552 +VERTEX2 4745 -9.00938 -45.5048 -2.50075 +VERTEX2 4746 -8.49057 -46.2803 -0.919025 +VERTEX2 4747 -7.93722 -47.0818 -0.906064 +VERTEX2 4748 -7.33856 -47.8939 -0.925139 +VERTEX2 4749 -6.71571 -48.6997 -0.884337 +VERTEX2 4750 -6.03973 -49.4607 -0.910685 +VERTEX2 4751 -5.25421 -48.8406 0.696258 +VERTEX2 4752 -4.47401 -48.2067 0.691408 +VERTEX2 4753 -3.64071 -47.5385 0.681243 +VERTEX2 4754 -2.86022 -46.8322 0.669474 +VERTEX2 4755 -2.05962 -46.1932 0.688112 +VERTEX2 4756 -1.46789 -47.0605 -0.869649 +VERTEX2 4757 -0.785849 -47.9092 -0.904679 +VERTEX2 4758 -0.210626 -48.6906 -0.894866 +VERTEX2 4759 0.494879 -49.476 -0.913067 +VERTEX2 4760 1.17655 -50.2543 -0.926645 +VERTEX2 4761 1.9042 -49.6826 0.662213 +VERTEX2 4762 2.65657 -49.0963 0.661173 +VERTEX2 4763 3.44721 -48.5402 0.683902 +VERTEX2 4764 4.15708 -47.8568 0.702786 +VERTEX2 4765 4.90126 -47.2595 0.676911 +VERTEX2 4766 5.6409 -48.0444 -0.927351 +VERTEX2 4767 6.15561 -48.7672 -0.893006 +VERTEX2 4768 6.85517 -49.5343 -0.861239 +VERTEX2 4769 7.46924 -50.32 -0.83282 +VERTEX2 4770 8.09461 -51.0328 -0.856446 +VERTEX2 4771 8.83177 -50.3451 0.739283 +VERTEX2 4772 9.6306 -49.6535 0.744455 +VERTEX2 4773 10.3428 -48.9323 0.754012 +VERTEX2 4774 11.0089 -48.2896 0.732999 +VERTEX2 4775 11.7535 -47.6744 0.708544 +VERTEX2 4776 12.4033 -48.3204 -0.856677 +VERTEX2 4777 13.0846 -49.1147 -0.894237 +VERTEX2 4778 13.6779 -49.9275 -0.892589 +VERTEX2 4779 14.3553 -50.7347 -0.903454 +VERTEX2 4780 14.9957 -51.5874 -0.911216 +VERTEX2 4781 14.1731 -52.2515 -2.48903 +VERTEX2 4782 13.3637 -52.8489 -2.46244 +VERTEX2 4783 12.5443 -53.4838 -2.48074 +VERTEX2 4784 11.7015 -54.0938 -2.48646 +VERTEX2 4785 10.8393 -54.6026 -2.47534 +VERTEX2 4786 11.524 -55.4737 -0.888157 +VERTEX2 4787 12.1474 -56.2861 -0.90858 +VERTEX2 4788 12.7742 -57.1483 -0.948152 +VERTEX2 4789 13.2866 -57.9439 -0.959259 +VERTEX2 4790 13.8149 -58.7279 -0.972061 +VERTEX2 4791 14.7029 -58.1544 0.608171 +VERTEX2 4792 15.6157 -57.5859 0.592592 +VERTEX2 4793 16.4004 -57.0504 0.607535 +VERTEX2 4794 17.2573 -56.4905 0.621936 +VERTEX2 4795 18.0024 -55.8826 0.613564 +VERTEX2 4796 17.425 -55.0492 2.18607 +VERTEX2 4797 16.8428 -54.1825 2.17231 +VERTEX2 4798 16.2475 -53.3699 2.21069 +VERTEX2 4799 15.6443 -52.5837 2.19949 +VERTEX2 4800 15.0764 -51.7869 2.20251 +VERTEX2 4801 14.336 -52.3636 -2.53969 +VERTEX2 4802 13.5083 -52.8175 -2.53837 +VERTEX2 4803 12.7584 -53.3159 -2.54003 +VERTEX2 4804 11.9161 -53.8939 -2.50387 +VERTEX2 4805 11.1222 -54.4864 -2.53169 +VERTEX2 4806 10.5512 -53.6959 2.1776 +VERTEX2 4807 10.0935 -52.9434 2.21271 +VERTEX2 4808 9.44955 -52.1659 2.23726 +VERTEX2 4809 8.87601 -51.4052 2.22694 +VERTEX2 4810 8.29738 -50.6236 2.25878 +VERTEX2 4811 7.4936 -51.3214 -2.46511 +VERTEX2 4812 6.73383 -52.0244 -2.47772 +VERTEX2 4813 5.91676 -52.6173 -2.46022 +VERTEX2 4814 5.07058 -53.2566 -2.44164 +VERTEX2 4815 4.35167 -53.9258 -2.40112 +VERTEX2 4816 4.99035 -54.7474 -0.820758 +VERTEX2 4817 5.74207 -55.5495 -0.808265 +VERTEX2 4818 6.40362 -56.2297 -0.814156 +VERTEX2 4819 7.12629 -56.876 -0.826015 +VERTEX2 4820 7.773 -57.6642 -0.815631 +VERTEX2 4821 8.54097 -56.9821 0.771491 +VERTEX2 4822 9.2545 -56.218 0.810141 +VERTEX2 4823 9.90638 -55.5055 0.812337 +VERTEX2 4824 10.6525 -54.7186 0.845559 +VERTEX2 4825 11.2934 -53.9233 0.852013 +VERTEX2 4826 10.5366 -53.2577 2.37933 +VERTEX2 4827 9.87136 -52.5955 2.37858 +VERTEX2 4828 9.19526 -51.884 2.3642 +VERTEX2 4829 8.4794 -51.1127 2.38033 +VERTEX2 4830 7.7473 -50.4371 2.37968 +VERTEX2 4831 7.01943 -51.2374 -2.36331 +VERTEX2 4832 6.32621 -51.9363 -2.36098 +VERTEX2 4833 5.6162 -52.638 -2.36282 +VERTEX2 4834 4.83736 -53.3799 -2.37781 +VERTEX2 4835 4.0728 -54.0309 -2.35909 +VERTEX2 4836 4.74362 -54.6586 -0.790894 +VERTEX2 4837 5.46125 -55.4099 -0.805391 +VERTEX2 4838 6.21003 -56.0923 -0.754499 +VERTEX2 4839 6.95445 -56.8041 -0.784107 +VERTEX2 4840 7.67127 -57.4187 -0.814865 +VERTEX2 4841 8.44327 -56.7499 0.73045 +VERTEX2 4842 9.21262 -56.0658 0.719707 +VERTEX2 4843 9.96986 -55.3688 0.72289 +VERTEX2 4844 10.7518 -54.6678 0.748912 +VERTEX2 4845 11.4991 -53.9967 0.763222 +VERTEX2 4846 12.1644 -54.6979 -0.7675 +VERTEX2 4847 12.7978 -55.365 -0.789533 +VERTEX2 4848 13.5096 -56.092 -0.782393 +VERTEX2 4849 14.1761 -56.819 -0.792532 +VERTEX2 4850 14.8756 -57.4984 -0.770318 +VERTEX2 4851 15.5855 -56.7424 0.799679 +VERTEX2 4852 16.2774 -55.9265 0.811588 +VERTEX2 4853 16.9787 -55.2942 0.815129 +VERTEX2 4854 17.6456 -54.5679 0.795801 +VERTEX2 4855 18.3976 -53.9441 0.779372 +VERTEX2 4856 17.6262 -53.2248 2.35983 +VERTEX2 4857 16.9013 -52.4722 2.33466 +VERTEX2 4858 16.1557 -51.6838 2.3481 +VERTEX2 4859 15.5043 -51.0347 2.37583 +VERTEX2 4860 14.8168 -50.2671 2.35819 +VERTEX2 4861 14.0758 -50.9493 -2.35564 +VERTEX2 4862 13.337 -51.6124 -2.36779 +VERTEX2 4863 12.5821 -52.3466 -2.34866 +VERTEX2 4864 11.8866 -52.9859 -2.37673 +VERTEX2 4865 11.1095 -53.6224 -2.3669 +VERTEX2 4866 11.8939 -54.2818 -0.803851 +VERTEX2 4867 12.6386 -54.9983 -0.790404 +VERTEX2 4868 13.4255 -55.7502 -0.775933 +VERTEX2 4869 14.1933 -56.4216 -0.769147 +VERTEX2 4870 14.8903 -57.1517 -0.773201 +VERTEX2 4871 14.2664 -57.9339 -2.36323 +VERTEX2 4872 13.5362 -58.6011 -2.32607 +VERTEX2 4873 12.7933 -59.3927 -2.34812 +VERTEX2 4874 12.1507 -60.1339 -2.33059 +VERTEX2 4875 11.4792 -60.8643 -2.34039 +VERTEX2 4876 12.2381 -61.5774 -0.76354 +VERTEX2 4877 12.9886 -62.2329 -0.747171 +VERTEX2 4878 13.8296 -63.0406 -0.715293 +VERTEX2 4879 14.5753 -63.7217 -0.693861 +VERTEX2 4880 15.3301 -64.3163 -0.7109 +VERTEX2 4881 14.6914 -65.1827 -2.29213 +VERTEX2 4882 14.0124 -65.9288 -2.3208 +VERTEX2 4883 13.3391 -66.7998 -2.32574 +VERTEX2 4884 12.7042 -67.562 -2.29706 +VERTEX2 4885 11.9699 -68.2611 -2.30849 +VERTEX2 4886 12.7165 -69.0068 -0.673402 +VERTEX2 4887 13.5273 -69.6107 -0.643014 +VERTEX2 4888 14.3173 -70.2111 -0.668204 +VERTEX2 4889 15.1107 -70.7841 -0.671282 +VERTEX2 4890 15.9031 -71.393 -0.660835 +VERTEX2 4891 15.2899 -72.1894 -2.25604 +VERTEX2 4892 14.6854 -72.9398 -2.31585 +VERTEX2 4893 13.9562 -73.6439 -2.2587 +VERTEX2 4894 13.3157 -74.4473 -2.24353 +VERTEX2 4895 12.7538 -75.1825 -2.24875 +VERTEX2 4896 13.5174 -75.7447 -0.687845 +VERTEX2 4897 14.3185 -76.3201 -0.716183 +VERTEX2 4898 15.0618 -76.943 -0.766858 +VERTEX2 4899 15.7312 -77.5594 -0.761389 +VERTEX2 4900 16.3313 -78.2741 -0.753417 +VERTEX2 4901 16.9718 -77.5701 0.810697 +VERTEX2 4902 17.5923 -76.8853 0.805013 +VERTEX2 4903 18.2682 -76.2076 0.804338 +VERTEX2 4904 18.8912 -75.4582 0.783004 +VERTEX2 4905 19.6447 -74.7628 0.806646 +VERTEX2 4906 18.8884 -74.0384 2.39374 +VERTEX2 4907 18.1568 -73.3609 2.38183 +VERTEX2 4908 17.4838 -72.6642 2.37408 +VERTEX2 4909 16.75 -72.0101 2.42599 +VERTEX2 4910 15.8738 -71.3182 2.42204 +VERTEX2 4911 15.1884 -72.0494 -2.24403 +VERTEX2 4912 14.5607 -72.7873 -2.24378 +VERTEX2 4913 13.9142 -73.6338 -2.25969 +VERTEX2 4914 13.3024 -74.5031 -2.25152 +VERTEX2 4915 12.6795 -75.2931 -2.244 +VERTEX2 4916 13.5128 -75.9703 -0.672879 +VERTEX2 4917 14.2837 -76.5983 -0.709836 +VERTEX2 4918 15.0288 -77.2288 -0.691293 +VERTEX2 4919 15.8209 -77.9745 -0.689756 +VERTEX2 4920 16.6453 -78.6214 -0.679345 +VERTEX2 4921 17.2156 -77.7642 0.855711 +VERTEX2 4922 17.8305 -76.9711 0.845869 +VERTEX2 4923 18.48 -76.2347 0.835899 +VERTEX2 4924 19.0382 -75.5453 0.773258 +VERTEX2 4925 19.7402 -74.8596 0.747387 +VERTEX2 4926 19.0624 -74.0739 2.33313 +VERTEX2 4927 18.4133 -73.3469 2.31249 +VERTEX2 4928 17.6773 -72.6191 2.33796 +VERTEX2 4929 16.9719 -71.9275 2.31645 +VERTEX2 4930 16.3365 -71.1128 2.29565 +VERTEX2 4931 15.6137 -71.7684 -2.4215 +VERTEX2 4932 14.8418 -72.3501 -2.43113 +VERTEX2 4933 14.108 -72.9687 -2.4366 +VERTEX2 4934 13.2787 -73.5287 -2.42939 +VERTEX2 4935 12.5675 -74.2118 -2.43457 +VERTEX2 4936 11.889 -73.394 2.28259 +VERTEX2 4937 11.3164 -72.7038 2.29553 +VERTEX2 4938 10.6509 -72.03 2.28307 +VERTEX2 4939 9.9583 -71.244 2.28957 +VERTEX2 4940 9.32599 -70.5192 2.31843 +VERTEX2 4941 10.0578 -69.881 0.732102 +VERTEX2 4942 10.78 -69.2654 0.715239 +VERTEX2 4943 11.5758 -68.6487 0.712107 +VERTEX2 4944 12.3211 -68.0512 0.72646 +VERTEX2 4945 13.0364 -67.3567 0.693861 +VERTEX2 4946 13.675 -68.0862 -0.885859 +VERTEX2 4947 14.3026 -68.8195 -0.900957 +VERTEX2 4948 14.9256 -69.567 -0.89932 +VERTEX2 4949 15.5379 -70.4349 -0.917236 +VERTEX2 4950 16.2334 -71.2196 -0.933464 +VERTEX2 4951 17.0628 -70.611 0.650604 +VERTEX2 4952 17.8291 -69.8847 0.63282 +VERTEX2 4953 18.5583 -69.2884 0.604401 +VERTEX2 4954 19.3546 -68.725 0.640839 +VERTEX2 4955 20.1355 -68.1448 0.64548 +VERTEX2 4956 19.591 -67.3443 2.21779 +VERTEX2 4957 18.9368 -66.5824 2.24477 +VERTEX2 4958 18.3027 -65.7732 2.2227 +VERTEX2 4959 17.6861 -65.0218 2.20357 +VERTEX2 4960 17.1119 -64.2069 2.22626 +VERTEX2 4961 16.2168 -64.821 -2.47028 +VERTEX2 4962 15.4265 -65.491 -2.46023 +VERTEX2 4963 14.6418 -66.0524 -2.45151 +VERTEX2 4964 13.897 -66.6124 -2.47358 +VERTEX2 4965 13.0842 -67.2021 -2.46765 +VERTEX2 4966 12.4399 -66.4183 2.26325 +VERTEX2 4967 11.794 -65.622 2.24364 +VERTEX2 4968 11.2032 -64.8729 2.21493 +VERTEX2 4969 10.6942 -64.0653 2.20831 +VERTEX2 4970 10.055 -63.2202 2.20567 +VERTEX2 4971 10.8565 -62.5952 0.648626 +VERTEX2 4972 11.5761 -61.9939 0.613353 +VERTEX2 4973 12.3223 -61.3803 0.614904 +VERTEX2 4974 13.035 -60.7238 0.607027 +VERTEX2 4975 13.8212 -60.1202 0.615421 +VERTEX2 4976 13.2356 -59.3269 2.18068 +VERTEX2 4977 12.6449 -58.5696 2.19652 +VERTEX2 4978 12.1183 -57.6956 2.18731 +VERTEX2 4979 11.6052 -56.917 2.17333 +VERTEX2 4980 11.0666 -56.0699 2.1977 +VERTEX2 4981 10.2989 -56.6212 -2.50158 +VERTEX2 4982 9.50476 -57.1915 -2.50382 +VERTEX2 4983 8.79153 -57.7131 -2.50885 +VERTEX2 4984 7.97961 -58.2768 -2.50877 +VERTEX2 4985 7.15881 -58.9477 -2.50233 +VERTEX2 4986 6.50519 -58.2517 2.23269 +VERTEX2 4987 5.85992 -57.4072 2.2456 +VERTEX2 4988 5.23486 -56.522 2.26271 +VERTEX2 4989 4.5299 -55.7709 2.24907 +VERTEX2 4990 3.9361 -54.971 2.25064 +VERTEX2 4991 3.11353 -55.6356 -2.50876 +VERTEX2 4992 2.26549 -56.2341 -2.49398 +VERTEX2 4993 1.44627 -56.82 -2.48962 +VERTEX2 4994 0.688531 -57.3415 -2.48786 +VERTEX2 4995 -0.13343 -57.8988 -2.47913 +VERTEX2 4996 0.551213 -58.7567 -0.932949 +VERTEX2 4997 1.10131 -59.4832 -0.926021 +VERTEX2 4998 1.55728 -60.2744 -0.954977 +VERTEX2 4999 2.27321 -61.0033 -0.917979 +VERTEX2 5000 2.8533 -61.7671 -0.925571 +VERTEX2 5001 3.6778 -61.1884 0.649814 +VERTEX2 5002 4.53225 -60.6833 0.663814 +VERTEX2 5003 5.24538 -60.0464 0.662342 +VERTEX2 5004 6.04476 -59.4385 0.654399 +VERTEX2 5005 6.79361 -58.7574 0.677668 +VERTEX2 5006 7.42803 -59.5221 -0.930746 +VERTEX2 5007 8.04681 -60.2788 -0.933136 +VERTEX2 5008 8.76955 -61.1032 -0.887246 +VERTEX2 5009 9.34863 -61.8157 -0.897623 +VERTEX2 5010 10.0189 -62.6573 -0.901867 +VERTEX2 5011 10.8352 -62.0043 0.672716 +VERTEX2 5012 11.5926 -61.4527 0.664797 +VERTEX2 5013 12.3765 -60.9171 0.632973 +VERTEX2 5014 13.1547 -60.2651 0.634288 +VERTEX2 5015 13.9635 -59.6521 0.638012 +VERTEX2 5016 13.3546 -58.891 2.2052 +VERTEX2 5017 12.7439 -58.0651 2.2166 +VERTEX2 5018 12.2337 -57.2706 2.2103 +VERTEX2 5019 11.5824 -56.5188 2.19982 +VERTEX2 5020 10.878 -55.6943 2.17544 +VERTEX2 5021 9.9591 -56.2748 -2.54185 +VERTEX2 5022 9.11242 -56.81 -2.58056 +VERTEX2 5023 8.21724 -57.3071 -2.57699 +VERTEX2 5024 7.38639 -57.8446 -2.59371 +VERTEX2 5025 6.65167 -58.3137 -2.58626 +VERTEX2 5026 6.16101 -57.4939 2.10942 +VERTEX2 5027 5.68711 -56.5643 2.05671 +VERTEX2 5028 5.28765 -55.7294 2.05187 +VERTEX2 5029 4.85949 -54.8503 2.03083 +VERTEX2 5030 4.48141 -53.8812 2.01017 +VERTEX2 5031 3.65193 -54.2256 -2.7053 +VERTEX2 5032 2.6278 -54.682 -2.71054 +VERTEX2 5033 1.67608 -55.0312 -2.70487 +VERTEX2 5034 0.697763 -55.4993 -2.67245 +VERTEX2 5035 -0.237826 -55.8948 -2.66455 +VERTEX2 5036 0.117862 -56.8203 -1.09804 +VERTEX2 5037 0.5763 -57.7286 -1.09672 +VERTEX2 5038 1.06593 -58.579 -1.10353 +VERTEX2 5039 1.48284 -59.42 -1.0822 +VERTEX2 5040 1.87752 -60.2884 -1.11134 +VERTEX2 5041 2.83406 -59.8548 0.477361 +VERTEX2 5042 3.71752 -59.4033 0.479488 +VERTEX2 5043 4.6171 -58.9568 0.492269 +VERTEX2 5044 5.45719 -58.4617 0.501039 +VERTEX2 5045 6.22352 -57.9992 0.48338 +VERTEX2 5046 5.83108 -57.1023 2.05161 +VERTEX2 5047 5.30874 -56.2962 2.04542 +VERTEX2 5048 4.84579 -55.3531 2.05571 +VERTEX2 5049 4.26974 -54.4719 2.05569 +VERTEX2 5050 3.8181 -53.4941 2.04186 +VERTEX2 5051 2.91681 -53.849 -2.6758 +VERTEX2 5052 1.99999 -54.3158 -2.6755 +VERTEX2 5053 1.11403 -54.8233 -2.68864 +VERTEX2 5054 0.224667 -55.3299 -2.67647 +VERTEX2 5055 -0.693033 -55.8644 -2.69626 +VERTEX2 5056 -0.252401 -56.7585 -1.10845 +VERTEX2 5057 0.220464 -57.7084 -1.10836 +VERTEX2 5058 0.725857 -58.702 -1.10928 +VERTEX2 5059 1.16702 -59.5535 -1.10224 +VERTEX2 5060 1.5499 -60.469 -1.10192 +VERTEX2 5061 2.37383 -59.9148 0.452606 +VERTEX2 5062 3.26551 -59.4402 0.460283 +VERTEX2 5063 4.10098 -59.0242 0.463289 +VERTEX2 5064 5.07182 -58.5684 0.457477 +VERTEX2 5065 6.02809 -58.1249 0.461979 +VERTEX2 5066 6.45629 -59.0236 -1.14406 +VERTEX2 5067 6.81709 -59.9271 -1.17194 +VERTEX2 5068 7.24216 -60.7963 -1.14443 +VERTEX2 5069 7.6622 -61.7217 -1.15424 +VERTEX2 5070 8.04508 -62.6144 -1.16832 +VERTEX2 5071 8.94801 -62.284 0.405336 +VERTEX2 5072 9.95382 -61.8347 0.431883 +VERTEX2 5073 10.8634 -61.3819 0.441658 +VERTEX2 5074 11.8546 -60.9632 0.466718 +VERTEX2 5075 12.7488 -60.4878 0.468593 +VERTEX2 5076 13.197 -61.2921 -1.11971 +VERTEX2 5077 13.6615 -62.2188 -1.12413 +VERTEX2 5078 14.0456 -63.0749 -1.13543 +VERTEX2 5079 14.4748 -63.9771 -1.11874 +VERTEX2 5080 14.8725 -64.8523 -1.11739 +VERTEX2 5081 15.6613 -64.3677 0.474751 +VERTEX2 5082 16.5124 -63.8878 0.485436 +VERTEX2 5083 17.399 -63.3995 0.505104 +VERTEX2 5084 18.3012 -62.943 0.484434 +VERTEX2 5085 19.2233 -62.4287 0.471356 +VERTEX2 5086 18.8012 -61.5645 2.03011 +VERTEX2 5087 18.3327 -60.6754 2.03297 +VERTEX2 5088 17.933 -59.7146 2.0374 +VERTEX2 5089 17.408 -58.8273 2.08809 +VERTEX2 5090 16.9361 -57.8785 2.08827 +VERTEX2 5091 17.7807 -57.4093 0.532814 +VERTEX2 5092 18.6081 -56.9586 0.530842 +VERTEX2 5093 19.4939 -56.4625 0.538829 +VERTEX2 5094 20.3594 -55.9607 0.544952 +VERTEX2 5095 21.2885 -55.3936 0.531396 +VERTEX2 5096 20.8032 -54.5173 2.12038 +VERTEX2 5097 20.2474 -53.7582 2.12813 +VERTEX2 5098 19.7729 -52.7935 2.12658 +VERTEX2 5099 19.2862 -51.8976 2.15092 +VERTEX2 5100 18.7813 -51.04 2.16296 +VERTEX2 5101 17.8953 -51.5497 -2.55606 +VERTEX2 5102 17.0433 -52.1224 -2.56112 +VERTEX2 5103 16.1616 -52.6536 -2.5812 +VERTEX2 5104 15.2876 -53.24 -2.55826 +VERTEX2 5105 14.367 -53.7054 -2.62608 +VERTEX2 5106 14.8485 -54.5074 -1.09338 +VERTEX2 5107 15.3695 -55.3995 -1.0707 +VERTEX2 5108 15.8102 -56.2145 -1.1024 +VERTEX2 5109 16.3023 -57.1641 -1.13103 +VERTEX2 5110 16.6529 -58.0812 -1.09236 +VERTEX2 5111 17.5421 -57.6137 0.444075 +VERTEX2 5112 18.4457 -57.2429 0.42371 +VERTEX2 5113 19.414 -56.8383 0.447015 +VERTEX2 5114 20.3305 -56.4917 0.431146 +VERTEX2 5115 21.2229 -56.1061 0.422809 +VERTEX2 5116 21.6926 -56.9208 -1.12527 +VERTEX2 5117 22.1493 -57.748 -1.09981 +VERTEX2 5118 22.5769 -58.672 -1.08605 +VERTEX2 5119 23.1006 -59.5399 -1.0454 +VERTEX2 5120 23.6247 -60.3659 -1.06763 +VERTEX2 5121 24.5107 -59.8432 0.507138 +VERTEX2 5122 25.4375 -59.3354 0.527482 +VERTEX2 5123 26.2886 -58.8817 0.548296 +VERTEX2 5124 27.1807 -58.3557 0.563265 +VERTEX2 5125 28.0098 -57.8734 0.568303 +VERTEX2 5126 27.4637 -57.0586 2.13348 +VERTEX2 5127 26.973 -56.142 2.11837 +VERTEX2 5128 26.4582 -55.2911 2.12094 +VERTEX2 5129 25.9707 -54.4083 2.10876 +VERTEX2 5130 25.3829 -53.7011 2.1546 +VERTEX2 5131 24.5596 -54.2746 -2.54701 +VERTEX2 5132 23.7384 -54.7926 -2.54554 +VERTEX2 5133 22.8738 -55.3931 -2.52673 +VERTEX2 5134 21.9996 -55.9463 -2.54453 +VERTEX2 5135 21.2219 -56.5404 -2.55121 +VERTEX2 5136 20.676 -55.6796 2.19046 +VERTEX2 5137 20.1158 -54.8246 2.18479 +VERTEX2 5138 19.5725 -53.9507 2.21319 +VERTEX2 5139 18.9164 -53.1277 2.19157 +VERTEX2 5140 18.2696 -52.4009 2.18325 +VERTEX2 5141 17.5097 -52.9245 -2.51782 +VERTEX2 5142 16.7134 -53.5159 -2.55477 +VERTEX2 5143 15.8501 -54.0073 -2.5318 +VERTEX2 5144 14.9684 -54.5984 -2.5719 +VERTEX2 5145 14.1205 -55.2551 -2.59282 +VERTEX2 5146 14.6137 -56.0884 -0.996661 +VERTEX2 5147 15.0905 -56.941 -0.983541 +VERTEX2 5148 15.6879 -57.7605 -0.981511 +VERTEX2 5149 16.2318 -58.5985 -1.00648 +VERTEX2 5150 16.8238 -59.3949 -0.99481 +VERTEX2 5151 17.6487 -58.8154 0.579106 +VERTEX2 5152 18.5168 -58.3005 0.534854 +VERTEX2 5153 19.3869 -57.8063 0.5057 +VERTEX2 5154 20.14 -57.2397 0.503887 +VERTEX2 5155 21.1175 -56.7255 0.508323 +VERTEX2 5156 20.682 -55.8323 2.08413 +VERTEX2 5157 20.1761 -54.9766 2.11738 +VERTEX2 5158 19.6691 -54.1525 2.14498 +VERTEX2 5159 19.0847 -53.2775 2.16736 +VERTEX2 5160 18.4616 -52.4442 2.19244 +VERTEX2 5161 19.2183 -51.9363 0.636296 +VERTEX2 5162 20.0305 -51.3913 0.638798 +VERTEX2 5163 20.8207 -50.8001 0.65211 +VERTEX2 5164 21.6191 -50.1217 0.639714 +VERTEX2 5165 22.4506 -49.4262 0.672179 +VERTEX2 5166 23.0877 -50.2876 -0.85461 +VERTEX2 5167 23.8446 -50.9783 -0.836466 +VERTEX2 5168 24.5407 -51.7009 -0.860448 +VERTEX2 5169 25.1843 -52.5372 -0.904741 +VERTEX2 5170 25.8959 -53.2671 -0.866374 +VERTEX2 5171 26.6028 -52.568 0.709843 +VERTEX2 5172 27.2948 -51.8906 0.689844 +VERTEX2 5173 28.0927 -51.2303 0.659767 +VERTEX2 5174 28.8638 -50.5343 0.663098 +VERTEX2 5175 29.588 -49.9973 0.658137 +VERTEX2 5176 30.2303 -50.6521 -0.91766 +VERTEX2 5177 30.8341 -51.4776 -0.912771 +VERTEX2 5178 31.4519 -52.2893 -0.92422 +VERTEX2 5179 31.9834 -53.0707 -0.924689 +VERTEX2 5180 32.6078 -53.9642 -0.910857 +VERTEX2 5181 33.373 -53.3311 0.672085 +VERTEX2 5182 34.1654 -52.7649 0.643956 +VERTEX2 5183 34.9008 -52.1252 0.674701 +VERTEX2 5184 35.6299 -51.5813 0.674542 +VERTEX2 5185 36.4729 -50.9261 0.687491 +VERTEX2 5186 35.7625 -50.2289 2.25241 +VERTEX2 5187 35.1933 -49.4426 2.26558 +VERTEX2 5188 34.5436 -48.6978 2.30003 +VERTEX2 5189 33.8595 -47.9264 2.30285 +VERTEX2 5190 33.1609 -47.1657 2.27892 +VERTEX2 5191 32.3696 -47.7933 -2.45005 +VERTEX2 5192 31.5636 -48.3545 -2.44927 +VERTEX2 5193 30.7573 -49.0331 -2.45287 +VERTEX2 5194 29.9527 -49.6562 -2.45622 +VERTEX2 5195 29.1217 -50.2181 -2.46536 +VERTEX2 5196 29.7201 -50.8884 -0.903007 +VERTEX2 5197 30.2958 -51.6511 -0.90348 +VERTEX2 5198 30.9055 -52.4189 -0.926583 +VERTEX2 5199 31.5672 -53.2526 -0.928863 +VERTEX2 5200 32.2312 -54.1135 -0.932249 +VERTEX2 5201 33.0567 -53.5213 0.630502 +VERTEX2 5202 33.9014 -52.9015 0.600752 +VERTEX2 5203 34.712 -52.3313 0.597881 +VERTEX2 5204 35.5661 -51.7192 0.605347 +VERTEX2 5205 36.4439 -51.2478 0.634483 +VERTEX2 5206 35.8348 -50.4147 2.16991 +VERTEX2 5207 35.2179 -49.598 2.14944 +VERTEX2 5208 34.5907 -48.7906 2.15595 +VERTEX2 5209 34.1072 -47.8951 2.17479 +VERTEX2 5210 33.5526 -47.0086 2.17682 +VERTEX2 5211 32.7741 -47.5261 -2.5245 +VERTEX2 5212 31.9571 -48.1101 -2.53771 +VERTEX2 5213 31.1117 -48.6028 -2.53391 +VERTEX2 5214 30.3024 -49.1743 -2.54626 +VERTEX2 5215 29.5549 -49.7494 -2.5214 +VERTEX2 5216 28.9586 -48.9273 2.17834 +VERTEX2 5217 28.316 -48.043 2.20522 +VERTEX2 5218 27.7377 -47.2807 2.19904 +VERTEX2 5219 27.1633 -46.5688 2.22185 +VERTEX2 5220 26.4828 -45.7238 2.20444 +VERTEX2 5221 25.6793 -46.2269 -2.47634 +VERTEX2 5222 24.921 -46.8066 -2.48976 +VERTEX2 5223 24.0872 -47.4109 -2.48839 +VERTEX2 5224 23.3081 -48.0329 -2.46365 +VERTEX2 5225 22.4416 -48.6465 -2.45619 +VERTEX2 5226 21.7899 -47.8544 2.26129 +VERTEX2 5227 21.0476 -47.1553 2.27207 +VERTEX2 5228 20.453 -46.3569 2.29958 +VERTEX2 5229 19.7946 -45.5432 2.33525 +VERTEX2 5230 19.1635 -44.8031 2.35841 +VERTEX2 5231 19.9233 -44.0717 0.798498 +VERTEX2 5232 20.6216 -43.2897 0.786405 +VERTEX2 5233 21.3238 -42.6238 0.824428 +VERTEX2 5234 21.9119 -41.9289 0.818723 +VERTEX2 5235 22.5769 -41.178 0.793992 +VERTEX2 5236 21.8124 -40.5012 2.34555 +VERTEX2 5237 21.0733 -39.7432 2.32683 +VERTEX2 5238 20.4801 -38.9671 2.32903 +VERTEX2 5239 19.7543 -38.2199 2.32909 +VERTEX2 5240 19.0587 -37.4915 2.2874 +VERTEX2 5241 18.3819 -38.1307 -2.42026 +VERTEX2 5242 17.5907 -38.6923 -2.41483 +VERTEX2 5243 16.8768 -39.4066 -2.4077 +VERTEX2 5244 16.1083 -40.1117 -2.40173 +VERTEX2 5245 15.3697 -40.8573 -2.40163 +VERTEX2 5246 16.0719 -41.567 -0.833528 +VERTEX2 5247 16.9033 -42.3673 -0.853071 +VERTEX2 5248 17.4404 -43.1779 -0.870649 +VERTEX2 5249 18.0506 -43.9501 -0.866601 +VERTEX2 5250 18.6831 -44.6963 -0.870933 +VERTEX2 5251 19.4872 -44.0499 0.689968 +VERTEX2 5252 20.2358 -43.4303 0.72517 +VERTEX2 5253 21.0391 -42.7993 0.709845 +VERTEX2 5254 21.753 -42.0749 0.7303 +VERTEX2 5255 22.5544 -41.4569 0.731534 +VERTEX2 5256 23.2163 -42.2302 -0.81977 +VERTEX2 5257 23.9125 -42.8803 -0.828714 +VERTEX2 5258 24.5134 -43.6257 -0.829183 +VERTEX2 5259 25.1681 -44.4343 -0.859932 +VERTEX2 5260 25.8455 -45.2851 -0.862443 +VERTEX2 5261 25.0115 -45.8859 -2.47343 +VERTEX2 5262 24.2945 -46.4733 -2.48466 +VERTEX2 5263 23.4813 -47.03 -2.50459 +VERTEX2 5264 22.6208 -47.6724 -2.49216 +VERTEX2 5265 21.7909 -48.3729 -2.51834 +VERTEX2 5266 22.4105 -49.1454 -0.945124 +VERTEX2 5267 23.0486 -49.8805 -0.925485 +VERTEX2 5268 23.7042 -50.543 -0.892167 +VERTEX2 5269 24.3147 -51.3629 -0.907544 +VERTEX2 5270 24.9619 -52.2227 -0.924486 +VERTEX2 5271 25.7498 -51.6072 0.628993 +VERTEX2 5272 26.4823 -50.9847 0.632859 +VERTEX2 5273 27.3161 -50.3887 0.625573 +VERTEX2 5274 28.0343 -49.7944 0.643618 +VERTEX2 5275 28.8056 -49.225 0.660884 +VERTEX2 5276 28.2434 -48.4885 2.21142 +VERTEX2 5277 27.6807 -47.775 2.22379 +VERTEX2 5278 27.1289 -47.0138 2.23523 +VERTEX2 5279 26.583 -46.1913 2.20782 +VERTEX2 5280 25.9959 -45.429 2.2196 +VERTEX2 5281 25.2107 -46.0178 -2.48952 +VERTEX2 5282 24.4097 -46.6193 -2.50031 +VERTEX2 5283 23.6956 -47.1851 -2.46497 +VERTEX2 5284 22.997 -47.8589 -2.47616 +VERTEX2 5285 22.2926 -48.4383 -2.46002 +VERTEX2 5286 22.9639 -49.2606 -0.860456 +VERTEX2 5287 23.6242 -50.065 -0.866074 +VERTEX2 5288 24.2374 -50.8681 -0.853407 +VERTEX2 5289 24.9184 -51.6618 -0.88285 +VERTEX2 5290 25.6032 -52.5128 -0.914106 +VERTEX2 5291 26.3385 -51.907 0.671935 +VERTEX2 5292 27.1618 -51.2359 0.653954 +VERTEX2 5293 27.8954 -50.6979 0.655867 +VERTEX2 5294 28.6853 -50.0789 0.656417 +VERTEX2 5295 29.4446 -49.5525 0.644098 +VERTEX2 5296 28.8684 -48.6843 2.20715 +VERTEX2 5297 28.266 -47.8655 2.18583 +VERTEX2 5298 27.6471 -46.9523 2.15254 +VERTEX2 5299 27.1355 -46.2676 2.17497 +VERTEX2 5300 26.514 -45.5127 2.18546 +VERTEX2 5301 27.2821 -45.0246 0.595726 +VERTEX2 5302 28.2185 -44.3933 0.58769 +VERTEX2 5303 29.1064 -43.9073 0.55446 +VERTEX2 5304 29.9569 -43.3437 0.590725 +VERTEX2 5305 30.7575 -42.8088 0.59359 +VERTEX2 5306 30.198 -41.995 2.15999 +VERTEX2 5307 29.5977 -41.069 2.19613 +VERTEX2 5308 28.9979 -40.334 2.1811 +VERTEX2 5309 28.4174 -39.5401 2.17811 +VERTEX2 5310 27.774 -38.7326 2.219 +VERTEX2 5311 26.9544 -39.3306 -2.49614 +VERTEX2 5312 26.1231 -39.9 -2.46364 +VERTEX2 5313 25.3296 -40.552 -2.45551 +VERTEX2 5314 24.5767 -41.1852 -2.46935 +VERTEX2 5315 23.845 -41.8369 -2.45778 +VERTEX2 5316 23.2706 -40.9771 2.25749 +VERTEX2 5317 22.5758 -40.1955 2.2513 +VERTEX2 5318 22.026 -39.3989 2.25789 +VERTEX2 5319 21.3995 -38.5252 2.2709 +VERTEX2 5320 20.6788 -37.7863 2.24343 +VERTEX2 5321 19.8765 -38.4169 -2.46364 +VERTEX2 5322 18.9908 -39.0289 -2.45386 +VERTEX2 5323 18.1559 -39.601 -2.43026 +VERTEX2 5324 17.358 -40.2174 -2.43479 +VERTEX2 5325 16.6067 -40.8186 -2.40988 +VERTEX2 5326 15.922 -40.1023 2.29284 +VERTEX2 5327 15.2509 -39.4067 2.27704 +VERTEX2 5328 14.5944 -38.7101 2.30233 +VERTEX2 5329 13.9065 -38.0524 2.31773 +VERTEX2 5330 13.2392 -37.3103 2.30504 +VERTEX2 5331 12.5581 -38.0054 -2.37346 +VERTEX2 5332 11.7823 -38.7634 -2.3858 +VERTEX2 5333 11.0727 -39.4436 -2.37791 +VERTEX2 5334 10.356 -40.1111 -2.33705 +VERTEX2 5335 9.73764 -40.7658 -2.33468 +VERTEX2 5336 9.00048 -40.0305 2.35875 +VERTEX2 5337 8.40914 -39.2532 2.34639 +VERTEX2 5338 7.68762 -38.4699 2.33427 +VERTEX2 5339 7.01771 -37.7664 2.37651 +VERTEX2 5340 6.34379 -37.1328 2.40257 +VERTEX2 5341 6.97547 -36.3759 0.809712 +VERTEX2 5342 7.71887 -35.6899 0.799167 +VERTEX2 5343 8.40156 -34.9025 0.802586 +VERTEX2 5344 9.16506 -34.2311 0.810185 +VERTEX2 5345 9.85417 -33.5278 0.836192 +VERTEX2 5346 9.16265 -32.8473 2.36448 +VERTEX2 5347 8.41518 -32.0816 2.36127 +VERTEX2 5348 7.56959 -31.447 2.35891 +VERTEX2 5349 6.80744 -30.7157 2.3743 +VERTEX2 5350 6.20923 -29.9574 2.38818 +VERTEX2 5351 5.52584 -30.7266 -2.33038 +VERTEX2 5352 4.89138 -31.4623 -2.30181 +VERTEX2 5353 4.24469 -32.1874 -2.30568 +VERTEX2 5354 3.5503 -32.9849 -2.30854 +VERTEX2 5355 2.90314 -33.7039 -2.34163 +VERTEX2 5356 3.60999 -34.3626 -0.76903 +VERTEX2 5357 4.32119 -35.0778 -0.787564 +VERTEX2 5358 5.07922 -35.7817 -0.808837 +VERTEX2 5359 5.6973 -36.5794 -0.816603 +VERTEX2 5360 6.34497 -37.3026 -0.817438 +VERTEX2 5361 7.11802 -36.6993 0.74778 +VERTEX2 5362 7.86105 -36.0566 0.738145 +VERTEX2 5363 8.53165 -35.3311 0.748702 +VERTEX2 5364 9.28891 -34.6008 0.757551 +VERTEX2 5365 10.0023 -33.9216 0.752301 +VERTEX2 5366 9.29631 -33.1439 2.30477 +VERTEX2 5367 8.53909 -32.3522 2.31053 +VERTEX2 5368 7.79853 -31.5068 2.303 +VERTEX2 5369 7.17393 -30.7137 2.2577 +VERTEX2 5370 6.54051 -30.015 2.26031 +VERTEX2 5371 5.77894 -30.7016 -2.44628 +VERTEX2 5372 4.97436 -31.3154 -2.46417 +VERTEX2 5373 4.14944 -31.9511 -2.49152 +VERTEX2 5374 3.37781 -32.5662 -2.48797 +VERTEX2 5375 2.60011 -33.0823 -2.50593 +VERTEX2 5376 3.30177 -33.9023 -0.929871 +VERTEX2 5377 3.8877 -34.7219 -0.931907 +VERTEX2 5378 4.47545 -35.5596 -0.959311 +VERTEX2 5379 5.03274 -36.3398 -0.930857 +VERTEX2 5380 5.61207 -37.1963 -0.939776 +VERTEX2 5381 6.45073 -36.5198 0.635023 +VERTEX2 5382 7.28523 -35.8739 0.625549 +VERTEX2 5383 8.10731 -35.3026 0.635418 +VERTEX2 5384 8.90086 -34.6768 0.674559 +VERTEX2 5385 9.59194 -34.0442 0.681378 +VERTEX2 5386 9.01499 -33.3505 2.25455 +VERTEX2 5387 8.3576 -32.6362 2.27242 +VERTEX2 5388 7.76982 -31.8579 2.24275 +VERTEX2 5389 7.15826 -31.0781 2.23065 +VERTEX2 5390 6.52887 -30.3094 2.21879 +VERTEX2 5391 5.68148 -30.9278 -2.50897 +VERTEX2 5392 4.90532 -31.466 -2.54483 +VERTEX2 5393 4.18371 -31.9771 -2.54909 +VERTEX2 5394 3.32274 -32.567 -2.54984 +VERTEX2 5395 2.48991 -33.0962 -2.53966 +VERTEX2 5396 2.90834 -34.0048 -0.995535 +VERTEX2 5397 3.44309 -34.8125 -1.02059 +VERTEX2 5398 3.90781 -35.719 -1.04953 +VERTEX2 5399 4.37334 -36.5576 -1.057 +VERTEX2 5400 4.93633 -37.4842 -1.04765 +VERTEX2 5401 4.01933 -37.9799 -2.63198 +VERTEX2 5402 3.05174 -38.4988 -2.62908 +VERTEX2 5403 2.18468 -38.9502 -2.61243 +VERTEX2 5404 1.26887 -39.4884 -2.61526 +VERTEX2 5405 0.316709 -39.9615 -2.58893 +VERTEX2 5406 0.786928 -40.8459 -1.00714 +VERTEX2 5407 1.31927 -41.6566 -0.983764 +VERTEX2 5408 1.8055 -42.5124 -0.97469 +VERTEX2 5409 2.41724 -43.3181 -0.972532 +VERTEX2 5410 2.98628 -44.1722 -0.980885 +VERTEX2 5411 2.09566 -44.7321 -2.5463 +VERTEX2 5412 1.19032 -45.311 -2.59234 +VERTEX2 5413 0.326785 -45.6888 -2.60517 +VERTEX2 5414 -0.421539 -46.1928 -2.60903 +VERTEX2 5415 -1.33782 -46.6993 -2.61687 +VERTEX2 5416 -1.79572 -45.797 2.10304 +VERTEX2 5417 -2.3356 -45.0063 2.10163 +VERTEX2 5418 -2.83249 -44.169 2.12753 +VERTEX2 5419 -3.4022 -43.3527 2.12961 +VERTEX2 5420 -3.98925 -42.4868 2.13155 +VERTEX2 5421 -4.83381 -43.0466 -2.56925 +VERTEX2 5422 -5.67037 -43.618 -2.55941 +VERTEX2 5423 -6.49957 -44.1619 -2.52817 +VERTEX2 5424 -7.33054 -44.7354 -2.48731 +VERTEX2 5425 -8.10117 -45.3925 -2.49336 +VERTEX2 5426 -8.76533 -44.4925 2.23984 +VERTEX2 5427 -9.44143 -43.6965 2.25714 +VERTEX2 5428 -10.0687 -42.9068 2.24923 +VERTEX2 5429 -10.7227 -42.0601 2.26903 +VERTEX2 5430 -11.3696 -41.3474 2.26747 +VERTEX2 5431 -12.1334 -41.9318 -2.46555 +VERTEX2 5432 -12.9248 -42.5681 -2.42033 +VERTEX2 5433 -13.566 -43.1993 -2.40409 +VERTEX2 5434 -14.2719 -43.8502 -2.39087 +VERTEX2 5435 -14.9674 -44.4436 -2.41461 +VERTEX2 5436 -14.2784 -45.2969 -0.865458 +VERTEX2 5437 -13.6233 -46.1276 -0.834683 +VERTEX2 5438 -12.9182 -46.9648 -0.813929 +VERTEX2 5439 -12.2535 -47.6483 -0.811643 +VERTEX2 5440 -11.6008 -48.3454 -0.804951 +VERTEX2 5441 -12.3598 -49.0271 -2.32935 +VERTEX2 5442 -13.0695 -49.7293 -2.34356 +VERTEX2 5443 -13.8326 -50.4982 -2.36446 +VERTEX2 5444 -14.4827 -51.2262 -2.31523 +VERTEX2 5445 -15.1206 -52.0228 -2.31259 +VERTEX2 5446 -15.8201 -51.3249 2.44284 +VERTEX2 5447 -16.6074 -50.7092 2.43453 +VERTEX2 5448 -17.3826 -50.0433 2.45169 +VERTEX2 5449 -18.1158 -49.3626 2.46777 +VERTEX2 5450 -18.8875 -48.7385 2.44914 +VERTEX2 5451 -19.5496 -49.5463 -2.25541 +VERTEX2 5452 -20.2309 -50.2674 -2.27682 +VERTEX2 5453 -20.8304 -51.0412 -2.30576 +VERTEX2 5454 -21.4434 -51.9181 -2.29559 +VERTEX2 5455 -22.0727 -52.6238 -2.31344 +VERTEX2 5456 -21.3277 -53.3258 -0.758775 +VERTEX2 5457 -20.6589 -54.0025 -0.763709 +VERTEX2 5458 -19.9395 -54.6738 -0.778762 +VERTEX2 5459 -19.2492 -55.334 -0.761228 +VERTEX2 5460 -18.5363 -56.021 -0.73632 +VERTEX2 5461 -19.1463 -56.7996 -2.29517 +VERTEX2 5462 -19.8219 -57.5799 -2.28485 +VERTEX2 5463 -20.4593 -58.2179 -2.26491 +VERTEX2 5464 -21.1437 -59.0578 -2.26378 +VERTEX2 5465 -21.8247 -59.8226 -2.25845 +VERTEX2 5466 -21.0469 -60.3502 -0.665473 +VERTEX2 5467 -20.2971 -61.0465 -0.619157 +VERTEX2 5468 -19.4428 -61.5491 -0.586575 +VERTEX2 5469 -18.6247 -62.076 -0.594066 +VERTEX2 5470 -17.7791 -62.7032 -0.587471 +VERTEX2 5471 -18.3604 -63.6434 -2.15179 +VERTEX2 5472 -18.8965 -64.4249 -2.1507 +VERTEX2 5473 -19.5151 -65.2707 -2.13799 +VERTEX2 5474 -20.0828 -66.124 -2.12696 +VERTEX2 5475 -20.4913 -67.0272 -2.10346 +VERTEX2 5476 -19.6122 -67.5551 -0.510832 +VERTEX2 5477 -18.7463 -68.0407 -0.444021 +VERTEX2 5478 -17.7907 -68.4652 -0.460865 +VERTEX2 5479 -16.9075 -68.9376 -0.454915 +VERTEX2 5480 -16.0369 -69.3879 -0.454255 +VERTEX2 5481 -15.6432 -68.4893 1.11661 +VERTEX2 5482 -15.1667 -67.5949 1.10504 +VERTEX2 5483 -14.7532 -66.7355 1.12045 +VERTEX2 5484 -14.3114 -65.8546 1.12726 +VERTEX2 5485 -13.8651 -64.9689 1.15214 +VERTEX2 5486 -14.7461 -64.6297 2.72592 +VERTEX2 5487 -15.6499 -64.2034 2.71873 +VERTEX2 5488 -16.5027 -63.8168 2.7113 +VERTEX2 5489 -17.5351 -63.4342 2.71176 +VERTEX2 5490 -18.3622 -62.9075 2.7478 +VERTEX2 5491 -18.7638 -63.883 -1.93901 +VERTEX2 5492 -19.0928 -64.7444 -1.92364 +VERTEX2 5493 -19.4138 -65.7189 -1.93698 +VERTEX2 5494 -19.8109 -66.6506 -1.91558 +VERTEX2 5495 -20.1819 -67.4585 -1.92053 +VERTEX2 5496 -21.0857 -67.1565 2.79947 +VERTEX2 5497 -21.9781 -66.8034 2.79268 +VERTEX2 5498 -22.8332 -66.5116 2.80715 +VERTEX2 5499 -23.7637 -66.2263 2.80371 +VERTEX2 5500 -24.7294 -65.895 2.78902 +VERTEX2 5501 -25.1104 -66.8128 -1.94356 +VERTEX2 5502 -25.5029 -67.7323 -1.91728 +VERTEX2 5503 -25.8365 -68.6717 -1.95214 +VERTEX2 5504 -26.2339 -69.6282 -1.97278 +VERTEX2 5505 -26.571 -70.512 -1.96561 +VERTEX2 5506 -25.5612 -70.8734 -0.39921 +VERTEX2 5507 -24.7554 -71.1599 -0.418421 +VERTEX2 5508 -23.8411 -71.7385 -0.418351 +VERTEX2 5509 -22.9338 -72.1147 -0.43897 +VERTEX2 5510 -22.0135 -72.5938 -0.434726 +VERTEX2 5511 -22.5004 -73.544 -1.99954 +VERTEX2 5512 -22.9958 -74.3611 -1.98784 +VERTEX2 5513 -23.424 -75.3159 -2.01202 +VERTEX2 5514 -23.8397 -76.1152 -1.99672 +VERTEX2 5515 -24.2491 -77.001 -2.01191 +VERTEX2 5516 -23.3336 -77.4141 -0.437996 +VERTEX2 5517 -22.4338 -77.8107 -0.434282 +VERTEX2 5518 -21.6025 -78.1786 -0.427972 +VERTEX2 5519 -20.8028 -78.6588 -0.408697 +VERTEX2 5520 -19.8233 -79.0225 -0.455644 +VERTEX2 5521 -19.3431 -78.2092 1.11931 +VERTEX2 5522 -18.982 -77.2332 1.11303 +VERTEX2 5523 -18.5051 -76.3669 1.16659 +VERTEX2 5524 -18.0979 -75.4406 1.20558 +VERTEX2 5525 -17.6662 -74.6241 1.22828 +VERTEX2 5526 -18.5819 -74.2678 2.78422 +VERTEX2 5527 -19.6333 -73.8765 2.77312 +VERTEX2 5528 -20.5704 -73.4782 2.75311 +VERTEX2 5529 -21.4075 -73.102 2.72786 +VERTEX2 5530 -22.3402 -72.81 2.7454 +VERTEX2 5531 -22.7873 -73.6421 -1.98467 +VERTEX2 5532 -23.2707 -74.6169 -1.9943 +VERTEX2 5533 -23.7202 -75.5118 -1.99573 +VERTEX2 5534 -24.1342 -76.4032 -1.98542 +VERTEX2 5535 -24.4722 -77.2922 -1.99296 +VERTEX2 5536 -23.5569 -77.6525 -0.436495 +VERTEX2 5537 -22.6805 -78.0444 -0.424937 +VERTEX2 5538 -21.7993 -78.4595 -0.403034 +VERTEX2 5539 -20.9355 -78.8637 -0.406641 +VERTEX2 5540 -19.9696 -79.2527 -0.398705 +VERTEX2 5541 -20.3803 -80.1677 -1.9597 +VERTEX2 5542 -20.8131 -81.1027 -1.9459 +VERTEX2 5543 -21.1551 -82.0111 -1.92997 +VERTEX2 5544 -21.4381 -82.91 -1.96934 +VERTEX2 5545 -21.8378 -83.8343 -2.00169 +VERTEX2 5546 -22.5794 -83.3976 2.69382 +VERTEX2 5547 -23.514 -82.9723 2.69875 +VERTEX2 5548 -24.4351 -82.6225 2.6827 +VERTEX2 5549 -25.3145 -82.1758 2.65606 +VERTEX2 5550 -26.2524 -81.7331 2.70302 +VERTEX2 5551 -25.7601 -80.8071 1.1297 +VERTEX2 5552 -25.2725 -79.9894 1.13228 +VERTEX2 5553 -24.8881 -79.1185 1.13408 +VERTEX2 5554 -24.4942 -78.2609 1.15487 +VERTEX2 5555 -24.1262 -77.4038 1.15264 +VERTEX2 5556 -23.127 -77.7938 -0.422485 +VERTEX2 5557 -22.1543 -78.1831 -0.443991 +VERTEX2 5558 -21.2886 -78.6359 -0.470216 +VERTEX2 5559 -20.3087 -79.0389 -0.462826 +VERTEX2 5560 -19.4277 -79.5676 -0.457744 +VERTEX2 5561 -18.9472 -78.6553 1.07794 +VERTEX2 5562 -18.4054 -77.7805 1.03566 +VERTEX2 5563 -18.0267 -76.9886 1.01532 +VERTEX2 5564 -17.5379 -76.1087 1.03197 +VERTEX2 5565 -17.0112 -75.2752 1.01359 +VERTEX2 5566 -17.8826 -74.7128 2.58347 +VERTEX2 5567 -18.7295 -74.0921 2.59639 +VERTEX2 5568 -19.5354 -73.5895 2.57265 +VERTEX2 5569 -20.2732 -72.9972 2.56936 +VERTEX2 5570 -21.0702 -72.5182 2.53686 +VERTEX2 5571 -21.6153 -73.277 -2.15339 +VERTEX2 5572 -22.1707 -74.0639 -2.15715 +VERTEX2 5573 -22.6587 -74.9481 -2.18993 +VERTEX2 5574 -23.1735 -75.7027 -2.2053 +VERTEX2 5575 -23.7685 -76.4725 -2.21321 +VERTEX2 5576 -24.5502 -75.8285 2.50665 +VERTEX2 5577 -25.3277 -75.2669 2.48891 +VERTEX2 5578 -26.0648 -74.6958 2.4803 +VERTEX2 5579 -26.9216 -74.0931 2.49459 +VERTEX2 5580 -27.6749 -73.5731 2.47739 +VERTEX2 5581 -28.2756 -74.4596 -2.22567 +VERTEX2 5582 -28.9694 -75.1819 -2.22902 +VERTEX2 5583 -29.6356 -76.0083 -2.22667 +VERTEX2 5584 -30.3092 -76.8419 -2.2386 +VERTEX2 5585 -30.9027 -77.5931 -2.20783 +VERTEX2 5586 -30.1519 -78.2269 -0.670443 +VERTEX2 5587 -29.4012 -78.9147 -0.688203 +VERTEX2 5588 -28.5873 -79.5708 -0.651261 +VERTEX2 5589 -27.7436 -80.2168 -0.656827 +VERTEX2 5590 -26.9987 -80.8359 -0.695153 +VERTEX2 5591 -26.2663 -80.0463 0.880183 +VERTEX2 5592 -25.6379 -79.2221 0.868641 +VERTEX2 5593 -24.9706 -78.5076 0.875201 +VERTEX2 5594 -24.3458 -77.7257 0.877597 +VERTEX2 5595 -23.7119 -76.8559 0.904122 +VERTEX2 5596 -22.962 -77.4502 -0.666278 +VERTEX2 5597 -22.2162 -78.05 -0.654604 +VERTEX2 5598 -21.4675 -78.6112 -0.656381 +VERTEX2 5599 -20.636 -79.2756 -0.639838 +VERTEX2 5600 -19.831 -79.8682 -0.618839 +VERTEX2 5601 -19.292 -79.0473 0.927276 +VERTEX2 5602 -18.7625 -78.194 0.932024 +VERTEX2 5603 -18.1649 -77.3871 0.947583 +VERTEX2 5604 -17.559 -76.6271 0.94527 +VERTEX2 5605 -16.9203 -75.786 0.941992 +VERTEX2 5606 -17.5814 -75.2662 2.50228 +VERTEX2 5607 -18.4871 -74.6215 2.50668 +VERTEX2 5608 -19.2805 -74.0822 2.52557 +VERTEX2 5609 -20.1497 -73.5203 2.54346 +VERTEX2 5610 -21.0098 -73.0083 2.53598 +VERTEX2 5611 -21.666 -73.8066 -2.19078 +VERTEX2 5612 -22.3051 -74.7042 -2.17543 +VERTEX2 5613 -22.9078 -75.5123 -2.18148 +VERTEX2 5614 -23.4685 -76.415 -2.17255 +VERTEX2 5615 -24.0468 -77.085 -2.20293 +VERTEX2 5616 -24.8336 -76.5642 2.49308 +VERTEX2 5617 -25.6494 -75.9382 2.51669 +VERTEX2 5618 -26.5558 -75.3383 2.5502 +VERTEX2 5619 -27.3766 -74.8125 2.55869 +VERTEX2 5620 -28.1831 -74.2825 2.55043 +VERTEX2 5621 -28.7035 -75.1296 -2.16806 +VERTEX2 5622 -29.232 -75.9213 -2.15599 +VERTEX2 5623 -29.7811 -76.7245 -2.15169 +VERTEX2 5624 -30.2942 -77.6049 -2.14534 +VERTEX2 5625 -30.8282 -78.4246 -2.12633 +VERTEX2 5626 -31.6091 -77.8907 2.60828 +VERTEX2 5627 -32.3695 -77.4399 2.61152 +VERTEX2 5628 -33.2228 -76.9318 2.61005 +VERTEX2 5629 -34.0274 -76.4239 2.6166 +VERTEX2 5630 -34.8735 -75.8826 2.6232 +VERTEX2 5631 -34.4541 -75.0239 1.05602 +VERTEX2 5632 -33.9784 -74.2003 1.02279 +VERTEX2 5633 -33.4668 -73.2765 1.01999 +VERTEX2 5634 -32.9798 -72.4998 0.99926 +VERTEX2 5635 -32.3714 -71.643 0.990251 +VERTEX2 5636 -33.1983 -71.1389 2.54171 +VERTEX2 5637 -33.9899 -70.5241 2.53846 +VERTEX2 5638 -34.8243 -69.918 2.52743 +VERTEX2 5639 -35.6336 -69.3423 2.52738 +VERTEX2 5640 -36.4188 -68.7491 2.5439 +VERTEX2 5641 -35.833 -67.9378 0.986254 +VERTEX2 5642 -35.2948 -67.0134 0.981133 +VERTEX2 5643 -34.6711 -66.1736 0.954496 +VERTEX2 5644 -33.9831 -65.4243 0.933698 +VERTEX2 5645 -33.3331 -64.6262 0.95277 +VERTEX2 5646 -32.471 -65.1625 -0.616855 +VERTEX2 5647 -31.6244 -65.7478 -0.615705 +VERTEX2 5648 -30.7471 -66.3364 -0.611854 +VERTEX2 5649 -29.9343 -66.8831 -0.625546 +VERTEX2 5650 -29.1785 -67.4256 -0.594202 +VERTEX2 5651 -28.6505 -66.5869 1.00061 +VERTEX2 5652 -28.1197 -65.8318 1.01113 +VERTEX2 5653 -27.5806 -65.067 1.01614 +VERTEX2 5654 -27.0969 -64.2397 1.02959 +VERTEX2 5655 -26.5893 -63.3486 1.05139 +VERTEX2 5656 -27.4709 -62.8504 2.63829 +VERTEX2 5657 -28.365 -62.2933 2.66673 +VERTEX2 5658 -29.2176 -61.8584 2.69271 +VERTEX2 5659 -30.1827 -61.4766 2.68155 +VERTEX2 5660 -31.008 -61.1012 2.67828 +VERTEX2 5661 -31.4288 -62.0327 -2.0101 +VERTEX2 5662 -31.871 -62.9432 -2.02678 +VERTEX2 5663 -32.2678 -63.836 -2.02236 +VERTEX2 5664 -32.7646 -64.74 -2.04617 +VERTEX2 5665 -33.2189 -65.6506 -2.00068 +VERTEX2 5666 -32.3829 -66.1334 -0.443177 +VERTEX2 5667 -31.479 -66.5631 -0.440493 +VERTEX2 5668 -30.6038 -66.8785 -0.431885 +VERTEX2 5669 -29.7039 -67.2881 -0.426945 +VERTEX2 5670 -28.8684 -67.6912 -0.422484 +VERTEX2 5671 -29.2849 -68.637 -1.98201 +VERTEX2 5672 -29.7372 -69.575 -1.98312 +VERTEX2 5673 -30.0971 -70.4969 -1.99688 +VERTEX2 5674 -30.5211 -71.4368 -1.9877 +VERTEX2 5675 -30.8944 -72.2617 -1.94136 +VERTEX2 5676 -31.7235 -71.9288 2.79248 +VERTEX2 5677 -32.6624 -71.6595 2.81748 +VERTEX2 5678 -33.5932 -71.3557 2.84532 +VERTEX2 5679 -34.5354 -71.1027 2.87103 +VERTEX2 5680 -35.4266 -70.9044 2.8673 +VERTEX2 5681 -35.6841 -71.8961 -1.82396 +VERTEX2 5682 -36.0013 -72.8578 -1.80386 +VERTEX2 5683 -36.1997 -73.8147 -1.83864 +VERTEX2 5684 -36.6071 -74.7712 -1.81442 +VERTEX2 5685 -36.8545 -75.7675 -1.77325 +VERTEX2 5686 -35.7858 -75.9691 -0.198391 +VERTEX2 5687 -34.7908 -76.2183 -0.161977 +VERTEX2 5688 -33.8648 -76.348 -0.171452 +VERTEX2 5689 -32.8412 -76.5497 -0.176861 +VERTEX2 5690 -31.9104 -76.7642 -0.203602 +VERTEX2 5691 -31.7434 -75.8638 1.35527 +VERTEX2 5692 -31.5409 -74.8863 1.3474 +VERTEX2 5693 -31.3542 -73.8649 1.35172 +VERTEX2 5694 -31.1124 -72.8326 1.34968 +VERTEX2 5695 -30.8956 -71.8244 1.3585 +VERTEX2 5696 -31.8856 -71.6629 2.91312 +VERTEX2 5697 -32.8845 -71.4519 2.91003 +VERTEX2 5698 -33.8307 -71.185 2.93905 +VERTEX2 5699 -34.7419 -70.9648 2.95099 +VERTEX2 5700 -35.6968 -70.7917 2.92599 +VERTEX2 5701 -35.903 -71.7002 -1.76967 +VERTEX2 5702 -36.1343 -72.7133 -1.78791 +VERTEX2 5703 -36.319 -73.6573 -1.80073 +VERTEX2 5704 -36.6285 -74.6275 -1.76028 +VERTEX2 5705 -36.8628 -75.6828 -1.7781 +VERTEX2 5706 -35.8377 -75.8945 -0.162393 +VERTEX2 5707 -34.7252 -76.1215 -0.147863 +VERTEX2 5708 -33.8901 -76.2804 -0.132776 +VERTEX2 5709 -32.9813 -76.3629 -0.140186 +VERTEX2 5710 -31.8661 -76.5658 -0.122736 +VERTEX2 5711 -31.7728 -75.5266 1.43156 +VERTEX2 5712 -31.6726 -74.4917 1.41373 +VERTEX2 5713 -31.5692 -73.5573 1.39144 +VERTEX2 5714 -31.4079 -72.5409 1.41654 +VERTEX2 5715 -31.25 -71.5862 1.3767 +VERTEX2 5716 -32.2855 -71.4233 2.93707 +VERTEX2 5717 -33.292 -71.1783 2.9624 +VERTEX2 5718 -34.2658 -70.9403 2.95801 +VERTEX2 5719 -35.1581 -70.6886 2.95185 +VERTEX2 5720 -36.0867 -70.5836 2.92379 +VERTEX2 5721 -36.2429 -71.5473 -1.7684 +VERTEX2 5722 -36.3357 -72.5849 -1.76606 +VERTEX2 5723 -36.5168 -73.5952 -1.75674 +VERTEX2 5724 -36.7068 -74.5832 -1.773 +VERTEX2 5725 -36.8251 -75.5985 -1.74433 +VERTEX2 5726 -37.9322 -75.4015 2.96761 +VERTEX2 5727 -38.9794 -75.1803 2.99521 +VERTEX2 5728 -39.9756 -74.949 2.99603 +VERTEX2 5729 -40.9793 -74.8089 2.95936 +VERTEX2 5730 -41.9232 -74.6596 2.9608 +VERTEX2 5731 -42.0669 -75.681 -1.7683 +VERTEX2 5732 -42.2411 -76.6556 -1.74296 +VERTEX2 5733 -42.3726 -77.647 -1.75541 +VERTEX2 5734 -42.5459 -78.6084 -1.75924 +VERTEX2 5735 -42.756 -79.5282 -1.73985 +VERTEX2 5736 -41.8032 -79.7263 -0.191261 +VERTEX2 5737 -40.8112 -79.9543 -0.187674 +VERTEX2 5738 -39.869 -80.0883 -0.215503 +VERTEX2 5739 -38.8283 -80.2891 -0.202249 +VERTEX2 5740 -37.8251 -80.4333 -0.159871 +VERTEX2 5741 -37.6436 -79.5216 1.40583 +VERTEX2 5742 -37.5391 -78.5508 1.41712 +VERTEX2 5743 -37.3777 -77.6553 1.40676 +VERTEX2 5744 -37.1945 -76.6202 1.39793 +VERTEX2 5745 -37.0445 -75.6478 1.36934 +VERTEX2 5746 -36.1062 -75.871 -0.164692 +VERTEX2 5747 -35.0909 -75.9939 -0.14685 +VERTEX2 5748 -34.1575 -76.1426 -0.144486 +VERTEX2 5749 -33.2397 -76.2757 -0.143986 +VERTEX2 5750 -32.242 -76.4385 -0.116509 +VERTEX2 5751 -32.085 -75.4164 1.44454 +VERTEX2 5752 -31.941 -74.5737 1.45495 +VERTEX2 5753 -31.8497 -73.5829 1.46093 +VERTEX2 5754 -31.6456 -72.6889 1.46693 +VERTEX2 5755 -31.5919 -71.7312 1.44901 +VERTEX2 5756 -30.6339 -71.8574 -0.121113 +VERTEX2 5757 -29.6035 -71.9326 -0.135719 +VERTEX2 5758 -28.6102 -72.1052 -0.141299 +VERTEX2 5759 -27.6364 -72.2292 -0.139233 +VERTEX2 5760 -26.6031 -72.385 -0.140406 +VERTEX2 5761 -26.5621 -71.4554 1.43016 +VERTEX2 5762 -26.4334 -70.4907 1.43588 +VERTEX2 5763 -26.3153 -69.5446 1.43096 +VERTEX2 5764 -26.1039 -68.5802 1.44533 +VERTEX2 5765 -25.9817 -67.5707 1.46931 +VERTEX2 5766 -26.9288 -67.5002 3.05517 +VERTEX2 5767 -27.911 -67.4817 3.09272 +VERTEX2 5768 -28.9335 -67.4032 3.09399 +VERTEX2 5769 -29.9334 -67.3247 3.0986 +VERTEX2 5770 -30.9441 -67.3144 3.12365 +VERTEX2 5771 -30.9537 -66.3701 1.5813 +VERTEX2 5772 -30.929 -65.3849 1.56301 +VERTEX2 5773 -30.9426 -64.4778 1.58481 +VERTEX2 5774 -30.9618 -63.5413 1.59381 +VERTEX2 5775 -30.9982 -62.5389 1.63217 +VERTEX2 5776 -32.0611 -62.5603 -3.07954 +VERTEX2 5777 -33.1185 -62.5599 -3.07121 +VERTEX2 5778 -34.136 -62.6449 -3.04909 +VERTEX2 5779 -35.1215 -62.6985 -3.03885 +VERTEX2 5780 -36.1002 -62.7855 -3.01918 +VERTEX2 5781 -36.1278 -61.8217 1.64536 +VERTEX2 5782 -36.2636 -60.7319 1.66255 +VERTEX2 5783 -36.3323 -59.7388 1.68582 +VERTEX2 5784 -36.483 -58.7478 1.68665 +VERTEX2 5785 -36.581 -57.7619 1.6671 +VERTEX2 5786 -37.6033 -57.8551 -3.0452 +VERTEX2 5787 -38.6076 -57.9762 -3.04804 +VERTEX2 5788 -39.5884 -58.09 -3.044 +VERTEX2 5789 -40.5303 -58.129 -3.03658 +VERTEX2 5790 -41.4606 -58.3423 -3.08229 +VERTEX2 5791 -41.3515 -59.2931 -1.46855 +VERTEX2 5792 -41.2207 -60.2187 -1.47804 +VERTEX2 5793 -41.1419 -61.2208 -1.46449 +VERTEX2 5794 -41.0603 -62.1781 -1.48083 +VERTEX2 5795 -40.9617 -63.1436 -1.49464 +VERTEX2 5796 -40.0059 -63.1137 0.101979 +VERTEX2 5797 -39.0088 -62.987 0.0883737 +VERTEX2 5798 -38.032 -62.8987 0.0882457 +VERTEX2 5799 -36.9687 -62.8173 0.0712693 +VERTEX2 5800 -36.0163 -62.8055 0.0606248 +VERTEX2 5801 -36.1703 -61.7432 1.61968 +VERTEX2 5802 -36.3005 -60.6513 1.65479 +VERTEX2 5803 -36.4251 -59.644 1.66318 +VERTEX2 5804 -36.4775 -58.6629 1.65305 +VERTEX2 5805 -36.4711 -57.744 1.63815 +VERTEX2 5806 -37.41 -57.7882 -3.04779 +VERTEX2 5807 -38.4 -57.824 -3.03565 +VERTEX2 5808 -39.3333 -57.8481 -3.03173 +VERTEX2 5809 -40.2705 -57.9603 -3.01452 +VERTEX2 5810 -41.2535 -58.1527 -3.05584 +VERTEX2 5811 -41.2971 -57.2131 1.61013 +VERTEX2 5812 -41.3093 -56.3304 1.61768 +VERTEX2 5813 -41.3577 -55.3977 1.5896 +VERTEX2 5814 -41.3602 -54.4374 1.56531 +VERTEX2 5815 -41.3452 -53.4971 1.56518 +VERTEX2 5816 -42.3252 -53.42 -3.1393 +VERTEX2 5817 -43.3583 -53.5337 3.12931 +VERTEX2 5818 -44.3415 -53.5092 3.1382 +VERTEX2 5819 -45.3682 -53.4975 3.13695 +VERTEX2 5820 -46.5138 -53.4677 3.12723 +VERTEX2 5821 -46.6278 -54.4679 -1.53096 +VERTEX2 5822 -46.6362 -55.4521 -1.53973 +VERTEX2 5823 -46.6398 -56.4724 -1.53093 +VERTEX2 5824 -46.5704 -57.4099 -1.5562 +VERTEX2 5825 -46.5298 -58.3989 -1.55472 +VERTEX2 5826 -45.4969 -58.5047 0.0312615 +VERTEX2 5827 -44.4476 -58.4857 0.0386397 +VERTEX2 5828 -43.467 -58.4284 0.0566954 +VERTEX2 5829 -42.4152 -58.3328 0.0590274 +VERTEX2 5830 -41.4611 -58.2712 0.0274288 +VERTEX2 5831 -41.5269 -57.2034 1.61461 +VERTEX2 5832 -41.6058 -56.2116 1.62442 +VERTEX2 5833 -41.6807 -55.1434 1.63069 +VERTEX2 5834 -41.7254 -54.1863 1.65177 +VERTEX2 5835 -41.8276 -53.1412 1.65184 +VERTEX2 5836 -42.7825 -53.2285 -3.08047 +VERTEX2 5837 -43.7581 -53.329 -3.10017 +VERTEX2 5838 -44.7572 -53.4218 -3.12149 +VERTEX2 5839 -45.7863 -53.4497 3.13466 +VERTEX2 5840 -46.824 -53.4751 -3.11402 +VERTEX2 5841 -46.8411 -54.4186 -1.54543 +VERTEX2 5842 -46.7762 -55.3735 -1.55303 +VERTEX2 5843 -46.7848 -56.3563 -1.51189 +VERTEX2 5844 -46.647 -57.3902 -1.50419 +VERTEX2 5845 -46.5101 -58.3795 -1.49642 +VERTEX2 5846 -45.4944 -58.3442 0.08029 +VERTEX2 5847 -44.5224 -58.2592 0.0832147 +VERTEX2 5848 -43.4487 -58.2089 0.0855484 +VERTEX2 5849 -42.4137 -58.0249 0.0682927 +VERTEX2 5850 -41.4469 -57.9705 0.036255 +VERTEX2 5851 -41.3115 -58.9025 -1.53781 +VERTEX2 5852 -41.31 -59.9096 -1.50937 +VERTEX2 5853 -41.3021 -60.8642 -1.53577 +VERTEX2 5854 -41.2171 -61.9283 -1.58059 +VERTEX2 5855 -41.1795 -62.8487 -1.55979 +VERTEX2 5856 -42.1765 -62.8764 3.13508 +VERTEX2 5857 -43.1115 -62.9361 3.13474 +VERTEX2 5858 -44.1236 -62.9494 -3.12501 +VERTEX2 5859 -45.0716 -62.8533 -3.09459 +VERTEX2 5860 -46.1025 -62.9289 -3.10381 +VERTEX2 5861 -46.0588 -63.9321 -1.51584 +VERTEX2 5862 -45.9204 -64.9394 -1.50097 +VERTEX2 5863 -45.8462 -65.9416 -1.51026 +VERTEX2 5864 -45.8008 -66.963 -1.48914 +VERTEX2 5865 -45.7509 -67.9909 -1.45537 +VERTEX2 5866 -44.675 -67.8904 0.138128 +VERTEX2 5867 -43.674 -67.7912 0.134104 +VERTEX2 5868 -42.7006 -67.6655 0.11225 +VERTEX2 5869 -41.7136 -67.6298 0.130831 +VERTEX2 5870 -40.6843 -67.5629 0.121457 +VERTEX2 5871 -40.7285 -66.5694 1.65518 +VERTEX2 5872 -40.8674 -65.6316 1.65927 +VERTEX2 5873 -40.8796 -64.6384 1.64729 +VERTEX2 5874 -41.0442 -63.6896 1.62866 +VERTEX2 5875 -41.147 -62.5928 1.61383 +VERTEX2 5876 -42.1677 -62.6231 -3.11128 +VERTEX2 5877 -43.1223 -62.6869 -3.11025 +VERTEX2 5878 -44.092 -62.7412 -3.08922 +VERTEX2 5879 -45.1515 -62.7301 -3.09467 +VERTEX2 5880 -46.1562 -62.8561 -3.11196 +VERTEX2 5881 -46.1864 -61.7833 1.58219 +VERTEX2 5882 -46.1963 -60.7985 1.58763 +VERTEX2 5883 -46.2993 -59.8219 1.61239 +VERTEX2 5884 -46.3584 -58.8403 1.63441 +VERTEX2 5885 -46.362 -57.8317 1.65795 +VERTEX2 5886 -47.3844 -57.8997 -3.05999 +VERTEX2 5887 -48.3608 -57.9429 -3.09377 +VERTEX2 5888 -49.3532 -58.0557 -3.11547 +VERTEX2 5889 -50.4295 -58.0499 -3.102 +VERTEX2 5890 -51.4845 -58.1195 -3.09555 +VERTEX2 5891 -51.5108 -57.0642 1.60793 +VERTEX2 5892 -51.5454 -56.0847 1.64345 +VERTEX2 5893 -51.6078 -55.0994 1.63992 +VERTEX2 5894 -51.5664 -54.069 1.61118 +VERTEX2 5895 -51.5685 -53.0275 1.63519 +VERTEX2 5896 -52.5398 -53.0412 -3.06222 +VERTEX2 5897 -53.5604 -53.1416 -3.05826 +VERTEX2 5898 -54.5502 -53.3308 -3.05911 +VERTEX2 5899 -55.5577 -53.515 -3.05002 +VERTEX2 5900 -56.5558 -53.6025 -3.07147 +VERTEX2 5901 -56.6275 -52.642 1.64427 +VERTEX2 5902 -56.7066 -51.6352 1.67204 +VERTEX2 5903 -56.8069 -50.65 1.67464 +VERTEX2 5904 -56.9876 -49.6333 1.67614 +VERTEX2 5905 -57.0046 -48.6265 1.67058 +VERTEX2 5906 -57.9677 -48.7617 -2.96896 +VERTEX2 5907 -58.929 -48.9138 -2.97456 +VERTEX2 5908 -59.905 -49.1086 -2.9706 +VERTEX2 5909 -60.8242 -49.4115 -2.99404 +VERTEX2 5910 -61.8121 -49.5411 -2.99214 +VERTEX2 5911 -61.9722 -48.5035 1.71437 +VERTEX2 5912 -62.1814 -47.581 1.70621 +VERTEX2 5913 -62.3074 -46.5995 1.70371 +VERTEX2 5914 -62.4346 -45.6838 1.72236 +VERTEX2 5915 -62.5792 -44.7384 1.72998 +VERTEX2 5916 -63.5445 -44.934 -3.02634 +VERTEX2 5917 -64.5562 -45.1102 -3.03481 +VERTEX2 5918 -65.5306 -45.1981 -3.02827 +VERTEX2 5919 -66.6364 -45.2351 -3.01458 +VERTEX2 5920 -67.6676 -45.4345 -3.01723 +VERTEX2 5921 -67.5887 -46.3468 -1.42484 +VERTEX2 5922 -67.4639 -47.3214 -1.45133 +VERTEX2 5923 -67.3315 -48.2787 -1.43117 +VERTEX2 5924 -67.1755 -49.2221 -1.42849 +VERTEX2 5925 -67.0641 -50.1989 -1.43549 +VERTEX2 5926 -66.0974 -50.0926 0.140372 +VERTEX2 5927 -65.0901 -49.9019 0.172699 +VERTEX2 5928 -64.2278 -49.7854 0.16467 +VERTEX2 5929 -63.3163 -49.627 0.162851 +VERTEX2 5930 -62.3338 -49.4081 0.161035 +VERTEX2 5931 -62.4057 -48.3969 1.70678 +VERTEX2 5932 -62.5664 -47.4175 1.71793 +VERTEX2 5933 -62.759 -46.4515 1.71056 +VERTEX2 5934 -62.9286 -45.492 1.69702 +VERTEX2 5935 -62.937 -44.5067 1.69182 +VERTEX2 5936 -61.9943 -44.4657 0.118624 +VERTEX2 5937 -61.0042 -44.336 0.124906 +VERTEX2 5938 -60.0901 -44.3169 0.126715 +VERTEX2 5939 -59.1422 -44.1011 0.132897 +VERTEX2 5940 -58.1579 -43.9847 0.119271 +VERTEX2 5941 -58.0228 -45.0239 -1.43355 +VERTEX2 5942 -57.8398 -46.0277 -1.4335 +VERTEX2 5943 -57.7397 -47.0303 -1.44731 +VERTEX2 5944 -57.5441 -47.9907 -1.48937 +VERTEX2 5945 -57.5481 -49.0308 -1.50896 +VERTEX2 5946 -56.5739 -48.9638 0.0403406 +VERTEX2 5947 -55.6517 -48.9114 0.03191 +VERTEX2 5948 -54.6771 -48.951 0.0312414 +VERTEX2 5949 -53.6488 -48.9516 0.0325338 +VERTEX2 5950 -52.5922 -48.9789 0.0393461 +VERTEX2 5951 -52.6152 -47.9764 1.56555 +VERTEX2 5952 -52.5637 -46.9369 1.54269 +VERTEX2 5953 -52.5442 -45.9627 1.54407 +VERTEX2 5954 -52.5517 -44.9533 1.53767 +VERTEX2 5955 -52.5899 -43.9737 1.55301 +VERTEX2 5956 -53.5786 -43.9327 3.11315 +VERTEX2 5957 -54.6108 -43.9565 -3.13933 +VERTEX2 5958 -55.5674 -43.8866 -3.12827 +VERTEX2 5959 -56.6354 -43.8797 -3.09276 +VERTEX2 5960 -57.7587 -43.955 -3.07797 +VERTEX2 5961 -57.6605 -44.9842 -1.47775 +VERTEX2 5962 -57.5696 -45.9716 -1.47467 +VERTEX2 5963 -57.4051 -46.9645 -1.46411 +VERTEX2 5964 -57.3131 -48.0382 -1.47601 +VERTEX2 5965 -57.2591 -49.0223 -1.46312 +VERTEX2 5966 -56.2352 -48.9785 0.168822 +VERTEX2 5967 -55.2615 -48.8233 0.150368 +VERTEX2 5968 -54.2683 -48.7145 0.152869 +VERTEX2 5969 -53.2465 -48.58 0.150575 +VERTEX2 5970 -52.3986 -48.421 0.159202 +VERTEX2 5971 -52.5621 -47.4549 1.75261 +VERTEX2 5972 -52.7495 -46.5216 1.71682 +VERTEX2 5973 -52.7987 -45.5982 1.71184 +VERTEX2 5974 -52.9402 -44.5955 1.73327 +VERTEX2 5975 -53.1464 -43.6915 1.75671 +VERTEX2 5976 -54.1878 -43.8874 -2.95257 +VERTEX2 5977 -55.1055 -44.1057 -2.9432 +VERTEX2 5978 -56.1664 -44.3267 -2.95529 +VERTEX2 5979 -57.1609 -44.4712 -2.95968 +VERTEX2 5980 -58.1567 -44.6271 -2.93659 +VERTEX2 5981 -57.971 -45.5957 -1.3548 +VERTEX2 5982 -57.6651 -46.492 -1.33283 +VERTEX2 5983 -57.4657 -47.4395 -1.35674 +VERTEX2 5984 -57.2019 -48.4169 -1.33848 +VERTEX2 5985 -57.0059 -49.3489 -1.35078 +VERTEX2 5986 -56.0487 -49.1498 0.24016 +VERTEX2 5987 -55.0555 -48.9756 0.229313 +VERTEX2 5988 -54.0455 -48.7971 0.244565 +VERTEX2 5989 -53.1649 -48.5164 0.231506 +VERTEX2 5990 -52.1908 -48.2994 0.19471 +VERTEX2 5991 -52.398 -47.323 1.74781 +VERTEX2 5992 -52.493 -46.2984 1.74953 +VERTEX2 5993 -52.6445 -45.3405 1.75655 +VERTEX2 5994 -52.8235 -44.4794 1.74345 +VERTEX2 5995 -53.006 -43.4739 1.75411 +VERTEX2 5996 -53.9238 -43.6444 -2.95834 +VERTEX2 5997 -54.8825 -43.7825 -2.91812 +VERTEX2 5998 -55.8029 -44.0081 -2.91078 +VERTEX2 5999 -56.7349 -44.2661 -2.89639 +VERTEX2 6000 -57.7452 -44.5657 -2.88949 +VERTEX2 6001 -58.0381 -43.5073 1.84546 +VERTEX2 6002 -58.3982 -42.4673 1.82684 +VERTEX2 6003 -58.7451 -41.4613 1.81834 +VERTEX2 6004 -59.01 -40.5082 1.84117 +VERTEX2 6005 -59.31 -39.5958 1.83541 +VERTEX2 6006 -60.2331 -39.8249 -2.87844 +VERTEX2 6007 -61.2152 -40.0717 -2.89911 +VERTEX2 6008 -62.2282 -40.3617 -2.88548 +VERTEX2 6009 -63.1848 -40.5879 -2.89997 +VERTEX2 6010 -64.1532 -40.8271 -2.93035 +VERTEX2 6011 -63.8737 -41.8089 -1.33056 +VERTEX2 6012 -63.6672 -42.8284 -1.31465 +VERTEX2 6013 -63.4319 -43.7807 -1.2938 +VERTEX2 6014 -63.0436 -44.7931 -1.34298 +VERTEX2 6015 -62.8032 -45.8095 -1.33544 +VERTEX2 6016 -63.7529 -46.0349 -2.91884 +VERTEX2 6017 -64.6523 -46.2566 -2.93053 +VERTEX2 6018 -65.6629 -46.528 -2.93917 +VERTEX2 6019 -66.6349 -46.6679 -2.94873 +VERTEX2 6020 -67.5676 -46.9496 -2.95011 +VERTEX2 6021 -67.8127 -45.9438 1.74948 +VERTEX2 6022 -68.0321 -44.9557 1.76399 +VERTEX2 6023 -68.152 -44.0065 1.74879 +VERTEX2 6024 -68.2919 -43.0338 1.75337 +VERTEX2 6025 -68.4806 -42.0034 1.75103 +VERTEX2 6026 -69.5224 -42.1025 -2.97673 +VERTEX2 6027 -70.5099 -42.2458 -2.93789 +VERTEX2 6028 -71.4053 -42.5336 -2.94061 +VERTEX2 6029 -72.3808 -42.768 -2.91569 +VERTEX2 6030 -73.3857 -43.0142 -2.95115 +VERTEX2 6031 -73.5859 -42.0316 1.74147 +VERTEX2 6032 -73.7374 -41.0661 1.77591 +VERTEX2 6033 -73.9636 -40.1359 1.80814 +VERTEX2 6034 -74.263 -39.2253 1.81443 +VERTEX2 6035 -74.456 -38.238 1.82168 +VERTEX2 6036 -75.5208 -38.4767 -2.89697 +VERTEX2 6037 -76.39 -38.7177 -2.8801 +VERTEX2 6038 -77.3367 -39.0823 -2.84313 +VERTEX2 6039 -78.3216 -39.3714 -2.8582 +VERTEX2 6040 -79.2534 -39.7143 -2.90317 +VERTEX2 6041 -78.9413 -40.6972 -1.35042 +VERTEX2 6042 -78.7206 -41.6933 -1.32029 +VERTEX2 6043 -78.4731 -42.6423 -1.3362 +VERTEX2 6044 -78.1795 -43.6102 -1.3542 +VERTEX2 6045 -77.9681 -44.5838 -1.3513 +VERTEX2 6046 -76.9291 -44.3338 0.204646 +VERTEX2 6047 -75.8826 -44.2057 0.225223 +VERTEX2 6048 -74.9309 -43.9332 0.214877 +VERTEX2 6049 -73.9911 -43.7257 0.211112 +VERTEX2 6050 -72.9428 -43.4839 0.231382 +VERTEX2 6051 -73.2118 -42.535 1.79298 +VERTEX2 6052 -73.4453 -41.5059 1.7796 +VERTEX2 6053 -73.6771 -40.4777 1.75498 +VERTEX2 6054 -73.885 -39.3911 1.76689 +VERTEX2 6055 -74.1176 -38.3197 1.74156 +VERTEX2 6056 -75.0765 -38.4887 -2.98938 +VERTEX2 6057 -76.0526 -38.7068 -2.96215 +VERTEX2 6058 -76.9626 -38.837 -2.97429 +VERTEX2 6059 -77.9795 -38.9843 -2.96043 +VERTEX2 6060 -78.9808 -39.2107 -2.98848 +VERTEX2 6061 -78.8013 -40.1409 -1.42957 +VERTEX2 6062 -78.6937 -41.1427 -1.41945 +VERTEX2 6063 -78.4213 -42.131 -1.44403 +VERTEX2 6064 -78.3093 -43.2059 -1.43928 +VERTEX2 6065 -78.1635 -44.2296 -1.43063 +VERTEX2 6066 -77.1835 -44.0971 0.118524 +VERTEX2 6067 -76.2682 -44.0452 0.105789 +VERTEX2 6068 -75.2577 -43.9752 0.120976 +VERTEX2 6069 -74.3079 -43.9204 0.140365 +VERTEX2 6070 -73.2968 -43.7315 0.152085 +VERTEX2 6071 -73.4638 -42.7375 1.70137 +VERTEX2 6072 -73.5945 -41.7759 1.69128 +VERTEX2 6073 -73.7942 -40.7647 1.69397 +VERTEX2 6074 -73.9441 -39.775 1.68755 +VERTEX2 6075 -74.0675 -38.7664 1.69227 +VERTEX2 6076 -75.1154 -38.9332 -3.01783 +VERTEX2 6077 -76.1932 -39.0176 -3.01083 +VERTEX2 6078 -77.2111 -39.1216 -3.01052 +VERTEX2 6079 -78.2096 -39.2433 -3.00937 +VERTEX2 6080 -79.1647 -39.3175 -2.97164 +VERTEX2 6081 -79.1135 -40.2779 -1.39108 +VERTEX2 6082 -78.9942 -41.2888 -1.38156 +VERTEX2 6083 -78.8271 -42.3401 -1.38643 +VERTEX2 6084 -78.5956 -43.3457 -1.38232 +VERTEX2 6085 -78.4069 -44.5079 -1.40309 +VERTEX2 6086 -77.4161 -44.2991 0.152464 +VERTEX2 6087 -76.4139 -44.1634 0.180468 +VERTEX2 6088 -75.4565 -44.0331 0.156176 +VERTEX2 6089 -74.4823 -43.8973 0.177685 +VERTEX2 6090 -73.5424 -43.797 0.163824 +VERTEX2 6091 -73.6823 -42.7674 1.68024 +VERTEX2 6092 -73.8378 -41.7065 1.67394 +VERTEX2 6093 -73.9223 -40.694 1.6983 +VERTEX2 6094 -74.012 -39.6846 1.68773 +VERTEX2 6095 -74.1525 -38.6727 1.67719 +VERTEX2 6096 -75.2253 -38.83 -3.02616 +VERTEX2 6097 -76.1954 -38.902 -3.04347 +VERTEX2 6098 -77.1237 -38.9804 -3.0287 +VERTEX2 6099 -78.1749 -39.0375 -3.04072 +VERTEX2 6100 -79.1269 -39.1641 -3.06023 +VERTEX2 6101 -79.2012 -38.1441 1.64933 +VERTEX2 6102 -79.2516 -37.1718 1.65598 +VERTEX2 6103 -79.3525 -36.1777 1.61522 +VERTEX2 6104 -79.4065 -35.159 1.62157 +VERTEX2 6105 -79.4211 -34.1932 1.64192 +VERTEX2 6106 -80.4102 -34.177 -3.06582 +VERTEX2 6107 -81.3861 -34.2881 -3.10696 +VERTEX2 6108 -82.4505 -34.3553 -3.09016 +VERTEX2 6109 -83.4386 -34.4113 -3.08828 +VERTEX2 6110 -84.4656 -34.5137 -3.06663 +VERTEX2 6111 -84.6001 -33.6007 1.66636 +VERTEX2 6112 -84.6303 -32.5688 1.67337 +VERTEX2 6113 -84.7575 -31.6476 1.68848 +VERTEX2 6114 -84.9315 -30.6354 1.67717 +VERTEX2 6115 -85.0937 -29.6091 1.65881 +VERTEX2 6116 -86.1153 -29.8257 -3.04155 +VERTEX2 6117 -86.991 -30.013 -3.0208 +VERTEX2 6118 -87.951 -30.1285 -2.99815 +VERTEX2 6119 -88.9005 -30.2933 -2.97906 +VERTEX2 6120 -89.9103 -30.4828 -2.97951 +VERTEX2 6121 -89.7295 -31.4677 -1.39791 +VERTEX2 6122 -89.5072 -32.341 -1.38874 +VERTEX2 6123 -89.3757 -33.3075 -1.35789 +VERTEX2 6124 -89.1448 -34.2268 -1.34795 +VERTEX2 6125 -88.9364 -35.2538 -1.34535 +VERTEX2 6126 -89.8248 -35.4571 -2.90936 +VERTEX2 6127 -90.8418 -35.6565 -2.94219 +VERTEX2 6128 -91.7928 -35.8379 -2.94773 +VERTEX2 6129 -92.7119 -35.9749 -2.92064 +VERTEX2 6130 -93.7047 -36.0964 -2.91227 +VERTEX2 6131 -93.9323 -35.1819 1.75968 +VERTEX2 6132 -94.1093 -34.207 1.74528 +VERTEX2 6133 -94.2198 -33.2167 1.7611 +VERTEX2 6134 -94.4067 -32.2991 1.76983 +VERTEX2 6135 -94.5558 -31.2995 1.77133 +VERTEX2 6136 -95.4972 -31.4702 -2.92351 +VERTEX2 6137 -96.4786 -31.675 -2.93419 +VERTEX2 6138 -97.4072 -31.8412 -2.95235 +VERTEX2 6139 -98.3249 -32.0116 -2.97248 +VERTEX2 6140 -99.2546 -32.1915 -2.95972 +VERTEX2 6141 -99.0905 -33.1146 -1.3574 +VERTEX2 6142 -98.8731 -34.0318 -1.35845 +VERTEX2 6143 -98.7239 -35.0531 -1.37679 +VERTEX2 6144 -98.5401 -36.0235 -1.37185 +VERTEX2 6145 -98.3508 -36.9776 -1.37152 +VERTEX2 6146 -97.3613 -36.7991 0.179453 +VERTEX2 6147 -96.3592 -36.6174 0.164649 +VERTEX2 6148 -95.385 -36.4116 0.186623 +VERTEX2 6149 -94.4531 -36.1755 0.174273 +VERTEX2 6150 -93.3753 -35.8894 0.173969 +VERTEX2 6151 -93.1646 -36.8555 -1.37798 +VERTEX2 6152 -93.0083 -37.8615 -1.33032 +VERTEX2 6153 -92.7527 -38.814 -1.34278 +VERTEX2 6154 -92.4733 -39.7993 -1.35482 +VERTEX2 6155 -92.3467 -40.756 -1.33463 +VERTEX2 6156 -91.3817 -40.548 0.238223 +VERTEX2 6157 -90.3875 -40.41 0.26063 +VERTEX2 6158 -89.3857 -40.0783 0.225299 +VERTEX2 6159 -88.4019 -39.8958 0.210709 +VERTEX2 6160 -87.4648 -39.64 0.185376 +VERTEX2 6161 -87.6864 -38.6585 1.74065 +VERTEX2 6162 -87.8203 -37.6252 1.75048 +VERTEX2 6163 -88.0046 -36.5149 1.75994 +VERTEX2 6164 -88.1661 -35.4833 1.77098 +VERTEX2 6165 -88.3358 -34.4038 1.74969 +VERTEX2 6166 -87.3229 -34.1485 0.189996 +VERTEX2 6167 -86.2783 -33.9518 0.206331 +VERTEX2 6168 -85.332 -33.7135 0.175411 +VERTEX2 6169 -84.299 -33.5708 0.189777 +VERTEX2 6170 -83.261 -33.3565 0.141259 +VERTEX2 6171 -83.4446 -32.3577 1.7099 +VERTEX2 6172 -83.5591 -31.3062 1.73088 +VERTEX2 6173 -83.8199 -30.3827 1.71968 +VERTEX2 6174 -83.9757 -29.3722 1.73136 +VERTEX2 6175 -84.1307 -28.369 1.73554 +VERTEX2 6176 -85.0521 -28.5358 -3.00048 +VERTEX2 6177 -86.1456 -28.6526 -3.02406 +VERTEX2 6178 -87.125 -28.7801 -3.04941 +VERTEX2 6179 -88.1082 -28.8841 -3.04819 +VERTEX2 6180 -89.1593 -28.9495 -3.07139 +VERTEX2 6181 -89.0874 -29.8637 -1.46533 +VERTEX2 6182 -89.0002 -30.7991 -1.46222 +VERTEX2 6183 -88.913 -31.7602 -1.48485 +VERTEX2 6184 -88.8451 -32.7264 -1.49734 +VERTEX2 6185 -88.7448 -33.8531 -1.54486 +VERTEX2 6186 -87.7007 -33.8395 0.0119257 +VERTEX2 6187 -86.7482 -33.9121 0.040341 +VERTEX2 6188 -85.7973 -33.7874 0.0761346 +VERTEX2 6189 -84.7897 -33.7446 0.0823012 +VERTEX2 6190 -83.7453 -33.6302 0.0611603 +VERTEX2 6191 -83.6232 -34.5434 -1.54021 +VERTEX2 6192 -83.5505 -35.5708 -1.54185 +VERTEX2 6193 -83.5471 -36.6465 -1.53798 +VERTEX2 6194 -83.5285 -37.6574 -1.54157 +VERTEX2 6195 -83.4396 -38.6243 -1.55108 +VERTEX2 6196 -82.3636 -38.6124 0.00114447 +VERTEX2 6197 -81.3599 -38.654 -0.014088 +VERTEX2 6198 -80.3182 -38.628 -0.0237824 +VERTEX2 6199 -79.3417 -38.6184 -0.0103398 +VERTEX2 6200 -78.3167 -38.7345 0.00489277 +VERTEX2 6201 -78.4205 -37.766 1.60293 +VERTEX2 6202 -78.3716 -36.8396 1.57927 +VERTEX2 6203 -78.325 -35.8026 1.58379 +VERTEX2 6204 -78.2861 -34.7781 1.57777 +VERTEX2 6205 -78.3163 -33.7326 1.58306 +VERTEX2 6206 -79.3284 -33.8457 -3.12665 +VERTEX2 6207 -80.3381 -33.8674 -3.11087 +VERTEX2 6208 -81.3532 -33.9217 -3.11416 +VERTEX2 6209 -82.4095 -33.9648 -3.12289 +VERTEX2 6210 -83.3925 -33.9499 -3.12064 +VERTEX2 6211 -83.3782 -34.8871 -1.53779 +VERTEX2 6212 -83.3948 -35.9505 -1.56596 +VERTEX2 6213 -83.3417 -36.8587 -1.59067 +VERTEX2 6214 -83.3629 -37.8522 -1.61199 +VERTEX2 6215 -83.3725 -38.8657 -1.63095 +VERTEX2 6216 -82.3715 -38.9874 -0.0968905 +VERTEX2 6217 -81.3608 -39.0697 -0.0957888 +VERTEX2 6218 -80.3449 -39.1142 -0.0682555 +VERTEX2 6219 -79.3549 -39.171 -0.0665884 +VERTEX2 6220 -78.3741 -39.2377 -0.0595807 +VERTEX2 6221 -78.4933 -40.2601 -1.63903 +VERTEX2 6222 -78.4962 -41.2499 -1.63065 +VERTEX2 6223 -78.5563 -42.305 -1.64318 +VERTEX2 6224 -78.7141 -43.4019 -1.6253 +VERTEX2 6225 -78.7601 -44.4476 -1.62657 +VERTEX2 6226 -79.8458 -44.5049 3.05265 +VERTEX2 6227 -80.8571 -44.4509 3.04279 +VERTEX2 6228 -81.8285 -44.2622 3.00635 +VERTEX2 6229 -82.7429 -44.1189 2.98968 +VERTEX2 6230 -83.7174 -43.9565 2.97341 +VERTEX2 6231 -83.883 -44.9419 -1.7511 +VERTEX2 6232 -84.0974 -45.8703 -1.71434 +VERTEX2 6233 -84.3247 -46.8147 -1.73895 +VERTEX2 6234 -84.4857 -47.8404 -1.73238 +VERTEX2 6235 -84.5617 -48.7517 -1.70166 +VERTEX2 6236 -83.553 -48.925 -0.130756 +VERTEX2 6237 -82.5569 -49.0847 -0.138437 +VERTEX2 6238 -81.6643 -49.1752 -0.143211 +VERTEX2 6239 -80.5517 -49.3322 -0.123588 +VERTEX2 6240 -79.502 -49.4209 -0.120967 +VERTEX2 6241 -79.3676 -48.3457 1.46946 +VERTEX2 6242 -79.1932 -47.3198 1.45892 +VERTEX2 6243 -79.0688 -46.3361 1.43922 +VERTEX2 6244 -78.9478 -45.3624 1.43943 +VERTEX2 6245 -78.8163 -44.4738 1.44013 +VERTEX2 6246 -77.9294 -44.5614 -0.104276 +VERTEX2 6247 -77.0001 -44.6719 -0.133839 +VERTEX2 6248 -76.0019 -44.9316 -0.174378 +VERTEX2 6249 -75.0696 -45.0598 -0.196733 +VERTEX2 6250 -74.1112 -45.3041 -0.190011 +VERTEX2 6251 -73.8488 -44.4066 1.37139 +VERTEX2 6252 -73.6917 -43.4398 1.36677 +VERTEX2 6253 -73.4903 -42.4536 1.37385 +VERTEX2 6254 -73.3114 -41.5234 1.3897 +VERTEX2 6255 -73.1623 -40.5684 1.38046 +VERTEX2 6256 -74.198 -40.386 2.94178 +VERTEX2 6257 -75.1505 -40.134 2.93764 +VERTEX2 6258 -76.0919 -39.9699 2.96587 +VERTEX2 6259 -77.1504 -39.8113 2.98654 +VERTEX2 6260 -78.1107 -39.6496 3.00005 +VERTEX2 6261 -78.2664 -40.6823 -1.74126 +VERTEX2 6262 -78.4225 -41.6121 -1.71968 +VERTEX2 6263 -78.6102 -42.5622 -1.72136 +VERTEX2 6264 -78.7108 -43.6243 -1.68367 +VERTEX2 6265 -78.8194 -44.5088 -1.7022 +VERTEX2 6266 -79.824 -44.3907 3.01863 +VERTEX2 6267 -80.8663 -44.226 3.00441 +VERTEX2 6268 -81.8111 -44.0337 3.04574 +VERTEX2 6269 -82.7709 -43.9158 3.06826 +VERTEX2 6270 -83.7136 -43.8313 3.10321 +VERTEX2 6271 -83.7786 -44.8335 -1.62473 +VERTEX2 6272 -83.8375 -45.8761 -1.61866 +VERTEX2 6273 -83.8505 -46.8644 -1.63344 +VERTEX2 6274 -83.8413 -47.9346 -1.5807 +VERTEX2 6275 -83.8125 -48.9409 -1.56779 +VERTEX2 6276 -84.7963 -48.9764 -3.1157 +VERTEX2 6277 -85.8226 -48.9975 -3.1181 +VERTEX2 6278 -86.8095 -48.9751 -3.09576 +VERTEX2 6279 -87.8054 -48.9137 -3.12569 +VERTEX2 6280 -88.7846 -48.9212 -3.10644 +VERTEX2 6281 -88.8198 -47.9435 1.60069 +VERTEX2 6282 -88.8367 -46.9002 1.5749 +VERTEX2 6283 -88.8632 -45.9582 1.55103 +VERTEX2 6284 -88.8784 -44.991 1.56185 +VERTEX2 6285 -88.8212 -44.0061 1.56744 +VERTEX2 6286 -89.7787 -44.0267 3.13614 +VERTEX2 6287 -90.8275 -43.983 3.11473 +VERTEX2 6288 -91.8505 -44.0507 3.12595 +VERTEX2 6289 -92.9116 -44.0093 -3.13812 +VERTEX2 6290 -93.8986 -43.944 -3.13528 +VERTEX2 6291 -93.9473 -44.8748 -1.58523 +VERTEX2 6292 -93.9498 -45.8453 -1.59358 +VERTEX2 6293 -94.0137 -46.8399 -1.59079 +VERTEX2 6294 -93.9834 -47.9159 -1.61317 +VERTEX2 6295 -93.9661 -48.891 -1.61285 +VERTEX2 6296 -92.9645 -48.9471 0.00222777 +VERTEX2 6297 -91.9506 -48.8678 -0.0281307 +VERTEX2 6298 -90.9594 -48.8478 -0.0359985 +VERTEX2 6299 -89.9132 -48.8644 -0.0223417 +VERTEX2 6300 -88.9157 -48.8376 -0.00144769 +VERTEX2 6301 -88.8609 -49.7789 -1.57084 +VERTEX2 6302 -88.7949 -50.7268 -1.5975 +VERTEX2 6303 -88.7977 -51.7309 -1.61782 +VERTEX2 6304 -88.8657 -52.6986 -1.6165 +VERTEX2 6305 -88.8715 -53.7499 -1.59657 +VERTEX2 6306 -87.8591 -53.7889 -0.03719 +VERTEX2 6307 -86.8916 -53.7886 -0.0287355 +VERTEX2 6308 -85.8467 -53.8445 -0.0357096 +VERTEX2 6309 -84.8972 -53.8845 -0.0425316 +VERTEX2 6310 -83.9602 -53.9199 -0.0366193 +VERTEX2 6311 -83.937 -52.879 1.5541 +VERTEX2 6312 -83.9094 -51.8145 1.52229 +VERTEX2 6313 -83.8888 -50.7096 1.53695 +VERTEX2 6314 -83.7941 -49.6871 1.50824 +VERTEX2 6315 -83.7923 -48.7213 1.53751 +VERTEX2 6316 -84.7812 -48.764 3.10597 +VERTEX2 6317 -85.8269 -48.73 3.09449 +VERTEX2 6318 -86.8144 -48.7004 3.09916 +VERTEX2 6319 -87.8922 -48.6374 3.09952 +VERTEX2 6320 -88.8559 -48.6685 3.09399 +VERTEX2 6321 -88.8435 -47.7146 1.53973 +VERTEX2 6322 -88.7826 -46.7029 1.53209 +VERTEX2 6323 -88.6367 -45.6484 1.50425 +VERTEX2 6324 -88.6036 -44.6576 1.5001 +VERTEX2 6325 -88.5374 -43.6216 1.49711 +VERTEX2 6326 -89.5318 -43.5294 3.06476 +VERTEX2 6327 -90.564 -43.4707 3.05586 +VERTEX2 6328 -91.6068 -43.3762 3.00837 +VERTEX2 6329 -92.6297 -43.2215 3.00658 +VERTEX2 6330 -93.6316 -43.0298 3.04442 +VERTEX2 6331 -93.5448 -41.9843 1.46243 +VERTEX2 6332 -93.447 -40.9204 1.47446 +VERTEX2 6333 -93.4074 -39.867 1.46389 +VERTEX2 6334 -93.3628 -38.8357 1.49223 +VERTEX2 6335 -93.259 -37.8511 1.50759 +VERTEX2 6336 -94.2235 -37.7072 3.09374 +VERTEX2 6337 -95.2014 -37.7497 3.10198 +VERTEX2 6338 -96.2094 -37.6571 3.08897 +VERTEX2 6339 -97.1761 -37.5135 3.10791 +VERTEX2 6340 -98.285 -37.5618 3.07644 +VERTEX2 6341 -98.1987 -36.5922 1.50587 +VERTEX2 6342 -98.1079 -35.5781 1.48886 +VERTEX2 6343 -98.03 -34.5473 1.50777 +VERTEX2 6344 -97.8941 -33.509 1.52018 +VERTEX2 6345 -97.8331 -32.5724 1.49926 +VERTEX2 6346 -98.8297 -32.55 3.03244 +VERTEX2 6347 -99.7692 -32.5238 3.02735 +VERTEX2 6348 -100.8 -32.4002 3.04141 +VERTEX2 6349 -101.7 -32.2598 3.06044 +VERTEX2 6350 -102.671 -32.16 3.0669 +VERTEX2 6351 -102.783 -33.0727 -1.67166 +VERTEX2 6352 -102.829 -34.0325 -1.68169 +VERTEX2 6353 -102.931 -35.0109 -1.68602 +VERTEX2 6354 -103.16 -36 -1.68007 +VERTEX2 6355 -103.284 -37.0661 -1.69407 +VERTEX2 6356 -104.243 -36.883 3.03613 +VERTEX2 6357 -105.229 -36.7552 3.03295 +VERTEX2 6358 -106.215 -36.7327 3.05036 +VERTEX2 6359 -107.239 -36.6979 3.05293 +VERTEX2 6360 -108.285 -36.6504 3.06755 +VERTEX2 6361 -108.347 -37.6408 -1.61707 +VERTEX2 6362 -108.403 -38.5931 -1.6455 +VERTEX2 6363 -108.433 -39.5314 -1.65248 +VERTEX2 6364 -108.469 -40.4617 -1.63698 +VERTEX2 6365 -108.693 -41.418 -1.60678 +VERTEX2 6366 -107.693 -41.3618 -0.00842936 +VERTEX2 6367 -106.678 -41.4622 0.00565403 +VERTEX2 6368 -105.753 -41.5342 -0.0244463 +VERTEX2 6369 -104.74 -41.5365 -0.0127125 +VERTEX2 6370 -103.681 -41.4573 0.0109387 +VERTEX2 6371 -103.587 -40.4239 1.61081 +VERTEX2 6372 -103.5 -39.4052 1.65598 +VERTEX2 6373 -103.569 -38.3412 1.69895 +VERTEX2 6374 -103.678 -37.2788 1.67389 +VERTEX2 6375 -103.892 -36.243 1.67615 +VERTEX2 6376 -102.89 -36.1853 0.0985972 +VERTEX2 6377 -101.903 -36.0864 0.0786757 +VERTEX2 6378 -100.88 -36.0515 0.0759905 +VERTEX2 6379 -99.9317 -36.0217 0.0733796 +VERTEX2 6380 -99.0022 -35.9607 0.081027 +VERTEX2 6381 -98.901 -36.9139 -1.49353 +VERTEX2 6382 -98.9247 -37.8999 -1.48123 +VERTEX2 6383 -98.8459 -38.9023 -1.47607 +VERTEX2 6384 -98.7025 -39.8171 -1.48961 +VERTEX2 6385 -98.6509 -40.8246 -1.48929 +VERTEX2 6386 -97.6038 -40.784 0.0651093 +VERTEX2 6387 -96.6264 -40.7695 0.0558695 +VERTEX2 6388 -95.6397 -40.7406 0.0572899 +VERTEX2 6389 -94.6501 -40.6994 0.0613327 +VERTEX2 6390 -93.6972 -40.5482 0.0694693 +VERTEX2 6391 -93.7692 -39.5536 1.61592 +VERTEX2 6392 -93.8343 -38.5279 1.59025 +VERTEX2 6393 -93.81 -37.4395 1.59124 +VERTEX2 6394 -93.879 -36.4361 1.59227 +VERTEX2 6395 -93.8111 -35.4199 1.62927 +VERTEX2 6396 -92.8643 -35.3441 0.0166728 +VERTEX2 6397 -91.8779 -35.3867 -0.00839612 +VERTEX2 6398 -90.7986 -35.3865 -0.0132777 +VERTEX2 6399 -89.8082 -35.4247 -0.0107773 +VERTEX2 6400 -88.8307 -35.4021 -0.0195343 +VERTEX2 6401 -88.7956 -36.337 -1.61861 +VERTEX2 6402 -88.9589 -37.3102 -1.63209 +VERTEX2 6403 -89.0043 -38.2905 -1.65564 +VERTEX2 6404 -89.1429 -39.2778 -1.66597 +VERTEX2 6405 -89.3124 -40.2387 -1.64357 +VERTEX2 6406 -90.3022 -40.0742 3.01989 +VERTEX2 6407 -91.3108 -40.0004 3.0579 +VERTEX2 6408 -92.2323 -39.9434 3.0561 +VERTEX2 6409 -93.3541 -39.8828 3.0403 +VERTEX2 6410 -94.334 -39.7738 3.01437 +VERTEX2 6411 -94.5162 -40.7556 -1.69472 +VERTEX2 6412 -94.7474 -41.7704 -1.73533 +VERTEX2 6413 -94.9009 -42.7347 -1.71283 +VERTEX2 6414 -95.0477 -43.8077 -1.72473 +VERTEX2 6415 -95.2187 -44.8173 -1.72541 +VERTEX2 6416 -96.1707 -44.587 2.99989 +VERTEX2 6417 -97.2145 -44.4282 3.02808 +VERTEX2 6418 -98.1843 -44.2723 3.01402 +VERTEX2 6419 -99.1851 -44.164 3.01046 +VERTEX2 6420 -100.13 -43.9849 3.00899 +VERTEX2 6421 -100.282 -44.9458 -1.67089 +VERTEX2 6422 -100.424 -45.9631 -1.65025 +VERTEX2 6423 -100.482 -46.9527 -1.6862 +VERTEX2 6424 -100.523 -47.8978 -1.67239 +VERTEX2 6425 -100.531 -48.8468 -1.67511 +VERTEX2 6426 -99.5733 -48.8612 -0.0835822 +VERTEX2 6427 -98.6279 -48.9539 -0.0494284 +VERTEX2 6428 -97.6489 -48.9233 -0.046855 +VERTEX2 6429 -96.7124 -48.9084 -0.0279074 +VERTEX2 6430 -95.6672 -48.9508 -0.0158817 +VERTEX2 6431 -95.7512 -47.9396 1.5692 +VERTEX2 6432 -95.746 -46.8687 1.57533 +VERTEX2 6433 -95.7107 -45.854 1.58456 +VERTEX2 6434 -95.7491 -44.9341 1.56815 +VERTEX2 6435 -95.7204 -43.9265 1.55897 +VERTEX2 6436 -96.7773 -43.8196 3.13104 +VERTEX2 6437 -97.7767 -43.8563 -3.11063 +VERTEX2 6438 -98.7525 -43.8688 -3.10964 +VERTEX2 6439 -99.7553 -43.8896 -3.08813 +VERTEX2 6440 -100.75 -43.9514 -3.11633 +VERTEX2 6441 -100.701 -44.9781 -1.57522 +VERTEX2 6442 -100.709 -46.0783 -1.5592 +VERTEX2 6443 -100.701 -47.1151 -1.58237 +VERTEX2 6444 -100.686 -48.0548 -1.62464 +VERTEX2 6445 -100.743 -49.0291 -1.62687 +VERTEX2 6446 -99.8433 -49.0824 -0.0643356 +VERTEX2 6447 -98.8798 -49.1661 -0.0394945 +VERTEX2 6448 -97.8727 -49.2252 -0.0236482 +VERTEX2 6449 -96.8446 -49.2192 0.027166 +VERTEX2 6450 -95.7737 -49.197 -0.0126856 +VERTEX2 6451 -95.7496 -48.1841 1.54409 +VERTEX2 6452 -95.7336 -47.224 1.51124 +VERTEX2 6453 -95.6625 -46.2938 1.53225 +VERTEX2 6454 -95.5721 -45.3232 1.53901 +VERTEX2 6455 -95.5636 -44.4075 1.52552 +VERTEX2 6456 -96.5397 -44.3867 3.11699 +VERTEX2 6457 -97.5894 -44.357 -3.13138 +VERTEX2 6458 -98.5593 -44.4008 3.13212 +VERTEX2 6459 -99.5784 -44.3792 3.14075 +VERTEX2 6460 -100.501 -44.3829 -3.13105 +VERTEX2 6461 -100.536 -45.3547 -1.54156 +VERTEX2 6462 -100.477 -46.4448 -1.55683 +VERTEX2 6463 -100.448 -47.44 -1.51934 +VERTEX2 6464 -100.279 -48.3664 -1.54131 +VERTEX2 6465 -100.302 -49.4504 -1.52185 +VERTEX2 6466 -99.2989 -49.41 0.0354043 +VERTEX2 6467 -98.3601 -49.3202 0.0423868 +VERTEX2 6468 -97.3218 -49.2453 0.0596215 +VERTEX2 6469 -96.2895 -49.1896 0.0771093 +VERTEX2 6470 -95.3295 -49.1244 0.0709682 +VERTEX2 6471 -95.3718 -50.1276 -1.51089 +VERTEX2 6472 -95.3383 -51.1494 -1.47426 +VERTEX2 6473 -95.2895 -52.17 -1.46504 +VERTEX2 6474 -95.2151 -53.1187 -1.435 +VERTEX2 6475 -95.1736 -54.0551 -1.42472 +VERTEX2 6476 -94.2108 -53.8318 0.14928 +VERTEX2 6477 -93.167 -53.6973 0.152449 +VERTEX2 6478 -92.1964 -53.6397 0.134872 +VERTEX2 6479 -91.2066 -53.4346 0.146403 +VERTEX2 6480 -90.1622 -53.3423 0.128697 +VERTEX2 6481 -90.2393 -52.4041 1.73859 +VERTEX2 6482 -90.4221 -51.4034 1.72972 +VERTEX2 6483 -90.506 -50.4925 1.74593 +VERTEX2 6484 -90.6605 -49.5094 1.73429 +VERTEX2 6485 -90.896 -48.5173 1.7117 +VERTEX2 6486 -91.8643 -48.6732 -2.98106 +VERTEX2 6487 -92.8315 -48.8108 -2.95817 +VERTEX2 6488 -93.7456 -48.9019 -2.92117 +VERTEX2 6489 -94.7305 -49.1403 -2.9249 +VERTEX2 6490 -95.7157 -49.3453 -2.92078 +VERTEX2 6491 -95.5081 -50.3351 -1.32906 +VERTEX2 6492 -95.2999 -51.3107 -1.32659 +VERTEX2 6493 -95.0451 -52.3757 -1.32459 +VERTEX2 6494 -94.8115 -53.3751 -1.34213 +VERTEX2 6495 -94.5383 -54.3792 -1.33593 +VERTEX2 6496 -93.4344 -54.0372 0.223976 +VERTEX2 6497 -92.4883 -53.8199 0.193522 +VERTEX2 6498 -91.5195 -53.5997 0.200993 +VERTEX2 6499 -90.4578 -53.3649 0.200161 +VERTEX2 6500 -89.6088 -53.1573 0.18122 +VERTEX2 6501 -89.6904 -52.167 1.74446 +VERTEX2 6502 -89.9046 -51.1389 1.74031 +VERTEX2 6503 -90.0382 -50.1289 1.70003 +VERTEX2 6504 -90.2226 -49.2017 1.68502 +VERTEX2 6505 -90.3334 -48.125 1.67217 +VERTEX2 6506 -91.2338 -48.2719 -3.06584 +VERTEX2 6507 -92.3344 -48.3239 -3.03582 +VERTEX2 6508 -93.4328 -48.4828 -3.02993 +VERTEX2 6509 -94.4664 -48.5822 -3.05327 +VERTEX2 6510 -95.434 -48.7224 -3.07682 +VERTEX2 6511 -95.3694 -49.7042 -1.50764 +VERTEX2 6512 -95.3021 -50.7269 -1.53654 +VERTEX2 6513 -95.1587 -51.7554 -1.53983 +VERTEX2 6514 -95.1187 -52.7355 -1.51026 +VERTEX2 6515 -95.0588 -53.7052 -1.55068 +VERTEX2 6516 -96.0224 -53.6817 -3.13405 +VERTEX2 6517 -97.0858 -53.7483 3.14159 +VERTEX2 6518 -98.0857 -53.7381 -3.11039 +VERTEX2 6519 -99.0897 -53.7632 -3.1234 +VERTEX2 6520 -100.039 -53.7574 -3.13403 +VERTEX2 6521 -100.014 -54.7467 -1.5764 +VERTEX2 6522 -100.107 -55.7493 -1.60469 +VERTEX2 6523 -100.141 -56.684 -1.57013 +VERTEX2 6524 -100.122 -57.6244 -1.56537 +VERTEX2 6525 -100.014 -58.6573 -1.57128 +VERTEX2 6526 -101.033 -58.7465 3.12797 +VERTEX2 6527 -102.13 -58.7435 3.13827 +VERTEX2 6528 -103.141 -58.7492 -3.12456 +VERTEX2 6529 -104.165 -58.7483 3.14155 +VERTEX2 6530 -105.23 -58.7341 3.1053 +VERTEX2 6531 -105.194 -59.6881 -1.60419 +VERTEX2 6532 -105.243 -60.6534 -1.60673 +VERTEX2 6533 -105.378 -61.6587 -1.58128 +VERTEX2 6534 -105.32 -62.6707 -1.57936 +VERTEX2 6535 -105.247 -63.633 -1.60964 +VERTEX2 6536 -104.265 -63.6819 -0.0237791 +VERTEX2 6537 -103.245 -63.7135 -0.0481741 +VERTEX2 6538 -102.301 -63.8168 -0.0568929 +VERTEX2 6539 -101.292 -63.9079 -0.0609568 +VERTEX2 6540 -100.299 -63.9586 -0.0490849 +VERTEX2 6541 -100.271 -64.9398 -1.62309 +VERTEX2 6542 -100.346 -66.0226 -1.58307 +VERTEX2 6543 -100.364 -66.984 -1.56682 +VERTEX2 6544 -100.362 -68.0238 -1.5504 +VERTEX2 6545 -100.356 -69.0232 -1.56565 +VERTEX2 6546 -101.252 -68.9643 -3.1334 +VERTEX2 6547 -102.184 -68.972 -3.10631 +VERTEX2 6548 -103.201 -69.0137 -3.13771 +VERTEX2 6549 -104.201 -68.9797 3.12802 +VERTEX2 6550 -105.026 -68.9795 3.11077 +VERTEX2 6551 -105.05 -69.9605 -1.63076 +VERTEX2 6552 -105.083 -70.9715 -1.65785 +VERTEX2 6553 -105.202 -71.9314 -1.66734 +VERTEX2 6554 -105.275 -72.94 -1.65421 +VERTEX2 6555 -105.342 -73.8947 -1.65435 +VERTEX2 6556 -104.239 -73.895 -0.0725565 +VERTEX2 6557 -103.257 -73.9362 -0.0447162 +VERTEX2 6558 -102.253 -73.8788 -0.0620724 +VERTEX2 6559 -101.211 -73.9343 -0.0619649 +VERTEX2 6560 -100.173 -74.0048 -0.0299364 +VERTEX2 6561 -100.134 -72.9187 1.50767 +VERTEX2 6562 -100.134 -72.022 1.45429 +VERTEX2 6563 -100.032 -71.0362 1.45871 +VERTEX2 6564 -99.9317 -70.0452 1.46029 +VERTEX2 6565 -99.8936 -69.0624 1.43798 +VERTEX2 6566 -100.888 -68.9126 3.00099 +VERTEX2 6567 -101.899 -68.7522 2.99074 +VERTEX2 6568 -102.909 -68.5745 3.02372 +VERTEX2 6569 -103.886 -68.4317 3.0306 +VERTEX2 6570 -104.882 -68.3201 3.02741 +VERTEX2 6571 -104.998 -69.2836 -1.7057 +VERTEX2 6572 -105.093 -70.3169 -1.68263 +VERTEX2 6573 -105.169 -71.2491 -1.6858 +VERTEX2 6574 -105.237 -72.1902 -1.68018 +VERTEX2 6575 -105.347 -73.1367 -1.68323 +VERTEX2 6576 -104.309 -73.2041 -0.0784054 +VERTEX2 6577 -103.267 -73.2789 -0.0862606 +VERTEX2 6578 -102.24 -73.3255 -0.125255 +VERTEX2 6579 -101.21 -73.4175 -0.115629 +VERTEX2 6580 -100.203 -73.6281 -0.0830754 +VERTEX2 6581 -100.046 -72.6823 1.47611 +VERTEX2 6582 -99.9229 -71.7443 1.46364 +VERTEX2 6583 -99.8195 -70.7598 1.47171 +VERTEX2 6584 -99.7728 -69.7371 1.44658 +VERTEX2 6585 -99.6032 -68.7345 1.45004 +VERTEX2 6586 -100.625 -68.7341 3.02777 +VERTEX2 6587 -101.619 -68.651 3.02072 +VERTEX2 6588 -102.661 -68.5207 3.04633 +VERTEX2 6589 -103.733 -68.4573 3.00955 +VERTEX2 6590 -104.805 -68.358 3.02314 +VERTEX2 6591 -104.667 -67.3859 1.43963 +VERTEX2 6592 -104.552 -66.4973 1.46176 +VERTEX2 6593 -104.461 -65.5085 1.44541 +VERTEX2 6594 -104.295 -64.464 1.48237 +VERTEX2 6595 -104.161 -63.542 1.47522 +VERTEX2 6596 -105.173 -63.4167 3.07516 +VERTEX2 6597 -106.232 -63.382 3.05905 +VERTEX2 6598 -107.261 -63.1845 3.00764 +VERTEX2 6599 -108.233 -62.9393 2.9865 +VERTEX2 6600 -109.165 -62.7824 2.95999 +VERTEX2 6601 -108.988 -61.731 1.40044 +VERTEX2 6602 -108.777 -60.7831 1.41561 +VERTEX2 6603 -108.584 -59.818 1.40456 +VERTEX2 6604 -108.454 -58.8597 1.41875 +VERTEX2 6605 -108.324 -57.9287 1.44937 +VERTEX2 6606 -109.235 -57.833 3.037 +VERTEX2 6607 -110.274 -57.8101 3.06861 +VERTEX2 6608 -111.195 -57.7293 3.07983 +VERTEX2 6609 -112.276 -57.6486 3.09012 +VERTEX2 6610 -113.272 -57.7022 3.10023 +VERTEX2 6611 -113.259 -58.5997 -1.59979 +VERTEX2 6612 -113.238 -59.6138 -1.61541 +VERTEX2 6613 -113.305 -60.6226 -1.60036 +VERTEX2 6614 -113.381 -61.5492 -1.59074 +VERTEX2 6615 -113.47 -62.5296 -1.55178 +VERTEX2 6616 -112.475 -62.4943 0.0315598 +VERTEX2 6617 -111.541 -62.4322 0.0465775 +VERTEX2 6618 -110.506 -62.4513 0.045891 +VERTEX2 6619 -109.575 -62.3474 0.0574613 +VERTEX2 6620 -108.609 -62.2963 0.069921 +VERTEX2 6621 -108.512 -63.325 -1.526 +VERTEX2 6622 -108.463 -64.3559 -1.53244 +VERTEX2 6623 -108.393 -65.3489 -1.5471 +VERTEX2 6624 -108.418 -66.3442 -1.56909 +VERTEX2 6625 -108.397 -67.3326 -1.58594 +VERTEX2 6626 -107.377 -67.3702 -0.0181997 +VERTEX2 6627 -106.341 -67.2485 -0.014525 +VERTEX2 6628 -105.342 -67.2703 -0.0576866 +VERTEX2 6629 -104.371 -67.3512 -0.100681 +VERTEX2 6630 -103.29 -67.3334 -0.0811012 +VERTEX2 6631 -103.332 -66.3863 1.48381 +VERTEX2 6632 -103.246 -65.3104 1.47477 +VERTEX2 6633 -103.076 -64.3952 1.46287 +VERTEX2 6634 -102.989 -63.417 1.43489 +VERTEX2 6635 -102.827 -62.3526 1.4227 +VERTEX2 6636 -103.849 -62.228 2.99233 +VERTEX2 6637 -104.743 -62.0101 3.03497 +VERTEX2 6638 -105.629 -61.9372 3.03333 +VERTEX2 6639 -106.522 -61.7991 3.06498 +VERTEX2 6640 -107.494 -61.67 3.04849 +VERTEX2 6641 -107.536 -62.6649 -1.64674 +VERTEX2 6642 -107.629 -63.6236 -1.63912 +VERTEX2 6643 -107.683 -64.6102 -1.6509 +VERTEX2 6644 -107.745 -65.6398 -1.67496 +VERTEX2 6645 -107.93 -66.5673 -1.66076 +VERTEX2 6646 -106.97 -66.7233 -0.0928057 +VERTEX2 6647 -105.999 -66.8608 -0.0780668 +VERTEX2 6648 -105.008 -66.9634 -0.0913592 +VERTEX2 6649 -103.949 -67.0488 -0.0923287 +VERTEX2 6650 -102.954 -67.1391 -0.0938945 +VERTEX2 6651 -102.772 -66.1208 1.46548 +VERTEX2 6652 -102.678 -65.1065 1.4905 +VERTEX2 6653 -102.581 -64.0713 1.49183 +VERTEX2 6654 -102.554 -63.0498 1.47874 +VERTEX2 6655 -102.435 -61.9914 1.49073 +VERTEX2 6656 -101.475 -62.0985 -0.0748341 +VERTEX2 6657 -100.48 -62.2172 -0.103901 +VERTEX2 6658 -99.4742 -62.2113 -0.108843 +VERTEX2 6659 -98.5623 -62.3381 -0.0850021 +VERTEX2 6660 -97.5249 -62.3756 -0.0712402 +VERTEX2 6661 -97.506 -61.3598 1.5003 +VERTEX2 6662 -97.4266 -60.4153 1.53233 +VERTEX2 6663 -97.4149 -59.3817 1.54115 +VERTEX2 6664 -97.4645 -58.3458 1.53864 +VERTEX2 6665 -97.38 -57.2739 1.56365 +VERTEX2 6666 -98.3402 -57.3762 -3.13751 +VERTEX2 6667 -99.2558 -57.4007 3.12097 +VERTEX2 6668 -100.28 -57.3624 3.14102 +VERTEX2 6669 -101.295 -57.3609 3.13123 +VERTEX2 6670 -102.312 -57.3014 -3.14012 +VERTEX2 6671 -102.296 -58.3297 -1.58197 +VERTEX2 6672 -102.361 -59.2678 -1.58595 +VERTEX2 6673 -102.369 -60.2866 -1.59346 +VERTEX2 6674 -102.413 -61.2642 -1.58538 +VERTEX2 6675 -102.366 -62.2993 -1.5697 +VERTEX2 6676 -103.427 -62.3094 -3.13891 +VERTEX2 6677 -104.362 -62.335 -3.12506 +VERTEX2 6678 -105.416 -62.2898 -3.12763 +VERTEX2 6679 -106.516 -62.336 3.12738 +VERTEX2 6680 -107.509 -62.2771 3.1332 +VERTEX2 6681 -107.483 -63.2535 -1.5859 +VERTEX2 6682 -107.527 -64.3214 -1.58436 +VERTEX2 6683 -107.54 -65.2555 -1.57528 +VERTEX2 6684 -107.498 -66.2178 -1.55426 +VERTEX2 6685 -107.465 -67.2308 -1.54504 +VERTEX2 6686 -106.416 -67.1771 0.0181466 +VERTEX2 6687 -105.346 -67.1205 0.0216812 +VERTEX2 6688 -104.318 -67.0908 0.0186813 +VERTEX2 6689 -103.273 -67.095 0.00113823 +VERTEX2 6690 -102.288 -67.1369 0.0215079 +VERTEX2 6691 -102.243 -68.1001 -1.52769 +VERTEX2 6692 -102.225 -69.1282 -1.53315 +VERTEX2 6693 -102.214 -70.1379 -1.53735 +VERTEX2 6694 -102.192 -71.1392 -1.53379 +VERTEX2 6695 -102.062 -72.1986 -1.54335 +VERTEX2 6696 -103.052 -72.2054 -3.09392 +VERTEX2 6697 -104.15 -72.2958 -3.08061 +VERTEX2 6698 -105.136 -72.3093 -3.09269 +VERTEX2 6699 -106.106 -72.3524 -3.07149 +VERTEX2 6700 -107.134 -72.4292 -3.05714 +VERTEX2 6701 -107.018 -73.4688 -1.50688 +VERTEX2 6702 -106.867 -74.4503 -1.46632 +VERTEX2 6703 -106.635 -75.4215 -1.4631 +VERTEX2 6704 -106.496 -76.5479 -1.46203 +VERTEX2 6705 -106.484 -77.6055 -1.46631 +VERTEX2 6706 -105.502 -77.5059 0.105828 +VERTEX2 6707 -104.55 -77.3477 0.148933 +VERTEX2 6708 -103.527 -77.2112 0.186381 +VERTEX2 6709 -102.522 -77.0226 0.20275 +VERTEX2 6710 -101.433 -76.7085 0.197262 +VERTEX2 6711 -101.211 -77.6428 -1.38152 +VERTEX2 6712 -101.003 -78.7137 -1.40659 +VERTEX2 6713 -100.878 -79.6478 -1.38364 +VERTEX2 6714 -100.751 -80.5889 -1.3686 +VERTEX2 6715 -100.461 -81.6324 -1.39081 +VERTEX2 6716 -101.46 -81.8424 -2.96053 +VERTEX2 6717 -102.449 -82.0844 -2.9698 +VERTEX2 6718 -103.423 -82.2518 -2.98125 +VERTEX2 6719 -104.382 -82.3526 -2.98251 +VERTEX2 6720 -105.408 -82.528 -2.9693 +VERTEX2 6721 -105.238 -83.5967 -1.3927 +VERTEX2 6722 -105.061 -84.694 -1.40902 +VERTEX2 6723 -104.95 -85.6832 -1.40929 +VERTEX2 6724 -104.821 -86.6727 -1.40584 +VERTEX2 6725 -104.632 -87.6575 -1.41215 +VERTEX2 6726 -103.637 -87.3764 0.142355 +VERTEX2 6727 -102.75 -87.2346 0.11597 +VERTEX2 6728 -101.673 -87.1418 0.107584 +VERTEX2 6729 -100.714 -87.0685 0.105684 +VERTEX2 6730 -99.743 -87.0447 0.0868742 +VERTEX2 6731 -99.7692 -85.9888 1.66668 +VERTEX2 6732 -99.8644 -84.9353 1.66308 +VERTEX2 6733 -99.8526 -83.8664 1.66052 +VERTEX2 6734 -99.8831 -82.9146 1.68151 +VERTEX2 6735 -99.9861 -81.8937 1.68269 +VERTEX2 6736 -100.958 -81.991 -3.04732 +VERTEX2 6737 -101.956 -82.0951 -3.07211 +VERTEX2 6738 -102.954 -82.2478 -3.08901 +VERTEX2 6739 -103.909 -82.3205 -3.07924 +VERTEX2 6740 -104.848 -82.4495 -3.03822 +VERTEX2 6741 -104.922 -81.5015 1.65244 +VERTEX2 6742 -105.015 -80.3963 1.67283 +VERTEX2 6743 -105.047 -79.444 1.67681 +VERTEX2 6744 -105.226 -78.4333 1.68223 +VERTEX2 6745 -105.304 -77.4282 1.70206 +VERTEX2 6746 -106.312 -77.5909 -2.98774 +VERTEX2 6747 -107.2 -77.7573 -2.98451 +VERTEX2 6748 -108.213 -77.8853 -3.04457 +VERTEX2 6749 -109.185 -77.9627 -3.06618 +VERTEX2 6750 -110.206 -78.013 -3.04518 +VERTEX2 6751 -110.393 -76.9709 1.61682 +VERTEX2 6752 -110.436 -76.0587 1.59915 +VERTEX2 6753 -110.507 -75.0535 1.60663 +VERTEX2 6754 -110.507 -74.0683 1.57492 +VERTEX2 6755 -110.46 -73.1052 1.58903 +VERTEX2 6756 -111.564 -73.1228 -3.11485 +VERTEX2 6757 -112.591 -73.2062 3.13318 +VERTEX2 6758 -113.623 -73.1758 3.12287 +VERTEX2 6759 -114.665 -73.0865 -3.13622 +VERTEX2 6760 -115.625 -73.0505 -3.11596 +VERTEX2 6761 -115.553 -74.0628 -1.57515 +VERTEX2 6762 -115.596 -75.0356 -1.55251 +VERTEX2 6763 -115.647 -75.9606 -1.55042 +VERTEX2 6764 -115.602 -76.9382 -1.56834 +VERTEX2 6765 -115.707 -77.9713 -1.60451 +VERTEX2 6766 -116.721 -77.9921 3.09612 +VERTEX2 6767 -117.745 -77.9981 3.11279 +VERTEX2 6768 -118.789 -77.9169 3.09958 +VERTEX2 6769 -119.831 -77.8464 3.09895 +VERTEX2 6770 -120.802 -77.7875 3.10884 +VERTEX2 6771 -120.823 -78.7233 -1.60535 +VERTEX2 6772 -120.844 -79.7078 -1.62295 +VERTEX2 6773 -120.901 -80.6941 -1.61446 +VERTEX2 6774 -120.989 -81.7231 -1.6335 +VERTEX2 6775 -121.109 -82.6657 -1.64764 +VERTEX2 6776 -120.139 -82.7202 -0.0675466 +VERTEX2 6777 -119.154 -82.7114 -0.08861 +VERTEX2 6778 -118.233 -82.7937 -0.105165 +VERTEX2 6779 -117.246 -82.9355 -0.112463 +VERTEX2 6780 -116.363 -83.0717 -0.124517 +VERTEX2 6781 -116.18 -82.0273 1.45555 +VERTEX2 6782 -116.091 -81.0523 1.45521 +VERTEX2 6783 -115.997 -80.0374 1.46921 +VERTEX2 6784 -115.974 -79.0184 1.51229 +VERTEX2 6785 -115.879 -78.15 1.52721 +VERTEX2 6786 -116.838 -78.1811 3.11883 +VERTEX2 6787 -117.773 -78.0823 3.13807 +VERTEX2 6788 -118.843 -77.9935 -3.10897 +VERTEX2 6789 -119.831 -78.0245 -3.06146 +VERTEX2 6790 -120.796 -78.0867 -3.09 +VERTEX2 6791 -120.797 -79.1296 -1.48442 +VERTEX2 6792 -120.676 -80.1401 -1.50205 +VERTEX2 6793 -120.66 -81.2109 -1.52281 +VERTEX2 6794 -120.618 -82.2556 -1.52777 +VERTEX2 6795 -120.577 -83.2318 -1.49381 +VERTEX2 6796 -119.558 -83.1726 0.0639852 +VERTEX2 6797 -118.588 -83.0885 0.05005 +VERTEX2 6798 -117.623 -83.1056 0.0756003 +VERTEX2 6799 -116.652 -83.0848 0.0829253 +VERTEX2 6800 -115.536 -83.0085 0.105952 +VERTEX2 6801 -115.437 -83.9876 -1.46363 +VERTEX2 6802 -115.319 -84.9782 -1.4631 +VERTEX2 6803 -115.228 -85.9235 -1.46538 +VERTEX2 6804 -115.085 -86.8758 -1.493 +VERTEX2 6805 -114.944 -87.8443 -1.48972 +VERTEX2 6806 -113.934 -87.7856 0.0718585 +VERTEX2 6807 -112.939 -87.6955 0.0591272 +VERTEX2 6808 -112.028 -87.6307 0.0679771 +VERTEX2 6809 -111.009 -87.5891 0.0482791 +VERTEX2 6810 -109.999 -87.6095 0.0436897 +VERTEX2 6811 -109.999 -86.5725 1.60748 +VERTEX2 6812 -110.102 -85.5678 1.59516 +VERTEX2 6813 -110.134 -84.439 1.57569 +VERTEX2 6814 -110.109 -83.4891 1.55628 +VERTEX2 6815 -110.002 -82.4726 1.53571 +VERTEX2 6816 -111.108 -82.4568 3.12237 +VERTEX2 6817 -112.126 -82.4386 3.13292 +VERTEX2 6818 -113.051 -82.5551 3.10667 +VERTEX2 6819 -114.093 -82.4066 3.12691 +VERTEX2 6820 -115.1 -82.3655 -3.11068 +VERTEX2 6821 -115.092 -83.3372 -1.54466 +VERTEX2 6822 -114.945 -84.3975 -1.5437 +VERTEX2 6823 -114.864 -85.483 -1.52607 +VERTEX2 6824 -114.72 -86.4513 -1.53829 +VERTEX2 6825 -114.666 -87.424 -1.55412 +VERTEX2 6826 -113.59 -87.4821 0.00788443 +VERTEX2 6827 -112.587 -87.5072 0.0205695 +VERTEX2 6828 -111.594 -87.5162 0.0287946 +VERTEX2 6829 -110.489 -87.5102 0.0156364 +VERTEX2 6830 -109.458 -87.5642 0.0045405 +VERTEX2 6831 -109.534 -86.6546 1.56394 +VERTEX2 6832 -109.519 -85.678 1.5424 +VERTEX2 6833 -109.514 -84.7127 1.56178 +VERTEX2 6834 -109.612 -83.6929 1.54985 +VERTEX2 6835 -109.547 -82.7104 1.55142 +VERTEX2 6836 -108.524 -82.6345 -0.00576659 +VERTEX2 6837 -107.533 -82.6124 0.0243778 +VERTEX2 6838 -106.518 -82.5697 0.0324679 +VERTEX2 6839 -105.545 -82.6001 0.017922 +VERTEX2 6840 -104.544 -82.5 0.0115211 +VERTEX2 6841 -104.502 -81.5569 1.54984 +VERTEX2 6842 -104.458 -80.6047 1.52804 +VERTEX2 6843 -104.429 -79.5703 1.54468 +VERTEX2 6844 -104.457 -78.546 1.53778 +VERTEX2 6845 -104.401 -77.6133 1.54417 +VERTEX2 6846 -105.426 -77.5435 3.09564 +VERTEX2 6847 -106.375 -77.5536 3.10232 +VERTEX2 6848 -107.29 -77.5012 3.10471 +VERTEX2 6849 -108.3 -77.4074 3.1115 +VERTEX2 6850 -109.292 -77.3862 3.08281 +VERTEX2 6851 -109.348 -78.3682 -1.61916 +VERTEX2 6852 -109.388 -79.3468 -1.59474 +VERTEX2 6853 -109.38 -80.3343 -1.59229 +VERTEX2 6854 -109.437 -81.3348 -1.59357 +VERTEX2 6855 -109.545 -82.3256 -1.59763 +VERTEX2 6856 -110.528 -82.3137 3.11472 +VERTEX2 6857 -111.389 -82.2496 3.11277 +VERTEX2 6858 -112.462 -82.2556 3.1118 +VERTEX2 6859 -113.449 -82.2154 3.10767 +VERTEX2 6860 -114.467 -82.1453 3.10295 +VERTEX2 6861 -114.529 -83.2174 -1.61941 +VERTEX2 6862 -114.586 -84.1785 -1.62146 +VERTEX2 6863 -114.645 -85.0973 -1.62256 +VERTEX2 6864 -114.682 -86.1527 -1.62635 +VERTEX2 6865 -114.731 -87.1524 -1.63831 +VERTEX2 6866 -115.731 -87.0801 3.08089 +VERTEX2 6867 -116.712 -87.1331 3.07265 +VERTEX2 6868 -117.784 -87.0671 3.05225 +VERTEX2 6869 -118.733 -86.9806 3.06949 +VERTEX2 6870 -119.724 -86.8899 3.13094 +VERTEX2 6871 -119.785 -85.9012 1.56442 +VERTEX2 6872 -119.783 -84.9882 1.58417 +VERTEX2 6873 -119.839 -84.0324 1.54979 +VERTEX2 6874 -119.747 -83.048 1.54924 +VERTEX2 6875 -119.697 -82.0928 1.54144 +VERTEX2 6876 -120.676 -82.0732 3.10977 +VERTEX2 6877 -121.709 -81.9965 3.1076 +VERTEX2 6878 -122.741 -81.9578 3.10828 +VERTEX2 6879 -123.858 -81.8332 3.08849 +VERTEX2 6880 -124.873 -81.7278 3.11434 +VERTEX2 6881 -124.904 -82.8154 -1.64613 +VERTEX2 6882 -124.931 -83.7883 -1.6254 +VERTEX2 6883 -125.012 -84.8038 -1.63151 +VERTEX2 6884 -125.093 -85.7868 -1.63705 +VERTEX2 6885 -125.107 -86.7178 -1.61366 +VERTEX2 6886 -124.188 -86.8267 -0.0554178 +VERTEX2 6887 -123.253 -86.8866 -0.0647836 +VERTEX2 6888 -122.239 -86.9712 -0.0730096 +VERTEX2 6889 -121.242 -87.0963 -0.0621278 +VERTEX2 6890 -120.225 -87.0975 -0.0466834 +VERTEX2 6891 -120.23 -88.0685 -1.62004 +VERTEX2 6892 -120.287 -89.0788 -1.62296 +VERTEX2 6893 -120.361 -90.1313 -1.61026 +VERTEX2 6894 -120.403 -91.1467 -1.59416 +VERTEX2 6895 -120.398 -92.1393 -1.59327 +VERTEX2 6896 -119.489 -92.0592 -0.0405167 +VERTEX2 6897 -118.493 -92.0227 -0.0335985 +VERTEX2 6898 -117.526 -92.0522 -0.0500058 +VERTEX2 6899 -116.575 -92.1361 -0.03198 +VERTEX2 6900 -115.591 -92.174 -0.0228332 +VERTEX2 6901 -115.522 -91.2274 1.53283 +VERTEX2 6902 -115.502 -90.153 1.55865 +VERTEX2 6903 -115.507 -89.0749 1.55505 +VERTEX2 6904 -115.411 -88.1203 1.53758 +VERTEX2 6905 -115.355 -87.1137 1.52295 +VERTEX2 6906 -116.402 -87.0355 3.09542 +VERTEX2 6907 -117.395 -86.9537 3.10085 +VERTEX2 6908 -118.455 -86.9622 3.09151 +VERTEX2 6909 -119.401 -86.8789 3.11747 +VERTEX2 6910 -120.381 -86.8143 3.12854 +VERTEX2 6911 -120.389 -87.8544 -1.61627 +VERTEX2 6912 -120.488 -88.9421 -1.58248 +VERTEX2 6913 -120.583 -89.9959 -1.59098 +VERTEX2 6914 -120.629 -91.0086 -1.58327 +VERTEX2 6915 -120.66 -92.0846 -1.5659 +VERTEX2 6916 -121.687 -92.0816 -3.13727 +VERTEX2 6917 -122.648 -92.0717 -3.10501 +VERTEX2 6918 -123.651 -92.2564 -3.11443 +VERTEX2 6919 -124.7 -92.2241 -3.11067 +VERTEX2 6920 -125.727 -92.2245 -3.12099 +VERTEX2 6921 -125.63 -93.2988 -1.54476 +VERTEX2 6922 -125.645 -94.3377 -1.50133 +VERTEX2 6923 -125.562 -95.3478 -1.50388 +VERTEX2 6924 -125.365 -96.429 -1.53541 +VERTEX2 6925 -125.423 -97.501 -1.52629 +VERTEX2 6926 -124.435 -97.3835 0.0530061 +VERTEX2 6927 -123.46 -97.3397 -0.0207878 +VERTEX2 6928 -122.496 -97.34 0.00096932 +VERTEX2 6929 -121.582 -97.3877 -0.0130099 +VERTEX2 6930 -120.545 -97.397 -0.037277 +VERTEX2 6931 -120.586 -98.4802 -1.63061 +VERTEX2 6932 -120.608 -99.4899 -1.6301 +VERTEX2 6933 -120.661 -100.448 -1.64124 +VERTEX2 6934 -120.689 -101.396 -1.61724 +VERTEX2 6935 -120.717 -102.36 -1.63832 +VERTEX2 6936 -119.61 -102.427 -0.0671792 +VERTEX2 6937 -118.696 -102.52 -0.0781918 +VERTEX2 6938 -117.749 -102.679 -0.0961668 +VERTEX2 6939 -116.709 -102.83 -0.0662185 +VERTEX2 6940 -115.772 -102.94 -0.00255246 +VERTEX2 6941 -115.763 -102.009 1.56039 +VERTEX2 6942 -115.776 -101.053 1.56817 +VERTEX2 6943 -115.807 -100.113 1.55428 +VERTEX2 6944 -115.803 -99.1328 1.54419 +VERTEX2 6945 -115.698 -98.2268 1.55079 +VERTEX2 6946 -116.68 -98.3287 3.12781 +VERTEX2 6947 -117.754 -98.263 3.13245 +VERTEX2 6948 -118.844 -98.242 3.1355 +VERTEX2 6949 -119.796 -98.2084 3.10119 +VERTEX2 6950 -120.764 -98.1698 3.06617 +VERTEX2 6951 -120.695 -97.1514 1.49311 +VERTEX2 6952 -120.623 -96.1034 1.48874 +VERTEX2 6953 -120.591 -95.0866 1.47567 +VERTEX2 6954 -120.44 -94.1093 1.46706 +VERTEX2 6955 -120.286 -93.1368 1.49518 +VERTEX2 6956 -121.354 -93.0963 3.07146 +VERTEX2 6957 -122.366 -93.025 3.09532 +VERTEX2 6958 -123.276 -92.9841 3.10361 +VERTEX2 6959 -124.359 -92.9894 3.12245 +VERTEX2 6960 -125.334 -92.9248 3.10543 +VERTEX2 6961 -125.297 -91.917 1.52377 +VERTEX2 6962 -125.206 -90.8501 1.52563 +VERTEX2 6963 -125.202 -89.8356 1.53128 +VERTEX2 6964 -125.247 -88.874 1.51795 +VERTEX2 6965 -125.195 -87.8814 1.53968 +VERTEX2 6966 -124.086 -87.9056 -0.0181705 +VERTEX2 6967 -123.131 -87.9143 -0.00937919 +VERTEX2 6968 -122.066 -87.8632 -0.022796 +VERTEX2 6969 -121.1 -87.818 -0.0372232 +VERTEX2 6970 -120.044 -87.8992 -0.01482 +VERTEX2 6971 -119.931 -86.8774 1.56431 +VERTEX2 6972 -119.931 -85.8754 1.5369 +VERTEX2 6973 -119.88 -84.9367 1.49301 +VERTEX2 6974 -119.786 -83.9396 1.47156 +VERTEX2 6975 -119.688 -82.95 1.49138 +VERTEX2 6976 -120.653 -82.8664 3.08674 +VERTEX2 6977 -121.702 -82.881 3.04777 +VERTEX2 6978 -122.706 -82.7608 3.0566 +VERTEX2 6979 -123.672 -82.7112 3.07518 +VERTEX2 6980 -124.762 -82.6077 3.07917 +VERTEX2 6981 -124.653 -81.5925 1.51478 +VERTEX2 6982 -124.661 -80.5672 1.52523 +VERTEX2 6983 -124.648 -79.6192 1.51006 +VERTEX2 6984 -124.582 -78.5991 1.49794 +VERTEX2 6985 -124.511 -77.5937 1.49583 +VERTEX2 6986 -125.491 -77.544 3.04721 +VERTEX2 6987 -126.498 -77.4925 3.03521 +VERTEX2 6988 -127.506 -77.4418 3.0353 +VERTEX2 6989 -128.517 -77.4099 3.0256 +VERTEX2 6990 -129.508 -77.211 3.06391 +VERTEX2 6991 -129.494 -76.1366 1.51156 +VERTEX2 6992 -129.363 -75.2171 1.50288 +VERTEX2 6993 -129.256 -74.2164 1.47137 +VERTEX2 6994 -129.104 -73.2059 1.43737 +VERTEX2 6995 -129 -72.3715 1.46639 +VERTEX2 6996 -128.041 -72.5204 -0.110358 +VERTEX2 6997 -127.131 -72.5464 -0.111097 +VERTEX2 6998 -126.029 -72.6404 -0.151441 +VERTEX2 6999 -125.007 -72.8343 -0.146496 +VERTEX2 7000 -124.059 -73.0266 -0.150994 +VERTEX2 7001 -123.877 -71.9623 1.39171 +VERTEX2 7002 -123.661 -70.8974 1.40237 +VERTEX2 7003 -123.547 -69.959 1.40277 +VERTEX2 7004 -123.39 -69.0135 1.43013 +VERTEX2 7005 -123.231 -68.0186 1.4254 +VERTEX2 7006 -124.317 -67.9137 3.00178 +VERTEX2 7007 -125.333 -67.7235 2.99739 +VERTEX2 7008 -126.286 -67.5703 3.03474 +VERTEX2 7009 -127.252 -67.3977 3.00321 +VERTEX2 7010 -128.237 -67.2299 3.02506 +VERTEX2 7011 -128.532 -68.236 -1.69619 +VERTEX2 7012 -128.68 -69.2916 -1.69644 +VERTEX2 7013 -128.774 -70.2981 -1.69446 +VERTEX2 7014 -129.023 -71.2469 -1.71019 +VERTEX2 7015 -129.148 -72.1595 -1.72172 +VERTEX2 7016 -128.186 -72.2596 -0.151856 +VERTEX2 7017 -127.283 -72.3906 -0.180587 +VERTEX2 7018 -126.284 -72.4999 -0.14583 +VERTEX2 7019 -125.245 -72.6743 -0.173778 +VERTEX2 7020 -124.211 -72.8117 -0.168973 +VERTEX2 7021 -124.071 -71.8615 1.39123 +VERTEX2 7022 -123.89 -70.8447 1.34801 +VERTEX2 7023 -123.682 -69.8133 1.3506 +VERTEX2 7024 -123.521 -68.8214 1.34202 +VERTEX2 7025 -123.299 -67.9516 1.34307 +VERTEX2 7026 -124.298 -67.7904 2.91538 +VERTEX2 7027 -125.247 -67.6424 2.87946 +VERTEX2 7028 -126.181 -67.428 2.88752 +VERTEX2 7029 -127.203 -67.1964 2.8725 +VERTEX2 7030 -128.149 -66.937 2.89567 +VERTEX2 7031 -128.419 -67.9238 -1.77705 +VERTEX2 7032 -128.639 -68.8328 -1.75106 +VERTEX2 7033 -128.677 -69.7497 -1.76966 +VERTEX2 7034 -128.936 -70.7626 -1.8064 +VERTEX2 7035 -129.209 -71.8015 -1.79512 +VERTEX2 7036 -128.193 -71.9299 -0.251292 +VERTEX2 7037 -127.253 -72.1514 -0.223522 +VERTEX2 7038 -126.34 -72.3952 -0.229947 +VERTEX2 7039 -125.444 -72.6949 -0.224938 +VERTEX2 7040 -124.502 -72.9345 -0.229447 +VERTEX2 7041 -124.31 -71.9497 1.31356 +VERTEX2 7042 -124.032 -70.9974 1.28997 +VERTEX2 7043 -123.718 -70.0044 1.29905 +VERTEX2 7044 -123.38 -69.0428 1.31093 +VERTEX2 7045 -123.153 -68.118 1.32211 +VERTEX2 7046 -124.188 -67.8758 2.86331 +VERTEX2 7047 -125.104 -67.6213 2.84458 +VERTEX2 7048 -126.045 -67.3416 2.86154 +VERTEX2 7049 -127.033 -67.0781 2.84525 +VERTEX2 7050 -127.925 -66.7941 2.84092 +VERTEX2 7051 -127.631 -65.8746 1.29631 +VERTEX2 7052 -127.382 -64.9499 1.26244 +VERTEX2 7053 -127.169 -63.9466 1.27128 +VERTEX2 7054 -126.845 -63.0358 1.29013 +VERTEX2 7055 -126.609 -62.0529 1.29296 +VERTEX2 7056 -127.613 -61.8554 2.84097 +VERTEX2 7057 -128.524 -61.5035 2.79622 +VERTEX2 7058 -129.495 -61.207 2.81173 +VERTEX2 7059 -130.44 -60.8589 2.80995 +VERTEX2 7060 -131.286 -60.5605 2.77142 +VERTEX2 7061 -130.879 -59.6795 1.21352 +VERTEX2 7062 -130.517 -58.7479 1.21227 +VERTEX2 7063 -130.213 -57.8631 1.23135 +VERTEX2 7064 -129.915 -56.953 1.21644 +VERTEX2 7065 -129.58 -56.0762 1.23481 +VERTEX2 7066 -130.495 -55.7726 2.82161 +VERTEX2 7067 -131.455 -55.4542 2.81836 +VERTEX2 7068 -132.35 -55.0874 2.80466 +VERTEX2 7069 -133.286 -54.7619 2.79183 +VERTEX2 7070 -134.219 -54.4466 2.78259 +VERTEX2 7071 -133.829 -53.4627 1.22916 +VERTEX2 7072 -133.456 -52.5299 1.22539 +VERTEX2 7073 -133.083 -51.6352 1.2137 +VERTEX2 7074 -132.706 -50.7336 1.223 +VERTEX2 7075 -132.398 -49.8848 1.24691 +VERTEX2 7076 -133.334 -49.5568 2.8423 +VERTEX2 7077 -134.256 -49.3265 2.87404 +VERTEX2 7078 -135.241 -49.1052 2.89309 +VERTEX2 7079 -136.235 -48.7579 2.89736 +VERTEX2 7080 -137.266 -48.4646 2.88557 +VERTEX2 7081 -137.531 -49.4236 -1.82822 +VERTEX2 7082 -137.781 -50.2874 -1.84906 +VERTEX2 7083 -138.047 -51.1216 -1.81782 +VERTEX2 7084 -138.213 -52.0385 -1.83476 +VERTEX2 7085 -138.562 -52.9548 -1.84569 +VERTEX2 7086 -137.607 -53.2389 -0.300297 +VERTEX2 7087 -136.549 -53.4943 -0.296233 +VERTEX2 7088 -135.582 -53.7608 -0.298386 +VERTEX2 7089 -134.576 -53.9654 -0.283985 +VERTEX2 7090 -133.661 -54.2851 -0.277666 +VERTEX2 7091 -133.934 -55.2478 -1.79913 +VERTEX2 7092 -134.139 -56.2211 -1.82833 +VERTEX2 7093 -134.347 -57.1667 -1.80663 +VERTEX2 7094 -134.585 -58.0757 -1.81044 +VERTEX2 7095 -134.815 -59.0519 -1.80585 +VERTEX2 7096 -133.771 -59.2846 -0.222661 +VERTEX2 7097 -132.795 -59.4097 -0.231386 +VERTEX2 7098 -131.82 -59.6035 -0.225253 +VERTEX2 7099 -130.867 -59.8089 -0.194812 +VERTEX2 7100 -129.819 -60.0674 -0.196981 +VERTEX2 7101 -129.643 -59.1207 1.39039 +VERTEX2 7102 -129.437 -58.14 1.36058 +VERTEX2 7103 -129.121 -57.1449 1.3391 +VERTEX2 7104 -128.889 -56.1823 1.32002 +VERTEX2 7105 -128.686 -55.2392 1.37352 +VERTEX2 7106 -127.669 -55.4353 -0.193456 +VERTEX2 7107 -126.615 -55.539 -0.210001 +VERTEX2 7108 -125.636 -55.7374 -0.207716 +VERTEX2 7109 -124.689 -55.9535 -0.198503 +VERTEX2 7110 -123.603 -56.2218 -0.238771 +VERTEX2 7111 -123.428 -55.2677 1.31721 +VERTEX2 7112 -123.144 -54.2256 1.29671 +VERTEX2 7113 -122.901 -53.3099 1.31281 +VERTEX2 7114 -122.542 -52.3583 1.32463 +VERTEX2 7115 -122.299 -51.4145 1.33458 +VERTEX2 7116 -123.33 -51.1041 2.87238 +VERTEX2 7117 -124.313 -50.8705 2.83989 +VERTEX2 7118 -125.217 -50.6502 2.86389 +VERTEX2 7119 -126.19 -50.3355 2.85333 +VERTEX2 7120 -127.112 -50.0745 2.85406 +VERTEX2 7121 -127.424 -50.958 -1.83353 +VERTEX2 7122 -127.727 -51.9035 -1.84256 +VERTEX2 7123 -127.928 -52.8452 -1.833 +VERTEX2 7124 -128.278 -53.7548 -1.82239 +VERTEX2 7125 -128.514 -54.7417 -1.80976 +VERTEX2 7126 -127.577 -54.9483 -0.249655 +VERTEX2 7127 -126.684 -55.1842 -0.261806 +VERTEX2 7128 -125.674 -55.4192 -0.254041 +VERTEX2 7129 -124.725 -55.6447 -0.259982 +VERTEX2 7130 -123.733 -55.9093 -0.243384 +VERTEX2 7131 -123.495 -54.9256 1.31298 +VERTEX2 7132 -123.335 -53.9525 1.30753 +VERTEX2 7133 -123.062 -53.057 1.31345 +VERTEX2 7134 -122.83 -52.1558 1.32514 +VERTEX2 7135 -122.586 -51.1754 1.33243 +VERTEX2 7136 -123.627 -50.9382 2.92123 +VERTEX2 7137 -124.668 -50.7134 2.91954 +VERTEX2 7138 -125.633 -50.4963 2.95116 +VERTEX2 7139 -126.586 -50.3004 2.92344 +VERTEX2 7140 -127.498 -50.0982 2.92295 +VERTEX2 7141 -127.298 -49.0799 1.34217 +VERTEX2 7142 -126.986 -48.1003 1.3332 +VERTEX2 7143 -126.651 -47.1592 1.30543 +VERTEX2 7144 -126.378 -46.1911 1.31554 +VERTEX2 7145 -126.014 -45.1598 1.32523 +VERTEX2 7146 -127.046 -44.9647 2.89306 +VERTEX2 7147 -127.956 -44.7517 2.91255 +VERTEX2 7148 -128.927 -44.5356 2.89466 +VERTEX2 7149 -129.952 -44.2794 2.90803 +VERTEX2 7150 -130.894 -44.0242 2.913 +VERTEX2 7151 -131.154 -44.9167 -1.79998 +VERTEX2 7152 -131.481 -45.8791 -1.8162 +VERTEX2 7153 -131.683 -46.7901 -1.83081 +VERTEX2 7154 -131.947 -47.7988 -1.80822 +VERTEX2 7155 -132.11 -48.7378 -1.80684 +VERTEX2 7156 -131.081 -48.974 -0.224551 +VERTEX2 7157 -130.138 -49.1895 -0.231782 +VERTEX2 7158 -129.204 -49.4605 -0.24374 +VERTEX2 7159 -128.261 -49.7181 -0.234687 +VERTEX2 7160 -127.284 -49.9138 -0.245303 +VERTEX2 7161 -127.093 -49.0168 1.35984 +VERTEX2 7162 -126.877 -47.9752 1.38522 +VERTEX2 7163 -126.65 -46.8919 1.37189 +VERTEX2 7164 -126.404 -45.9244 1.40606 +VERTEX2 7165 -126.266 -44.9913 1.41735 +VERTEX2 7166 -125.358 -45.1406 -0.160199 +VERTEX2 7167 -124.342 -45.2606 -0.181945 +VERTEX2 7168 -123.343 -45.3699 -0.163069 +VERTEX2 7169 -122.406 -45.5199 -0.128061 +VERTEX2 7170 -121.406 -45.6941 -0.122743 +VERTEX2 7171 -121.611 -46.7349 -1.68293 +VERTEX2 7172 -121.678 -47.6966 -1.69954 +VERTEX2 7173 -121.707 -48.571 -1.66069 +VERTEX2 7174 -121.693 -49.5965 -1.6666 +VERTEX2 7175 -121.86 -50.6743 -1.67017 +VERTEX2 7176 -120.792 -50.7619 -0.12419 +VERTEX2 7177 -119.744 -50.8549 -0.0915942 +VERTEX2 7178 -118.775 -50.9459 -0.0923109 +VERTEX2 7179 -117.716 -51.0297 -0.0988942 +VERTEX2 7180 -116.681 -51.1295 -0.0881777 +VERTEX2 7181 -116.648 -50.1538 1.46654 +VERTEX2 7182 -116.584 -49.2277 1.49388 +VERTEX2 7183 -116.463 -48.1693 1.55334 +VERTEX2 7184 -116.438 -47.1731 1.54018 +VERTEX2 7185 -116.413 -46.1385 1.5199 +VERTEX2 7186 -115.499 -46.2661 -0.0398051 +VERTEX2 7187 -114.506 -46.2693 -0.0289453 +VERTEX2 7188 -113.498 -46.2955 -0.0252874 +VERTEX2 7189 -112.493 -46.3203 -0.0239326 +VERTEX2 7190 -111.522 -46.4006 -0.0306392 +VERTEX2 7191 -111.696 -47.4546 -1.59821 +VERTEX2 7192 -111.746 -48.4706 -1.58704 +VERTEX2 7193 -111.77 -49.5104 -1.60411 +VERTEX2 7194 -111.818 -50.4651 -1.59838 +VERTEX2 7195 -111.847 -51.4158 -1.59737 +VERTEX2 7196 -110.869 -51.4795 -0.0203797 +VERTEX2 7197 -109.876 -51.5976 -0.00847247 +VERTEX2 7198 -108.76 -51.6297 -0.031108 +VERTEX2 7199 -107.789 -51.5685 -0.0289861 +VERTEX2 7200 -106.792 -51.6359 -0.0260686 +VERTEX2 7201 -106.856 -52.6843 -1.60902 +VERTEX2 7202 -106.997 -53.7266 -1.59146 +VERTEX2 7203 -106.979 -54.8235 -1.55839 +VERTEX2 7204 -106.945 -55.8103 -1.58432 +VERTEX2 7205 -106.95 -56.8896 -1.56438 +VERTEX2 7206 -105.937 -56.9083 0.0297384 +VERTEX2 7207 -104.939 -56.9125 0.0351546 +VERTEX2 7208 -103.883 -56.8672 0.0497035 +VERTEX2 7209 -102.894 -56.7456 0.055923 +VERTEX2 7210 -101.851 -56.6667 0.0760431 +VERTEX2 7211 -101.919 -55.6343 1.63142 +VERTEX2 7212 -101.959 -54.5873 1.63246 +VERTEX2 7213 -102.088 -53.5399 1.61285 +VERTEX2 7214 -102.159 -52.5233 1.57393 +VERTEX2 7215 -102.142 -51.4801 1.58514 +VERTEX2 7216 -103.103 -51.5394 -3.1338 +VERTEX2 7217 -104.072 -51.5349 -3.12127 +VERTEX2 7218 -105.189 -51.5278 -3.09333 +VERTEX2 7219 -106.243 -51.5618 -3.12903 +VERTEX2 7220 -107.186 -51.5382 -3.12677 +VERTEX2 7221 -107.185 -52.6214 -1.55408 +VERTEX2 7222 -107.174 -53.5581 -1.54711 +VERTEX2 7223 -107.191 -54.5487 -1.56537 +VERTEX2 7224 -107.192 -55.5384 -1.53508 +VERTEX2 7225 -107.053 -56.5541 -1.53702 +VERTEX2 7226 -108.064 -56.5606 -3.13895 +VERTEX2 7227 -109.004 -56.5217 3.11979 +VERTEX2 7228 -110.1 -56.5686 3.10582 +VERTEX2 7229 -111.124 -56.5834 3.12614 +VERTEX2 7230 -112.007 -56.5519 3.12755 +VERTEX2 7231 -112.109 -57.49 -1.58808 +VERTEX2 7232 -112.127 -58.4803 -1.57043 +VERTEX2 7233 -112.105 -59.4891 -1.55838 +VERTEX2 7234 -112.106 -60.5154 -1.52403 +VERTEX2 7235 -111.951 -61.5089 -1.53258 +VERTEX2 7236 -112.978 -61.647 -3.10374 +VERTEX2 7237 -114.019 -61.6882 -3.10316 +VERTEX2 7238 -115.029 -61.6785 -3.121 +VERTEX2 7239 -116.041 -61.771 3.12202 +VERTEX2 7240 -117.008 -61.7426 3.10655 +VERTEX2 7241 -117.015 -60.8177 1.53836 +VERTEX2 7242 -116.954 -59.8477 1.50858 +VERTEX2 7243 -116.967 -58.871 1.50998 +VERTEX2 7244 -116.842 -57.863 1.50523 +VERTEX2 7245 -116.817 -56.8917 1.49291 +VERTEX2 7246 -117.837 -56.7968 3.05237 +VERTEX2 7247 -118.853 -56.6011 3.06546 +VERTEX2 7248 -119.865 -56.5189 3.05075 +VERTEX2 7249 -120.8 -56.4614 3.03351 +VERTEX2 7250 -121.873 -56.3681 3.06225 +VERTEX2 7251 -121.711 -55.3282 1.47296 +VERTEX2 7252 -121.585 -54.3164 1.49311 +VERTEX2 7253 -121.535 -53.2556 1.51275 +VERTEX2 7254 -121.551 -52.2099 1.51436 +VERTEX2 7255 -121.551 -51.3235 1.53235 +VERTEX2 7256 -122.605 -51.2691 3.11086 +VERTEX2 7257 -123.655 -51.2784 3.09801 +VERTEX2 7258 -124.751 -51.3019 3.13108 +VERTEX2 7259 -125.771 -51.2431 3.11065 +VERTEX2 7260 -126.742 -51.2431 3.10168 +VERTEX2 7261 -126.764 -52.2782 -1.62653 +VERTEX2 7262 -126.839 -53.1511 -1.60432 +VERTEX2 7263 -126.877 -54.2017 -1.59287 +VERTEX2 7264 -126.825 -55.197 -1.57408 +VERTEX2 7265 -126.825 -56.1345 -1.5472 +VERTEX2 7266 -125.849 -56.0679 0.0241168 +VERTEX2 7267 -124.913 -55.972 -0.0103136 +VERTEX2 7268 -123.983 -56.0677 0.0126762 +VERTEX2 7269 -123.008 -56.0554 0.0249546 +VERTEX2 7270 -122.048 -56.0556 0.021812 +VERTEX2 7271 -122.115 -55.1244 1.59653 +VERTEX2 7272 -122.118 -54.1298 1.60828 +VERTEX2 7273 -122.107 -53.166 1.61001 +VERTEX2 7274 -122.207 -52.1208 1.60677 +VERTEX2 7275 -122.301 -51.1444 1.61925 +VERTEX2 7276 -121.292 -51.0015 0.00997543 +VERTEX2 7277 -120.303 -51.0714 0.00529427 +VERTEX2 7278 -119.182 -51.1419 0.0506201 +VERTEX2 7279 -118.24 -51.1267 0.037245 +VERTEX2 7280 -117.211 -51.1269 0.00165641 +VERTEX2 7281 -117.241 -50.1951 1.55467 +VERTEX2 7282 -117.22 -49.2197 1.54575 +VERTEX2 7283 -117.14 -48.2626 1.53447 +VERTEX2 7284 -117.135 -47.2967 1.52885 +VERTEX2 7285 -117.1 -46.3435 1.52447 +VERTEX2 7286 -118.033 -46.3342 3.11932 +VERTEX2 7287 -118.999 -46.4474 3.11192 +VERTEX2 7288 -120.032 -46.5142 -3.12826 +VERTEX2 7289 -120.962 -46.5087 -3.13277 +VERTEX2 7290 -121.901 -46.4691 -3.12405 +VERTEX2 7291 -121.875 -47.5065 -1.60713 +VERTEX2 7292 -121.937 -48.5423 -1.62928 +VERTEX2 7293 -121.992 -49.6212 -1.61592 +VERTEX2 7294 -122.057 -50.6397 -1.59695 +VERTEX2 7295 -122.133 -51.6565 -1.58158 +VERTEX2 7296 -121.088 -51.6527 -0.0150209 +VERTEX2 7297 -120.119 -51.6438 -0.022545 +VERTEX2 7298 -119.198 -51.5977 -0.0448837 +VERTEX2 7299 -118.253 -51.6422 -0.0312476 +VERTEX2 7300 -117.215 -51.708 -0.0425471 +VERTEX2 7301 -117.15 -50.6956 1.513 +VERTEX2 7302 -117.1 -49.7006 1.4984 +VERTEX2 7303 -117.022 -48.7311 1.46728 +VERTEX2 7304 -116.959 -47.8363 1.45986 +VERTEX2 7305 -116.825 -46.7761 1.44447 +VERTEX2 7306 -117.746 -46.6177 3.00818 +VERTEX2 7307 -118.763 -46.5006 3.01415 +VERTEX2 7308 -119.782 -46.3717 3.00155 +VERTEX2 7309 -120.808 -46.2223 2.98802 +VERTEX2 7310 -121.835 -46.0687 2.93323 +VERTEX2 7311 -122.019 -47.0122 -1.80361 +VERTEX2 7312 -122.24 -47.9386 -1.79133 +VERTEX2 7313 -122.44 -48.9606 -1.77397 +VERTEX2 7314 -122.658 -49.9456 -1.76555 +VERTEX2 7315 -122.822 -50.9501 -1.78555 +VERTEX2 7316 -121.762 -51.1542 -0.187852 +VERTEX2 7317 -120.753 -51.3761 -0.196833 +VERTEX2 7318 -119.744 -51.6225 -0.199532 +VERTEX2 7319 -118.716 -51.8744 -0.200801 +VERTEX2 7320 -117.735 -52.0369 -0.226709 +VERTEX2 7321 -117.537 -50.9465 1.34405 +VERTEX2 7322 -117.346 -49.9392 1.31786 +VERTEX2 7323 -117.005 -48.9308 1.31311 +VERTEX2 7324 -116.756 -47.9867 1.32073 +VERTEX2 7325 -116.531 -47.0076 1.29167 +VERTEX2 7326 -117.483 -46.7377 2.84961 +VERTEX2 7327 -118.473 -46.4477 2.86145 +VERTEX2 7328 -119.452 -46.1196 2.87786 +VERTEX2 7329 -120.303 -45.7658 2.8451 +VERTEX2 7330 -121.335 -45.4525 2.79664 +VERTEX2 7331 -121.658 -46.408 -1.91662 +VERTEX2 7332 -121.936 -47.3836 -1.92829 +VERTEX2 7333 -122.323 -48.2822 -1.95447 +VERTEX2 7334 -122.689 -49.2084 -1.9551 +VERTEX2 7335 -123.005 -50.1715 -1.94235 +VERTEX2 7336 -122.091 -50.4884 -0.347364 +VERTEX2 7337 -121.127 -50.7829 -0.345071 +VERTEX2 7338 -120.228 -51.1428 -0.314479 +VERTEX2 7339 -119.224 -51.5157 -0.336249 +VERTEX2 7340 -118.257 -51.8785 -0.367908 +VERTEX2 7341 -117.928 -50.9353 1.22477 +VERTEX2 7342 -117.543 -49.9756 1.24655 +VERTEX2 7343 -117.199 -49.0575 1.2575 +VERTEX2 7344 -116.942 -48.1123 1.27322 +VERTEX2 7345 -116.739 -47.185 1.29671 +VERTEX2 7346 -117.769 -46.9352 2.86601 +VERTEX2 7347 -118.646 -46.6375 2.84373 +VERTEX2 7348 -119.659 -46.3008 2.81374 +VERTEX2 7349 -120.645 -45.9083 2.8024 +VERTEX2 7350 -121.598 -45.4955 2.82991 +VERTEX2 7351 -121.881 -46.4958 -1.86644 +VERTEX2 7352 -122.14 -47.4968 -1.87397 +VERTEX2 7353 -122.439 -48.4551 -1.8932 +VERTEX2 7354 -122.795 -49.4087 -1.89142 +VERTEX2 7355 -123.111 -50.2876 -1.87133 +VERTEX2 7356 -122.09 -50.5593 -0.280037 +VERTEX2 7357 -121.079 -50.8638 -0.291344 +VERTEX2 7358 -120.187 -51.1656 -0.317781 +VERTEX2 7359 -119.229 -51.4593 -0.338535 +VERTEX2 7360 -118.3 -51.8 -0.326067 +VERTEX2 7361 -117.995 -50.8196 1.25644 +VERTEX2 7362 -117.635 -49.8239 1.23983 +VERTEX2 7363 -117.355 -48.8528 1.25505 +VERTEX2 7364 -117.084 -47.9719 1.2655 +VERTEX2 7365 -116.819 -46.9843 1.28839 +VERTEX2 7366 -115.865 -47.2566 -0.317772 +VERTEX2 7367 -114.887 -47.4988 -0.31315 +VERTEX2 7368 -113.926 -47.7338 -0.274014 +VERTEX2 7369 -112.892 -48.0063 -0.266873 +VERTEX2 7370 -111.865 -48.2721 -0.245983 +VERTEX2 7371 -111.629 -47.2475 1.34581 +VERTEX2 7372 -111.406 -46.2085 1.34903 +VERTEX2 7373 -111.214 -45.2515 1.33309 +VERTEX2 7374 -110.972 -44.2986 1.32217 +VERTEX2 7375 -110.722 -43.2461 1.29452 +VERTEX2 7376 -111.673 -43.0344 2.8897 +VERTEX2 7377 -112.585 -42.8419 2.88462 +VERTEX2 7378 -113.505 -42.6208 2.91749 +VERTEX2 7379 -114.491 -42.5162 2.93981 +VERTEX2 7380 -115.494 -42.3351 2.94248 +VERTEX2 7381 -115.253 -41.3592 1.39044 +VERTEX2 7382 -115.107 -40.3806 1.38859 +VERTEX2 7383 -114.915 -39.3663 1.36488 +VERTEX2 7384 -114.766 -38.3194 1.34858 +VERTEX2 7385 -114.452 -37.3523 1.38332 +VERTEX2 7386 -115.412 -37.2102 2.95976 +VERTEX2 7387 -116.468 -36.9755 2.98364 +VERTEX2 7388 -117.43 -36.8695 2.98298 +VERTEX2 7389 -118.38 -36.7051 2.95464 +VERTEX2 7390 -119.363 -36.4991 2.9532 +VERTEX2 7391 -119.531 -37.5709 -1.75561 +VERTEX2 7392 -119.688 -38.5381 -1.77029 +VERTEX2 7393 -119.885 -39.5941 -1.77496 +VERTEX2 7394 -119.998 -40.505 -1.79234 +VERTEX2 7395 -120.259 -41.5503 -1.75941 +VERTEX2 7396 -121.253 -41.3907 2.97327 +VERTEX2 7397 -122.296 -41.2403 2.95351 +VERTEX2 7398 -123.26 -41.0476 2.93384 +VERTEX2 7399 -124.258 -40.8447 2.94132 +VERTEX2 7400 -125.228 -40.6536 2.94691 +VERTEX2 7401 -125.454 -41.6828 -1.74259 +VERTEX2 7402 -125.561 -42.5921 -1.72437 +VERTEX2 7403 -125.681 -43.5588 -1.73603 +VERTEX2 7404 -125.753 -44.5066 -1.74494 +VERTEX2 7405 -125.956 -45.4852 -1.72142 +VERTEX2 7406 -126.993 -45.2611 2.99295 +VERTEX2 7407 -127.992 -45.112 3.02027 +VERTEX2 7408 -129.007 -44.9767 2.99738 +VERTEX2 7409 -129.935 -44.8666 3.00163 +VERTEX2 7410 -130.965 -44.7693 2.98904 +VERTEX2 7411 -131.119 -45.8016 -1.68102 +VERTEX2 7412 -131.276 -46.8996 -1.68803 +VERTEX2 7413 -131.353 -47.9034 -1.73076 +VERTEX2 7414 -131.392 -48.9074 -1.69492 +VERTEX2 7415 -131.489 -49.9008 -1.7067 +VERTEX2 7416 -130.479 -50.0606 -0.0980373 +VERTEX2 7417 -129.613 -50.2104 -0.107165 +VERTEX2 7418 -128.653 -50.367 -0.121291 +VERTEX2 7419 -127.693 -50.4968 -0.134858 +VERTEX2 7420 -126.8 -50.5548 -0.151702 +VERTEX2 7421 -126.957 -51.6415 -1.72435 +VERTEX2 7422 -127.084 -52.667 -1.72892 +VERTEX2 7423 -127.283 -53.5875 -1.7238 +VERTEX2 7424 -127.451 -54.581 -1.71282 +VERTEX2 7425 -127.627 -55.5795 -1.72398 +VERTEX2 7426 -126.602 -55.7122 -0.174798 +VERTEX2 7427 -125.698 -55.9105 -0.190432 +VERTEX2 7428 -124.674 -56.1579 -0.190644 +VERTEX2 7429 -123.629 -56.332 -0.174151 +VERTEX2 7430 -122.715 -56.5028 -0.164077 +VERTEX2 7431 -122.615 -55.5173 1.41431 +VERTEX2 7432 -122.449 -54.4762 1.4217 +VERTEX2 7433 -122.271 -53.5408 1.42906 +VERTEX2 7434 -122.17 -52.4895 1.4263 +VERTEX2 7435 -121.926 -51.4494 1.39245 +VERTEX2 7436 -122.911 -51.2867 2.9991 +VERTEX2 7437 -123.928 -51.085 3.00989 +VERTEX2 7438 -124.826 -50.9793 2.99517 +VERTEX2 7439 -125.815 -50.833 2.97027 +VERTEX2 7440 -126.819 -50.6488 3.00178 +VERTEX2 7441 -126.667 -49.5949 1.40949 +VERTEX2 7442 -126.457 -48.6283 1.45081 +VERTEX2 7443 -126.323 -47.6593 1.44385 +VERTEX2 7444 -126.225 -46.722 1.41258 +VERTEX2 7445 -126.1 -45.7437 1.42519 +VERTEX2 7446 -125.2 -45.9687 -0.165978 +VERTEX2 7447 -124.182 -46.1686 -0.152182 +VERTEX2 7448 -123.253 -46.2994 -0.143395 +VERTEX2 7449 -122.334 -46.4532 -0.140618 +VERTEX2 7450 -121.304 -46.5587 -0.154023 +VERTEX2 7451 -121.108 -45.6269 1.43475 +VERTEX2 7452 -120.991 -44.6213 1.44194 +VERTEX2 7453 -120.941 -43.6759 1.47449 +VERTEX2 7454 -120.812 -42.6431 1.48257 +VERTEX2 7455 -120.709 -41.6821 1.49853 +VERTEX2 7456 -119.709 -41.7768 -0.110946 +VERTEX2 7457 -118.684 -41.7913 -0.125272 +VERTEX2 7458 -117.721 -41.9501 -0.109347 +VERTEX2 7459 -116.674 -42.0632 -0.106314 +VERTEX2 7460 -115.723 -42.1963 -0.0837022 +VERTEX2 7461 -115.645 -41.2344 1.47226 +VERTEX2 7462 -115.597 -40.2216 1.4967 +VERTEX2 7463 -115.388 -39.1582 1.48256 +VERTEX2 7464 -115.356 -38.1696 1.49449 +VERTEX2 7465 -115.221 -37.2252 1.52699 +VERTEX2 7466 -116.355 -37.3029 3.07199 +VERTEX2 7467 -117.41 -37.2011 3.03739 +VERTEX2 7468 -118.383 -37.1235 3.03362 +VERTEX2 7469 -119.398 -37.017 3.03704 +VERTEX2 7470 -120.385 -36.7133 3.01709 +VERTEX2 7471 -120.473 -37.701 -1.68872 +VERTEX2 7472 -120.58 -38.7561 -1.68169 +VERTEX2 7473 -120.626 -39.7136 -1.66253 +VERTEX2 7474 -120.648 -40.7617 -1.66332 +VERTEX2 7475 -120.724 -41.6568 -1.66579 +VERTEX2 7476 -121.653 -41.4762 3.04913 +VERTEX2 7477 -122.642 -41.3474 3.02005 +VERTEX2 7478 -123.614 -41.2475 2.98174 +VERTEX2 7479 -124.56 -41.1278 2.98682 +VERTEX2 7480 -125.578 -40.9106 2.97945 +VERTEX2 7481 -125.369 -40.0052 1.41541 +VERTEX2 7482 -125.277 -39.0977 1.40942 +VERTEX2 7483 -124.939 -38.1057 1.41759 +VERTEX2 7484 -124.762 -37.1725 1.40662 +VERTEX2 7485 -124.661 -36.1707 1.39315 +VERTEX2 7486 -125.631 -35.952 2.97554 +VERTEX2 7487 -126.635 -35.7816 2.96843 +VERTEX2 7488 -127.605 -35.5849 2.98387 +VERTEX2 7489 -128.618 -35.4626 2.97721 +VERTEX2 7490 -129.599 -35.3747 2.99464 +VERTEX2 7491 -129.753 -36.4573 -1.71509 +VERTEX2 7492 -129.908 -37.4806 -1.76794 +VERTEX2 7493 -130.118 -38.414 -1.79219 +VERTEX2 7494 -130.345 -39.4161 -1.79017 +VERTEX2 7495 -130.604 -40.4072 -1.81297 +VERTEX2 7496 -129.625 -40.6289 -0.238355 +VERTEX2 7497 -128.68 -40.9304 -0.256957 +VERTEX2 7498 -127.712 -41.1498 -0.237674 +VERTEX2 7499 -126.769 -41.4094 -0.255246 +VERTEX2 7500 -125.786 -41.7414 -0.251413 +VERTEX2 7501 -126.018 -42.6714 -1.86065 +VERTEX2 7502 -126.33 -43.6641 -1.87548 +VERTEX2 7503 -126.609 -44.5877 -1.87091 +VERTEX2 7504 -126.933 -45.5068 -1.87679 +VERTEX2 7505 -127.203 -46.5213 -1.8797 +VERTEX2 7506 -126.229 -46.7892 -0.324904 +VERTEX2 7507 -125.248 -47.1925 -0.344678 +VERTEX2 7508 -124.229 -47.5512 -0.348738 +VERTEX2 7509 -123.217 -47.8301 -0.345459 +VERTEX2 7510 -122.245 -48.2034 -0.38076 +VERTEX2 7511 -121.862 -47.3089 1.18551 +VERTEX2 7512 -121.483 -46.4182 1.19482 +VERTEX2 7513 -121.089 -45.4965 1.20892 +VERTEX2 7514 -120.728 -44.5581 1.24177 +VERTEX2 7515 -120.455 -43.6285 1.26422 +VERTEX2 7516 -119.594 -44.0172 -0.282713 +VERTEX2 7517 -118.613 -44.3584 -0.317787 +VERTEX2 7518 -117.669 -44.6268 -0.29029 +VERTEX2 7519 -116.77 -44.966 -0.294421 +VERTEX2 7520 -115.796 -45.2501 -0.308279 +VERTEX2 7521 -116.127 -46.1849 -1.88259 +VERTEX2 7522 -116.426 -47.1908 -1.90392 +VERTEX2 7523 -116.719 -48.0838 -1.93261 +VERTEX2 7524 -117.179 -49.0028 -1.90926 +VERTEX2 7525 -117.512 -50.0176 -1.91918 +VERTEX2 7526 -118.399 -49.6111 2.8278 +VERTEX2 7527 -119.401 -49.2779 2.80709 +VERTEX2 7528 -120.408 -49.0504 2.84143 +VERTEX2 7529 -121.362 -48.6894 2.85005 +VERTEX2 7530 -122.328 -48.4556 2.82812 +VERTEX2 7531 -122.051 -47.5277 1.25588 +VERTEX2 7532 -121.732 -46.6817 1.27354 +VERTEX2 7533 -121.46 -45.742 1.30527 +VERTEX2 7534 -121.18 -44.8019 1.29502 +VERTEX2 7535 -120.953 -43.8272 1.28782 +VERTEX2 7536 -120.019 -44.0727 -0.301441 +VERTEX2 7537 -118.965 -44.5013 -0.356258 +VERTEX2 7538 -118.056 -44.84 -0.354594 +VERTEX2 7539 -117.147 -45.245 -0.35795 +VERTEX2 7540 -116.255 -45.5911 -0.359959 +VERTEX2 7541 -115.893 -44.6454 1.2289 +VERTEX2 7542 -115.581 -43.664 1.20553 +VERTEX2 7543 -115.237 -42.7764 1.23457 +VERTEX2 7544 -114.853 -41.8133 1.23664 +VERTEX2 7545 -114.52 -40.8248 1.26424 +VERTEX2 7546 -115.492 -40.5204 2.82667 +VERTEX2 7547 -116.473 -40.2448 2.81596 +VERTEX2 7548 -117.424 -39.9018 2.79975 +VERTEX2 7549 -118.319 -39.6188 2.80535 +VERTEX2 7550 -119.16 -39.2648 2.81534 +VERTEX2 7551 -119.452 -40.1698 -1.90251 +VERTEX2 7552 -119.779 -41.1317 -1.90225 +VERTEX2 7553 -120.183 -42.0585 -1.89843 +VERTEX2 7554 -120.501 -43.103 -1.89274 +VERTEX2 7555 -120.755 -44.0149 -1.86855 +VERTEX2 7556 -119.813 -44.2879 -0.294308 +VERTEX2 7557 -118.847 -44.5956 -0.329827 +VERTEX2 7558 -117.896 -44.9174 -0.368299 +VERTEX2 7559 -117.012 -45.2701 -0.411796 +VERTEX2 7560 -116.174 -45.5851 -0.418241 +VERTEX2 7561 -115.75 -44.6207 1.14411 +VERTEX2 7562 -115.317 -43.6866 1.14051 +VERTEX2 7563 -114.804 -42.8047 1.17107 +VERTEX2 7564 -114.382 -41.933 1.12601 +VERTEX2 7565 -113.907 -41.11 1.14198 +VERTEX2 7566 -114.827 -40.71 2.72756 +VERTEX2 7567 -115.734 -40.3833 2.71779 +VERTEX2 7568 -116.699 -39.963 2.72652 +VERTEX2 7569 -117.605 -39.5662 2.70281 +VERTEX2 7570 -118.453 -39.1336 2.67312 +VERTEX2 7571 -118.879 -40.0332 -2.05153 +VERTEX2 7572 -119.355 -40.8724 -2.06652 +VERTEX2 7573 -119.813 -41.6451 -2.07392 +VERTEX2 7574 -120.298 -42.5017 -2.04076 +VERTEX2 7575 -120.721 -43.3897 -2.05148 +VERTEX2 7576 -119.878 -43.9196 -0.465373 +VERTEX2 7577 -118.931 -44.3514 -0.451387 +VERTEX2 7578 -118.074 -44.8158 -0.448738 +VERTEX2 7579 -117.176 -45.3445 -0.441407 +VERTEX2 7580 -116.319 -45.7924 -0.432 +VERTEX2 7581 -115.965 -44.915 1.12354 +VERTEX2 7582 -115.489 -44.026 1.13735 +VERTEX2 7583 -115.101 -43.1793 1.12852 +VERTEX2 7584 -114.654 -42.2597 1.10617 +VERTEX2 7585 -114.332 -41.4273 1.12321 +VERTEX2 7586 -113.343 -41.8029 -0.466537 +VERTEX2 7587 -112.494 -42.1638 -0.460484 +VERTEX2 7588 -111.581 -42.7056 -0.482564 +VERTEX2 7589 -110.73 -43.1408 -0.507033 +VERTEX2 7590 -109.925 -43.6005 -0.546902 +VERTEX2 7591 -110.483 -44.4007 -2.11652 +VERTEX2 7592 -111.028 -45.302 -2.11448 +VERTEX2 7593 -111.507 -46.2012 -2.1086 +VERTEX2 7594 -112.044 -47.0606 -2.11453 +VERTEX2 7595 -112.597 -47.9068 -2.11868 +VERTEX2 7596 -111.732 -48.481 -0.538461 +VERTEX2 7597 -110.907 -48.9508 -0.50964 +VERTEX2 7598 -109.987 -49.4849 -0.531825 +VERTEX2 7599 -109.043 -50.0262 -0.543785 +VERTEX2 7600 -108.129 -50.5974 -0.521677 +VERTEX2 7601 -108.698 -51.396 -2.0779 +VERTEX2 7602 -109.207 -52.2999 -2.05659 +VERTEX2 7603 -109.674 -53.1427 -2.03948 +VERTEX2 7604 -110.15 -54.129 -2.02978 +VERTEX2 7605 -110.692 -55.0591 -2.02806 +VERTEX2 7606 -109.787 -55.5798 -0.456223 +VERTEX2 7607 -108.898 -56.0252 -0.468343 +VERTEX2 7608 -108.055 -56.4346 -0.453555 +VERTEX2 7609 -107.19 -56.8514 -0.449977 +VERTEX2 7610 -106.368 -57.3709 -0.43566 +VERTEX2 7611 -106.007 -56.4965 1.12994 +VERTEX2 7612 -105.503 -55.566 1.09749 +VERTEX2 7613 -104.96 -54.6226 1.08407 +VERTEX2 7614 -104.513 -53.7393 1.1019 +VERTEX2 7615 -104.07 -52.9298 1.09872 +VERTEX2 7616 -105.007 -52.4425 2.6698 +VERTEX2 7617 -105.848 -52.0518 2.67312 +VERTEX2 7618 -106.714 -51.5689 2.68426 +VERTEX2 7619 -107.548 -51.1548 2.64932 +VERTEX2 7620 -108.43 -50.64 2.64322 +VERTEX2 7621 -108.974 -51.4581 -2.03981 +VERTEX2 7622 -109.315 -52.2979 -2.06101 +VERTEX2 7623 -109.809 -53.1869 -2.06413 +VERTEX2 7624 -110.372 -54.0826 -2.06158 +VERTEX2 7625 -110.791 -54.9772 -2.10529 +VERTEX2 7626 -111.717 -54.417 2.61961 +VERTEX2 7627 -112.599 -54.0494 2.61404 +VERTEX2 7628 -113.511 -53.5367 2.62459 +VERTEX2 7629 -114.33 -53.0362 2.62739 +VERTEX2 7630 -115.287 -52.6581 2.6128 +VERTEX2 7631 -114.746 -51.7915 1.04547 +VERTEX2 7632 -114.239 -50.9099 1.02946 +VERTEX2 7633 -113.677 -49.9791 1.06705 +VERTEX2 7634 -113.2 -49.1553 1.05014 +VERTEX2 7635 -112.771 -48.3369 1.01957 +VERTEX2 7636 -111.912 -48.8738 -0.543226 +VERTEX2 7637 -111.052 -49.4524 -0.499608 +VERTEX2 7638 -110.132 -49.931 -0.48195 +VERTEX2 7639 -109.254 -50.384 -0.486471 +VERTEX2 7640 -108.422 -50.7807 -0.51918 +VERTEX2 7641 -107.822 -49.9687 1.05247 +VERTEX2 7642 -107.365 -49.171 1.03253 +VERTEX2 7643 -106.762 -48.3889 1.04403 +VERTEX2 7644 -106.225 -47.5519 1.04979 +VERTEX2 7645 -105.774 -46.7158 1.04129 +VERTEX2 7646 -104.959 -47.2495 -0.529572 +VERTEX2 7647 -103.995 -47.688 -0.523794 +VERTEX2 7648 -103.238 -48.1428 -0.533321 +VERTEX2 7649 -102.387 -48.6336 -0.549929 +VERTEX2 7650 -101.563 -49.1253 -0.540833 +VERTEX2 7651 -101.047 -48.2711 0.990846 +VERTEX2 7652 -100.527 -47.409 0.986443 +VERTEX2 7653 -99.9386 -46.5157 0.989084 +VERTEX2 7654 -99.4032 -45.764 1.00429 +VERTEX2 7655 -98.9284 -44.8979 0.992435 +VERTEX2 7656 -98.0969 -45.4562 -0.602928 +VERTEX2 7657 -97.3228 -46.1333 -0.616628 +VERTEX2 7658 -96.5682 -46.6491 -0.600372 +VERTEX2 7659 -95.7268 -47.2914 -0.610301 +VERTEX2 7660 -94.729 -47.8867 -0.635449 +VERTEX2 7661 -95.3545 -48.6994 -2.18875 +VERTEX2 7662 -95.9375 -49.5046 -2.16894 +VERTEX2 7663 -96.4543 -50.3096 -2.19383 +VERTEX2 7664 -97.0064 -51.0506 -2.18535 +VERTEX2 7665 -97.6674 -51.8651 -2.16322 +VERTEX2 7666 -96.8093 -52.4497 -0.560369 +VERTEX2 7667 -95.8903 -52.9632 -0.558339 +VERTEX2 7668 -94.9959 -53.4794 -0.564269 +VERTEX2 7669 -94.1984 -54.0534 -0.583679 +VERTEX2 7670 -93.3835 -54.6688 -0.584668 +VERTEX2 7671 -92.7806 -53.9333 0.955206 +VERTEX2 7672 -92.228 -53.1275 0.942366 +VERTEX2 7673 -91.7051 -52.2898 0.929582 +VERTEX2 7674 -91.131 -51.4425 0.898809 +VERTEX2 7675 -90.5136 -50.6228 0.864514 +VERTEX2 7676 -91.2638 -49.9858 2.42874 +VERTEX2 7677 -92.0377 -49.2361 2.41505 +VERTEX2 7678 -92.6567 -48.5793 2.41118 +VERTEX2 7679 -93.4478 -47.8991 2.38207 +VERTEX2 7680 -94.0867 -47.2481 2.38295 +VERTEX2 7681 -94.7221 -47.9576 -2.34084 +VERTEX2 7682 -95.4247 -48.7079 -2.3028 +VERTEX2 7683 -96.1001 -49.4451 -2.29436 +VERTEX2 7684 -96.7283 -50.1294 -2.30489 +VERTEX2 7685 -97.3806 -50.8995 -2.31095 +VERTEX2 7686 -96.576 -51.6706 -0.748531 +VERTEX2 7687 -95.8906 -52.4749 -0.747765 +VERTEX2 7688 -95.1418 -53.2023 -0.750619 +VERTEX2 7689 -94.3144 -53.8464 -0.755589 +VERTEX2 7690 -93.5541 -54.4277 -0.725823 +VERTEX2 7691 -94.2223 -55.1673 -2.31191 +VERTEX2 7692 -94.8866 -55.9372 -2.30174 +VERTEX2 7693 -95.6183 -56.6328 -2.30923 +VERTEX2 7694 -96.2954 -57.3722 -2.31856 +VERTEX2 7695 -97.0788 -58.0542 -2.33174 +VERTEX2 7696 -97.9039 -57.3986 2.36619 +VERTEX2 7697 -98.6139 -56.7655 2.368 +VERTEX2 7698 -99.2954 -56.0815 2.37591 +VERTEX2 7699 -100.016 -55.449 2.39184 +VERTEX2 7700 -100.71 -54.7917 2.39031 +VERTEX2 7701 -101.42 -55.524 -2.29701 +VERTEX2 7702 -102.137 -56.2292 -2.34639 +VERTEX2 7703 -102.844 -56.9479 -2.35464 +VERTEX2 7704 -103.539 -57.6766 -2.3742 +VERTEX2 7705 -104.26 -58.2706 -2.36269 +VERTEX2 7706 -103.581 -58.9399 -0.789786 +VERTEX2 7707 -102.951 -59.7025 -0.783855 +VERTEX2 7708 -102.3 -60.4886 -0.784411 +VERTEX2 7709 -101.645 -61.1175 -0.751341 +VERTEX2 7710 -100.866 -61.7831 -0.732705 +VERTEX2 7711 -100.188 -61.114 0.837975 +VERTEX2 7712 -99.4151 -60.3567 0.821669 +VERTEX2 7713 -98.7576 -59.6496 0.811388 +VERTEX2 7714 -98.0835 -58.9105 0.814732 +VERTEX2 7715 -97.4166 -58.1751 0.831505 +VERTEX2 7716 -98.1959 -57.4133 2.38133 +VERTEX2 7717 -98.9971 -56.7069 2.40115 +VERTEX2 7718 -99.7227 -55.9971 2.37628 +VERTEX2 7719 -100.423 -55.3106 2.36834 +VERTEX2 7720 -101.049 -54.5885 2.37728 +VERTEX2 7721 -101.688 -55.3081 -2.35036 +VERTEX2 7722 -102.311 -56.0578 -2.34478 +VERTEX2 7723 -103.008 -56.8285 -2.34158 +VERTEX2 7724 -103.657 -57.517 -2.33764 +VERTEX2 7725 -104.338 -58.1941 -2.29661 +VERTEX2 7726 -105.184 -57.5948 2.42647 +VERTEX2 7727 -105.883 -56.9826 2.42924 +VERTEX2 7728 -106.58 -56.3064 2.41715 +VERTEX2 7729 -107.34 -55.6397 2.40528 +VERTEX2 7730 -108.121 -54.9447 2.40936 +VERTEX2 7731 -108.791 -55.6489 -2.2966 +VERTEX2 7732 -109.387 -56.4704 -2.31346 +VERTEX2 7733 -110.06 -57.1805 -2.33449 +VERTEX2 7734 -110.739 -57.9434 -2.33366 +VERTEX2 7735 -111.381 -58.6365 -2.33474 +VERTEX2 7736 -112.142 -57.9472 2.40942 +VERTEX2 7737 -112.78 -57.3049 2.41559 +VERTEX2 7738 -113.493 -56.6332 2.41675 +VERTEX2 7739 -114.255 -55.9657 2.41186 +VERTEX2 7740 -114.975 -55.2121 2.4113 +VERTEX2 7741 -115.664 -55.9071 -2.27559 +VERTEX2 7742 -116.24 -56.6864 -2.28638 +VERTEX2 7743 -117.002 -57.4645 -2.3211 +VERTEX2 7744 -117.629 -58.2183 -2.333 +VERTEX2 7745 -118.357 -58.8911 -2.34447 +VERTEX2 7746 -118.979 -58.2028 2.42757 +VERTEX2 7747 -119.801 -57.6012 2.4059 +VERTEX2 7748 -120.518 -56.8864 2.39948 +VERTEX2 7749 -121.189 -56.107 2.40139 +VERTEX2 7750 -121.873 -55.3744 2.41739 +VERTEX2 7751 -122.551 -56.0483 -2.25611 +VERTEX2 7752 -123.085 -56.7241 -2.25103 +VERTEX2 7753 -123.692 -57.4968 -2.25892 +VERTEX2 7754 -124.394 -58.2458 -2.26005 +VERTEX2 7755 -125.114 -59.0515 -2.27076 +VERTEX2 7756 -125.936 -58.4206 2.50214 +VERTEX2 7757 -126.675 -57.7605 2.48347 +VERTEX2 7758 -127.46 -57.2523 2.48298 +VERTEX2 7759 -128.307 -56.6716 2.48417 +VERTEX2 7760 -129.086 -56.0743 2.48865 +VERTEX2 7761 -129.602 -56.8198 -2.23065 +VERTEX2 7762 -130.238 -57.5875 -2.21629 +VERTEX2 7763 -131.023 -58.4873 -2.20368 +VERTEX2 7764 -131.623 -59.2704 -2.21745 +VERTEX2 7765 -132.208 -60.0735 -2.21307 +VERTEX2 7766 -133.021 -59.5694 2.49704 +VERTEX2 7767 -133.865 -58.9294 2.51021 +VERTEX2 7768 -134.642 -58.3565 2.51933 +VERTEX2 7769 -135.492 -57.7867 2.5338 +VERTEX2 7770 -136.338 -57.225 2.53258 +VERTEX2 7771 -136.857 -58.112 -2.19618 +VERTEX2 7772 -137.46 -58.9136 -2.18018 +VERTEX2 7773 -138.077 -59.7697 -2.16251 +VERTEX2 7774 -138.6 -60.6774 -2.20094 +VERTEX2 7775 -139.303 -61.4537 -2.2015 +VERTEX2 7776 -138.515 -62.0612 -0.628211 +VERTEX2 7777 -137.673 -62.615 -0.640061 +VERTEX2 7778 -136.949 -63.2013 -0.653212 +VERTEX2 7779 -136.131 -63.856 -0.635541 +VERTEX2 7780 -135.317 -64.4611 -0.648934 +VERTEX2 7781 -134.701 -63.6097 0.909767 +VERTEX2 7782 -134.13 -62.8148 0.906057 +VERTEX2 7783 -133.491 -62.0196 0.894511 +VERTEX2 7784 -132.94 -61.2449 0.88775 +VERTEX2 7785 -132.27 -60.5607 0.869049 +VERTEX2 7786 -133.004 -60.0394 2.44769 +VERTEX2 7787 -133.751 -59.422 2.44964 +VERTEX2 7788 -134.469 -58.7301 2.45462 +VERTEX2 7789 -135.193 -58.1282 2.46686 +VERTEX2 7790 -135.93 -57.5611 2.4785 +VERTEX2 7791 -136.556 -58.3038 -2.24855 +VERTEX2 7792 -137.148 -59.0153 -2.24765 +VERTEX2 7793 -137.775 -59.8679 -2.23542 +VERTEX2 7794 -138.428 -60.6446 -2.23788 +VERTEX2 7795 -139.014 -61.4722 -2.21936 +VERTEX2 7796 -139.896 -60.9662 2.53112 +VERTEX2 7797 -140.608 -60.4179 2.5259 +VERTEX2 7798 -141.54 -59.8766 2.50673 +VERTEX2 7799 -142.379 -59.3301 2.48905 +VERTEX2 7800 -143.194 -58.7437 2.48116 +VERTEX2 7801 -142.515 -58.055 0.914242 +VERTEX2 7802 -141.834 -57.2023 0.924688 +VERTEX2 7803 -141.162 -56.4147 0.894439 +VERTEX2 7804 -140.433 -55.6441 0.887952 +VERTEX2 7805 -139.818 -54.7621 0.883496 +VERTEX2 7806 -139.049 -55.4078 -0.6922 +VERTEX2 7807 -138.326 -56.0466 -0.71523 +VERTEX2 7808 -137.553 -56.7482 -0.668435 +VERTEX2 7809 -136.788 -57.3504 -0.678431 +VERTEX2 7810 -136.01 -58.0093 -0.661708 +VERTEX2 7811 -135.335 -57.1738 0.916685 +VERTEX2 7812 -134.799 -56.3197 0.911849 +VERTEX2 7813 -134.277 -55.4386 0.931854 +VERTEX2 7814 -133.637 -54.6461 0.910689 +VERTEX2 7815 -133.035 -53.9249 0.889933 +VERTEX2 7816 -133.803 -53.3233 2.46782 +VERTEX2 7817 -134.633 -52.6655 2.47009 +VERTEX2 7818 -135.482 -51.9867 2.47878 +VERTEX2 7819 -136.323 -51.4146 2.47774 +VERTEX2 7820 -137.181 -50.8064 2.48648 +VERTEX2 7821 -137.822 -51.5488 -2.22662 +VERTEX2 7822 -138.381 -52.3383 -2.23481 +VERTEX2 7823 -139.048 -53.1329 -2.22832 +VERTEX2 7824 -139.681 -53.8902 -2.21777 +VERTEX2 7825 -140.299 -54.6766 -2.21588 +VERTEX2 7826 -139.521 -55.2669 -0.633071 +VERTEX2 7827 -138.755 -55.8546 -0.65281 +VERTEX2 7828 -137.917 -56.5047 -0.662035 +VERTEX2 7829 -137.117 -57.0837 -0.688913 +VERTEX2 7830 -136.221 -57.7035 -0.685608 +VERTEX2 7831 -135.636 -56.8619 0.909667 +VERTEX2 7832 -135.019 -56.2145 0.914355 +VERTEX2 7833 -134.463 -55.4474 0.909668 +VERTEX2 7834 -133.84 -54.7458 0.915436 +VERTEX2 7835 -133.266 -53.9239 0.913839 +VERTEX2 7836 -134.025 -53.2799 2.47462 +VERTEX2 7837 -134.851 -52.6535 2.51019 +VERTEX2 7838 -135.694 -52.057 2.48855 +VERTEX2 7839 -136.458 -51.4456 2.4752 +VERTEX2 7840 -137.175 -50.7977 2.49124 +VERTEX2 7841 -137.779 -51.5646 -2.2347 +VERTEX2 7842 -138.351 -52.3819 -2.2351 +VERTEX2 7843 -138.969 -53.1739 -2.22176 +VERTEX2 7844 -139.595 -53.988 -2.20392 +VERTEX2 7845 -140.212 -54.8589 -2.18947 +VERTEX2 7846 -139.387 -55.4144 -0.595682 +VERTEX2 7847 -138.577 -55.9747 -0.58149 +VERTEX2 7848 -137.796 -56.4914 -0.578625 +VERTEX2 7849 -136.958 -56.95 -0.581794 +VERTEX2 7850 -136.1 -57.4853 -0.579337 +VERTEX2 7851 -135.558 -56.6595 0.973728 +VERTEX2 7852 -134.958 -55.8027 0.973085 +VERTEX2 7853 -134.347 -54.846 0.938682 +VERTEX2 7854 -133.778 -54.1553 0.952426 +VERTEX2 7855 -133.254 -53.2747 0.964267 +VERTEX2 7856 -132.44 -53.8581 -0.58655 +VERTEX2 7857 -131.504 -54.4732 -0.576999 +VERTEX2 7858 -130.705 -55.0701 -0.566149 +VERTEX2 7859 -129.84 -55.6089 -0.569918 +VERTEX2 7860 -129.029 -56.1582 -0.574193 +VERTEX2 7861 -128.324 -55.427 0.986394 +VERTEX2 7862 -127.673 -54.6107 0.955569 +VERTEX2 7863 -127.089 -53.7935 0.933405 +VERTEX2 7864 -126.434 -53.0415 0.928305 +VERTEX2 7865 -125.887 -52.2499 0.968261 +VERTEX2 7866 -126.692 -51.6192 2.52139 +VERTEX2 7867 -127.588 -51.0706 2.52151 +VERTEX2 7868 -128.312 -50.535 2.52724 +VERTEX2 7869 -129.18 -49.9162 2.48999 +VERTEX2 7870 -129.953 -49.3343 2.48687 +VERTEX2 7871 -130.544 -50.1101 -2.25373 +VERTEX2 7872 -131.165 -50.7704 -2.25302 +VERTEX2 7873 -131.76 -51.4497 -2.22547 +VERTEX2 7874 -132.326 -52.153 -2.20912 +VERTEX2 7875 -132.911 -53.0459 -2.20544 +VERTEX2 7876 -132.126 -53.685 -0.610331 +VERTEX2 7877 -131.254 -54.2145 -0.643217 +VERTEX2 7878 -130.494 -54.7982 -0.654534 +VERTEX2 7879 -129.669 -55.3572 -0.647919 +VERTEX2 7880 -128.94 -56.0083 -0.659071 +VERTEX2 7881 -128.262 -55.3233 0.915149 +VERTEX2 7882 -127.721 -54.4999 0.874252 +VERTEX2 7883 -127.154 -53.8066 0.863113 +VERTEX2 7884 -126.515 -53.1544 0.847916 +VERTEX2 7885 -125.828 -52.3901 0.858842 +VERTEX2 7886 -125.159 -52.972 -0.705011 +VERTEX2 7887 -124.387 -53.6644 -0.727214 +VERTEX2 7888 -123.598 -54.2733 -0.709415 +VERTEX2 7889 -122.841 -54.9778 -0.708861 +VERTEX2 7890 -122.067 -55.5831 -0.704262 +VERTEX2 7891 -121.424 -54.8214 0.88248 +VERTEX2 7892 -120.795 -54.0634 0.86065 +VERTEX2 7893 -120.032 -53.252 0.892034 +VERTEX2 7894 -119.429 -52.4946 0.881405 +VERTEX2 7895 -118.82 -51.7241 0.900622 +VERTEX2 7896 -119.624 -51.1331 2.49616 +VERTEX2 7897 -120.428 -50.5292 2.48319 +VERTEX2 7898 -121.259 -49.7788 2.46021 +VERTEX2 7899 -122.025 -49.1852 2.48897 +VERTEX2 7900 -122.921 -48.5766 2.50739 +VERTEX2 7901 -123.502 -49.321 -2.23006 +VERTEX2 7902 -124.169 -50.0033 -2.22878 +VERTEX2 7903 -124.736 -50.7147 -2.22702 +VERTEX2 7904 -125.339 -51.4725 -2.20839 +VERTEX2 7905 -125.922 -52.2212 -2.22661 +VERTEX2 7906 -125.14 -52.8367 -0.657432 +VERTEX2 7907 -124.375 -53.4331 -0.624694 +VERTEX2 7908 -123.442 -54.0542 -0.643871 +VERTEX2 7909 -122.577 -54.718 -0.650815 +VERTEX2 7910 -121.759 -55.3381 -0.669283 +VERTEX2 7911 -121.082 -54.5685 0.865957 +VERTEX2 7912 -120.416 -53.7862 0.854376 +VERTEX2 7913 -119.802 -53.0399 0.841406 +VERTEX2 7914 -119.038 -52.3109 0.875382 +VERTEX2 7915 -118.37 -51.4417 0.881478 +VERTEX2 7916 -119.13 -50.7768 2.44998 +VERTEX2 7917 -119.93 -50.0595 2.45901 +VERTEX2 7918 -120.711 -49.3925 2.43644 +VERTEX2 7919 -121.445 -48.6943 2.45369 +VERTEX2 7920 -122.169 -48.0748 2.45325 +VERTEX2 7921 -121.542 -47.2879 0.900246 +VERTEX2 7922 -120.943 -46.4343 0.897081 +VERTEX2 7923 -120.328 -45.6766 0.928847 +VERTEX2 7924 -119.714 -44.8873 0.905272 +VERTEX2 7925 -119.003 -44.1014 0.924782 +VERTEX2 7926 -119.804 -43.463 2.48127 +VERTEX2 7927 -120.664 -42.7702 2.48467 +VERTEX2 7928 -121.422 -42.237 2.47125 +VERTEX2 7929 -122.165 -41.56 2.45178 +VERTEX2 7930 -122.938 -40.9783 2.46039 +VERTEX2 7931 -122.353 -40.1773 0.885227 +VERTEX2 7932 -121.736 -39.43 0.869733 +VERTEX2 7933 -121.046 -38.683 0.868709 +VERTEX2 7934 -120.441 -37.9436 0.878956 +VERTEX2 7935 -119.786 -37.1801 0.88408 +VERTEX2 7936 -119.032 -37.8621 -0.691384 +VERTEX2 7937 -118.222 -38.4539 -0.67719 +VERTEX2 7938 -117.351 -39.0998 -0.670783 +VERTEX2 7939 -116.524 -39.724 -0.691187 +VERTEX2 7940 -115.779 -40.3895 -0.703487 +VERTEX2 7941 -116.36 -41.2001 -2.29153 +VERTEX2 7942 -116.948 -41.9993 -2.30793 +VERTEX2 7943 -117.656 -42.7668 -2.31349 +VERTEX2 7944 -118.387 -43.4579 -2.3216 +VERTEX2 7945 -119.019 -44.2291 -2.30662 +VERTEX2 7946 -119.76 -43.527 2.41903 +VERTEX2 7947 -120.439 -42.8865 2.40137 +VERTEX2 7948 -121.151 -42.2078 2.43357 +VERTEX2 7949 -121.866 -41.535 2.42555 +VERTEX2 7950 -122.717 -40.9287 2.43093 +VERTEX2 7951 -122.085 -40.1532 0.81519 +VERTEX2 7952 -121.435 -39.5273 0.830045 +VERTEX2 7953 -120.741 -38.7373 0.857284 +VERTEX2 7954 -120.086 -37.9567 0.873384 +VERTEX2 7955 -119.484 -37.1725 0.910118 +VERTEX2 7956 -118.72 -37.8037 -0.675496 +VERTEX2 7957 -117.938 -38.381 -0.687221 +VERTEX2 7958 -117.155 -39.0487 -0.685216 +VERTEX2 7959 -116.396 -39.6847 -0.671466 +VERTEX2 7960 -115.678 -40.2768 -0.67743 +VERTEX2 7961 -115.018 -39.4997 0.907079 +VERTEX2 7962 -114.456 -38.6516 0.928433 +VERTEX2 7963 -113.933 -37.9099 0.914413 +VERTEX2 7964 -113.385 -37.1193 0.920367 +VERTEX2 7965 -112.808 -36.3877 0.909246 +VERTEX2 7966 -112.026 -36.8904 -0.671851 +VERTEX2 7967 -111.191 -37.4879 -0.674283 +VERTEX2 7968 -110.458 -38.1412 -0.692124 +VERTEX2 7969 -109.594 -38.7259 -0.685877 +VERTEX2 7970 -108.78 -39.3884 -0.695014 +VERTEX2 7971 -109.528 -40.0979 -2.27293 +VERTEX2 7972 -110.159 -40.889 -2.27826 +VERTEX2 7973 -110.861 -41.6714 -2.30271 +VERTEX2 7974 -111.585 -42.3955 -2.29557 +VERTEX2 7975 -112.317 -43.183 -2.2828 +VERTEX2 7976 -111.543 -43.798 -0.726083 +VERTEX2 7977 -110.767 -44.5273 -0.737574 +VERTEX2 7978 -109.99 -45.1911 -0.737965 +VERTEX2 7979 -109.192 -45.8338 -0.745915 +VERTEX2 7980 -108.436 -46.4933 -0.777616 +VERTEX2 7981 -107.742 -45.805 0.808863 +VERTEX2 7982 -106.993 -45.1458 0.786875 +VERTEX2 7983 -106.227 -44.465 0.782076 +VERTEX2 7984 -105.474 -43.7773 0.796622 +VERTEX2 7985 -104.811 -43.0047 0.810561 +VERTEX2 7986 -104.013 -43.6648 -0.74156 +VERTEX2 7987 -103.239 -44.2932 -0.754054 +VERTEX2 7988 -102.564 -45.0074 -0.796835 +VERTEX2 7989 -101.855 -45.7849 -0.804638 +VERTEX2 7990 -101.19 -46.5163 -0.811553 +VERTEX2 7991 -100.409 -45.8089 0.805453 +VERTEX2 7992 -99.7738 -45.082 0.821269 +VERTEX2 7993 -99.1852 -44.409 0.800176 +VERTEX2 7994 -98.6024 -43.7163 0.783828 +VERTEX2 7995 -97.8756 -42.9772 0.795163 +VERTEX2 7996 -97.2215 -43.712 -0.758685 +VERTEX2 7997 -96.5641 -44.4642 -0.784483 +VERTEX2 7998 -95.852 -45.1827 -0.781343 +VERTEX2 7999 -95.1596 -45.9476 -0.771641 +VERTEX2 8000 -94.4011 -46.6197 -0.764742 +VERTEX2 8001 -95.0143 -47.4523 -2.37362 +VERTEX2 8002 -95.656 -48.1853 -2.37693 +VERTEX2 8003 -96.3184 -48.9161 -2.38961 +VERTEX2 8004 -97.0425 -49.62 -2.40045 +VERTEX2 8005 -97.8322 -50.26 -2.38977 +VERTEX2 8006 -97.1231 -51.0356 -0.815726 +VERTEX2 8007 -96.3458 -51.7414 -0.839094 +VERTEX2 8008 -95.7092 -52.4829 -0.870487 +VERTEX2 8009 -95.1057 -53.2375 -0.868287 +VERTEX2 8010 -94.4498 -53.9261 -0.844195 +VERTEX2 8011 -95.2278 -54.628 -2.44497 +VERTEX2 8012 -95.9492 -55.2388 -2.47191 +VERTEX2 8013 -96.6731 -55.8329 -2.45671 +VERTEX2 8014 -97.4193 -56.5328 -2.48543 +VERTEX2 8015 -98.3068 -57.1858 -2.47444 +VERTEX2 8016 -97.5924 -57.8738 -0.897712 +VERTEX2 8017 -97.0257 -58.6595 -0.90968 +VERTEX2 8018 -96.3814 -59.5018 -0.93116 +VERTEX2 8019 -95.8153 -60.2804 -0.93027 +VERTEX2 8020 -95.3247 -61.0863 -0.966874 +VERTEX2 8021 -94.5581 -60.5462 0.598429 +VERTEX2 8022 -93.7093 -59.881 0.576666 +VERTEX2 8023 -92.8972 -59.301 0.576662 +VERTEX2 8024 -91.9683 -58.7851 0.577921 +VERTEX2 8025 -91.1288 -58.2774 0.614589 +VERTEX2 8026 -91.6613 -57.5212 2.17043 +VERTEX2 8027 -92.2433 -56.687 2.19051 +VERTEX2 8028 -92.7931 -55.8038 2.15915 +VERTEX2 8029 -93.3392 -54.9476 2.14033 +VERTEX2 8030 -94.0332 -54.0784 2.18828 +VERTEX2 8031 -94.735 -54.7064 -2.50882 +VERTEX2 8032 -95.5624 -55.292 -2.49265 +VERTEX2 8033 -96.4199 -55.8484 -2.46661 +VERTEX2 8034 -97.2331 -56.4479 -2.46389 +VERTEX2 8035 -98.0569 -57.0872 -2.48129 +VERTEX2 8036 -98.6837 -56.2796 2.22253 +VERTEX2 8037 -99.2561 -55.4624 2.22948 +VERTEX2 8038 -99.8209 -54.6379 2.22916 +VERTEX2 8039 -100.458 -53.7777 2.24823 +VERTEX2 8040 -101.11 -52.9795 2.25524 +VERTEX2 8041 -101.828 -53.5755 -2.48249 +VERTEX2 8042 -102.633 -54.2098 -2.46736 +VERTEX2 8043 -103.393 -54.9208 -2.46477 +VERTEX2 8044 -104.205 -55.4821 -2.46226 +VERTEX2 8045 -105.063 -56.158 -2.44666 +VERTEX2 8046 -104.394 -56.9365 -0.873307 +VERTEX2 8047 -103.715 -57.7305 -0.897192 +VERTEX2 8048 -103.01 -58.5043 -0.889218 +VERTEX2 8049 -102.315 -59.299 -0.907438 +VERTEX2 8050 -101.72 -60.104 -0.917175 +VERTEX2 8051 -102.523 -60.6905 -2.49045 +VERTEX2 8052 -103.222 -61.2891 -2.50633 +VERTEX2 8053 -104.035 -61.8877 -2.5016 +VERTEX2 8054 -104.869 -62.484 -2.51063 +VERTEX2 8055 -105.68 -63.1526 -2.50224 +VERTEX2 8056 -106.285 -62.406 2.19509 +VERTEX2 8057 -106.803 -61.6384 2.20959 +VERTEX2 8058 -107.369 -60.9457 2.20614 +VERTEX2 8059 -107.962 -60.1173 2.19646 +VERTEX2 8060 -108.523 -59.2279 2.22142 +VERTEX2 8061 -109.341 -59.8499 -2.5094 +VERTEX2 8062 -110.132 -60.53 -2.5271 +VERTEX2 8063 -110.895 -61.0263 -2.5447 +VERTEX2 8064 -111.767 -61.5989 -2.58305 +VERTEX2 8065 -112.601 -62.0793 -2.59204 +VERTEX2 8066 -112.025 -62.877 -1.00286 +VERTEX2 8067 -111.547 -63.674 -0.988555 +VERTEX2 8068 -110.967 -64.4605 -0.929826 +VERTEX2 8069 -110.378 -65.2291 -0.946176 +VERTEX2 8070 -109.735 -66.1142 -0.97141 +VERTEX2 8071 -108.922 -65.5237 0.597156 +VERTEX2 8072 -108.036 -64.8707 0.619513 +VERTEX2 8073 -107.168 -64.2592 0.624611 +VERTEX2 8074 -106.244 -63.5695 0.640054 +VERTEX2 8075 -105.48 -62.9721 0.619273 +VERTEX2 8076 -104.899 -63.7929 -0.912583 +VERTEX2 8077 -104.313 -64.5797 -0.940542 +VERTEX2 8078 -103.815 -65.3225 -0.946929 +VERTEX2 8079 -103.175 -66.1425 -0.917163 +VERTEX2 8080 -102.591 -66.9258 -0.931596 +VERTEX2 8081 -103.424 -67.498 -2.49304 +VERTEX2 8082 -104.269 -68.0981 -2.48101 +VERTEX2 8083 -105.065 -68.628 -2.51125 +VERTEX2 8084 -105.85 -69.2112 -2.49622 +VERTEX2 8085 -106.655 -69.8559 -2.50306 +VERTEX2 8086 -106.001 -70.5982 -0.951359 +VERTEX2 8087 -105.36 -71.4066 -0.932005 +VERTEX2 8088 -104.787 -72.1553 -0.907651 +VERTEX2 8089 -104.235 -73.0065 -0.941177 +VERTEX2 8090 -103.67 -73.8233 -0.920966 +VERTEX2 8091 -102.909 -73.288 0.660019 +VERTEX2 8092 -102.111 -72.7241 0.666756 +VERTEX2 8093 -101.384 -72.0933 0.651137 +VERTEX2 8094 -100.691 -71.4734 0.62789 +VERTEX2 8095 -99.8451 -70.8949 0.627407 +VERTEX2 8096 -99.2595 -71.7015 -0.891951 +VERTEX2 8097 -98.6046 -72.4595 -0.899535 +VERTEX2 8098 -98.041 -73.171 -0.916527 +VERTEX2 8099 -97.5037 -73.9914 -0.928489 +VERTEX2 8100 -96.899 -74.8684 -0.905509 +VERTEX2 8101 -97.7426 -75.5291 -2.49574 +VERTEX2 8102 -98.5868 -76.117 -2.54383 +VERTEX2 8103 -99.4975 -76.6512 -2.52304 +VERTEX2 8104 -100.264 -77.2102 -2.50344 +VERTEX2 8105 -101.096 -77.7795 -2.52253 +VERTEX2 8106 -101.75 -76.9567 2.1846 +VERTEX2 8107 -102.315 -76.161 2.17631 +VERTEX2 8108 -102.829 -75.4043 2.17668 +VERTEX2 8109 -103.385 -74.4307 2.2061 +VERTEX2 8110 -103.904 -73.6392 2.17127 +VERTEX2 8111 -104.659 -74.2103 -2.54383 +VERTEX2 8112 -105.467 -74.7153 -2.54399 +VERTEX2 8113 -106.242 -75.3128 -2.56251 +VERTEX2 8114 -107.09 -75.8671 -2.51674 +VERTEX2 8115 -107.976 -76.5042 -2.53717 +VERTEX2 8116 -107.387 -77.2761 -0.977741 +VERTEX2 8117 -106.865 -78.1598 -0.956034 +VERTEX2 8118 -106.319 -78.9926 -0.899977 +VERTEX2 8119 -105.699 -79.7921 -0.91421 +VERTEX2 8120 -105.079 -80.5658 -0.908609 +VERTEX2 8121 -104.203 -79.9977 0.665855 +VERTEX2 8122 -103.389 -79.3269 0.64262 +VERTEX2 8123 -102.612 -78.6594 0.623244 +VERTEX2 8124 -101.754 -78.111 0.614849 +VERTEX2 8125 -100.945 -77.5362 0.593844 +VERTEX2 8126 -100.396 -78.2668 -0.991407 +VERTEX2 8127 -99.7998 -79.1566 -1.00508 +VERTEX2 8128 -99.2356 -80.0461 -1.00459 +VERTEX2 8129 -98.75 -80.8951 -0.973868 +VERTEX2 8130 -98.192 -81.6921 -0.973064 +VERTEX2 8131 -97.3372 -81.1264 0.605885 +VERTEX2 8132 -96.5242 -80.5332 0.598151 +VERTEX2 8133 -95.751 -79.9411 0.616352 +VERTEX2 8134 -94.9486 -79.1921 0.593796 +VERTEX2 8135 -94.1655 -78.6502 0.634717 +VERTEX2 8136 -94.7887 -77.8352 2.18829 +VERTEX2 8137 -95.2767 -77.0513 2.21247 +VERTEX2 8138 -95.8261 -76.2018 2.19342 +VERTEX2 8139 -96.4513 -75.3201 2.19331 +VERTEX2 8140 -97.0532 -74.5457 2.17606 +VERTEX2 8141 -97.8814 -75.1374 -2.50777 +VERTEX2 8142 -98.6967 -75.7216 -2.49524 +VERTEX2 8143 -99.4317 -76.2764 -2.48333 +VERTEX2 8144 -100.085 -76.8954 -2.48295 +VERTEX2 8145 -100.918 -77.4481 -2.45697 +VERTEX2 8146 -100.313 -78.2136 -0.888653 +VERTEX2 8147 -99.6205 -79.012 -0.859498 +VERTEX2 8148 -98.8625 -79.7513 -0.830007 +VERTEX2 8149 -98.1983 -80.4268 -0.843278 +VERTEX2 8150 -97.5359 -81.1669 -0.826611 +VERTEX2 8151 -96.7694 -80.5107 0.744068 +VERTEX2 8152 -95.9941 -79.8041 0.747935 +VERTEX2 8153 -95.2943 -79.172 0.755128 +VERTEX2 8154 -94.4187 -78.4326 0.745261 +VERTEX2 8155 -93.6174 -77.7318 0.734454 +VERTEX2 8156 -94.1893 -76.9666 2.29138 +VERTEX2 8157 -94.8435 -76.1838 2.28 +VERTEX2 8158 -95.4465 -75.3882 2.24584 +VERTEX2 8159 -96.1389 -74.6016 2.24623 +VERTEX2 8160 -96.8358 -73.8394 2.27078 +VERTEX2 8161 -97.5025 -74.3628 -2.40517 +VERTEX2 8162 -98.2978 -75.0927 -2.42979 +VERTEX2 8163 -99.0626 -75.6885 -2.3934 +VERTEX2 8164 -99.808 -76.3217 -2.37906 +VERTEX2 8165 -100.562 -76.9908 -2.41511 +VERTEX2 8166 -99.8769 -77.8499 -0.813795 +VERTEX2 8167 -99.1205 -78.5865 -0.803976 +VERTEX2 8168 -98.4701 -79.3871 -0.774872 +VERTEX2 8169 -97.7432 -80.0782 -0.778751 +VERTEX2 8170 -97.001 -80.7714 -0.787048 +VERTEX2 8171 -97.6977 -81.5681 -2.37828 +VERTEX2 8172 -98.3459 -82.2008 -2.4062 +VERTEX2 8173 -99.0637 -82.9078 -2.3651 +VERTEX2 8174 -99.7846 -83.6457 -2.35405 +VERTEX2 8175 -100.525 -84.314 -2.33813 +VERTEX2 8176 -99.8239 -84.9988 -0.760898 +VERTEX2 8177 -99.0643 -85.6711 -0.755109 +VERTEX2 8178 -98.341 -86.369 -0.754544 +VERTEX2 8179 -97.5569 -87.0883 -0.708855 +VERTEX2 8180 -96.8132 -87.8208 -0.707104 +VERTEX2 8181 -97.5642 -88.5612 -2.23157 +VERTEX2 8182 -98.2254 -89.3538 -2.26356 +VERTEX2 8183 -98.8663 -90.1157 -2.27797 +VERTEX2 8184 -99.4512 -90.8985 -2.27122 +VERTEX2 8185 -100.126 -91.6579 -2.25675 +VERTEX2 8186 -99.4247 -92.3028 -0.673516 +VERTEX2 8187 -98.6111 -92.9101 -0.689518 +VERTEX2 8188 -97.7743 -93.5119 -0.680566 +VERTEX2 8189 -96.8901 -94.2195 -0.651008 +VERTEX2 8190 -96.0754 -94.8001 -0.645913 +VERTEX2 8191 -96.6677 -95.6457 -2.19979 +VERTEX2 8192 -97.2337 -96.4621 -2.18345 +VERTEX2 8193 -97.8783 -97.2169 -2.22078 +VERTEX2 8194 -98.4345 -97.9534 -2.20207 +VERTEX2 8195 -99.0271 -98.7345 -2.16477 +VERTEX2 8196 -98.1894 -99.2376 -0.609153 +VERTEX2 8197 -97.3077 -99.7033 -0.580712 +VERTEX2 8198 -96.5361 -100.237 -0.578126 +VERTEX2 8199 -95.6173 -100.743 -0.551544 +VERTEX2 8200 -94.8409 -101.215 -0.554045 +VERTEX2 8201 -95.3621 -102.05 -2.14084 +VERTEX2 8202 -95.8931 -102.916 -2.14457 +VERTEX2 8203 -96.4616 -103.73 -2.15845 +VERTEX2 8204 -97.0233 -104.593 -2.14768 +VERTEX2 8205 -97.4916 -105.368 -2.13059 +VERTEX2 8206 -96.5917 -105.959 -0.549339 +VERTEX2 8207 -95.7282 -106.455 -0.572517 +VERTEX2 8208 -94.948 -107.032 -0.563887 +VERTEX2 8209 -94.1304 -107.604 -0.560338 +VERTEX2 8210 -93.2654 -108.102 -0.593294 +VERTEX2 8211 -92.7496 -107.332 0.954063 +VERTEX2 8212 -92.1508 -106.449 0.952984 +VERTEX2 8213 -91.6025 -105.566 0.955166 +VERTEX2 8214 -90.9831 -104.739 0.933778 +VERTEX2 8215 -90.3746 -103.962 0.920049 +VERTEX2 8216 -91.1795 -103.319 2.49745 +VERTEX2 8217 -92.0009 -102.697 2.44305 +VERTEX2 8218 -92.8118 -102.016 2.47245 +VERTEX2 8219 -93.5916 -101.41 2.47769 +VERTEX2 8220 -94.3482 -100.718 2.46909 +VERTEX2 8221 -94.9541 -101.495 -2.21762 +VERTEX2 8222 -95.5026 -102.278 -2.20152 +VERTEX2 8223 -96.1129 -103.092 -2.16445 +VERTEX2 8224 -96.785 -103.845 -2.14106 +VERTEX2 8225 -97.4685 -104.691 -2.1398 +VERTEX2 8226 -96.573 -105.238 -0.580005 +VERTEX2 8227 -95.7077 -105.798 -0.576535 +VERTEX2 8228 -94.9905 -106.367 -0.561695 +VERTEX2 8229 -94.1715 -106.928 -0.537636 +VERTEX2 8230 -93.3269 -107.404 -0.576539 +VERTEX2 8231 -92.8459 -106.51 1.01704 +VERTEX2 8232 -92.339 -105.594 1.01471 +VERTEX2 8233 -91.7871 -104.849 0.979887 +VERTEX2 8234 -91.1325 -104.027 0.988085 +VERTEX2 8235 -90.5435 -103.241 0.996155 +VERTEX2 8236 -91.415 -102.748 2.55167 +VERTEX2 8237 -92.2719 -102.136 2.55211 +VERTEX2 8238 -93.0769 -101.629 2.53084 +VERTEX2 8239 -93.9068 -101.127 2.53758 +VERTEX2 8240 -94.754 -100.552 2.56411 +VERTEX2 8241 -95.2342 -101.441 -2.13372 +VERTEX2 8242 -95.674 -102.274 -2.1211 +VERTEX2 8243 -96.1855 -103.041 -2.15542 +VERTEX2 8244 -96.7066 -103.849 -2.15451 +VERTEX2 8245 -97.2235 -104.679 -2.12664 +VERTEX2 8246 -96.3907 -105.29 -0.591869 +VERTEX2 8247 -95.6349 -105.823 -0.608248 +VERTEX2 8248 -94.7702 -106.428 -0.637884 +VERTEX2 8249 -93.9442 -106.998 -0.62368 +VERTEX2 8250 -93.1159 -107.651 -0.644111 +VERTEX2 8251 -92.4634 -106.724 0.921459 +VERTEX2 8252 -91.8154 -105.838 0.909975 +VERTEX2 8253 -91.2023 -105.074 0.908572 +VERTEX2 8254 -90.6248 -104.226 0.90476 +VERTEX2 8255 -90.0191 -103.467 0.91011 +VERTEX2 8256 -90.7475 -102.826 2.52401 +VERTEX2 8257 -91.6565 -102.195 2.52 +VERTEX2 8258 -92.4923 -101.649 2.51647 +VERTEX2 8259 -93.2302 -101.038 2.51112 +VERTEX2 8260 -94.0087 -100.454 2.54342 +VERTEX2 8261 -94.6552 -101.235 -2.1946 +VERTEX2 8262 -95.2268 -102.077 -2.17711 +VERTEX2 8263 -95.767 -102.718 -2.17138 +VERTEX2 8264 -96.3654 -103.559 -2.15547 +VERTEX2 8265 -96.9232 -104.431 -2.17395 +VERTEX2 8266 -97.7699 -103.814 2.53895 +VERTEX2 8267 -98.5474 -103.298 2.54208 +VERTEX2 8268 -99.2997 -102.65 2.56171 +VERTEX2 8269 -100.18 -102.08 2.57624 +VERTEX2 8270 -101.052 -101.527 2.56102 +VERTEX2 8271 -101.654 -102.352 -2.17278 +VERTEX2 8272 -102.246 -103.216 -2.18931 +VERTEX2 8273 -102.823 -104.065 -2.18405 +VERTEX2 8274 -103.462 -104.927 -2.18588 +VERTEX2 8275 -103.981 -105.737 -2.17962 +VERTEX2 8276 -103.093 -106.293 -0.652405 +VERTEX2 8277 -102.276 -106.934 -0.646707 +VERTEX2 8278 -101.472 -107.563 -0.64439 +VERTEX2 8279 -100.783 -108.132 -0.662192 +VERTEX2 8280 -100.092 -108.737 -0.675378 +VERTEX2 8281 -100.69 -109.449 -2.22957 +VERTEX2 8282 -101.367 -110.176 -2.26103 +VERTEX2 8283 -102.019 -110.988 -2.24529 +VERTEX2 8284 -102.58 -111.674 -2.22907 +VERTEX2 8285 -103.291 -112.406 -2.23652 +VERTEX2 8286 -102.471 -113.087 -0.699177 +VERTEX2 8287 -101.765 -113.86 -0.711969 +VERTEX2 8288 -100.989 -114.501 -0.724848 +VERTEX2 8289 -100.151 -115.114 -0.747956 +VERTEX2 8290 -99.3733 -115.83 -0.724866 +VERTEX2 8291 -100.091 -116.5 -2.29379 +VERTEX2 8292 -100.695 -117.286 -2.27378 +VERTEX2 8293 -101.35 -118.054 -2.26808 +VERTEX2 8294 -101.994 -118.828 -2.26815 +VERTEX2 8295 -102.592 -119.603 -2.24813 +VERTEX2 8296 -101.84 -120.295 -0.673172 +VERTEX2 8297 -101.023 -120.845 -0.689328 +VERTEX2 8298 -100.264 -121.452 -0.704721 +VERTEX2 8299 -99.4775 -122.141 -0.683964 +VERTEX2 8300 -98.7161 -122.746 -0.700982 +VERTEX2 8301 -98.1252 -121.924 0.881231 +VERTEX2 8302 -97.5502 -121.152 0.887317 +VERTEX2 8303 -96.9203 -120.352 0.882734 +VERTEX2 8304 -96.2135 -119.552 0.867596 +VERTEX2 8305 -95.6816 -118.831 0.871757 +VERTEX2 8306 -94.8598 -119.506 -0.691027 +VERTEX2 8307 -94.021 -120.044 -0.709383 +VERTEX2 8308 -93.2025 -120.682 -0.716292 +VERTEX2 8309 -92.4146 -121.329 -0.732386 +VERTEX2 8310 -91.5962 -121.984 -0.706955 +VERTEX2 8311 -90.9608 -121.227 0.847955 +VERTEX2 8312 -90.2811 -120.497 0.879678 +VERTEX2 8313 -89.6364 -119.77 0.903019 +VERTEX2 8314 -88.982 -119.033 0.916171 +VERTEX2 8315 -88.3573 -118.197 0.873512 +VERTEX2 8316 -87.584 -118.954 -0.687417 +VERTEX2 8317 -86.8687 -119.673 -0.691017 +VERTEX2 8318 -86.0936 -120.284 -0.698631 +VERTEX2 8319 -85.3951 -120.945 -0.705281 +VERTEX2 8320 -84.5852 -121.565 -0.74065 +VERTEX2 8321 -83.8595 -120.914 0.806741 +VERTEX2 8322 -83.1974 -120.182 0.789618 +VERTEX2 8323 -82.3916 -119.583 0.765776 +VERTEX2 8324 -81.7537 -118.87 0.76325 +VERTEX2 8325 -81.0458 -118.269 0.780361 +VERTEX2 8326 -81.745 -117.626 2.3473 +VERTEX2 8327 -82.4545 -116.844 2.3453 +VERTEX2 8328 -83.1841 -116.202 2.3443 +VERTEX2 8329 -83.8471 -115.522 2.36325 +VERTEX2 8330 -84.4907 -114.891 2.33183 +VERTEX2 8331 -83.7939 -114.2 0.74364 +VERTEX2 8332 -82.9523 -113.464 0.719504 +VERTEX2 8333 -82.1605 -112.723 0.72186 +VERTEX2 8334 -81.3001 -112.04 0.69919 +VERTEX2 8335 -80.49 -111.421 0.683961 +VERTEX2 8336 -79.8278 -112.197 -0.894365 +VERTEX2 8337 -79.223 -113.046 -0.867216 +VERTEX2 8338 -78.5188 -113.782 -0.875662 +VERTEX2 8339 -77.8736 -114.6 -0.868728 +VERTEX2 8340 -77.2974 -115.423 -0.876429 +VERTEX2 8341 -76.5968 -114.78 0.68733 +VERTEX2 8342 -75.9034 -114.135 0.710598 +VERTEX2 8343 -75.1477 -113.469 0.676954 +VERTEX2 8344 -74.3133 -112.822 0.690841 +VERTEX2 8345 -73.4859 -112.142 0.657002 +VERTEX2 8346 -72.82 -112.908 -0.955624 +VERTEX2 8347 -72.284 -113.753 -0.939883 +VERTEX2 8348 -71.7338 -114.549 -0.944033 +VERTEX2 8349 -71.1486 -115.301 -0.962131 +VERTEX2 8350 -70.588 -116.157 -0.957412 +VERTEX2 8351 -69.7495 -115.556 0.588408 +VERTEX2 8352 -69.0122 -114.973 0.60575 +VERTEX2 8353 -68.1437 -114.377 0.627816 +VERTEX2 8354 -67.2986 -113.759 0.636965 +VERTEX2 8355 -66.3956 -113.177 0.61713 +VERTEX2 8356 -67.0125 -112.376 2.18092 +VERTEX2 8357 -67.642 -111.549 2.182 +VERTEX2 8358 -68.3121 -110.679 2.18585 +VERTEX2 8359 -68.9351 -109.929 2.20031 +VERTEX2 8360 -69.5257 -109.03 2.21291 +VERTEX2 8361 -68.7149 -108.488 0.664238 +VERTEX2 8362 -67.959 -107.878 0.668962 +VERTEX2 8363 -67.2345 -107.269 0.65101 +VERTEX2 8364 -66.3982 -106.574 0.608381 +VERTEX2 8365 -65.5613 -105.912 0.601445 +VERTEX2 8366 -66.2071 -105.121 2.1551 +VERTEX2 8367 -66.7554 -104.245 2.12694 +VERTEX2 8368 -67.2061 -103.351 2.08829 +VERTEX2 8369 -67.7469 -102.501 2.09309 +VERTEX2 8370 -68.255 -101.694 2.07662 +VERTEX2 8371 -69.0446 -102.284 -2.59912 +VERTEX2 8372 -69.8327 -102.734 -2.56566 +VERTEX2 8373 -70.7718 -103.221 -2.59286 +VERTEX2 8374 -71.6865 -103.711 -2.60809 +VERTEX2 8375 -72.4996 -104.271 -2.60328 +VERTEX2 8376 -71.974 -105.116 -1.05604 +VERTEX2 8377 -71.4702 -106.067 -1.08402 +VERTEX2 8378 -71.074 -106.915 -1.09006 +VERTEX2 8379 -70.6163 -107.761 -1.14377 +VERTEX2 8380 -70.1844 -108.717 -1.16929 +VERTEX2 8381 -69.2623 -108.279 0.401431 +VERTEX2 8382 -68.3806 -107.989 0.426394 +VERTEX2 8383 -67.443 -107.564 0.393496 +VERTEX2 8384 -66.5882 -107.168 0.357389 +VERTEX2 8385 -65.626 -106.816 0.378038 +VERTEX2 8386 -65.2415 -107.696 -1.1862 +VERTEX2 8387 -64.846 -108.596 -1.17146 +VERTEX2 8388 -64.4708 -109.535 -1.14868 +VERTEX2 8389 -64.0351 -110.48 -1.16596 +VERTEX2 8390 -63.6795 -111.334 -1.17532 +VERTEX2 8391 -64.6425 -111.76 -2.75825 +VERTEX2 8392 -65.5614 -112.228 -2.73998 +VERTEX2 8393 -66.4019 -112.58 -2.76276 +VERTEX2 8394 -67.2861 -112.97 -2.77057 +VERTEX2 8395 -68.1996 -113.297 -2.80018 +VERTEX2 8396 -68.5469 -112.427 1.9188 +VERTEX2 8397 -68.8567 -111.489 1.92009 +VERTEX2 8398 -69.2202 -110.627 1.91531 +VERTEX2 8399 -69.5573 -109.708 1.93609 +VERTEX2 8400 -69.8698 -108.815 1.88911 +VERTEX2 8401 -70.827 -109.12 -2.84331 +VERTEX2 8402 -71.8016 -109.313 -2.84408 +VERTEX2 8403 -72.7703 -109.685 -2.82719 +VERTEX2 8404 -73.6519 -109.913 -2.82708 +VERTEX2 8405 -74.5705 -110.126 -2.8252 +VERTEX2 8406 -74.2153 -111.11 -1.23166 +VERTEX2 8407 -73.9686 -112.093 -1.24857 +VERTEX2 8408 -73.7434 -113.105 -1.23334 +VERTEX2 8409 -73.3451 -114.15 -1.23795 +VERTEX2 8410 -73.0001 -115.13 -1.25236 +VERTEX2 8411 -72.0671 -114.809 0.331798 +VERTEX2 8412 -71.1762 -114.516 0.357441 +VERTEX2 8413 -70.228 -114.151 0.380684 +VERTEX2 8414 -69.3425 -113.938 0.390978 +VERTEX2 8415 -68.358 -113.549 0.4054 +VERTEX2 8416 -68.7345 -112.578 2.00525 +VERTEX2 8417 -69.2146 -111.72 2.04455 +VERTEX2 8418 -69.7232 -110.855 1.98878 +VERTEX2 8419 -70.1867 -109.912 1.96193 +VERTEX2 8420 -70.5219 -108.952 1.96037 +VERTEX2 8421 -69.6192 -108.6 0.408419 +VERTEX2 8422 -68.6565 -108.172 0.434571 +VERTEX2 8423 -67.8308 -107.714 0.431657 +VERTEX2 8424 -67.022 -107.169 0.466941 +VERTEX2 8425 -66.069 -106.743 0.419053 +VERTEX2 8426 -66.4988 -105.816 1.97182 +VERTEX2 8427 -66.9368 -104.927 1.96905 +VERTEX2 8428 -67.306 -104.064 1.91899 +VERTEX2 8429 -67.635 -103.221 1.91933 +VERTEX2 8430 -68.0688 -102.202 1.90859 +VERTEX2 8431 -67.1197 -101.902 0.350262 +VERTEX2 8432 -66.0623 -101.481 0.330283 +VERTEX2 8433 -65.0808 -101.168 0.340375 +VERTEX2 8434 -64.1748 -100.805 0.277505 +VERTEX2 8435 -63.1108 -100.547 0.279622 +VERTEX2 8436 -63.3705 -99.5948 1.8685 +VERTEX2 8437 -63.678 -98.6914 1.83628 +VERTEX2 8438 -63.8946 -97.6914 1.8284 +VERTEX2 8439 -64.1273 -96.6502 1.81943 +VERTEX2 8440 -64.3399 -95.726 1.7814 +VERTEX2 8441 -65.342 -95.9694 -2.96544 +VERTEX2 8442 -66.2911 -96.2198 -2.99721 +VERTEX2 8443 -67.2542 -96.463 -2.96399 +VERTEX2 8444 -68.3488 -96.6757 -2.99831 +VERTEX2 8445 -69.3034 -96.7848 -2.97743 +VERTEX2 8446 -69.4462 -95.7597 1.74808 +VERTEX2 8447 -69.5693 -94.8015 1.76214 +VERTEX2 8448 -69.7528 -93.8571 1.74161 +VERTEX2 8449 -69.9339 -92.8543 1.75778 +VERTEX2 8450 -70.0624 -91.8571 1.77214 +VERTEX2 8451 -70.9253 -91.9912 -2.95604 +VERTEX2 8452 -71.9079 -92.1521 -2.97847 +VERTEX2 8453 -72.8984 -92.2564 -2.96069 +VERTEX2 8454 -73.926 -92.3515 -2.93363 +VERTEX2 8455 -74.9152 -92.4986 -2.96047 +VERTEX2 8456 -74.7096 -93.4913 -1.44584 +VERTEX2 8457 -74.5681 -94.4941 -1.43518 +VERTEX2 8458 -74.3327 -95.4608 -1.4731 +VERTEX2 8459 -74.1715 -96.388 -1.4744 +VERTEX2 8460 -73.9935 -97.3268 -1.47708 +VERTEX2 8461 -72.9796 -97.2104 0.119673 +VERTEX2 8462 -71.922 -97.1132 0.135968 +VERTEX2 8463 -70.9683 -96.9888 0.127262 +VERTEX2 8464 -70.0333 -96.8568 0.0895558 +VERTEX2 8465 -68.9514 -96.7867 0.0911054 +VERTEX2 8466 -68.8148 -97.7956 -1.48258 +VERTEX2 8467 -68.6003 -98.8774 -1.48267 +VERTEX2 8468 -68.6035 -99.8096 -1.47945 +VERTEX2 8469 -68.5705 -100.786 -1.48634 +VERTEX2 8470 -68.5132 -101.707 -1.45459 +VERTEX2 8471 -69.4272 -101.854 -3.05925 +VERTEX2 8472 -70.4887 -101.943 -3.0504 +VERTEX2 8473 -71.5598 -101.972 -3.03864 +VERTEX2 8474 -72.5565 -102.037 -3.03116 +VERTEX2 8475 -73.5823 -102.207 -3.02761 +VERTEX2 8476 -73.4762 -103.245 -1.44465 +VERTEX2 8477 -73.3379 -104.192 -1.43769 +VERTEX2 8478 -73.1854 -105.123 -1.47314 +VERTEX2 8479 -73.0754 -106.124 -1.45181 +VERTEX2 8480 -72.9253 -107.08 -1.47795 +VERTEX2 8481 -71.9129 -106.974 0.0753511 +VERTEX2 8482 -70.9262 -106.927 0.0846558 +VERTEX2 8483 -69.9381 -106.897 0.0969547 +VERTEX2 8484 -68.8947 -106.78 0.0762663 +VERTEX2 8485 -67.8361 -106.713 0.0844611 +VERTEX2 8486 -67.6701 -107.692 -1.49246 +VERTEX2 8487 -67.5928 -108.697 -1.52798 +VERTEX2 8488 -67.5156 -109.773 -1.50073 +VERTEX2 8489 -67.504 -110.81 -1.53546 +VERTEX2 8490 -67.4297 -111.753 -1.55895 +VERTEX2 8491 -66.2733 -111.721 -0.00392687 +VERTEX2 8492 -65.2522 -111.708 -0.0203961 +VERTEX2 8493 -64.1505 -111.637 -0.0149033 +VERTEX2 8494 -63.1024 -111.601 -0.0353848 +VERTEX2 8495 -62.0445 -111.511 -0.0547877 +VERTEX2 8496 -61.94 -110.503 1.48711 +VERTEX2 8497 -61.8772 -109.495 1.46414 +VERTEX2 8498 -61.78 -108.473 1.44627 +VERTEX2 8499 -61.6793 -107.443 1.45772 +VERTEX2 8500 -61.5428 -106.395 1.44061 +VERTEX2 8501 -60.5825 -106.507 -0.145345 +VERTEX2 8502 -59.5701 -106.752 -0.0827655 +VERTEX2 8503 -58.5165 -106.808 -0.0571406 +VERTEX2 8504 -57.5159 -106.792 -0.0696611 +VERTEX2 8505 -56.4986 -106.882 -0.0785507 +VERTEX2 8506 -56.5517 -107.923 -1.65151 +VERTEX2 8507 -56.6373 -109.012 -1.64849 +VERTEX2 8508 -56.6668 -110.024 -1.64196 +VERTEX2 8509 -56.7526 -110.935 -1.62832 +VERTEX2 8510 -56.8177 -111.885 -1.68147 +VERTEX2 8511 -57.7346 -111.75 3.02404 +VERTEX2 8512 -58.8043 -111.573 2.99653 +VERTEX2 8513 -59.8548 -111.377 2.96563 +VERTEX2 8514 -60.814 -111.142 2.95475 +VERTEX2 8515 -61.92 -110.945 2.93241 +VERTEX2 8516 -62.1294 -111.956 -1.76719 +VERTEX2 8517 -62.37 -112.901 -1.75787 +VERTEX2 8518 -62.5153 -113.928 -1.75733 +VERTEX2 8519 -62.8128 -114.943 -1.73415 +VERTEX2 8520 -62.9654 -115.931 -1.74784 +VERTEX2 8521 -61.8938 -116.126 -0.139653 +VERTEX2 8522 -60.9372 -116.271 -0.150531 +VERTEX2 8523 -59.8725 -116.349 -0.157866 +VERTEX2 8524 -58.8345 -116.595 -0.151077 +VERTEX2 8525 -57.755 -116.721 -0.173259 +VERTEX2 8526 -57.9659 -117.752 -1.73119 +VERTEX2 8527 -58.0891 -118.767 -1.74608 +VERTEX2 8528 -58.2001 -119.791 -1.75293 +VERTEX2 8529 -58.387 -120.787 -1.71655 +VERTEX2 8530 -58.5641 -121.813 -1.70037 +VERTEX2 8531 -59.5976 -121.717 3.01306 +VERTEX2 8532 -60.5883 -121.613 3.02456 +VERTEX2 8533 -61.5502 -121.561 3.03067 +VERTEX2 8534 -62.5019 -121.52 3.02489 +VERTEX2 8535 -63.436 -121.513 3.01458 +VERTEX2 8536 -63.324 -120.517 1.44622 +VERTEX2 8537 -63.1214 -119.534 1.45487 +VERTEX2 8538 -63.007 -118.549 1.45868 +VERTEX2 8539 -62.9317 -117.519 1.48852 +VERTEX2 8540 -62.7608 -116.539 1.51103 +VERTEX2 8541 -63.7443 -116.571 3.11623 +VERTEX2 8542 -64.7172 -116.504 3.12203 +VERTEX2 8543 -65.7014 -116.485 3.09379 +VERTEX2 8544 -66.7039 -116.297 3.09341 +VERTEX2 8545 -67.6488 -116.279 3.07125 +VERTEX2 8546 -67.6023 -115.343 1.50243 +VERTEX2 8547 -67.5407 -114.398 1.52683 +VERTEX2 8548 -67.4553 -113.418 1.48828 +VERTEX2 8549 -67.3943 -112.438 1.48681 +VERTEX2 8550 -67.3099 -111.411 1.47892 +VERTEX2 8551 -68.2275 -111.265 3.05452 +VERTEX2 8552 -69.2543 -111.1 3.04878 +VERTEX2 8553 -70.2399 -111.023 3.0433 +VERTEX2 8554 -71.2476 -110.946 3.08839 +VERTEX2 8555 -72.1698 -110.902 3.09824 +VERTEX2 8556 -72.3456 -111.924 -1.564 +VERTEX2 8557 -72.3579 -112.939 -1.5485 +VERTEX2 8558 -72.2758 -113.935 -1.56096 +VERTEX2 8559 -72.3587 -114.877 -1.58198 +VERTEX2 8560 -72.3866 -115.846 -1.57461 +VERTEX2 8561 -71.3952 -115.778 -0.0065147 +VERTEX2 8562 -70.4011 -115.711 0.0517799 +VERTEX2 8563 -69.3815 -115.712 0.0700085 +VERTEX2 8564 -68.4662 -115.645 0.0887423 +VERTEX2 8565 -67.5898 -115.48 0.106141 +VERTEX2 8566 -67.7297 -114.488 1.67213 +VERTEX2 8567 -67.7612 -113.465 1.65638 +VERTEX2 8568 -67.8176 -112.51 1.67704 +VERTEX2 8569 -67.8526 -111.562 1.66517 +VERTEX2 8570 -67.9594 -110.527 1.68422 +VERTEX2 8571 -66.8857 -110.451 0.118329 +VERTEX2 8572 -65.9038 -110.338 0.128883 +VERTEX2 8573 -64.8687 -110.253 0.134321 +VERTEX2 8574 -63.9872 -110.109 0.126839 +VERTEX2 8575 -63.0099 -110.021 0.0979401 +VERTEX2 8576 -63.1571 -109.025 1.6446 +VERTEX2 8577 -63.2383 -108.004 1.6286 +VERTEX2 8578 -63.269 -107.043 1.63181 +VERTEX2 8579 -63.2816 -106.046 1.62858 +VERTEX2 8580 -63.3482 -104.989 1.64479 +VERTEX2 8581 -62.3528 -104.931 0.0737824 +VERTEX2 8582 -61.423 -104.891 0.0724339 +VERTEX2 8583 -60.425 -104.821 0.0765569 +VERTEX2 8584 -59.4755 -104.767 0.067676 +VERTEX2 8585 -58.5193 -104.769 0.0605341 +VERTEX2 8586 -58.5635 -103.811 1.60166 +VERTEX2 8587 -58.6406 -102.829 1.59326 +VERTEX2 8588 -58.5551 -101.778 1.57504 +VERTEX2 8589 -58.6254 -100.795 1.5549 +VERTEX2 8590 -58.6085 -99.7478 1.53476 +VERTEX2 8591 -59.4881 -99.7863 3.07478 +VERTEX2 8592 -60.4865 -99.7167 3.09559 +VERTEX2 8593 -61.5082 -99.7146 3.07126 +VERTEX2 8594 -62.3897 -99.5904 3.05122 +VERTEX2 8595 -63.3668 -99.5054 3.00701 +VERTEX2 8596 -63.1821 -98.594 1.41044 +VERTEX2 8597 -62.9773 -97.5167 1.39024 +VERTEX2 8598 -62.8297 -96.4919 1.42992 +VERTEX2 8599 -62.6891 -95.4913 1.42858 +VERTEX2 8600 -62.5574 -94.5265 1.42326 +VERTEX2 8601 -63.5378 -94.367 3.03354 +VERTEX2 8602 -64.5108 -94.2234 3.03573 +VERTEX2 8603 -65.524 -94.1803 3.03843 +VERTEX2 8604 -66.5912 -94.1092 3.02725 +VERTEX2 8605 -67.6041 -93.9386 3.01068 +VERTEX2 8606 -67.7324 -94.9401 -1.68755 +VERTEX2 8607 -67.9026 -96.0267 -1.68364 +VERTEX2 8608 -68.1118 -97.0379 -1.69188 +VERTEX2 8609 -68.2553 -98.0218 -1.70278 +VERTEX2 8610 -68.3331 -98.9708 -1.70039 +VERTEX2 8611 -69.2659 -98.9001 2.98341 +VERTEX2 8612 -70.2537 -98.7421 2.97086 +VERTEX2 8613 -71.1835 -98.6539 2.95693 +VERTEX2 8614 -72.1981 -98.5098 2.98199 +VERTEX2 8615 -73.2309 -98.2772 2.96372 +VERTEX2 8616 -73.4109 -99.3025 -1.73297 +VERTEX2 8617 -73.6728 -100.288 -1.74694 +VERTEX2 8618 -73.8368 -101.309 -1.74854 +VERTEX2 8619 -74.055 -102.259 -1.73568 +VERTEX2 8620 -74.2706 -103.304 -1.7379 +VERTEX2 8621 -73.2165 -103.398 -0.176439 +VERTEX2 8622 -72.1801 -103.653 -0.158086 +VERTEX2 8623 -71.1734 -103.772 -0.155723 +VERTEX2 8624 -70.2296 -103.871 -0.171627 +VERTEX2 8625 -69.2796 -104.039 -0.166137 +VERTEX2 8626 -69.1024 -103.07 1.43991 +VERTEX2 8627 -68.9939 -102.103 1.43951 +VERTEX2 8628 -68.853 -101.158 1.46337 +VERTEX2 8629 -68.6887 -100.165 1.44543 +VERTEX2 8630 -68.5273 -99.2377 1.42369 +VERTEX2 8631 -69.477 -99.0412 2.99036 +VERTEX2 8632 -70.4436 -98.9174 3.00843 +VERTEX2 8633 -71.4395 -98.7505 3.01745 +VERTEX2 8634 -72.382 -98.5839 3.01845 +VERTEX2 8635 -73.2339 -98.4527 3.03542 +VERTEX2 8636 -72.9965 -97.3656 1.45706 +VERTEX2 8637 -72.8849 -96.3867 1.46444 +VERTEX2 8638 -72.7478 -95.3828 1.4788 +VERTEX2 8639 -72.6685 -94.3998 1.47805 +VERTEX2 8640 -72.5449 -93.4439 1.4383 +VERTEX2 8641 -73.5897 -93.348 3.03866 +VERTEX2 8642 -74.5566 -93.2585 3.03211 +VERTEX2 8643 -75.5305 -93.0167 3.04086 +VERTEX2 8644 -76.5582 -92.8552 3.01677 +VERTEX2 8645 -77.5851 -92.6919 3.0528 +VERTEX2 8646 -77.7146 -93.638 -1.64168 +VERTEX2 8647 -77.8394 -94.6329 -1.607 +VERTEX2 8648 -77.8484 -95.6563 -1.6012 +VERTEX2 8649 -77.8139 -96.6779 -1.60682 +VERTEX2 8650 -77.7893 -97.676 -1.59562 +VERTEX2 8651 -76.8045 -97.7272 -0.0569162 +VERTEX2 8652 -75.7327 -97.8198 -0.0634174 +VERTEX2 8653 -74.7302 -97.8301 -0.12158 +VERTEX2 8654 -73.7929 -97.9179 -0.0811746 +VERTEX2 8655 -72.9103 -97.9523 -0.115139 +VERTEX2 8656 -72.9421 -98.8911 -1.70731 +VERTEX2 8657 -73.1284 -99.9558 -1.69814 +VERTEX2 8658 -73.3007 -100.881 -1.68236 +VERTEX2 8659 -73.3773 -101.836 -1.67521 +VERTEX2 8660 -73.3785 -102.798 -1.68838 +VERTEX2 8661 -74.3753 -102.621 3.03094 +VERTEX2 8662 -75.3438 -102.469 3.04242 +VERTEX2 8663 -76.3183 -102.385 3.01734 +VERTEX2 8664 -77.2913 -102.205 3.04286 +VERTEX2 8665 -78.3196 -102.115 3.04618 +VERTEX2 8666 -78.4377 -103.149 -1.65767 +VERTEX2 8667 -78.5099 -104.127 -1.66551 +VERTEX2 8668 -78.5532 -105.182 -1.66659 +VERTEX2 8669 -78.6186 -106.118 -1.70072 +VERTEX2 8670 -78.7832 -107.054 -1.69073 +VERTEX2 8671 -77.9018 -107.199 -0.105898 +VERTEX2 8672 -76.9625 -107.31 -0.141014 +VERTEX2 8673 -75.9926 -107.422 -0.129859 +VERTEX2 8674 -75.0061 -107.587 -0.171686 +VERTEX2 8675 -74.0533 -107.787 -0.205336 +VERTEX2 8676 -73.8139 -106.738 1.34268 +VERTEX2 8677 -73.6015 -105.776 1.33913 +VERTEX2 8678 -73.343 -104.942 1.35656 +VERTEX2 8679 -73.0824 -103.965 1.36728 +VERTEX2 8680 -72.8903 -102.932 1.3582 +VERTEX2 8681 -73.9242 -102.754 2.90066 +VERTEX2 8682 -74.92 -102.552 2.92829 +VERTEX2 8683 -75.8949 -102.304 2.93781 +VERTEX2 8684 -76.8829 -102.097 2.96703 +VERTEX2 8685 -77.8581 -101.95 2.94935 +VERTEX2 8686 -77.6292 -100.951 1.39142 +VERTEX2 8687 -77.4957 -99.9774 1.40847 +VERTEX2 8688 -77.2584 -98.9711 1.42369 +VERTEX2 8689 -77.1327 -98.0102 1.40773 +VERTEX2 8690 -76.9965 -97.0477 1.39893 +VERTEX2 8691 -77.9366 -96.9478 2.98189 +VERTEX2 8692 -78.9389 -96.7382 2.96931 +VERTEX2 8693 -80.0072 -96.5496 2.99642 +VERTEX2 8694 -80.9935 -96.4742 3.0408 +VERTEX2 8695 -81.984 -96.3975 3.01535 +VERTEX2 8696 -82.1297 -97.3304 -1.71087 +VERTEX2 8697 -82.3008 -98.4481 -1.71224 +VERTEX2 8698 -82.413 -99.4565 -1.71008 +VERTEX2 8699 -82.6048 -100.493 -1.72917 +VERTEX2 8700 -82.7581 -101.517 -1.71661 +VERTEX2 8701 -81.7896 -101.556 -0.138905 +VERTEX2 8702 -80.7222 -101.63 -0.161398 +VERTEX2 8703 -79.8445 -101.803 -0.176031 +VERTEX2 8704 -78.9057 -101.982 -0.17919 +VERTEX2 8705 -77.9595 -102.246 -0.184549 +VERTEX2 8706 -78.1493 -103.208 -1.76798 +VERTEX2 8707 -78.4181 -104.183 -1.76156 +VERTEX2 8708 -78.6337 -105.167 -1.79228 +VERTEX2 8709 -78.8307 -106.1 -1.78598 +VERTEX2 8710 -79.0428 -107.116 -1.7791 +VERTEX2 8711 -78.1054 -107.387 -0.191322 +VERTEX2 8712 -77.1476 -107.575 -0.185706 +VERTEX2 8713 -76.1661 -107.721 -0.186128 +VERTEX2 8714 -75.1687 -107.908 -0.193072 +VERTEX2 8715 -74.2001 -108.127 -0.211777 +VERTEX2 8716 -74.0094 -107.048 1.36135 +VERTEX2 8717 -73.7451 -106.036 1.39004 +VERTEX2 8718 -73.5 -105.078 1.40377 +VERTEX2 8719 -73.2924 -104.007 1.4274 +VERTEX2 8720 -73.1504 -103.027 1.45157 +VERTEX2 8721 -74.2395 -102.893 2.9971 +VERTEX2 8722 -75.2806 -102.72 2.98426 +VERTEX2 8723 -76.1974 -102.535 2.97913 +VERTEX2 8724 -77.2491 -102.368 2.97339 +VERTEX2 8725 -78.2524 -102.184 2.96329 +VERTEX2 8726 -78.4799 -103.116 -1.73534 +VERTEX2 8727 -78.7219 -104.094 -1.74739 +VERTEX2 8728 -78.8488 -105.151 -1.7716 +VERTEX2 8729 -79.0002 -106.099 -1.78051 +VERTEX2 8730 -79.2694 -107.042 -1.78435 +VERTEX2 8731 -78.26 -107.254 -0.184554 +VERTEX2 8732 -77.2879 -107.384 -0.203132 +VERTEX2 8733 -76.292 -107.547 -0.225016 +VERTEX2 8734 -75.2514 -107.741 -0.252495 +VERTEX2 8735 -74.3761 -108 -0.284197 +VERTEX2 8736 -74.1162 -107.019 1.27841 +VERTEX2 8737 -73.8579 -106.14 1.31496 +VERTEX2 8738 -73.5963 -105.199 1.31236 +VERTEX2 8739 -73.3698 -104.31 1.32864 +VERTEX2 8740 -73.0741 -103.35 1.35769 +VERTEX2 8741 -72.121 -103.609 -0.214078 +VERTEX2 8742 -71.1878 -103.926 -0.189959 +VERTEX2 8743 -70.2871 -104.106 -0.166539 +VERTEX2 8744 -69.313 -104.248 -0.164858 +VERTEX2 8745 -68.3342 -104.362 -0.146386 +VERTEX2 8746 -68.2379 -103.354 1.43285 +VERTEX2 8747 -68.1299 -102.35 1.43681 +VERTEX2 8748 -67.9288 -101.334 1.44119 +VERTEX2 8749 -67.7301 -100.409 1.46882 +VERTEX2 8750 -67.6722 -99.3661 1.48425 +VERTEX2 8751 -66.7048 -99.507 -0.065134 +VERTEX2 8752 -65.6313 -99.6044 -0.0515136 +VERTEX2 8753 -64.5988 -99.6582 -0.053663 +VERTEX2 8754 -63.5491 -99.7423 -0.073788 +VERTEX2 8755 -62.5379 -99.8306 -0.0986922 +VERTEX2 8756 -62.3866 -98.8457 1.52075 +VERTEX2 8757 -62.3502 -97.8327 1.53217 +VERTEX2 8758 -62.3373 -96.8203 1.53693 +VERTEX2 8759 -62.292 -95.7624 1.518 +VERTEX2 8760 -62.2741 -94.7477 1.53387 +VERTEX2 8761 -61.2705 -94.7739 -0.0293375 +VERTEX2 8762 -60.3117 -94.7281 -0.0116905 +VERTEX2 8763 -59.2252 -94.7375 -0.0239569 +VERTEX2 8764 -58.2507 -94.7572 -0.0474456 +VERTEX2 8765 -57.1619 -94.783 -0.0536103 +VERTEX2 8766 -57.158 -93.8189 1.52384 +VERTEX2 8767 -57.0615 -92.8632 1.55214 +VERTEX2 8768 -57.0382 -91.8943 1.56428 +VERTEX2 8769 -57.0469 -90.8408 1.55397 +VERTEX2 8770 -57.0425 -89.8731 1.54889 +VERTEX2 8771 -58.1456 -89.7309 3.10454 +VERTEX2 8772 -59.1671 -89.6277 3.10454 +VERTEX2 8773 -60.1152 -89.6162 3.11351 +VERTEX2 8774 -61.0791 -89.5791 3.11665 +VERTEX2 8775 -62.0643 -89.4895 3.10933 +VERTEX2 8776 -62.0117 -90.3992 -1.63159 +VERTEX2 8777 -62.0803 -91.4775 -1.60977 +VERTEX2 8778 -62.1532 -92.4449 -1.60528 +VERTEX2 8779 -62.1516 -93.5121 -1.59293 +VERTEX2 8780 -62.2027 -94.4924 -1.60308 +VERTEX2 8781 -61.193 -94.4523 -0.0506986 +VERTEX2 8782 -60.2462 -94.4931 -0.0589714 +VERTEX2 8783 -59.2205 -94.5249 -0.030266 +VERTEX2 8784 -58.1811 -94.5868 -0.0176461 +VERTEX2 8785 -57.2552 -94.7072 -0.023265 +VERTEX2 8786 -57.2318 -93.6682 1.56695 +VERTEX2 8787 -57.2039 -92.7306 1.58093 +VERTEX2 8788 -57.197 -91.6381 1.55443 +VERTEX2 8789 -57.2312 -90.6138 1.5554 +VERTEX2 8790 -57.1712 -89.6613 1.56362 +VERTEX2 8791 -58.1833 -89.5845 -3.11001 +VERTEX2 8792 -59.2077 -89.5982 -3.08954 +VERTEX2 8793 -60.2395 -89.6886 -3.12228 +VERTEX2 8794 -61.2177 -89.7583 -3.12186 +VERTEX2 8795 -62.2017 -89.665 -3.13119 +VERTEX2 8796 -62.1474 -88.6801 1.56415 +VERTEX2 8797 -62.2019 -87.6934 1.56287 +VERTEX2 8798 -62.2716 -86.7322 1.57361 +VERTEX2 8799 -62.261 -85.7292 1.57244 +VERTEX2 8800 -62.3308 -84.7823 1.5699 +VERTEX2 8801 -63.3946 -84.797 -3.12468 +VERTEX2 8802 -64.4514 -84.8854 -3.11549 +VERTEX2 8803 -65.4572 -84.9417 -3.09131 +VERTEX2 8804 -66.4773 -85.0393 -3.11474 +VERTEX2 8805 -67.4499 -85.0761 -3.1201 +VERTEX2 8806 -67.4946 -86.1434 -1.5441 +VERTEX2 8807 -67.4095 -87.1267 -1.54681 +VERTEX2 8808 -67.3384 -88.0598 -1.53305 +VERTEX2 8809 -67.3248 -89.0221 -1.51726 +VERTEX2 8810 -67.2608 -89.9704 -1.51579 +VERTEX2 8811 -66.2817 -89.9139 0.0803264 +VERTEX2 8812 -65.2502 -89.9094 0.0608903 +VERTEX2 8813 -64.1727 -89.9426 0.0582652 +VERTEX2 8814 -63.1801 -89.8531 0.0813548 +VERTEX2 8815 -62.174 -89.805 0.086275 +VERTEX2 8816 -62.3193 -88.7999 1.67926 +VERTEX2 8817 -62.3815 -87.93 1.68251 +VERTEX2 8818 -62.6093 -86.9422 1.62421 +VERTEX2 8819 -62.6075 -85.9362 1.62589 +VERTEX2 8820 -62.628 -84.8973 1.58155 +VERTEX2 8821 -61.7091 -84.8897 0.0233991 +VERTEX2 8822 -60.6636 -84.8489 -0.00203481 +VERTEX2 8823 -59.5967 -84.949 0.00330084 +VERTEX2 8824 -58.6326 -85.037 -0.0279889 +VERTEX2 8825 -57.6491 -85.1214 -0.0254917 +VERTEX2 8826 -57.6831 -84.2097 1.49314 +VERTEX2 8827 -57.589 -83.181 1.47566 +VERTEX2 8828 -57.5503 -82.2336 1.43628 +VERTEX2 8829 -57.355 -81.1675 1.43156 +VERTEX2 8830 -57.1832 -80.1317 1.42191 +VERTEX2 8831 -58.1723 -80.0132 2.99408 +VERTEX2 8832 -59.206 -79.8026 2.97076 +VERTEX2 8833 -60.2039 -79.5778 2.98114 +VERTEX2 8834 -61.1945 -79.4135 2.96609 +VERTEX2 8835 -62.1294 -79.2553 2.94646 +VERTEX2 8836 -62.3371 -80.286 -1.77099 +VERTEX2 8837 -62.6074 -81.2868 -1.79591 +VERTEX2 8838 -62.8853 -82.3701 -1.79909 +VERTEX2 8839 -63.0728 -83.3496 -1.8234 +VERTEX2 8840 -63.3172 -84.374 -1.81721 +VERTEX2 8841 -62.3474 -84.6462 -0.25101 +VERTEX2 8842 -61.2996 -84.7802 -0.219171 +VERTEX2 8843 -60.3166 -84.9765 -0.249683 +VERTEX2 8844 -59.3714 -85.2029 -0.283549 +VERTEX2 8845 -58.3707 -85.4936 -0.318883 +VERTEX2 8846 -58.6557 -86.4555 -1.88407 +VERTEX2 8847 -58.9706 -87.3999 -1.83042 +VERTEX2 8848 -59.2549 -88.4097 -1.81653 +VERTEX2 8849 -59.4484 -89.4921 -1.82993 +VERTEX2 8850 -59.7057 -90.4499 -1.84423 +VERTEX2 8851 -58.7074 -90.7723 -0.270867 +VERTEX2 8852 -57.705 -91.1084 -0.267467 +VERTEX2 8853 -56.7804 -91.4652 -0.283876 +VERTEX2 8854 -55.8533 -91.7902 -0.291672 +VERTEX2 8855 -54.8781 -92.1549 -0.333326 +VERTEX2 8856 -54.6081 -91.2209 1.25813 +VERTEX2 8857 -54.2224 -90.3187 1.23843 +VERTEX2 8858 -53.9039 -89.4258 1.24091 +VERTEX2 8859 -53.4871 -88.5487 1.21848 +VERTEX2 8860 -53.1474 -87.6139 1.16537 +VERTEX2 8861 -52.2266 -87.9826 -0.404522 +VERTEX2 8862 -51.3772 -88.4511 -0.400477 +VERTEX2 8863 -50.3858 -88.8102 -0.398715 +VERTEX2 8864 -49.4239 -89.1102 -0.401278 +VERTEX2 8865 -48.5444 -89.464 -0.398398 +VERTEX2 8866 -48.1688 -88.6445 1.16732 +VERTEX2 8867 -47.8464 -87.747 1.18686 +VERTEX2 8868 -47.3957 -86.8141 1.18419 +VERTEX2 8869 -47.0231 -85.9116 1.16804 +VERTEX2 8870 -46.648 -85.0497 1.22878 +VERTEX2 8871 -47.5164 -84.6943 2.77775 +VERTEX2 8872 -48.4708 -84.41 2.76343 +VERTEX2 8873 -49.3924 -84.1632 2.73932 +VERTEX2 8874 -50.3574 -83.7057 2.7274 +VERTEX2 8875 -51.374 -83.2784 2.74421 +VERTEX2 8876 -50.9555 -82.4077 1.19342 +VERTEX2 8877 -50.6262 -81.4225 1.18946 +VERTEX2 8878 -50.2633 -80.4386 1.18764 +VERTEX2 8879 -49.9498 -79.5397 1.20836 +VERTEX2 8880 -49.621 -78.6485 1.20851 +VERTEX2 8881 -50.5676 -78.2695 2.79279 +VERTEX2 8882 -51.5294 -77.8713 2.78335 +VERTEX2 8883 -52.39 -77.5728 2.79849 +VERTEX2 8884 -53.2811 -77.3468 2.80203 +VERTEX2 8885 -54.2689 -76.9219 2.75961 +VERTEX2 8886 -53.8697 -75.9801 1.20034 +VERTEX2 8887 -53.474 -75.0992 1.20961 +VERTEX2 8888 -53.1056 -74.1196 1.23567 +VERTEX2 8889 -52.6829 -73.2404 1.22417 +VERTEX2 8890 -52.2791 -72.3012 1.23002 +VERTEX2 8891 -53.2123 -71.9943 2.82861 +VERTEX2 8892 -54.2186 -71.6824 2.79919 +VERTEX2 8893 -55.2024 -71.3759 2.79936 +VERTEX2 8894 -56.197 -71.0421 2.78887 +VERTEX2 8895 -57.1806 -70.6997 2.77926 +VERTEX2 8896 -57.527 -71.6624 -1.92533 +VERTEX2 8897 -57.9118 -72.5993 -1.95752 +VERTEX2 8898 -58.3048 -73.613 -1.95379 +VERTEX2 8899 -58.6169 -74.5409 -1.99091 +VERTEX2 8900 -59.0938 -75.4751 -1.9647 +VERTEX2 8901 -58.1485 -75.8488 -0.400769 +VERTEX2 8902 -57.2636 -76.2223 -0.416185 +VERTEX2 8903 -56.3337 -76.654 -0.390312 +VERTEX2 8904 -55.402 -77.0065 -0.381874 +VERTEX2 8905 -54.4908 -77.4682 -0.400137 +VERTEX2 8906 -54.1407 -76.5608 1.15069 +VERTEX2 8907 -53.7254 -75.6869 1.14733 +VERTEX2 8908 -53.3059 -74.6695 1.15691 +VERTEX2 8909 -52.9207 -73.8234 1.17251 +VERTEX2 8910 -52.4772 -72.8699 1.17473 +VERTEX2 8911 -53.3609 -72.5205 2.75494 +VERTEX2 8912 -54.2765 -72.1506 2.77776 +VERTEX2 8913 -55.2348 -71.8151 2.81387 +VERTEX2 8914 -56.2137 -71.4802 2.78484 +VERTEX2 8915 -57.1257 -71.0949 2.75274 +VERTEX2 8916 -57.5454 -72.054 -1.95584 +VERTEX2 8917 -57.951 -72.8848 -1.9821 +VERTEX2 8918 -58.369 -73.8513 -1.98666 +VERTEX2 8919 -58.8376 -74.7813 -1.98568 +VERTEX2 8920 -59.2186 -75.6431 -1.97617 +VERTEX2 8921 -58.2992 -76.0403 -0.405082 +VERTEX2 8922 -57.3954 -76.5088 -0.400181 +VERTEX2 8923 -56.4389 -76.8903 -0.417625 +VERTEX2 8924 -55.4253 -77.3637 -0.409449 +VERTEX2 8925 -54.484 -77.786 -0.453618 +VERTEX2 8926 -54.9493 -78.6624 -2.05524 +VERTEX2 8927 -55.4044 -79.5473 -2.10261 +VERTEX2 8928 -55.9081 -80.4608 -2.10011 +VERTEX2 8929 -56.4642 -81.3214 -2.06385 +VERTEX2 8930 -56.9234 -82.0652 -2.06554 +VERTEX2 8931 -56.0722 -82.5719 -0.491079 +VERTEX2 8932 -55.2566 -83.1154 -0.432428 +VERTEX2 8933 -54.3214 -83.678 -0.423449 +VERTEX2 8934 -53.317 -84.1388 -0.425717 +VERTEX2 8935 -52.4292 -84.6158 -0.408381 +VERTEX2 8936 -52.0059 -83.7473 1.17007 +VERTEX2 8937 -51.6147 -82.8257 1.16866 +VERTEX2 8938 -51.2295 -81.8871 1.18521 +VERTEX2 8939 -50.7679 -81.0432 1.18748 +VERTEX2 8940 -50.4774 -80.1684 1.1498 +VERTEX2 8941 -49.6322 -80.5498 -0.40961 +VERTEX2 8942 -48.7555 -80.9546 -0.407508 +VERTEX2 8943 -47.7948 -81.366 -0.414014 +VERTEX2 8944 -46.9044 -81.7804 -0.413663 +VERTEX2 8945 -46.1497 -82.2705 -0.406507 +VERTEX2 8946 -46.5311 -83.1681 -1.99723 +VERTEX2 8947 -46.9911 -84.1 -1.98852 +VERTEX2 8948 -47.4168 -85.0376 -1.99114 +VERTEX2 8949 -47.7732 -85.9265 -1.97927 +VERTEX2 8950 -48.1183 -86.9106 -2.01308 +VERTEX2 8951 -47.18 -87.3552 -0.419856 +VERTEX2 8952 -46.2959 -87.6823 -0.422057 +VERTEX2 8953 -45.4111 -88.1008 -0.428144 +VERTEX2 8954 -44.5035 -88.5176 -0.426252 +VERTEX2 8955 -43.6208 -88.9645 -0.409817 +VERTEX2 8956 -43.2137 -88.1489 1.15856 +VERTEX2 8957 -42.8153 -87.2155 1.1689 +VERTEX2 8958 -42.4622 -86.2344 1.17818 +VERTEX2 8959 -42.0456 -85.2527 1.17207 +VERTEX2 8960 -41.715 -84.3732 1.15236 +VERTEX2 8961 -42.622 -83.9627 2.71895 +VERTEX2 8962 -43.5114 -83.5435 2.72398 +VERTEX2 8963 -44.4068 -83.1407 2.7395 +VERTEX2 8964 -45.3157 -82.8693 2.74101 +VERTEX2 8965 -46.2166 -82.4624 2.76052 +VERTEX2 8966 -45.8631 -81.5282 1.22159 +VERTEX2 8967 -45.5393 -80.6098 1.19527 +VERTEX2 8968 -45.1904 -79.6777 1.20295 +VERTEX2 8969 -44.7563 -78.7843 1.21786 +VERTEX2 8970 -44.3028 -77.8366 1.26734 +VERTEX2 8971 -45.1789 -77.6542 2.8304 +VERTEX2 8972 -46.1559 -77.3067 2.80366 +VERTEX2 8973 -47.1036 -76.9997 2.8164 +VERTEX2 8974 -48.0987 -76.6058 2.81617 +VERTEX2 8975 -49.0633 -76.33 2.80784 +VERTEX2 8976 -48.8167 -75.4011 1.24127 +VERTEX2 8977 -48.5524 -74.5001 1.21705 +VERTEX2 8978 -48.3006 -73.5285 1.23245 +VERTEX2 8979 -47.9722 -72.6307 1.2303 +VERTEX2 8980 -47.6051 -71.6747 1.26032 +VERTEX2 8981 -48.5372 -71.4408 2.85443 +VERTEX2 8982 -49.5236 -71.1439 2.86969 +VERTEX2 8983 -50.494 -70.8964 2.88809 +VERTEX2 8984 -51.4096 -70.6265 2.88115 +VERTEX2 8985 -52.3997 -70.3867 2.86426 +VERTEX2 8986 -52.5967 -71.385 -1.86454 +VERTEX2 8987 -53.0434 -72.3279 -1.85099 +VERTEX2 8988 -53.2301 -73.3285 -1.86947 +VERTEX2 8989 -53.5487 -74.3036 -1.88626 +VERTEX2 8990 -53.7782 -75.2708 -1.90118 +VERTEX2 8991 -54.7031 -74.9019 2.78731 +VERTEX2 8992 -55.6642 -74.6034 2.80056 +VERTEX2 8993 -56.5694 -74.2348 2.77403 +VERTEX2 8994 -57.4879 -73.913 2.74799 +VERTEX2 8995 -58.3994 -73.6353 2.77543 +VERTEX2 8996 -58.0063 -72.7395 1.17884 +VERTEX2 8997 -57.5867 -71.85 1.1904 +VERTEX2 8998 -57.2225 -70.9474 1.19128 +VERTEX2 8999 -56.9041 -70.0017 1.18748 +VERTEX2 9000 -56.5398 -69.081 1.22388 +VERTEX2 9001 -57.4509 -68.7059 2.76651 +VERTEX2 9002 -58.3842 -68.4142 2.72557 +VERTEX2 9003 -59.2889 -67.9718 2.73508 +VERTEX2 9004 -60.1935 -67.5505 2.72417 +VERTEX2 9005 -61.1276 -67.1549 2.7205 +VERTEX2 9006 -61.4491 -68.0658 -2.00107 +VERTEX2 9007 -61.8374 -69.0442 -2.01965 +VERTEX2 9008 -62.2641 -69.9078 -2.00079 +VERTEX2 9009 -62.7547 -70.8121 -1.9968 +VERTEX2 9010 -63.1016 -71.8179 -2.00714 +VERTEX2 9011 -62.1485 -72.2873 -0.433925 +VERTEX2 9012 -61.2582 -72.7728 -0.44368 +VERTEX2 9013 -60.2955 -73.1642 -0.445253 +VERTEX2 9014 -59.4564 -73.6238 -0.459347 +VERTEX2 9015 -58.6147 -74.0003 -0.465377 +VERTEX2 9016 -59.1375 -74.7576 -2.05763 +VERTEX2 9017 -59.6242 -75.6725 -2.04685 +VERTEX2 9018 -60.0257 -76.6099 -2.00775 +VERTEX2 9019 -60.4514 -77.5457 -1.99969 +VERTEX2 9020 -60.9557 -78.4081 -2.02063 +VERTEX2 9021 -60.0262 -78.7657 -0.4374 +VERTEX2 9022 -59.1239 -79.178 -0.46377 +VERTEX2 9023 -58.2229 -79.5893 -0.479523 +VERTEX2 9024 -57.2969 -79.9963 -0.488531 +VERTEX2 9025 -56.38 -80.4484 -0.516283 +VERTEX2 9026 -55.8717 -79.5424 1.08835 +VERTEX2 9027 -55.4622 -78.6456 1.10708 +VERTEX2 9028 -54.8751 -77.7605 1.14622 +VERTEX2 9029 -54.5547 -76.8861 1.12961 +VERTEX2 9030 -54.1062 -75.9298 1.11259 +VERTEX2 9031 -55.0161 -75.4947 2.67937 +VERTEX2 9032 -55.9321 -74.9568 2.66537 +VERTEX2 9033 -56.7637 -74.5775 2.61889 +VERTEX2 9034 -57.597 -74.0448 2.64221 +VERTEX2 9035 -58.4461 -73.5927 2.61107 +VERTEX2 9036 -59.0334 -74.4838 -2.1141 +VERTEX2 9037 -59.6473 -75.3548 -2.10178 +VERTEX2 9038 -60.0793 -76.1813 -2.11553 +VERTEX2 9039 -60.5903 -77.0476 -2.10548 +VERTEX2 9040 -61.0973 -77.8416 -2.10192 +VERTEX2 9041 -60.2554 -78.3217 -0.509912 +VERTEX2 9042 -59.4282 -78.7924 -0.527282 +VERTEX2 9043 -58.5127 -79.3102 -0.499706 +VERTEX2 9044 -57.6383 -79.8248 -0.507831 +VERTEX2 9045 -56.7578 -80.3617 -0.466997 +VERTEX2 9046 -56.291 -79.4275 1.10733 +VERTEX2 9047 -55.8311 -78.489 1.1216 +VERTEX2 9048 -55.3869 -77.5296 1.11974 +VERTEX2 9049 -54.9298 -76.5501 1.12583 +VERTEX2 9050 -54.4906 -75.6328 1.13813 +VERTEX2 9051 -55.4255 -75.1655 2.71433 +VERTEX2 9052 -56.2911 -74.7732 2.6855 +VERTEX2 9053 -57.1917 -74.3246 2.68415 +VERTEX2 9054 -58.0324 -73.7589 2.70914 +VERTEX2 9055 -58.8881 -73.3239 2.68567 +VERTEX2 9056 -59.372 -74.1821 -2.01232 +VERTEX2 9057 -59.7842 -75.0966 -2.04682 +VERTEX2 9058 -60.2784 -75.9919 -2.03513 +VERTEX2 9059 -60.6424 -76.887 -2.05605 +VERTEX2 9060 -61.0554 -77.7089 -2.09932 +VERTEX2 9061 -61.9459 -77.2952 2.61539 +VERTEX2 9062 -62.8169 -76.7837 2.58186 +VERTEX2 9063 -63.7257 -76.2532 2.59711 +VERTEX2 9064 -64.6355 -75.7158 2.58943 +VERTEX2 9065 -65.453 -75.1682 2.57163 +VERTEX2 9066 -64.9766 -74.2704 1.01256 +VERTEX2 9067 -64.4597 -73.3052 1.02821 +VERTEX2 9068 -63.938 -72.4211 1.03251 +VERTEX2 9069 -63.4761 -71.5796 1.02213 +VERTEX2 9070 -62.8883 -70.8236 0.999017 +VERTEX2 9071 -63.7223 -70.3094 2.56228 +VERTEX2 9072 -64.4694 -69.742 2.56602 +VERTEX2 9073 -65.2448 -69.2512 2.55972 +VERTEX2 9074 -66.1155 -68.6494 2.57328 +VERTEX2 9075 -67.02 -68.097 2.58339 +VERTEX2 9076 -66.4654 -67.211 0.993777 +VERTEX2 9077 -65.8168 -66.2368 1.011 +VERTEX2 9078 -65.2189 -65.4246 1.01045 +VERTEX2 9079 -64.755 -64.5984 1.00767 +VERTEX2 9080 -64.2143 -63.7345 1.0007 +VERTEX2 9081 -65.1012 -63.1936 2.54589 +VERTEX2 9082 -65.891 -62.5405 2.56394 +VERTEX2 9083 -66.761 -62.0022 2.56381 +VERTEX2 9084 -67.6244 -61.3979 2.58521 +VERTEX2 9085 -68.5073 -60.822 2.58845 +VERTEX2 9086 -69.1272 -61.6975 -2.1208 +VERTEX2 9087 -69.5462 -62.5441 -2.17671 +VERTEX2 9088 -70.202 -63.3096 -2.1768 +VERTEX2 9089 -70.7506 -64.0404 -2.21557 +VERTEX2 9090 -71.3495 -64.8116 -2.18732 +VERTEX2 9091 -70.4973 -65.3936 -0.642047 +VERTEX2 9092 -69.6484 -66.071 -0.644653 +VERTEX2 9093 -68.8148 -66.6646 -0.606731 +VERTEX2 9094 -68.0137 -67.2981 -0.598451 +VERTEX2 9095 -67.1201 -67.864 -0.596624 +VERTEX2 9096 -66.6024 -67.0555 0.968684 +VERTEX2 9097 -66.0547 -66.2543 0.941428 +VERTEX2 9098 -65.5265 -65.4768 0.92583 +VERTEX2 9099 -64.9295 -64.6325 0.90761 +VERTEX2 9100 -64.3168 -63.8485 0.924221 +VERTEX2 9101 -65.1825 -63.2656 2.46436 +VERTEX2 9102 -65.9076 -62.645 2.49096 +VERTEX2 9103 -66.6038 -62.142 2.4721 +VERTEX2 9104 -67.4319 -61.4795 2.45482 +VERTEX2 9105 -68.2127 -60.7722 2.45635 +VERTEX2 9106 -67.5396 -59.9742 0.894254 +VERTEX2 9107 -66.8944 -59.1794 0.906661 +VERTEX2 9108 -66.3061 -58.3809 0.892937 +VERTEX2 9109 -65.7195 -57.6941 0.920669 +VERTEX2 9110 -65.0465 -56.8575 0.921549 +VERTEX2 9111 -65.7762 -56.408 2.50178 +VERTEX2 9112 -66.5313 -55.8101 2.51438 +VERTEX2 9113 -67.3428 -55.1487 2.53448 +VERTEX2 9114 -68.1685 -54.6024 2.54749 +VERTEX2 9115 -69.0691 -53.985 2.55415 +VERTEX2 9116 -68.4379 -53.2893 0.966097 +VERTEX2 9117 -67.9178 -52.4312 0.987591 +VERTEX2 9118 -67.3929 -51.6644 0.97655 +VERTEX2 9119 -66.7279 -50.7917 0.989801 +VERTEX2 9120 -66.1944 -49.9321 0.966598 +VERTEX2 9121 -66.9916 -49.2867 2.51154 +VERTEX2 9122 -67.8299 -48.6367 2.51446 +VERTEX2 9123 -68.588 -48.0444 2.50183 +VERTEX2 9124 -69.3253 -47.4255 2.48541 +VERTEX2 9125 -70.0828 -46.8536 2.48175 +VERTEX2 9126 -70.7149 -47.6629 -2.24521 +VERTEX2 9127 -71.281 -48.4417 -2.27578 +VERTEX2 9128 -71.8587 -49.1928 -2.24009 +VERTEX2 9129 -72.5739 -50.0741 -2.26259 +VERTEX2 9130 -73.2541 -50.8239 -2.2443 +VERTEX2 9131 -74.0689 -50.1968 2.46447 +VERTEX2 9132 -74.9393 -49.6108 2.45743 +VERTEX2 9133 -75.6985 -48.9326 2.47118 +VERTEX2 9134 -76.4 -48.3835 2.45615 +VERTEX2 9135 -77.2963 -47.6916 2.46587 +VERTEX2 9136 -77.8937 -48.4557 -2.2531 +VERTEX2 9137 -78.5312 -49.2348 -2.20968 +VERTEX2 9138 -79.1356 -50.0738 -2.21398 +VERTEX2 9139 -79.7088 -50.8007 -2.18736 +VERTEX2 9140 -80.2522 -51.5674 -2.16815 +VERTEX2 9141 -81.0035 -50.9624 2.52511 +VERTEX2 9142 -81.7831 -50.4105 2.54089 +VERTEX2 9143 -82.6081 -49.8698 2.57213 +VERTEX2 9144 -83.4984 -49.3777 2.59355 +VERTEX2 9145 -84.3002 -48.8697 2.60811 +VERTEX2 9146 -84.8273 -49.7335 -2.11085 +VERTEX2 9147 -85.3178 -50.5627 -2.10947 +VERTEX2 9148 -85.7956 -51.4578 -2.13946 +VERTEX2 9149 -86.2815 -52.2846 -2.1192 +VERTEX2 9150 -86.8741 -53.0883 -2.1167 +VERTEX2 9151 -85.9732 -53.6074 -0.538522 +VERTEX2 9152 -85.0734 -54.1168 -0.497932 +VERTEX2 9153 -84.1564 -54.5057 -0.535244 +VERTEX2 9154 -83.2034 -54.9951 -0.519251 +VERTEX2 9155 -82.3487 -55.5176 -0.517094 +VERTEX2 9156 -82.8138 -56.3009 -2.1183 +VERTEX2 9157 -83.3608 -57.1852 -2.11422 +VERTEX2 9158 -83.918 -57.9799 -2.11025 +VERTEX2 9159 -84.4421 -58.8589 -2.1196 +VERTEX2 9160 -85.0334 -59.6714 -2.12631 +VERTEX2 9161 -84.1785 -60.1929 -0.542101 +VERTEX2 9162 -83.2813 -60.6713 -0.524484 +VERTEX2 9163 -82.4528 -61.1659 -0.535525 +VERTEX2 9164 -81.5871 -61.6722 -0.541288 +VERTEX2 9165 -80.7108 -62.2921 -0.536353 +VERTEX2 9166 -80.2468 -61.399 1.04897 +VERTEX2 9167 -79.7449 -60.5086 1.05727 +VERTEX2 9168 -79.2822 -59.612 1.09034 +VERTEX2 9169 -78.8484 -58.7485 1.09347 +VERTEX2 9170 -78.4556 -57.8399 1.09718 +VERTEX2 9171 -77.6049 -58.3428 -0.504538 +VERTEX2 9172 -76.7081 -58.8096 -0.524736 +VERTEX2 9173 -75.8913 -59.3728 -0.548498 +VERTEX2 9174 -74.9921 -59.8508 -0.52513 +VERTEX2 9175 -74.1025 -60.2924 -0.509048 +VERTEX2 9176 -73.6258 -59.3401 1.09698 +VERTEX2 9177 -73.1869 -58.3844 1.08989 +VERTEX2 9178 -72.7926 -57.517 1.09961 +VERTEX2 9179 -72.2001 -56.613 1.10551 +VERTEX2 9180 -71.7301 -55.7102 1.12646 +VERTEX2 9181 -72.5712 -55.2473 2.67373 +VERTEX2 9182 -73.4448 -54.8112 2.66629 +VERTEX2 9183 -74.3738 -54.2992 2.69422 +VERTEX2 9184 -75.2778 -53.8311 2.70742 +VERTEX2 9185 -76.1904 -53.3548 2.71214 +VERTEX2 9186 -76.571 -54.3057 -1.97618 +VERTEX2 9187 -77.0239 -55.141 -1.98198 +VERTEX2 9188 -77.4641 -56.0753 -2.00792 +VERTEX2 9189 -77.8492 -56.9801 -1.97937 +VERTEX2 9190 -78.2909 -57.925 -1.97751 +VERTEX2 9191 -77.4493 -58.3189 -0.363523 +VERTEX2 9192 -76.5192 -58.6351 -0.362147 +VERTEX2 9193 -75.6665 -58.9396 -0.367759 +VERTEX2 9194 -74.7457 -59.2716 -0.359586 +VERTEX2 9195 -73.7814 -59.667 -0.360969 +VERTEX2 9196 -74.1215 -60.5858 -1.93576 +VERTEX2 9197 -74.521 -61.5617 -1.9409 +VERTEX2 9198 -74.7902 -62.46 -1.93491 +VERTEX2 9199 -75.0605 -63.3301 -1.96247 +VERTEX2 9200 -75.4163 -64.2511 -1.98073 +VERTEX2 9201 -74.516 -64.6523 -0.406283 +VERTEX2 9202 -73.5754 -65.0908 -0.395649 +VERTEX2 9203 -72.6351 -65.5173 -0.407254 +VERTEX2 9204 -71.7109 -65.944 -0.38779 +VERTEX2 9205 -70.8245 -66.3097 -0.429072 +VERTEX2 9206 -71.2125 -67.2225 -1.99507 +VERTEX2 9207 -71.6191 -68.1411 -1.9645 +VERTEX2 9208 -72.0762 -69.0288 -1.96146 +VERTEX2 9209 -72.3986 -70.0296 -1.93574 +VERTEX2 9210 -72.8536 -70.8721 -1.94182 +VERTEX2 9211 -71.9383 -71.2015 -0.362501 +VERTEX2 9212 -70.943 -71.5474 -0.346292 +VERTEX2 9213 -69.9068 -71.8941 -0.357453 +VERTEX2 9214 -68.9686 -72.2794 -0.35891 +VERTEX2 9215 -67.965 -72.6966 -0.362294 +VERTEX2 9216 -67.6393 -71.8209 1.18846 +VERTEX2 9217 -67.268 -70.9763 1.15275 +VERTEX2 9218 -66.8364 -70.0245 1.14789 +VERTEX2 9219 -66.4414 -69.1259 1.13482 +VERTEX2 9220 -65.9924 -68.2287 1.15706 +VERTEX2 9221 -66.8617 -67.8682 2.66685 +VERTEX2 9222 -67.6856 -67.4741 2.66977 +VERTEX2 9223 -68.4631 -67.0415 2.68485 +VERTEX2 9224 -69.32 -66.6261 2.69047 +VERTEX2 9225 -70.2793 -66.0567 2.69399 +VERTEX2 9226 -69.849 -65.2083 1.11392 +VERTEX2 9227 -69.4461 -64.2516 1.09115 +VERTEX2 9228 -68.973 -63.3756 1.11093 +VERTEX2 9229 -68.5338 -62.392 1.12561 +VERTEX2 9230 -68.2017 -61.4682 1.13578 +VERTEX2 9231 -69.1681 -61.082 2.68999 +VERTEX2 9232 -70.0359 -60.6115 2.69291 +VERTEX2 9233 -70.9962 -60.2166 2.66173 +VERTEX2 9234 -71.9146 -59.7895 2.65114 +VERTEX2 9235 -72.8925 -59.3757 2.66465 +VERTEX2 9236 -72.511 -58.545 1.08304 +VERTEX2 9237 -72.0338 -57.5645 1.05934 +VERTEX2 9238 -71.5694 -56.721 1.08738 +VERTEX2 9239 -71.0357 -55.747 1.06613 +VERTEX2 9240 -70.5217 -54.857 1.0687 +VERTEX2 9241 -71.4091 -54.2333 2.66047 +VERTEX2 9242 -72.299 -53.8499 2.62361 +VERTEX2 9243 -73.1535 -53.3401 2.66199 +VERTEX2 9244 -74.0398 -52.864 2.68368 +VERTEX2 9245 -74.9117 -52.3822 2.67519 +VERTEX2 9246 -75.4049 -53.2981 -2.03606 +VERTEX2 9247 -75.8774 -54.1608 -2.03631 +VERTEX2 9248 -76.2624 -55.0962 -2.05382 +VERTEX2 9249 -76.8363 -55.9514 -2.04624 +VERTEX2 9250 -77.3518 -56.8553 -2.0152 +VERTEX2 9251 -76.5011 -57.2538 -0.424411 +VERTEX2 9252 -75.5927 -57.6277 -0.421061 +VERTEX2 9253 -74.6741 -58.0473 -0.410814 +VERTEX2 9254 -73.7949 -58.369 -0.434598 +VERTEX2 9255 -73.0528 -58.7177 -0.442616 +VERTEX2 9256 -72.6609 -57.7202 1.09329 +VERTEX2 9257 -72.2846 -56.7639 1.09469 +VERTEX2 9258 -71.8636 -55.9127 1.10667 +VERTEX2 9259 -71.4839 -55.0919 1.09955 +VERTEX2 9260 -70.8974 -54.1908 1.11467 +VERTEX2 9261 -70.004 -54.6779 -0.451455 +VERTEX2 9262 -69.0476 -55.127 -0.45997 +VERTEX2 9263 -68.1126 -55.6056 -0.511682 +VERTEX2 9264 -67.1829 -56.2476 -0.533485 +VERTEX2 9265 -66.2818 -56.7362 -0.528075 +VERTEX2 9266 -66.8163 -57.5882 -2.10506 +VERTEX2 9267 -67.3291 -58.4587 -2.12503 +VERTEX2 9268 -67.7224 -59.3404 -2.11921 +VERTEX2 9269 -68.2417 -60.1749 -2.10904 +VERTEX2 9270 -68.7365 -60.9638 -2.12952 +VERTEX2 9271 -67.9284 -61.4073 -0.581209 +VERTEX2 9272 -67.0278 -61.9291 -0.559851 +VERTEX2 9273 -66.2673 -62.482 -0.573062 +VERTEX2 9274 -65.476 -62.96 -0.570113 +VERTEX2 9275 -64.7166 -63.4721 -0.581585 +VERTEX2 9276 -64.1586 -62.6602 1.00027 +VERTEX2 9277 -63.5118 -61.7992 1.0005 +VERTEX2 9278 -62.9805 -60.866 1.00426 +VERTEX2 9279 -62.37 -59.9655 1.02957 +VERTEX2 9280 -61.8759 -59.1362 1.02967 +VERTEX2 9281 -62.6544 -58.6126 2.60929 +VERTEX2 9282 -63.4543 -58.0871 2.59994 +VERTEX2 9283 -64.3097 -57.5513 2.55929 +VERTEX2 9284 -65.2299 -57.0908 2.57014 +VERTEX2 9285 -66.0786 -56.4855 2.59455 +VERTEX2 9286 -66.5854 -57.3429 -2.08435 +VERTEX2 9287 -67.1117 -58.2658 -2.09592 +VERTEX2 9288 -67.6537 -59.1026 -2.09152 +VERTEX2 9289 -68.1974 -59.9909 -2.0977 +VERTEX2 9290 -68.7093 -60.8331 -2.1313 +VERTEX2 9291 -67.8945 -61.2883 -0.561224 +VERTEX2 9292 -67.0151 -61.8351 -0.5665 +VERTEX2 9293 -66.1604 -62.4491 -0.552672 +VERTEX2 9294 -65.3597 -63.0001 -0.579472 +VERTEX2 9295 -64.4568 -63.5123 -0.556801 +VERTEX2 9296 -63.9548 -62.6304 1.01635 +VERTEX2 9297 -63.4878 -61.8583 1.00742 +VERTEX2 9298 -63.0091 -61.0131 0.998204 +VERTEX2 9299 -62.4663 -60.0798 0.994634 +VERTEX2 9300 -62.0455 -59.3102 0.970151 +VERTEX2 9301 -62.8624 -58.7879 2.52139 +VERTEX2 9302 -63.6241 -58.2017 2.54286 +VERTEX2 9303 -64.4926 -57.6269 2.54534 +VERTEX2 9304 -65.3457 -57.0835 2.54838 +VERTEX2 9305 -66.1321 -56.5436 2.55622 +VERTEX2 9306 -66.6539 -57.3334 -2.13504 +VERTEX2 9307 -67.216 -58.1788 -2.14746 +VERTEX2 9308 -67.656 -58.9849 -2.11657 +VERTEX2 9309 -68.2399 -59.7883 -2.12426 +VERTEX2 9310 -68.7651 -60.7072 -2.13176 +VERTEX2 9311 -68.0034 -61.252 -0.53409 +VERTEX2 9312 -67.1217 -61.8202 -0.51899 +VERTEX2 9313 -66.2473 -62.404 -0.511047 +VERTEX2 9314 -65.4419 -62.8928 -0.524173 +VERTEX2 9315 -64.6409 -63.4312 -0.517432 +VERTEX2 9316 -64.2143 -62.5735 1.05901 +VERTEX2 9317 -63.6387 -61.7246 1.08027 +VERTEX2 9318 -63.1321 -60.901 1.09138 +VERTEX2 9319 -62.6929 -60.043 1.10362 +VERTEX2 9320 -62.2254 -59.1584 1.13127 +VERTEX2 9321 -63.1942 -58.6996 2.70184 +VERTEX2 9322 -64.1012 -58.2678 2.69296 +VERTEX2 9323 -65.0033 -57.7947 2.7018 +VERTEX2 9324 -65.949 -57.3377 2.69202 +VERTEX2 9325 -66.8652 -56.8756 2.67226 +VERTEX2 9326 -66.4076 -55.9926 1.08716 +VERTEX2 9327 -65.9505 -55.0704 1.07364 +VERTEX2 9328 -65.4731 -54.055 1.08177 +VERTEX2 9329 -64.9703 -53.0968 1.08391 +VERTEX2 9330 -64.3934 -52.2737 1.0706 +VERTEX2 9331 -63.4744 -52.6778 -0.481347 +VERTEX2 9332 -62.4968 -53.2168 -0.446259 +VERTEX2 9333 -61.6236 -53.6987 -0.415312 +VERTEX2 9334 -60.6446 -54.1373 -0.403672 +VERTEX2 9335 -59.7645 -54.5727 -0.415358 +VERTEX2 9336 -59.3141 -53.6132 1.13205 +VERTEX2 9337 -58.7894 -52.7277 1.13029 +VERTEX2 9338 -58.4131 -51.8333 1.17544 +VERTEX2 9339 -57.9985 -50.9483 1.16272 +VERTEX2 9340 -57.5307 -50.0926 1.14642 +VERTEX2 9341 -56.6771 -50.4572 -0.404181 +VERTEX2 9342 -55.8467 -50.8157 -0.389459 +VERTEX2 9343 -54.9869 -51.2431 -0.371721 +VERTEX2 9344 -54.1252 -51.6283 -0.380194 +VERTEX2 9345 -53.1598 -51.9424 -0.365315 +VERTEX2 9346 -52.6883 -51.0002 1.21018 +VERTEX2 9347 -52.2853 -50.0914 1.22361 +VERTEX2 9348 -51.9134 -49.1872 1.22453 +VERTEX2 9349 -51.6064 -48.3132 1.22231 +VERTEX2 9350 -51.246 -47.3266 1.21124 +VERTEX2 9351 -52.1681 -47.0059 2.7833 +VERTEX2 9352 -53.0663 -46.745 2.76029 +VERTEX2 9353 -53.8709 -46.3175 2.73811 +VERTEX2 9354 -54.8435 -45.8954 2.74989 +VERTEX2 9355 -55.767 -45.4918 2.75815 +VERTEX2 9356 -55.4527 -44.4891 1.20922 +VERTEX2 9357 -55.0867 -43.5406 1.20989 +VERTEX2 9358 -54.7828 -42.5803 1.21199 +VERTEX2 9359 -54.3892 -41.582 1.22804 +VERTEX2 9360 -54.132 -40.6773 1.20692 +VERTEX2 9361 -55.0815 -40.2783 2.78286 +VERTEX2 9362 -56.0326 -39.8971 2.78995 +VERTEX2 9363 -56.9752 -39.4969 2.79235 +VERTEX2 9364 -57.8676 -39.1791 2.75426 +VERTEX2 9365 -58.854 -38.8141 2.75394 +VERTEX2 9366 -58.5562 -37.9852 1.19936 +VERTEX2 9367 -58.189 -37.0259 1.19209 +VERTEX2 9368 -57.925 -36.1423 1.19418 +VERTEX2 9369 -57.5589 -35.2305 1.16921 +VERTEX2 9370 -57.2047 -34.2613 1.20938 +VERTEX2 9371 -58.106 -33.9693 2.81272 +VERTEX2 9372 -59.0748 -33.6456 2.82464 +VERTEX2 9373 -59.9528 -33.3251 2.82805 +VERTEX2 9374 -60.8794 -33.0741 2.8188 +VERTEX2 9375 -61.7877 -32.8432 2.83957 +VERTEX2 9376 -61.4796 -31.8484 1.28213 +VERTEX2 9377 -61.1687 -30.9236 1.30411 +VERTEX2 9378 -60.9686 -29.9965 1.27423 +VERTEX2 9379 -60.7073 -28.9687 1.26902 +VERTEX2 9380 -60.3784 -28.0813 1.25725 +VERTEX2 9381 -59.3906 -28.369 -0.315651 +VERTEX2 9382 -58.4725 -28.7511 -0.352368 +VERTEX2 9383 -57.5554 -29.1182 -0.351512 +VERTEX2 9384 -56.5615 -29.4922 -0.361775 +VERTEX2 9385 -55.6601 -29.865 -0.394949 +VERTEX2 9386 -56.1295 -30.8728 -1.97126 +VERTEX2 9387 -56.5214 -31.692 -1.98243 +VERTEX2 9388 -56.9253 -32.6101 -1.99436 +VERTEX2 9389 -57.3144 -33.5617 -1.94844 +VERTEX2 9390 -57.7583 -34.4693 -1.9847 +VERTEX2 9391 -56.8111 -34.8538 -0.424279 +VERTEX2 9392 -55.8453 -35.2902 -0.401781 +VERTEX2 9393 -54.871 -35.6177 -0.397755 +VERTEX2 9394 -53.9667 -35.9785 -0.390515 +VERTEX2 9395 -53.1622 -36.3314 -0.368239 +VERTEX2 9396 -53.4978 -37.1829 -1.93165 +VERTEX2 9397 -53.9183 -38.1651 -1.94417 +VERTEX2 9398 -54.197 -39.0877 -1.9521 +VERTEX2 9399 -54.5128 -39.9961 -1.93292 +VERTEX2 9400 -54.9671 -40.9328 -1.91037 +VERTEX2 9401 -53.8883 -41.2358 -0.366274 +VERTEX2 9402 -52.8488 -41.687 -0.392106 +VERTEX2 9403 -51.9462 -42.0876 -0.416578 +VERTEX2 9404 -51.0307 -42.5405 -0.451682 +VERTEX2 9405 -50.0664 -42.9514 -0.441824 +VERTEX2 9406 -49.5579 -42.0013 1.11977 +VERTEX2 9407 -49.1526 -41.0923 1.10283 +VERTEX2 9408 -48.7596 -40.1318 1.1264 +VERTEX2 9409 -48.2813 -39.2452 1.15736 +VERTEX2 9410 -47.8559 -38.3676 1.1379 +VERTEX2 9411 -46.8927 -38.7152 -0.452801 +VERTEX2 9412 -45.9325 -39.1015 -0.445611 +VERTEX2 9413 -45.0514 -39.5624 -0.431436 +VERTEX2 9414 -44.1387 -39.9887 -0.419526 +VERTEX2 9415 -43.2851 -40.4164 -0.405281 +VERTEX2 9416 -42.8681 -39.4523 1.17476 +VERTEX2 9417 -42.5786 -38.5922 1.14418 +VERTEX2 9418 -42.2017 -37.709 1.11786 +VERTEX2 9419 -41.7698 -36.8426 1.12458 +VERTEX2 9420 -41.3809 -35.9075 1.12974 +VERTEX2 9421 -40.4664 -36.4944 -0.441424 +VERTEX2 9422 -39.4877 -36.9528 -0.451492 +VERTEX2 9423 -38.5596 -37.3806 -0.468242 +VERTEX2 9424 -37.6023 -37.8752 -0.485299 +VERTEX2 9425 -36.6951 -38.3257 -0.51642 +VERTEX2 9426 -36.1956 -37.4296 1.07681 +VERTEX2 9427 -35.7618 -36.5092 1.07917 +VERTEX2 9428 -35.3027 -35.5862 1.12869 +VERTEX2 9429 -34.9205 -34.5867 1.13948 +VERTEX2 9430 -34.5808 -33.7381 1.09855 +VERTEX2 9431 -33.6688 -34.1296 -0.456071 +VERTEX2 9432 -32.6631 -34.5062 -0.447532 +VERTEX2 9433 -31.7626 -34.934 -0.474197 +VERTEX2 9434 -30.9097 -35.3403 -0.481574 +VERTEX2 9435 -30.0318 -35.8065 -0.486126 +VERTEX2 9436 -29.5181 -34.9009 1.06773 +VERTEX2 9437 -29.0775 -33.9674 1.07182 +VERTEX2 9438 -28.6011 -33.0529 1.1286 +VERTEX2 9439 -28.1424 -32.1714 1.14928 +VERTEX2 9440 -27.6855 -31.2532 1.14935 +VERTEX2 9441 -28.5804 -30.8047 2.72888 +VERTEX2 9442 -29.4779 -30.4084 2.72299 +VERTEX2 9443 -30.3716 -30.0522 2.73931 +VERTEX2 9444 -31.2971 -29.6889 2.75167 +VERTEX2 9445 -32.1655 -29.3262 2.74442 +VERTEX2 9446 -32.5291 -30.2507 -1.94664 +VERTEX2 9447 -32.8769 -31.2166 -1.92003 +VERTEX2 9448 -33.2364 -32.1798 -1.91657 +VERTEX2 9449 -33.5235 -33.1991 -1.91736 +VERTEX2 9450 -33.8335 -34.1553 -1.91356 +VERTEX2 9451 -32.8121 -34.4341 -0.337317 +VERTEX2 9452 -31.7948 -34.7349 -0.354098 +VERTEX2 9453 -30.8353 -35.0741 -0.351223 +VERTEX2 9454 -29.8354 -35.4552 -0.361859 +VERTEX2 9455 -28.9439 -35.8 -0.365401 +VERTEX2 9456 -28.5668 -34.7826 1.19972 +VERTEX2 9457 -28.1786 -33.8465 1.20538 +VERTEX2 9458 -27.7625 -32.9658 1.21298 +VERTEX2 9459 -27.3621 -32.0112 1.21455 +VERTEX2 9460 -27.0749 -31.0909 1.18594 +VERTEX2 9461 -28.0374 -30.7063 2.74972 +VERTEX2 9462 -29.0601 -30.3232 2.75281 +VERTEX2 9463 -29.8901 -29.8815 2.73701 +VERTEX2 9464 -30.8234 -29.4738 2.73058 +VERTEX2 9465 -31.6776 -29.0815 2.73371 +VERTEX2 9466 -31.3476 -28.1914 1.17747 +VERTEX2 9467 -31.01 -27.3152 1.18086 +VERTEX2 9468 -30.6287 -26.4624 1.16559 +VERTEX2 9469 -30.3046 -25.6162 1.19491 +VERTEX2 9470 -29.8987 -24.7228 1.20796 +VERTEX2 9471 -30.7876 -24.3914 2.82157 +VERTEX2 9472 -31.7806 -24.0591 2.83097 +VERTEX2 9473 -32.6754 -23.8021 2.82915 +VERTEX2 9474 -33.7028 -23.5182 2.87402 +VERTEX2 9475 -34.7317 -23.2922 2.87737 +VERTEX2 9476 -34.9409 -24.2504 -1.8103 +VERTEX2 9477 -35.125 -25.1853 -1.83035 +VERTEX2 9478 -35.3976 -26.1906 -1.81867 +VERTEX2 9479 -35.6545 -27.2495 -1.82135 +VERTEX2 9480 -35.9444 -28.1808 -1.88634 +VERTEX2 9481 -36.9739 -27.9229 2.77706 +VERTEX2 9482 -37.9376 -27.612 2.77722 +VERTEX2 9483 -38.8966 -27.2507 2.77681 +VERTEX2 9484 -39.812 -26.9513 2.76901 +VERTEX2 9485 -40.7739 -26.6258 2.77045 +VERTEX2 9486 -40.4832 -25.6883 1.22628 +VERTEX2 9487 -40.1395 -24.8168 1.22782 +VERTEX2 9488 -39.867 -23.8897 1.26993 +VERTEX2 9489 -39.4917 -22.9824 1.25371 +VERTEX2 9490 -39.1349 -21.9361 1.25244 +VERTEX2 9491 -40.0215 -21.65 2.80504 +VERTEX2 9492 -41.034 -21.317 2.80321 +VERTEX2 9493 -41.9317 -20.96 2.77208 +VERTEX2 9494 -42.8517 -20.5404 2.7541 +VERTEX2 9495 -43.7403 -20.2171 2.74494 +VERTEX2 9496 -43.4179 -19.2699 1.17921 +VERTEX2 9497 -42.9636 -18.4557 1.19602 +VERTEX2 9498 -42.6449 -17.5081 1.19799 +VERTEX2 9499 -42.3087 -16.577 1.18867 +VERTEX2 9500 -41.8581 -15.6197 1.20505 +VERTEX2 9501 -42.8483 -15.3136 2.73041 +VERTEX2 9502 -43.7457 -14.8167 2.74958 +VERTEX2 9503 -44.6542 -14.4487 2.77013 +VERTEX2 9504 -45.5324 -14.0539 2.74197 +VERTEX2 9505 -46.4969 -13.6515 2.7174 +VERTEX2 9506 -46.1308 -12.6877 1.12399 +VERTEX2 9507 -45.702 -11.7954 1.11849 +VERTEX2 9508 -45.2973 -10.8829 1.16598 +VERTEX2 9509 -45.0018 -9.9433 1.15375 +VERTEX2 9510 -44.6324 -9.03942 1.17407 +VERTEX2 9511 -45.5827 -8.64687 2.73772 +VERTEX2 9512 -46.5058 -8.27573 2.73823 +VERTEX2 9513 -47.3873 -7.85054 2.72409 +VERTEX2 9514 -48.2885 -7.36677 2.73007 +VERTEX2 9515 -49.1387 -7.06198 2.72024 +VERTEX2 9516 -49.5461 -7.93529 -1.99354 +VERTEX2 9517 -50.0204 -8.83276 -1.96096 +VERTEX2 9518 -50.3524 -9.73583 -1.96151 +VERTEX2 9519 -50.693 -10.581 -1.92098 +VERTEX2 9520 -50.9872 -11.4834 -1.94079 +VERTEX2 9521 -49.9998 -11.8354 -0.355381 +VERTEX2 9522 -49.0262 -12.1845 -0.325624 +VERTEX2 9523 -48.0006 -12.4856 -0.308807 +VERTEX2 9524 -47.0794 -12.7457 -0.339237 +VERTEX2 9525 -46.1031 -13.0821 -0.317385 +VERTEX2 9526 -46.4001 -13.968 -1.94482 +VERTEX2 9527 -46.7723 -14.9045 -1.94527 +VERTEX2 9528 -47.0342 -15.824 -1.91332 +VERTEX2 9529 -47.4401 -16.779 -1.91975 +VERTEX2 9530 -47.7551 -17.6917 -1.93156 +VERTEX2 9531 -48.6011 -17.4304 2.73419 +VERTEX2 9532 -49.4633 -17.1131 2.72609 +VERTEX2 9533 -50.3732 -16.7565 2.74109 +VERTEX2 9534 -51.2819 -16.4237 2.72156 +VERTEX2 9535 -52.1841 -15.9201 2.7188 +VERTEX2 9536 -51.7843 -15.117 1.14129 +VERTEX2 9537 -51.3902 -14.1509 1.14242 +VERTEX2 9538 -50.9815 -13.2986 1.09817 +VERTEX2 9539 -50.5791 -12.3454 1.10336 +VERTEX2 9540 -50.1171 -11.4108 1.0734 +VERTEX2 9541 -50.984 -10.9895 2.61461 +VERTEX2 9542 -51.8663 -10.4649 2.63961 +VERTEX2 9543 -52.75 -10.0386 2.66738 +VERTEX2 9544 -53.6316 -9.546 2.63184 +VERTEX2 9545 -54.5102 -9.03855 2.64304 +VERTEX2 9546 -54.1109 -8.13389 1.05544 +VERTEX2 9547 -53.7054 -7.30686 1.047 +VERTEX2 9548 -53.319 -6.40738 1.03601 +VERTEX2 9549 -52.8421 -5.44987 1.03266 +VERTEX2 9550 -52.3469 -4.48373 1.01054 +VERTEX2 9551 -53.1721 -3.94687 2.59329 +VERTEX2 9552 -54.0831 -3.46268 2.61626 +VERTEX2 9553 -54.9118 -3.01851 2.60254 +VERTEX2 9554 -55.7722 -2.54902 2.60151 +VERTEX2 9555 -56.6285 -2.05732 2.6347 +VERTEX2 9556 -56.1732 -1.12842 1.08177 +VERTEX2 9557 -55.6124 -0.200081 1.05251 +VERTEX2 9558 -55.1561 0.679245 1.03558 +VERTEX2 9559 -54.6464 1.66726 1.06057 +VERTEX2 9560 -54.1456 2.58303 1.08122 +VERTEX2 9561 -55.0217 3.092 2.65487 +VERTEX2 9562 -55.9336 3.59868 2.65328 +VERTEX2 9563 -56.7943 4.0174 2.68532 +VERTEX2 9564 -57.7334 4.52428 2.67612 +VERTEX2 9565 -58.6737 5.06317 2.65393 +VERTEX2 9566 -58.1859 5.90803 1.06992 +VERTEX2 9567 -57.7664 6.75566 1.04065 +VERTEX2 9568 -57.328 7.70053 1.03329 +VERTEX2 9569 -56.8125 8.61371 1.01291 +VERTEX2 9570 -56.2323 9.51586 1.01771 +VERTEX2 9571 -57.0367 9.98244 2.57836 +VERTEX2 9572 -57.9077 10.5519 2.59103 +VERTEX2 9573 -58.7175 11.1525 2.54058 +VERTEX2 9574 -59.5449 11.7253 2.54824 +VERTEX2 9575 -60.3568 12.2442 2.54279 +VERTEX2 9576 -60.9678 11.347 -2.16691 +VERTEX2 9577 -61.4604 10.4803 -2.18825 +VERTEX2 9578 -62.1053 9.60359 -2.20962 +VERTEX2 9579 -62.702 8.80002 -2.20534 +VERTEX2 9580 -63.3041 8.14086 -2.20585 +VERTEX2 9581 -62.5135 7.48486 -0.633567 +VERTEX2 9582 -61.7142 6.8944 -0.625361 +VERTEX2 9583 -60.9622 6.29721 -0.640831 +VERTEX2 9584 -60.1281 5.77962 -0.633172 +VERTEX2 9585 -59.3137 5.1866 -0.638377 +VERTEX2 9586 -58.7678 6.02055 0.918988 +VERTEX2 9587 -58.1583 6.86004 0.910689 +VERTEX2 9588 -57.5345 7.61451 0.909708 +VERTEX2 9589 -56.9363 8.34343 0.930774 +VERTEX2 9590 -56.3227 9.17995 0.931932 +VERTEX2 9591 -57.1359 9.74999 2.53411 +VERTEX2 9592 -57.9834 10.32 2.52247 +VERTEX2 9593 -58.828 11.0379 2.51671 +VERTEX2 9594 -59.6248 11.5934 2.53314 +VERTEX2 9595 -60.3464 12.1352 2.54134 +VERTEX2 9596 -60.8448 11.2894 -2.17063 +VERTEX2 9597 -61.3453 10.4988 -2.14663 +VERTEX2 9598 -61.9365 9.6161 -2.15201 +VERTEX2 9599 -62.5582 8.81769 -2.17117 +VERTEX2 9600 -63.0792 7.99016 -2.18062 +VERTEX2 9601 -62.239 7.44184 -0.599021 +VERTEX2 9602 -61.4192 6.89673 -0.598518 +VERTEX2 9603 -60.6214 6.2986 -0.617356 +VERTEX2 9604 -59.8508 5.84879 -0.613612 +VERTEX2 9605 -59.0698 5.20677 -0.593845 +VERTEX2 9606 -59.5518 4.43627 -2.20749 +VERTEX2 9607 -60.1528 3.67243 -2.19336 +VERTEX2 9608 -60.7239 2.86509 -2.18673 +VERTEX2 9609 -61.4575 2.04561 -2.20469 +VERTEX2 9610 -62.1031 1.26312 -2.2209 +VERTEX2 9611 -62.8231 1.88101 2.49338 +VERTEX2 9612 -63.5878 2.48968 2.48369 +VERTEX2 9613 -64.4429 3.04738 2.47499 +VERTEX2 9614 -65.2087 3.70233 2.47817 +VERTEX2 9615 -66.0254 4.38946 2.49075 +VERTEX2 9616 -66.5482 3.65351 -2.21244 +VERTEX2 9617 -67.161 2.8023 -2.19077 +VERTEX2 9618 -67.6603 2.01811 -2.20792 +VERTEX2 9619 -68.2207 1.21193 -2.19169 +VERTEX2 9620 -68.8062 0.345485 -2.1729 +VERTEX2 9621 -69.7077 0.848849 2.52562 +VERTEX2 9622 -70.5286 1.47844 2.51755 +VERTEX2 9623 -71.377 2.11433 2.49766 +VERTEX2 9624 -72.2186 2.72087 2.50637 +VERTEX2 9625 -73.0308 3.30217 2.4922 +VERTEX2 9626 -73.6566 2.58909 -2.21078 +VERTEX2 9627 -74.1528 1.79072 -2.19058 +VERTEX2 9628 -74.7099 1.01597 -2.1894 +VERTEX2 9629 -75.2303 0.275335 -2.21413 +VERTEX2 9630 -75.7655 -0.53385 -2.20907 +VERTEX2 9631 -74.8993 -1.09522 -0.656072 +VERTEX2 9632 -74.0658 -1.80718 -0.678376 +VERTEX2 9633 -73.3196 -2.43858 -0.632732 +VERTEX2 9634 -72.4229 -2.99058 -0.591391 +VERTEX2 9635 -71.6124 -3.49842 -0.589624 +VERTEX2 9636 -71.0036 -2.66709 0.97251 +VERTEX2 9637 -70.3072 -1.90061 0.961768 +VERTEX2 9638 -69.7592 -1.09372 0.999047 +VERTEX2 9639 -69.2203 -0.271436 0.973781 +VERTEX2 9640 -68.6513 0.434672 1.0095 +VERTEX2 9641 -69.5056 0.972509 2.58496 +VERTEX2 9642 -70.3478 1.55278 2.57687 +VERTEX2 9643 -71.1512 2.07607 2.61622 +VERTEX2 9644 -71.9308 2.58463 2.60988 +VERTEX2 9645 -72.883 3.09164 2.64882 +VERTEX2 9646 -73.3496 2.1768 -2.07369 +VERTEX2 9647 -73.8301 1.23199 -2.03394 +VERTEX2 9648 -74.3193 0.28181 -2.02375 +VERTEX2 9649 -74.7731 -0.616936 -2.03063 +VERTEX2 9650 -75.1224 -1.48016 -2.04942 +VERTEX2 9651 -74.3377 -2.03622 -0.486489 +VERTEX2 9652 -73.4498 -2.45191 -0.467222 +VERTEX2 9653 -72.568 -2.99474 -0.483896 +VERTEX2 9654 -71.5984 -3.41095 -0.476057 +VERTEX2 9655 -70.7112 -3.82275 -0.458749 +VERTEX2 9656 -71.2752 -4.74546 -2.041 +VERTEX2 9657 -71.6945 -5.597 -2.0604 +VERTEX2 9658 -72.1833 -6.49556 -2.05493 +VERTEX2 9659 -72.7462 -7.30773 -2.05606 +VERTEX2 9660 -73.3287 -8.16813 -2.02486 +VERTEX2 9661 -72.522 -8.54694 -0.448595 +VERTEX2 9662 -71.6574 -8.99362 -0.444837 +VERTEX2 9663 -70.7336 -9.43917 -0.403802 +VERTEX2 9664 -69.7967 -9.79378 -0.434594 +VERTEX2 9665 -68.8978 -10.1997 -0.449426 +VERTEX2 9666 -69.3082 -11.0664 -1.99862 +VERTEX2 9667 -69.7856 -11.9757 -2.00442 +VERTEX2 9668 -70.1879 -12.9402 -1.97863 +VERTEX2 9669 -70.5398 -13.9082 -1.94992 +VERTEX2 9670 -70.93 -14.7614 -1.9735 +VERTEX2 9671 -71.8081 -14.4027 2.73224 +VERTEX2 9672 -72.7201 -14.0757 2.73199 +VERTEX2 9673 -73.6643 -13.6658 2.73646 +VERTEX2 9674 -74.5337 -13.3195 2.76912 +VERTEX2 9675 -75.3659 -12.9776 2.75409 +VERTEX2 9676 -75.7077 -13.9423 -1.99077 +VERTEX2 9677 -76.1029 -14.9001 -2.00871 +VERTEX2 9678 -76.6753 -15.7832 -1.99848 +VERTEX2 9679 -77.0149 -16.6494 -2.01119 +VERTEX2 9680 -77.4147 -17.5499 -2.03548 +VERTEX2 9681 -78.2205 -17.055 2.74786 +VERTEX2 9682 -79.1026 -16.6567 2.7398 +VERTEX2 9683 -79.9919 -16.3686 2.75057 +VERTEX2 9684 -80.9315 -16.0648 2.72081 +VERTEX2 9685 -81.8174 -15.7306 2.75436 +VERTEX2 9686 -82.1282 -16.6166 -1.9879 +VERTEX2 9687 -82.5426 -17.6299 -2.02609 +VERTEX2 9688 -82.9816 -18.5656 -2.01324 +VERTEX2 9689 -83.4328 -19.4347 -2.0447 +VERTEX2 9690 -84.0025 -20.3736 -2.07497 +VERTEX2 9691 -83.274 -20.9144 -0.511507 +VERTEX2 9692 -82.3986 -21.4201 -0.533494 +VERTEX2 9693 -81.4739 -22.0096 -0.510679 +VERTEX2 9694 -80.5177 -22.4944 -0.507358 +VERTEX2 9695 -79.6941 -23.0298 -0.530213 +VERTEX2 9696 -79.1225 -22.2481 1.0976 +VERTEX2 9697 -78.5999 -21.3848 1.12467 +VERTEX2 9698 -78.2058 -20.486 1.12673 +VERTEX2 9699 -77.6792 -19.475 1.1281 +VERTEX2 9700 -77.1845 -18.5831 1.1347 +VERTEX2 9701 -78.0552 -18.1588 2.70761 +VERTEX2 9702 -78.9475 -17.7588 2.6946 +VERTEX2 9703 -79.7991 -17.3124 2.68794 +VERTEX2 9704 -80.6405 -16.8856 2.67935 +VERTEX2 9705 -81.5049 -16.3667 2.66358 +VERTEX2 9706 -81.9754 -17.2318 -2.02395 +VERTEX2 9707 -82.2982 -18.1182 -2.03776 +VERTEX2 9708 -82.7521 -18.9743 -2.0403 +VERTEX2 9709 -83.257 -19.8747 -2.0132 +VERTEX2 9710 -83.7275 -20.7895 -1.99738 +VERTEX2 9711 -82.8018 -21.2419 -0.417237 +VERTEX2 9712 -81.9864 -21.6279 -0.408187 +VERTEX2 9713 -81.1748 -21.9031 -0.378632 +VERTEX2 9714 -80.1609 -22.2387 -0.407001 +VERTEX2 9715 -79.2056 -22.6814 -0.419057 +VERTEX2 9716 -79.614 -23.6166 -1.96772 +VERTEX2 9717 -79.9754 -24.5642 -1.95071 +VERTEX2 9718 -80.3854 -25.4327 -1.95149 +VERTEX2 9719 -80.8061 -26.3536 -1.94678 +VERTEX2 9720 -81.2114 -27.1948 -1.9285 +VERTEX2 9721 -82.1097 -26.9005 2.77675 +VERTEX2 9722 -83.0718 -26.5792 2.81552 +VERTEX2 9723 -84.107 -26.2884 2.77881 +VERTEX2 9724 -85.043 -25.9829 2.75425 +VERTEX2 9725 -85.9894 -25.5635 2.75377 +VERTEX2 9726 -86.4315 -26.5174 -1.95192 +VERTEX2 9727 -86.8481 -27.4276 -1.94769 +VERTEX2 9728 -87.1986 -28.2971 -1.96212 +VERTEX2 9729 -87.6034 -29.1969 -1.97921 +VERTEX2 9730 -88.0464 -30.0924 -2.00679 +VERTEX2 9731 -88.9344 -29.7385 2.6656 +VERTEX2 9732 -89.9369 -29.3066 2.65945 +VERTEX2 9733 -90.8597 -28.7857 2.67488 +VERTEX2 9734 -91.7387 -28.3978 2.69664 +VERTEX2 9735 -92.5797 -27.8845 2.70472 +VERTEX2 9736 -92.15 -26.9434 1.13575 +VERTEX2 9737 -91.8571 -26.0755 1.11661 +VERTEX2 9738 -91.4318 -25.2022 1.12683 +VERTEX2 9739 -91.0374 -24.2795 1.16793 +VERTEX2 9740 -90.7002 -23.3864 1.1479 +VERTEX2 9741 -91.5674 -23.0107 2.71989 +VERTEX2 9742 -92.3902 -22.5679 2.70772 +VERTEX2 9743 -93.3005 -22.2093 2.71107 +VERTEX2 9744 -94.2267 -21.8826 2.69034 +VERTEX2 9745 -95.1207 -21.3817 2.66918 +VERTEX2 9746 -94.7069 -20.4726 1.09153 +VERTEX2 9747 -94.1871 -19.5646 1.08799 +VERTEX2 9748 -93.7557 -18.6681 1.10031 +VERTEX2 9749 -93.291 -17.7633 1.13076 +VERTEX2 9750 -92.8068 -16.7126 1.1472 +VERTEX2 9751 -93.6963 -16.3227 2.68632 +VERTEX2 9752 -94.5259 -15.8846 2.66355 +VERTEX2 9753 -95.3701 -15.5004 2.69398 +VERTEX2 9754 -96.2664 -15.0261 2.69279 +VERTEX2 9755 -97.1773 -14.6332 2.68454 +VERTEX2 9756 -97.6683 -15.6148 -2.04345 +VERTEX2 9757 -98.0611 -16.4122 -2.04468 +VERTEX2 9758 -98.508 -17.2925 -2.0601 +VERTEX2 9759 -98.9702 -18.1779 -2.05595 +VERTEX2 9760 -99.4449 -19.0333 -2.04569 +VERTEX2 9761 -100.276 -18.5424 2.65808 +VERTEX2 9762 -101.24 -18.0451 2.66014 +VERTEX2 9763 -102.193 -17.6439 2.62449 +VERTEX2 9764 -103.007 -17.1274 2.6087 +VERTEX2 9765 -103.812 -16.6509 2.63764 +VERTEX2 9766 -104.267 -17.4466 -2.05141 +VERTEX2 9767 -104.643 -18.2967 -2.05943 +VERTEX2 9768 -105.065 -19.115 -2.06871 +VERTEX2 9769 -105.659 -20.0096 -2.07859 +VERTEX2 9770 -106.113 -20.9569 -2.05031 +VERTEX2 9771 -105.26 -21.5171 -0.505926 +VERTEX2 9772 -104.328 -22.0166 -0.517928 +VERTEX2 9773 -103.456 -22.6262 -0.49946 +VERTEX2 9774 -102.702 -22.9834 -0.505761 +VERTEX2 9775 -101.868 -23.4451 -0.485276 +VERTEX2 9776 -101.331 -22.5763 1.07114 +VERTEX2 9777 -100.786 -21.6943 1.07648 +VERTEX2 9778 -100.307 -20.8636 1.0656 +VERTEX2 9779 -99.796 -20.1238 1.0679 +VERTEX2 9780 -99.3826 -19.3021 1.0652 +VERTEX2 9781 -100.271 -18.7283 2.62488 +VERTEX2 9782 -101.127 -18.2172 2.64615 +VERTEX2 9783 -101.968 -17.7918 2.63941 +VERTEX2 9784 -102.882 -17.1475 2.62893 +VERTEX2 9785 -103.694 -16.5912 2.63727 +VERTEX2 9786 -104.188 -17.5575 -2.0872 +VERTEX2 9787 -104.656 -18.4438 -2.07018 +VERTEX2 9788 -105.168 -19.356 -2.07849 +VERTEX2 9789 -105.647 -20.1555 -2.12265 +VERTEX2 9790 -106.158 -20.9995 -2.11475 +VERTEX2 9791 -105.332 -21.6029 -0.538615 +VERTEX2 9792 -104.509 -21.9902 -0.530094 +VERTEX2 9793 -103.651 -22.5156 -0.537692 +VERTEX2 9794 -102.905 -23.0383 -0.568266 +VERTEX2 9795 -102.014 -23.5902 -0.529897 +VERTEX2 9796 -101.501 -22.7426 1.0426 +VERTEX2 9797 -100.967 -21.8545 1.06315 +VERTEX2 9798 -100.516 -21.0031 1.03978 +VERTEX2 9799 -99.9875 -20.132 1.04838 +VERTEX2 9800 -99.4642 -19.3199 1.05906 +VERTEX2 9801 -100.291 -18.8906 2.60231 +VERTEX2 9802 -101.149 -18.3418 2.60159 +VERTEX2 9803 -101.998 -17.837 2.58178 +VERTEX2 9804 -102.836 -17.2993 2.56749 +VERTEX2 9805 -103.683 -16.7119 2.58311 +VERTEX2 9806 -104.195 -17.607 -2.09043 +VERTEX2 9807 -104.751 -18.5348 -2.12012 +VERTEX2 9808 -105.269 -19.3316 -2.09252 +VERTEX2 9809 -105.785 -20.2218 -2.08341 +VERTEX2 9810 -106.229 -21.0305 -2.07029 +VERTEX2 9811 -107.175 -20.5826 2.61759 +VERTEX2 9812 -108.039 -20.0552 2.60669 +VERTEX2 9813 -108.937 -19.5805 2.61296 +VERTEX2 9814 -109.834 -19.0781 2.60897 +VERTEX2 9815 -110.701 -18.6199 2.6197 +VERTEX2 9816 -111.129 -19.4499 -2.05656 +VERTEX2 9817 -111.605 -20.3904 -2.0973 +VERTEX2 9818 -112.201 -21.3117 -2.09592 +VERTEX2 9819 -112.765 -22.2341 -2.11126 +VERTEX2 9820 -113.279 -23.1111 -2.11554 +VERTEX2 9821 -114.084 -22.5949 2.5818 +VERTEX2 9822 -114.825 -22.0525 2.55511 +VERTEX2 9823 -115.697 -21.4534 2.56566 +VERTEX2 9824 -116.505 -20.9033 2.53447 +VERTEX2 9825 -117.426 -20.3824 2.52764 +VERTEX2 9826 -117.952 -21.2943 -2.14148 +VERTEX2 9827 -118.48 -21.9753 -2.1373 +VERTEX2 9828 -118.906 -22.8273 -2.16106 +VERTEX2 9829 -119.46 -23.6309 -2.12835 +VERTEX2 9830 -120.048 -24.3723 -2.13192 +VERTEX2 9831 -119.205 -24.817 -0.541663 +VERTEX2 9832 -118.348 -25.3573 -0.519136 +VERTEX2 9833 -117.428 -25.9292 -0.498784 +VERTEX2 9834 -116.592 -26.2934 -0.506281 +VERTEX2 9835 -115.687 -26.668 -0.51749 +VERTEX2 9836 -115.235 -25.7741 1.04371 +VERTEX2 9837 -114.723 -24.9241 1.0563 +VERTEX2 9838 -114.257 -24.1249 1.04077 +VERTEX2 9839 -113.78 -23.2309 1.04757 +VERTEX2 9840 -113.376 -22.3593 1.05508 +VERTEX2 9841 -112.52 -22.843 -0.504899 +VERTEX2 9842 -111.544 -23.3322 -0.508822 +VERTEX2 9843 -110.724 -23.8004 -0.484292 +VERTEX2 9844 -109.909 -24.3225 -0.529217 +VERTEX2 9845 -108.981 -24.7237 -0.534152 +VERTEX2 9846 -108.494 -23.9351 1.05237 +VERTEX2 9847 -108.006 -23.0099 1.04108 +VERTEX2 9848 -107.539 -22.1394 1.05633 +VERTEX2 9849 -106.995 -21.258 1.06771 +VERTEX2 9850 -106.497 -20.3817 1.06554 +VERTEX2 9851 -105.642 -20.8353 -0.50741 +VERTEX2 9852 -104.836 -21.373 -0.475294 +VERTEX2 9853 -103.88 -21.8858 -0.48749 +VERTEX2 9854 -102.931 -22.3112 -0.447867 +VERTEX2 9855 -102.039 -22.7058 -0.481411 +VERTEX2 9856 -101.618 -21.6727 1.10176 +VERTEX2 9857 -101.187 -20.853 1.08957 +VERTEX2 9858 -100.734 -20.0138 1.12211 +VERTEX2 9859 -100.381 -19.179 1.14188 +VERTEX2 9860 -100.098 -18.2819 1.12144 +VERTEX2 9861 -101.026 -17.7828 2.69529 +VERTEX2 9862 -101.858 -17.3516 2.67889 +VERTEX2 9863 -102.777 -16.9013 2.67371 +VERTEX2 9864 -103.608 -16.4306 2.65846 +VERTEX2 9865 -104.541 -16.0159 2.6598 +VERTEX2 9866 -104.061 -15.1076 1.06196 +VERTEX2 9867 -103.583 -14.3092 1.05684 +VERTEX2 9868 -103.106 -13.4989 1.05039 +VERTEX2 9869 -102.61 -12.7087 1.06332 +VERTEX2 9870 -102.064 -11.8143 1.04812 +VERTEX2 9871 -102.873 -11.3375 2.65608 +VERTEX2 9872 -103.817 -10.8468 2.64686 +VERTEX2 9873 -104.772 -10.3049 2.66349 +VERTEX2 9874 -105.649 -9.83927 2.63909 +VERTEX2 9875 -106.542 -9.28355 2.62154 +VERTEX2 9876 -106.987 -10.178 -2.09781 +VERTEX2 9877 -107.431 -11.0046 -2.07634 +VERTEX2 9878 -107.864 -11.9194 -2.07816 +VERTEX2 9879 -108.338 -12.8386 -2.09721 +VERTEX2 9880 -108.906 -13.7851 -2.05364 +VERTEX2 9881 -109.833 -13.2854 2.63036 +VERTEX2 9882 -110.627 -12.857 2.67907 +VERTEX2 9883 -111.499 -12.4176 2.6469 +VERTEX2 9884 -112.384 -11.9465 2.65263 +VERTEX2 9885 -113.291 -11.4366 2.63514 +VERTEX2 9886 -113.71 -12.3272 -2.07991 +VERTEX2 9887 -114.178 -13.184 -2.06835 +VERTEX2 9888 -114.749 -14.0485 -2.04521 +VERTEX2 9889 -115.22 -14.8576 -2.04545 +VERTEX2 9890 -115.697 -15.7259 -2.0215 +VERTEX2 9891 -116.534 -15.2802 2.69909 +VERTEX2 9892 -117.387 -14.8026 2.71265 +VERTEX2 9893 -118.272 -14.4015 2.66865 +VERTEX2 9894 -119.234 -13.9692 2.62826 +VERTEX2 9895 -120.174 -13.4036 2.61861 +VERTEX2 9896 -120.633 -14.2198 -2.10738 +VERTEX2 9897 -121.123 -15.1745 -2.12083 +VERTEX2 9898 -121.743 -16.0618 -2.11786 +VERTEX2 9899 -122.249 -16.9518 -2.13819 +VERTEX2 9900 -122.844 -17.7822 -2.11904 +VERTEX2 9901 -122.039 -18.3767 -0.563011 +VERTEX2 9902 -121.205 -18.9165 -0.580563 +VERTEX2 9903 -120.376 -19.4427 -0.582493 +VERTEX2 9904 -119.549 -20.0472 -0.576526 +VERTEX2 9905 -118.697 -20.5564 -0.593904 +VERTEX2 9906 -118.07 -19.756 0.996773 +VERTEX2 9907 -117.543 -18.8783 0.993455 +VERTEX2 9908 -117.002 -18.0861 0.976775 +VERTEX2 9909 -116.44 -17.2417 0.975208 +VERTEX2 9910 -115.847 -16.3862 1.00672 +VERTEX2 9911 -116.773 -15.8736 2.6092 +VERTEX2 9912 -117.623 -15.3695 2.6338 +VERTEX2 9913 -118.376 -14.8312 2.60374 +VERTEX2 9914 -119.192 -14.2517 2.60757 +VERTEX2 9915 -119.977 -13.7437 2.60683 +VERTEX2 9916 -119.459 -12.9072 1.02562 +VERTEX2 9917 -118.924 -12.0078 1.03625 +VERTEX2 9918 -118.442 -11.1409 1.04472 +VERTEX2 9919 -117.942 -10.2114 1.00869 +VERTEX2 9920 -117.423 -9.28902 1.05695 +VERTEX2 9921 -118.224 -8.69913 2.64704 +VERTEX2 9922 -119.118 -8.22835 2.63877 +VERTEX2 9923 -120.023 -7.69814 2.64821 +VERTEX2 9924 -121.005 -7.23081 2.65649 +VERTEX2 9925 -121.917 -6.74438 2.68871 +VERTEX2 9926 -121.485 -5.76996 1.13221 +VERTEX2 9927 -121.063 -4.8439 1.14157 +VERTEX2 9928 -120.646 -4.01191 1.12897 +VERTEX2 9929 -120.191 -3.09373 1.15789 +VERTEX2 9930 -119.883 -2.09537 1.16123 +VERTEX2 9931 -118.978 -2.5337 -0.410907 +VERTEX2 9932 -118.065 -2.89183 -0.41776 +VERTEX2 9933 -117.114 -3.19784 -0.431993 +VERTEX2 9934 -116.213 -3.68608 -0.427199 +VERTEX2 9935 -115.337 -4.13683 -0.415923 +VERTEX2 9936 -114.936 -3.24999 1.1557 +VERTEX2 9937 -114.545 -2.36608 1.16673 +VERTEX2 9938 -114.149 -1.47994 1.14636 +VERTEX2 9939 -113.815 -0.517612 1.11143 +VERTEX2 9940 -113.328 0.399331 1.10847 +VERTEX2 9941 -114.246 0.848741 2.68025 +VERTEX2 9942 -115.213 1.26668 2.7165 +VERTEX2 9943 -116.142 1.63806 2.70825 +VERTEX2 9944 -116.991 2.04597 2.69658 +VERTEX2 9945 -117.906 2.50108 2.72286 +VERTEX2 9946 -118.361 1.50093 -1.99167 +VERTEX2 9947 -118.799 0.467395 -2.01856 +VERTEX2 9948 -119.208 -0.363331 -2.01314 +VERTEX2 9949 -119.626 -1.27171 -2.0389 +VERTEX2 9950 -120.113 -2.24123 -2.05252 +VERTEX2 9951 -119.23 -2.70465 -0.481905 +VERTEX2 9952 -118.44 -3.20417 -0.497544 +VERTEX2 9953 -117.661 -3.71983 -0.519583 +VERTEX2 9954 -116.766 -4.19731 -0.519563 +VERTEX2 9955 -115.869 -4.65086 -0.529339 +VERTEX2 9956 -115.289 -3.77101 1.00828 +VERTEX2 9957 -114.803 -2.97706 0.995194 +VERTEX2 9958 -114.278 -2.13619 1.00679 +VERTEX2 9959 -113.754 -1.22926 0.978576 +VERTEX2 9960 -113.236 -0.480462 0.974536 +VERTEX2 9961 -114.13 0.0403742 2.51385 +VERTEX2 9962 -115.055 0.663267 2.49462 +VERTEX2 9963 -115.907 1.22613 2.49843 +VERTEX2 9964 -116.603 1.77325 2.51697 +VERTEX2 9965 -117.399 2.44093 2.51813 +VERTEX2 9966 -117.971 1.70098 -2.20697 +VERTEX2 9967 -118.525 0.826003 -2.21572 +VERTEX2 9968 -119.119 0.024998 -2.23607 +VERTEX2 9969 -119.724 -0.676423 -2.21458 +VERTEX2 9970 -120.299 -1.52814 -2.23129 +VERTEX2 9971 -119.479 -2.15754 -0.643099 +VERTEX2 9972 -118.58 -2.78546 -0.62909 +VERTEX2 9973 -117.728 -3.39823 -0.635238 +VERTEX2 9974 -116.999 -4.00366 -0.665793 +VERTEX2 9975 -116.242 -4.59085 -0.601455 +VERTEX2 9976 -115.573 -3.70784 0.983081 +VERTEX2 9977 -115.052 -2.92623 0.968719 +VERTEX2 9978 -114.566 -2.12187 0.991841 +VERTEX2 9979 -113.991 -1.31041 1.01622 +VERTEX2 9980 -113.44 -0.457234 1.03988 +VERTEX2 9981 -114.286 0.0671307 2.61418 +VERTEX2 9982 -115.205 0.554771 2.61969 +VERTEX2 9983 -116.027 1.08787 2.60848 +VERTEX2 9984 -116.831 1.67035 2.64272 +VERTEX2 9985 -117.738 2.10518 2.61843 +VERTEX2 9986 -118.203 1.25094 -2.09909 +VERTEX2 9987 -118.752 0.389027 -2.12476 +VERTEX2 9988 -119.294 -0.55898 -2.12047 +VERTEX2 9989 -119.812 -1.43536 -2.14774 +VERTEX2 9990 -120.388 -2.32302 -2.17611 +VERTEX2 9991 -119.576 -2.86576 -0.574045 +VERTEX2 9992 -118.74 -3.44061 -0.577672 +VERTEX2 9993 -117.874 -4.03335 -0.577067 +VERTEX2 9994 -116.984 -4.53922 -0.591014 +VERTEX2 9995 -116.144 -5.06775 -0.567995 +VERTEX2 9996 -116.715 -5.76917 -2.1293 +VERTEX2 9997 -117.27 -6.59472 -2.10929 +VERTEX2 9998 -117.826 -7.43123 -2.08772 +VERTEX2 9999 -118.333 -8.3691 -2.09906 +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 +EDGE2 100 59 1.08069 -0.0518308 -3.08916 1 0 1 1 0 0 +EDGE2 100 39 1.00289 0.0114224 -3.1693 1 0 1 1 0 0 +EDGE2 100 19 0.941169 0.00648842 -3.14301 1 0 1 1 0 0 +EDGE2 100 40 0.0434694 -0.0711626 -3.1681 1 0 1 1 0 0 +EDGE2 100 1 -0.0395844 -1.07477 -1.54184 1 0 1 1 0 0 +EDGE2 100 21 -0.0119089 -0.930649 -1.56973 1 0 1 1 0 0 +EDGE2 100 41 0.0252901 -1.08523 -1.60047 1 0 1 1 0 0 +EDGE2 100 60 0.0228941 0.0411609 -3.12517 1 0 1 1 0 0 +EDGE2 100 0 0.00043468 -0.0820808 -1.59425 1 0 1 1 0 0 +EDGE2 100 20 -0.0367136 0.0129785 -3.13676 1 0 1 1 0 0 +EDGE2 100 61 -0.00509627 0.949855 1.58568 1 0 1 1 0 0 +EDGE2 100 99 -1.04611 0.0261828 -0.0203352 1 0 1 1 0 0 +EDGE2 101 40 -0.936743 -0.0306572 1.5594 1 0 1 1 0 0 +EDGE2 101 60 -1.01889 0.0163602 1.56356 1 0 1 1 0 0 +EDGE2 101 0 -0.982408 -0.0108775 -3.13026 1 0 1 1 0 0 +EDGE2 101 20 -0.964797 0.0791721 1.58449 1 0 1 1 0 0 +EDGE2 101 62 1.00931 0.0661434 0.000850871 1 0 1 1 0 0 +EDGE2 101 61 0.0383635 0.00863977 -0.00410465 1 0 1 1 0 0 +EDGE2 101 100 -0.951439 0.061399 -1.56335 1 0 1 1 0 0 +EDGE2 102 63 1.06284 -0.0161768 0.0123056 1 0 1 1 0 0 +EDGE2 102 62 -0.0464663 -0.000333223 -0.00933395 1 0 1 1 0 0 +EDGE2 102 61 -1.00955 0.0454655 -0.015992 1 0 1 1 0 0 +EDGE2 102 101 -1.00596 -0.069805 0.0285064 1 0 1 1 0 0 +EDGE2 103 63 -0.0052412 0.0221839 -0.00956066 1 0 1 1 0 0 +EDGE2 103 62 -1.07058 -0.0249889 -0.00156066 1 0 1 1 0 0 +EDGE2 103 64 0.979706 0.00875307 0.00622216 1 0 1 1 0 0 +EDGE2 103 102 -0.931748 0.0291063 -0.00791128 1 0 1 1 0 0 +EDGE2 104 65 1.02059 -0.014294 -0.00507548 1 0 1 1 0 0 +EDGE2 104 63 -0.995401 -0.0265148 0.00999989 1 0 1 1 0 0 +EDGE2 104 64 -0.069825 -0.0781554 -0.0124915 1 0 1 1 0 0 +EDGE2 104 103 -0.94416 0.0173656 -0.00580989 1 0 1 1 0 0 +EDGE2 104 85 0.995603 0.0718037 -3.14198 1 0 1 1 0 0 +EDGE2 105 65 0.0543914 -0.0332879 0.0129441 1 0 1 1 0 0 +EDGE2 105 66 0.0519486 -0.994342 -1.55742 1 0 1 1 0 0 +EDGE2 105 64 -0.943196 -0.0362649 -0.00409268 1 0 1 1 0 0 +EDGE2 105 86 0.0894104 1.00641 1.56174 1 0 1 1 0 0 +EDGE2 105 85 -0.0233592 -0.0525133 -3.11994 1 0 1 1 0 0 +EDGE2 105 104 -1.02195 -0.0283723 0.00407205 1 0 1 1 0 0 +EDGE2 105 84 0.94002 0.0110819 -3.14322 1 0 1 1 0 0 +EDGE2 106 67 1.02553 -0.0151586 -0.0265549 1 0 1 1 0 0 +EDGE2 106 65 -0.928377 0.0149873 1.5799 1 0 1 1 0 0 +EDGE2 106 66 -0.0565539 0.000293982 -0.0109146 1 0 1 1 0 0 +EDGE2 106 85 -1.02622 0.0155542 -1.55916 1 0 1 1 0 0 +EDGE2 106 105 -1.0249 0.0694939 1.58011 1 0 1 1 0 0 +EDGE2 107 68 0.980127 -0.0152544 0.00440178 1 0 1 1 0 0 +EDGE2 107 67 0.00900461 -0.0355515 0.0073384 1 0 1 1 0 0 +EDGE2 107 66 -1.01824 -0.0416522 0.0109807 1 0 1 1 0 0 +EDGE2 107 106 -0.990058 0.00886643 0.0113334 1 0 1 1 0 0 +EDGE2 108 69 1.02795 0.0133817 -0.0131252 1 0 1 1 0 0 +EDGE2 108 68 0.0724491 0.0505481 0.0187089 1 0 1 1 0 0 +EDGE2 108 67 -1.04492 0.00833801 -0.0148086 1 0 1 1 0 0 +EDGE2 108 107 -1.00102 -0.069685 -0.00961719 1 0 1 1 0 0 +EDGE2 109 69 -0.0591468 -0.10349 -0.0178891 1 0 1 1 0 0 +EDGE2 109 70 1.04036 -0.0171813 0.00730525 1 0 1 1 0 0 +EDGE2 109 68 -1.0184 -0.0795368 -0.0041462 1 0 1 1 0 0 +EDGE2 109 108 -0.986294 -0.051136 0.00788157 1 0 1 1 0 0 +EDGE2 110 69 -1.03047 -0.0100597 -0.000634834 1 0 1 1 0 0 +EDGE2 110 71 -0.00481601 1.00192 1.55541 1 0 1 1 0 0 +EDGE2 110 70 -0.0261569 0.0127655 0.0154567 1 0 1 1 0 0 +EDGE2 110 109 -1.00699 0.0570053 -0.00434957 1 0 1 1 0 0 +EDGE2 111 71 -0.0205872 0.0147246 0.0175177 1 0 1 1 0 0 +EDGE2 111 110 -0.994884 -0.00691826 -1.60454 1 0 1 1 0 0 +EDGE2 111 70 -0.898778 0.0227439 -1.61915 1 0 1 1 0 0 +EDGE2 111 72 1.03192 0.0718435 0.0321249 1 0 1 1 0 0 +EDGE2 112 71 -1.10392 -0.0904298 0.000977932 1 0 1 1 0 0 +EDGE2 112 111 -1.06299 0.0133559 0.0132728 1 0 1 1 0 0 +EDGE2 112 73 1.02496 0.0349469 -0.00961043 1 0 1 1 0 0 +EDGE2 112 72 -0.00646788 0.0348682 0.0201003 1 0 1 1 0 0 +EDGE2 113 74 0.97682 0.0163576 0.00987597 1 0 1 1 0 0 +EDGE2 113 73 0.0255101 -0.000958362 0.0341606 1 0 1 1 0 0 +EDGE2 113 72 -0.98796 -0.0937562 0.00616208 1 0 1 1 0 0 +EDGE2 113 112 -0.96479 -0.0765335 -0.0142661 1 0 1 1 0 0 +EDGE2 114 74 0.0241845 -0.0590674 -0.0483164 1 0 1 1 0 0 +EDGE2 114 73 -1.06184 -0.0240754 -0.0248072 1 0 1 1 0 0 +EDGE2 114 75 0.94812 0.012904 -0.0146337 1 0 1 1 0 0 +EDGE2 114 113 -1.05439 -0.0236046 0.0356974 1 0 1 1 0 0 +EDGE2 115 74 -1.02348 0.0153997 0.000778446 1 0 1 1 0 0 +EDGE2 115 75 0.0673953 0.0161745 -0.0209363 1 0 1 1 0 0 +EDGE2 115 114 -1.05982 -0.00631774 -0.00393088 1 0 1 1 0 0 +EDGE2 115 76 -0.0251311 1.00852 1.57845 1 0 1 1 0 0 +EDGE2 116 75 -0.911709 0.0668855 1.59908 1 0 1 1 0 0 +EDGE2 116 115 -1.06028 0.0413526 1.55704 1 0 1 1 0 0 +EDGE2 117 116 -1.04836 0.0137675 -0.00743944 1 0 1 1 0 0 +EDGE2 118 117 -0.95632 -0.130118 0.0164283 1 0 1 1 0 0 +EDGE2 119 118 -0.982604 -0.052321 -0.0116922 1 0 1 1 0 0 +EDGE2 120 119 -0.97268 0.0698862 -0.0119169 1 0 1 1 0 0 +EDGE2 121 120 -1.05245 0.0410851 -1.59706 1 0 1 1 0 0 +EDGE2 122 121 -1.07422 -0.0155499 -0.0520292 1 0 1 1 0 0 +EDGE2 123 122 -1.01002 -0.0231877 0.0130629 1 0 1 1 0 0 +EDGE2 124 123 -0.970452 -0.0955207 -0.0114429 1 0 1 1 0 0 +EDGE2 125 124 -1.04915 0.0492259 0.012681 1 0 1 1 0 0 +EDGE2 126 125 -0.987687 0.08958 1.55662 1 0 1 1 0 0 +EDGE2 127 126 -1.03036 0.059023 0.0151419 1 0 1 1 0 0 +EDGE2 128 127 -1.11517 -0.0334584 -0.0248465 1 0 1 1 0 0 +EDGE2 129 128 -1.03712 0.0163988 -0.0160573 1 0 1 1 0 0 +EDGE2 130 129 -1.0124 -0.0136151 -0.0132044 1 0 1 1 0 0 +EDGE2 131 130 -0.995958 -0.0761961 -1.57788 1 0 1 1 0 0 +EDGE2 132 131 -1.02023 -0.0142924 0.00810813 1 0 1 1 0 0 +EDGE2 133 132 -0.994567 0.0646623 0.0329302 1 0 1 1 0 0 +EDGE2 134 133 -0.919542 0.0383419 -0.0178644 1 0 1 1 0 0 +EDGE2 135 134 -0.994196 -0.0395168 -0.0249434 1 0 1 1 0 0 +EDGE2 136 135 -0.989945 -0.0154472 1.55901 1 0 1 1 0 0 +EDGE2 137 136 -1.03119 -0.0579728 0.0218175 1 0 1 1 0 0 +EDGE2 138 137 -0.995916 -0.00149311 -0.0269163 1 0 1 1 0 0 +EDGE2 139 138 -0.963011 0.0620535 0.0222719 1 0 1 1 0 0 +EDGE2 140 139 -1.06907 -0.108741 0.0103155 1 0 1 1 0 0 +EDGE2 141 140 -1.05765 0.02653 -1.61527 1 0 1 1 0 0 +EDGE2 142 141 -1.02827 0.0417719 -0.0173821 1 0 1 1 0 0 +EDGE2 143 142 -0.991576 -0.0598364 0.009055 1 0 1 1 0 0 +EDGE2 144 143 -0.975219 -0.0325853 -0.00870101 1 0 1 1 0 0 +EDGE2 145 144 -0.933869 -0.0438419 0.0170074 1 0 1 1 0 0 +EDGE2 146 145 -0.907595 -0.0103871 -1.54872 1 0 1 1 0 0 +EDGE2 147 146 -0.984972 -0.0543603 -0.0412944 1 0 1 1 0 0 +EDGE2 148 147 -1.03655 -0.00443375 0.00698945 1 0 1 1 0 0 +EDGE2 149 148 -0.980461 0.00985135 -0.023863 1 0 1 1 0 0 +EDGE2 150 149 -0.963237 0.0537277 -0.00768305 1 0 1 1 0 0 +EDGE2 151 150 -1.03792 -0.0713551 1.58335 1 0 1 1 0 0 +EDGE2 152 151 -0.98401 0.0393048 0.0140481 1 0 1 1 0 0 +EDGE2 153 152 -1.05464 0.0166463 0.0065766 1 0 1 1 0 0 +EDGE2 154 153 -0.921597 -0.0026144 -0.0273713 1 0 1 1 0 0 +EDGE2 155 154 -1.08959 0.00678529 0.00215644 1 0 1 1 0 0 +EDGE2 156 155 -0.982119 -0.0413002 1.58927 1 0 1 1 0 0 +EDGE2 157 156 -0.968007 0.0505392 0.0256908 1 0 1 1 0 0 +EDGE2 158 157 -1.00428 0.0217146 -0.0285127 1 0 1 1 0 0 +EDGE2 159 158 -0.907848 -0.0575078 -0.00431097 1 0 1 1 0 0 +EDGE2 160 159 -1.13983 0.00744323 0.0536954 1 0 1 1 0 0 +EDGE2 161 160 -0.931787 0.00862255 -1.58192 1 0 1 1 0 0 +EDGE2 162 161 -1.07203 0.0636929 -0.00225791 1 0 1 1 0 0 +EDGE2 163 162 -1.09178 0.00106748 0.0200127 1 0 1 1 0 0 +EDGE2 164 163 -0.920722 0.00053977 -0.0204136 1 0 1 1 0 0 +EDGE2 165 164 -0.990861 0.0360437 -0.00630758 1 0 1 1 0 0 +EDGE2 166 165 -1.05273 0.0432619 1.60489 1 0 1 1 0 0 +EDGE2 167 166 -0.998162 -0.0314142 0.0100183 1 0 1 1 0 0 +EDGE2 168 167 -1.01873 -0.0616856 0.0247476 1 0 1 1 0 0 +EDGE2 169 168 -0.959539 0.0464371 0.010262 1 0 1 1 0 0 +EDGE2 170 169 -0.933987 0.00235417 -0.0206218 1 0 1 1 0 0 +EDGE2 171 170 -1.04668 -0.00238392 1.55744 1 0 1 1 0 0 +EDGE2 172 171 -1.03956 -0.0382585 -0.0235603 1 0 1 1 0 0 +EDGE2 173 172 -0.943841 0.0473052 0.00626678 1 0 1 1 0 0 +EDGE2 174 173 -1.05422 -0.060546 -0.0109376 1 0 1 1 0 0 +EDGE2 175 174 -1.02763 0.0801065 -0.0409022 1 0 1 1 0 0 +EDGE2 176 175 -1.04252 -0.067188 -1.57359 1 0 1 1 0 0 +EDGE2 177 176 -1.01383 0.0558712 -0.025645 1 0 1 1 0 0 +EDGE2 178 177 -1.05076 0.050172 -0.0205854 1 0 1 1 0 0 +EDGE2 179 178 -1.05678 0.0158702 0.043573 1 0 1 1 0 0 +EDGE2 180 179 -1.00334 0.0586563 0.0184129 1 0 1 1 0 0 +EDGE2 181 180 -1.04878 -0.09556 -1.59051 1 0 1 1 0 0 +EDGE2 182 181 -0.980983 -0.00188589 -0.0109944 1 0 1 1 0 0 +EDGE2 183 182 -0.942531 0.0575713 0.0115697 1 0 1 1 0 0 +EDGE2 184 183 -0.974943 -0.00890103 0.00502544 1 0 1 1 0 0 +EDGE2 185 184 -0.968407 -0.0650878 -0.0143496 1 0 1 1 0 0 +EDGE2 186 185 -1.04111 0.0943249 -1.56153 1 0 1 1 0 0 +EDGE2 187 186 -0.98931 0.00213439 0.0170415 1 0 1 1 0 0 +EDGE2 188 187 -1.0663 0.0157609 0.00678287 1 0 1 1 0 0 +EDGE2 189 188 -0.997789 -0.0497433 0.000977651 1 0 1 1 0 0 +EDGE2 189 170 1.03535 -0.0404705 -3.16051 1 0 1 1 0 0 +EDGE2 190 171 -0.0062713 1.00493 1.57318 1 0 1 1 0 0 +EDGE2 190 189 -1.03106 -0.0673417 0.00834556 1 0 1 1 0 0 +EDGE2 190 170 0.0386733 -0.0021765 -3.14408 1 0 1 1 0 0 +EDGE2 190 169 0.982889 -0.00536033 -3.14445 1 0 1 1 0 0 +EDGE2 191 171 -0.066673 0.0328661 0.00676244 1 0 1 1 0 0 +EDGE2 191 172 1.0198 -0.000573872 -0.0219424 1 0 1 1 0 0 +EDGE2 191 170 -0.962367 -0.0306386 1.5716 1 0 1 1 0 0 +EDGE2 191 190 -0.940714 0.0456371 -1.56356 1 0 1 1 0 0 +EDGE2 192 171 -1.0273 -0.0316163 0.00859611 1 0 1 1 0 0 +EDGE2 192 173 1.10096 -0.0147177 -0.00971001 1 0 1 1 0 0 +EDGE2 192 172 -0.0536856 -0.0705937 -0.00350799 1 0 1 1 0 0 +EDGE2 192 191 -1.02697 0.0214852 0.0120515 1 0 1 1 0 0 +EDGE2 193 173 0.0372571 0.0153201 -0.0208635 1 0 1 1 0 0 +EDGE2 193 174 1.01233 0.0223852 -0.00101308 1 0 1 1 0 0 +EDGE2 193 172 -0.987408 0.0104096 0.0149688 1 0 1 1 0 0 +EDGE2 193 192 -0.979711 0.00830695 0.00164064 1 0 1 1 0 0 +EDGE2 194 175 1.01286 0.0321114 0.00475335 1 0 1 1 0 0 +EDGE2 194 173 -1.05398 -0.0326516 0.0311913 1 0 1 1 0 0 +EDGE2 194 174 0.0474337 -0.088264 -0.00206216 1 0 1 1 0 0 +EDGE2 194 193 -1.0178 0.0683059 0.00761931 1 0 1 1 0 0 +EDGE2 195 176 -0.00568681 0.907567 1.572 1 0 1 1 0 0 +EDGE2 195 175 -0.0265028 -0.00612291 -0.0174273 1 0 1 1 0 0 +EDGE2 195 174 -0.985193 -0.0522823 0.0126794 1 0 1 1 0 0 +EDGE2 195 194 -1.00986 -0.0376365 0.0140058 1 0 1 1 0 0 +EDGE2 196 177 0.985217 -0.0670152 0.0260563 1 0 1 1 0 0 +EDGE2 196 176 0.0932871 0.0031972 -0.00508134 1 0 1 1 0 0 +EDGE2 196 175 -0.985945 -0.0325072 -1.57716 1 0 1 1 0 0 +EDGE2 196 195 -0.985636 -0.105162 -1.56769 1 0 1 1 0 0 +EDGE2 197 177 -0.0289772 -0.0501712 -0.0116356 1 0 1 1 0 0 +EDGE2 197 178 1.01479 0.0364353 -0.00160233 1 0 1 1 0 0 +EDGE2 197 196 -0.956498 -0.0113133 -0.00612639 1 0 1 1 0 0 +EDGE2 197 176 -1.02106 0.0402531 -0.012531 1 0 1 1 0 0 +EDGE2 198 179 0.975695 -0.0434756 0.0291572 1 0 1 1 0 0 +EDGE2 198 177 -0.95851 0.0351441 -0.0199634 1 0 1 1 0 0 +EDGE2 198 178 0.0147153 -0.0514171 -0.00117641 1 0 1 1 0 0 +EDGE2 198 197 -0.905375 0.0320393 0.00608291 1 0 1 1 0 0 +EDGE2 199 198 -1.02072 0.1152 -0.00268652 1 0 1 1 0 0 +EDGE2 199 180 1.00369 -0.0808598 0.0136348 1 0 1 1 0 0 +EDGE2 199 179 -0.00846365 -0.00203881 -0.0442484 1 0 1 1 0 0 +EDGE2 199 178 -1.00235 -0.0106746 -0.0502239 1 0 1 1 0 0 +EDGE2 200 181 0.0316305 1.03939 1.60591 1 0 1 1 0 0 +EDGE2 200 180 -0.112838 0.0723116 0.0301603 1 0 1 1 0 0 +EDGE2 200 199 -1.00464 0.0533918 -0.00229157 1 0 1 1 0 0 +EDGE2 200 179 -0.990547 0.0124142 0.00377485 1 0 1 1 0 0 +EDGE2 201 181 -0.0631899 0.0626786 -0.00344802 1 0 1 1 0 0 +EDGE2 201 180 -0.928777 0.0229898 -1.54095 1 0 1 1 0 0 +EDGE2 201 200 -0.935974 0.0434445 -1.56446 1 0 1 1 0 0 +EDGE2 201 182 1.02305 0.0620905 -0.00947462 1 0 1 1 0 0 +EDGE2 202 181 -0.98559 -0.0678782 -0.00987621 1 0 1 1 0 0 +EDGE2 202 201 -0.978584 -0.000260867 -0.00880832 1 0 1 1 0 0 +EDGE2 202 182 -0.0373631 0.0144921 -4.34129e-05 1 0 1 1 0 0 +EDGE2 202 183 1.0634 -0.0317077 0.00605129 1 0 1 1 0 0 +EDGE2 203 202 -1.06009 -0.0110486 0.00618185 1 0 1 1 0 0 +EDGE2 203 182 -0.98423 0.0163906 0.0144674 1 0 1 1 0 0 +EDGE2 203 184 0.998633 -0.0400373 -0.000444741 1 0 1 1 0 0 +EDGE2 203 183 -0.0509773 -0.0172349 0.0103442 1 0 1 1 0 0 +EDGE2 204 184 -0.0410936 -0.0161087 0.0105868 1 0 1 1 0 0 +EDGE2 204 183 -1.03795 -0.00342323 -0.00702916 1 0 1 1 0 0 +EDGE2 204 203 -0.976414 0.0177453 0.00961665 1 0 1 1 0 0 +EDGE2 204 185 1.00198 -0.0499327 -0.019744 1 0 1 1 0 0 +EDGE2 205 184 -0.966934 -0.0455641 0.0516675 1 0 1 1 0 0 +EDGE2 205 204 -1.06771 -0.0299423 -0.0322938 1 0 1 1 0 0 +EDGE2 205 185 0.0172648 0.145607 -0.0143245 1 0 1 1 0 0 +EDGE2 205 186 -0.0540167 0.956486 1.55287 1 0 1 1 0 0 +EDGE2 206 205 -1.04106 0.00631527 1.56379 1 0 1 1 0 0 +EDGE2 206 185 -0.920689 -0.141123 1.54969 1 0 1 1 0 0 +EDGE2 207 206 -1.01559 -0.0205942 -0.00658617 1 0 1 1 0 0 +EDGE2 208 207 -1.13857 -0.0209236 0.0358307 1 0 1 1 0 0 +EDGE2 209 208 -1.01263 -0.0680235 -0.0203744 1 0 1 1 0 0 +EDGE2 210 209 -0.971016 -0.0299733 -0.0208929 1 0 1 1 0 0 +EDGE2 211 210 -1.01846 -0.0495481 -1.57097 1 0 1 1 0 0 +EDGE2 212 211 -1.00682 -0.0700291 0.0428093 1 0 1 1 0 0 +EDGE2 213 212 -0.995889 0.0434515 -0.00933083 1 0 1 1 0 0 +EDGE2 214 213 -1.11417 -0.0110297 -0.0102234 1 0 1 1 0 0 +EDGE2 215 214 -0.997737 -0.0302179 0.00145048 1 0 1 1 0 0 +EDGE2 216 215 -1.06941 -0.0541744 -1.58616 1 0 1 1 0 0 +EDGE2 217 216 -0.918235 0.0194373 -0.00297036 1 0 1 1 0 0 +EDGE2 218 217 -0.999078 -0.068366 -0.021023 1 0 1 1 0 0 +EDGE2 219 218 -1.07978 -0.0215746 0.0344501 1 0 1 1 0 0 +EDGE2 220 219 -0.943583 -0.0738134 0.014349 1 0 1 1 0 0 +EDGE2 221 220 -0.939321 0.00971984 -1.57648 1 0 1 1 0 0 +EDGE2 222 221 -0.968802 0.0605812 0.00170538 1 0 1 1 0 0 +EDGE2 223 222 -1.0161 0.00118843 0.00270329 1 0 1 1 0 0 +EDGE2 224 205 0.948493 -0.0230449 -3.15329 1 0 1 1 0 0 +EDGE2 224 223 -1.00416 -0.0273871 0.00388937 1 0 1 1 0 0 +EDGE2 224 185 1.0389 0.0861245 -3.14681 1 0 1 1 0 0 +EDGE2 225 206 0.00587987 0.990648 1.58715 1 0 1 1 0 0 +EDGE2 225 205 0.111332 0.00296517 -3.20679 1 0 1 1 0 0 +EDGE2 225 184 1.06616 -0.0446999 -3.15684 1 0 1 1 0 0 +EDGE2 225 204 0.953396 -0.0373338 -3.19154 1 0 1 1 0 0 +EDGE2 225 224 -1.0142 0.0313331 0.0218264 1 0 1 1 0 0 +EDGE2 225 185 -0.0208037 0.0363499 -3.12198 1 0 1 1 0 0 +EDGE2 225 186 -0.0223746 -0.996794 -1.58359 1 0 1 1 0 0 +EDGE2 226 206 0.0887687 0.0153149 -0.00688865 1 0 1 1 0 0 +EDGE2 226 207 1.05185 -0.0473262 -0.00721103 1 0 1 1 0 0 +EDGE2 226 205 -0.943987 -0.0335662 1.58524 1 0 1 1 0 0 +EDGE2 226 225 -1.05062 -0.0703611 -1.53931 1 0 1 1 0 0 +EDGE2 226 185 -1.02155 -0.0434301 1.59061 1 0 1 1 0 0 +EDGE2 227 208 1.00002 0.0080054 0.0171411 1 0 1 1 0 0 +EDGE2 227 206 -1.03412 -0.0293964 -0.011109 1 0 1 1 0 0 +EDGE2 227 207 0.0361208 -0.0222127 0.0158397 1 0 1 1 0 0 +EDGE2 227 226 -1.13309 0.0166796 -0.0541074 1 0 1 1 0 0 +EDGE2 228 209 0.988608 0.0572882 0.0448466 1 0 1 1 0 0 +EDGE2 228 208 0.0287596 -0.0120215 0.00651466 1 0 1 1 0 0 +EDGE2 228 207 -1.06988 0.00953783 0.015785 1 0 1 1 0 0 +EDGE2 228 227 -0.997221 -0.00444556 0.0072668 1 0 1 1 0 0 +EDGE2 229 228 -0.97076 0.0103909 0.00744336 1 0 1 1 0 0 +EDGE2 229 210 0.907425 -0.0108908 0.00871227 1 0 1 1 0 0 +EDGE2 229 209 0.0678344 0.0149309 0.00915945 1 0 1 1 0 0 +EDGE2 229 208 -0.960102 0.0636842 -0.00719953 1 0 1 1 0 0 +EDGE2 230 210 -0.0368707 0.0641839 0.00445594 1 0 1 1 0 0 +EDGE2 230 209 -0.997215 -0.00468012 0.0048537 1 0 1 1 0 0 +EDGE2 230 229 -0.948788 0.0610043 -0.0358728 1 0 1 1 0 0 +EDGE2 230 211 0.0190307 0.982278 1.5721 1 0 1 1 0 0 +EDGE2 231 210 -0.925208 -0.0691993 1.55098 1 0 1 1 0 0 +EDGE2 231 230 -0.969448 -0.0399664 1.54905 1 0 1 1 0 0 +EDGE2 232 231 -1.0027 0.0385524 -0.023788 1 0 1 1 0 0 +EDGE2 233 232 -1.00871 -0.120173 -0.0106568 1 0 1 1 0 0 +EDGE2 234 233 -0.972536 0.0585087 0.0167705 1 0 1 1 0 0 +EDGE2 235 234 -0.990329 -0.00707986 -0.0131082 1 0 1 1 0 0 +EDGE2 236 235 -0.959518 -0.0519359 -1.62451 1 0 1 1 0 0 +EDGE2 237 236 -1.03543 0.0645172 -9.45212e-05 1 0 1 1 0 0 +EDGE2 238 237 -1.01129 0.0686573 0.00162668 1 0 1 1 0 0 +EDGE2 239 238 -1.01294 0.0199432 0.0077918 1 0 1 1 0 0 +EDGE2 240 239 -0.980688 0.0785878 -0.0246631 1 0 1 1 0 0 +EDGE2 241 240 -1.0686 -0.0621547 -1.5682 1 0 1 1 0 0 +EDGE2 242 241 -1.0764 0.0293462 -0.00285832 1 0 1 1 0 0 +EDGE2 243 242 -0.892695 0.00173381 -0.00185319 1 0 1 1 0 0 +EDGE2 244 243 -0.967948 0.0271711 0.00949542 1 0 1 1 0 0 +EDGE2 245 244 -1.11763 0.0115506 0.0182625 1 0 1 1 0 0 +EDGE2 246 245 -0.957183 0.0163728 -1.57739 1 0 1 1 0 0 +EDGE2 247 246 -1.03748 -0.0103326 -0.0277392 1 0 1 1 0 0 +EDGE2 248 247 -1.10262 -0.0887786 0.0100498 1 0 1 1 0 0 +EDGE2 249 248 -1.02023 -0.0560576 -0.0189541 1 0 1 1 0 0 +EDGE2 249 210 1.03499 -0.0111154 -3.13944 1 0 1 1 0 0 +EDGE2 249 230 1.02141 -0.0304403 -3.15897 1 0 1 1 0 0 +EDGE2 250 231 0.0149354 1.01743 1.59735 1 0 1 1 0 0 +EDGE2 250 249 -1.00181 0.0845188 0.00661741 1 0 1 1 0 0 +EDGE2 250 210 0.0119669 0.0154293 -3.16778 1 0 1 1 0 0 +EDGE2 250 230 0.0259334 0.105739 -3.14393 1 0 1 1 0 0 +EDGE2 250 209 1.02724 -0.0440954 -3.17573 1 0 1 1 0 0 +EDGE2 250 229 1.01281 -0.08787 -3.10588 1 0 1 1 0 0 +EDGE2 250 211 0.0258623 -1.04557 -1.56419 1 0 1 1 0 0 +EDGE2 251 231 0.0329668 0.0116104 0.0371017 1 0 1 1 0 0 +EDGE2 251 232 1.07213 -0.0387592 0.0129117 1 0 1 1 0 0 +EDGE2 251 210 -0.971202 0.015651 1.58791 1 0 1 1 0 0 +EDGE2 251 230 -0.939574 0.0525149 1.60058 1 0 1 1 0 0 +EDGE2 251 250 -0.988965 -0.0444915 -1.59945 1 0 1 1 0 0 +EDGE2 252 231 -0.950215 -0.11724 -0.0158416 1 0 1 1 0 0 +EDGE2 252 233 1.00764 -0.0143232 0.0172258 1 0 1 1 0 0 +EDGE2 252 232 0.012579 -0.00835223 0.0157861 1 0 1 1 0 0 +EDGE2 252 251 -0.932464 -0.00991313 0.0172123 1 0 1 1 0 0 +EDGE2 253 234 1.02374 0.0506844 0.0304058 1 0 1 1 0 0 +EDGE2 253 233 0.0524403 -0.0709678 -0.0100597 1 0 1 1 0 0 +EDGE2 253 232 -0.957406 -0.0472771 0.0095734 1 0 1 1 0 0 +EDGE2 253 252 -1.07259 -0.0132071 -0.0320015 1 0 1 1 0 0 +EDGE2 254 235 1.01283 -0.0100882 -0.0126825 1 0 1 1 0 0 +EDGE2 254 253 -0.995641 -0.0807042 0.0189131 1 0 1 1 0 0 +EDGE2 254 234 0.0539201 0.0760808 0.0129775 1 0 1 1 0 0 +EDGE2 254 233 -1.03412 0.0279614 -0.00386827 1 0 1 1 0 0 +EDGE2 255 236 0.000867593 0.967132 1.56496 1 0 1 1 0 0 +EDGE2 255 235 -0.0386367 -0.0445356 0.00546656 1 0 1 1 0 0 +EDGE2 255 234 -1.03332 0.0743762 0.0113581 1 0 1 1 0 0 +EDGE2 255 254 -0.996568 0.0879913 0.0108378 1 0 1 1 0 0 +EDGE2 256 235 -1.02585 0.0152894 1.58934 1 0 1 1 0 0 +EDGE2 256 255 -1.06724 -0.0274454 1.58138 1 0 1 1 0 0 +EDGE2 257 256 -1.0348 0.0664905 -0.00699347 1 0 1 1 0 0 +EDGE2 258 257 -1.0104 -0.0474854 -0.000285067 1 0 1 1 0 0 +EDGE2 259 258 -0.936043 0.0469796 0.0135325 1 0 1 1 0 0 +EDGE2 259 180 0.933242 0.0264844 -3.1783 1 0 1 1 0 0 +EDGE2 259 200 0.970732 0.0632373 -3.1441 1 0 1 1 0 0 +EDGE2 260 181 -0.0186429 -1.02795 -1.55346 1 0 1 1 0 0 +EDGE2 260 259 -0.960586 -0.0873867 -0.00254107 1 0 1 1 0 0 +EDGE2 260 180 0.0388058 -0.015754 -3.13253 1 0 1 1 0 0 +EDGE2 260 200 -0.0663094 -0.0274282 -3.14012 1 0 1 1 0 0 +EDGE2 260 201 -0.067914 -1.01313 -1.57938 1 0 1 1 0 0 +EDGE2 260 199 0.968053 0.0670202 -3.11935 1 0 1 1 0 0 +EDGE2 260 179 0.981526 0.020732 -3.13716 1 0 1 1 0 0 +EDGE2 261 260 -0.97771 -0.0120342 -1.5368 1 0 1 1 0 0 +EDGE2 261 180 -0.98886 0.0866971 1.59592 1 0 1 1 0 0 +EDGE2 261 200 -0.989408 -0.0185871 1.57069 1 0 1 1 0 0 +EDGE2 262 261 -0.995051 -0.0128923 0.0215409 1 0 1 1 0 0 +EDGE2 263 262 -1.08017 0.104448 0.00196789 1 0 1 1 0 0 +EDGE2 264 263 -0.996187 0.0243206 -0.0188593 1 0 1 1 0 0 +EDGE2 265 264 -1.01424 0.0210914 -0.0192807 1 0 1 1 0 0 +EDGE2 266 265 -0.991202 0.0517045 1.56968 1 0 1 1 0 0 +EDGE2 267 266 -1.06701 -0.00427451 0.0423659 1 0 1 1 0 0 +EDGE2 268 267 -0.966821 -0.00862653 0.0105035 1 0 1 1 0 0 +EDGE2 269 268 -0.983899 -0.0620666 -0.031424 1 0 1 1 0 0 +EDGE2 270 269 -1.05732 0.0133452 0.0411046 1 0 1 1 0 0 +EDGE2 271 270 -0.978235 -0.00814872 -1.58104 1 0 1 1 0 0 +EDGE2 272 271 -0.928061 0.0193911 0.02364 1 0 1 1 0 0 +EDGE2 273 272 -1.04978 0.0341459 0.0157441 1 0 1 1 0 0 +EDGE2 274 273 -1.00565 -0.00115033 0.00283776 1 0 1 1 0 0 +EDGE2 275 274 -0.931256 0.0562279 0.0117425 1 0 1 1 0 0 +EDGE2 276 275 -1.0689 -0.0647808 -1.55895 1 0 1 1 0 0 +EDGE2 277 276 -0.958975 0.033834 0.00722896 1 0 1 1 0 0 +EDGE2 278 277 -0.96274 0.0235955 0.0219001 1 0 1 1 0 0 +EDGE2 279 278 -1.03937 0.00834043 0.00987821 1 0 1 1 0 0 +EDGE2 280 279 -1.0858 0.0383681 0.0154221 1 0 1 1 0 0 +EDGE2 281 280 -0.983883 0.080184 -1.56751 1 0 1 1 0 0 +EDGE2 282 281 -1.0417 0.082632 -0.0495892 1 0 1 1 0 0 +EDGE2 283 282 -1.02361 -0.0672171 0.0283386 1 0 1 1 0 0 +EDGE2 284 283 -0.993906 0.0296932 -0.0424879 1 0 1 1 0 0 +EDGE2 284 265 0.997532 0.055114 -3.11528 1 0 1 1 0 0 +EDGE2 285 284 -1.08097 0.122903 -0.0138224 1 0 1 1 0 0 +EDGE2 285 265 0.0233629 0.0340438 -3.14102 1 0 1 1 0 0 +EDGE2 285 264 1.03221 0.0361538 -3.17221 1 0 1 1 0 0 +EDGE2 285 266 0.051391 0.963301 1.57958 1 0 1 1 0 0 +EDGE2 286 265 -0.987556 -0.0854594 1.5753 1 0 1 1 0 0 +EDGE2 286 285 -1.03622 0.0556515 -1.59248 1 0 1 1 0 0 +EDGE2 286 266 0.0224708 0.0284241 0.0144112 1 0 1 1 0 0 +EDGE2 286 267 0.984305 0.00297155 -0.0301031 1 0 1 1 0 0 +EDGE2 287 266 -0.986472 -0.0258566 0.0211849 1 0 1 1 0 0 +EDGE2 287 286 -1.09165 0.0420513 -0.000807378 1 0 1 1 0 0 +EDGE2 287 267 0.0234069 -0.0554699 -0.00959709 1 0 1 1 0 0 +EDGE2 287 268 0.982102 -0.0543667 0.0217029 1 0 1 1 0 0 +EDGE2 288 287 -1.02756 -0.0347395 -0.00301245 1 0 1 1 0 0 +EDGE2 288 267 -1.00235 -0.0218035 -0.0011993 1 0 1 1 0 0 +EDGE2 288 269 0.951188 0.0104908 -0.0134197 1 0 1 1 0 0 +EDGE2 288 268 -0.00180451 -0.0153683 0.0341868 1 0 1 1 0 0 +EDGE2 289 269 0.0272258 0.0112407 -0.000770791 1 0 1 1 0 0 +EDGE2 289 268 -1.02344 0.00722098 -0.0298748 1 0 1 1 0 0 +EDGE2 289 288 -1.06998 -0.0613446 -0.0130324 1 0 1 1 0 0 +EDGE2 289 270 1.01959 -0.096506 0.0267945 1 0 1 1 0 0 +EDGE2 290 269 -1.01026 0.040431 -0.0297377 1 0 1 1 0 0 +EDGE2 290 289 -1.04994 0.0422135 -0.00794733 1 0 1 1 0 0 +EDGE2 290 271 -0.0389291 1.00913 1.59656 1 0 1 1 0 0 +EDGE2 290 270 0.0313199 0.0559041 -0.00696959 1 0 1 1 0 0 +EDGE2 291 272 0.887269 -0.00513299 0.0146811 1 0 1 1 0 0 +EDGE2 291 271 0.0193715 -0.00590938 0.0301476 1 0 1 1 0 0 +EDGE2 291 270 -1.04391 -0.00242755 -1.58628 1 0 1 1 0 0 +EDGE2 291 290 -1.09121 0.0502871 -1.56782 1 0 1 1 0 0 +EDGE2 292 291 -0.999759 -0.0211813 0.0354644 1 0 1 1 0 0 +EDGE2 292 273 1.03036 0.0511473 -0.0126404 1 0 1 1 0 0 +EDGE2 292 272 -0.0157977 -0.0271064 0.00872994 1 0 1 1 0 0 +EDGE2 292 271 -0.996396 -0.0321903 0.00165275 1 0 1 1 0 0 +EDGE2 293 274 1.04037 -0.0149463 -0.0131203 1 0 1 1 0 0 +EDGE2 293 273 0.0481857 -0.0775935 0.00522886 1 0 1 1 0 0 +EDGE2 293 292 -0.974797 -0.0705898 0.0126775 1 0 1 1 0 0 +EDGE2 293 272 -1.03932 -0.0267565 -0.0117164 1 0 1 1 0 0 +EDGE2 294 275 0.980519 -0.06543 -0.0172807 1 0 1 1 0 0 +EDGE2 294 274 0.0689434 -0.0136945 0.0148159 1 0 1 1 0 0 +EDGE2 294 273 -0.990998 0.00128949 0.0179971 1 0 1 1 0 0 +EDGE2 294 293 -1.04861 -0.0174061 -0.00569592 1 0 1 1 0 0 +EDGE2 295 276 -0.00562866 1.03868 1.55219 1 0 1 1 0 0 +EDGE2 295 275 -0.0166408 0.063865 -0.00327191 1 0 1 1 0 0 +EDGE2 295 294 -0.943583 0.0100689 0.0118891 1 0 1 1 0 0 +EDGE2 295 274 -0.934709 0.0351985 0.0149186 1 0 1 1 0 0 +EDGE2 296 277 0.998313 0.0228161 -0.00865922 1 0 1 1 0 0 +EDGE2 296 276 0.0684484 0.00536779 -0.0124965 1 0 1 1 0 0 +EDGE2 296 275 -1.03411 0.110379 -1.57708 1 0 1 1 0 0 +EDGE2 296 295 -0.917205 0.0103311 -1.57031 1 0 1 1 0 0 +EDGE2 297 278 0.978852 0.0017514 0.0195057 1 0 1 1 0 0 +EDGE2 297 277 0.0737525 0.00120277 -0.0189685 1 0 1 1 0 0 +EDGE2 297 296 -1.02704 -0.0785475 -0.00482635 1 0 1 1 0 0 +EDGE2 297 276 -1.07338 0.0468344 0.030906 1 0 1 1 0 0 +EDGE2 298 279 0.947647 0.0257525 0.0039442 1 0 1 1 0 0 +EDGE2 298 278 -0.0741288 -0.0127093 0.00238615 1 0 1 1 0 0 +EDGE2 298 277 -1.02749 -0.0296649 0.013374 1 0 1 1 0 0 +EDGE2 298 297 -1.05576 0.0627335 0.0467369 1 0 1 1 0 0 +EDGE2 299 280 1.01126 -0.00417437 -0.0233659 1 0 1 1 0 0 +EDGE2 299 279 -0.0280618 -0.108907 0.0131081 1 0 1 1 0 0 +EDGE2 299 298 -1.04242 0.0358523 0.0217988 1 0 1 1 0 0 +EDGE2 299 278 -1.09331 -0.030841 0.00968742 1 0 1 1 0 0 +EDGE2 300 280 0.0219769 0.020666 0.0157306 1 0 1 1 0 0 +EDGE2 300 281 -0.0412772 1.02 1.57021 1 0 1 1 0 0 +EDGE2 300 299 -1.02038 0.0431214 -0.0228237 1 0 1 1 0 0 +EDGE2 300 279 -1.06756 0.0140752 0.023178 1 0 1 1 0 0 +EDGE2 301 300 -1.00455 -0.00438501 1.58529 1 0 1 1 0 0 +EDGE2 301 280 -0.99337 0.0608578 1.56392 1 0 1 1 0 0 +EDGE2 302 301 -0.983609 -0.0955402 -0.013492 1 0 1 1 0 0 +EDGE2 303 302 -0.931797 -0.000540591 0.0191314 1 0 1 1 0 0 +EDGE2 304 303 -1.02079 0.0470907 -0.0185606 1 0 1 1 0 0 +EDGE2 305 304 -0.957944 -0.0125841 -0.0144769 1 0 1 1 0 0 +EDGE2 306 305 -1.04676 0.046431 1.54188 1 0 1 1 0 0 +EDGE2 307 306 -1.04168 -0.0123813 0.0483307 1 0 1 1 0 0 +EDGE2 308 307 -1.04785 0.0560082 0.0201868 1 0 1 1 0 0 +EDGE2 309 308 -1.00568 0.0699202 -0.0277523 1 0 1 1 0 0 +EDGE2 310 309 -0.99312 -0.0202349 0.00578647 1 0 1 1 0 0 +EDGE2 311 310 -0.951967 0.016229 1.57099 1 0 1 1 0 0 +EDGE2 312 311 -1.01346 0.0992812 -0.0134632 1 0 1 1 0 0 +EDGE2 313 312 -1.05588 0.00434816 0.00969748 1 0 1 1 0 0 +EDGE2 314 313 -0.985718 0.0938375 0.00937384 1 0 1 1 0 0 +EDGE2 314 275 0.997855 0.0082961 -3.14015 1 0 1 1 0 0 +EDGE2 314 295 0.999757 0.0647507 -3.15954 1 0 1 1 0 0 +EDGE2 315 314 -1.01291 -0.0286651 0.00585106 1 0 1 1 0 0 +EDGE2 315 296 -0.0606997 -1.00209 -1.55264 1 0 1 1 0 0 +EDGE2 315 276 -0.0634739 -0.981278 -1.5733 1 0 1 1 0 0 +EDGE2 315 275 -0.0617715 -0.0307556 -3.10594 1 0 1 1 0 0 +EDGE2 315 295 -0.0101674 0.0273863 -3.11625 1 0 1 1 0 0 +EDGE2 315 294 1.02967 0.0408111 -3.17912 1 0 1 1 0 0 +EDGE2 315 274 1.04323 -0.00589104 -3.12935 1 0 1 1 0 0 +EDGE2 316 315 -1.00802 -0.0354128 -1.56564 1 0 1 1 0 0 +EDGE2 316 275 -0.991259 0.09735 1.54275 1 0 1 1 0 0 +EDGE2 316 295 -1.10293 -0.0569836 1.55237 1 0 1 1 0 0 +EDGE2 317 316 -1.05607 0.0242599 -0.0264643 1 0 1 1 0 0 +EDGE2 318 317 -1.04449 0.0413409 -0.00157362 1 0 1 1 0 0 +EDGE2 319 318 -1.11341 -0.00169401 -0.00631167 1 0 1 1 0 0 +EDGE2 319 140 0.985414 -0.02363 -3.1861 1 0 1 1 0 0 +EDGE2 320 141 -0.0351018 -0.995731 -1.5855 1 0 1 1 0 0 +EDGE2 320 319 -0.916618 0.00743586 0.00346085 1 0 1 1 0 0 +EDGE2 320 140 0.0550555 0.0871761 -3.17551 1 0 1 1 0 0 +EDGE2 320 139 1.09049 0.0137958 -3.17065 1 0 1 1 0 0 +EDGE2 321 141 -0.00692556 -0.108443 0.0158813 1 0 1 1 0 0 +EDGE2 321 320 -0.970383 0.0406494 1.60498 1 0 1 1 0 0 +EDGE2 321 140 -1.00251 0.0392201 -1.57829 1 0 1 1 0 0 +EDGE2 321 142 0.980676 -0.00947623 0.0131915 1 0 1 1 0 0 +EDGE2 322 141 -1.0076 -0.0755406 -0.0530275 1 0 1 1 0 0 +EDGE2 322 321 -0.887534 -0.0328373 -0.0137991 1 0 1 1 0 0 +EDGE2 322 142 -0.0933923 0.00253918 -0.00924363 1 0 1 1 0 0 +EDGE2 322 143 0.940437 0.0341087 0.0163465 1 0 1 1 0 0 +EDGE2 323 322 -1.03941 0.0690387 -0.0500789 1 0 1 1 0 0 +EDGE2 323 142 -1.02173 -0.00750776 -0.0179098 1 0 1 1 0 0 +EDGE2 323 143 -0.0438918 -0.0753381 0.0242969 1 0 1 1 0 0 +EDGE2 323 144 1.01537 0.0738324 0.0161831 1 0 1 1 0 0 +EDGE2 324 323 -0.957244 -0.0659361 -0.0426594 1 0 1 1 0 0 +EDGE2 324 143 -1.03345 0.0200791 0.0289815 1 0 1 1 0 0 +EDGE2 324 145 0.944403 -0.0172994 -0.0111807 1 0 1 1 0 0 +EDGE2 324 144 -0.0359069 0.00413178 0.0255016 1 0 1 1 0 0 +EDGE2 325 146 -0.01496 0.983688 1.57773 1 0 1 1 0 0 +EDGE2 325 145 -0.0109934 0.00201261 0.0154798 1 0 1 1 0 0 +EDGE2 325 144 -1.03602 -0.0167051 0.0026791 1 0 1 1 0 0 +EDGE2 325 324 -1.05993 0.0230482 0.0019306 1 0 1 1 0 0 +EDGE2 326 146 -0.0314091 0.0136968 -0.0149681 1 0 1 1 0 0 +EDGE2 326 145 -0.96241 0.0208298 -1.58365 1 0 1 1 0 0 +EDGE2 326 325 -1.16188 0.0371223 -1.55627 1 0 1 1 0 0 +EDGE2 326 147 0.979322 -0.0182966 0.0178328 1 0 1 1 0 0 +EDGE2 327 146 -1.04449 -0.0228833 0.0180027 1 0 1 1 0 0 +EDGE2 327 326 -0.938473 -0.0623385 -0.00510423 1 0 1 1 0 0 +EDGE2 327 147 -0.0528446 0.0136248 0.0108673 1 0 1 1 0 0 +EDGE2 327 148 1.04131 0.00217537 0.0363522 1 0 1 1 0 0 +EDGE2 328 149 1.03568 0.0763655 -0.0156121 1 0 1 1 0 0 +EDGE2 328 147 -0.942284 0.0303029 0.00764426 1 0 1 1 0 0 +EDGE2 328 327 -1.02434 -0.00991295 0.0300128 1 0 1 1 0 0 +EDGE2 328 148 0.0123132 -0.0271774 -0.00811093 1 0 1 1 0 0 +EDGE2 329 149 -0.0198851 0.0329202 0.00309058 1 0 1 1 0 0 +EDGE2 329 328 -1.03502 0.121245 -0.00683712 1 0 1 1 0 0 +EDGE2 329 148 -1.0584 -0.0108499 -0.0149064 1 0 1 1 0 0 +EDGE2 329 150 0.978032 0.0192173 -0.000825661 1 0 1 1 0 0 +EDGE2 330 149 -1.00878 0.0178434 -0.0114125 1 0 1 1 0 0 +EDGE2 330 329 -0.972702 0.0343284 -0.00462873 1 0 1 1 0 0 +EDGE2 330 150 0.00238211 -0.0747704 0.0142853 1 0 1 1 0 0 +EDGE2 330 151 -0.0884636 -0.972508 -1.55956 1 0 1 1 0 0 +EDGE2 331 150 -0.960109 0.0194813 -1.58192 1 0 1 1 0 0 +EDGE2 331 330 -1.07232 0.0198178 -1.5987 1 0 1 1 0 0 +EDGE2 332 331 -0.960055 -0.066207 0.0382957 1 0 1 1 0 0 +EDGE2 333 332 -1.04408 -0.00871841 -0.00288772 1 0 1 1 0 0 +EDGE2 334 333 -0.986677 0.0947757 0.00433876 1 0 1 1 0 0 +EDGE2 334 135 0.974813 0.0334172 -3.10785 1 0 1 1 0 0 +EDGE2 335 334 -0.973856 -0.0491621 -0.00017424 1 0 1 1 0 0 +EDGE2 335 136 -0.101665 1.10777 1.56092 1 0 1 1 0 0 +EDGE2 335 134 0.997497 0.0181477 -3.10418 1 0 1 1 0 0 +EDGE2 335 135 -0.0750477 0.0879573 -3.16388 1 0 1 1 0 0 +EDGE2 336 137 1.05601 -0.0744381 0.0081098 1 0 1 1 0 0 +EDGE2 336 335 -1.09524 0.0587924 -1.58397 1 0 1 1 0 0 +EDGE2 336 136 0.0343041 -0.106787 0.00975101 1 0 1 1 0 0 +EDGE2 336 135 -1.03941 0.0719973 1.5321 1 0 1 1 0 0 +EDGE2 337 138 1.04537 0.00832492 0.00692063 1 0 1 1 0 0 +EDGE2 337 137 -0.00694995 0.0665459 -0.0113134 1 0 1 1 0 0 +EDGE2 337 336 -1.02171 0.0876837 0.00628278 1 0 1 1 0 0 +EDGE2 337 136 -1.00001 -0.00626509 -0.000986147 1 0 1 1 0 0 +EDGE2 338 139 0.99748 -0.0576202 0.0275536 1 0 1 1 0 0 +EDGE2 338 138 0.0851323 0.00875204 0.00359782 1 0 1 1 0 0 +EDGE2 338 137 -0.987765 0.0100882 0.0236557 1 0 1 1 0 0 +EDGE2 338 337 -1.02737 0.0199432 -0.00134054 1 0 1 1 0 0 +EDGE2 339 320 0.944519 0.0412678 -3.16056 1 0 1 1 0 0 +EDGE2 339 140 1.09737 -0.101809 -0.0245942 1 0 1 1 0 0 +EDGE2 339 139 -0.0497592 -0.0225318 -0.0109802 1 0 1 1 0 0 +EDGE2 339 138 -0.936329 -0.117928 -0.00356715 1 0 1 1 0 0 +EDGE2 339 338 -0.901996 -0.0181948 -0.00325328 1 0 1 1 0 0 +EDGE2 340 141 0.0347745 0.99591 1.57966 1 0 1 1 0 0 +EDGE2 340 320 -0.00726923 -0.0214086 -3.16084 1 0 1 1 0 0 +EDGE2 340 319 0.963882 0.0153726 -3.13961 1 0 1 1 0 0 +EDGE2 340 140 0.0376022 0.0258391 0.00846876 1 0 1 1 0 0 +EDGE2 340 321 0.0442825 0.998575 1.56057 1 0 1 1 0 0 +EDGE2 340 339 -1.02888 -0.000629263 0.0147428 1 0 1 1 0 0 +EDGE2 340 139 -0.996673 0.0100372 -0.0188653 1 0 1 1 0 0 +EDGE2 341 141 -0.0204612 -0.00684656 0.0235285 1 0 1 1 0 0 +EDGE2 341 320 -0.953831 0.00958725 1.55211 1 0 1 1 0 0 +EDGE2 341 340 -1.00831 0.0597172 -1.55984 1 0 1 1 0 0 +EDGE2 341 140 -1.05212 -0.0572095 -1.58293 1 0 1 1 0 0 +EDGE2 341 321 -0.0433574 -0.0358681 -0.0165584 1 0 1 1 0 0 +EDGE2 341 322 0.997416 0.0182547 0.0126865 1 0 1 1 0 0 +EDGE2 341 142 1.05229 -0.0282593 0.0315944 1 0 1 1 0 0 +EDGE2 342 141 -1.03748 0.0409462 -0.00828443 1 0 1 1 0 0 +EDGE2 342 341 -0.933354 -0.0541994 0.000705127 1 0 1 1 0 0 +EDGE2 342 321 -0.959753 0.00756849 0.019942 1 0 1 1 0 0 +EDGE2 342 322 0.0523934 -0.0262233 0.0241918 1 0 1 1 0 0 +EDGE2 342 142 -0.0180132 0.00366763 0.00234914 1 0 1 1 0 0 +EDGE2 342 323 0.981047 0.0216761 -0.000179713 1 0 1 1 0 0 +EDGE2 342 143 1.01676 0.0713003 0.00835713 1 0 1 1 0 0 +EDGE2 343 322 -1.05765 0.0845533 0.0193414 1 0 1 1 0 0 +EDGE2 343 342 -0.96719 0.0397655 0.0515457 1 0 1 1 0 0 +EDGE2 343 142 -1.00005 0.0362951 0.000189687 1 0 1 1 0 0 +EDGE2 343 323 0.0276855 0.00137953 0.00984422 1 0 1 1 0 0 +EDGE2 343 143 0.00215755 0.0281899 0.00235529 1 0 1 1 0 0 +EDGE2 343 144 1.03089 0.00384179 0.0450656 1 0 1 1 0 0 +EDGE2 343 324 1.10736 0.0680282 -0.00177145 1 0 1 1 0 0 +EDGE2 344 323 -0.912318 0.0980387 0.00308913 1 0 1 1 0 0 +EDGE2 344 343 -1.03864 -0.00764176 -0.046609 1 0 1 1 0 0 +EDGE2 344 143 -0.992085 0.0337518 -0.0346263 1 0 1 1 0 0 +EDGE2 344 145 1.03539 -0.0792257 -0.0162485 1 0 1 1 0 0 +EDGE2 344 144 0.0228107 0.00801491 -0.00497929 1 0 1 1 0 0 +EDGE2 344 324 0.0335927 0.0218513 -0.00631766 1 0 1 1 0 0 +EDGE2 344 325 1.01494 -0.0592503 -0.0393743 1 0 1 1 0 0 +EDGE2 345 146 -0.0561875 1.03904 1.54852 1 0 1 1 0 0 +EDGE2 345 145 0.0321541 0.00850545 -0.000485773 1 0 1 1 0 0 +EDGE2 345 144 -0.966716 -0.0126625 0.0102553 1 0 1 1 0 0 +EDGE2 345 324 -0.938704 0.000678928 0.0066252 1 0 1 1 0 0 +EDGE2 345 344 -0.937717 0.0485604 0.0348205 1 0 1 1 0 0 +EDGE2 345 325 -0.0593075 -0.0321066 0.0139647 1 0 1 1 0 0 +EDGE2 345 326 0.0240737 1.03969 1.57582 1 0 1 1 0 0 +EDGE2 346 146 -0.0404803 0.0149644 0.0167848 1 0 1 1 0 0 +EDGE2 346 145 -1.02157 -0.0152007 -1.55049 1 0 1 1 0 0 +EDGE2 346 325 -1.06425 0.0415451 -1.57956 1 0 1 1 0 0 +EDGE2 346 345 -0.976201 -0.0110188 -1.6132 1 0 1 1 0 0 +EDGE2 346 326 -0.0818485 0.00263273 -0.00987404 1 0 1 1 0 0 +EDGE2 346 147 0.944304 -0.0785785 0.027773 1 0 1 1 0 0 +EDGE2 346 327 1.04324 -0.00367249 0.0190487 1 0 1 1 0 0 +EDGE2 347 146 -1.06337 -0.0589152 -0.0209029 1 0 1 1 0 0 +EDGE2 347 346 -0.969295 0.0255736 -0.00700173 1 0 1 1 0 0 +EDGE2 347 326 -0.977572 0.0327162 0.00167604 1 0 1 1 0 0 +EDGE2 347 328 1.02218 0.046691 -0.0237782 1 0 1 1 0 0 +EDGE2 347 147 -0.00406939 -0.00253152 -0.0186197 1 0 1 1 0 0 +EDGE2 347 327 0.041444 0.0266505 0.00320486 1 0 1 1 0 0 +EDGE2 347 148 1.03603 -0.0139795 0.00545512 1 0 1 1 0 0 +EDGE2 348 149 1.01118 0.0304839 -0.00304702 1 0 1 1 0 0 +EDGE2 348 328 -0.105139 -0.0664387 0.00372921 1 0 1 1 0 0 +EDGE2 348 147 -1.07808 -0.0335986 -0.0488093 1 0 1 1 0 0 +EDGE2 348 347 -0.99897 -0.069158 0.00123947 1 0 1 1 0 0 +EDGE2 348 327 -1.0809 0.0520311 -0.00370497 1 0 1 1 0 0 +EDGE2 348 148 -0.0408177 0.0226147 0.0561296 1 0 1 1 0 0 +EDGE2 348 329 1.00681 -0.112233 -0.036587 1 0 1 1 0 0 +EDGE2 349 149 -0.0682059 0.00828495 0.0226214 1 0 1 1 0 0 +EDGE2 349 328 -1.01888 -0.036682 0.0457323 1 0 1 1 0 0 +EDGE2 349 348 -0.954991 0.0884074 -0.0239535 1 0 1 1 0 0 +EDGE2 349 148 -1.00734 0.012494 0.0332182 1 0 1 1 0 0 +EDGE2 349 329 -0.00604733 0.0309048 0.0135306 1 0 1 1 0 0 +EDGE2 349 150 1.01787 0.00225654 0.0202799 1 0 1 1 0 0 +EDGE2 349 330 1.03753 0.013359 0.0209852 1 0 1 1 0 0 +EDGE2 350 149 -0.976861 0.00534047 0.00577345 1 0 1 1 0 0 +EDGE2 350 349 -1.0454 -0.0677234 -0.0034093 1 0 1 1 0 0 +EDGE2 350 329 -1.05177 -0.0191826 -0.00802369 1 0 1 1 0 0 +EDGE2 350 150 -0.0268314 -0.0701461 0.0130155 1 0 1 1 0 0 +EDGE2 350 331 -0.0629594 1.01945 1.55341 1 0 1 1 0 0 +EDGE2 350 330 -0.0519318 0.0312789 0.0118928 1 0 1 1 0 0 +EDGE2 350 151 -0.0135905 -1.0535 -1.56467 1 0 1 1 0 0 +EDGE2 351 150 -0.996949 -0.0257942 1.56956 1 0 1 1 0 0 +EDGE2 351 350 -1.05026 0.0322168 1.57729 1 0 1 1 0 0 +EDGE2 351 330 -0.973476 0.0389424 1.55412 1 0 1 1 0 0 +EDGE2 351 151 0.0117874 -0.0380698 -0.00487154 1 0 1 1 0 0 +EDGE2 351 152 0.920963 0.0317809 -0.00262497 1 0 1 1 0 0 +EDGE2 352 151 -0.967231 -0.0110297 -0.00739797 1 0 1 1 0 0 +EDGE2 352 351 -0.895923 0.0208458 0.00609653 1 0 1 1 0 0 +EDGE2 352 152 -0.0370196 0.0877795 -0.0203233 1 0 1 1 0 0 +EDGE2 352 153 0.992413 -0.0347192 0.0298697 1 0 1 1 0 0 +EDGE2 353 152 -1.00405 0.0826277 0.00188123 1 0 1 1 0 0 +EDGE2 353 352 -0.950188 -0.0582715 0.0198057 1 0 1 1 0 0 +EDGE2 353 153 0.00705353 -0.0323646 -0.00339335 1 0 1 1 0 0 +EDGE2 353 154 0.996013 0.100394 -0.0140073 1 0 1 1 0 0 +EDGE2 354 353 -0.951646 0.000487337 -0.00206691 1 0 1 1 0 0 +EDGE2 354 153 -0.983527 -0.0101225 0.0172418 1 0 1 1 0 0 +EDGE2 354 154 -0.0648475 0.0844686 -0.0061613 1 0 1 1 0 0 +EDGE2 354 155 0.937738 -0.0163485 0.00629075 1 0 1 1 0 0 +EDGE2 355 156 0.0278 -0.941368 -1.58824 1 0 1 1 0 0 +EDGE2 355 154 -1.07828 -0.0392567 -0.034315 1 0 1 1 0 0 +EDGE2 355 354 -1.02488 0.103705 0.00565897 1 0 1 1 0 0 +EDGE2 355 155 0.0718132 0.0989572 -0.0034898 1 0 1 1 0 0 +EDGE2 356 355 -0.924034 0.000898823 -1.55676 1 0 1 1 0 0 +EDGE2 356 155 -0.993433 0.067184 -1.55047 1 0 1 1 0 0 +EDGE2 357 356 -0.989553 0.0222139 0.0314838 1 0 1 1 0 0 +EDGE2 358 357 -1.00913 0.00670377 -0.00172544 1 0 1 1 0 0 +EDGE2 359 358 -1.00241 0.0844381 0.00649201 1 0 1 1 0 0 +EDGE2 360 359 -0.971081 0.0414071 -0.0292567 1 0 1 1 0 0 +EDGE2 361 360 -0.995405 0.0911711 -1.56488 1 0 1 1 0 0 +EDGE2 362 361 -0.85653 -0.00351448 0.00624414 1 0 1 1 0 0 +EDGE2 363 362 -0.985225 0.0104997 5.48901e-05 1 0 1 1 0 0 +EDGE2 364 363 -1.00975 -0.00503642 -0.0194504 1 0 1 1 0 0 +EDGE2 365 364 -1.00038 -0.0174668 0.0277579 1 0 1 1 0 0 +EDGE2 366 365 -1.03705 -0.0438083 -1.5895 1 0 1 1 0 0 +EDGE2 367 366 -0.957106 0.0692229 0.0145349 1 0 1 1 0 0 +EDGE2 368 367 -1.03525 0.0592008 -0.0293899 1 0 1 1 0 0 +EDGE2 369 150 1.02724 0.0240689 -3.11527 1 0 1 1 0 0 +EDGE2 369 350 0.977025 0.0302814 -3.12328 1 0 1 1 0 0 +EDGE2 369 330 0.986311 0.00475614 -3.16452 1 0 1 1 0 0 +EDGE2 369 368 -0.992414 -0.136385 -0.00034604 1 0 1 1 0 0 +EDGE2 370 149 1.09863 0.0140768 -3.14156 1 0 1 1 0 0 +EDGE2 370 349 1.03748 -0.0714949 -3.13086 1 0 1 1 0 0 +EDGE2 370 329 1.04033 0.00145687 -3.15534 1 0 1 1 0 0 +EDGE2 370 150 -0.058043 0.047886 -3.15723 1 0 1 1 0 0 +EDGE2 370 350 -0.000477295 0.0712746 -3.11498 1 0 1 1 0 0 +EDGE2 370 331 -0.028781 -0.930131 -1.57076 1 0 1 1 0 0 +EDGE2 370 330 -0.0457607 0.0153778 -3.14173 1 0 1 1 0 0 +EDGE2 370 151 -0.00182855 1.05103 1.56559 1 0 1 1 0 0 +EDGE2 370 351 0.0303107 0.91779 1.58761 1 0 1 1 0 0 +EDGE2 370 369 -0.941208 0.00374797 -0.0168333 1 0 1 1 0 0 +EDGE2 371 150 -0.995769 -0.00164086 1.5841 1 0 1 1 0 0 +EDGE2 371 350 -0.990687 0.0162268 1.57364 1 0 1 1 0 0 +EDGE2 371 370 -0.992139 0.0875104 -1.58452 1 0 1 1 0 0 +EDGE2 371 330 -0.915135 -0.0573733 1.57229 1 0 1 1 0 0 +EDGE2 371 151 0.00613103 0.0164656 -0.00955548 1 0 1 1 0 0 +EDGE2 371 351 0.00997757 0.0607516 0.0252572 1 0 1 1 0 0 +EDGE2 371 152 0.94855 -0.00106908 0.0441771 1 0 1 1 0 0 +EDGE2 371 352 0.981372 0.00661065 -0.002385 1 0 1 1 0 0 +EDGE2 372 353 1.04874 0.00275383 -0.0212458 1 0 1 1 0 0 +EDGE2 372 151 -1.09577 -0.0136383 -0.0280671 1 0 1 1 0 0 +EDGE2 372 371 -0.989506 0.00334604 -0.0157864 1 0 1 1 0 0 +EDGE2 372 351 -0.987243 -0.0433526 0.0136213 1 0 1 1 0 0 +EDGE2 372 152 -0.0369599 0.0663101 -0.00940498 1 0 1 1 0 0 +EDGE2 372 352 0.0202793 0.044036 -0.0379086 1 0 1 1 0 0 +EDGE2 372 153 0.9849 -0.0465307 -0.00867665 1 0 1 1 0 0 +EDGE2 373 353 0.06041 0.0409817 0.0178866 1 0 1 1 0 0 +EDGE2 373 152 -1.0306 -0.00622101 0.00747908 1 0 1 1 0 0 +EDGE2 373 352 -0.92901 0.0204433 0.0277354 1 0 1 1 0 0 +EDGE2 373 372 -0.967763 -0.00676442 0.0293944 1 0 1 1 0 0 +EDGE2 373 153 -0.0390506 0.0204675 0.0494969 1 0 1 1 0 0 +EDGE2 373 154 1.02389 0.0583921 -0.00951179 1 0 1 1 0 0 +EDGE2 373 354 0.995704 -0.0377234 -0.00470782 1 0 1 1 0 0 +EDGE2 374 353 -0.949283 -0.00733675 -0.0114433 1 0 1 1 0 0 +EDGE2 374 373 -1.02063 -0.0189697 -0.0113492 1 0 1 1 0 0 +EDGE2 374 153 -0.96191 0.0134475 0.0218271 1 0 1 1 0 0 +EDGE2 374 355 1.00487 0.0258561 0.00328116 1 0 1 1 0 0 +EDGE2 374 154 0.0328216 0.0591291 0.003098 1 0 1 1 0 0 +EDGE2 374 354 0.020052 -0.0756487 0.00617022 1 0 1 1 0 0 +EDGE2 374 155 1.03414 0.0353636 -0.00325564 1 0 1 1 0 0 +EDGE2 375 156 0.00234572 -0.998589 -1.54844 1 0 1 1 0 0 +EDGE2 375 355 0.0473998 0.0408317 0.000485781 1 0 1 1 0 0 +EDGE2 375 154 -1.0097 -0.00471492 -0.0579508 1 0 1 1 0 0 +EDGE2 375 354 -0.966546 -0.00754192 0.0174466 1 0 1 1 0 0 +EDGE2 375 374 -1.03845 0.0485415 -0.0122152 1 0 1 1 0 0 +EDGE2 375 356 0.0494355 1.00023 1.59567 1 0 1 1 0 0 +EDGE2 375 155 0.0676031 -0.0484884 -6.61484e-05 1 0 1 1 0 0 +EDGE2 376 157 1.12555 0.0418621 -0.00569736 1 0 1 1 0 0 +EDGE2 376 156 -0.0710516 0.000353013 0.00260649 1 0 1 1 0 0 +EDGE2 376 355 -1.00044 0.0509481 1.59829 1 0 1 1 0 0 +EDGE2 376 375 -0.934833 -0.00943084 1.55943 1 0 1 1 0 0 +EDGE2 376 155 -1.0068 0.0637036 1.57172 1 0 1 1 0 0 +EDGE2 377 158 1.08265 0.0107028 -0.0183686 1 0 1 1 0 0 +EDGE2 377 157 -0.043601 -0.00663302 0.00732368 1 0 1 1 0 0 +EDGE2 377 156 -0.957511 -0.0214601 -0.0065632 1 0 1 1 0 0 +EDGE2 377 376 -0.992438 0.0274093 0.0182011 1 0 1 1 0 0 +EDGE2 378 159 1.04462 0.0297478 -0.00528026 1 0 1 1 0 0 +EDGE2 378 158 0.0239728 0.0367374 -0.000437012 1 0 1 1 0 0 +EDGE2 378 157 -1.05469 -0.0240482 -0.00828235 1 0 1 1 0 0 +EDGE2 378 377 -1.00914 -0.0209924 -0.025891 1 0 1 1 0 0 +EDGE2 379 160 1.02213 -0.0642854 -0.0153511 1 0 1 1 0 0 +EDGE2 379 378 -0.913692 -0.155683 0.0344828 1 0 1 1 0 0 +EDGE2 379 159 0.053886 0.0936253 0.00792927 1 0 1 1 0 0 +EDGE2 379 158 -0.924317 -0.0316439 -0.0045375 1 0 1 1 0 0 +EDGE2 380 161 -0.0327835 1.00669 1.55491 1 0 1 1 0 0 +EDGE2 380 160 -0.0505177 0.0813357 0.0120065 1 0 1 1 0 0 +EDGE2 380 159 -1.0458 0.00557244 -0.00104859 1 0 1 1 0 0 +EDGE2 380 379 -0.94741 -0.0215038 -0.0133243 1 0 1 1 0 0 +EDGE2 381 380 -0.981683 0.0530795 1.56173 1 0 1 1 0 0 +EDGE2 381 160 -1.05167 0.116331 1.5904 1 0 1 1 0 0 +EDGE2 382 381 -0.950499 -0.00770337 0.00227682 1 0 1 1 0 0 +EDGE2 383 382 -0.877725 -0.01241 -0.00664537 1 0 1 1 0 0 +EDGE2 384 145 0.953264 -0.0954296 -3.12083 1 0 1 1 0 0 +EDGE2 384 325 1.00269 -0.0374514 -3.16579 1 0 1 1 0 0 +EDGE2 384 345 0.976224 0.00943881 -3.17002 1 0 1 1 0 0 +EDGE2 384 383 -0.921704 0.0164399 0.0020997 1 0 1 1 0 0 +EDGE2 385 146 0.0736793 -1.0307 -1.56248 1 0 1 1 0 0 +EDGE2 385 145 -0.0287288 0.0418859 -3.14081 1 0 1 1 0 0 +EDGE2 385 144 0.994597 -0.00217362 -3.135 1 0 1 1 0 0 +EDGE2 385 324 1.02065 0.084161 -3.16687 1 0 1 1 0 0 +EDGE2 385 344 1.04314 -0.0190637 -3.1098 1 0 1 1 0 0 +EDGE2 385 325 0.0558943 -0.0217213 -3.11998 1 0 1 1 0 0 +EDGE2 385 345 0.00400304 -0.0795216 -3.14342 1 0 1 1 0 0 +EDGE2 385 384 -0.937222 -0.049328 0.0194805 1 0 1 1 0 0 +EDGE2 385 346 -0.0173012 -1.01034 -1.56834 1 0 1 1 0 0 +EDGE2 385 326 -0.0404751 -1.04363 -1.56053 1 0 1 1 0 0 +EDGE2 386 145 -1.02541 -0.0334882 1.59454 1 0 1 1 0 0 +EDGE2 386 385 -1.05425 -0.0728097 -1.55538 1 0 1 1 0 0 +EDGE2 386 325 -0.977568 -0.0424052 1.58704 1 0 1 1 0 0 +EDGE2 386 345 -0.91585 -0.0088905 1.58359 1 0 1 1 0 0 +EDGE2 387 386 -0.991249 0.0530245 0.0138695 1 0 1 1 0 0 +EDGE2 388 387 -0.985075 -0.000350093 0.0203779 1 0 1 1 0 0 +EDGE2 389 270 0.96207 -0.0488674 -3.1361 1 0 1 1 0 0 +EDGE2 389 290 0.990992 -0.0372821 -3.1266 1 0 1 1 0 0 +EDGE2 389 388 -0.991371 0.0481841 0.00614784 1 0 1 1 0 0 +EDGE2 390 291 0.0139418 -0.993395 -1.56786 1 0 1 1 0 0 +EDGE2 390 269 0.988069 0.114884 -3.13025 1 0 1 1 0 0 +EDGE2 390 289 1.03555 0.0220209 -3.14591 1 0 1 1 0 0 +EDGE2 390 271 -0.00725568 -1.01953 -1.56742 1 0 1 1 0 0 +EDGE2 390 270 0.0153693 0.027026 -3.1414 1 0 1 1 0 0 +EDGE2 390 290 -0.0397651 0.00710437 -3.12226 1 0 1 1 0 0 +EDGE2 390 389 -1.01488 -0.0552564 -0.0221756 1 0 1 1 0 0 +EDGE2 391 291 0.00143168 -0.0420049 0.00955847 1 0 1 1 0 0 +EDGE2 391 292 1.08159 -0.0181252 0.00874637 1 0 1 1 0 0 +EDGE2 391 272 0.965937 -0.0189699 -0.0287797 1 0 1 1 0 0 +EDGE2 391 271 0.00733498 -0.0755732 0.00749357 1 0 1 1 0 0 +EDGE2 391 270 -1.00297 -0.056683 -1.55761 1 0 1 1 0 0 +EDGE2 391 290 -0.942902 -0.0476502 -1.5751 1 0 1 1 0 0 +EDGE2 391 390 -0.937487 -0.0179805 1.57593 1 0 1 1 0 0 +EDGE2 392 291 -0.987978 -0.0253143 0.0127575 1 0 1 1 0 0 +EDGE2 392 273 1.0282 -0.0394227 0.0123766 1 0 1 1 0 0 +EDGE2 392 293 0.99784 -0.0301356 0.038116 1 0 1 1 0 0 +EDGE2 392 292 -0.00248789 0.0632831 -0.00270278 1 0 1 1 0 0 +EDGE2 392 272 0.0610707 -0.00360162 0.0181424 1 0 1 1 0 0 +EDGE2 392 391 -0.958686 -0.0984037 -0.0314874 1 0 1 1 0 0 +EDGE2 392 271 -1.0025 -0.0475829 0.0450633 1 0 1 1 0 0 +EDGE2 393 294 0.969538 -0.0141526 -0.0132133 1 0 1 1 0 0 +EDGE2 393 274 1.06757 0.00774765 -0.0253892 1 0 1 1 0 0 +EDGE2 393 273 -0.00368196 -0.000783919 -0.0260801 1 0 1 1 0 0 +EDGE2 393 293 0.0230733 0.00879816 -0.0304785 1 0 1 1 0 0 +EDGE2 393 292 -1.01183 -0.0906332 -0.0243033 1 0 1 1 0 0 +EDGE2 393 392 -1.0015 -0.00876961 -0.0186097 1 0 1 1 0 0 +EDGE2 393 272 -1.01257 -0.00366692 -0.0187185 1 0 1 1 0 0 +EDGE2 394 393 -0.963741 -0.0262988 -0.0347051 1 0 1 1 0 0 +EDGE2 394 315 0.932492 -0.0378351 -3.16234 1 0 1 1 0 0 +EDGE2 394 275 1.02288 -0.0282636 -0.0356328 1 0 1 1 0 0 +EDGE2 394 295 0.992465 0.11558 0.0417468 1 0 1 1 0 0 +EDGE2 394 294 0.0673369 0.0455908 -0.011152 1 0 1 1 0 0 +EDGE2 394 274 -0.0258534 -0.0276761 -0.00690655 1 0 1 1 0 0 +EDGE2 394 273 -0.958047 0.0750083 -0.0110016 1 0 1 1 0 0 +EDGE2 394 293 -0.99065 0.0142468 0.0151325 1 0 1 1 0 0 +EDGE2 395 314 0.990476 -0.0596721 -3.14332 1 0 1 1 0 0 +EDGE2 395 296 -0.0982759 0.956943 1.53902 1 0 1 1 0 0 +EDGE2 395 276 0.0459252 1.06409 1.55013 1 0 1 1 0 0 +EDGE2 395 315 -0.000110456 -8.84263e-05 -3.14365 1 0 1 1 0 0 +EDGE2 395 275 0.00305935 -0.00865493 -0.0340535 1 0 1 1 0 0 +EDGE2 395 295 0.0122091 -0.102376 0.0274174 1 0 1 1 0 0 +EDGE2 395 294 -0.973697 -0.00738927 0.0333712 1 0 1 1 0 0 +EDGE2 395 394 -1.03117 0.0611183 -0.0067367 1 0 1 1 0 0 +EDGE2 395 274 -1.01239 -0.0537659 0.00386308 1 0 1 1 0 0 +EDGE2 395 316 -0.00770119 -1.01791 -1.56759 1 0 1 1 0 0 +EDGE2 396 277 1.03807 0.037971 -0.00933334 1 0 1 1 0 0 +EDGE2 396 297 1.00057 -0.0453342 -0.00907743 1 0 1 1 0 0 +EDGE2 396 296 0.118825 -0.108928 0.015271 1 0 1 1 0 0 +EDGE2 396 276 0.0238572 -0.0524425 -0.0121166 1 0 1 1 0 0 +EDGE2 396 315 -1.00848 0.0101279 1.55233 1 0 1 1 0 0 +EDGE2 396 395 -0.985861 -0.0187637 -1.5586 1 0 1 1 0 0 +EDGE2 396 275 -0.984653 0.0116726 -1.56425 1 0 1 1 0 0 +EDGE2 396 295 -0.956267 -0.035933 -1.59047 1 0 1 1 0 0 +EDGE2 397 298 0.965909 0.0394194 -0.0277357 1 0 1 1 0 0 +EDGE2 397 278 1.00364 -0.0758156 0.0294329 1 0 1 1 0 0 +EDGE2 397 277 -0.0420576 0.00782648 0.0166643 1 0 1 1 0 0 +EDGE2 397 297 -0.0759503 -0.0527378 0.0155635 1 0 1 1 0 0 +EDGE2 397 296 -0.985929 0.0231642 0.000433182 1 0 1 1 0 0 +EDGE2 397 396 -0.93422 -0.0258763 -0.00815082 1 0 1 1 0 0 +EDGE2 397 276 -0.969872 -0.0137338 0.0477529 1 0 1 1 0 0 +EDGE2 398 299 0.969004 -0.0489374 0.00162505 1 0 1 1 0 0 +EDGE2 398 279 0.950668 -0.0310186 -0.0402736 1 0 1 1 0 0 +EDGE2 398 298 0.0222554 -0.022611 0.00440518 1 0 1 1 0 0 +EDGE2 398 278 0.067119 -0.118914 -0.00302677 1 0 1 1 0 0 +EDGE2 398 277 -1.01946 0.0805687 -0.0134116 1 0 1 1 0 0 +EDGE2 398 297 -1.02483 -0.0172231 -0.042952 1 0 1 1 0 0 +EDGE2 398 397 -0.987823 -0.0286812 -0.0176777 1 0 1 1 0 0 +EDGE2 399 300 1.05642 -0.0467444 0.0143938 1 0 1 1 0 0 +EDGE2 399 280 1.05891 -0.0235513 0.00838631 1 0 1 1 0 0 +EDGE2 399 299 0.0603464 0.000595639 0.00845742 1 0 1 1 0 0 +EDGE2 399 279 -0.0662669 -0.0504379 -0.00148319 1 0 1 1 0 0 +EDGE2 399 298 -0.964816 0.0822421 -0.0167203 1 0 1 1 0 0 +EDGE2 399 398 -0.99516 -0.0532776 -0.0196761 1 0 1 1 0 0 +EDGE2 399 278 -1.01657 -0.0206543 -0.00732686 1 0 1 1 0 0 +EDGE2 400 301 -0.00769194 -1.07002 -1.52345 1 0 1 1 0 0 +EDGE2 400 300 -0.0588222 -0.027229 0.018227 1 0 1 1 0 0 +EDGE2 400 280 -0.0514894 -0.0590976 -0.0194785 1 0 1 1 0 0 +EDGE2 400 281 -0.00631447 0.992758 1.57559 1 0 1 1 0 0 +EDGE2 400 299 -1.0863 0.0215277 0.00410338 1 0 1 1 0 0 +EDGE2 400 399 -0.988756 0.0709737 -0.00664373 1 0 1 1 0 0 +EDGE2 400 279 -1.04386 0.063806 -0.0147586 1 0 1 1 0 0 +EDGE2 401 300 -1.02039 -0.117326 -1.55106 1 0 1 1 0 0 +EDGE2 401 400 -0.996828 -0.0485079 -1.54549 1 0 1 1 0 0 +EDGE2 401 280 -0.924051 -0.102498 -1.54676 1 0 1 1 0 0 +EDGE2 401 281 -0.00830927 -0.0302051 0.0175871 1 0 1 1 0 0 +EDGE2 401 282 1.03595 0.0226039 0.00271425 1 0 1 1 0 0 +EDGE2 402 401 -1.06241 -0.0172928 -0.0420496 1 0 1 1 0 0 +EDGE2 402 281 -1.00809 0.059007 0.0314411 1 0 1 1 0 0 +EDGE2 402 282 0.109501 -0.0508234 0.000640207 1 0 1 1 0 0 +EDGE2 402 283 0.979544 0.00597726 0.00377608 1 0 1 1 0 0 +EDGE2 403 402 -0.975695 -0.0193793 0.0323733 1 0 1 1 0 0 +EDGE2 403 282 -1.04533 -0.0731718 -0.0218801 1 0 1 1 0 0 +EDGE2 403 283 0.0701018 0.0140047 0.0212082 1 0 1 1 0 0 +EDGE2 403 284 0.92545 0.0144972 -0.0403596 1 0 1 1 0 0 +EDGE2 404 403 -1.04233 0.0419434 -0.0280921 1 0 1 1 0 0 +EDGE2 404 283 -0.973112 -0.0152834 0.0214656 1 0 1 1 0 0 +EDGE2 404 284 0.0295888 0.029396 -0.0211266 1 0 1 1 0 0 +EDGE2 404 265 1.03593 -0.0455672 -3.15484 1 0 1 1 0 0 +EDGE2 404 285 1.0287 0.0555355 -0.00126819 1 0 1 1 0 0 +EDGE2 405 404 -0.961626 -0.0283054 0.0048833 1 0 1 1 0 0 +EDGE2 405 284 -0.989718 -0.0588675 0.0262578 1 0 1 1 0 0 +EDGE2 405 265 -0.000434581 0.0815604 -3.1312 1 0 1 1 0 0 +EDGE2 405 285 0.0844701 0.0174903 0.0266762 1 0 1 1 0 0 +EDGE2 405 264 1.07777 0.0697797 -3.13994 1 0 1 1 0 0 +EDGE2 405 266 0.0639083 1.02362 1.58372 1 0 1 1 0 0 +EDGE2 405 286 0.0013909 1.04571 1.57553 1 0 1 1 0 0 +EDGE2 406 265 -0.93499 0.111172 1.57294 1 0 1 1 0 0 +EDGE2 406 405 -1.04006 -0.0534447 -1.54906 1 0 1 1 0 0 +EDGE2 406 285 -1.03347 -0.001634 -1.58179 1 0 1 1 0 0 +EDGE2 406 266 -0.0792315 -0.0129972 0.00780597 1 0 1 1 0 0 +EDGE2 406 286 -0.0763399 -0.0672026 -0.0343862 1 0 1 1 0 0 +EDGE2 406 287 0.946716 0.00630445 -0.00487778 1 0 1 1 0 0 +EDGE2 406 267 1.04409 -0.0143213 0.0072643 1 0 1 1 0 0 +EDGE2 407 266 -0.976063 -0.0220643 -0.0100104 1 0 1 1 0 0 +EDGE2 407 286 -0.992783 -0.0227853 -0.00567047 1 0 1 1 0 0 +EDGE2 407 406 -1.00749 -0.0281447 -0.0382447 1 0 1 1 0 0 +EDGE2 407 287 0.0356504 -0.055142 0.00861543 1 0 1 1 0 0 +EDGE2 407 267 0.0251154 0.0671007 -0.0245662 1 0 1 1 0 0 +EDGE2 407 268 1.02945 0.0857917 0.0160796 1 0 1 1 0 0 +EDGE2 407 288 1.04303 -0.0305692 0.000871149 1 0 1 1 0 0 +EDGE2 408 287 -0.95197 0.010936 -0.0151983 1 0 1 1 0 0 +EDGE2 408 407 -1.00367 0.0866996 -0.00630845 1 0 1 1 0 0 +EDGE2 408 267 -0.946167 0.0366834 -0.0210108 1 0 1 1 0 0 +EDGE2 408 269 1.03767 -0.0435419 -0.000416206 1 0 1 1 0 0 +EDGE2 408 268 -0.037118 0.0371986 0.020695 1 0 1 1 0 0 +EDGE2 408 288 -0.0404548 0.0517828 0.0137088 1 0 1 1 0 0 +EDGE2 408 289 1.00428 -0.0166745 0.00872011 1 0 1 1 0 0 +EDGE2 409 269 0.0320748 0.0448723 -0.00428824 1 0 1 1 0 0 +EDGE2 409 268 -0.985953 -0.0173314 0.0270149 1 0 1 1 0 0 +EDGE2 409 408 -1.00629 -0.0647396 0.0229831 1 0 1 1 0 0 +EDGE2 409 288 -0.987059 0.0727707 -0.0198976 1 0 1 1 0 0 +EDGE2 409 289 -0.0105562 -0.0570495 -0.00602649 1 0 1 1 0 0 +EDGE2 409 270 0.926415 -0.0230645 0.0250978 1 0 1 1 0 0 +EDGE2 409 290 0.958863 -0.0457894 0.0115589 1 0 1 1 0 0 +EDGE2 409 390 0.951704 -0.0112857 -3.12417 1 0 1 1 0 0 +EDGE2 410 291 -0.00817069 1.03715 1.55268 1 0 1 1 0 0 +EDGE2 410 391 -0.11099 0.930196 1.59229 1 0 1 1 0 0 +EDGE2 410 269 -1.02226 -0.057801 -0.00369232 1 0 1 1 0 0 +EDGE2 410 409 -0.967249 0.0771033 -0.00626901 1 0 1 1 0 0 +EDGE2 410 289 -0.998982 0.0124947 -0.00279266 1 0 1 1 0 0 +EDGE2 410 271 -0.0941339 0.999089 1.57488 1 0 1 1 0 0 +EDGE2 410 270 -0.0335496 -0.0103659 0.0177094 1 0 1 1 0 0 +EDGE2 410 290 0.00763521 -0.0265706 -0.0211899 1 0 1 1 0 0 +EDGE2 410 390 0.0224986 0.00141077 -3.13901 1 0 1 1 0 0 +EDGE2 410 389 0.941409 -0.0241968 -3.11166 1 0 1 1 0 0 +EDGE2 411 291 0.0638323 -0.0370818 0.00972919 1 0 1 1 0 0 +EDGE2 411 292 1.01343 0.0604151 -0.0135533 1 0 1 1 0 0 +EDGE2 411 392 0.970575 -0.0408039 -0.00355515 1 0 1 1 0 0 +EDGE2 411 272 0.960021 -0.0761845 0.0374773 1 0 1 1 0 0 +EDGE2 411 391 0.0746437 0.0734977 -0.00742588 1 0 1 1 0 0 +EDGE2 411 410 -0.985818 0.011017 -1.54929 1 0 1 1 0 0 +EDGE2 411 271 0.00734958 0.0263961 0.0163084 1 0 1 1 0 0 +EDGE2 411 270 -1.03614 0.0569313 -1.56637 1 0 1 1 0 0 +EDGE2 411 290 -1.05664 -0.0450869 -1.56302 1 0 1 1 0 0 +EDGE2 411 390 -0.956331 0.0379009 1.56015 1 0 1 1 0 0 +EDGE2 412 291 -0.982371 0.0668362 0.00933447 1 0 1 1 0 0 +EDGE2 412 393 1.02941 -0.00649172 -0.0126765 1 0 1 1 0 0 +EDGE2 412 273 1.03903 -0.00926258 -0.0280532 1 0 1 1 0 0 +EDGE2 412 293 0.992544 0.0510683 -0.00898946 1 0 1 1 0 0 +EDGE2 412 292 -0.0281516 -0.00856799 0.044246 1 0 1 1 0 0 +EDGE2 412 392 -0.0994081 -0.0218833 0.0178213 1 0 1 1 0 0 +EDGE2 412 272 0.0257364 0.0410079 0.00554306 1 0 1 1 0 0 +EDGE2 412 411 -0.944627 0.00409748 0.00516683 1 0 1 1 0 0 +EDGE2 412 391 -0.978216 0.0328626 -0.00168747 1 0 1 1 0 0 +EDGE2 412 271 -0.997363 -0.092394 0.00347311 1 0 1 1 0 0 +EDGE2 413 393 -0.0209156 -0.00629927 -0.046631 1 0 1 1 0 0 +EDGE2 413 294 0.932864 0.0323975 -0.00951648 1 0 1 1 0 0 +EDGE2 413 394 0.963944 -0.00108685 0.00299376 1 0 1 1 0 0 +EDGE2 413 274 1.04437 -0.0182894 -0.0153135 1 0 1 1 0 0 +EDGE2 413 273 0.13751 -0.0298871 -0.0339254 1 0 1 1 0 0 +EDGE2 413 293 0.00385683 -0.155331 0.0205533 1 0 1 1 0 0 +EDGE2 413 292 -0.999877 -0.0385669 0.00325125 1 0 1 1 0 0 +EDGE2 413 392 -1.09881 -0.0412981 0.0110831 1 0 1 1 0 0 +EDGE2 413 412 -1.03872 0.0113587 -0.022807 1 0 1 1 0 0 +EDGE2 413 272 -1.03476 0.112331 -0.0305 1 0 1 1 0 0 +EDGE2 414 393 -0.953012 -0.0674484 0.0105198 1 0 1 1 0 0 +EDGE2 414 315 1.0019 -0.102071 -3.19994 1 0 1 1 0 0 +EDGE2 414 395 0.977541 -0.0706743 0.0274817 1 0 1 1 0 0 +EDGE2 414 275 0.999539 0.0883581 -0.0256082 1 0 1 1 0 0 +EDGE2 414 295 0.983793 0.0341411 -0.0194073 1 0 1 1 0 0 +EDGE2 414 294 -0.0265015 -0.0281529 0.0581888 1 0 1 1 0 0 +EDGE2 414 394 0.0260455 0.0259189 0.0135711 1 0 1 1 0 0 +EDGE2 414 274 -0.0557284 0.0470036 0.0216889 1 0 1 1 0 0 +EDGE2 414 413 -1.013 0.00908506 -0.0125998 1 0 1 1 0 0 +EDGE2 414 273 -1.01609 -0.0639205 -0.0351377 1 0 1 1 0 0 +EDGE2 414 293 -1.10821 -0.0646373 -0.0137291 1 0 1 1 0 0 +EDGE2 415 314 1.0321 -0.0125572 -3.14208 1 0 1 1 0 0 +EDGE2 415 296 0.0201452 1.06607 1.57959 1 0 1 1 0 0 +EDGE2 415 396 0.00443425 0.965096 1.58422 1 0 1 1 0 0 +EDGE2 415 276 -0.0160463 1.03444 1.56369 1 0 1 1 0 0 +EDGE2 415 315 0.0459492 0.0355525 -3.15915 1 0 1 1 0 0 +EDGE2 415 395 0.00306508 0.0260917 0.0288994 1 0 1 1 0 0 +EDGE2 415 275 0.0508721 -0.00248724 -0.0249373 1 0 1 1 0 0 +EDGE2 415 295 0.118033 -0.0684033 0.00816212 1 0 1 1 0 0 +EDGE2 415 294 -0.971544 0.0381312 0.00988649 1 0 1 1 0 0 +EDGE2 415 394 -1.10066 -0.153602 -0.0146702 1 0 1 1 0 0 +EDGE2 415 414 -0.960781 -0.0417653 0.0306394 1 0 1 1 0 0 +EDGE2 415 274 -1.00521 -0.0762882 0.00296146 1 0 1 1 0 0 +EDGE2 415 316 -0.0208013 -1.05187 -1.56629 1 0 1 1 0 0 +EDGE2 416 315 -0.98353 -0.04459 -1.57497 1 0 1 1 0 0 +EDGE2 416 415 -1.04585 -0.00487034 1.56824 1 0 1 1 0 0 +EDGE2 416 395 -1.02327 -0.0500214 1.5662 1 0 1 1 0 0 +EDGE2 416 275 -0.922334 0.0870901 1.58121 1 0 1 1 0 0 +EDGE2 416 295 -1.08655 -0.0594535 1.59119 1 0 1 1 0 0 +EDGE2 416 317 1.05598 0.0930426 0.0207128 1 0 1 1 0 0 +EDGE2 416 316 0.078691 0.0425304 -0.0408022 1 0 1 1 0 0 +EDGE2 417 318 1.0254 -0.0976616 0.0219228 1 0 1 1 0 0 +EDGE2 417 416 -1.03329 -3.44934e-05 0.0167236 1 0 1 1 0 0 +EDGE2 417 317 -0.00314238 -0.0100424 0.00591819 1 0 1 1 0 0 +EDGE2 417 316 -1.05092 0.00220485 -0.031245 1 0 1 1 0 0 +EDGE2 418 318 -0.0381456 0.0110592 0.00804189 1 0 1 1 0 0 +EDGE2 418 317 -1.02643 -0.0899828 0.00580289 1 0 1 1 0 0 +EDGE2 418 417 -1.07691 -0.0447119 0.0188413 1 0 1 1 0 0 +EDGE2 418 319 0.979284 -0.0659658 0.0211492 1 0 1 1 0 0 +EDGE2 419 318 -1.08833 0.0020639 -0.00803414 1 0 1 1 0 0 +EDGE2 419 418 -0.930667 0.0258017 -0.0371241 1 0 1 1 0 0 +EDGE2 419 320 1.08297 -0.000673799 -0.00141634 1 0 1 1 0 0 +EDGE2 419 319 6.66251e-05 -0.0302387 0.0152627 1 0 1 1 0 0 +EDGE2 419 340 1.04013 0.0111132 -3.12769 1 0 1 1 0 0 +EDGE2 419 140 1.01266 -0.0448346 -3.15983 1 0 1 1 0 0 +EDGE2 420 141 0.00115599 -0.975248 -1.57386 1 0 1 1 0 0 +EDGE2 420 320 0.010862 0.067464 -0.0229988 1 0 1 1 0 0 +EDGE2 420 319 -0.990425 -0.00986783 0.0364771 1 0 1 1 0 0 +EDGE2 420 419 -1.01431 0.145655 0.0277826 1 0 1 1 0 0 +EDGE2 420 340 -0.0933427 0.0232274 -3.15484 1 0 1 1 0 0 +EDGE2 420 341 0.00775605 -0.961198 -1.5795 1 0 1 1 0 0 +EDGE2 420 140 0.0473573 0.0505227 -3.1759 1 0 1 1 0 0 +EDGE2 420 321 0.0534989 -1.0127 -1.55849 1 0 1 1 0 0 +EDGE2 420 339 1.03163 -0.0222373 -3.14767 1 0 1 1 0 0 +EDGE2 420 139 0.933672 0.032437 -3.15462 1 0 1 1 0 0 +EDGE2 421 141 -0.0753104 0.0633365 -0.00784697 1 0 1 1 0 0 +EDGE2 421 320 -0.95288 0.0255982 1.56321 1 0 1 1 0 0 +EDGE2 421 420 -0.994866 0.033491 1.56391 1 0 1 1 0 0 +EDGE2 421 340 -1.05143 0.0333671 -1.58425 1 0 1 1 0 0 +EDGE2 421 341 0.0443769 -0.0737338 -0.0289412 1 0 1 1 0 0 +EDGE2 421 140 -0.974181 -0.0208728 -1.56287 1 0 1 1 0 0 +EDGE2 421 321 0.0217976 -0.0830984 -0.0281338 1 0 1 1 0 0 +EDGE2 421 322 1.09642 -0.0775574 -0.0274123 1 0 1 1 0 0 +EDGE2 421 342 0.963119 -0.0202452 -0.00738238 1 0 1 1 0 0 +EDGE2 421 142 1.04695 -0.0413328 -0.02413 1 0 1 1 0 0 +EDGE2 422 141 -1.00581 0.0222474 0.0104856 1 0 1 1 0 0 +EDGE2 422 341 -1.0922 0.0584691 -0.0204582 1 0 1 1 0 0 +EDGE2 422 421 -1.00321 -0.0253556 -0.0345875 1 0 1 1 0 0 +EDGE2 422 321 -1.00448 -0.0212989 -0.000557705 1 0 1 1 0 0 +EDGE2 422 322 0.00227711 0.0326635 -0.00173474 1 0 1 1 0 0 +EDGE2 422 342 0.0295293 0.0105346 -0.00246967 1 0 1 1 0 0 +EDGE2 422 142 0.0610281 -0.00849926 0.0218131 1 0 1 1 0 0 +EDGE2 422 323 1.06342 -0.0220861 0.0281676 1 0 1 1 0 0 +EDGE2 422 343 1.06055 0.0751652 -0.0201539 1 0 1 1 0 0 +EDGE2 422 143 0.984537 -0.0155865 -0.0246457 1 0 1 1 0 0 +EDGE2 423 322 -0.92311 0.0662331 -0.0193578 1 0 1 1 0 0 +EDGE2 423 342 -1.11051 0.0208088 0.0267235 1 0 1 1 0 0 +EDGE2 423 422 -0.912277 0.0182846 -0.0135295 1 0 1 1 0 0 +EDGE2 423 142 -1.06553 -0.00272166 -0.0190838 1 0 1 1 0 0 +EDGE2 423 323 -0.00305581 0.0781719 -0.0109294 1 0 1 1 0 0 +EDGE2 423 343 -0.00988634 0.0632553 0.0183724 1 0 1 1 0 0 +EDGE2 423 143 0.0136251 -0.000180105 -0.0190177 1 0 1 1 0 0 +EDGE2 423 144 0.956043 -0.0405788 -0.0344956 1 0 1 1 0 0 +EDGE2 423 324 1.06309 0.025011 0.0094149 1 0 1 1 0 0 +EDGE2 423 344 1.03922 -0.0469242 -0.0145056 1 0 1 1 0 0 +EDGE2 424 423 -0.985002 0.0570452 -0.0263372 1 0 1 1 0 0 +EDGE2 424 323 -1.00079 0.0585445 0.0108254 1 0 1 1 0 0 +EDGE2 424 343 -0.943133 0.0210539 -0.0143774 1 0 1 1 0 0 +EDGE2 424 143 -0.977883 0.0274548 -0.0204391 1 0 1 1 0 0 +EDGE2 424 145 1.04106 0.00541972 0.000561592 1 0 1 1 0 0 +EDGE2 424 385 0.943302 0.0109976 -3.14573 1 0 1 1 0 0 +EDGE2 424 144 0.0150208 0.0295538 0.0123307 1 0 1 1 0 0 +EDGE2 424 324 -0.0243331 -0.101958 0.0175719 1 0 1 1 0 0 +EDGE2 424 344 -0.0286902 0.0282225 -0.00165669 1 0 1 1 0 0 +EDGE2 424 325 1.08791 -0.0500762 0.0161541 1 0 1 1 0 0 +EDGE2 424 345 1.03481 -0.00295701 -0.0339705 1 0 1 1 0 0 +EDGE2 425 424 -0.937653 0.00741667 0.00554876 1 0 1 1 0 0 +EDGE2 425 386 0.0483192 -1.04517 -1.56714 1 0 1 1 0 0 +EDGE2 425 146 0.0113296 1.10938 1.60171 1 0 1 1 0 0 +EDGE2 425 145 0.0339705 -0.0655518 -0.0036138 1 0 1 1 0 0 +EDGE2 425 385 0.0320938 -0.0756513 -3.13152 1 0 1 1 0 0 +EDGE2 425 144 -1.05808 0.0189543 -0.00161667 1 0 1 1 0 0 +EDGE2 425 324 -0.881631 -0.0132843 0.0142901 1 0 1 1 0 0 +EDGE2 425 344 -0.994641 -0.044348 -0.0204806 1 0 1 1 0 0 +EDGE2 425 325 -0.00800763 0.0126933 0.00261598 1 0 1 1 0 0 +EDGE2 425 345 -0.0255809 -0.0543475 -0.0451564 1 0 1 1 0 0 +EDGE2 425 384 1.0095 0.0237787 -3.1304 1 0 1 1 0 0 +EDGE2 425 346 0.0116731 1.03138 1.5719 1 0 1 1 0 0 +EDGE2 425 326 -0.00575737 0.920077 1.56513 1 0 1 1 0 0 +EDGE2 426 387 0.951208 0.00853007 -0.000373422 1 0 1 1 0 0 +EDGE2 426 386 -0.00331965 0.0077678 0.0221017 1 0 1 1 0 0 +EDGE2 426 145 -0.988662 0.024096 1.57814 1 0 1 1 0 0 +EDGE2 426 385 -0.977278 -0.0355083 -1.56445 1 0 1 1 0 0 +EDGE2 426 425 -0.950093 -0.014241 1.54989 1 0 1 1 0 0 +EDGE2 426 325 -1.02956 -0.00916487 1.56273 1 0 1 1 0 0 +EDGE2 426 345 -0.967347 -0.0177166 1.56184 1 0 1 1 0 0 +EDGE2 427 387 -0.082561 0.0069733 -0.00473986 1 0 1 1 0 0 +EDGE2 427 388 0.994141 0.0430846 -0.0516436 1 0 1 1 0 0 +EDGE2 427 386 -0.995803 -0.0982427 0.0218289 1 0 1 1 0 0 +EDGE2 427 426 -1.06865 0.117396 -0.00261297 1 0 1 1 0 0 +EDGE2 428 389 1.05279 -0.0606238 -0.0206395 1 0 1 1 0 0 +EDGE2 428 387 -0.978446 -0.00129109 -0.0100595 1 0 1 1 0 0 +EDGE2 428 388 -0.0383529 -0.0476912 0.0114217 1 0 1 1 0 0 +EDGE2 428 427 -0.993522 0.0560569 -0.0139039 1 0 1 1 0 0 +EDGE2 429 410 0.954027 0.0462855 -3.1415 1 0 1 1 0 0 +EDGE2 429 270 0.944692 0.0325477 -3.11726 1 0 1 1 0 0 +EDGE2 429 290 0.980579 0.0279955 -3.1392 1 0 1 1 0 0 +EDGE2 429 390 0.989336 0.0610925 0.0208771 1 0 1 1 0 0 +EDGE2 429 389 -0.0532412 -0.0604126 -0.0464942 1 0 1 1 0 0 +EDGE2 429 388 -1.08369 -0.0153959 0.00644926 1 0 1 1 0 0 +EDGE2 429 428 -0.951417 0.0428014 -0.0315984 1 0 1 1 0 0 +EDGE2 430 291 0.0536281 -1.06207 -1.52951 1 0 1 1 0 0 +EDGE2 430 411 -0.0261892 -1.06065 -1.56709 1 0 1 1 0 0 +EDGE2 430 391 -0.0190288 -1.00103 -1.58286 1 0 1 1 0 0 +EDGE2 430 269 1.06603 -0.0481866 -3.16148 1 0 1 1 0 0 +EDGE2 430 409 1.00626 -0.00164712 -3.1632 1 0 1 1 0 0 +EDGE2 430 289 0.953803 0.0664871 -3.15403 1 0 1 1 0 0 +EDGE2 430 410 0.0315166 0.0955379 -3.12464 1 0 1 1 0 0 +EDGE2 430 271 0.0429293 -1.04667 -1.5766 1 0 1 1 0 0 +EDGE2 430 270 0.0956272 -0.0465573 -3.15111 1 0 1 1 0 0 +EDGE2 430 290 -0.0678121 -0.00725409 -3.14838 1 0 1 1 0 0 +EDGE2 430 390 -0.0138044 -0.0289291 0.00274291 1 0 1 1 0 0 +EDGE2 430 389 -0.982039 0.0480142 0.00230263 1 0 1 1 0 0 +EDGE2 430 429 -1.06662 0.0100184 -0.022387 1 0 1 1 0 0 +EDGE2 431 291 -0.0146081 -0.0676071 -0.00894301 1 0 1 1 0 0 +EDGE2 431 292 1.00329 0.0589661 -0.0113483 1 0 1 1 0 0 +EDGE2 431 392 0.983933 -0.00466383 -0.00889187 1 0 1 1 0 0 +EDGE2 431 412 0.967611 -0.0135121 0.0210574 1 0 1 1 0 0 +EDGE2 431 272 1.02146 0.0222625 0.0188772 1 0 1 1 0 0 +EDGE2 431 411 -0.00711455 0.0395357 0.0137749 1 0 1 1 0 0 +EDGE2 431 391 0.0241157 0.0109988 0.0290978 1 0 1 1 0 0 +EDGE2 431 410 -0.976602 0.049946 -1.58533 1 0 1 1 0 0 +EDGE2 431 271 -0.0302079 -0.0394397 0.0140468 1 0 1 1 0 0 +EDGE2 431 430 -0.994052 0.0856247 1.56779 1 0 1 1 0 0 +EDGE2 431 270 -0.9968 -0.00228166 -1.54349 1 0 1 1 0 0 +EDGE2 431 290 -1.01572 -0.0703041 -1.58509 1 0 1 1 0 0 +EDGE2 431 390 -0.953979 -0.0595501 1.59855 1 0 1 1 0 0 +EDGE2 432 291 -0.994697 0.0633445 -0.00559648 1 0 1 1 0 0 +EDGE2 432 393 0.97625 -0.0160676 0.0247749 1 0 1 1 0 0 +EDGE2 432 413 1.00659 0.048552 -0.0154007 1 0 1 1 0 0 +EDGE2 432 273 0.992259 -0.0662628 0.0463762 1 0 1 1 0 0 +EDGE2 432 293 1.02112 -0.173164 -0.010645 1 0 1 1 0 0 +EDGE2 432 292 -0.0119793 -0.0502029 0.0278385 1 0 1 1 0 0 +EDGE2 432 392 -0.0470653 -0.00689562 0.0387982 1 0 1 1 0 0 +EDGE2 432 412 -0.0443229 0.0103538 -0.0354382 1 0 1 1 0 0 +EDGE2 432 272 0.00692605 -0.0044565 -0.0464933 1 0 1 1 0 0 +EDGE2 432 411 -1.01337 -0.0183429 0.00275541 1 0 1 1 0 0 +EDGE2 432 431 -1.01848 0.00789801 -0.0143994 1 0 1 1 0 0 +EDGE2 432 391 -1.04085 0.0128069 0.00176517 1 0 1 1 0 0 +EDGE2 432 271 -1.1308 -0.0380164 0.0166144 1 0 1 1 0 0 +EDGE2 433 393 0.0228745 0.0571573 -0.00786634 1 0 1 1 0 0 +EDGE2 433 294 0.997543 -0.0086591 -0.00507047 1 0 1 1 0 0 +EDGE2 433 394 0.922443 -0.0503574 0.0412534 1 0 1 1 0 0 +EDGE2 433 414 0.974876 0.0041872 0.00120395 1 0 1 1 0 0 +EDGE2 433 274 1.04563 -0.00809485 0.00244944 1 0 1 1 0 0 +EDGE2 433 413 0.0496567 -0.0219755 0.0244117 1 0 1 1 0 0 +EDGE2 433 432 -1.11421 0.0321778 0.00613244 1 0 1 1 0 0 +EDGE2 433 273 -0.0186047 0.106428 0.00120338 1 0 1 1 0 0 +EDGE2 433 293 0.00484888 -0.00513634 -0.00898195 1 0 1 1 0 0 +EDGE2 433 292 -0.973858 0.0162031 0.00832047 1 0 1 1 0 0 +EDGE2 433 392 -1.04281 -0.0129204 0.048678 1 0 1 1 0 0 +EDGE2 433 412 -0.960465 0.0740139 -0.0533772 1 0 1 1 0 0 +EDGE2 433 272 -0.992142 -0.000712389 0.0127361 1 0 1 1 0 0 +EDGE2 434 393 -1.06783 -0.0473128 0.00329004 1 0 1 1 0 0 +EDGE2 434 315 0.989285 -0.0680893 -3.1291 1 0 1 1 0 0 +EDGE2 434 415 0.944833 0.091274 0.0122416 1 0 1 1 0 0 +EDGE2 434 395 0.859213 -0.0679104 0.00253849 1 0 1 1 0 0 +EDGE2 434 275 0.985762 0.108017 0.00652878 1 0 1 1 0 0 +EDGE2 434 295 1.02425 0.023922 -0.00637856 1 0 1 1 0 0 +EDGE2 434 294 -0.0627739 0.0427211 -0.00676333 1 0 1 1 0 0 +EDGE2 434 394 -0.00773736 -0.00536491 0.000716177 1 0 1 1 0 0 +EDGE2 434 414 0.0177597 -0.0516485 0.0081864 1 0 1 1 0 0 +EDGE2 434 274 0.0598589 -0.00505446 0.031619 1 0 1 1 0 0 +EDGE2 434 433 -0.977727 0.0571677 -0.0358187 1 0 1 1 0 0 +EDGE2 434 413 -0.848457 -0.0450688 -0.0233585 1 0 1 1 0 0 +EDGE2 434 273 -1.04143 0.0505249 0.00762339 1 0 1 1 0 0 +EDGE2 434 293 -1.02352 0.0122544 0.00523087 1 0 1 1 0 0 +EDGE2 435 314 1.01015 -0.0390475 -3.13322 1 0 1 1 0 0 +EDGE2 435 296 0.0147992 1.01844 1.53964 1 0 1 1 0 0 +EDGE2 435 396 -0.0668458 0.967524 1.57215 1 0 1 1 0 0 +EDGE2 435 276 0.0184569 1.01481 1.55592 1 0 1 1 0 0 +EDGE2 435 434 -1.02283 -0.00606474 0.0102586 1 0 1 1 0 0 +EDGE2 435 315 -0.0306231 0.0445257 -3.12718 1 0 1 1 0 0 +EDGE2 435 415 -0.0114773 0.0349867 0.000305147 1 0 1 1 0 0 +EDGE2 435 395 0.0260434 0.00126814 -0.0184081 1 0 1 1 0 0 +EDGE2 435 275 -0.123343 0.0336792 0.0046584 1 0 1 1 0 0 +EDGE2 435 295 0.0533129 0.00184641 0.027792 1 0 1 1 0 0 +EDGE2 435 294 -1.03695 -0.00962191 -0.0275406 1 0 1 1 0 0 +EDGE2 435 394 -1.04338 -0.103554 -0.00964694 1 0 1 1 0 0 +EDGE2 435 414 -1.08269 -0.0033356 0.00557513 1 0 1 1 0 0 +EDGE2 435 274 -0.938282 0.0189882 0.0245234 1 0 1 1 0 0 +EDGE2 435 416 -0.0158179 -1.03966 -1.59999 1 0 1 1 0 0 +EDGE2 435 316 -0.0539843 -0.958963 -1.5369 1 0 1 1 0 0 +EDGE2 436 277 0.98589 -0.0985355 0.0130161 1 0 1 1 0 0 +EDGE2 436 297 0.99197 -0.0245561 -0.0299764 1 0 1 1 0 0 +EDGE2 436 397 1.03279 0.0511763 0.0113872 1 0 1 1 0 0 +EDGE2 436 296 0.0308333 -0.0181116 -0.00811917 1 0 1 1 0 0 +EDGE2 436 396 -0.0354694 -0.0371159 -0.0100388 1 0 1 1 0 0 +EDGE2 436 276 -0.049159 0.0115672 0.00254273 1 0 1 1 0 0 +EDGE2 436 315 -1.04306 -0.017637 1.59929 1 0 1 1 0 0 +EDGE2 436 415 -0.973477 0.0232618 -1.59082 1 0 1 1 0 0 +EDGE2 436 435 -1.02124 -0.0549841 -1.59673 1 0 1 1 0 0 +EDGE2 436 395 -1.06808 0.0789837 -1.5703 1 0 1 1 0 0 +EDGE2 436 275 -1.06147 0.0210697 -1.60362 1 0 1 1 0 0 +EDGE2 436 295 -1.056 0.0292779 -1.59128 1 0 1 1 0 0 +EDGE2 437 298 0.94604 0.0659307 -0.0261681 1 0 1 1 0 0 +EDGE2 437 398 1.03009 -0.0255218 0.032508 1 0 1 1 0 0 +EDGE2 437 278 0.967233 0.00650196 0.0154004 1 0 1 1 0 0 +EDGE2 437 277 0.0234142 0.0033455 0.0181259 1 0 1 1 0 0 +EDGE2 437 297 -0.0136114 0.0831849 -0.0169448 1 0 1 1 0 0 +EDGE2 437 397 0.0101294 -0.048933 -0.0150437 1 0 1 1 0 0 +EDGE2 437 296 -1.02182 -0.0346532 0.00616141 1 0 1 1 0 0 +EDGE2 437 396 -1.01013 0.0425121 0.00690023 1 0 1 1 0 0 +EDGE2 437 436 -1.05851 0.0628964 -0.0285682 1 0 1 1 0 0 +EDGE2 437 276 -0.964115 -0.00508621 -0.0147671 1 0 1 1 0 0 +EDGE2 438 299 1.02536 -0.0660064 -0.0174449 1 0 1 1 0 0 +EDGE2 438 399 0.986677 0.0485557 -0.0367935 1 0 1 1 0 0 +EDGE2 438 279 1.07563 -0.0376673 -0.0284502 1 0 1 1 0 0 +EDGE2 438 298 -0.0345315 0.0340381 -0.0139469 1 0 1 1 0 0 +EDGE2 438 398 0.0735976 -0.0293694 0.0253549 1 0 1 1 0 0 +EDGE2 438 278 0.0149988 0.0358383 -0.014479 1 0 1 1 0 0 +EDGE2 438 437 -0.944354 0.0425956 -0.0175225 1 0 1 1 0 0 +EDGE2 438 277 -0.958002 -0.00583431 0.0019279 1 0 1 1 0 0 +EDGE2 438 297 -1.05103 -0.0342949 0.0202915 1 0 1 1 0 0 +EDGE2 438 397 -0.960981 0.0848987 0.0227999 1 0 1 1 0 0 +EDGE2 439 300 1.02346 -0.130475 0.0203307 1 0 1 1 0 0 +EDGE2 439 400 0.982896 -0.00284861 0.02846 1 0 1 1 0 0 +EDGE2 439 280 0.914478 0.0170343 0.0261958 1 0 1 1 0 0 +EDGE2 439 299 -0.0073332 -0.00499894 -0.00429119 1 0 1 1 0 0 +EDGE2 439 399 0.0142246 0.024772 0.0328883 1 0 1 1 0 0 +EDGE2 439 279 0.0424859 0.0343019 -0.0349778 1 0 1 1 0 0 +EDGE2 439 298 -0.995718 -0.0364842 0.00111827 1 0 1 1 0 0 +EDGE2 439 398 -0.906182 -0.0038096 -0.000730397 1 0 1 1 0 0 +EDGE2 439 438 -1.02327 0.00922843 -0.00860043 1 0 1 1 0 0 +EDGE2 439 278 -0.96485 -0.00220345 0.014672 1 0 1 1 0 0 +EDGE2 440 301 0.0573375 -1.00792 -1.59007 1 0 1 1 0 0 +EDGE2 440 300 -0.0396594 0.0485781 0.0204187 1 0 1 1 0 0 +EDGE2 440 400 -0.0284198 -0.0883054 -0.027303 1 0 1 1 0 0 +EDGE2 440 280 0.0126398 -0.0256312 -0.0252277 1 0 1 1 0 0 +EDGE2 440 401 -0.14479 0.968109 1.56857 1 0 1 1 0 0 +EDGE2 440 281 -0.0724136 1.07618 1.56109 1 0 1 1 0 0 +EDGE2 440 299 -1.02543 0.164132 -0.0230271 1 0 1 1 0 0 +EDGE2 440 439 -1.05389 -0.0797206 -0.0060049 1 0 1 1 0 0 +EDGE2 440 399 -1.02208 -0.0125319 -0.0125868 1 0 1 1 0 0 +EDGE2 440 279 -1.12328 -0.00349084 -0.0344985 1 0 1 1 0 0 +EDGE2 441 300 -1.00936 -0.0121015 -1.54848 1 0 1 1 0 0 +EDGE2 441 400 -1.05231 -0.0378777 -1.59915 1 0 1 1 0 0 +EDGE2 441 440 -0.952447 0.0518874 -1.58936 1 0 1 1 0 0 +EDGE2 441 280 -1.04992 -0.0652287 -1.51724 1 0 1 1 0 0 +EDGE2 441 401 -0.0255912 -0.0397475 -0.000813028 1 0 1 1 0 0 +EDGE2 441 281 0.0589014 -0.0100261 0.00109426 1 0 1 1 0 0 +EDGE2 441 402 1.1541 -0.0189278 -0.0361903 1 0 1 1 0 0 +EDGE2 441 282 1.01384 0.00593399 0.0129759 1 0 1 1 0 0 +EDGE2 442 401 -0.993581 0.0663918 -0.0180726 1 0 1 1 0 0 +EDGE2 442 441 -1.02164 0.00474917 0.0254024 1 0 1 1 0 0 +EDGE2 442 281 -1.02781 0.0241164 -0.0214398 1 0 1 1 0 0 +EDGE2 442 402 -0.0572684 0.0498375 0.00736485 1 0 1 1 0 0 +EDGE2 442 282 -0.00953964 -0.0526534 0.00552118 1 0 1 1 0 0 +EDGE2 442 403 0.973225 -0.00421226 0.0165581 1 0 1 1 0 0 +EDGE2 442 283 0.973804 -0.0154394 -0.0159052 1 0 1 1 0 0 +EDGE2 443 402 -0.959622 -0.0312431 -0.0142844 1 0 1 1 0 0 +EDGE2 443 442 -1.01872 0.00139436 -0.0256598 1 0 1 1 0 0 +EDGE2 443 282 -1.01859 -0.0613935 0.0124112 1 0 1 1 0 0 +EDGE2 443 403 -0.0664919 0.00566359 -0.00573984 1 0 1 1 0 0 +EDGE2 443 283 0.0756211 -0.0115424 -0.00872566 1 0 1 1 0 0 +EDGE2 443 404 0.95004 0.040971 0.0106283 1 0 1 1 0 0 +EDGE2 443 284 1.0291 -0.00429323 0.00206426 1 0 1 1 0 0 +EDGE2 444 403 -0.969641 -0.145183 -0.0189881 1 0 1 1 0 0 +EDGE2 444 443 -1.01481 -0.0387605 0.0321155 1 0 1 1 0 0 +EDGE2 444 283 -1.15457 -0.00682001 -0.0479224 1 0 1 1 0 0 +EDGE2 444 404 0.0224797 -0.0376684 -0.00367627 1 0 1 1 0 0 +EDGE2 444 284 0.0389047 0.0284941 0.0256765 1 0 1 1 0 0 +EDGE2 444 265 1.01891 -0.03295 -3.08872 1 0 1 1 0 0 +EDGE2 444 405 1.05638 -0.042438 -0.0242875 1 0 1 1 0 0 +EDGE2 444 285 1.00787 0.00337815 -0.0195872 1 0 1 1 0 0 +EDGE2 445 404 -0.978702 -0.104544 0.00580469 1 0 1 1 0 0 +EDGE2 445 444 -0.976324 -0.0798205 -0.00186007 1 0 1 1 0 0 +EDGE2 445 284 -0.987009 0.0305191 -0.00162716 1 0 1 1 0 0 +EDGE2 445 265 0.0465159 -0.013797 -3.12586 1 0 1 1 0 0 +EDGE2 445 405 -0.00286836 0.0361794 0.00659384 1 0 1 1 0 0 +EDGE2 445 285 0.0654935 -0.0635299 0.0201743 1 0 1 1 0 0 +EDGE2 445 264 1.10239 -0.0624895 -3.14982 1 0 1 1 0 0 +EDGE2 445 266 0.0788387 0.972397 1.5582 1 0 1 1 0 0 +EDGE2 445 286 0.0226877 1.00838 1.5599 1 0 1 1 0 0 +EDGE2 445 406 0.0396642 0.968138 1.54456 1 0 1 1 0 0 +EDGE2 446 265 -0.914044 0.0391305 1.58302 1 0 1 1 0 0 +EDGE2 446 405 -1.0494 0.121821 -1.52482 1 0 1 1 0 0 +EDGE2 446 445 -0.974621 0.0981328 -1.5604 1 0 1 1 0 0 +EDGE2 446 285 -1.01463 -0.0697148 -1.5558 1 0 1 1 0 0 +EDGE2 446 266 -0.0993909 -0.0368063 0.0223707 1 0 1 1 0 0 +EDGE2 446 286 0.0412377 -0.0430771 0.018153 1 0 1 1 0 0 +EDGE2 446 406 0.104578 -0.0334413 -0.0433217 1 0 1 1 0 0 +EDGE2 446 287 0.979397 0.0411971 -0.0116117 1 0 1 1 0 0 +EDGE2 446 407 0.9123 0.0518003 0.00333906 1 0 1 1 0 0 +EDGE2 446 267 0.97172 0.0496714 0.0131113 1 0 1 1 0 0 +EDGE2 447 446 -0.946238 0.0231346 0.0229653 1 0 1 1 0 0 +EDGE2 447 266 -0.98548 0.0168695 0.0124102 1 0 1 1 0 0 +EDGE2 447 286 -0.940676 0.0673863 -0.00562532 1 0 1 1 0 0 +EDGE2 447 406 -0.997892 -0.039334 -0.0180806 1 0 1 1 0 0 +EDGE2 447 287 -0.0989935 -0.0459611 0.0303817 1 0 1 1 0 0 +EDGE2 447 407 -0.0252861 -0.00298777 0.00821911 1 0 1 1 0 0 +EDGE2 447 267 -0.0149836 -0.0218368 -0.0150936 1 0 1 1 0 0 +EDGE2 447 268 0.993936 0.0535412 0.0448617 1 0 1 1 0 0 +EDGE2 447 408 1.02496 0.011659 -0.00321333 1 0 1 1 0 0 +EDGE2 447 288 1.00291 0.024498 0.0213873 1 0 1 1 0 0 +EDGE2 448 447 -1.1006 0.0197051 -0.00401132 1 0 1 1 0 0 +EDGE2 448 287 -0.980404 0.0164247 -0.0107556 1 0 1 1 0 0 +EDGE2 448 407 -1.0126 0.0537179 0.00248022 1 0 1 1 0 0 +EDGE2 448 267 -0.94535 0.0164369 -0.00981474 1 0 1 1 0 0 +EDGE2 448 269 1.0363 -0.0416107 -0.0196509 1 0 1 1 0 0 +EDGE2 448 268 -0.00491624 0.0817633 -0.0147776 1 0 1 1 0 0 +EDGE2 448 408 -0.0338841 0.064255 0.0172306 1 0 1 1 0 0 +EDGE2 448 288 -0.104642 0.0265867 0.00389304 1 0 1 1 0 0 +EDGE2 448 409 0.991006 0.0541615 -0.0015326 1 0 1 1 0 0 +EDGE2 448 289 0.949224 -0.0233163 0.000721575 1 0 1 1 0 0 +EDGE2 449 269 0.00997954 0.00147049 -0.0128378 1 0 1 1 0 0 +EDGE2 449 268 -1.07732 0.0111604 0.0141952 1 0 1 1 0 0 +EDGE2 449 408 -0.987315 0.0570572 0.0236416 1 0 1 1 0 0 +EDGE2 449 448 -0.931627 0.017677 -0.0204723 1 0 1 1 0 0 +EDGE2 449 288 -0.992418 0.00373589 0.0036468 1 0 1 1 0 0 +EDGE2 449 409 0.0699501 0.0593266 -0.0198273 1 0 1 1 0 0 +EDGE2 449 289 0.0148607 -0.0246144 -0.0254969 1 0 1 1 0 0 +EDGE2 449 410 0.994995 0.0642083 -0.0121872 1 0 1 1 0 0 +EDGE2 449 430 0.993001 0.00575354 -3.15917 1 0 1 1 0 0 +EDGE2 449 270 0.92033 -0.0166392 -0.00179165 1 0 1 1 0 0 +EDGE2 449 290 1.0344 -0.020889 0.0299289 1 0 1 1 0 0 +EDGE2 449 390 1.08714 -0.0425582 -3.159 1 0 1 1 0 0 +EDGE2 450 291 -0.0139498 0.972067 1.53983 1 0 1 1 0 0 +EDGE2 450 411 0.0343607 0.996031 1.58653 1 0 1 1 0 0 +EDGE2 450 431 -0.0598316 0.98606 1.59394 1 0 1 1 0 0 +EDGE2 450 391 0.0142032 0.975114 1.58819 1 0 1 1 0 0 +EDGE2 450 269 -1.08466 0.0465378 0.00409747 1 0 1 1 0 0 +EDGE2 450 409 -0.99529 -0.0240022 -0.0464369 1 0 1 1 0 0 +EDGE2 450 449 -0.931005 0.045658 -0.0115396 1 0 1 1 0 0 +EDGE2 450 289 -0.92776 -0.078995 0.0101649 1 0 1 1 0 0 +EDGE2 450 410 0.0354544 0.0447424 -0.0138109 1 0 1 1 0 0 +EDGE2 450 271 0.124915 0.976054 1.56215 1 0 1 1 0 0 +EDGE2 450 430 0.0700707 0.0575565 -3.19232 1 0 1 1 0 0 +EDGE2 450 270 -0.00982212 -0.0313794 0.0243646 1 0 1 1 0 0 +EDGE2 450 290 0.0717302 -0.105942 -0.00728967 1 0 1 1 0 0 +EDGE2 450 390 -0.0023405 0.0307134 -3.12669 1 0 1 1 0 0 +EDGE2 450 389 1.05646 0.0557127 -3.15666 1 0 1 1 0 0 +EDGE2 450 429 1.10605 0.124821 -3.12674 1 0 1 1 0 0 +EDGE2 451 291 -0.0543524 -0.0304121 -0.05023 1 0 1 1 0 0 +EDGE2 451 432 0.955625 0.0528316 -0.0139686 1 0 1 1 0 0 +EDGE2 451 292 1.02784 0.0406631 0.00946834 1 0 1 1 0 0 +EDGE2 451 392 0.9912 -0.0508126 0.0113504 1 0 1 1 0 0 +EDGE2 451 412 1.03069 0.0083757 0.0109676 1 0 1 1 0 0 +EDGE2 451 272 1.04646 0.0283593 -0.0116831 1 0 1 1 0 0 +EDGE2 451 411 -0.10653 0.066406 -0.00813945 1 0 1 1 0 0 +EDGE2 451 431 -0.0680615 0.0342112 -0.046031 1 0 1 1 0 0 +EDGE2 451 391 0.100471 0.0463599 0.0147048 1 0 1 1 0 0 +EDGE2 451 410 -0.884662 -0.101548 -1.56083 1 0 1 1 0 0 +EDGE2 451 450 -0.94901 0.0121964 -1.55377 1 0 1 1 0 0 +EDGE2 451 271 -0.0678393 0.0508904 0.012011 1 0 1 1 0 0 +EDGE2 451 430 -0.881038 0.036266 1.53562 1 0 1 1 0 0 +EDGE2 451 270 -0.990492 0.0504411 -1.58303 1 0 1 1 0 0 +EDGE2 451 290 -1.05002 -0.00409603 -1.53019 1 0 1 1 0 0 +EDGE2 451 390 -0.941722 0.024229 1.56678 1 0 1 1 0 0 +EDGE2 452 291 -0.946259 -0.00784109 0.0045821 1 0 1 1 0 0 +EDGE2 452 393 0.881875 -0.051469 0.0117054 1 0 1 1 0 0 +EDGE2 452 433 1.05059 0.157634 0.0104151 1 0 1 1 0 0 +EDGE2 452 413 0.985202 0.140465 0.00861688 1 0 1 1 0 0 +EDGE2 452 432 0.0282481 -0.0156812 0.0110931 1 0 1 1 0 0 +EDGE2 452 273 0.902279 0.0840588 -0.00828748 1 0 1 1 0 0 +EDGE2 452 293 0.975106 0.0335735 0.00838324 1 0 1 1 0 0 +EDGE2 452 292 0.0598055 0.011177 -0.0108461 1 0 1 1 0 0 +EDGE2 452 392 -0.0687317 -0.0158611 -0.0283537 1 0 1 1 0 0 +EDGE2 452 412 -0.0113906 -0.0973188 0.0254799 1 0 1 1 0 0 +EDGE2 452 272 0.00366288 -0.0305013 -0.0230223 1 0 1 1 0 0 +EDGE2 452 411 -1.03797 -0.00269094 -0.0190708 1 0 1 1 0 0 +EDGE2 452 431 -1.03687 0.0409927 -0.0424022 1 0 1 1 0 0 +EDGE2 452 451 -1.06447 0.0287356 -0.0272743 1 0 1 1 0 0 +EDGE2 452 391 -0.984328 -0.0231213 -0.031986 1 0 1 1 0 0 +EDGE2 452 271 -0.994481 0.0128304 -0.00467299 1 0 1 1 0 0 +EDGE2 453 393 -0.0508333 0.0254504 0.00423258 1 0 1 1 0 0 +EDGE2 453 434 1.0315 -0.0224388 -0.0447323 1 0 1 1 0 0 +EDGE2 453 294 0.937827 0.0214568 -0.00776117 1 0 1 1 0 0 +EDGE2 453 394 0.946796 -0.0533932 -0.0388368 1 0 1 1 0 0 +EDGE2 453 414 0.913857 0.0400399 0.00406507 1 0 1 1 0 0 +EDGE2 453 274 0.959527 -0.0403285 -0.00704045 1 0 1 1 0 0 +EDGE2 453 433 0.0213519 0.00591115 0.00966202 1 0 1 1 0 0 +EDGE2 453 413 -0.0304088 -0.0941508 -0.0200581 1 0 1 1 0 0 +EDGE2 453 432 -0.948722 -0.0334506 0.0312313 1 0 1 1 0 0 +EDGE2 453 273 -0.0289974 0.0318105 -0.00387149 1 0 1 1 0 0 +EDGE2 453 293 -0.0118367 -0.072431 -0.0209731 1 0 1 1 0 0 +EDGE2 453 452 -0.975467 -0.000111772 -0.0217065 1 0 1 1 0 0 +EDGE2 453 292 -1.05274 0.0150901 -0.014655 1 0 1 1 0 0 +EDGE2 453 392 -0.978456 0.0897502 -0.00700076 1 0 1 1 0 0 +EDGE2 453 412 -0.978461 0.00711817 -0.00646627 1 0 1 1 0 0 +EDGE2 453 272 -1.04439 -0.0590973 -0.00838662 1 0 1 1 0 0 +EDGE2 454 393 -1.03328 -0.0812428 -0.0334823 1 0 1 1 0 0 +EDGE2 454 434 -0.100402 0.0650093 -0.00324144 1 0 1 1 0 0 +EDGE2 454 315 0.935342 -0.0752239 -3.15195 1 0 1 1 0 0 +EDGE2 454 415 0.997644 -0.07038 0.0245577 1 0 1 1 0 0 +EDGE2 454 435 0.976659 -0.0365201 -0.0328801 1 0 1 1 0 0 +EDGE2 454 395 1.05595 0.0054849 0.0116693 1 0 1 1 0 0 +EDGE2 454 275 0.96225 0.0504466 -0.024911 1 0 1 1 0 0 +EDGE2 454 295 0.93705 0.00384831 0.0265144 1 0 1 1 0 0 +EDGE2 454 294 0.0308718 -0.0839611 0.0103412 1 0 1 1 0 0 +EDGE2 454 394 -0.0173086 -0.0521367 0.0237207 1 0 1 1 0 0 +EDGE2 454 414 0.0666142 -0.0490736 0.00824899 1 0 1 1 0 0 +EDGE2 454 274 -0.0618978 -0.0938965 -0.0183516 1 0 1 1 0 0 +EDGE2 454 433 -1.02622 0.0428118 0.0141776 1 0 1 1 0 0 +EDGE2 454 453 -0.904911 -0.0284013 -0.00685749 1 0 1 1 0 0 +EDGE2 454 413 -1.04766 0.0687508 -0.00757832 1 0 1 1 0 0 +EDGE2 454 273 -0.978144 0.0134332 -0.00833443 1 0 1 1 0 0 +EDGE2 454 293 -1.07525 0.0597829 -0.0249159 1 0 1 1 0 0 +EDGE2 455 314 0.977014 -0.0177927 -3.15981 1 0 1 1 0 0 +EDGE2 455 296 -0.084225 0.982105 1.62819 1 0 1 1 0 0 +EDGE2 455 396 0.00613465 1.01223 1.55202 1 0 1 1 0 0 +EDGE2 455 436 0.0740437 1.07937 1.59054 1 0 1 1 0 0 +EDGE2 455 276 -0.00386972 1.04777 1.59381 1 0 1 1 0 0 +EDGE2 455 434 -1.05247 -0.0155408 0.0139703 1 0 1 1 0 0 +EDGE2 455 315 -0.037836 0.035477 -3.10942 1 0 1 1 0 0 +EDGE2 455 415 0.0713599 0.00613067 -0.0127512 1 0 1 1 0 0 +EDGE2 455 435 -0.000435465 -0.00320765 0.028608 1 0 1 1 0 0 +EDGE2 455 395 -0.010936 0.0482571 0.00535934 1 0 1 1 0 0 +EDGE2 455 275 -0.00825978 -0.00999726 0.040209 1 0 1 1 0 0 +EDGE2 455 295 -0.0418579 0.00196469 0.0287798 1 0 1 1 0 0 +EDGE2 455 454 -1.03611 -0.0167848 -0.0232015 1 0 1 1 0 0 +EDGE2 455 294 -0.963855 0.10805 -0.0115365 1 0 1 1 0 0 +EDGE2 455 394 -1.04106 0.136844 0.028868 1 0 1 1 0 0 +EDGE2 455 414 -0.957749 -0.0411543 0.00568492 1 0 1 1 0 0 +EDGE2 455 274 -0.986012 -0.00521992 -0.0480792 1 0 1 1 0 0 +EDGE2 455 416 0.0332467 -0.985601 -1.56319 1 0 1 1 0 0 +EDGE2 455 316 0.00837276 -0.995626 -1.58838 1 0 1 1 0 0 +EDGE2 456 437 1.01116 0.123053 0.00584504 1 0 1 1 0 0 +EDGE2 456 277 1.02988 0.0223239 -0.00537706 1 0 1 1 0 0 +EDGE2 456 297 1.11657 0.0366122 -0.0195261 1 0 1 1 0 0 +EDGE2 456 397 0.928558 -0.00679591 -0.00676148 1 0 1 1 0 0 +EDGE2 456 296 -0.108006 0.00532281 -0.0034934 1 0 1 1 0 0 +EDGE2 456 396 -0.0480721 -0.0356933 -0.010856 1 0 1 1 0 0 +EDGE2 456 436 0.0265332 0.0233809 -0.00848364 1 0 1 1 0 0 +EDGE2 456 276 -0.0593907 -0.000785935 -0.0299645 1 0 1 1 0 0 +EDGE2 456 315 -1.04345 0.0157653 1.54224 1 0 1 1 0 0 +EDGE2 456 415 -0.975751 -0.0182842 -1.56484 1 0 1 1 0 0 +EDGE2 456 435 -0.912843 -0.0280867 -1.60664 1 0 1 1 0 0 +EDGE2 456 455 -1.04386 -0.0347579 -1.57823 1 0 1 1 0 0 +EDGE2 456 395 -1.0497 0.00767642 -1.57718 1 0 1 1 0 0 +EDGE2 456 275 -1.00996 -0.0160247 -1.56881 1 0 1 1 0 0 +EDGE2 456 295 -0.939041 0.00460357 -1.56498 1 0 1 1 0 0 +EDGE2 457 298 1.0533 0.0557931 0.0173787 1 0 1 1 0 0 +EDGE2 457 398 0.996591 -0.0481043 -0.0103921 1 0 1 1 0 0 +EDGE2 457 438 1.03814 0.0819158 -0.00417219 1 0 1 1 0 0 +EDGE2 457 278 0.935274 -0.0236598 -0.00813967 1 0 1 1 0 0 +EDGE2 457 437 -0.00298801 0.0906385 -0.0128929 1 0 1 1 0 0 +EDGE2 457 456 -0.94768 0.0666331 -0.0169531 1 0 1 1 0 0 +EDGE2 457 277 -0.0148038 0.0104062 0.0117937 1 0 1 1 0 0 +EDGE2 457 297 -0.0217267 -0.0243733 -0.0215781 1 0 1 1 0 0 +EDGE2 457 397 -0.0231766 0.0625431 -0.0112556 1 0 1 1 0 0 +EDGE2 457 296 -1.04841 -0.0904273 0.0148037 1 0 1 1 0 0 +EDGE2 457 396 -1.10614 -0.018008 0.0108172 1 0 1 1 0 0 +EDGE2 457 436 -1.00157 0.0410241 -0.0384012 1 0 1 1 0 0 +EDGE2 457 276 -1.04828 -0.0416803 0.0445214 1 0 1 1 0 0 +EDGE2 458 299 1.04774 0.0408617 -0.000178218 1 0 1 1 0 0 +EDGE2 458 439 1.06962 0.0485683 0.0127536 1 0 1 1 0 0 +EDGE2 458 399 1.02505 0.0502376 0.00249366 1 0 1 1 0 0 +EDGE2 458 279 0.883094 0.0505864 -0.00811908 1 0 1 1 0 0 +EDGE2 458 298 0.0321745 -0.0239452 0.000914406 1 0 1 1 0 0 +EDGE2 458 398 0.00169623 0.0135407 0.000656995 1 0 1 1 0 0 +EDGE2 458 438 0.0148311 0.0929293 0.00137246 1 0 1 1 0 0 +EDGE2 458 278 0.0841982 -0.052914 -0.00794753 1 0 1 1 0 0 +EDGE2 458 437 -1.01272 -0.0191958 -1.42409e-06 1 0 1 1 0 0 +EDGE2 458 457 -1.03891 -0.0565493 0.0325851 1 0 1 1 0 0 +EDGE2 458 277 -0.976864 0.022198 -0.0413125 1 0 1 1 0 0 +EDGE2 458 297 -1.00247 0.00573847 -0.011486 1 0 1 1 0 0 +EDGE2 458 397 -1.04369 -0.0128407 -0.0207529 1 0 1 1 0 0 +EDGE2 459 300 0.945818 0.0445222 -0.0202485 1 0 1 1 0 0 +EDGE2 459 400 0.986487 -0.00389061 -0.0159207 1 0 1 1 0 0 +EDGE2 459 440 0.98921 -0.0268321 0.0451162 1 0 1 1 0 0 +EDGE2 459 280 0.953689 -0.0309408 0.0166567 1 0 1 1 0 0 +EDGE2 459 299 0.0930543 -0.0673066 -0.00636594 1 0 1 1 0 0 +EDGE2 459 439 0.0342127 -0.00866239 0.0183817 1 0 1 1 0 0 +EDGE2 459 399 -0.0205745 -0.0010823 -0.0116276 1 0 1 1 0 0 +EDGE2 459 458 -1.05789 -0.0321739 0.00823277 1 0 1 1 0 0 +EDGE2 459 279 -0.0252691 -0.0772359 -0.0422733 1 0 1 1 0 0 +EDGE2 459 298 -0.980786 0.0129743 0.0226611 1 0 1 1 0 0 +EDGE2 459 398 -1.01185 -0.000656116 0.012387 1 0 1 1 0 0 +EDGE2 459 438 -1.05657 0.0361667 0.00465037 1 0 1 1 0 0 +EDGE2 459 278 -1.0594 0.00741261 0.00954283 1 0 1 1 0 0 +EDGE2 460 301 -0.0228636 -0.982149 -1.57267 1 0 1 1 0 0 +EDGE2 460 300 -0.0451319 -0.0181321 -0.00822093 1 0 1 1 0 0 +EDGE2 460 400 0.0715627 0.0522051 0.00514346 1 0 1 1 0 0 +EDGE2 460 440 -0.0149126 0.0445466 -0.0218992 1 0 1 1 0 0 +EDGE2 460 280 0.0683299 -0.0901113 0.00197348 1 0 1 1 0 0 +EDGE2 460 401 0.0417833 1.03434 1.54534 1 0 1 1 0 0 +EDGE2 460 441 0.00469808 0.979823 1.56612 1 0 1 1 0 0 +EDGE2 460 281 -0.0329069 0.994251 1.58427 1 0 1 1 0 0 +EDGE2 460 299 -0.94783 0.0775178 -0.0126183 1 0 1 1 0 0 +EDGE2 460 439 -1.06609 -0.0061966 -0.00597096 1 0 1 1 0 0 +EDGE2 460 459 -1.00967 -0.0102919 0.00119164 1 0 1 1 0 0 +EDGE2 460 399 -0.969981 -0.0603318 -0.00432435 1 0 1 1 0 0 +EDGE2 460 279 -1.06263 0.0369641 -0.0387038 1 0 1 1 0 0 +EDGE2 461 460 -0.949521 0.056313 -1.57608 1 0 1 1 0 0 +EDGE2 461 300 -1.00116 -0.0358253 -1.58204 1 0 1 1 0 0 +EDGE2 461 400 -0.933871 -0.0800557 -1.54344 1 0 1 1 0 0 +EDGE2 461 440 -0.967457 -0.162591 -1.58688 1 0 1 1 0 0 +EDGE2 461 280 -0.937467 0.0789501 -1.59424 1 0 1 1 0 0 +EDGE2 461 401 0.0423324 -0.0169667 0.00808183 1 0 1 1 0 0 +EDGE2 461 441 -0.0471237 -0.0814521 0.00685223 1 0 1 1 0 0 +EDGE2 461 281 0.0267028 -0.034531 -0.000858758 1 0 1 1 0 0 +EDGE2 461 402 0.991432 0.0476524 0.00489405 1 0 1 1 0 0 +EDGE2 461 442 1.04422 0.0697523 -0.00499551 1 0 1 1 0 0 +EDGE2 461 282 0.956296 -0.0307464 0.0371193 1 0 1 1 0 0 +EDGE2 462 401 -0.959848 -0.0696206 -0.0161519 1 0 1 1 0 0 +EDGE2 462 441 -0.992621 0.0208658 -0.00457866 1 0 1 1 0 0 +EDGE2 462 461 -1.02283 -0.0176359 -0.00533183 1 0 1 1 0 0 +EDGE2 462 281 -1.01969 0.0193841 -0.0211096 1 0 1 1 0 0 +EDGE2 462 402 0.0127213 0.100405 -0.0379552 1 0 1 1 0 0 +EDGE2 462 442 0.00732981 0.0988542 0.00199412 1 0 1 1 0 0 +EDGE2 462 282 -0.0154315 0.0836612 -0.0108402 1 0 1 1 0 0 +EDGE2 462 403 1.01918 -0.0161587 -0.011123 1 0 1 1 0 0 +EDGE2 462 443 0.981998 0.0276664 0.0444079 1 0 1 1 0 0 +EDGE2 462 283 0.95792 -0.0230966 0.0137257 1 0 1 1 0 0 +EDGE2 463 402 -0.990636 0.0575992 -0.00474659 1 0 1 1 0 0 +EDGE2 463 442 -0.970288 0.0467768 0.0258911 1 0 1 1 0 0 +EDGE2 463 462 -1.01585 0.0168002 -0.00871378 1 0 1 1 0 0 +EDGE2 463 282 -1.04381 0.0857311 -0.0114768 1 0 1 1 0 0 +EDGE2 463 403 -0.0475471 -0.0034545 -0.00495041 1 0 1 1 0 0 +EDGE2 463 443 0.0296623 0.10299 -0.00583251 1 0 1 1 0 0 +EDGE2 463 283 -0.0417287 -0.0321915 0.0245837 1 0 1 1 0 0 +EDGE2 463 404 0.985739 0.0141753 -0.0172072 1 0 1 1 0 0 +EDGE2 463 444 1.01136 0.0149302 0.0182147 1 0 1 1 0 0 +EDGE2 463 284 1.06383 -0.0101195 0.0224506 1 0 1 1 0 0 +EDGE2 464 403 -1.15938 0.0878801 0.0423359 1 0 1 1 0 0 +EDGE2 464 443 -1.03561 0.0821227 0.0203304 1 0 1 1 0 0 +EDGE2 464 463 -0.975611 0.00138531 0.0189329 1 0 1 1 0 0 +EDGE2 464 283 -0.980535 0.0468369 0.0159172 1 0 1 1 0 0 +EDGE2 464 404 -0.0408218 -0.00052347 0.0369182 1 0 1 1 0 0 +EDGE2 464 444 0.00354073 -0.0441877 -0.0162696 1 0 1 1 0 0 +EDGE2 464 284 -0.0589381 0.0348686 0.0114881 1 0 1 1 0 0 +EDGE2 464 265 0.988641 -0.0432346 -3.10145 1 0 1 1 0 0 +EDGE2 464 405 1.06804 0.00913849 -0.00929745 1 0 1 1 0 0 +EDGE2 464 445 0.91568 -0.0632628 -0.0244015 1 0 1 1 0 0 +EDGE2 464 285 0.963251 0.0249322 -0.0282253 1 0 1 1 0 0 +EDGE2 465 404 -0.974989 0.0604704 -0.00106462 1 0 1 1 0 0 +EDGE2 465 444 -1.00362 -0.0408974 -0.0391572 1 0 1 1 0 0 +EDGE2 465 464 -0.935101 0.0311859 -0.00296031 1 0 1 1 0 0 +EDGE2 465 284 -1.05281 -0.0530008 -0.00220624 1 0 1 1 0 0 +EDGE2 465 265 -0.0400663 0.0370705 -3.16196 1 0 1 1 0 0 +EDGE2 465 405 0.0290833 0.0568207 -0.0201128 1 0 1 1 0 0 +EDGE2 465 445 0.0265374 -0.012954 -0.00769419 1 0 1 1 0 0 +EDGE2 465 285 0.035511 0.0403715 -0.0068923 1 0 1 1 0 0 +EDGE2 465 264 1.02638 -0.00145169 -3.10798 1 0 1 1 0 0 +EDGE2 465 446 0.00793022 1.00666 1.5522 1 0 1 1 0 0 +EDGE2 465 266 -0.0591526 1.05107 1.59316 1 0 1 1 0 0 +EDGE2 465 286 0.0312542 1.02421 1.58407 1 0 1 1 0 0 +EDGE2 465 406 -0.00709496 1.01447 1.5581 1 0 1 1 0 0 +EDGE2 466 265 -1.04247 0.0385332 1.5818 1 0 1 1 0 0 +EDGE2 466 405 -0.937267 0.0411085 -1.57831 1 0 1 1 0 0 +EDGE2 466 445 -0.984603 -0.0143891 -1.56555 1 0 1 1 0 0 +EDGE2 466 465 -0.93862 0.0501904 -1.57971 1 0 1 1 0 0 +EDGE2 466 285 -0.957533 0.0235038 -1.53652 1 0 1 1 0 0 +EDGE2 466 446 -0.0246011 0.0484461 -0.00544587 1 0 1 1 0 0 +EDGE2 466 447 1.0322 -0.0592713 -0.013437 1 0 1 1 0 0 +EDGE2 466 266 0.0353521 -0.0262699 -0.0116705 1 0 1 1 0 0 +EDGE2 466 286 -0.00327816 0.0643384 -0.0195055 1 0 1 1 0 0 +EDGE2 466 406 0.00273727 0.0138327 0.0206918 1 0 1 1 0 0 +EDGE2 466 287 0.955387 -0.0234368 0.00560468 1 0 1 1 0 0 +EDGE2 466 407 1.01396 -0.0403135 0.00679029 1 0 1 1 0 0 +EDGE2 466 267 1.02944 0.0769644 0.0183013 1 0 1 1 0 0 +EDGE2 467 446 -1.03498 0.0182346 0.0241207 1 0 1 1 0 0 +EDGE2 467 466 -1.00475 0.0576656 0.018113 1 0 1 1 0 0 +EDGE2 467 447 -0.0998229 -0.0192592 -0.0113992 1 0 1 1 0 0 +EDGE2 467 266 -0.994529 -0.0631555 0.017978 1 0 1 1 0 0 +EDGE2 467 286 -1.01967 0.0323307 -0.00423457 1 0 1 1 0 0 +EDGE2 467 406 -1.0625 -0.0119716 -0.0369315 1 0 1 1 0 0 +EDGE2 467 287 0.0245008 0.000631678 -0.00218975 1 0 1 1 0 0 +EDGE2 467 407 -0.0079272 0.000415408 -0.0208193 1 0 1 1 0 0 +EDGE2 467 267 0.00111181 -0.0391881 -0.0112085 1 0 1 1 0 0 +EDGE2 467 268 0.848536 -0.0952945 0.0313758 1 0 1 1 0 0 +EDGE2 467 408 1.05931 0.0338294 -0.014211 1 0 1 1 0 0 +EDGE2 467 448 0.983933 0.0982608 0.0119677 1 0 1 1 0 0 +EDGE2 467 288 0.970401 -0.0128628 0.00557446 1 0 1 1 0 0 +EDGE2 468 447 -0.962397 -0.024461 0.022835 1 0 1 1 0 0 +EDGE2 468 467 -1.07503 0.0251469 -0.00785563 1 0 1 1 0 0 +EDGE2 468 287 -1.02307 0.0856082 -0.0497683 1 0 1 1 0 0 +EDGE2 468 407 -0.981723 0.0182746 0.0318029 1 0 1 1 0 0 +EDGE2 468 267 -0.979747 -0.00554669 0.00791403 1 0 1 1 0 0 +EDGE2 468 269 0.946665 0.0222098 -0.0227217 1 0 1 1 0 0 +EDGE2 468 268 0.0975434 -0.0135999 -0.01039 1 0 1 1 0 0 +EDGE2 468 408 -0.0235311 -0.0581779 0.0199354 1 0 1 1 0 0 +EDGE2 468 448 -0.0757718 -0.035996 0.0127887 1 0 1 1 0 0 +EDGE2 468 288 -0.0150015 -0.00134915 -0.0171586 1 0 1 1 0 0 +EDGE2 468 409 1.03421 -0.0321739 0.0244194 1 0 1 1 0 0 +EDGE2 468 449 1.05503 -0.0469719 0.0111984 1 0 1 1 0 0 +EDGE2 468 289 1.03268 -0.0436331 -0.0155993 1 0 1 1 0 0 +EDGE2 469 269 0.0496559 0.0243708 -0.0199295 1 0 1 1 0 0 +EDGE2 469 268 -1.03082 -0.0368617 0.0112512 1 0 1 1 0 0 +EDGE2 469 408 -0.957467 0.0147947 -0.0175395 1 0 1 1 0 0 +EDGE2 469 448 -0.947371 0.0223921 0.00996149 1 0 1 1 0 0 +EDGE2 469 468 -0.942361 -0.011829 0.00187586 1 0 1 1 0 0 +EDGE2 469 288 -0.950225 0.0377636 -0.00212469 1 0 1 1 0 0 +EDGE2 469 409 0.00673086 0.0523558 -0.034059 1 0 1 1 0 0 +EDGE2 469 449 -0.0253244 -0.0608044 -0.0234926 1 0 1 1 0 0 +EDGE2 469 289 -0.0172071 0.0366618 0.00867695 1 0 1 1 0 0 +EDGE2 469 410 1.00331 0.00749529 -0.00450637 1 0 1 1 0 0 +EDGE2 469 450 1.00174 -0.00845049 0.0131021 1 0 1 1 0 0 +EDGE2 469 430 0.932652 -0.0281243 -3.12877 1 0 1 1 0 0 +EDGE2 469 270 0.999693 -0.0742293 0.0258551 1 0 1 1 0 0 +EDGE2 469 290 0.899609 0.0326675 -0.00768527 1 0 1 1 0 0 +EDGE2 469 390 1.00372 0.122102 -3.17103 1 0 1 1 0 0 +EDGE2 470 291 -0.0424295 0.989026 1.5992 1 0 1 1 0 0 +EDGE2 470 411 -0.0557664 1.01875 1.54589 1 0 1 1 0 0 +EDGE2 470 431 -0.100466 0.972939 1.58591 1 0 1 1 0 0 +EDGE2 470 451 -0.059384 1.02132 1.58652 1 0 1 1 0 0 +EDGE2 470 391 0.0434088 0.994949 1.57216 1 0 1 1 0 0 +EDGE2 470 269 -1.02091 -0.0180459 -0.0175484 1 0 1 1 0 0 +EDGE2 470 409 -0.972908 -0.00469047 0.0180961 1 0 1 1 0 0 +EDGE2 470 449 -0.999695 -0.022553 -0.00875391 1 0 1 1 0 0 +EDGE2 470 469 -1.01066 -0.00844905 -0.00340292 1 0 1 1 0 0 +EDGE2 470 289 -0.971827 0.0257057 -0.00672011 1 0 1 1 0 0 +EDGE2 470 410 0.0423763 0.0399283 -0.00231213 1 0 1 1 0 0 +EDGE2 470 450 -0.00142802 0.00325471 -0.00475928 1 0 1 1 0 0 +EDGE2 470 271 -0.177817 0.9578 1.57652 1 0 1 1 0 0 +EDGE2 470 430 0.0795338 0.0109479 -3.12308 1 0 1 1 0 0 +EDGE2 470 270 -0.0440563 0.0149 -0.0298246 1 0 1 1 0 0 +EDGE2 470 290 -0.0343542 0.035285 0.015186 1 0 1 1 0 0 +EDGE2 470 390 -0.029324 -0.0396446 -3.1402 1 0 1 1 0 0 +EDGE2 470 389 0.97101 0.0549752 -3.13479 1 0 1 1 0 0 +EDGE2 470 429 0.994642 0.00768394 -3.11532 1 0 1 1 0 0 +EDGE2 471 291 -0.0112068 -0.043905 0.0134064 1 0 1 1 0 0 +EDGE2 471 432 1.01209 -0.0519289 0.00604219 1 0 1 1 0 0 +EDGE2 471 452 1.03264 -0.042553 0.0232581 1 0 1 1 0 0 +EDGE2 471 292 1.02185 0.0614232 0.0157095 1 0 1 1 0 0 +EDGE2 471 392 0.952195 0.00836238 0.0180609 1 0 1 1 0 0 +EDGE2 471 412 1.03729 -0.0578447 -0.0202007 1 0 1 1 0 0 +EDGE2 471 272 1.03986 -0.0529961 0.0113765 1 0 1 1 0 0 +EDGE2 471 411 -0.0142089 0.030141 -0.00542021 1 0 1 1 0 0 +EDGE2 471 431 0.0670465 0.0159208 -0.00184464 1 0 1 1 0 0 +EDGE2 471 451 0.0936825 -0.0401677 -0.00261365 1 0 1 1 0 0 +EDGE2 471 391 0.0213469 -0.0581333 -0.0138763 1 0 1 1 0 0 +EDGE2 471 410 -1.01312 -0.0522006 -1.54924 1 0 1 1 0 0 +EDGE2 471 450 -1.00306 0.0412276 -1.55017 1 0 1 1 0 0 +EDGE2 471 470 -1.01923 0.00424218 -1.54711 1 0 1 1 0 0 +EDGE2 471 271 -0.0162646 -0.0341463 -0.0252498 1 0 1 1 0 0 +EDGE2 471 430 -1.02681 0.0335858 1.5836 1 0 1 1 0 0 +EDGE2 471 270 -1.06382 -0.00254261 -1.59269 1 0 1 1 0 0 +EDGE2 471 290 -1.01617 0.0359257 -1.55655 1 0 1 1 0 0 +EDGE2 471 390 -1.0447 0.00339461 1.60172 1 0 1 1 0 0 +EDGE2 472 291 -0.997192 0.0106704 0.0187919 1 0 1 1 0 0 +EDGE2 472 393 1.00146 0.0133485 0.00049167 1 0 1 1 0 0 +EDGE2 472 433 0.855407 0.0170123 0.0392604 1 0 1 1 0 0 +EDGE2 472 453 0.991886 0.0701678 0.028299 1 0 1 1 0 0 +EDGE2 472 413 0.993028 -0.084349 -0.0241932 1 0 1 1 0 0 +EDGE2 472 432 -0.117428 0.0116048 -0.0269305 1 0 1 1 0 0 +EDGE2 472 273 1.07018 -0.010739 0.0296578 1 0 1 1 0 0 +EDGE2 472 293 1.03721 0.0476352 0.004412 1 0 1 1 0 0 +EDGE2 472 452 -0.0169409 -0.0580461 0.00946819 1 0 1 1 0 0 +EDGE2 472 471 -0.954836 0.00802338 0.0118941 1 0 1 1 0 0 +EDGE2 472 292 -0.00699131 -0.00310301 -0.0282666 1 0 1 1 0 0 +EDGE2 472 392 -0.0566612 -0.0168737 0.000373502 1 0 1 1 0 0 +EDGE2 472 412 -0.019789 0.0043086 -0.00796988 1 0 1 1 0 0 +EDGE2 472 272 0.0757115 -0.0450337 -0.00325482 1 0 1 1 0 0 +EDGE2 472 411 -0.948893 -0.0937957 0.00103927 1 0 1 1 0 0 +EDGE2 472 431 -1.02453 0.0344506 -0.0171145 1 0 1 1 0 0 +EDGE2 472 451 -1.01577 -0.0146478 0.0119913 1 0 1 1 0 0 +EDGE2 472 391 -1.06674 -0.04798 0.0267172 1 0 1 1 0 0 +EDGE2 472 271 -1.01284 0.0432578 -0.00408537 1 0 1 1 0 0 +EDGE2 473 393 -0.00175316 -0.0017165 -0.0156984 1 0 1 1 0 0 +EDGE2 473 434 0.963613 -0.0168149 0.00905676 1 0 1 1 0 0 +EDGE2 473 454 0.974721 -0.0247152 -0.0182222 1 0 1 1 0 0 +EDGE2 473 294 0.994245 -0.0750885 -0.00402765 1 0 1 1 0 0 +EDGE2 473 394 1.00398 -0.0567483 0.0351891 1 0 1 1 0 0 +EDGE2 473 414 0.9862 0.000518724 -0.0117314 1 0 1 1 0 0 +EDGE2 473 274 0.988873 -0.0986844 0.0165392 1 0 1 1 0 0 +EDGE2 473 433 0.0364973 0.00538556 0.00107193 1 0 1 1 0 0 +EDGE2 473 453 0.106368 0.0939753 -0.0318478 1 0 1 1 0 0 +EDGE2 473 413 -0.0550907 0.0605685 -0.0136222 1 0 1 1 0 0 +EDGE2 473 432 -1.08731 0.0750837 -0.0237217 1 0 1 1 0 0 +EDGE2 473 472 -0.924186 -0.0662142 0.018707 1 0 1 1 0 0 +EDGE2 473 273 0.0673133 -0.0671535 0.0285006 1 0 1 1 0 0 +EDGE2 473 293 -0.0170619 0.0482936 -0.0244456 1 0 1 1 0 0 +EDGE2 473 452 -0.956123 0.0283782 0.0119942 1 0 1 1 0 0 +EDGE2 473 292 -0.903159 0.043719 0.0161696 1 0 1 1 0 0 +EDGE2 473 392 -0.929871 -0.0824524 0.0351541 1 0 1 1 0 0 +EDGE2 473 412 -0.966728 -0.0360701 0.00866717 1 0 1 1 0 0 +EDGE2 473 272 -0.964821 -0.042749 0.0192073 1 0 1 1 0 0 +EDGE2 474 393 -0.897924 -0.000966299 0.03115 1 0 1 1 0 0 +EDGE2 474 434 0.0584854 0.0347169 0.0244887 1 0 1 1 0 0 +EDGE2 474 315 1.00998 -0.00142355 -3.12681 1 0 1 1 0 0 +EDGE2 474 415 0.937564 -0.041871 -0.0200194 1 0 1 1 0 0 +EDGE2 474 435 0.985038 0.0774031 -0.00609844 1 0 1 1 0 0 +EDGE2 474 455 1.01459 -0.0602027 -0.0221085 1 0 1 1 0 0 +EDGE2 474 395 0.996247 0.00190237 0.00415711 1 0 1 1 0 0 +EDGE2 474 275 0.994578 -0.0582238 0.0095167 1 0 1 1 0 0 +EDGE2 474 295 0.948507 0.0104601 -0.0253773 1 0 1 1 0 0 +EDGE2 474 454 0.0150149 -0.0606835 -0.0110646 1 0 1 1 0 0 +EDGE2 474 473 -0.965042 0.0839223 -0.0238122 1 0 1 1 0 0 +EDGE2 474 294 -0.057992 -0.0222618 -0.00332165 1 0 1 1 0 0 +EDGE2 474 394 0.0140196 -0.110806 0.0151999 1 0 1 1 0 0 +EDGE2 474 414 -0.0282921 -0.0427622 -0.0100574 1 0 1 1 0 0 +EDGE2 474 274 -0.00743815 -0.0784496 0.00138919 1 0 1 1 0 0 +EDGE2 474 433 -0.949951 -0.0507464 -0.0147915 1 0 1 1 0 0 +EDGE2 474 453 -0.889484 0.0293951 0.0167891 1 0 1 1 0 0 +EDGE2 474 413 -1.00341 -0.0260931 0.0207753 1 0 1 1 0 0 +EDGE2 474 273 -1.02157 0.0634681 0.0155196 1 0 1 1 0 0 +EDGE2 474 293 -1.04415 0.0772072 -0.0102169 1 0 1 1 0 0 +EDGE2 475 314 1.02249 -0.0707876 -3.13354 1 0 1 1 0 0 +EDGE2 475 456 -0.0122575 1.02573 1.56462 1 0 1 1 0 0 +EDGE2 475 296 0.00953503 1.02268 1.58997 1 0 1 1 0 0 +EDGE2 475 396 0.0229536 0.971829 1.55102 1 0 1 1 0 0 +EDGE2 475 436 0.127841 0.956552 1.59383 1 0 1 1 0 0 +EDGE2 475 276 -0.0932707 0.949109 1.54957 1 0 1 1 0 0 +EDGE2 475 434 -1.03381 -0.00926303 0.00118727 1 0 1 1 0 0 +EDGE2 475 315 0.0559905 -0.0442583 -3.13754 1 0 1 1 0 0 +EDGE2 475 415 -0.0485529 -0.0238094 0.00440616 1 0 1 1 0 0 +EDGE2 475 435 -0.00911078 -0.0061932 -0.00472915 1 0 1 1 0 0 +EDGE2 475 455 -0.0373551 -0.0274354 0.00429621 1 0 1 1 0 0 +EDGE2 475 395 -0.0656847 -0.109181 0.00757409 1 0 1 1 0 0 +EDGE2 475 474 -0.927643 0.000667365 0.00206026 1 0 1 1 0 0 +EDGE2 475 275 0.0201825 0.0819931 0.000719349 1 0 1 1 0 0 +EDGE2 475 295 -0.0246632 -0.00965259 -0.0113642 1 0 1 1 0 0 +EDGE2 475 454 -1.06675 0.0168114 -0.0217368 1 0 1 1 0 0 +EDGE2 475 294 -0.924139 0.0317479 -0.0101379 1 0 1 1 0 0 +EDGE2 475 394 -0.930753 -0.0599537 0.0260956 1 0 1 1 0 0 +EDGE2 475 414 -0.959054 -0.00589602 -0.0426929 1 0 1 1 0 0 +EDGE2 475 274 -0.921229 -0.00256315 0.00170298 1 0 1 1 0 0 +EDGE2 475 416 -0.0235212 -0.970116 -1.58927 1 0 1 1 0 0 +EDGE2 475 316 0.030039 -1.01161 -1.58457 1 0 1 1 0 0 +EDGE2 476 475 -0.973966 -0.0398036 -1.54972 1 0 1 1 0 0 +EDGE2 476 437 1.01512 0.0143135 -0.00037515 1 0 1 1 0 0 +EDGE2 476 457 0.955843 0.0949638 -0.000782172 1 0 1 1 0 0 +EDGE2 476 456 -0.064566 -0.14938 0.00331514 1 0 1 1 0 0 +EDGE2 476 277 0.903127 -0.0433315 0.0333742 1 0 1 1 0 0 +EDGE2 476 297 0.944897 0.0649062 0.0325128 1 0 1 1 0 0 +EDGE2 476 397 1.04678 0.019977 -0.0112282 1 0 1 1 0 0 +EDGE2 476 296 -0.0541652 0.0229532 0.0401401 1 0 1 1 0 0 +EDGE2 476 396 0.00939557 -0.0356356 0.0332762 1 0 1 1 0 0 +EDGE2 476 436 0.0718407 0.0351477 0.0225459 1 0 1 1 0 0 +EDGE2 476 276 0.0509931 0.0746218 0.0210632 1 0 1 1 0 0 +EDGE2 476 315 -0.994918 -0.0157421 1.59179 1 0 1 1 0 0 +EDGE2 476 415 -1.00189 -0.00572981 -1.53201 1 0 1 1 0 0 +EDGE2 476 435 -1.04361 -0.0245676 -1.56586 1 0 1 1 0 0 +EDGE2 476 455 -0.984354 -0.0330616 -1.57273 1 0 1 1 0 0 +EDGE2 476 395 -1.00608 -0.0366693 -1.58574 1 0 1 1 0 0 +EDGE2 476 275 -0.997513 0.092469 -1.55958 1 0 1 1 0 0 +EDGE2 476 295 -1.02925 -0.00764188 -1.58316 1 0 1 1 0 0 +EDGE2 477 458 1.04512 0.000302705 0.00322349 1 0 1 1 0 0 +EDGE2 477 298 0.969222 -0.0720818 -0.0134213 1 0 1 1 0 0 +EDGE2 477 398 1.01861 -0.0647477 0.0287707 1 0 1 1 0 0 +EDGE2 477 438 0.951517 -0.000254983 -0.00230401 1 0 1 1 0 0 +EDGE2 477 278 1.03698 -0.0640462 0.00245127 1 0 1 1 0 0 +EDGE2 477 437 0.0455015 -0.0102436 0.0197156 1 0 1 1 0 0 +EDGE2 477 457 0.0120349 0.0319431 -0.00728526 1 0 1 1 0 0 +EDGE2 477 456 -0.960503 -0.0219684 0.0119775 1 0 1 1 0 0 +EDGE2 477 277 0.0779401 -0.0341038 -0.00475485 1 0 1 1 0 0 +EDGE2 477 297 -0.094242 0.0962671 0.00304293 1 0 1 1 0 0 +EDGE2 477 397 -0.104403 -0.0038786 0.00786937 1 0 1 1 0 0 +EDGE2 477 476 -1.01883 -0.037257 0.0192876 1 0 1 1 0 0 +EDGE2 477 296 -1.04918 0.0818154 -0.0271837 1 0 1 1 0 0 +EDGE2 477 396 -1.00216 0.0281094 0.0135248 1 0 1 1 0 0 +EDGE2 477 436 -0.958554 0.0460128 0.0252001 1 0 1 1 0 0 +EDGE2 477 276 -1.01979 0.0176681 -0.0295772 1 0 1 1 0 0 +EDGE2 478 299 1.03365 -0.0359898 -0.0265083 1 0 1 1 0 0 +EDGE2 478 439 0.986151 0.0195507 -0.00666842 1 0 1 1 0 0 +EDGE2 478 459 1.07413 0.0989139 -0.0336736 1 0 1 1 0 0 +EDGE2 478 399 0.965832 -0.0154359 0.0106558 1 0 1 1 0 0 +EDGE2 478 458 -0.0393824 -0.0333484 -0.0555988 1 0 1 1 0 0 +EDGE2 478 279 0.969251 -0.0149867 0.0284293 1 0 1 1 0 0 +EDGE2 478 298 -0.0302717 0.0054658 -0.0060246 1 0 1 1 0 0 +EDGE2 478 398 -0.0467226 0.0359803 0.00945619 1 0 1 1 0 0 +EDGE2 478 438 0.0333808 0.00249297 0.00261465 1 0 1 1 0 0 +EDGE2 478 278 0.0599204 -0.0840888 -0.00730821 1 0 1 1 0 0 +EDGE2 478 437 -1.04729 -0.0864298 0.0147217 1 0 1 1 0 0 +EDGE2 478 457 -0.851928 0.00709118 -0.035431 1 0 1 1 0 0 +EDGE2 478 477 -1.03471 -0.0342743 -0.0398784 1 0 1 1 0 0 +EDGE2 478 277 -0.929116 0.0659802 0.030891 1 0 1 1 0 0 +EDGE2 478 297 -0.907049 0.0133831 -0.0259583 1 0 1 1 0 0 +EDGE2 478 397 -1.01374 -0.0354279 -0.027386 1 0 1 1 0 0 +EDGE2 479 460 0.998283 0.0153403 0.0178504 1 0 1 1 0 0 +EDGE2 479 300 0.99906 0.0789934 -0.0152939 1 0 1 1 0 0 +EDGE2 479 400 0.995943 -0.0459008 -0.0147038 1 0 1 1 0 0 +EDGE2 479 440 1.00101 -0.0172547 -0.047408 1 0 1 1 0 0 +EDGE2 479 280 0.956941 0.0706587 -0.017533 1 0 1 1 0 0 +EDGE2 479 299 0.0970622 0.0369721 -0.0277379 1 0 1 1 0 0 +EDGE2 479 439 -0.0198138 0.00319115 -0.0245588 1 0 1 1 0 0 +EDGE2 479 459 -0.0375258 0.0437292 0.0109187 1 0 1 1 0 0 +EDGE2 479 399 -0.0844005 -0.00709333 -0.0595156 1 0 1 1 0 0 +EDGE2 479 458 -0.969317 0.0107982 -0.00749786 1 0 1 1 0 0 +EDGE2 479 279 -0.0808747 -0.00058557 -0.0183366 1 0 1 1 0 0 +EDGE2 479 478 -1.00805 0.0361777 -0.0232312 1 0 1 1 0 0 +EDGE2 479 298 -0.96864 -0.02412 -0.00619998 1 0 1 1 0 0 +EDGE2 479 398 -0.97611 -0.0123476 -0.00655501 1 0 1 1 0 0 +EDGE2 479 438 -1.03145 -0.0220788 -0.00441324 1 0 1 1 0 0 +EDGE2 479 278 -1.02405 -0.110459 -0.0134206 1 0 1 1 0 0 +EDGE2 480 460 -0.109717 -0.0278172 -0.0094034 1 0 1 1 0 0 +EDGE2 480 301 -0.0142325 -0.96553 -1.5993 1 0 1 1 0 0 +EDGE2 480 300 0.00140788 0.00914676 0.0040194 1 0 1 1 0 0 +EDGE2 480 400 0.0214309 -0.0277473 -0.0282461 1 0 1 1 0 0 +EDGE2 480 440 -0.0607245 0.00470836 0.0141087 1 0 1 1 0 0 +EDGE2 480 280 0.0513232 0.0682216 -0.00280067 1 0 1 1 0 0 +EDGE2 480 401 0.0546746 0.934682 1.53219 1 0 1 1 0 0 +EDGE2 480 441 -0.0665939 0.981514 1.58699 1 0 1 1 0 0 +EDGE2 480 461 0.0212377 0.938122 1.57327 1 0 1 1 0 0 +EDGE2 480 281 0.067726 0.963712 1.56751 1 0 1 1 0 0 +EDGE2 480 299 -1.00747 0.053364 0.0180442 1 0 1 1 0 0 +EDGE2 480 439 -0.995913 0.0687687 0.0172756 1 0 1 1 0 0 +EDGE2 480 459 -0.997053 -0.0605633 -0.036283 1 0 1 1 0 0 +EDGE2 480 479 -1.09279 -0.0450622 -0.0342868 1 0 1 1 0 0 +EDGE2 480 399 -1.02771 0.00542945 -0.00775711 1 0 1 1 0 0 +EDGE2 480 279 -0.957087 0.0488371 0.0124225 1 0 1 1 0 0 +EDGE2 481 460 -1.01387 -0.0271654 -1.57232 1 0 1 1 0 0 +EDGE2 481 480 -0.969262 0.0180452 -1.55287 1 0 1 1 0 0 +EDGE2 481 300 -0.968035 0.0804712 -1.57731 1 0 1 1 0 0 +EDGE2 481 400 -1.16194 -0.0405169 -1.58915 1 0 1 1 0 0 +EDGE2 481 440 -1.0611 0.0132606 -1.52626 1 0 1 1 0 0 +EDGE2 481 280 -0.989905 -0.076804 -1.56065 1 0 1 1 0 0 +EDGE2 481 401 0.0032874 0.00171203 0.0172824 1 0 1 1 0 0 +EDGE2 481 441 0.0200814 -0.0331508 0.0262313 1 0 1 1 0 0 +EDGE2 481 461 -0.0382333 0.00490823 0.0182962 1 0 1 1 0 0 +EDGE2 481 281 -0.0975046 -0.0128084 0.0296062 1 0 1 1 0 0 +EDGE2 481 402 0.920474 -0.0393793 0.00385348 1 0 1 1 0 0 +EDGE2 481 442 1.01499 -0.0251889 0.0106213 1 0 1 1 0 0 +EDGE2 481 462 0.984214 -0.0658664 0.0245405 1 0 1 1 0 0 +EDGE2 481 282 1.00015 -0.06121 0.0083731 1 0 1 1 0 0 +EDGE2 482 481 -1.02314 -0.0274808 -0.0016445 1 0 1 1 0 0 +EDGE2 482 401 -1.06689 0.0865762 -0.0132356 1 0 1 1 0 0 +EDGE2 482 441 -1.00082 -0.00143207 0.0171891 1 0 1 1 0 0 +EDGE2 482 461 -1.01285 -0.0756753 0.0284893 1 0 1 1 0 0 +EDGE2 482 281 -0.982618 0.0155841 0.0190378 1 0 1 1 0 0 +EDGE2 482 402 0.0750345 -0.0352563 -0.00683578 1 0 1 1 0 0 +EDGE2 482 442 -0.00701584 0.0368343 -0.00806421 1 0 1 1 0 0 +EDGE2 482 462 -0.00153082 0.113895 0.0148763 1 0 1 1 0 0 +EDGE2 482 282 0.0948792 -0.0691473 0.0134294 1 0 1 1 0 0 +EDGE2 482 403 0.972399 0.0235831 -0.0223898 1 0 1 1 0 0 +EDGE2 482 443 0.925097 -0.0764838 -0.00457198 1 0 1 1 0 0 +EDGE2 482 463 1.0071 0.0556113 -0.000287828 1 0 1 1 0 0 +EDGE2 482 283 0.991 -0.111587 -0.0337423 1 0 1 1 0 0 +EDGE2 483 482 -1.0309 -0.0583025 0.00919916 1 0 1 1 0 0 +EDGE2 483 402 -1.053 -0.0201875 0.00977608 1 0 1 1 0 0 +EDGE2 483 442 -0.945368 -0.125329 -0.0376517 1 0 1 1 0 0 +EDGE2 483 462 -1.02574 0.00326289 0.00374313 1 0 1 1 0 0 +EDGE2 483 282 -1.03712 0.0127246 0.0124758 1 0 1 1 0 0 +EDGE2 483 403 -0.0756291 0.0747963 0.0156165 1 0 1 1 0 0 +EDGE2 483 443 -0.00918607 0.0329442 0.0161801 1 0 1 1 0 0 +EDGE2 483 463 0.0141551 0.096843 0.00629651 1 0 1 1 0 0 +EDGE2 483 283 -0.0764608 -0.0778914 0.00678409 1 0 1 1 0 0 +EDGE2 483 404 1.00334 0.0194766 -0.0147213 1 0 1 1 0 0 +EDGE2 483 444 0.960018 -0.0746014 0.0084987 1 0 1 1 0 0 +EDGE2 483 464 0.874492 0.0014948 -0.000736655 1 0 1 1 0 0 +EDGE2 483 284 0.950913 -0.00402423 0.0135045 1 0 1 1 0 0 +EDGE2 484 483 -1.01052 0.120879 0.00592377 1 0 1 1 0 0 +EDGE2 484 403 -0.927732 -0.0435103 -0.019429 1 0 1 1 0 0 +EDGE2 484 443 -0.96827 0.00471318 -0.0084982 1 0 1 1 0 0 +EDGE2 484 463 -1.00044 -0.0225631 -0.000280423 1 0 1 1 0 0 +EDGE2 484 283 -0.992424 0.0185516 -0.0274077 1 0 1 1 0 0 +EDGE2 484 404 -0.0047034 -0.0294269 -0.0276659 1 0 1 1 0 0 +EDGE2 484 444 0.0383978 0.0754218 0.0219984 1 0 1 1 0 0 +EDGE2 484 464 0.0346627 0.0323142 -0.00569008 1 0 1 1 0 0 +EDGE2 484 284 -0.0274275 -0.145985 -0.0579133 1 0 1 1 0 0 +EDGE2 484 265 1.07336 0.00546554 -3.14975 1 0 1 1 0 0 +EDGE2 484 405 1.05761 0.0305455 -0.0131946 1 0 1 1 0 0 +EDGE2 484 445 0.990242 -0.0403448 -0.00322655 1 0 1 1 0 0 +EDGE2 484 465 0.995854 0.0154167 -0.0150945 1 0 1 1 0 0 +EDGE2 484 285 0.951632 0.0258851 -0.0185209 1 0 1 1 0 0 +EDGE2 485 484 -1.0014 0.0181538 0.0136348 1 0 1 1 0 0 +EDGE2 485 404 -1.05103 -0.100205 0.0147438 1 0 1 1 0 0 +EDGE2 485 444 -1.02386 -0.053115 -0.0144264 1 0 1 1 0 0 +EDGE2 485 464 -0.963188 0.0103985 0.0061402 1 0 1 1 0 0 +EDGE2 485 284 -1.06069 -0.0822353 0.0168732 1 0 1 1 0 0 +EDGE2 485 265 -0.0517051 0.0229581 -3.16908 1 0 1 1 0 0 +EDGE2 485 405 -0.0497025 -0.0541812 0.0271796 1 0 1 1 0 0 +EDGE2 485 445 0.0477291 0.00719213 -0.00792194 1 0 1 1 0 0 +EDGE2 485 465 0.064704 0.0727057 -0.00581452 1 0 1 1 0 0 +EDGE2 485 285 0.0322093 -0.0652035 0.00777655 1 0 1 1 0 0 +EDGE2 485 264 1.05909 -0.0836 -3.15089 1 0 1 1 0 0 +EDGE2 485 446 -0.0490789 1.06137 1.58882 1 0 1 1 0 0 +EDGE2 485 466 0.107971 0.964196 1.6 1 0 1 1 0 0 +EDGE2 485 266 -0.0210737 1.0437 1.58416 1 0 1 1 0 0 +EDGE2 485 286 -0.00811129 1.03179 1.57405 1 0 1 1 0 0 +EDGE2 485 406 -0.0770458 0.945526 1.55923 1 0 1 1 0 0 +EDGE2 486 485 -1.02238 -0.0735558 1.57021 1 0 1 1 0 0 +EDGE2 486 265 -1.08388 -0.0162621 -1.61934 1 0 1 1 0 0 +EDGE2 486 405 -1.09049 -0.0541697 1.59895 1 0 1 1 0 0 +EDGE2 486 445 -0.8142 -0.0531846 1.59528 1 0 1 1 0 0 +EDGE2 486 465 -1.00593 0.00735507 1.56347 1 0 1 1 0 0 +EDGE2 486 285 -0.9055 0.00116245 1.5925 1 0 1 1 0 0 +EDGE2 487 486 -1.00535 -0.00791997 0.0286408 1 0 1 1 0 0 +EDGE2 488 487 -1.03463 0.017866 -0.00406235 1 0 1 1 0 0 +EDGE2 489 488 -1.01795 -0.0795122 -0.0320585 1 0 1 1 0 0 +EDGE2 490 489 -1.03006 -0.0211822 -0.0121362 1 0 1 1 0 0 +EDGE2 491 490 -0.951142 -0.0318751 -1.58194 1 0 1 1 0 0 +EDGE2 492 491 -1.04447 -0.00932117 -0.0255116 1 0 1 1 0 0 +EDGE2 493 492 -1.05462 -0.0447479 -0.00313592 1 0 1 1 0 0 +EDGE2 494 493 -1.0393 -0.0107586 0.0231477 1 0 1 1 0 0 +EDGE2 494 235 0.964774 -0.0341111 -3.171 1 0 1 1 0 0 +EDGE2 494 255 0.970031 -0.0204866 -3.16799 1 0 1 1 0 0 +EDGE2 495 236 -0.00454494 -1.06161 -1.53248 1 0 1 1 0 0 +EDGE2 495 494 -0.914948 -0.0290772 0.00546252 1 0 1 1 0 0 +EDGE2 495 235 -0.0320556 0.00939473 -3.11881 1 0 1 1 0 0 +EDGE2 495 255 -0.0695434 0.00229568 -3.12298 1 0 1 1 0 0 +EDGE2 495 234 1.02434 0.00188746 -3.11881 1 0 1 1 0 0 +EDGE2 495 254 0.961661 0.0724544 -3.12948 1 0 1 1 0 0 +EDGE2 495 256 -0.0187795 1.02852 1.54924 1 0 1 1 0 0 +EDGE2 496 235 -0.97216 -0.0167394 1.56344 1 0 1 1 0 0 +EDGE2 496 495 -0.947996 0.0395238 -1.58155 1 0 1 1 0 0 +EDGE2 496 255 -1.00456 0.0415557 1.61014 1 0 1 1 0 0 +EDGE2 496 256 0.000307388 -0.071926 0.0271152 1 0 1 1 0 0 +EDGE2 496 257 1.06698 -0.00492717 0.00591191 1 0 1 1 0 0 +EDGE2 497 256 -0.942352 0.00729536 -0.0036228 1 0 1 1 0 0 +EDGE2 497 496 -1.03374 0.125805 -0.0200408 1 0 1 1 0 0 +EDGE2 497 257 0.0878932 0.0380665 0.0175887 1 0 1 1 0 0 +EDGE2 497 258 1.01831 0.0529339 -0.0207086 1 0 1 1 0 0 +EDGE2 498 497 -1.02109 -0.064761 -0.000484933 1 0 1 1 0 0 +EDGE2 498 257 -0.933012 0.0213369 0.0165448 1 0 1 1 0 0 +EDGE2 498 259 0.948607 -0.00489278 0.00685088 1 0 1 1 0 0 +EDGE2 498 258 -0.0180849 -0.000972713 -0.0131651 1 0 1 1 0 0 +EDGE2 499 498 -0.970178 -0.124541 0.00483687 1 0 1 1 0 0 +EDGE2 499 260 0.96367 -0.0259453 0.0154973 1 0 1 1 0 0 +EDGE2 499 259 -0.0292831 -0.0178072 0.00706534 1 0 1 1 0 0 +EDGE2 499 258 -0.926559 0.0464272 0.00520492 1 0 1 1 0 0 +EDGE2 499 180 0.998884 -0.0135414 -3.15804 1 0 1 1 0 0 +EDGE2 499 200 1.04471 -0.0808421 -3.12808 1 0 1 1 0 0 +EDGE2 500 261 0.0160997 0.956863 1.54328 1 0 1 1 0 0 +EDGE2 500 181 0.0754474 -1.0046 -1.60796 1 0 1 1 0 0 +EDGE2 500 260 -0.00792807 0.0164927 0.00459836 1 0 1 1 0 0 +EDGE2 500 259 -0.99343 0.0296209 0.00377084 1 0 1 1 0 0 +EDGE2 500 499 -1.13055 0.0925854 0.00623478 1 0 1 1 0 0 +EDGE2 500 180 -0.0485776 -0.041463 -3.12752 1 0 1 1 0 0 +EDGE2 500 200 0.0161158 -0.0257235 -3.15147 1 0 1 1 0 0 +EDGE2 500 201 0.018415 -1.01018 -1.5786 1 0 1 1 0 0 +EDGE2 500 199 1.0089 0.00238883 -3.18126 1 0 1 1 0 0 +EDGE2 500 179 0.980409 -0.0210936 -3.16869 1 0 1 1 0 0 +EDGE2 501 181 -0.0353461 -8.89785e-05 -0.0217552 1 0 1 1 0 0 +EDGE2 501 260 -0.952599 -0.00952052 1.58047 1 0 1 1 0 0 +EDGE2 501 500 -1.02052 0.0428347 1.5507 1 0 1 1 0 0 +EDGE2 501 180 -1.06139 0.0388865 -1.58971 1 0 1 1 0 0 +EDGE2 501 200 -0.987905 -0.0239371 -1.58259 1 0 1 1 0 0 +EDGE2 501 201 0.0473333 0.010707 -0.00688763 1 0 1 1 0 0 +EDGE2 501 202 1.0601 -0.0305978 -0.0169601 1 0 1 1 0 0 +EDGE2 501 182 1.07722 -0.0408317 -0.0176547 1 0 1 1 0 0 +EDGE2 502 181 -1.033 0.00661366 -0.0279949 1 0 1 1 0 0 +EDGE2 502 501 -0.988975 0.0413063 0.00236082 1 0 1 1 0 0 +EDGE2 502 201 -1.02292 0.0362645 0.00915368 1 0 1 1 0 0 +EDGE2 502 202 -0.035679 0.0210624 0.0290058 1 0 1 1 0 0 +EDGE2 502 182 -0.0498411 0.0155559 -0.0216979 1 0 1 1 0 0 +EDGE2 502 183 0.913702 0.00510418 -0.0160678 1 0 1 1 0 0 +EDGE2 502 203 1.00525 0.0124584 0.000879497 1 0 1 1 0 0 +EDGE2 503 202 -0.952278 -0.0398661 -0.0141552 1 0 1 1 0 0 +EDGE2 503 502 -0.974357 0.0097152 0.00826377 1 0 1 1 0 0 +EDGE2 503 182 -0.973693 -0.0276422 -0.0148811 1 0 1 1 0 0 +EDGE2 503 184 0.987521 0.0476063 0.0273545 1 0 1 1 0 0 +EDGE2 503 183 -0.014398 0.0231094 0.0177927 1 0 1 1 0 0 +EDGE2 503 203 0.0200698 0.0228167 0.00265295 1 0 1 1 0 0 +EDGE2 503 204 0.909255 0.0104182 -0.0379422 1 0 1 1 0 0 +EDGE2 504 503 -1.01938 -0.0348542 0.00127008 1 0 1 1 0 0 +EDGE2 504 205 1.04609 -0.00924191 0.00658939 1 0 1 1 0 0 +EDGE2 504 184 0.147114 -0.120259 -0.0161357 1 0 1 1 0 0 +EDGE2 504 183 -1.02533 -0.0115228 -0.0130319 1 0 1 1 0 0 +EDGE2 504 203 -1.06587 -0.00464738 -0.0334309 1 0 1 1 0 0 +EDGE2 504 204 -0.0462717 0.0495209 0.056959 1 0 1 1 0 0 +EDGE2 504 225 0.977212 0.088224 -3.14424 1 0 1 1 0 0 +EDGE2 504 185 1.06463 -0.00522272 0.0131284 1 0 1 1 0 0 +EDGE2 505 206 -0.0081 -0.984164 -1.59343 1 0 1 1 0 0 +EDGE2 505 226 -0.0549435 -1.00217 -1.5858 1 0 1 1 0 0 +EDGE2 505 205 -0.0319772 -0.0973236 -0.000366967 1 0 1 1 0 0 +EDGE2 505 184 -1.00734 -0.067063 -0.00500227 1 0 1 1 0 0 +EDGE2 505 504 -1.11743 -0.0016288 0.0397323 1 0 1 1 0 0 +EDGE2 505 204 -1.03326 -0.107329 0.0274827 1 0 1 1 0 0 +EDGE2 505 225 -0.0827982 0.00541027 -3.12969 1 0 1 1 0 0 +EDGE2 505 224 1.00553 -0.0324515 -3.177 1 0 1 1 0 0 +EDGE2 505 185 0.0254884 0.0445508 0.0220277 1 0 1 1 0 0 +EDGE2 505 186 0.0996275 1.01014 1.60252 1 0 1 1 0 0 +EDGE2 506 205 -1.02788 0.077249 -1.56035 1 0 1 1 0 0 +EDGE2 506 225 -1.09946 -0.0513587 1.55728 1 0 1 1 0 0 +EDGE2 506 505 -1.05498 -0.0188075 -1.58105 1 0 1 1 0 0 +EDGE2 506 185 -1.01027 0.080079 -1.56337 1 0 1 1 0 0 +EDGE2 506 186 -0.0271034 -0.108137 0.0041481 1 0 1 1 0 0 +EDGE2 506 187 0.920232 0.0789263 -0.00471004 1 0 1 1 0 0 +EDGE2 507 506 -1.02867 -0.0104695 -0.00288147 1 0 1 1 0 0 +EDGE2 507 186 -1.0036 0.00592774 0.0326462 1 0 1 1 0 0 +EDGE2 507 187 -0.00382982 -0.0161205 0.0409264 1 0 1 1 0 0 +EDGE2 507 188 0.984049 -0.0142432 0.00996592 1 0 1 1 0 0 +EDGE2 508 187 -1.0278 -0.0376901 0.013774 1 0 1 1 0 0 +EDGE2 508 507 -0.973508 0.0173161 -0.0249008 1 0 1 1 0 0 +EDGE2 508 188 -0.0211646 -0.0444734 0.0169101 1 0 1 1 0 0 +EDGE2 508 189 1.02117 -0.0809903 -0.0385228 1 0 1 1 0 0 +EDGE2 509 188 -0.972675 -0.0302115 0.00750226 1 0 1 1 0 0 +EDGE2 509 508 -1.03935 0.0283427 -0.0143866 1 0 1 1 0 0 +EDGE2 509 189 0.0626875 -0.0254435 0.0443421 1 0 1 1 0 0 +EDGE2 509 170 1.01925 -0.117869 -3.1751 1 0 1 1 0 0 +EDGE2 509 190 0.997568 0.0794002 -0.00877242 1 0 1 1 0 0 +EDGE2 510 171 0.000268239 0.936776 1.60005 1 0 1 1 0 0 +EDGE2 510 509 -0.997868 0.0418759 0.0273363 1 0 1 1 0 0 +EDGE2 510 189 -0.999578 -0.0478644 0.0444043 1 0 1 1 0 0 +EDGE2 510 191 0.0755985 0.971601 1.53978 1 0 1 1 0 0 +EDGE2 510 170 0.0632574 -0.0169063 -3.12058 1 0 1 1 0 0 +EDGE2 510 190 0.0828727 0.0183962 0.00179275 1 0 1 1 0 0 +EDGE2 510 169 0.980673 0.0473167 -3.1182 1 0 1 1 0 0 +EDGE2 511 170 -1.06956 0.0700442 -1.55182 1 0 1 1 0 0 +EDGE2 511 190 -0.995703 -0.0232225 1.55949 1 0 1 1 0 0 +EDGE2 511 510 -1.01955 0.0483228 1.56928 1 0 1 1 0 0 +EDGE2 512 511 -0.928297 -0.0149373 0.00802283 1 0 1 1 0 0 +EDGE2 513 512 -1.04654 0.0213121 -0.00829566 1 0 1 1 0 0 +EDGE2 514 513 -1.03325 -0.0159228 -0.00166793 1 0 1 1 0 0 +EDGE2 515 514 -0.936104 -0.0536365 -0.0156087 1 0 1 1 0 0 +EDGE2 516 515 -1.01317 0.0151175 -1.5438 1 0 1 1 0 0 +EDGE2 517 516 -1.05499 -0.0042139 -0.0107244 1 0 1 1 0 0 +EDGE2 518 517 -0.993755 -0.0797857 0.0115435 1 0 1 1 0 0 +EDGE2 519 518 -1.00802 -0.0222472 -0.0228397 1 0 1 1 0 0 +EDGE2 520 519 -0.986852 0.0186222 0.000964726 1 0 1 1 0 0 +EDGE2 521 520 -0.892176 -0.0217093 1.58758 1 0 1 1 0 0 +EDGE2 522 521 -1.01409 0.0325784 0.000544756 1 0 1 1 0 0 +EDGE2 523 522 -0.980095 0.0311644 -0.022426 1 0 1 1 0 0 +EDGE2 524 523 -1.03481 -0.025868 0.0348324 1 0 1 1 0 0 +EDGE2 525 524 -1.00879 -0.0063681 -0.0105593 1 0 1 1 0 0 +EDGE2 526 525 -0.963032 0.0550979 -1.5557 1 0 1 1 0 0 +EDGE2 527 526 -0.940257 0.0371392 -0.0264358 1 0 1 1 0 0 +EDGE2 528 527 -0.994954 0.0167585 -0.043028 1 0 1 1 0 0 +EDGE2 529 528 -1.0362 -0.110076 -0.00226272 1 0 1 1 0 0 +EDGE2 530 529 -1.02223 -0.0109656 0.0289831 1 0 1 1 0 0 +EDGE2 531 530 -1.06108 -0.121089 -1.54673 1 0 1 1 0 0 +EDGE2 532 531 -0.904769 0.0153188 -0.0184056 1 0 1 1 0 0 +EDGE2 533 532 -1.10531 -0.0139675 -0.00758959 1 0 1 1 0 0 +EDGE2 534 533 -1.03614 -0.0203644 0.0107839 1 0 1 1 0 0 +EDGE2 535 534 -0.938554 -0.095887 -0.00786866 1 0 1 1 0 0 +EDGE2 536 535 -0.975843 -0.0291868 -1.52103 1 0 1 1 0 0 +EDGE2 537 536 -0.973229 -0.0187179 0.0292916 1 0 1 1 0 0 +EDGE2 538 537 -1.03159 0.0135272 0.000887605 1 0 1 1 0 0 +EDGE2 539 520 1.0421 -0.00825265 -3.16913 1 0 1 1 0 0 +EDGE2 539 538 -0.965005 -0.00919667 0.00192367 1 0 1 1 0 0 +EDGE2 540 519 0.961684 0.0397209 -3.13763 1 0 1 1 0 0 +EDGE2 540 520 -0.00715438 0.0723713 -3.15493 1 0 1 1 0 0 +EDGE2 540 521 0.056701 0.972703 1.54567 1 0 1 1 0 0 +EDGE2 540 539 -1.02619 -0.0176533 0.00671587 1 0 1 1 0 0 +EDGE2 541 520 -1.05163 -0.0364537 -1.5775 1 0 1 1 0 0 +EDGE2 541 540 -1.03828 -0.0531352 1.56929 1 0 1 1 0 0 +EDGE2 542 541 -0.991512 0.0108359 0.0175491 1 0 1 1 0 0 +EDGE2 543 542 -1.04454 -0.0108814 -0.00342393 1 0 1 1 0 0 +EDGE2 544 165 0.986842 -0.036631 -3.15431 1 0 1 1 0 0 +EDGE2 544 543 -0.960533 -0.0370758 -0.0242235 1 0 1 1 0 0 +EDGE2 545 166 0.0580216 1.06007 1.58831 1 0 1 1 0 0 +EDGE2 545 544 -0.928276 0.00945314 -0.0195721 1 0 1 1 0 0 +EDGE2 545 164 0.987094 0.0217007 -3.11826 1 0 1 1 0 0 +EDGE2 545 165 -0.0120158 -0.00845003 -3.11893 1 0 1 1 0 0 +EDGE2 546 545 -1.06474 0.0527217 1.61323 1 0 1 1 0 0 +EDGE2 546 165 -0.964153 -0.0418414 -1.5273 1 0 1 1 0 0 +EDGE2 547 546 -1.05462 -0.00850539 -0.00659933 1 0 1 1 0 0 +EDGE2 548 547 -0.956535 0.0583722 0.000777076 1 0 1 1 0 0 +EDGE2 549 548 -1.06415 -0.0459027 0.0240779 1 0 1 1 0 0 +EDGE2 550 549 -0.972956 0.113231 -0.0172359 1 0 1 1 0 0 +EDGE2 551 550 -1.0015 0.0461091 1.58124 1 0 1 1 0 0 +EDGE2 552 551 -1.03081 0.0160035 -0.0227768 1 0 1 1 0 0 +EDGE2 553 552 -0.966144 0.0145637 0.0172355 1 0 1 1 0 0 +EDGE2 554 553 -0.958508 -0.11264 -0.0122259 1 0 1 1 0 0 +EDGE2 554 535 0.981297 -0.0581086 -3.11864 1 0 1 1 0 0 +EDGE2 555 534 0.962727 0.0187884 -3.15886 1 0 1 1 0 0 +EDGE2 555 536 -0.0548614 -0.91522 -1.60499 1 0 1 1 0 0 +EDGE2 555 554 -1.01411 -0.0369302 0.0230123 1 0 1 1 0 0 +EDGE2 555 535 -0.0123034 -0.000247839 -3.09805 1 0 1 1 0 0 +EDGE2 556 555 -0.973452 0.0169942 -1.54551 1 0 1 1 0 0 +EDGE2 556 535 -1.02838 0.0309447 1.62588 1 0 1 1 0 0 +EDGE2 557 556 -0.951603 0.0696264 0.0359682 1 0 1 1 0 0 +EDGE2 558 557 -1.01973 -0.0332312 -0.032132 1 0 1 1 0 0 +EDGE2 559 558 -0.928251 -0.0383098 0.000114499 1 0 1 1 0 0 +EDGE2 560 559 -0.956301 0.000682173 -0.00127682 1 0 1 1 0 0 +EDGE2 561 560 -0.980265 0.01057 1.56806 1 0 1 1 0 0 +EDGE2 562 561 -1.00541 0.0126667 0.00673411 1 0 1 1 0 0 +EDGE2 563 562 -1.03235 -0.0381457 -0.0148413 1 0 1 1 0 0 +EDGE2 564 563 -0.988362 -0.0113643 -0.00223228 1 0 1 1 0 0 +EDGE2 565 564 -0.963205 0.0655898 -0.015864 1 0 1 1 0 0 +EDGE2 566 565 -0.936971 -0.0805397 -1.61019 1 0 1 1 0 0 +EDGE2 567 566 -0.97164 0.0679178 0.0493468 1 0 1 1 0 0 +EDGE2 568 567 -0.917506 -0.0735887 0.0182816 1 0 1 1 0 0 +EDGE2 569 568 -0.999179 -0.0569117 0.00585808 1 0 1 1 0 0 +EDGE2 570 569 -0.953564 -0.0201128 -0.00253602 1 0 1 1 0 0 +EDGE2 571 570 -0.978685 -0.119068 1.56326 1 0 1 1 0 0 +EDGE2 572 571 -0.997879 -0.0160949 -0.00322153 1 0 1 1 0 0 +EDGE2 573 572 -0.987697 -0.000482517 -0.006304 1 0 1 1 0 0 +EDGE2 574 573 -0.888846 -0.0665069 0.00462262 1 0 1 1 0 0 +EDGE2 575 574 -0.991761 0.0169261 0.0125815 1 0 1 1 0 0 +EDGE2 576 575 -1.02182 0.0457307 -1.57597 1 0 1 1 0 0 +EDGE2 577 576 -1.0497 -0.00981091 0.0160578 1 0 1 1 0 0 +EDGE2 578 577 -0.979055 -0.0536499 -0.00266357 1 0 1 1 0 0 +EDGE2 579 578 -1.0897 -0.0259836 -0.00322182 1 0 1 1 0 0 +EDGE2 580 579 -1.08443 -0.0353979 0.034935 1 0 1 1 0 0 +EDGE2 581 580 -0.992486 0.0546998 1.54469 1 0 1 1 0 0 +EDGE2 582 581 -1.03336 0.0296225 -0.0181571 1 0 1 1 0 0 +EDGE2 583 582 -0.996487 0.0803869 -0.00241479 1 0 1 1 0 0 +EDGE2 584 583 -1.02789 0.0011751 -0.00881189 1 0 1 1 0 0 +EDGE2 585 584 -1.00175 -0.0060586 8.4945e-05 1 0 1 1 0 0 +EDGE2 586 585 -1.03683 0.00805738 -1.56397 1 0 1 1 0 0 +EDGE2 587 586 -0.970478 0.0595809 -0.00373618 1 0 1 1 0 0 +EDGE2 588 587 -1.05555 0.00881011 -0.0178818 1 0 1 1 0 0 +EDGE2 589 588 -1.01246 0.0567415 0.0257734 1 0 1 1 0 0 +EDGE2 590 589 -0.996627 -0.114209 0.0272816 1 0 1 1 0 0 +EDGE2 591 590 -1.04882 -0.0325469 1.58328 1 0 1 1 0 0 +EDGE2 592 591 -1.00487 0.0368769 -0.0158748 1 0 1 1 0 0 +EDGE2 593 592 -0.997364 -0.0444423 0.00232855 1 0 1 1 0 0 +EDGE2 594 593 -0.997976 -0.0326796 -0.00203239 1 0 1 1 0 0 +EDGE2 595 594 -0.909422 0.0245871 0.0578041 1 0 1 1 0 0 +EDGE2 596 595 -0.941734 -0.00794109 -1.60395 1 0 1 1 0 0 +EDGE2 597 596 -0.924003 0.00435161 0.0119912 1 0 1 1 0 0 +EDGE2 598 597 -1.00558 0.0511262 0.00683494 1 0 1 1 0 0 +EDGE2 599 598 -1.07572 -0.000378858 0.0247963 1 0 1 1 0 0 +EDGE2 600 599 -0.98284 0.0204911 0.0116805 1 0 1 1 0 0 +EDGE2 601 600 -0.997194 0.107949 -1.58561 1 0 1 1 0 0 +EDGE2 602 601 -1.03733 -3.96711e-05 -0.0102578 1 0 1 1 0 0 +EDGE2 603 602 -0.936612 -0.0547512 -0.00905842 1 0 1 1 0 0 +EDGE2 604 603 -1.02209 -0.0168496 0.00351108 1 0 1 1 0 0 +EDGE2 605 604 -1.07245 -0.137739 -0.0474661 1 0 1 1 0 0 +EDGE2 606 605 -0.954856 -0.035981 1.58022 1 0 1 1 0 0 +EDGE2 607 606 -1.05225 -0.0603187 0.00976099 1 0 1 1 0 0 +EDGE2 608 607 -0.997264 0.0584897 -0.0128574 1 0 1 1 0 0 +EDGE2 609 608 -1.01041 0.0155689 0.0390507 1 0 1 1 0 0 +EDGE2 610 609 -0.954143 0.0169681 -0.0151077 1 0 1 1 0 0 +EDGE2 611 610 -1.02713 -0.0138027 1.56423 1 0 1 1 0 0 +EDGE2 612 611 -0.997517 -0.0326425 -0.0174774 1 0 1 1 0 0 +EDGE2 613 612 -0.969019 -0.0174928 0.00771469 1 0 1 1 0 0 +EDGE2 614 613 -0.979477 -0.0586305 0.0116687 1 0 1 1 0 0 +EDGE2 615 614 -1.03418 0.0570392 -0.029252 1 0 1 1 0 0 +EDGE2 616 615 -1.03465 0.0185912 -1.57145 1 0 1 1 0 0 +EDGE2 617 616 -1.01096 0.0512759 -0.0197068 1 0 1 1 0 0 +EDGE2 618 617 -0.969197 0.0299786 -0.0023761 1 0 1 1 0 0 +EDGE2 619 618 -1.01784 0.0280199 -0.0145759 1 0 1 1 0 0 +EDGE2 620 619 -1.01844 -0.0309336 -0.0113745 1 0 1 1 0 0 +EDGE2 621 620 -0.906225 0.0105585 1.55172 1 0 1 1 0 0 +EDGE2 622 621 -0.954389 -0.0435734 -0.0326502 1 0 1 1 0 0 +EDGE2 623 622 -1.00767 0.00928202 -0.0140941 1 0 1 1 0 0 +EDGE2 624 623 -1.08794 -0.00655902 -0.0067322 1 0 1 1 0 0 +EDGE2 625 624 -0.983258 0.000832694 0.0231347 1 0 1 1 0 0 +EDGE2 626 625 -1.00122 0.0347913 1.57471 1 0 1 1 0 0 +EDGE2 627 626 -0.988076 -0.0142133 -0.0274332 1 0 1 1 0 0 +EDGE2 628 627 -1.0042 -0.0184629 -0.00625932 1 0 1 1 0 0 +EDGE2 629 628 -0.968824 -0.0914319 0.0212604 1 0 1 1 0 0 +EDGE2 630 629 -1.02371 0.0581906 -0.00420895 1 0 1 1 0 0 +EDGE2 631 630 -0.970616 0.000883726 -1.60432 1 0 1 1 0 0 +EDGE2 632 631 -0.973259 -0.039159 0.00789895 1 0 1 1 0 0 +EDGE2 633 632 -1.01838 -0.0100946 -0.00496689 1 0 1 1 0 0 +EDGE2 634 633 -0.977497 -0.0167645 0.0403412 1 0 1 1 0 0 +EDGE2 635 634 -0.926055 0.0882788 -0.00641983 1 0 1 1 0 0 +EDGE2 636 635 -0.983999 0.0797255 -1.58574 1 0 1 1 0 0 +EDGE2 637 636 -1.00117 0.0159726 0.00929688 1 0 1 1 0 0 +EDGE2 638 637 -1.00007 0.0117785 0.00851935 1 0 1 1 0 0 +EDGE2 639 638 -0.984878 -0.0630311 0.000878265 1 0 1 1 0 0 +EDGE2 640 639 -1.00375 0.0277419 -0.0167835 1 0 1 1 0 0 +EDGE2 641 640 -1.11628 0.00744241 -1.57375 1 0 1 1 0 0 +EDGE2 642 641 -0.987699 -0.00498387 0.0106514 1 0 1 1 0 0 +EDGE2 643 642 -1.02145 0.0486377 0.020507 1 0 1 1 0 0 +EDGE2 644 625 1.05889 -0.0422569 -3.14282 1 0 1 1 0 0 +EDGE2 644 643 -0.940927 -0.0202611 0.0397781 1 0 1 1 0 0 +EDGE2 645 624 0.953489 0.0118819 -3.15125 1 0 1 1 0 0 +EDGE2 645 626 0.0437742 0.908902 1.56371 1 0 1 1 0 0 +EDGE2 645 644 -0.993425 0.0162602 0.0288982 1 0 1 1 0 0 +EDGE2 645 625 -0.0260627 0.00757731 -3.16404 1 0 1 1 0 0 +EDGE2 646 626 -0.000874505 -3.68194e-05 0.0365181 1 0 1 1 0 0 +EDGE2 646 627 1.05827 -0.111291 0.00445057 1 0 1 1 0 0 +EDGE2 646 625 -1.01658 -0.0232441 1.56316 1 0 1 1 0 0 +EDGE2 646 645 -0.947437 -0.00892872 -1.54027 1 0 1 1 0 0 +EDGE2 647 626 -1.00872 -0.0274974 -0.00247032 1 0 1 1 0 0 +EDGE2 647 627 -0.075166 -0.00797096 -0.00741248 1 0 1 1 0 0 +EDGE2 647 628 0.928059 -0.0223918 0.000762217 1 0 1 1 0 0 +EDGE2 647 646 -1.05425 -0.0088557 -0.0198645 1 0 1 1 0 0 +EDGE2 648 629 0.92806 0.0825324 0.00592717 1 0 1 1 0 0 +EDGE2 648 627 -0.972383 0.0262558 -0.00618544 1 0 1 1 0 0 +EDGE2 648 647 -1.03157 -0.00991503 -0.00805822 1 0 1 1 0 0 +EDGE2 648 628 -0.0327143 0.00407262 -0.0132481 1 0 1 1 0 0 +EDGE2 649 630 1.06695 -0.0313366 -0.00164922 1 0 1 1 0 0 +EDGE2 649 648 -1.08144 0.0839391 -0.00608744 1 0 1 1 0 0 +EDGE2 649 629 -0.0255995 -0.0243674 0.00956789 1 0 1 1 0 0 +EDGE2 649 628 -1.02575 -0.138373 0.0131143 1 0 1 1 0 0 +EDGE2 650 630 -0.0245217 -0.053649 -0.00793558 1 0 1 1 0 0 +EDGE2 650 631 -0.00401838 0.962542 1.59119 1 0 1 1 0 0 +EDGE2 650 649 -0.96559 -0.00461982 0.00226287 1 0 1 1 0 0 +EDGE2 650 629 -1.00072 0.0888196 -0.0145956 1 0 1 1 0 0 +EDGE2 651 630 -0.959541 0.0687554 -1.57285 1 0 1 1 0 0 +EDGE2 651 650 -1.05319 -0.0701524 -1.55699 1 0 1 1 0 0 +EDGE2 651 631 -0.0152516 0.0405165 0.0165062 1 0 1 1 0 0 +EDGE2 651 632 1.07595 0.0465982 -0.022415 1 0 1 1 0 0 +EDGE2 652 651 -1.0277 0.0392475 -0.0390359 1 0 1 1 0 0 +EDGE2 652 631 -0.990541 -0.0211265 -0.0193188 1 0 1 1 0 0 +EDGE2 652 632 0.063636 -0.0753537 0.00214301 1 0 1 1 0 0 +EDGE2 652 633 0.997008 -0.00819416 -0.00100117 1 0 1 1 0 0 +EDGE2 653 652 -0.962776 -0.0751585 0.0219434 1 0 1 1 0 0 +EDGE2 653 632 -1.1116 -0.0766149 -0.0190175 1 0 1 1 0 0 +EDGE2 653 633 -0.0229445 -0.0195848 0.00481797 1 0 1 1 0 0 +EDGE2 653 634 1.02721 -0.0268188 0.00410987 1 0 1 1 0 0 +EDGE2 654 633 -0.87571 0.0824644 0.00390929 1 0 1 1 0 0 +EDGE2 654 653 -0.983768 0.00739539 0.0252459 1 0 1 1 0 0 +EDGE2 654 635 1.06847 -0.0457621 -0.0130272 1 0 1 1 0 0 +EDGE2 654 634 -0.00590258 0.00372929 -0.00967701 1 0 1 1 0 0 +EDGE2 655 635 0.00900248 0.034073 0.0172406 1 0 1 1 0 0 +EDGE2 655 634 -1.00005 -0.0474622 -0.0124335 1 0 1 1 0 0 +EDGE2 655 654 -1.00606 -0.0392174 -0.028934 1 0 1 1 0 0 +EDGE2 655 636 -0.00125612 1.05144 1.55502 1 0 1 1 0 0 +EDGE2 656 635 -0.982396 0.00435962 -1.54905 1 0 1 1 0 0 +EDGE2 656 655 -1.01898 0.0023445 -1.60132 1 0 1 1 0 0 +EDGE2 656 636 -0.0460716 -0.0402886 0.00756754 1 0 1 1 0 0 +EDGE2 656 637 1.0181 0.0375902 0.0191897 1 0 1 1 0 0 +EDGE2 657 656 -1.01923 -0.0475655 -0.0159199 1 0 1 1 0 0 +EDGE2 657 636 -0.985646 0.0374246 -0.02675 1 0 1 1 0 0 +EDGE2 657 637 0.0647302 0.0440874 -0.0042493 1 0 1 1 0 0 +EDGE2 657 638 1.02641 0.0417719 0.0180921 1 0 1 1 0 0 +EDGE2 658 657 -0.967164 -0.0970801 0.00981033 1 0 1 1 0 0 +EDGE2 658 637 -0.922757 -0.0121902 0.0259288 1 0 1 1 0 0 +EDGE2 658 638 -0.0425697 0.0249097 0.0323066 1 0 1 1 0 0 +EDGE2 658 639 0.987146 0.0307473 0.000216141 1 0 1 1 0 0 +EDGE2 659 658 -0.950514 -0.113432 0.0185846 1 0 1 1 0 0 +EDGE2 659 638 -0.937444 -0.0294359 0.0171358 1 0 1 1 0 0 +EDGE2 659 639 0.0228938 0.0221863 0.000872867 1 0 1 1 0 0 +EDGE2 659 640 0.979276 0.0384537 0.0207422 1 0 1 1 0 0 +EDGE2 660 639 -0.96637 0.0454004 -0.0262165 1 0 1 1 0 0 +EDGE2 660 659 -0.985441 -0.0101839 -0.0330751 1 0 1 1 0 0 +EDGE2 660 641 -0.00676604 0.985479 1.58256 1 0 1 1 0 0 +EDGE2 660 640 0.0292292 -0.0134136 -0.00456404 1 0 1 1 0 0 +EDGE2 661 640 -0.937427 0.0155962 1.5909 1 0 1 1 0 0 +EDGE2 661 660 -0.913285 0.0575382 1.5817 1 0 1 1 0 0 +EDGE2 662 661 -1.02957 0.00439684 0.00629337 1 0 1 1 0 0 +EDGE2 663 662 -0.925736 0.0441923 0.00244613 1 0 1 1 0 0 +EDGE2 664 663 -0.923863 0.0432385 -0.000432792 1 0 1 1 0 0 +EDGE2 665 664 -1.01639 0.0578353 -0.0303297 1 0 1 1 0 0 +EDGE2 666 665 -1.03093 0.072076 -1.5942 1 0 1 1 0 0 +EDGE2 667 666 -1.04806 0.000323751 0.0187504 1 0 1 1 0 0 +EDGE2 668 667 -0.900708 0.00341668 -0.0161888 1 0 1 1 0 0 +EDGE2 669 668 -0.994383 0.0109776 -0.0134472 1 0 1 1 0 0 +EDGE2 670 669 -1.0486 -0.0292462 0.00530722 1 0 1 1 0 0 +EDGE2 671 670 -1.05013 -0.0524251 -1.54584 1 0 1 1 0 0 +EDGE2 672 671 -1.09904 0.057232 -0.00868276 1 0 1 1 0 0 +EDGE2 673 672 -1.06033 -0.0733947 -0.00894376 1 0 1 1 0 0 +EDGE2 674 673 -1.0099 0.00320383 0.0109273 1 0 1 1 0 0 +EDGE2 675 674 -0.990679 0.0109315 0.0244224 1 0 1 1 0 0 +EDGE2 676 675 -1.00317 -0.0478957 1.58966 1 0 1 1 0 0 +EDGE2 677 676 -1.01812 -0.0443062 0.00536246 1 0 1 1 0 0 +EDGE2 678 677 -0.988363 -0.117057 0.0100022 1 0 1 1 0 0 +EDGE2 679 678 -1.04432 0.111225 -0.0159544 1 0 1 1 0 0 +EDGE2 680 679 -0.983458 -0.0115513 0.00148164 1 0 1 1 0 0 +EDGE2 681 680 -0.96006 0.00799815 -1.56426 1 0 1 1 0 0 +EDGE2 682 681 -1.00968 0.144007 0.0108645 1 0 1 1 0 0 +EDGE2 683 682 -0.995907 0.0206061 -0.018501 1 0 1 1 0 0 +EDGE2 684 683 -0.881375 -0.00865935 -0.0158057 1 0 1 1 0 0 +EDGE2 685 684 -0.939971 -0.00104398 -0.0129528 1 0 1 1 0 0 +EDGE2 686 685 -1.0209 -0.000880124 1.59486 1 0 1 1 0 0 +EDGE2 687 686 -0.920266 -0.197516 -0.0161772 1 0 1 1 0 0 +EDGE2 688 687 -1.02781 -0.0268124 -0.0336947 1 0 1 1 0 0 +EDGE2 689 688 -0.976848 0.0210124 -0.0494787 1 0 1 1 0 0 +EDGE2 690 689 -0.940515 -0.0321993 0.0283898 1 0 1 1 0 0 +EDGE2 691 690 -1.03223 -0.0232673 -1.55617 1 0 1 1 0 0 +EDGE2 692 691 -1.08233 0.013857 -0.00205678 1 0 1 1 0 0 +EDGE2 693 692 -0.952635 -0.0386177 -0.016556 1 0 1 1 0 0 +EDGE2 694 693 -1.00056 0.0652274 0.0421877 1 0 1 1 0 0 +EDGE2 695 694 -1.07205 -0.0421465 0.0142559 1 0 1 1 0 0 +EDGE2 696 695 -0.923733 -0.025709 1.5548 1 0 1 1 0 0 +EDGE2 697 696 -0.980837 0.0458146 0.000989911 1 0 1 1 0 0 +EDGE2 698 697 -1.05045 -0.0605976 0.00205651 1 0 1 1 0 0 +EDGE2 699 698 -1.10007 -0.0010042 -0.00254479 1 0 1 1 0 0 +EDGE2 700 699 -1.03322 -0.027048 0.0321946 1 0 1 1 0 0 +EDGE2 701 700 -0.967786 -0.0373999 1.58527 1 0 1 1 0 0 +EDGE2 702 701 -0.991789 0.0251844 0.024998 1 0 1 1 0 0 +EDGE2 703 702 -1.09424 -0.0551738 0.0129698 1 0 1 1 0 0 +EDGE2 704 703 -0.958703 -0.0482951 -0.0177369 1 0 1 1 0 0 +EDGE2 705 704 -0.992727 0.00209999 -0.0216804 1 0 1 1 0 0 +EDGE2 706 705 -1.00634 0.0216091 -1.59915 1 0 1 1 0 0 +EDGE2 707 706 -1.0273 0.0769383 0.00892962 1 0 1 1 0 0 +EDGE2 708 707 -0.975951 0.00128981 0.0100573 1 0 1 1 0 0 +EDGE2 709 708 -1.00312 -0.107949 -0.00298962 1 0 1 1 0 0 +EDGE2 710 709 -0.972231 -0.063297 0.0159068 1 0 1 1 0 0 +EDGE2 711 710 -0.968124 0.141295 -1.58313 1 0 1 1 0 0 +EDGE2 712 711 -0.968526 0.0261574 -0.00866988 1 0 1 1 0 0 +EDGE2 713 712 -0.953389 -0.00864359 0.0456326 1 0 1 1 0 0 +EDGE2 714 713 -1.04157 -0.0109008 -0.016396 1 0 1 1 0 0 +EDGE2 715 714 -1.04317 -0.0411538 0.0317176 1 0 1 1 0 0 +EDGE2 716 715 -0.983698 0.0775507 1.55721 1 0 1 1 0 0 +EDGE2 717 716 -1.00108 -0.0595939 0.0251503 1 0 1 1 0 0 +EDGE2 718 717 -1.00833 -0.0356875 -0.0593475 1 0 1 1 0 0 +EDGE2 719 718 -0.995637 -0.00225268 0.00522465 1 0 1 1 0 0 +EDGE2 720 719 -1.00865 0.00789439 0.0133314 1 0 1 1 0 0 +EDGE2 721 720 -1.00546 -0.0172746 1.56764 1 0 1 1 0 0 +EDGE2 722 721 -0.973793 0.0532386 -0.0193509 1 0 1 1 0 0 +EDGE2 723 722 -1.06582 0.0253653 -0.0374447 1 0 1 1 0 0 +EDGE2 724 723 -1.04346 0.00234407 0.0368518 1 0 1 1 0 0 +EDGE2 725 724 -1.04701 0.126912 -0.0243688 1 0 1 1 0 0 +EDGE2 726 725 -0.964941 -0.0694076 1.59025 1 0 1 1 0 0 +EDGE2 727 726 -0.95116 -0.00292344 -0.00361513 1 0 1 1 0 0 +EDGE2 728 727 -0.939548 0.00982116 0.00398849 1 0 1 1 0 0 +EDGE2 729 710 0.959136 -0.0856371 -3.16376 1 0 1 1 0 0 +EDGE2 729 728 -1.04468 0.0624824 0.0403656 1 0 1 1 0 0 +EDGE2 730 711 0.00045214 -1.10474 -1.54627 1 0 1 1 0 0 +EDGE2 730 709 0.978944 0.00215415 -3.14687 1 0 1 1 0 0 +EDGE2 730 710 0.0475644 0.0304379 -3.17289 1 0 1 1 0 0 +EDGE2 730 729 -1.00398 -0.116512 -0.0127278 1 0 1 1 0 0 +EDGE2 731 712 0.962698 -0.0703452 -0.00427963 1 0 1 1 0 0 +EDGE2 731 711 -0.00824934 0.00391569 -0.00714246 1 0 1 1 0 0 +EDGE2 731 730 -1.07361 0.0674765 1.60031 1 0 1 1 0 0 +EDGE2 731 710 -0.936873 0.0343109 -1.58101 1 0 1 1 0 0 +EDGE2 732 713 1.0677 -0.0213076 0.00198463 1 0 1 1 0 0 +EDGE2 732 712 0.112246 0.0229474 -0.0271135 1 0 1 1 0 0 +EDGE2 732 711 -1.00235 -0.0667512 -0.0117727 1 0 1 1 0 0 +EDGE2 732 731 -0.970158 0.0764007 -0.00588552 1 0 1 1 0 0 +EDGE2 733 714 1.06308 -0.0437486 0.00675792 1 0 1 1 0 0 +EDGE2 733 732 -1.04436 0.0374579 -0.0322735 1 0 1 1 0 0 +EDGE2 733 713 0.0294812 0.0379291 -0.0126546 1 0 1 1 0 0 +EDGE2 733 712 -0.960954 -0.0233677 0.0020163 1 0 1 1 0 0 +EDGE2 734 715 1.04934 0.0893481 -0.00224197 1 0 1 1 0 0 +EDGE2 734 714 -0.00541271 -0.0512887 -0.0268494 1 0 1 1 0 0 +EDGE2 734 713 -0.932874 3.74228e-05 0.0203538 1 0 1 1 0 0 +EDGE2 734 733 -0.998547 -0.0256871 -0.040342 1 0 1 1 0 0 +EDGE2 735 715 -0.0703776 0.0896383 0.0286872 1 0 1 1 0 0 +EDGE2 735 734 -0.947035 0.0274127 0.0130504 1 0 1 1 0 0 +EDGE2 735 714 -1.01051 0.0174734 0.0204335 1 0 1 1 0 0 +EDGE2 735 716 0.0592184 -1.04014 -1.56241 1 0 1 1 0 0 +EDGE2 736 715 -1.0114 -0.00703803 -1.54533 1 0 1 1 0 0 +EDGE2 736 735 -1.0666 -0.027026 -1.60594 1 0 1 1 0 0 +EDGE2 737 736 -0.9247 -0.0603988 0.0148156 1 0 1 1 0 0 +EDGE2 738 737 -1.02361 0.0354577 -0.0223621 1 0 1 1 0 0 +EDGE2 739 700 1.01754 -0.0411377 -3.14393 1 0 1 1 0 0 +EDGE2 739 738 -0.965077 -0.0210721 0.0178123 1 0 1 1 0 0 +EDGE2 740 699 0.937839 -0.026811 -3.12831 1 0 1 1 0 0 +EDGE2 740 701 0.0527722 0.913615 1.5517 1 0 1 1 0 0 +EDGE2 740 700 0.0613353 0.0421203 -3.14213 1 0 1 1 0 0 +EDGE2 740 739 -1.00177 -0.0113285 -0.0230735 1 0 1 1 0 0 +EDGE2 741 740 -1.04643 -0.0126065 1.58807 1 0 1 1 0 0 +EDGE2 741 700 -0.983279 -0.0924941 -1.55236 1 0 1 1 0 0 +EDGE2 742 741 -1.02831 0.0429155 -0.00393242 1 0 1 1 0 0 +EDGE2 743 742 -1.04038 -0.0712543 -0.00710013 1 0 1 1 0 0 +EDGE2 744 743 -0.946173 0.0466632 -0.00792238 1 0 1 1 0 0 +EDGE2 745 744 -1.08433 -0.0748837 -0.00265877 1 0 1 1 0 0 +EDGE2 746 745 -0.99496 0.0427488 -1.58318 1 0 1 1 0 0 +EDGE2 747 746 -0.891524 0.0321667 -0.00743283 1 0 1 1 0 0 +EDGE2 748 747 -0.904813 -0.104277 -0.00773778 1 0 1 1 0 0 +EDGE2 749 748 -1.07379 -0.0111954 -0.0188928 1 0 1 1 0 0 +EDGE2 750 749 -1.084 -0.0510539 -0.00335897 1 0 1 1 0 0 +EDGE2 751 750 -0.95036 0.0351272 -1.55368 1 0 1 1 0 0 +EDGE2 752 751 -1.0423 -0.00687769 -0.0069372 1 0 1 1 0 0 +EDGE2 753 752 -0.971493 0.0817314 -0.0111361 1 0 1 1 0 0 +EDGE2 754 753 -1.09749 -0.0228554 -0.0169722 1 0 1 1 0 0 +EDGE2 754 695 0.95068 0.0409714 -3.14276 1 0 1 1 0 0 +EDGE2 755 754 -0.981828 -0.109469 -0.00274513 1 0 1 1 0 0 +EDGE2 755 695 -0.0241496 0.0259232 -3.12695 1 0 1 1 0 0 +EDGE2 755 694 0.926642 -0.073467 -3.15864 1 0 1 1 0 0 +EDGE2 755 696 0.0333959 0.977849 1.59312 1 0 1 1 0 0 +EDGE2 756 755 -1.00288 0.0210612 -1.59874 1 0 1 1 0 0 +EDGE2 756 695 -1.05106 -0.0602973 1.54164 1 0 1 1 0 0 +EDGE2 756 696 -0.0823829 0.0992133 -0.000460847 1 0 1 1 0 0 +EDGE2 756 697 1.03183 0.0130372 -0.0630813 1 0 1 1 0 0 +EDGE2 757 696 -0.972892 -0.0500716 0.0108794 1 0 1 1 0 0 +EDGE2 757 756 -0.956968 0.00565824 0.00020081 1 0 1 1 0 0 +EDGE2 757 697 -0.0406109 0.0187117 0.00870317 1 0 1 1 0 0 +EDGE2 757 698 0.971764 0.0244966 0.029816 1 0 1 1 0 0 +EDGE2 758 697 -1.06005 0.00145507 0.0285224 1 0 1 1 0 0 +EDGE2 758 757 -0.988311 -0.0629633 0.0214712 1 0 1 1 0 0 +EDGE2 758 699 1.05978 0.0549405 0.00323451 1 0 1 1 0 0 +EDGE2 758 698 0.0209663 0.00837549 -0.00958378 1 0 1 1 0 0 +EDGE2 759 699 0.0263932 0.0571089 0.0189157 1 0 1 1 0 0 +EDGE2 759 698 -1.07818 0.0859264 -0.033076 1 0 1 1 0 0 +EDGE2 759 758 -1.06075 0.0245802 -0.00466319 1 0 1 1 0 0 +EDGE2 759 740 0.999714 0.040985 -3.13044 1 0 1 1 0 0 +EDGE2 759 700 0.962386 -0.0719336 -0.0600847 1 0 1 1 0 0 +EDGE2 760 741 -0.0415869 0.941422 1.60205 1 0 1 1 0 0 +EDGE2 760 699 -1.0221 -0.108199 -0.00717357 1 0 1 1 0 0 +EDGE2 760 759 -0.926451 0.0884662 0.0188234 1 0 1 1 0 0 +EDGE2 760 701 -0.0366523 -0.991905 -1.57276 1 0 1 1 0 0 +EDGE2 760 740 0.0247152 0.036449 -3.15295 1 0 1 1 0 0 +EDGE2 760 700 0.0617225 0.031826 0.0103596 1 0 1 1 0 0 +EDGE2 760 739 0.932042 -0.0278908 -3.16765 1 0 1 1 0 0 +EDGE2 761 742 1.01508 0.0463249 0.0145304 1 0 1 1 0 0 +EDGE2 761 741 -0.0434163 -0.0487798 -0.0209588 1 0 1 1 0 0 +EDGE2 761 740 -0.95795 -0.0306477 1.54745 1 0 1 1 0 0 +EDGE2 761 760 -1.0293 0.0335944 -1.585 1 0 1 1 0 0 +EDGE2 761 700 -1.01673 -0.0396814 -1.58711 1 0 1 1 0 0 +EDGE2 762 743 1.00836 0.0410871 -0.00755715 1 0 1 1 0 0 +EDGE2 762 742 -0.0478164 -0.0327616 -0.00244362 1 0 1 1 0 0 +EDGE2 762 761 -1.02283 -0.000612128 0.0100208 1 0 1 1 0 0 +EDGE2 762 741 -0.963701 -0.0499529 -0.0280892 1 0 1 1 0 0 +EDGE2 763 744 0.988468 -0.0191716 0.0390592 1 0 1 1 0 0 +EDGE2 763 743 -0.0255309 -0.0178804 -0.0152352 1 0 1 1 0 0 +EDGE2 763 742 -0.95904 0.0313035 -0.038442 1 0 1 1 0 0 +EDGE2 763 762 -1.02675 -0.00570407 0.00292028 1 0 1 1 0 0 +EDGE2 764 745 0.95632 0.0741453 0.0389059 1 0 1 1 0 0 +EDGE2 764 744 -0.029882 -0.101369 -0.0138121 1 0 1 1 0 0 +EDGE2 764 743 -0.985654 -0.060529 -0.00363996 1 0 1 1 0 0 +EDGE2 764 763 -1.03522 -0.067251 -0.00746115 1 0 1 1 0 0 +EDGE2 765 746 -0.0844506 0.962217 1.58368 1 0 1 1 0 0 +EDGE2 765 745 -0.0914276 0.0253166 -0.0180878 1 0 1 1 0 0 +EDGE2 765 744 -1.01823 -0.0280852 0.0287274 1 0 1 1 0 0 +EDGE2 765 764 -1.02529 -0.0348961 0.00553351 1 0 1 1 0 0 +EDGE2 766 747 1.00632 -0.111375 0.000868971 1 0 1 1 0 0 +EDGE2 766 746 0.0226791 0.0718034 -0.03084 1 0 1 1 0 0 +EDGE2 766 745 -0.990243 -0.0357588 -1.56461 1 0 1 1 0 0 +EDGE2 766 765 -0.944517 -0.015835 -1.59558 1 0 1 1 0 0 +EDGE2 767 748 0.980846 -0.0171443 -0.0340626 1 0 1 1 0 0 +EDGE2 767 747 -0.0383844 -0.0242943 0.00363031 1 0 1 1 0 0 +EDGE2 767 766 -0.973476 -0.0145345 0.0210438 1 0 1 1 0 0 +EDGE2 767 746 -0.976382 -0.050832 -0.00810513 1 0 1 1 0 0 +EDGE2 768 748 0.0149381 0.0202372 -0.0106515 1 0 1 1 0 0 +EDGE2 768 749 1.02822 -0.0320591 0.0124047 1 0 1 1 0 0 +EDGE2 768 747 -0.997351 0.0167644 -0.0014984 1 0 1 1 0 0 +EDGE2 768 767 -1.02348 -0.013994 0.0163326 1 0 1 1 0 0 +EDGE2 769 750 0.997916 0.104185 0.0114018 1 0 1 1 0 0 +EDGE2 769 748 -1.02079 -0.0719576 0.0278814 1 0 1 1 0 0 +EDGE2 769 749 0.0190556 -0.00587863 -0.00227208 1 0 1 1 0 0 +EDGE2 769 768 -0.987651 -0.0361177 0.00898215 1 0 1 1 0 0 +EDGE2 770 750 -0.0046039 -0.0584291 -0.0403329 1 0 1 1 0 0 +EDGE2 770 751 -0.0110648 0.983008 1.5276 1 0 1 1 0 0 +EDGE2 770 769 -0.950187 0.0239842 -0.0167714 1 0 1 1 0 0 +EDGE2 770 749 -0.982662 0.139484 0.00274097 1 0 1 1 0 0 +EDGE2 771 750 -0.983925 0.0270589 -1.57232 1 0 1 1 0 0 +EDGE2 771 770 -1.02924 -0.0582928 -1.58199 1 0 1 1 0 0 +EDGE2 771 751 -0.0081418 -0.0175873 -0.0239668 1 0 1 1 0 0 +EDGE2 771 752 1.03613 -0.0180946 -0.0362081 1 0 1 1 0 0 +EDGE2 772 753 1.04825 -0.0611242 -0.00936108 1 0 1 1 0 0 +EDGE2 772 751 -1.04901 0.0476314 -0.0250211 1 0 1 1 0 0 +EDGE2 772 771 -1.06234 -0.0124299 -0.00886503 1 0 1 1 0 0 +EDGE2 772 752 0.000411605 -0.00225703 -0.0229377 1 0 1 1 0 0 +EDGE2 773 753 0.0322486 0.0477918 -0.0145925 1 0 1 1 0 0 +EDGE2 773 772 -0.983464 -0.0748822 0.0284379 1 0 1 1 0 0 +EDGE2 773 752 -0.97287 -0.0318943 0.0255716 1 0 1 1 0 0 +EDGE2 773 754 1.01804 0.0522617 0.0199032 1 0 1 1 0 0 +EDGE2 774 753 -0.990002 -0.0491987 -0.023005 1 0 1 1 0 0 +EDGE2 774 773 -0.954897 -0.0347871 -0.0318406 1 0 1 1 0 0 +EDGE2 774 754 0.0130273 -0.15004 -0.0283093 1 0 1 1 0 0 +EDGE2 774 755 0.944177 0.0166763 0.00401937 1 0 1 1 0 0 +EDGE2 774 695 0.95894 0.00113461 -3.11624 1 0 1 1 0 0 +EDGE2 775 774 -0.966553 -0.0102313 -0.00830092 1 0 1 1 0 0 +EDGE2 775 754 -1.01824 0.00913137 0.0285258 1 0 1 1 0 0 +EDGE2 775 755 0.0901227 -0.0106094 0.0107649 1 0 1 1 0 0 +EDGE2 775 695 0.00541622 0.0907119 -3.11521 1 0 1 1 0 0 +EDGE2 775 694 0.903425 -0.00379821 -3.14928 1 0 1 1 0 0 +EDGE2 775 696 0.015595 0.994584 1.55447 1 0 1 1 0 0 +EDGE2 775 756 0.0585711 0.928181 1.56931 1 0 1 1 0 0 +EDGE2 776 755 -0.951638 0.0735579 -1.59051 1 0 1 1 0 0 +EDGE2 776 775 -1.02144 0.0950504 -1.56382 1 0 1 1 0 0 +EDGE2 776 695 -0.983532 -0.0673357 1.58827 1 0 1 1 0 0 +EDGE2 776 696 -0.0202387 -0.0383134 -0.0382491 1 0 1 1 0 0 +EDGE2 776 756 0.058741 0.0365399 0.0227981 1 0 1 1 0 0 +EDGE2 776 697 1.02237 0.0539624 -0.00203027 1 0 1 1 0 0 +EDGE2 776 757 1.05245 0.0756108 -0.0102627 1 0 1 1 0 0 +EDGE2 777 696 -0.979467 -0.0952123 0.00504312 1 0 1 1 0 0 +EDGE2 777 756 -1.08146 0.00207824 0.0151534 1 0 1 1 0 0 +EDGE2 777 776 -0.971971 0.0320272 0.0194683 1 0 1 1 0 0 +EDGE2 777 697 0.0969372 0.000662133 -0.0220726 1 0 1 1 0 0 +EDGE2 777 757 0.0114701 -0.0547442 0.00846731 1 0 1 1 0 0 +EDGE2 777 698 0.977336 0.00614617 -0.0333864 1 0 1 1 0 0 +EDGE2 777 758 1.08924 -0.090955 -0.000162902 1 0 1 1 0 0 +EDGE2 778 697 -1.01263 -0.115887 -0.00685933 1 0 1 1 0 0 +EDGE2 778 777 -0.990637 -0.0204391 0.00960252 1 0 1 1 0 0 +EDGE2 778 757 -0.978415 -0.0348127 0.0108944 1 0 1 1 0 0 +EDGE2 778 699 1.0514 0.00876609 -0.0318796 1 0 1 1 0 0 +EDGE2 778 698 0.0557964 -0.0183774 0.0112573 1 0 1 1 0 0 +EDGE2 778 758 0.064999 -0.0102684 -0.00733513 1 0 1 1 0 0 +EDGE2 778 759 0.943179 -0.0452356 0.0419783 1 0 1 1 0 0 +EDGE2 779 778 -1.01009 -0.0131991 0.0102417 1 0 1 1 0 0 +EDGE2 779 699 -0.0177675 0.0734852 -0.0200635 1 0 1 1 0 0 +EDGE2 779 698 -0.981665 -0.0487769 0.0107646 1 0 1 1 0 0 +EDGE2 779 758 -1.01661 -0.0231555 -0.0153242 1 0 1 1 0 0 +EDGE2 779 759 0.00841311 -0.0508409 0.0290534 1 0 1 1 0 0 +EDGE2 779 740 0.994922 0.0420993 -3.14835 1 0 1 1 0 0 +EDGE2 779 760 1.07764 -0.0103075 0.0185056 1 0 1 1 0 0 +EDGE2 779 700 1.11111 -0.0455199 -0.0263302 1 0 1 1 0 0 +EDGE2 780 761 -0.0959072 1.05619 1.56164 1 0 1 1 0 0 +EDGE2 780 741 0.120141 1.00444 1.53223 1 0 1 1 0 0 +EDGE2 780 699 -0.981406 0.00341151 -0.0179042 1 0 1 1 0 0 +EDGE2 780 779 -0.973196 -0.0844058 -0.00912292 1 0 1 1 0 0 +EDGE2 780 759 -1.0527 -0.0224332 -0.0246707 1 0 1 1 0 0 +EDGE2 780 701 -0.00221844 -1.02984 -1.56074 1 0 1 1 0 0 +EDGE2 780 740 0.019395 0.0211032 -3.08041 1 0 1 1 0 0 +EDGE2 780 760 0.0142936 -0.211514 0.00363883 1 0 1 1 0 0 +EDGE2 780 700 0.00753328 -0.057629 -0.0206489 1 0 1 1 0 0 +EDGE2 780 739 0.95259 -0.0368792 -3.14321 1 0 1 1 0 0 +EDGE2 781 742 0.986374 -0.0270265 0.0117488 1 0 1 1 0 0 +EDGE2 781 762 0.980777 -0.0393889 -0.0119025 1 0 1 1 0 0 +EDGE2 781 761 -0.0170363 0.0689773 -0.0102456 1 0 1 1 0 0 +EDGE2 781 741 -0.0404152 -0.0616136 0.00865806 1 0 1 1 0 0 +EDGE2 781 740 -0.991962 0.101415 1.62789 1 0 1 1 0 0 +EDGE2 781 760 -0.954965 -0.111066 -1.5437 1 0 1 1 0 0 +EDGE2 781 780 -0.96798 -0.00684487 -1.56175 1 0 1 1 0 0 +EDGE2 781 700 -1.0924 0.0362311 -1.57881 1 0 1 1 0 0 +EDGE2 782 743 0.965798 0.0109473 0.029139 1 0 1 1 0 0 +EDGE2 782 763 1.00194 -0.0171923 0.0237784 1 0 1 1 0 0 +EDGE2 782 742 0.0160821 -0.0343777 0.00371269 1 0 1 1 0 0 +EDGE2 782 762 0.0357173 -0.0107261 0.00634092 1 0 1 1 0 0 +EDGE2 782 761 -1.06159 0.0190499 0.0311637 1 0 1 1 0 0 +EDGE2 782 781 -1.07553 0.063208 0.0020158 1 0 1 1 0 0 +EDGE2 782 741 -0.88987 -0.0023928 0.0228761 1 0 1 1 0 0 +EDGE2 783 744 0.885942 0.0692614 0.0209088 1 0 1 1 0 0 +EDGE2 783 764 1.04097 0.0030946 0.00447576 1 0 1 1 0 0 +EDGE2 783 743 -0.0789369 -0.0336273 0.00214631 1 0 1 1 0 0 +EDGE2 783 763 -0.0327004 -0.00232553 0.0369717 1 0 1 1 0 0 +EDGE2 783 742 -1.01399 0.0356836 0.00205706 1 0 1 1 0 0 +EDGE2 783 762 -0.983609 -0.0506575 -0.00663771 1 0 1 1 0 0 +EDGE2 783 782 -0.904263 0.0542629 0.0316493 1 0 1 1 0 0 +EDGE2 784 783 -1.04432 -0.0220638 0.00174262 1 0 1 1 0 0 +EDGE2 784 745 1.14506 -0.0264805 0.0272718 1 0 1 1 0 0 +EDGE2 784 765 0.987577 -0.0247393 -0.00304576 1 0 1 1 0 0 +EDGE2 784 744 0.0468506 0.0033516 -0.038333 1 0 1 1 0 0 +EDGE2 784 764 0.00548664 -0.0771346 -0.00623979 1 0 1 1 0 0 +EDGE2 784 743 -1.00904 0.0171596 -0.0263855 1 0 1 1 0 0 +EDGE2 784 763 -1.0072 0.0877783 -0.0442696 1 0 1 1 0 0 +EDGE2 785 766 0.0492692 1.01657 1.5911 1 0 1 1 0 0 +EDGE2 785 746 -0.0236657 1.04993 1.58753 1 0 1 1 0 0 +EDGE2 785 784 -1.00507 -0.000743948 0.00226544 1 0 1 1 0 0 +EDGE2 785 745 0.0033934 -0.0545785 0.0160743 1 0 1 1 0 0 +EDGE2 785 765 0.00966567 -0.0320677 0.0118754 1 0 1 1 0 0 +EDGE2 785 744 -0.98733 -0.000988692 0.00158509 1 0 1 1 0 0 +EDGE2 785 764 -1.03776 0.00579071 0.0228497 1 0 1 1 0 0 +EDGE2 786 747 1.04054 -0.00837314 -0.0496825 1 0 1 1 0 0 +EDGE2 786 767 0.958569 -0.14347 -0.00933504 1 0 1 1 0 0 +EDGE2 786 766 -0.0192061 -0.0615674 -0.0281948 1 0 1 1 0 0 +EDGE2 786 746 0.0300326 -0.0540153 -0.00141842 1 0 1 1 0 0 +EDGE2 786 785 -0.938781 -0.0146541 -1.56455 1 0 1 1 0 0 +EDGE2 786 745 -1.09216 -0.0289125 -1.5227 1 0 1 1 0 0 +EDGE2 786 765 -0.956495 0.0295481 -1.58532 1 0 1 1 0 0 +EDGE2 787 748 0.921714 -0.0114155 0.0399162 1 0 1 1 0 0 +EDGE2 787 768 1.04493 0.0406316 0.00012003 1 0 1 1 0 0 +EDGE2 787 747 -0.0545229 0.0976536 0.0104077 1 0 1 1 0 0 +EDGE2 787 767 0.0476312 0.0526108 -0.00926028 1 0 1 1 0 0 +EDGE2 787 766 -0.983335 -0.088021 -0.0305627 1 0 1 1 0 0 +EDGE2 787 786 -1.08361 -0.0796197 0.00893827 1 0 1 1 0 0 +EDGE2 787 746 -0.965077 0.0359752 -0.0159086 1 0 1 1 0 0 +EDGE2 788 748 0.00761577 0.0282271 -0.0256275 1 0 1 1 0 0 +EDGE2 788 769 0.969662 0.0342265 0.030045 1 0 1 1 0 0 +EDGE2 788 749 1.06812 -0.0521467 0.00282403 1 0 1 1 0 0 +EDGE2 788 768 0.0148826 -0.0379116 0.00719719 1 0 1 1 0 0 +EDGE2 788 747 -1.02127 -0.048075 0.00398954 1 0 1 1 0 0 +EDGE2 788 767 -1.01097 0.0080239 -0.0212781 1 0 1 1 0 0 +EDGE2 788 787 -0.991579 0.020201 -0.0385081 1 0 1 1 0 0 +EDGE2 789 750 1.0556 0.00143597 0.00355825 1 0 1 1 0 0 +EDGE2 789 770 0.964718 -0.0193736 -0.00336014 1 0 1 1 0 0 +EDGE2 789 748 -1.07495 0.0171385 -0.033177 1 0 1 1 0 0 +EDGE2 789 788 -1.05394 0.00460183 -0.0132693 1 0 1 1 0 0 +EDGE2 789 769 0.0340267 -0.0179468 -0.0210643 1 0 1 1 0 0 +EDGE2 789 749 -0.0457809 0.0791756 0.0138161 1 0 1 1 0 0 +EDGE2 789 768 -1.04282 -0.00942719 0.00548468 1 0 1 1 0 0 +EDGE2 790 750 -0.0573882 0.00723652 -0.00103019 1 0 1 1 0 0 +EDGE2 790 770 -0.0300421 0.0259961 0.00208385 1 0 1 1 0 0 +EDGE2 790 751 -0.0172474 1.06181 1.56699 1 0 1 1 0 0 +EDGE2 790 771 -0.035928 0.992262 1.56022 1 0 1 1 0 0 +EDGE2 790 769 -1.03081 -0.0595617 -0.0175535 1 0 1 1 0 0 +EDGE2 790 789 -0.987093 0.0923595 0.00198459 1 0 1 1 0 0 +EDGE2 790 749 -1.00729 -0.000295252 0.00311554 1 0 1 1 0 0 +EDGE2 791 790 -0.930619 -0.0726054 -1.58967 1 0 1 1 0 0 +EDGE2 791 750 -1.04762 -0.026758 -1.58548 1 0 1 1 0 0 +EDGE2 791 770 -1.02411 -0.1009 -1.55715 1 0 1 1 0 0 +EDGE2 791 751 0.00236446 0.00764961 -0.0161274 1 0 1 1 0 0 +EDGE2 791 771 0.0928759 -0.0610241 -0.00847713 1 0 1 1 0 0 +EDGE2 791 772 0.975384 -0.118621 0.016222 1 0 1 1 0 0 +EDGE2 791 752 0.978114 0.033435 0.000866243 1 0 1 1 0 0 +EDGE2 792 753 1.06716 -0.0192473 0.0241841 1 0 1 1 0 0 +EDGE2 792 751 -1.0205 -0.0280145 0.0112469 1 0 1 1 0 0 +EDGE2 792 771 -1.02311 0.013799 0.000412431 1 0 1 1 0 0 +EDGE2 792 791 -0.975987 0.129821 0.00442615 1 0 1 1 0 0 +EDGE2 792 772 0.113782 0.0212209 0.0356254 1 0 1 1 0 0 +EDGE2 792 752 -0.0431008 -0.00528655 -0.000318923 1 0 1 1 0 0 +EDGE2 792 773 0.98804 0.0342203 0.0138879 1 0 1 1 0 0 +EDGE2 793 753 -0.00331738 0.0632209 -0.0115048 1 0 1 1 0 0 +EDGE2 793 772 -0.966708 -0.0158909 -0.00827282 1 0 1 1 0 0 +EDGE2 793 792 -1.11606 -0.0410341 0.0325328 1 0 1 1 0 0 +EDGE2 793 752 -1.10671 -0.0424795 0.0400871 1 0 1 1 0 0 +EDGE2 793 773 -0.0631455 0.0312638 0.0120144 1 0 1 1 0 0 +EDGE2 793 774 1.0112 -0.0482049 -0.0169747 1 0 1 1 0 0 +EDGE2 793 754 1.05609 -0.0185935 0.00265937 1 0 1 1 0 0 +EDGE2 794 753 -1.08369 0.0245752 -0.00740541 1 0 1 1 0 0 +EDGE2 794 793 -0.988099 0.101214 -0.00603192 1 0 1 1 0 0 +EDGE2 794 773 -1.02049 -0.0810915 0.0160455 1 0 1 1 0 0 +EDGE2 794 774 0.0339789 0.00683116 0.0101352 1 0 1 1 0 0 +EDGE2 794 754 0.0518301 0.0111522 -0.00255571 1 0 1 1 0 0 +EDGE2 794 755 1.00352 -0.0275281 -0.00539363 1 0 1 1 0 0 +EDGE2 794 775 0.961943 -0.0111905 -0.0222888 1 0 1 1 0 0 +EDGE2 794 695 0.916861 0.00321587 -3.15374 1 0 1 1 0 0 +EDGE2 795 774 -1.06227 0.0848736 -0.00586585 1 0 1 1 0 0 +EDGE2 795 794 -1.02882 0.0755159 0.00329013 1 0 1 1 0 0 +EDGE2 795 754 -1.03159 -0.00339597 -0.00739033 1 0 1 1 0 0 +EDGE2 795 755 -0.0356031 -0.00775627 0.0151891 1 0 1 1 0 0 +EDGE2 795 775 -0.102524 -0.0660802 -0.0265301 1 0 1 1 0 0 +EDGE2 795 695 0.0656927 -0.0185435 -3.15117 1 0 1 1 0 0 +EDGE2 795 694 0.921048 0.0676737 -3.15551 1 0 1 1 0 0 +EDGE2 795 696 -0.00183142 1.03371 1.543 1 0 1 1 0 0 +EDGE2 795 756 0.0203703 0.966509 1.57522 1 0 1 1 0 0 +EDGE2 795 776 0.060838 1.06305 1.55591 1 0 1 1 0 0 +EDGE2 796 795 -1.11269 0.0263227 -1.5657 1 0 1 1 0 0 +EDGE2 796 755 -1.03312 0.0443324 -1.54373 1 0 1 1 0 0 +EDGE2 796 775 -1.02974 -0.0435421 -1.5817 1 0 1 1 0 0 +EDGE2 796 695 -0.965519 0.0363703 1.56636 1 0 1 1 0 0 +EDGE2 796 696 -0.0797495 -0.0537146 -0.00894928 1 0 1 1 0 0 +EDGE2 796 756 -0.0106439 0.0472992 0.00725682 1 0 1 1 0 0 +EDGE2 796 776 0.0777264 -0.0307729 -0.0461913 1 0 1 1 0 0 +EDGE2 796 697 1.03432 0.0569119 0.029666 1 0 1 1 0 0 +EDGE2 796 777 0.969809 0.0391346 0.00181032 1 0 1 1 0 0 +EDGE2 796 757 1.05159 0.00950265 0.00625448 1 0 1 1 0 0 +EDGE2 797 796 -1.03701 -0.072702 -0.0274906 1 0 1 1 0 0 +EDGE2 797 696 -1.01765 0.0579301 0.0131045 1 0 1 1 0 0 +EDGE2 797 756 -0.95286 0.0639122 -0.00305674 1 0 1 1 0 0 +EDGE2 797 776 -1.0355 0.0162186 -0.0206883 1 0 1 1 0 0 +EDGE2 797 778 1.00328 0.0195963 -0.0380814 1 0 1 1 0 0 +EDGE2 797 697 -0.0135987 -0.0755971 -0.00769618 1 0 1 1 0 0 +EDGE2 797 777 -0.00378211 -0.0263322 0.0135486 1 0 1 1 0 0 +EDGE2 797 757 0.00769998 0.0439459 -0.00392169 1 0 1 1 0 0 +EDGE2 797 698 1.05665 -0.00290598 -0.0142703 1 0 1 1 0 0 +EDGE2 797 758 0.997977 -0.0529411 -0.00744234 1 0 1 1 0 0 +EDGE2 798 778 0.013772 0.0203429 0.0254169 1 0 1 1 0 0 +EDGE2 798 697 -0.97322 -0.00228386 -0.00107562 1 0 1 1 0 0 +EDGE2 798 777 -0.994801 -0.0436442 0.016946 1 0 1 1 0 0 +EDGE2 798 797 -0.967526 0.0028346 0.0228478 1 0 1 1 0 0 +EDGE2 798 757 -1.01481 0.0659121 0.0581935 1 0 1 1 0 0 +EDGE2 798 699 0.97289 -0.107863 -0.0211483 1 0 1 1 0 0 +EDGE2 798 698 0.00574767 -0.043513 0.00529804 1 0 1 1 0 0 +EDGE2 798 758 0.162836 0.015796 0.0175577 1 0 1 1 0 0 +EDGE2 798 779 0.963525 -0.0669723 -0.00523552 1 0 1 1 0 0 +EDGE2 798 759 0.903821 0.0192668 0.0118072 1 0 1 1 0 0 +EDGE2 799 778 -0.930436 -0.0283504 0.0159403 1 0 1 1 0 0 +EDGE2 799 798 -1.0498 -0.0281891 0.0143681 1 0 1 1 0 0 +EDGE2 799 699 -0.000595376 -0.0738818 -0.00892371 1 0 1 1 0 0 +EDGE2 799 698 -0.978054 -0.0216575 0.00619601 1 0 1 1 0 0 +EDGE2 799 758 -1.00615 -0.0314984 -0.0452747 1 0 1 1 0 0 +EDGE2 799 779 -0.0300849 -0.0157609 0.00735326 1 0 1 1 0 0 +EDGE2 799 759 0.0499262 -0.0879212 -0.0128653 1 0 1 1 0 0 +EDGE2 799 740 0.991034 0.0155753 -3.14032 1 0 1 1 0 0 +EDGE2 799 760 1.02277 0.0122308 -0.00545669 1 0 1 1 0 0 +EDGE2 799 780 1.0586 -0.00365443 0.00892973 1 0 1 1 0 0 +EDGE2 799 700 0.927963 0.0446336 0.0316951 1 0 1 1 0 0 +EDGE2 800 761 -0.020447 0.969174 1.57224 1 0 1 1 0 0 +EDGE2 800 781 -0.0847001 0.921932 1.59377 1 0 1 1 0 0 +EDGE2 800 741 0.0812587 1.01401 1.58579 1 0 1 1 0 0 +EDGE2 800 699 -1.01686 0.0567562 0.0223215 1 0 1 1 0 0 +EDGE2 800 779 -1.03309 -0.0863035 -0.01568 1 0 1 1 0 0 +EDGE2 800 799 -0.988693 -0.0773858 -0.0141345 1 0 1 1 0 0 +EDGE2 800 759 -1.0205 0.0577023 0.00335687 1 0 1 1 0 0 +EDGE2 800 701 -0.0591197 -1.08798 -1.52181 1 0 1 1 0 0 +EDGE2 800 740 0.0257779 -0.12736 -3.12047 1 0 1 1 0 0 +EDGE2 800 760 -0.0473434 0.0701085 0.016627 1 0 1 1 0 0 +EDGE2 800 780 -0.0157244 0.0309232 -0.014627 1 0 1 1 0 0 +EDGE2 800 700 -0.000613296 -0.00552041 -0.0126691 1 0 1 1 0 0 +EDGE2 800 739 0.99136 0.0629251 -3.17271 1 0 1 1 0 0 +EDGE2 801 742 0.966846 -0.0398038 0.0352258 1 0 1 1 0 0 +EDGE2 801 762 1.04969 0.0238282 -0.010676 1 0 1 1 0 0 +EDGE2 801 782 0.997974 0.044537 0.00465831 1 0 1 1 0 0 +EDGE2 801 761 0.0245601 -0.0173136 -0.0132664 1 0 1 1 0 0 +EDGE2 801 781 0.0143607 0.00970446 0.0225793 1 0 1 1 0 0 +EDGE2 801 741 -0.0163724 -0.0276663 -0.00970724 1 0 1 1 0 0 +EDGE2 801 800 -1.07654 -0.00986216 -1.57698 1 0 1 1 0 0 +EDGE2 801 740 -0.94406 0.0996514 1.5675 1 0 1 1 0 0 +EDGE2 801 760 -1.01741 0.0477121 -1.57379 1 0 1 1 0 0 +EDGE2 801 780 -0.950409 -0.0187753 -1.56785 1 0 1 1 0 0 +EDGE2 801 700 -1.02626 -0.00129566 -1.55179 1 0 1 1 0 0 +EDGE2 802 783 0.973316 0.0495612 0.0244814 1 0 1 1 0 0 +EDGE2 802 743 0.899102 0.0174185 0.0161328 1 0 1 1 0 0 +EDGE2 802 763 1.01586 0.0563452 -0.0121101 1 0 1 1 0 0 +EDGE2 802 801 -0.942411 0.0549756 -0.0160253 1 0 1 1 0 0 +EDGE2 802 742 0.0428278 -0.0261868 0.0117766 1 0 1 1 0 0 +EDGE2 802 762 0.0250792 0.0699136 0.011192 1 0 1 1 0 0 +EDGE2 802 782 -0.0167721 -0.00312908 -0.0452875 1 0 1 1 0 0 +EDGE2 802 761 -1.02669 0.0874319 -0.0227616 1 0 1 1 0 0 +EDGE2 802 781 -0.882351 0.0387703 -0.00132995 1 0 1 1 0 0 +EDGE2 802 741 -0.926512 0.0344303 -0.0102779 1 0 1 1 0 0 +EDGE2 803 783 -0.0378831 0.0040744 0.00704723 1 0 1 1 0 0 +EDGE2 803 784 1.13457 -0.00857724 -0.0437888 1 0 1 1 0 0 +EDGE2 803 744 0.916576 -0.0447449 -0.00463708 1 0 1 1 0 0 +EDGE2 803 764 0.981539 -0.0182368 0.00378892 1 0 1 1 0 0 +EDGE2 803 802 -0.969786 0.0387018 0.0278023 1 0 1 1 0 0 +EDGE2 803 743 0.0152952 0.0229119 0.00547623 1 0 1 1 0 0 +EDGE2 803 763 -0.149745 0.0327024 -0.0310143 1 0 1 1 0 0 +EDGE2 803 742 -1.04554 -0.0576502 0.0281776 1 0 1 1 0 0 +EDGE2 803 762 -0.980374 0.00177391 0.0117805 1 0 1 1 0 0 +EDGE2 803 782 -0.998091 0.0605595 0.0246865 1 0 1 1 0 0 +EDGE2 804 783 -1.04961 0.0863004 -0.0117988 1 0 1 1 0 0 +EDGE2 804 785 1.02185 0.0134669 0.00187314 1 0 1 1 0 0 +EDGE2 804 784 -0.0384091 -0.032251 -0.0100946 1 0 1 1 0 0 +EDGE2 804 745 1.08352 -0.0641453 -0.002014 1 0 1 1 0 0 +EDGE2 804 765 1.09882 -0.125711 0.00289668 1 0 1 1 0 0 +EDGE2 804 744 -0.0437885 -0.0149 0.00541822 1 0 1 1 0 0 +EDGE2 804 764 -0.0448815 -0.0602458 -0.0164396 1 0 1 1 0 0 +EDGE2 804 803 -0.996766 0.0471135 0.0373941 1 0 1 1 0 0 +EDGE2 804 743 -1.00669 -0.0418651 -0.0276891 1 0 1 1 0 0 +EDGE2 804 763 -0.993617 0.0511871 0.00864273 1 0 1 1 0 0 +EDGE2 805 766 0.0453714 1.02748 1.57237 1 0 1 1 0 0 +EDGE2 805 786 -0.0755194 1.00073 1.60861 1 0 1 1 0 0 +EDGE2 805 746 -0.0377459 1.0033 1.57546 1 0 1 1 0 0 +EDGE2 805 785 0.0131132 0.0773405 -0.0145719 1 0 1 1 0 0 +EDGE2 805 784 -0.926073 -0.00836085 0.00632249 1 0 1 1 0 0 +EDGE2 805 745 -0.0515813 -0.00136924 -0.0112436 1 0 1 1 0 0 +EDGE2 805 765 -0.0445328 0.0101536 -0.0297386 1 0 1 1 0 0 +EDGE2 805 804 -0.954184 -0.0211462 -0.0186997 1 0 1 1 0 0 +EDGE2 805 744 -1.04822 0.0596664 0.00254553 1 0 1 1 0 0 +EDGE2 805 764 -0.9598 0.0210443 0.0128347 1 0 1 1 0 0 +EDGE2 806 747 0.987044 0.0152253 -0.00149507 1 0 1 1 0 0 +EDGE2 806 767 0.953354 -0.0631837 0.0196087 1 0 1 1 0 0 +EDGE2 806 787 0.961443 0.000958078 -0.0140894 1 0 1 1 0 0 +EDGE2 806 766 -0.000935401 -0.0390183 -0.0275112 1 0 1 1 0 0 +EDGE2 806 786 0.0243566 0.00402544 -0.0128604 1 0 1 1 0 0 +EDGE2 806 746 -0.014662 -0.0488332 0.00384814 1 0 1 1 0 0 +EDGE2 806 785 -1.05692 -0.0353633 -1.58845 1 0 1 1 0 0 +EDGE2 806 805 -1.00586 0.0501538 -1.5823 1 0 1 1 0 0 +EDGE2 806 745 -1.02601 0.0116754 -1.56907 1 0 1 1 0 0 +EDGE2 806 765 -0.983521 -0.103509 -1.55975 1 0 1 1 0 0 +EDGE2 807 748 1.06963 0.0240274 0.0110535 1 0 1 1 0 0 +EDGE2 807 788 1.03627 0.0518115 -0.00563421 1 0 1 1 0 0 +EDGE2 807 768 1.11113 -0.0271707 0.018994 1 0 1 1 0 0 +EDGE2 807 747 -0.0232075 -0.000628486 0.00690185 1 0 1 1 0 0 +EDGE2 807 767 0.155264 -0.0431184 -0.0339789 1 0 1 1 0 0 +EDGE2 807 787 -0.064845 0.0101985 0.00386474 1 0 1 1 0 0 +EDGE2 807 806 -0.998508 0.012269 -0.00573898 1 0 1 1 0 0 +EDGE2 807 766 -0.967641 0.0563961 0.0182037 1 0 1 1 0 0 +EDGE2 807 786 -0.966058 0.0373333 -0.0233538 1 0 1 1 0 0 +EDGE2 807 746 -1.09334 -0.0394715 -0.00228229 1 0 1 1 0 0 +EDGE2 808 748 -0.0976673 -0.0928808 0.0409899 1 0 1 1 0 0 +EDGE2 808 788 -0.0806465 -0.00634904 0.025308 1 0 1 1 0 0 +EDGE2 808 769 1.04512 0.128302 0.0239434 1 0 1 1 0 0 +EDGE2 808 789 0.867671 0.0561619 0.00839428 1 0 1 1 0 0 +EDGE2 808 749 1.00058 0.0774607 -0.0210665 1 0 1 1 0 0 +EDGE2 808 768 0.0607909 -0.100904 -0.0129611 1 0 1 1 0 0 +EDGE2 808 747 -0.997766 0.00114718 0.0523903 1 0 1 1 0 0 +EDGE2 808 767 -1.05007 0.0106902 -0.0179353 1 0 1 1 0 0 +EDGE2 808 807 -0.957306 0.0334001 0.0234708 1 0 1 1 0 0 +EDGE2 808 787 -1.06773 0.0112824 0.00922021 1 0 1 1 0 0 +EDGE2 809 790 0.97623 0.00284268 0.00556048 1 0 1 1 0 0 +EDGE2 809 750 0.951101 0.0423368 0.0298782 1 0 1 1 0 0 +EDGE2 809 770 0.886231 -0.000950579 0.0271239 1 0 1 1 0 0 +EDGE2 809 748 -1.048 0.0862337 -0.00705839 1 0 1 1 0 0 +EDGE2 809 788 -0.933936 -0.0484341 -0.00595489 1 0 1 1 0 0 +EDGE2 809 769 -0.00171226 0.0793109 -0.0213587 1 0 1 1 0 0 +EDGE2 809 789 0.042832 0.00940114 0.0258001 1 0 1 1 0 0 +EDGE2 809 749 0.0357872 -0.0306725 0.0063226 1 0 1 1 0 0 +EDGE2 809 808 -0.953789 -0.0450174 -0.00419149 1 0 1 1 0 0 +EDGE2 809 768 -0.969188 -0.0258493 -0.0133509 1 0 1 1 0 0 +EDGE2 810 790 -0.0122585 -0.0216024 0.0186 1 0 1 1 0 0 +EDGE2 810 750 0.0227622 0.0517501 -0.00117182 1 0 1 1 0 0 +EDGE2 810 770 -0.00864875 0.0925505 -0.0371576 1 0 1 1 0 0 +EDGE2 810 751 -0.0269424 0.943157 1.57269 1 0 1 1 0 0 +EDGE2 810 771 0.0404512 1.01569 1.62849 1 0 1 1 0 0 +EDGE2 810 791 0.0405047 0.940561 1.57818 1 0 1 1 0 0 +EDGE2 810 769 -1.01808 -0.0562672 -0.0155925 1 0 1 1 0 0 +EDGE2 810 809 -0.950903 0.0199004 0.0242109 1 0 1 1 0 0 +EDGE2 810 789 -0.944193 -0.0135094 0.00437276 1 0 1 1 0 0 +EDGE2 810 749 -1.00736 0.00547075 -0.00766446 1 0 1 1 0 0 +EDGE2 811 790 -1.01713 -0.095858 -1.53541 1 0 1 1 0 0 +EDGE2 811 810 -1.02847 0.0435656 -1.6078 1 0 1 1 0 0 +EDGE2 811 750 -1.05901 -0.0229092 -1.58521 1 0 1 1 0 0 +EDGE2 811 770 -1.07548 -0.0283729 -1.54734 1 0 1 1 0 0 +EDGE2 811 751 -0.00729584 -0.0279965 -0.0250336 1 0 1 1 0 0 +EDGE2 811 771 0.0529656 0.053226 0.0336164 1 0 1 1 0 0 +EDGE2 811 791 0.0120026 -0.0571493 -0.0231786 1 0 1 1 0 0 +EDGE2 811 772 0.98965 -0.0016767 -0.0285347 1 0 1 1 0 0 +EDGE2 811 792 1.07815 0.0582232 0.00772741 1 0 1 1 0 0 +EDGE2 811 752 0.969787 -0.0152433 -0.0167735 1 0 1 1 0 0 +EDGE2 812 753 1.01974 -0.0250387 0.00117895 1 0 1 1 0 0 +EDGE2 812 811 -0.977796 0.0193161 0.0143867 1 0 1 1 0 0 +EDGE2 812 751 -1.0334 0.0095691 -0.0337364 1 0 1 1 0 0 +EDGE2 812 771 -1.06396 0.0459771 0.0380859 1 0 1 1 0 0 +EDGE2 812 791 -1.01553 0.00495014 -0.00424323 1 0 1 1 0 0 +EDGE2 812 772 -0.0187653 -0.0821531 0.0272405 1 0 1 1 0 0 +EDGE2 812 792 0.0332675 -0.00489123 -0.00133577 1 0 1 1 0 0 +EDGE2 812 752 0.0057256 0.00889728 0.0185038 1 0 1 1 0 0 +EDGE2 812 793 1.05627 0.0274031 -0.0373734 1 0 1 1 0 0 +EDGE2 812 773 0.94278 -0.0458899 -0.0224899 1 0 1 1 0 0 +EDGE2 813 753 -0.00215283 -0.0565752 -0.00202249 1 0 1 1 0 0 +EDGE2 813 772 -1.07941 -0.034716 -0.00265135 1 0 1 1 0 0 +EDGE2 813 792 -1.03836 -0.00439031 0.00200766 1 0 1 1 0 0 +EDGE2 813 812 -0.961321 -0.0904921 -0.0173465 1 0 1 1 0 0 +EDGE2 813 752 -0.939873 -0.0465623 0.029804 1 0 1 1 0 0 +EDGE2 813 793 -0.0578126 -0.0797778 0.00846834 1 0 1 1 0 0 +EDGE2 813 773 -0.0366963 -0.0558735 -0.00332387 1 0 1 1 0 0 +EDGE2 813 774 0.941482 -0.00151663 -0.0139085 1 0 1 1 0 0 +EDGE2 813 794 0.991089 -0.054219 -0.0245203 1 0 1 1 0 0 +EDGE2 813 754 1.169 0.0286578 0.00225729 1 0 1 1 0 0 +EDGE2 814 753 -0.947241 -0.0410611 -0.0074678 1 0 1 1 0 0 +EDGE2 814 793 -0.921536 0.0255402 -0.0241219 1 0 1 1 0 0 +EDGE2 814 813 -0.936156 -0.0341541 -0.0048646 1 0 1 1 0 0 +EDGE2 814 773 -1.03893 0.0312313 0.00946083 1 0 1 1 0 0 +EDGE2 814 774 -0.0692638 -0.0213185 -0.00823063 1 0 1 1 0 0 +EDGE2 814 794 0.0156812 0.0498521 0.0127561 1 0 1 1 0 0 +EDGE2 814 754 0.0296691 -0.0494056 -0.0102882 1 0 1 1 0 0 +EDGE2 814 795 1.04457 -0.0106423 -0.024683 1 0 1 1 0 0 +EDGE2 814 755 0.996171 0.0171519 -0.00984798 1 0 1 1 0 0 +EDGE2 814 775 0.937131 -0.00293841 -0.00407849 1 0 1 1 0 0 +EDGE2 814 695 1.08975 0.00832974 -3.14652 1 0 1 1 0 0 +EDGE2 815 774 -0.95754 0.00810496 -0.00106438 1 0 1 1 0 0 +EDGE2 815 814 -0.988288 0.0449267 0.0460616 1 0 1 1 0 0 +EDGE2 815 794 -0.993167 -0.0207654 -0.00742238 1 0 1 1 0 0 +EDGE2 815 754 -1.03463 -0.00963355 -0.0269215 1 0 1 1 0 0 +EDGE2 815 795 0.0661292 0.00657259 0.00893932 1 0 1 1 0 0 +EDGE2 815 755 -0.033201 0.0230421 0.00179832 1 0 1 1 0 0 +EDGE2 815 775 0.0667151 0.00191474 0.0157571 1 0 1 1 0 0 +EDGE2 815 695 -0.0482213 0.077356 -3.16298 1 0 1 1 0 0 +EDGE2 815 694 0.949164 0.0142394 -3.14143 1 0 1 1 0 0 +EDGE2 815 796 -0.0659435 0.970486 1.54714 1 0 1 1 0 0 +EDGE2 815 696 -0.0308067 1.00502 1.5748 1 0 1 1 0 0 +EDGE2 815 756 0.00237489 1.01228 1.56934 1 0 1 1 0 0 +EDGE2 815 776 0.110895 1.077 1.53624 1 0 1 1 0 0 +EDGE2 816 795 -0.940969 -0.017107 -1.55582 1 0 1 1 0 0 +EDGE2 816 815 -0.883724 -0.0458668 -1.57222 1 0 1 1 0 0 +EDGE2 816 755 -0.922669 -0.0663832 -1.57754 1 0 1 1 0 0 +EDGE2 816 775 -0.991802 -0.0304565 -1.57507 1 0 1 1 0 0 +EDGE2 816 695 -1.01716 0.0317729 1.58309 1 0 1 1 0 0 +EDGE2 816 796 -0.00680266 0.0148579 -3.14701e-05 1 0 1 1 0 0 +EDGE2 816 696 0.0469768 0.0948592 0.0102615 1 0 1 1 0 0 +EDGE2 816 756 -0.0197941 0.0200558 0.00831007 1 0 1 1 0 0 +EDGE2 816 776 0.00435361 0.0328703 -0.05514 1 0 1 1 0 0 +EDGE2 816 697 1.03085 0.0491204 -0.00812052 1 0 1 1 0 0 +EDGE2 816 777 0.946377 -0.0453745 0.0441082 1 0 1 1 0 0 +EDGE2 816 797 1.00883 -0.0995486 0.0215698 1 0 1 1 0 0 +EDGE2 816 757 0.979205 0.0180431 -0.0133759 1 0 1 1 0 0 +EDGE2 817 796 -1.07128 -0.0435003 -0.0315111 1 0 1 1 0 0 +EDGE2 817 816 -0.987976 -0.00951846 -0.04347 1 0 1 1 0 0 +EDGE2 817 696 -1.04284 0.0670384 0.0132268 1 0 1 1 0 0 +EDGE2 817 756 -1.04452 -0.0206982 0.00263337 1 0 1 1 0 0 +EDGE2 817 776 -1.05009 -0.0424609 0.009517 1 0 1 1 0 0 +EDGE2 817 778 0.99062 0.140956 0.012558 1 0 1 1 0 0 +EDGE2 817 798 1.05622 -0.0075242 0.0221799 1 0 1 1 0 0 +EDGE2 817 697 0.0229822 0.02396 -0.0593369 1 0 1 1 0 0 +EDGE2 817 777 -0.00925412 0.0178866 -0.0149127 1 0 1 1 0 0 +EDGE2 817 797 0.0210812 0.0139777 -0.016276 1 0 1 1 0 0 +EDGE2 817 757 -0.0214433 0.0360557 0.0334033 1 0 1 1 0 0 +EDGE2 817 698 0.978083 0.0794401 -0.00149067 1 0 1 1 0 0 +EDGE2 817 758 1.03746 0.0271093 0.0243719 1 0 1 1 0 0 +EDGE2 818 778 0.0107607 0.087805 -0.0313223 1 0 1 1 0 0 +EDGE2 818 798 0.0479949 0.00505924 -0.00428713 1 0 1 1 0 0 +EDGE2 818 697 -1.06728 0.0172405 0.00166497 1 0 1 1 0 0 +EDGE2 818 777 -0.944994 -0.0126745 -0.0272247 1 0 1 1 0 0 +EDGE2 818 797 -0.983017 0.0240628 -0.008099 1 0 1 1 0 0 +EDGE2 818 817 -1.02543 0.0176397 -0.0213907 1 0 1 1 0 0 +EDGE2 818 757 -1.0038 -0.0106597 0.0118849 1 0 1 1 0 0 +EDGE2 818 699 1.01265 -0.057671 -0.0319554 1 0 1 1 0 0 +EDGE2 818 698 -0.0423617 0.0166022 0.0317134 1 0 1 1 0 0 +EDGE2 818 758 0.0416154 0.0404235 -0.0150649 1 0 1 1 0 0 +EDGE2 818 779 1.05078 0.0176987 0.0104275 1 0 1 1 0 0 +EDGE2 818 799 0.999678 0.0214985 0.00747441 1 0 1 1 0 0 +EDGE2 818 759 0.937872 0.0329887 0.028268 1 0 1 1 0 0 +EDGE2 819 800 0.969199 -0.0384163 0.0107979 1 0 1 1 0 0 +EDGE2 819 778 -0.986577 -0.0494247 0.00945691 1 0 1 1 0 0 +EDGE2 819 798 -1.01362 -0.0967884 0.0438443 1 0 1 1 0 0 +EDGE2 819 818 -1.02008 -0.00124976 0.00998101 1 0 1 1 0 0 +EDGE2 819 699 -0.0353199 -0.035449 -0.0190641 1 0 1 1 0 0 +EDGE2 819 698 -1.01671 0.0718203 -0.011803 1 0 1 1 0 0 +EDGE2 819 758 -1.04207 0.0830447 -0.0109691 1 0 1 1 0 0 +EDGE2 819 779 0.00774577 0.0414226 0.0337031 1 0 1 1 0 0 +EDGE2 819 799 -0.0079257 -0.0237311 0.00561056 1 0 1 1 0 0 +EDGE2 819 759 0.0106848 0.00896775 0.00806073 1 0 1 1 0 0 +EDGE2 819 740 0.995485 0.0364221 -3.10467 1 0 1 1 0 0 +EDGE2 819 760 0.986384 -0.012264 -0.0257265 1 0 1 1 0 0 +EDGE2 819 780 0.953145 0.00963716 9.49367e-05 1 0 1 1 0 0 +EDGE2 819 700 0.914779 0.000604879 -0.0122665 1 0 1 1 0 0 +EDGE2 820 801 0.00953978 1.00995 1.56154 1 0 1 1 0 0 +EDGE2 820 761 0.0484179 1.03191 1.62169 1 0 1 1 0 0 +EDGE2 820 781 -0.0274896 0.99004 1.56379 1 0 1 1 0 0 +EDGE2 820 741 -0.0337639 1.02068 1.55471 1 0 1 1 0 0 +EDGE2 820 800 -0.0180462 0.00647928 0.0231376 1 0 1 1 0 0 +EDGE2 820 699 -0.991341 0.0203264 -0.005042 1 0 1 1 0 0 +EDGE2 820 779 -0.991435 -0.00153461 -0.0174387 1 0 1 1 0 0 +EDGE2 820 799 -0.920475 0.0776701 0.0251659 1 0 1 1 0 0 +EDGE2 820 819 -0.93502 -0.0176407 -0.00229029 1 0 1 1 0 0 +EDGE2 820 759 -1.04048 0.00458119 0.0187034 1 0 1 1 0 0 +EDGE2 820 701 -0.0357072 -0.887573 -1.61406 1 0 1 1 0 0 +EDGE2 820 740 -0.0464821 -0.0306901 -3.11526 1 0 1 1 0 0 +EDGE2 820 760 -0.0671983 -0.0170574 0.0424408 1 0 1 1 0 0 +EDGE2 820 780 -0.0268278 0.00805165 -0.0409946 1 0 1 1 0 0 +EDGE2 820 700 0.0753336 0.0290462 0.0106882 1 0 1 1 0 0 +EDGE2 820 739 0.949294 0.0180977 -3.15898 1 0 1 1 0 0 +EDGE2 821 800 -0.968717 -0.00470601 1.56716 1 0 1 1 0 0 +EDGE2 821 820 -1.04407 -0.0836935 1.56595 1 0 1 1 0 0 +EDGE2 821 701 0.0738686 -0.0820613 -0.00771267 1 0 1 1 0 0 +EDGE2 821 740 -1.08234 0.0427682 -1.56292 1 0 1 1 0 0 +EDGE2 821 760 -1.02631 0.0269241 1.55261 1 0 1 1 0 0 +EDGE2 821 780 -0.921764 0.0344935 1.54685 1 0 1 1 0 0 +EDGE2 821 700 -0.978355 0.0137548 1.61148 1 0 1 1 0 0 +EDGE2 821 702 0.932189 0.0324497 0.0441169 1 0 1 1 0 0 +EDGE2 822 701 -0.956813 0.0286999 -0.00330353 1 0 1 1 0 0 +EDGE2 822 821 -0.932635 0.0033721 0.0348856 1 0 1 1 0 0 +EDGE2 822 702 0.00728502 -0.0230496 0.00163964 1 0 1 1 0 0 +EDGE2 822 703 0.915955 0.0302994 -0.0215955 1 0 1 1 0 0 +EDGE2 823 822 -0.973657 0.0214371 0.00357261 1 0 1 1 0 0 +EDGE2 823 702 -0.993437 -0.0913822 -0.00484421 1 0 1 1 0 0 +EDGE2 823 703 -0.0377296 0.0441724 0.00110443 1 0 1 1 0 0 +EDGE2 823 704 1.01972 0.0235761 -0.0312152 1 0 1 1 0 0 +EDGE2 824 703 -0.983399 -0.0992243 -0.0401465 1 0 1 1 0 0 +EDGE2 824 823 -1.06841 -0.0427316 0.0284634 1 0 1 1 0 0 +EDGE2 824 704 0.072603 -0.028402 0.0409458 1 0 1 1 0 0 +EDGE2 824 705 1.04314 0.0589478 -0.0279559 1 0 1 1 0 0 +EDGE2 825 824 -0.960196 -0.0266913 -0.0249421 1 0 1 1 0 0 +EDGE2 825 704 -1.07369 -0.16007 0.0290263 1 0 1 1 0 0 +EDGE2 825 705 0.00155394 0.0302624 -0.00480086 1 0 1 1 0 0 +EDGE2 825 706 -0.0426297 0.936279 1.56537 1 0 1 1 0 0 +EDGE2 826 705 -0.972688 -0.0604336 1.58039 1 0 1 1 0 0 +EDGE2 826 825 -1.03055 3.29166e-05 1.56392 1 0 1 1 0 0 +EDGE2 827 826 -0.997685 0.0639734 0.020761 1 0 1 1 0 0 +EDGE2 828 827 -1.02785 0.0603507 -0.00558162 1 0 1 1 0 0 +EDGE2 829 690 1.00585 0.0115895 -3.14963 1 0 1 1 0 0 +EDGE2 829 828 -0.941542 0.037669 0.00166524 1 0 1 1 0 0 +EDGE2 830 691 0.0255241 -1.07092 -1.57038 1 0 1 1 0 0 +EDGE2 830 690 0.0353803 0.0281199 -3.17336 1 0 1 1 0 0 +EDGE2 830 689 1.04153 -0.0717463 -3.18143 1 0 1 1 0 0 +EDGE2 830 829 -0.958588 0.105568 0.0132798 1 0 1 1 0 0 +EDGE2 831 690 -0.948055 -0.00635831 1.57289 1 0 1 1 0 0 +EDGE2 831 830 -1.05061 0.0304232 -1.57066 1 0 1 1 0 0 +EDGE2 832 831 -0.998523 -0.0422728 -0.0103438 1 0 1 1 0 0 +EDGE2 833 832 -1.01376 0.0217491 -0.0137042 1 0 1 1 0 0 +EDGE2 834 833 -0.942125 -0.0406953 -0.0232405 1 0 1 1 0 0 +EDGE2 835 834 -1.0163 9.62191e-05 0.00663761 1 0 1 1 0 0 +EDGE2 836 835 -0.939549 -0.0359051 -1.61331 1 0 1 1 0 0 +EDGE2 837 836 -0.921513 -0.0275404 0.00716833 1 0 1 1 0 0 +EDGE2 838 837 -1.01849 0.0480591 -0.0168816 1 0 1 1 0 0 +EDGE2 839 838 -0.998105 -0.0444815 -0.0241785 1 0 1 1 0 0 +EDGE2 840 839 -1.0044 0.0387885 0.0165438 1 0 1 1 0 0 +EDGE2 841 840 -0.857325 -0.0316675 -1.57013 1 0 1 1 0 0 +EDGE2 842 841 -0.925773 0.0286151 0.0121278 1 0 1 1 0 0 +EDGE2 843 842 -1.03657 -0.011697 0.0131785 1 0 1 1 0 0 +EDGE2 844 705 1.03099 -0.00693443 -3.189 1 0 1 1 0 0 +EDGE2 844 825 0.915183 -0.00880792 -3.12249 1 0 1 1 0 0 +EDGE2 844 843 -1.03769 -0.0292703 0.0284987 1 0 1 1 0 0 +EDGE2 845 824 1.04695 0.0262252 -3.15281 1 0 1 1 0 0 +EDGE2 845 704 1.0229 0.0162803 -3.1538 1 0 1 1 0 0 +EDGE2 845 826 0.0388456 0.99473 1.59576 1 0 1 1 0 0 +EDGE2 845 705 0.0452062 0.0646702 -3.12103 1 0 1 1 0 0 +EDGE2 845 825 -0.0158379 0.0394008 -3.1085 1 0 1 1 0 0 +EDGE2 845 844 -0.888741 -0.0337898 -0.0219288 1 0 1 1 0 0 +EDGE2 845 706 -0.0246858 -0.980284 -1.57889 1 0 1 1 0 0 +EDGE2 846 827 0.946933 -0.0341665 0.0139755 1 0 1 1 0 0 +EDGE2 846 826 0.118155 0.0652906 -0.0190718 1 0 1 1 0 0 +EDGE2 846 705 -1.05225 0.0244503 1.57255 1 0 1 1 0 0 +EDGE2 846 825 -0.915597 -0.0465881 1.56256 1 0 1 1 0 0 +EDGE2 846 845 -1.02967 -0.0342215 -1.58325 1 0 1 1 0 0 +EDGE2 847 828 1.06973 -0.016352 0.00198496 1 0 1 1 0 0 +EDGE2 847 827 -0.0110826 -0.00871104 -0.00358268 1 0 1 1 0 0 +EDGE2 847 826 -0.963145 -0.0245967 0.012544 1 0 1 1 0 0 +EDGE2 847 846 -1.03027 0.0341937 0.00871591 1 0 1 1 0 0 +EDGE2 848 829 1.07862 -0.00684003 -0.0322395 1 0 1 1 0 0 +EDGE2 848 828 0.0344772 0.0232808 0.00907853 1 0 1 1 0 0 +EDGE2 848 847 -1.01769 0.110744 -0.0143496 1 0 1 1 0 0 +EDGE2 848 827 -1.01265 -0.0349736 -0.0200383 1 0 1 1 0 0 +EDGE2 849 690 0.97235 -0.0238068 -3.17186 1 0 1 1 0 0 +EDGE2 849 830 0.995704 -0.000177135 -0.0090856 1 0 1 1 0 0 +EDGE2 849 829 0.0221116 0.0141517 0.0111971 1 0 1 1 0 0 +EDGE2 849 828 -1.00489 -0.0262829 -0.0317681 1 0 1 1 0 0 +EDGE2 849 848 -1.02836 -0.124876 0.0241288 1 0 1 1 0 0 +EDGE2 850 691 -0.0862483 -0.957478 -1.55816 1 0 1 1 0 0 +EDGE2 850 690 0.0417354 0.00320767 -3.11411 1 0 1 1 0 0 +EDGE2 850 689 0.951732 0.00302232 -3.13283 1 0 1 1 0 0 +EDGE2 850 830 0.0289408 0.0244065 0.00720574 1 0 1 1 0 0 +EDGE2 850 831 -0.0130204 0.967537 1.55665 1 0 1 1 0 0 +EDGE2 850 829 -0.901517 -0.0551703 -0.0302245 1 0 1 1 0 0 +EDGE2 850 849 -0.989879 0.0779723 -0.0325541 1 0 1 1 0 0 +EDGE2 851 690 -1.01249 -0.0517811 1.57356 1 0 1 1 0 0 +EDGE2 851 850 -1.05591 -0.135006 -1.57321 1 0 1 1 0 0 +EDGE2 851 830 -0.970539 -0.0577691 -1.55271 1 0 1 1 0 0 +EDGE2 851 831 -0.053058 -0.0295675 -0.00656916 1 0 1 1 0 0 +EDGE2 851 832 1.05096 -0.0264416 0.00477779 1 0 1 1 0 0 +EDGE2 852 851 -1.04077 -0.0459349 0.00392616 1 0 1 1 0 0 +EDGE2 852 831 -1.06458 -0.036946 0.0270636 1 0 1 1 0 0 +EDGE2 852 832 -0.0783534 0.0860933 -0.00958949 1 0 1 1 0 0 +EDGE2 852 833 1.07845 0.00106833 -0.00224604 1 0 1 1 0 0 +EDGE2 853 832 -1.00913 0.0356147 0.00408096 1 0 1 1 0 0 +EDGE2 853 852 -0.95907 0.00942069 -0.00523938 1 0 1 1 0 0 +EDGE2 853 833 -0.0353214 -0.0674333 -0.00802346 1 0 1 1 0 0 +EDGE2 853 834 1.03065 0.0547557 -0.0108023 1 0 1 1 0 0 +EDGE2 854 833 -0.887005 -0.0140385 0.0192685 1 0 1 1 0 0 +EDGE2 854 853 -1.01895 0.0340336 0.0183916 1 0 1 1 0 0 +EDGE2 854 834 -0.0581471 0.0397678 -0.00104398 1 0 1 1 0 0 +EDGE2 854 835 0.955918 -0.0350617 -0.0420454 1 0 1 1 0 0 +EDGE2 855 834 -0.966496 -0.00921949 -0.00280609 1 0 1 1 0 0 +EDGE2 855 854 -1.05623 0.0899103 -0.0141769 1 0 1 1 0 0 +EDGE2 855 835 0.0942495 0.0186176 -0.0271727 1 0 1 1 0 0 +EDGE2 855 836 -0.0326112 0.927523 1.56184 1 0 1 1 0 0 +EDGE2 856 855 -0.95295 0.0371157 -1.61452 1 0 1 1 0 0 +EDGE2 856 835 -1.06621 0.0638966 -1.55379 1 0 1 1 0 0 +EDGE2 856 836 0.044631 0.0171689 -0.0414255 1 0 1 1 0 0 +EDGE2 856 837 1.14073 0.0259785 -0.044621 1 0 1 1 0 0 +EDGE2 857 856 -1.05665 0.0201597 0.0270844 1 0 1 1 0 0 +EDGE2 857 836 -1.07606 -0.0740837 0.0369179 1 0 1 1 0 0 +EDGE2 857 837 0.0387385 0.0251476 -0.00390476 1 0 1 1 0 0 +EDGE2 857 838 0.963934 -0.00253434 0.00882741 1 0 1 1 0 0 +EDGE2 858 857 -1.0031 0.0168313 -0.0124767 1 0 1 1 0 0 +EDGE2 858 837 -1.02304 -0.0270217 -0.0197189 1 0 1 1 0 0 +EDGE2 858 838 -0.0351691 -0.0135052 -0.0252139 1 0 1 1 0 0 +EDGE2 858 839 1.05169 0.0120064 -0.0397277 1 0 1 1 0 0 +EDGE2 859 858 -1.02767 -0.065047 -0.0364427 1 0 1 1 0 0 +EDGE2 859 838 -1.055 -0.0435416 -0.0203191 1 0 1 1 0 0 +EDGE2 859 839 -0.0234983 -0.0608665 -0.0560718 1 0 1 1 0 0 +EDGE2 859 840 0.986598 0.0153298 0.00796953 1 0 1 1 0 0 +EDGE2 860 839 -0.991546 0.00119273 -0.0247775 1 0 1 1 0 0 +EDGE2 860 859 -1.01802 0.0180341 -0.0192704 1 0 1 1 0 0 +EDGE2 860 841 0.0206616 1.0164 1.54547 1 0 1 1 0 0 +EDGE2 860 840 0.0640798 0.0295103 -0.0191 1 0 1 1 0 0 +EDGE2 861 842 1.03288 0.00606485 0.0286593 1 0 1 1 0 0 +EDGE2 861 841 0.0411912 0.00663197 -0.0129649 1 0 1 1 0 0 +EDGE2 861 840 -1.02897 0.0295763 -1.55244 1 0 1 1 0 0 +EDGE2 861 860 -0.995273 -0.00127546 -1.58206 1 0 1 1 0 0 +EDGE2 862 843 1.03261 0.00922297 0.0263826 1 0 1 1 0 0 +EDGE2 862 842 -0.054954 0.0159458 -0.0121906 1 0 1 1 0 0 +EDGE2 862 841 -0.984516 0.0407704 0.0225816 1 0 1 1 0 0 +EDGE2 862 861 -1.01971 -0.0190689 -0.00442791 1 0 1 1 0 0 +EDGE2 863 844 0.954161 -0.00954517 0.014347 1 0 1 1 0 0 +EDGE2 863 843 -0.0620428 -0.0258212 0.0139153 1 0 1 1 0 0 +EDGE2 863 842 -0.981308 -0.0336837 -0.0254372 1 0 1 1 0 0 +EDGE2 863 862 -1.06365 0.0454177 -0.0246521 1 0 1 1 0 0 +EDGE2 864 705 0.900709 0.0324458 -3.16577 1 0 1 1 0 0 +EDGE2 864 825 1.0584 0.00532619 -3.15657 1 0 1 1 0 0 +EDGE2 864 845 0.991379 0.00330885 0.0272754 1 0 1 1 0 0 +EDGE2 864 844 0.00682781 0.0219995 -0.0149469 1 0 1 1 0 0 +EDGE2 864 863 -1.03187 0.0542825 0.0154673 1 0 1 1 0 0 +EDGE2 864 843 -1.03576 -0.107112 0.0138726 1 0 1 1 0 0 +EDGE2 865 824 1.09309 -0.00139686 -3.09611 1 0 1 1 0 0 +EDGE2 865 704 1.04603 -0.0471786 -3.14001 1 0 1 1 0 0 +EDGE2 865 826 0.0334411 1.02733 1.60611 1 0 1 1 0 0 +EDGE2 865 846 0.0200124 1.05386 1.55064 1 0 1 1 0 0 +EDGE2 865 864 -1.05958 -0.0530779 -0.00907755 1 0 1 1 0 0 +EDGE2 865 705 -0.0418266 -0.131487 -3.13969 1 0 1 1 0 0 +EDGE2 865 825 0.0400518 0.0356685 -3.13917 1 0 1 1 0 0 +EDGE2 865 845 -0.0668286 -0.0352914 0.00247561 1 0 1 1 0 0 +EDGE2 865 844 -0.994077 0.0255992 -0.0301023 1 0 1 1 0 0 +EDGE2 865 706 0.0708384 -1.03913 -1.57128 1 0 1 1 0 0 +EDGE2 866 865 -1.05907 0.0469949 -1.57079 1 0 1 1 0 0 +EDGE2 866 847 0.943365 0.00430772 0.000775776 1 0 1 1 0 0 +EDGE2 866 827 0.927998 -0.0401914 0.0140703 1 0 1 1 0 0 +EDGE2 866 826 0.0724062 0.0347607 -0.0242336 1 0 1 1 0 0 +EDGE2 866 846 -0.136624 -0.00648025 0.00803768 1 0 1 1 0 0 +EDGE2 866 705 -0.967977 -0.00532707 1.54871 1 0 1 1 0 0 +EDGE2 866 825 -1.03248 -0.119999 1.58566 1 0 1 1 0 0 +EDGE2 866 845 -0.98346 -0.000751954 -1.56334 1 0 1 1 0 0 +EDGE2 867 828 0.988866 0.0523059 -0.0337011 1 0 1 1 0 0 +EDGE2 867 848 1.02786 0.0424659 -0.00398885 1 0 1 1 0 0 +EDGE2 867 847 0.061017 -0.00360069 -0.00132826 1 0 1 1 0 0 +EDGE2 867 827 -0.00561299 0.0307039 0.01797 1 0 1 1 0 0 +EDGE2 867 826 -0.983931 0.0185811 0.0219328 1 0 1 1 0 0 +EDGE2 867 866 -1.07379 0.00724418 0.00284524 1 0 1 1 0 0 +EDGE2 867 846 -1.04819 -0.0591448 -0.0135869 1 0 1 1 0 0 +EDGE2 868 829 0.99405 0.0131436 -0.0163163 1 0 1 1 0 0 +EDGE2 868 849 1.02062 0.045099 0.0204533 1 0 1 1 0 0 +EDGE2 868 828 -0.000792677 0.0787423 0.0223775 1 0 1 1 0 0 +EDGE2 868 848 0.0502005 0.0347936 0.000340937 1 0 1 1 0 0 +EDGE2 868 847 -1.02903 -0.0428279 0.00880318 1 0 1 1 0 0 +EDGE2 868 867 -0.972602 -0.00836861 0.00778216 1 0 1 1 0 0 +EDGE2 868 827 -0.982466 -0.0625614 0.0332364 1 0 1 1 0 0 +EDGE2 869 690 0.977039 0.0567404 -3.12744 1 0 1 1 0 0 +EDGE2 869 850 0.972779 -0.017379 0.010007 1 0 1 1 0 0 +EDGE2 869 830 0.990969 -0.0391452 -0.00800224 1 0 1 1 0 0 +EDGE2 869 829 0.0893417 -0.0142081 0.01367 1 0 1 1 0 0 +EDGE2 869 849 -0.0877129 -0.0738329 0.00550637 1 0 1 1 0 0 +EDGE2 869 828 -1.00596 -0.066576 0.0243074 1 0 1 1 0 0 +EDGE2 869 848 -1.09474 -0.00793776 0.0113374 1 0 1 1 0 0 +EDGE2 869 868 -0.975563 -0.0373911 0.0195671 1 0 1 1 0 0 +EDGE2 870 691 0.00717831 -1.0568 -1.59396 1 0 1 1 0 0 +EDGE2 870 690 -0.00038441 0.0169201 -3.11308 1 0 1 1 0 0 +EDGE2 870 689 0.949571 -0.00961048 -3.09597 1 0 1 1 0 0 +EDGE2 870 850 -0.06589 -0.0349811 0.00677169 1 0 1 1 0 0 +EDGE2 870 830 4.39718e-05 -0.0284744 -0.0303508 1 0 1 1 0 0 +EDGE2 870 851 0.0577917 0.914374 1.60889 1 0 1 1 0 0 +EDGE2 870 831 -0.0459557 0.995892 1.57654 1 0 1 1 0 0 +EDGE2 870 869 -1.05601 0.00426648 -0.0191827 1 0 1 1 0 0 +EDGE2 870 829 -1.07081 -0.045912 0.00229477 1 0 1 1 0 0 +EDGE2 870 849 -1.02314 -0.0268422 0.00404809 1 0 1 1 0 0 +EDGE2 871 692 0.957585 0.0255973 -0.00270184 1 0 1 1 0 0 +EDGE2 871 691 0.0659912 -0.00360959 0.02144 1 0 1 1 0 0 +EDGE2 871 690 -1.05528 0.00624702 -1.55826 1 0 1 1 0 0 +EDGE2 871 850 -1.00299 0.00130585 1.55781 1 0 1 1 0 0 +EDGE2 871 870 -0.98135 0.018816 1.55499 1 0 1 1 0 0 +EDGE2 871 830 -1.00513 -0.0293304 1.57107 1 0 1 1 0 0 +EDGE2 872 693 0.947413 0.0219862 0.00820313 1 0 1 1 0 0 +EDGE2 872 692 -0.01994 0.13077 -0.00103771 1 0 1 1 0 0 +EDGE2 872 691 -0.979995 0.0325607 -0.0174887 1 0 1 1 0 0 +EDGE2 872 871 -1.04773 0.021468 -0.0145539 1 0 1 1 0 0 +EDGE2 873 693 0.0399207 -0.0777956 0.0103178 1 0 1 1 0 0 +EDGE2 873 694 1.06575 0.0686032 0.0255898 1 0 1 1 0 0 +EDGE2 873 872 -0.917642 0.0362768 0.0207243 1 0 1 1 0 0 +EDGE2 873 692 -0.968248 0.03481 0.00058303 1 0 1 1 0 0 +EDGE2 874 795 0.998567 -0.067231 -3.15641 1 0 1 1 0 0 +EDGE2 874 815 0.985444 -0.0844719 -3.14591 1 0 1 1 0 0 +EDGE2 874 755 0.976006 0.0247596 -3.14483 1 0 1 1 0 0 +EDGE2 874 775 0.938879 0.0203284 -3.15561 1 0 1 1 0 0 +EDGE2 874 695 0.933613 -0.0711211 -0.000904665 1 0 1 1 0 0 +EDGE2 874 693 -1.06431 -0.0105101 0.00410995 1 0 1 1 0 0 +EDGE2 874 694 0.0317375 -0.0167542 -0.00740625 1 0 1 1 0 0 +EDGE2 874 873 -0.999209 -0.0337563 0.0401005 1 0 1 1 0 0 +EDGE2 875 774 0.994418 0.0205578 -3.14625 1 0 1 1 0 0 +EDGE2 875 814 0.954916 0.0207979 -3.13467 1 0 1 1 0 0 +EDGE2 875 794 0.983173 -0.0924748 -3.14615 1 0 1 1 0 0 +EDGE2 875 754 1.00655 -0.0104981 -3.15722 1 0 1 1 0 0 +EDGE2 875 795 -0.0288457 -0.0552889 -3.14718 1 0 1 1 0 0 +EDGE2 875 815 0.0420927 -0.037816 -3.10936 1 0 1 1 0 0 +EDGE2 875 755 -0.0523265 0.0164389 -3.11863 1 0 1 1 0 0 +EDGE2 875 775 -0.0834078 -0.0180757 -3.17158 1 0 1 1 0 0 +EDGE2 875 695 0.0241434 0.0740341 -0.000100456 1 0 1 1 0 0 +EDGE2 875 874 -1.01268 0.0338158 -0.000311194 1 0 1 1 0 0 +EDGE2 875 694 -1.11247 0.0380293 -0.00827001 1 0 1 1 0 0 +EDGE2 875 796 -0.0446962 -0.969339 -1.5719 1 0 1 1 0 0 +EDGE2 875 816 0.00470411 -0.907753 -1.5698 1 0 1 1 0 0 +EDGE2 875 696 0.0352418 -0.969213 -1.56008 1 0 1 1 0 0 +EDGE2 875 756 0.00280667 -0.957128 -1.53776 1 0 1 1 0 0 +EDGE2 875 776 0.038149 -0.974206 -1.57275 1 0 1 1 0 0 +EDGE2 876 795 -0.93654 -0.00973697 1.56104 1 0 1 1 0 0 +EDGE2 876 875 -0.959493 -0.0471528 -1.53589 1 0 1 1 0 0 +EDGE2 876 815 -1.05054 0.0505937 1.57556 1 0 1 1 0 0 +EDGE2 876 755 -1.06466 -0.0283842 1.5485 1 0 1 1 0 0 +EDGE2 876 775 -0.982965 0.0873326 1.54769 1 0 1 1 0 0 +EDGE2 876 695 -0.907838 0.0816715 -1.58763 1 0 1 1 0 0 +EDGE2 877 876 -1.02716 0.0139386 0.00532697 1 0 1 1 0 0 +EDGE2 878 877 -0.948332 -0.0489823 0.0186053 1 0 1 1 0 0 +EDGE2 879 878 -0.99124 0.0115367 0.00989167 1 0 1 1 0 0 +EDGE2 880 879 -1.06108 -0.0607787 -0.00135534 1 0 1 1 0 0 +EDGE2 881 880 -1.01362 -0.0671638 -1.61385 1 0 1 1 0 0 +EDGE2 882 881 -0.959321 -0.0251326 0.0274314 1 0 1 1 0 0 +EDGE2 883 882 -1.07026 0.0162418 -0.0212049 1 0 1 1 0 0 +EDGE2 884 883 -1.12593 0.0178338 -0.0333323 1 0 1 1 0 0 +EDGE2 884 685 1.015 -0.0536852 -3.15664 1 0 1 1 0 0 +EDGE2 885 884 -0.956129 0.031659 0.0073168 1 0 1 1 0 0 +EDGE2 885 685 0.00507871 -0.053856 -3.1551 1 0 1 1 0 0 +EDGE2 885 684 1.10326 0.0296604 -3.13216 1 0 1 1 0 0 +EDGE2 885 686 -0.100032 0.930506 1.5584 1 0 1 1 0 0 +EDGE2 886 885 -0.966525 0.0662208 -1.57224 1 0 1 1 0 0 +EDGE2 886 685 -0.992575 -0.070562 1.5592 1 0 1 1 0 0 +EDGE2 886 686 -0.0385127 -0.00129991 0.0422185 1 0 1 1 0 0 +EDGE2 886 687 1.00812 0.00427218 -0.00625937 1 0 1 1 0 0 +EDGE2 887 686 -0.928656 0.104003 0.00194908 1 0 1 1 0 0 +EDGE2 887 886 -1.0547 -0.0331058 0.0097778 1 0 1 1 0 0 +EDGE2 887 687 -0.108899 -0.0191306 0.00937911 1 0 1 1 0 0 +EDGE2 887 688 1.00927 -0.00335979 -0.0334347 1 0 1 1 0 0 +EDGE2 888 687 -0.987358 -0.0909836 0.0141794 1 0 1 1 0 0 +EDGE2 888 887 -0.989591 -0.057147 -0.00420915 1 0 1 1 0 0 +EDGE2 888 688 -0.0147532 -0.0635823 -0.0117171 1 0 1 1 0 0 +EDGE2 888 689 0.99457 0.0291348 0.0330578 1 0 1 1 0 0 +EDGE2 889 690 0.956407 -0.085326 -0.0201425 1 0 1 1 0 0 +EDGE2 889 888 -1.0861 -0.0875542 -0.0302447 1 0 1 1 0 0 +EDGE2 889 688 -1.05859 0.0139985 -0.0321801 1 0 1 1 0 0 +EDGE2 889 689 0.0400561 -0.0597096 -0.0036498 1 0 1 1 0 0 +EDGE2 889 850 1.03428 0.00876086 -3.12389 1 0 1 1 0 0 +EDGE2 889 870 0.98169 0.00107488 -3.17592 1 0 1 1 0 0 +EDGE2 889 830 0.964476 -0.04727 -3.08357 1 0 1 1 0 0 +EDGE2 890 691 0.0290975 1.05439 1.57727 1 0 1 1 0 0 +EDGE2 890 871 -0.0603978 0.965158 1.58222 1 0 1 1 0 0 +EDGE2 890 690 0.00974994 0.0125762 -0.00438846 1 0 1 1 0 0 +EDGE2 890 689 -0.917019 0.0834739 -0.0063404 1 0 1 1 0 0 +EDGE2 890 889 -1.01356 0.0834046 -0.00323848 1 0 1 1 0 0 +EDGE2 890 850 -0.0359816 0.0300143 -3.14299 1 0 1 1 0 0 +EDGE2 890 870 -0.0407012 0.0158593 -3.10111 1 0 1 1 0 0 +EDGE2 890 830 -0.0736267 0.0412232 -3.13049 1 0 1 1 0 0 +EDGE2 890 851 -0.0192016 -1.0911 -1.56464 1 0 1 1 0 0 +EDGE2 890 831 -0.0555932 -0.97149 -1.5701 1 0 1 1 0 0 +EDGE2 890 869 0.918664 -0.0219169 -3.16153 1 0 1 1 0 0 +EDGE2 890 829 1.07343 -0.00874186 -3.122 1 0 1 1 0 0 +EDGE2 890 849 0.984496 -0.0210631 -3.16524 1 0 1 1 0 0 +EDGE2 891 690 -1.03082 0.100734 1.57204 1 0 1 1 0 0 +EDGE2 891 850 -0.983367 0.0552491 -1.59677 1 0 1 1 0 0 +EDGE2 891 870 -0.952426 0.0950074 -1.562 1 0 1 1 0 0 +EDGE2 891 890 -1.00922 -0.0107702 1.58592 1 0 1 1 0 0 +EDGE2 891 830 -1.09518 0.0241018 -1.57586 1 0 1 1 0 0 +EDGE2 891 851 0.0177616 0.00557783 -0.000952939 1 0 1 1 0 0 +EDGE2 891 831 0.100908 -0.0122865 -0.0267784 1 0 1 1 0 0 +EDGE2 891 832 0.990343 -0.091267 0.0187165 1 0 1 1 0 0 +EDGE2 891 852 1.02977 0.0172976 0.0338453 1 0 1 1 0 0 +EDGE2 892 851 -0.993556 -0.0575712 -0.0121992 1 0 1 1 0 0 +EDGE2 892 891 -1.05405 0.00668297 -0.0190062 1 0 1 1 0 0 +EDGE2 892 831 -0.887075 -0.0529647 -0.00903956 1 0 1 1 0 0 +EDGE2 892 832 0.00919078 0.0242506 -0.00182692 1 0 1 1 0 0 +EDGE2 892 852 -0.00412503 -0.0675655 0.0183463 1 0 1 1 0 0 +EDGE2 892 833 1.05071 0.0184103 -0.00210815 1 0 1 1 0 0 +EDGE2 892 853 1.08734 -0.00866286 -0.0164343 1 0 1 1 0 0 +EDGE2 893 892 -1.05816 -0.0639719 0.0197601 1 0 1 1 0 0 +EDGE2 893 832 -1.04222 -0.0246653 -0.0117419 1 0 1 1 0 0 +EDGE2 893 852 -1.00583 -0.038781 0.0195356 1 0 1 1 0 0 +EDGE2 893 833 0.0380022 -0.0421054 0.00404506 1 0 1 1 0 0 +EDGE2 893 853 -0.0307495 -0.043111 0.016943 1 0 1 1 0 0 +EDGE2 893 834 0.8939 0.0306243 -0.0186642 1 0 1 1 0 0 +EDGE2 893 854 0.961663 -0.0571882 -0.00736278 1 0 1 1 0 0 +EDGE2 894 833 -1.00326 0.0668795 0.028913 1 0 1 1 0 0 +EDGE2 894 853 -1.02568 -0.00661951 -0.0212235 1 0 1 1 0 0 +EDGE2 894 893 -0.978537 -0.0107605 0.00233368 1 0 1 1 0 0 +EDGE2 894 834 0.0269017 -0.0327761 -0.011621 1 0 1 1 0 0 +EDGE2 894 854 -0.0447086 0.0340028 -0.0129379 1 0 1 1 0 0 +EDGE2 894 855 1.07065 0.0153488 0.0501778 1 0 1 1 0 0 +EDGE2 894 835 0.981148 0.0341945 0.0012649 1 0 1 1 0 0 +EDGE2 895 894 -1.01309 -0.00483226 -0.0078708 1 0 1 1 0 0 +EDGE2 895 834 -0.97175 -0.0221542 -0.002417 1 0 1 1 0 0 +EDGE2 895 854 -1.03091 -0.0228055 -0.0194096 1 0 1 1 0 0 +EDGE2 895 855 0.0851141 0.126152 -0.0121077 1 0 1 1 0 0 +EDGE2 895 835 -0.000536968 -0.0613781 0.0226209 1 0 1 1 0 0 +EDGE2 895 856 0.0270898 1.00947 1.52985 1 0 1 1 0 0 +EDGE2 895 836 0.0396865 1.01144 1.56452 1 0 1 1 0 0 +EDGE2 896 855 -1.10967 0.0549772 -1.59724 1 0 1 1 0 0 +EDGE2 896 895 -0.917662 0.0774445 -1.54868 1 0 1 1 0 0 +EDGE2 896 835 -1.00943 -0.0704072 -1.5311 1 0 1 1 0 0 +EDGE2 896 856 -0.0256298 0.106181 -0.0289041 1 0 1 1 0 0 +EDGE2 896 836 0.0630494 0.00954366 0.0184046 1 0 1 1 0 0 +EDGE2 896 857 0.997752 -0.0657967 -0.0184563 1 0 1 1 0 0 +EDGE2 896 837 1.00795 0.109025 0.00789337 1 0 1 1 0 0 +EDGE2 897 856 -1.14399 0.0568389 0.0198937 1 0 1 1 0 0 +EDGE2 897 896 -1.00995 -0.0923935 0.0188998 1 0 1 1 0 0 +EDGE2 897 836 -1.05392 0.0242294 0.0341908 1 0 1 1 0 0 +EDGE2 897 857 0.0639257 -0.123154 0.00359687 1 0 1 1 0 0 +EDGE2 897 837 0.0152073 0.0418086 0.0297244 1 0 1 1 0 0 +EDGE2 897 858 0.990511 -0.0721041 0.00962168 1 0 1 1 0 0 +EDGE2 897 838 0.931703 0.000594986 0.0233115 1 0 1 1 0 0 +EDGE2 898 857 -0.906155 -0.0223185 -0.0158804 1 0 1 1 0 0 +EDGE2 898 897 -1.04935 -0.0299751 -0.00291762 1 0 1 1 0 0 +EDGE2 898 837 -0.862993 0.00196863 -0.0344989 1 0 1 1 0 0 +EDGE2 898 858 -0.0731157 -0.0115522 0.00347256 1 0 1 1 0 0 +EDGE2 898 838 -0.00948227 -0.000183224 -0.0266787 1 0 1 1 0 0 +EDGE2 898 839 1.00529 0.0543846 0.0297195 1 0 1 1 0 0 +EDGE2 898 859 1.06027 0.0835859 0.009057 1 0 1 1 0 0 +EDGE2 899 858 -1.0102 0.0361343 0.0111263 1 0 1 1 0 0 +EDGE2 899 898 -1.02862 -0.0208845 0.00163311 1 0 1 1 0 0 +EDGE2 899 838 -1.04688 -0.0467605 -0.00741631 1 0 1 1 0 0 +EDGE2 899 839 0.171652 0.00151654 -0.0148602 1 0 1 1 0 0 +EDGE2 899 859 -0.0622642 0.0296366 -0.00399908 1 0 1 1 0 0 +EDGE2 899 840 0.993498 -0.0328455 0.0239867 1 0 1 1 0 0 +EDGE2 899 860 1.04048 -0.0320258 -0.00466713 1 0 1 1 0 0 +EDGE2 900 839 -1.09168 -0.00798499 -0.00261169 1 0 1 1 0 0 +EDGE2 900 899 -1.01665 0.0121159 -0.00894035 1 0 1 1 0 0 +EDGE2 900 859 -1.03707 0.0533154 0.0114659 1 0 1 1 0 0 +EDGE2 900 841 -0.0143609 0.963163 1.56134 1 0 1 1 0 0 +EDGE2 900 861 -0.0682991 1.00072 1.59023 1 0 1 1 0 0 +EDGE2 900 840 0.00817475 0.00359902 -0.0341111 1 0 1 1 0 0 +EDGE2 900 860 -0.0236251 -0.0384745 -0.0124209 1 0 1 1 0 0 +EDGE2 901 842 0.943512 -0.0804361 0.00473316 1 0 1 1 0 0 +EDGE2 901 862 0.876028 -0.0361846 -0.0276825 1 0 1 1 0 0 +EDGE2 901 841 -0.0100744 0.0433135 -0.0130661 1 0 1 1 0 0 +EDGE2 901 861 -0.0449161 0.135831 -0.00360959 1 0 1 1 0 0 +EDGE2 901 900 -0.957768 -0.0664954 -1.58458 1 0 1 1 0 0 +EDGE2 901 840 -1.01321 0.0380619 -1.56782 1 0 1 1 0 0 +EDGE2 901 860 -0.963209 0.0428227 -1.5548 1 0 1 1 0 0 +EDGE2 902 863 0.951217 0.0471363 0.0108117 1 0 1 1 0 0 +EDGE2 902 843 0.998884 0.0454096 0.000321951 1 0 1 1 0 0 +EDGE2 902 842 0.0145446 -0.0437175 0.0173691 1 0 1 1 0 0 +EDGE2 902 862 0.0134683 -0.106174 0.0229981 1 0 1 1 0 0 +EDGE2 902 841 -0.987752 0.0165474 -0.019934 1 0 1 1 0 0 +EDGE2 902 901 -1.04972 0.010881 -0.0432603 1 0 1 1 0 0 +EDGE2 902 861 -1.04043 -0.00977666 -0.0123371 1 0 1 1 0 0 +EDGE2 903 864 1.01266 -0.0848883 0.00556878 1 0 1 1 0 0 +EDGE2 903 844 0.94822 0.0510042 -0.00678164 1 0 1 1 0 0 +EDGE2 903 863 -0.0336771 -0.0105223 0.0196227 1 0 1 1 0 0 +EDGE2 903 843 -0.0622652 -0.025932 -0.0200463 1 0 1 1 0 0 +EDGE2 903 902 -1.04627 -0.0105956 -0.00658728 1 0 1 1 0 0 +EDGE2 903 842 -1.0047 0.0722693 -0.00548405 1 0 1 1 0 0 +EDGE2 903 862 -1.05471 0.0431132 0.00419548 1 0 1 1 0 0 +EDGE2 904 865 1.01322 -0.0983309 0.00290026 1 0 1 1 0 0 +EDGE2 904 864 0.0438849 0.00171579 0.0365952 1 0 1 1 0 0 +EDGE2 904 705 0.940478 -0.08013 -3.14129 1 0 1 1 0 0 +EDGE2 904 825 1.02553 0.0466159 -3.13021 1 0 1 1 0 0 +EDGE2 904 845 0.897663 -0.0158356 -0.00407256 1 0 1 1 0 0 +EDGE2 904 844 0.0362087 -0.0299863 -0.0193743 1 0 1 1 0 0 +EDGE2 904 863 -0.972795 0.0289689 0.0270503 1 0 1 1 0 0 +EDGE2 904 903 -0.946301 0.0386082 -0.0188662 1 0 1 1 0 0 +EDGE2 904 843 -0.98029 0.0199033 -0.000979501 1 0 1 1 0 0 +EDGE2 905 824 0.992263 0.047337 -3.14504 1 0 1 1 0 0 +EDGE2 905 704 0.986539 0.0776203 -3.14283 1 0 1 1 0 0 +EDGE2 905 865 -0.0176075 -0.0319301 0.0148228 1 0 1 1 0 0 +EDGE2 905 826 0.0258485 1.00253 1.56888 1 0 1 1 0 0 +EDGE2 905 866 -0.0312333 0.95775 1.55623 1 0 1 1 0 0 +EDGE2 905 846 0.0466651 0.995999 1.57452 1 0 1 1 0 0 +EDGE2 905 864 -0.978134 0.0196048 0.00285575 1 0 1 1 0 0 +EDGE2 905 705 -0.0417524 -0.0458884 -3.12844 1 0 1 1 0 0 +EDGE2 905 825 -0.0171428 0.0111138 -3.13906 1 0 1 1 0 0 +EDGE2 905 845 -0.0525425 0.028095 0.00128178 1 0 1 1 0 0 +EDGE2 905 904 -0.983409 0.0651049 -0.00919656 1 0 1 1 0 0 +EDGE2 905 844 -1.01859 0.0129523 0.0338911 1 0 1 1 0 0 +EDGE2 905 706 -0.034708 -1.02259 -1.55328 1 0 1 1 0 0 +EDGE2 906 865 -1.00365 -0.00671527 -1.5833 1 0 1 1 0 0 +EDGE2 906 847 1.05738 -0.0257266 -0.0245761 1 0 1 1 0 0 +EDGE2 906 867 1.00089 0.0855922 -0.00386637 1 0 1 1 0 0 +EDGE2 906 827 1.00048 0.0100423 0.0180939 1 0 1 1 0 0 +EDGE2 906 826 0.0184391 -0.000457008 0.0182964 1 0 1 1 0 0 +EDGE2 906 866 0.00677949 -0.00575764 0.0111488 1 0 1 1 0 0 +EDGE2 906 846 0.0229726 -0.0682188 0.0176103 1 0 1 1 0 0 +EDGE2 906 905 -1.07779 -0.0114615 -1.52339 1 0 1 1 0 0 +EDGE2 906 705 -0.96249 0.0709903 1.60217 1 0 1 1 0 0 +EDGE2 906 825 -1.06988 -0.115759 1.57127 1 0 1 1 0 0 +EDGE2 906 845 -0.967826 0.0746671 -1.57019 1 0 1 1 0 0 +EDGE2 907 828 1.06155 0.0861464 -0.0176254 1 0 1 1 0 0 +EDGE2 907 848 0.946601 0.0399376 0.00358673 1 0 1 1 0 0 +EDGE2 907 868 0.998458 -0.0926816 -0.0630019 1 0 1 1 0 0 +EDGE2 907 847 0.00880527 0.0267376 -0.0128776 1 0 1 1 0 0 +EDGE2 907 867 -0.0524926 -0.0930973 0.00605724 1 0 1 1 0 0 +EDGE2 907 827 -0.0488557 -0.052694 0.0114541 1 0 1 1 0 0 +EDGE2 907 826 -1.01987 -0.00327621 0.0356739 1 0 1 1 0 0 +EDGE2 907 866 -0.960431 0.0197732 0.013329 1 0 1 1 0 0 +EDGE2 907 906 -0.96403 0.0180786 -0.0102046 1 0 1 1 0 0 +EDGE2 907 846 -1.07635 0.0913645 -0.0112666 1 0 1 1 0 0 +EDGE2 908 869 1.05652 0.00922741 -0.0236702 1 0 1 1 0 0 +EDGE2 908 829 1.05073 0.0520907 -0.00502499 1 0 1 1 0 0 +EDGE2 908 849 1.01515 -0.0926229 0.0115194 1 0 1 1 0 0 +EDGE2 908 828 0.0714971 0.0633133 -0.00469015 1 0 1 1 0 0 +EDGE2 908 848 0.0503876 0.0295351 -0.0229744 1 0 1 1 0 0 +EDGE2 908 868 -0.0905768 -0.044094 -0.00292197 1 0 1 1 0 0 +EDGE2 908 847 -0.980615 0.0253758 -0.0210109 1 0 1 1 0 0 +EDGE2 908 867 -1.02588 -0.0822777 0.000559789 1 0 1 1 0 0 +EDGE2 908 907 -1.07347 0.0283254 0.0100021 1 0 1 1 0 0 +EDGE2 908 827 -0.959358 0.00341306 -0.00904992 1 0 1 1 0 0 +EDGE2 909 908 -0.982179 0.0141092 0.0109816 1 0 1 1 0 0 +EDGE2 909 690 1.03576 -0.0218463 -3.11939 1 0 1 1 0 0 +EDGE2 909 850 1.00285 0.169291 -0.0201441 1 0 1 1 0 0 +EDGE2 909 870 0.99652 -0.00463257 0.00693162 1 0 1 1 0 0 +EDGE2 909 890 1.0266 -0.0244167 -3.19381 1 0 1 1 0 0 +EDGE2 909 830 1.03036 0.0281795 0.00318596 1 0 1 1 0 0 +EDGE2 909 869 0.0446423 0.00992175 0.0157609 1 0 1 1 0 0 +EDGE2 909 829 -0.0354661 0.0203821 -0.0153243 1 0 1 1 0 0 +EDGE2 909 849 -0.0185017 -0.0762808 -0.0321464 1 0 1 1 0 0 +EDGE2 909 828 -1.00102 -0.0738436 -0.0177072 1 0 1 1 0 0 +EDGE2 909 848 -1.01091 -0.00883845 0.000601518 1 0 1 1 0 0 +EDGE2 909 868 -1.0248 -0.0100176 -0.0128622 1 0 1 1 0 0 +EDGE2 910 691 -0.0844799 -0.973636 -1.57062 1 0 1 1 0 0 +EDGE2 910 871 -0.00343708 -0.859125 -1.58605 1 0 1 1 0 0 +EDGE2 910 690 0.0926545 -0.0235565 -3.15771 1 0 1 1 0 0 +EDGE2 910 689 0.939334 -0.096067 -3.12162 1 0 1 1 0 0 +EDGE2 910 889 1.00502 0.0781228 -3.12873 1 0 1 1 0 0 +EDGE2 910 850 0.00842661 -0.112204 0.00442082 1 0 1 1 0 0 +EDGE2 910 870 -0.060005 0.0540003 -0.0167584 1 0 1 1 0 0 +EDGE2 910 890 -0.0120497 0.0169972 -3.13217 1 0 1 1 0 0 +EDGE2 910 830 -0.0584674 0.0106562 0.0138426 1 0 1 1 0 0 +EDGE2 910 851 0.0437491 1.01952 1.59507 1 0 1 1 0 0 +EDGE2 910 891 -0.0394817 0.970219 1.59427 1 0 1 1 0 0 +EDGE2 910 831 -0.0900954 0.944261 1.5468 1 0 1 1 0 0 +EDGE2 910 869 -0.932952 -0.0309857 0.00813536 1 0 1 1 0 0 +EDGE2 910 909 -1.06153 0.0334359 0.00715396 1 0 1 1 0 0 +EDGE2 910 829 -1.02009 0.00795546 0.0111611 1 0 1 1 0 0 +EDGE2 910 849 -0.975188 0.074356 0.00869346 1 0 1 1 0 0 +EDGE2 911 690 -0.987384 -0.0269868 1.60089 1 0 1 1 0 0 +EDGE2 911 910 -1.05761 0.00897193 -1.55571 1 0 1 1 0 0 +EDGE2 911 850 -1.01637 0.00492615 -1.57168 1 0 1 1 0 0 +EDGE2 911 870 -1.00169 -0.0589325 -1.54059 1 0 1 1 0 0 +EDGE2 911 890 -1.02854 -0.0186757 1.58593 1 0 1 1 0 0 +EDGE2 911 830 -0.960917 0.048429 -1.58848 1 0 1 1 0 0 +EDGE2 911 892 0.977947 -0.0160095 0.00544519 1 0 1 1 0 0 +EDGE2 911 851 -0.0402474 0.0667169 0.0159774 1 0 1 1 0 0 +EDGE2 911 891 -0.00348838 -0.06209 -0.0100549 1 0 1 1 0 0 +EDGE2 911 831 -0.0100638 -0.0561004 -0.0158466 1 0 1 1 0 0 +EDGE2 911 832 1.02548 -0.0382921 0.00378124 1 0 1 1 0 0 +EDGE2 911 852 0.991889 0.0363745 -0.00815736 1 0 1 1 0 0 +EDGE2 912 892 -0.00258509 0.0333988 0.00838269 1 0 1 1 0 0 +EDGE2 912 851 -0.963511 0.0423943 0.00066693 1 0 1 1 0 0 +EDGE2 912 911 -1.00382 0.0722158 -0.0129311 1 0 1 1 0 0 +EDGE2 912 891 -1.06133 0.138986 -0.0115952 1 0 1 1 0 0 +EDGE2 912 831 -0.954413 0.0264051 -0.0178952 1 0 1 1 0 0 +EDGE2 912 832 0.0451103 -0.0698406 0.0128655 1 0 1 1 0 0 +EDGE2 912 852 -0.0165521 0.0428279 0.00557638 1 0 1 1 0 0 +EDGE2 912 833 0.983753 0.0116593 -0.0403109 1 0 1 1 0 0 +EDGE2 912 853 0.979666 -0.069051 0.0114609 1 0 1 1 0 0 +EDGE2 912 893 1.03366 0.0334244 -0.0082806 1 0 1 1 0 0 +EDGE2 913 892 -0.939647 0.139202 -0.0100166 1 0 1 1 0 0 +EDGE2 913 912 -0.961021 0.0826365 0.00251685 1 0 1 1 0 0 +EDGE2 913 832 -0.954665 -0.0959584 -0.0278318 1 0 1 1 0 0 +EDGE2 913 852 -1.05614 -0.0888685 0.0107048 1 0 1 1 0 0 +EDGE2 913 833 -0.00719488 0.0384691 -0.0165447 1 0 1 1 0 0 +EDGE2 913 853 -0.052398 -0.0621433 0.0140464 1 0 1 1 0 0 +EDGE2 913 893 -0.00561206 -0.00534206 0.0646817 1 0 1 1 0 0 +EDGE2 913 894 0.977976 -0.0366812 0.0232567 1 0 1 1 0 0 +EDGE2 913 834 0.941145 0.00680004 -0.0188724 1 0 1 1 0 0 +EDGE2 913 854 0.99472 -0.00786641 -0.000877347 1 0 1 1 0 0 +EDGE2 914 913 -1.02529 0.11396 0.0196124 1 0 1 1 0 0 +EDGE2 914 833 -0.956977 0.0563183 0.00565992 1 0 1 1 0 0 +EDGE2 914 853 -0.968813 0.0573539 0.0381273 1 0 1 1 0 0 +EDGE2 914 893 -0.941347 0.036218 -0.0143136 1 0 1 1 0 0 +EDGE2 914 894 -0.00797192 0.056419 0.000489045 1 0 1 1 0 0 +EDGE2 914 834 0.0164954 -0.0714753 0.0359449 1 0 1 1 0 0 +EDGE2 914 854 0.0553129 -0.0453064 0.00799841 1 0 1 1 0 0 +EDGE2 914 855 0.992733 -0.0189951 -0.0311882 1 0 1 1 0 0 +EDGE2 914 895 1.10902 0.00212252 -0.000628178 1 0 1 1 0 0 +EDGE2 914 835 1.02755 0.0081674 -0.000530975 1 0 1 1 0 0 +EDGE2 915 894 -0.961548 -0.0364167 -0.0146245 1 0 1 1 0 0 +EDGE2 915 914 -1.01703 0.0433098 -0.036829 1 0 1 1 0 0 +EDGE2 915 834 -0.891259 -0.0236212 -0.0152533 1 0 1 1 0 0 +EDGE2 915 854 -0.993243 0.0325995 -0.0108864 1 0 1 1 0 0 +EDGE2 915 855 0.0403732 -0.00743977 0.0188377 1 0 1 1 0 0 +EDGE2 915 895 -0.0346951 0.0320465 -0.0152241 1 0 1 1 0 0 +EDGE2 915 835 4.23963e-06 -0.0764835 0.00368946 1 0 1 1 0 0 +EDGE2 915 856 0.0239179 1.00148 1.57414 1 0 1 1 0 0 +EDGE2 915 896 0.0264491 0.888466 1.5772 1 0 1 1 0 0 +EDGE2 915 836 0.0269818 0.913693 1.56358 1 0 1 1 0 0 +EDGE2 916 855 -1.00524 0.019876 1.58309 1 0 1 1 0 0 +EDGE2 916 895 -0.993739 0.0161521 1.58746 1 0 1 1 0 0 +EDGE2 916 915 -1.04571 0.0434773 1.54541 1 0 1 1 0 0 +EDGE2 916 835 -1.04827 0.0424732 1.58869 1 0 1 1 0 0 +EDGE2 917 916 -0.97968 0.0514389 0.0258899 1 0 1 1 0 0 +EDGE2 918 917 -0.932333 -0.0964718 0.0161639 1 0 1 1 0 0 +EDGE2 919 680 0.968118 -0.00406942 -3.13773 1 0 1 1 0 0 +EDGE2 919 918 -1.01737 0.0158307 0.00853316 1 0 1 1 0 0 +EDGE2 920 679 1.02703 0.100202 -3.12807 1 0 1 1 0 0 +EDGE2 920 681 0.0520503 -1.08008 -1.56843 1 0 1 1 0 0 +EDGE2 920 680 0.01105 -0.0334833 -3.18846 1 0 1 1 0 0 +EDGE2 920 919 -1.0823 -0.0509026 -0.0056902 1 0 1 1 0 0 +EDGE2 921 920 -0.905716 0.0376476 -1.53966 1 0 1 1 0 0 +EDGE2 921 680 -1.00018 -0.00760417 1.55855 1 0 1 1 0 0 +EDGE2 922 921 -0.973587 -0.0226256 -0.0206155 1 0 1 1 0 0 +EDGE2 923 922 -0.959623 -0.0222361 0.0159034 1 0 1 1 0 0 +EDGE2 924 923 -0.945913 -0.00436779 0.0247846 1 0 1 1 0 0 +EDGE2 925 924 -0.955602 0.0192923 0.0100684 1 0 1 1 0 0 +EDGE2 926 925 -1.1116 0.0278474 1.59952 1 0 1 1 0 0 +EDGE2 927 926 -0.947537 -0.0127535 0.0225582 1 0 1 1 0 0 +EDGE2 928 927 -0.936744 0.0421605 0.0321072 1 0 1 1 0 0 +EDGE2 929 670 0.944634 0.10631 -3.15763 1 0 1 1 0 0 +EDGE2 929 928 -0.999431 0.0174395 0.0128387 1 0 1 1 0 0 +EDGE2 930 669 0.941204 0.0745641 -3.17359 1 0 1 1 0 0 +EDGE2 930 671 0.0564955 -0.993383 -1.54192 1 0 1 1 0 0 +EDGE2 930 670 0.018377 0.000868804 -3.14119 1 0 1 1 0 0 +EDGE2 930 929 -1.04104 -0.0727195 -0.0087291 1 0 1 1 0 0 +EDGE2 931 930 -0.957474 -0.0518303 -1.52972 1 0 1 1 0 0 +EDGE2 931 670 -0.930989 -0.0358368 1.57122 1 0 1 1 0 0 +EDGE2 932 931 -1.07094 -0.096542 0.0180498 1 0 1 1 0 0 +EDGE2 933 932 -1.00023 0.0458422 0.0322128 1 0 1 1 0 0 +EDGE2 934 933 -1.01465 -0.0271594 -0.0221211 1 0 1 1 0 0 +EDGE2 935 934 -0.99067 -0.0363635 0.0227909 1 0 1 1 0 0 +EDGE2 936 935 -0.931038 -0.0578901 -1.56012 1 0 1 1 0 0 +EDGE2 937 936 -1.03561 -0.0550052 0.00237643 1 0 1 1 0 0 +EDGE2 938 937 -1.09719 -0.0251288 0.0145619 1 0 1 1 0 0 +EDGE2 939 938 -0.999348 0.0011848 -0.0021124 1 0 1 1 0 0 +EDGE2 940 939 -0.964326 -0.11414 -0.0378396 1 0 1 1 0 0 +EDGE2 941 940 -1.02444 0.046198 1.58532 1 0 1 1 0 0 +EDGE2 942 941 -0.948728 -0.0393091 -0.0013065 1 0 1 1 0 0 +EDGE2 943 942 -1.07315 0.0594671 -0.00509695 1 0 1 1 0 0 +EDGE2 944 943 -0.97263 0.0485469 0.00767309 1 0 1 1 0 0 +EDGE2 945 944 -1.04753 0.0353044 -0.0299609 1 0 1 1 0 0 +EDGE2 946 945 -1.10091 -0.0381692 1.53439 1 0 1 1 0 0 +EDGE2 947 946 -0.934713 0.0587927 0.0280197 1 0 1 1 0 0 +EDGE2 948 947 -0.919381 0.0254598 -0.00901029 1 0 1 1 0 0 +EDGE2 949 948 -1.04227 0.0392386 0.0338427 1 0 1 1 0 0 +EDGE2 950 949 -0.96768 -0.022937 -0.000672899 1 0 1 1 0 0 +EDGE2 951 950 -1.03701 0.0903099 1.56411 1 0 1 1 0 0 +EDGE2 952 951 -1.11222 0.0983579 0.00640553 1 0 1 1 0 0 +EDGE2 953 952 -1.04335 -0.0664931 0.0112784 1 0 1 1 0 0 +EDGE2 954 953 -1.08869 -0.0462722 0.00295753 1 0 1 1 0 0 +EDGE2 954 935 1.0239 -0.0503345 -3.13246 1 0 1 1 0 0 +EDGE2 955 936 -0.050187 -1.01743 -1.55969 1 0 1 1 0 0 +EDGE2 955 934 0.968946 -0.0536194 -3.15437 1 0 1 1 0 0 +EDGE2 955 954 -1.05907 -0.0270214 -0.0257329 1 0 1 1 0 0 +EDGE2 955 935 0.0407667 -0.0195033 -3.14092 1 0 1 1 0 0 +EDGE2 956 955 -0.907421 -0.104439 -1.57324 1 0 1 1 0 0 +EDGE2 956 935 -0.947242 -0.0512266 1.58504 1 0 1 1 0 0 +EDGE2 957 956 -0.969087 0.0210552 -0.000914483 1 0 1 1 0 0 +EDGE2 958 957 -1.03617 0.0682115 -0.0165694 1 0 1 1 0 0 +EDGE2 959 958 -0.944913 0.0195752 0.0107571 1 0 1 1 0 0 +EDGE2 960 959 -1.00173 0.065316 0.0159579 1 0 1 1 0 0 +EDGE2 961 960 -1.06426 0.0758305 -1.54208 1 0 1 1 0 0 +EDGE2 962 961 -0.91583 0.0500287 -0.0350901 1 0 1 1 0 0 +EDGE2 963 962 -1.03856 -0.00408722 -0.00584628 1 0 1 1 0 0 +EDGE2 964 963 -1.08673 0.00439003 0.00422153 1 0 1 1 0 0 +EDGE2 965 964 -1.08361 -0.021102 -0.00328771 1 0 1 1 0 0 +EDGE2 966 965 -0.938589 -0.0395725 -1.60471 1 0 1 1 0 0 +EDGE2 967 966 -1.01188 -0.0488286 0.00215492 1 0 1 1 0 0 +EDGE2 968 967 -1.01251 -0.0753209 -0.0208824 1 0 1 1 0 0 +EDGE2 969 968 -1.02523 -0.0139428 0.0266718 1 0 1 1 0 0 +EDGE2 969 950 0.967665 0.012244 -3.16639 1 0 1 1 0 0 +EDGE2 970 969 -0.982381 0.0256053 -0.00260956 1 0 1 1 0 0 +EDGE2 970 950 0.0305291 -0.0319476 -3.18002 1 0 1 1 0 0 +EDGE2 970 951 0.026685 1.0307 1.56366 1 0 1 1 0 0 +EDGE2 970 949 0.998108 -0.0564999 -3.17054 1 0 1 1 0 0 +EDGE2 971 952 1.00822 -0.0239069 -0.0866108 1 0 1 1 0 0 +EDGE2 971 950 -0.935928 0.0484774 1.5753 1 0 1 1 0 0 +EDGE2 971 951 -0.00263458 0.0429201 0.023518 1 0 1 1 0 0 +EDGE2 971 970 -0.851968 -0.039497 -1.57073 1 0 1 1 0 0 +EDGE2 972 953 1.03613 -0.0112196 -0.00735768 1 0 1 1 0 0 +EDGE2 972 952 0.018121 0.0744458 0.0491468 1 0 1 1 0 0 +EDGE2 972 951 -0.979864 -0.0124253 0.00152907 1 0 1 1 0 0 +EDGE2 972 971 -1.01026 0.0130869 -0.0219865 1 0 1 1 0 0 +EDGE2 973 953 0.0087829 -0.047995 -0.0172233 1 0 1 1 0 0 +EDGE2 973 954 0.946956 0.0204926 8.57879e-05 1 0 1 1 0 0 +EDGE2 973 952 -0.968943 0.0661456 0.0106625 1 0 1 1 0 0 +EDGE2 973 972 -0.989193 -0.0372875 0.00929928 1 0 1 1 0 0 +EDGE2 974 955 0.952564 0.132046 -0.0102648 1 0 1 1 0 0 +EDGE2 974 953 -0.944035 0.0022862 0.00422868 1 0 1 1 0 0 +EDGE2 974 954 0.117818 -0.0372904 0.0169735 1 0 1 1 0 0 +EDGE2 974 935 1.03544 -0.0920407 -3.1608 1 0 1 1 0 0 +EDGE2 974 973 -1.00245 0.0476167 0.011707 1 0 1 1 0 0 +EDGE2 975 956 -0.0268342 0.966534 1.55088 1 0 1 1 0 0 +EDGE2 975 936 -0.0376432 -1.08256 -1.5741 1 0 1 1 0 0 +EDGE2 975 955 -0.0483092 0.000982282 -0.013849 1 0 1 1 0 0 +EDGE2 975 934 0.975119 -0.0357594 -3.14398 1 0 1 1 0 0 +EDGE2 975 954 -0.909023 -0.0159799 -0.00379655 1 0 1 1 0 0 +EDGE2 975 974 -1.02286 -0.0875301 -0.00914051 1 0 1 1 0 0 +EDGE2 975 935 0.0335795 -0.0230505 -3.14579 1 0 1 1 0 0 +EDGE2 976 936 0.032521 0.0253995 0.00765828 1 0 1 1 0 0 +EDGE2 976 955 -0.990765 0.0518272 1.58179 1 0 1 1 0 0 +EDGE2 976 975 -1.05891 -0.0542199 1.5402 1 0 1 1 0 0 +EDGE2 976 935 -1.08526 0.0552679 -1.56104 1 0 1 1 0 0 +EDGE2 976 937 1.03259 -0.0160948 -0.00806004 1 0 1 1 0 0 +EDGE2 977 936 -0.933965 0.00651289 0.0170676 1 0 1 1 0 0 +EDGE2 977 976 -1.07707 -0.0389604 -0.0204131 1 0 1 1 0 0 +EDGE2 977 938 0.990141 -0.0468987 -0.00383651 1 0 1 1 0 0 +EDGE2 977 937 -0.0548959 0.085561 0.000873219 1 0 1 1 0 0 +EDGE2 978 938 0.110564 0.0769748 0.0196664 1 0 1 1 0 0 +EDGE2 978 937 -1.00011 0.0107879 0.0264799 1 0 1 1 0 0 +EDGE2 978 977 -1.01612 -0.00383331 0.013402 1 0 1 1 0 0 +EDGE2 978 939 0.982209 0.028837 0.0142889 1 0 1 1 0 0 +EDGE2 979 938 -1.01973 -0.0117055 -0.00816315 1 0 1 1 0 0 +EDGE2 979 978 -0.956492 -0.117969 -0.028637 1 0 1 1 0 0 +EDGE2 979 939 -0.0186568 0.0033323 -0.0142241 1 0 1 1 0 0 +EDGE2 979 940 0.920205 -0.0388615 -0.0220165 1 0 1 1 0 0 +EDGE2 980 979 -0.981043 0.000899238 -0.00140754 1 0 1 1 0 0 +EDGE2 980 939 -0.969802 0.0032247 -0.00828181 1 0 1 1 0 0 +EDGE2 980 940 0.0175008 0.0959944 -0.0185673 1 0 1 1 0 0 +EDGE2 980 941 -0.0314804 -0.988605 -1.54567 1 0 1 1 0 0 +EDGE2 981 942 0.934908 0.0417524 -0.000655518 1 0 1 1 0 0 +EDGE2 981 980 -1.11387 0.0109565 1.59079 1 0 1 1 0 0 +EDGE2 981 940 -1.03359 -0.0264439 1.57078 1 0 1 1 0 0 +EDGE2 981 941 -0.0291666 -0.000384554 -0.0172331 1 0 1 1 0 0 +EDGE2 982 942 0.0162139 0.034592 -0.00619801 1 0 1 1 0 0 +EDGE2 982 941 -0.971779 0.0300779 0.0427992 1 0 1 1 0 0 +EDGE2 982 981 -1.03288 -0.0110317 0.00791639 1 0 1 1 0 0 +EDGE2 982 943 1.0397 -0.0145627 -0.0229614 1 0 1 1 0 0 +EDGE2 983 942 -1.02307 -0.0383581 0.0171098 1 0 1 1 0 0 +EDGE2 983 982 -1.05138 -0.0213517 -0.0193237 1 0 1 1 0 0 +EDGE2 983 943 0.151262 0.014014 0.0200592 1 0 1 1 0 0 +EDGE2 983 944 0.991156 0.0454297 0.0204632 1 0 1 1 0 0 +EDGE2 984 983 -1.07083 -0.0383071 -0.00896294 1 0 1 1 0 0 +EDGE2 984 943 -1.02238 -0.0280286 -0.0279471 1 0 1 1 0 0 +EDGE2 984 944 0.0381643 0.0835564 0.0189547 1 0 1 1 0 0 +EDGE2 984 945 0.926129 -0.0267968 0.0481569 1 0 1 1 0 0 +EDGE2 985 946 -0.0931568 -0.884885 -1.61889 1 0 1 1 0 0 +EDGE2 985 944 -0.975691 0.0179223 -0.026511 1 0 1 1 0 0 +EDGE2 985 984 -1.00177 0.0671173 0.00694588 1 0 1 1 0 0 +EDGE2 985 945 0.00872974 -0.0364739 -0.0119838 1 0 1 1 0 0 +EDGE2 986 945 -1.0223 0.0865732 -1.61067 1 0 1 1 0 0 +EDGE2 986 985 -1.09162 0.0188673 -1.55448 1 0 1 1 0 0 +EDGE2 987 986 -0.972263 -0.0293235 -0.0189127 1 0 1 1 0 0 +EDGE2 988 987 -1.02367 0.0994816 0.00133232 1 0 1 1 0 0 +EDGE2 989 988 -1.05113 0.0144571 0.0193891 1 0 1 1 0 0 +EDGE2 990 989 -1.05268 0.00950794 0.0323801 1 0 1 1 0 0 +EDGE2 991 990 -0.964307 -0.0845936 -1.5634 1 0 1 1 0 0 +EDGE2 992 991 -1.0419 0.00821899 -0.000360675 1 0 1 1 0 0 +EDGE2 993 992 -0.971907 0.0285206 -0.036179 1 0 1 1 0 0 +EDGE2 994 993 -1.05718 -0.00378994 -0.024076 1 0 1 1 0 0 +EDGE2 995 994 -0.969877 0.0820477 0.00486393 1 0 1 1 0 0 +EDGE2 996 995 -1.02268 -0.0101529 -1.55619 1 0 1 1 0 0 +EDGE2 997 996 -1.00723 -0.0557638 0.0399748 1 0 1 1 0 0 +EDGE2 998 997 -1.04229 0.0720804 -0.0388277 1 0 1 1 0 0 +EDGE2 999 980 0.993441 -0.0441473 -3.18735 1 0 1 1 0 0 +EDGE2 999 940 1.05311 0.0337276 -3.15086 1 0 1 1 0 0 +EDGE2 999 998 -0.99269 -0.0596223 -0.00419028 1 0 1 1 0 0 +EDGE2 1000 979 1.00546 -0.0307203 -3.15748 1 0 1 1 0 0 +EDGE2 1000 939 0.953905 0.0244746 -3.14726 1 0 1 1 0 0 +EDGE2 1000 980 -0.127526 0.0426767 -3.14022 1 0 1 1 0 0 +EDGE2 1000 940 -0.00207764 0.104509 -3.14454 1 0 1 1 0 0 +EDGE2 1000 941 0.0316453 0.988128 1.56619 1 0 1 1 0 0 +EDGE2 1000 981 -0.0342577 0.896526 1.5881 1 0 1 1 0 0 +EDGE2 1000 999 -0.964344 0.00199524 -0.0161703 1 0 1 1 0 0 +EDGE2 1001 942 1.07597 -0.0567102 0.0115588 1 0 1 1 0 0 +EDGE2 1001 980 -1.12278 0.0231203 1.56771 1 0 1 1 0 0 +EDGE2 1001 1000 -0.98345 0.0277882 -1.56029 1 0 1 1 0 0 +EDGE2 1001 940 -1.00745 -0.018321 1.57027 1 0 1 1 0 0 +EDGE2 1001 941 0.000207974 0.00980271 -0.0143632 1 0 1 1 0 0 +EDGE2 1001 981 -0.0589104 -0.0395849 0.0039964 1 0 1 1 0 0 +EDGE2 1001 982 1.05094 -0.0269482 -0.0321988 1 0 1 1 0 0 +EDGE2 1002 942 0.0743688 -0.0121334 0.0448948 1 0 1 1 0 0 +EDGE2 1002 1001 -1.02098 0.100738 0.0169181 1 0 1 1 0 0 +EDGE2 1002 941 -0.997028 0.0565863 -0.0198248 1 0 1 1 0 0 +EDGE2 1002 981 -0.999483 0.0194362 -0.0239212 1 0 1 1 0 0 +EDGE2 1002 982 -0.0937673 0.0081885 0.024172 1 0 1 1 0 0 +EDGE2 1002 983 0.991241 -0.0283247 -0.0227181 1 0 1 1 0 0 +EDGE2 1002 943 1.0419 -0.0217992 -0.0255545 1 0 1 1 0 0 +EDGE2 1003 942 -0.867884 -0.00944142 -0.0204113 1 0 1 1 0 0 +EDGE2 1003 982 -1.03183 -0.0227616 0.0406141 1 0 1 1 0 0 +EDGE2 1003 1002 -1.0124 -0.00953939 -0.0615147 1 0 1 1 0 0 +EDGE2 1003 983 0.00173833 0.115102 -0.0245993 1 0 1 1 0 0 +EDGE2 1003 943 0.0479079 0.0235266 0.00383131 1 0 1 1 0 0 +EDGE2 1003 944 1.09222 0.0537162 0.0308269 1 0 1 1 0 0 +EDGE2 1003 984 1.02109 -0.0337322 0.0205667 1 0 1 1 0 0 +EDGE2 1004 983 -1.04437 -0.0567163 0.0071636 1 0 1 1 0 0 +EDGE2 1004 1003 -1.01965 -0.0662665 0.0107955 1 0 1 1 0 0 +EDGE2 1004 943 -1.04046 -0.0506245 0.017791 1 0 1 1 0 0 +EDGE2 1004 944 0.00194488 0.0749197 -0.014285 1 0 1 1 0 0 +EDGE2 1004 984 -0.0631932 -0.0276023 0.00777034 1 0 1 1 0 0 +EDGE2 1004 945 0.979168 0.0659021 0.0225975 1 0 1 1 0 0 +EDGE2 1004 985 1.00616 0.0217371 0.0530872 1 0 1 1 0 0 +EDGE2 1005 946 0.00444184 -1.01267 -1.55435 1 0 1 1 0 0 +EDGE2 1005 1004 -1.05799 -0.00369371 -0.00812627 1 0 1 1 0 0 +EDGE2 1005 944 -1.0463 0.00566981 -0.0222132 1 0 1 1 0 0 +EDGE2 1005 984 -1.00531 -0.0400067 -0.0236004 1 0 1 1 0 0 +EDGE2 1005 945 0.0273047 -0.0283773 -0.0115514 1 0 1 1 0 0 +EDGE2 1005 985 -0.0237535 -0.0390678 0.0329638 1 0 1 1 0 0 +EDGE2 1005 986 -0.05714 1.002 1.56566 1 0 1 1 0 0 +EDGE2 1006 945 -0.958335 -0.0210759 -1.61919 1 0 1 1 0 0 +EDGE2 1006 985 -0.901543 -0.0807483 -1.53471 1 0 1 1 0 0 +EDGE2 1006 1005 -1.03614 0.0455943 -1.54528 1 0 1 1 0 0 +EDGE2 1006 987 0.928741 -0.0124934 -0.000524384 1 0 1 1 0 0 +EDGE2 1006 986 -0.0139076 -0.0471595 -0.0134555 1 0 1 1 0 0 +EDGE2 1007 987 -0.0410816 -0.018071 0.0184361 1 0 1 1 0 0 +EDGE2 1007 986 -1.11166 0.0453993 0.0171823 1 0 1 1 0 0 +EDGE2 1007 1006 -1.03748 0.0554618 -0.0259281 1 0 1 1 0 0 +EDGE2 1007 988 1.15704 -0.0422556 -0.00627648 1 0 1 1 0 0 +EDGE2 1008 987 -0.954198 0.0387609 0.00275646 1 0 1 1 0 0 +EDGE2 1008 1007 -1.01458 -0.0908723 -0.00135614 1 0 1 1 0 0 +EDGE2 1008 988 0.0088263 0.0209628 -0.0627932 1 0 1 1 0 0 +EDGE2 1008 989 0.983705 -0.00966779 0.015633 1 0 1 1 0 0 +EDGE2 1009 988 -1.00218 0.0987582 -0.0204007 1 0 1 1 0 0 +EDGE2 1009 1008 -0.95401 0.0702969 0.00221482 1 0 1 1 0 0 +EDGE2 1009 989 -0.0549976 0.0946067 0.0118182 1 0 1 1 0 0 +EDGE2 1009 990 0.96206 0.0176835 0.0307713 1 0 1 1 0 0 +EDGE2 1010 989 -0.967248 0.0147757 0.0558768 1 0 1 1 0 0 +EDGE2 1010 1009 -0.981797 -0.021677 -0.0100961 1 0 1 1 0 0 +EDGE2 1010 991 0.0503447 0.998717 1.54646 1 0 1 1 0 0 +EDGE2 1010 990 0.00620379 0.0342158 0.0112622 1 0 1 1 0 0 +EDGE2 1011 992 0.956753 -0.052996 0.0263961 1 0 1 1 0 0 +EDGE2 1011 1010 -1.03002 -0.0194549 -1.57013 1 0 1 1 0 0 +EDGE2 1011 991 -0.0237562 -0.0723335 0.0115736 1 0 1 1 0 0 +EDGE2 1011 990 -1.01024 0.0406171 -1.54897 1 0 1 1 0 0 +EDGE2 1012 992 0.0606279 -0.0334448 0.00145616 1 0 1 1 0 0 +EDGE2 1012 993 0.944039 -0.0548563 -0.0112319 1 0 1 1 0 0 +EDGE2 1012 1011 -1.00714 -0.0643748 0.00289751 1 0 1 1 0 0 +EDGE2 1012 991 -0.988932 0.0413032 -0.00550353 1 0 1 1 0 0 +EDGE2 1013 994 0.969603 -0.0241584 0.0121122 1 0 1 1 0 0 +EDGE2 1013 992 -1.00137 -0.0165484 -0.000532906 1 0 1 1 0 0 +EDGE2 1013 993 0.0896585 0.0182117 0.00961195 1 0 1 1 0 0 +EDGE2 1013 1012 -1.05013 0.0515895 -0.0370971 1 0 1 1 0 0 +EDGE2 1014 995 1.01792 0.0535566 0.00783332 1 0 1 1 0 0 +EDGE2 1014 994 0.0515918 -0.055467 0.00121684 1 0 1 1 0 0 +EDGE2 1014 993 -0.96317 -0.0286386 0.0202736 1 0 1 1 0 0 +EDGE2 1014 1013 -1.01254 -0.0352111 0.00673137 1 0 1 1 0 0 +EDGE2 1015 996 -0.102104 0.998448 1.59853 1 0 1 1 0 0 +EDGE2 1015 995 -0.0718542 0.00421794 -0.000452234 1 0 1 1 0 0 +EDGE2 1015 1014 -1.01881 0.0431626 -0.0174742 1 0 1 1 0 0 +EDGE2 1015 994 -1.08446 -0.0498336 -0.000414759 1 0 1 1 0 0 +EDGE2 1016 997 0.968964 0.0594152 -0.00495365 1 0 1 1 0 0 +EDGE2 1016 996 0.138879 0.0211307 -0.0165333 1 0 1 1 0 0 +EDGE2 1016 995 -1.0255 0.0428177 -1.60916 1 0 1 1 0 0 +EDGE2 1016 1015 -0.996191 0.00117435 -1.57026 1 0 1 1 0 0 +EDGE2 1017 998 0.987053 -0.0478456 0.0236419 1 0 1 1 0 0 +EDGE2 1017 997 -0.0243354 0.0240686 0.0212267 1 0 1 1 0 0 +EDGE2 1017 1016 -1.00421 -0.0285701 -0.014093 1 0 1 1 0 0 +EDGE2 1017 996 -1.07759 0.00799997 -0.0446859 1 0 1 1 0 0 +EDGE2 1018 999 0.897258 0.0390224 0.0183312 1 0 1 1 0 0 +EDGE2 1018 998 -0.00325317 -0.0109766 0.0175323 1 0 1 1 0 0 +EDGE2 1018 997 -0.990664 0.030368 -0.00936783 1 0 1 1 0 0 +EDGE2 1018 1017 -1.00653 0.0239907 -0.023513 1 0 1 1 0 0 +EDGE2 1019 980 1.04432 0.00465281 -3.1154 1 0 1 1 0 0 +EDGE2 1019 1000 1.10415 0.00893306 -0.0130339 1 0 1 1 0 0 +EDGE2 1019 940 1.05987 -0.0363674 -3.15681 1 0 1 1 0 0 +EDGE2 1019 999 -0.0832928 -0.00924794 -0.00910333 1 0 1 1 0 0 +EDGE2 1019 998 -1.03324 -0.0908629 -0.0173371 1 0 1 1 0 0 +EDGE2 1019 1018 -0.975619 0.0990846 0.0142333 1 0 1 1 0 0 +EDGE2 1020 979 0.923529 0.0631258 -3.14585 1 0 1 1 0 0 +EDGE2 1020 939 0.963204 0.14151 -3.12364 1 0 1 1 0 0 +EDGE2 1020 980 0.00705054 -0.0327451 -3.14963 1 0 1 1 0 0 +EDGE2 1020 1000 0.015652 -0.00846921 -0.00677122 1 0 1 1 0 0 +EDGE2 1020 1001 0.0376572 1.00118 1.57171 1 0 1 1 0 0 +EDGE2 1020 940 0.0594175 0.0448935 -3.1423 1 0 1 1 0 0 +EDGE2 1020 941 -0.0633775 0.897716 1.55944 1 0 1 1 0 0 +EDGE2 1020 981 -0.0569466 1.03009 1.54047 1 0 1 1 0 0 +EDGE2 1020 1019 -0.977585 -0.0567536 -0.00588804 1 0 1 1 0 0 +EDGE2 1020 999 -1.09565 0.00870477 -0.00408045 1 0 1 1 0 0 +EDGE2 1021 942 0.963432 0.082417 -0.00344811 1 0 1 1 0 0 +EDGE2 1021 980 -0.966646 0.00212081 1.57908 1 0 1 1 0 0 +EDGE2 1021 1020 -0.958088 0.0532486 -1.57931 1 0 1 1 0 0 +EDGE2 1021 1000 -1.02252 0.0114857 -1.56391 1 0 1 1 0 0 +EDGE2 1021 1001 -0.0381938 -0.0321693 -0.00290127 1 0 1 1 0 0 +EDGE2 1021 940 -0.979658 -0.00198417 1.57519 1 0 1 1 0 0 +EDGE2 1021 941 0.0526992 -0.102332 -0.0189765 1 0 1 1 0 0 +EDGE2 1021 981 0.0242129 -0.059495 0.0233055 1 0 1 1 0 0 +EDGE2 1021 982 1.00802 -0.0813568 0.0297476 1 0 1 1 0 0 +EDGE2 1021 1002 0.984 -0.149852 -0.01055 1 0 1 1 0 0 +EDGE2 1022 942 0.0187137 -0.0186309 -0.00636367 1 0 1 1 0 0 +EDGE2 1022 1001 -1.02001 -0.039507 -0.0209421 1 0 1 1 0 0 +EDGE2 1022 1021 -0.982263 0.0100831 -0.0160671 1 0 1 1 0 0 +EDGE2 1022 941 -0.919193 0.0331998 -0.00934679 1 0 1 1 0 0 +EDGE2 1022 981 -0.979951 -0.031334 -0.0226215 1 0 1 1 0 0 +EDGE2 1022 982 -0.00348579 0.0478651 0.00341135 1 0 1 1 0 0 +EDGE2 1022 1002 -0.00939372 -0.0189508 0.0125183 1 0 1 1 0 0 +EDGE2 1022 983 1.00231 -0.0470554 -0.0255212 1 0 1 1 0 0 +EDGE2 1022 1003 0.965892 -0.042398 0.00346269 1 0 1 1 0 0 +EDGE2 1022 943 1.05865 -0.0967454 0.0129742 1 0 1 1 0 0 +EDGE2 1023 942 -1.00136 0.000481824 0.0129047 1 0 1 1 0 0 +EDGE2 1023 1022 -1.02802 0.0630178 0.0120674 1 0 1 1 0 0 +EDGE2 1023 982 -1.01553 0.0131369 -0.0165046 1 0 1 1 0 0 +EDGE2 1023 1002 -0.998023 0.0931728 0.0163591 1 0 1 1 0 0 +EDGE2 1023 1004 1.02969 0.0763272 -0.0209236 1 0 1 1 0 0 +EDGE2 1023 983 -0.0106603 -0.0073841 -0.00100982 1 0 1 1 0 0 +EDGE2 1023 1003 -0.0708034 0.095609 -0.0011059 1 0 1 1 0 0 +EDGE2 1023 943 -0.0810058 0.0587046 0.0057128 1 0 1 1 0 0 +EDGE2 1023 944 0.960824 -0.0682975 0.0166714 1 0 1 1 0 0 +EDGE2 1023 984 1.02706 -0.0207805 0.0179998 1 0 1 1 0 0 +EDGE2 1024 1004 0.00266369 -0.00488877 0.0253356 1 0 1 1 0 0 +EDGE2 1024 983 -1.02163 0.0102825 0.00992696 1 0 1 1 0 0 +EDGE2 1024 1023 -1.02809 0.0823306 -0.0378968 1 0 1 1 0 0 +EDGE2 1024 1003 -1.01682 -0.0222069 -0.0227514 1 0 1 1 0 0 +EDGE2 1024 943 -0.95165 0.0210903 -0.000845787 1 0 1 1 0 0 +EDGE2 1024 944 0.0763698 -0.0550741 0.0131411 1 0 1 1 0 0 +EDGE2 1024 984 0.0410714 0.0832388 -0.0173444 1 0 1 1 0 0 +EDGE2 1024 945 1.06069 -0.0220994 0.0116283 1 0 1 1 0 0 +EDGE2 1024 985 1.05993 0.0768538 -0.0142811 1 0 1 1 0 0 +EDGE2 1024 1005 1.05615 0.0443954 0.00968481 1 0 1 1 0 0 +EDGE2 1025 946 -0.0317051 -0.969414 -1.56773 1 0 1 1 0 0 +EDGE2 1025 1004 -0.971113 -0.0202332 0.0282868 1 0 1 1 0 0 +EDGE2 1025 1024 -1.03622 -0.0277218 -0.00380654 1 0 1 1 0 0 +EDGE2 1025 944 -1.05196 0.0344575 0.0325925 1 0 1 1 0 0 +EDGE2 1025 984 -0.985642 -0.0728193 -0.00259936 1 0 1 1 0 0 +EDGE2 1025 945 -0.0284427 0.00720386 0.0386575 1 0 1 1 0 0 +EDGE2 1025 985 0.0443087 0.000627705 0.0308173 1 0 1 1 0 0 +EDGE2 1025 1005 7.81953e-05 -0.0987247 -0.000201891 1 0 1 1 0 0 +EDGE2 1025 986 0.0271954 1.0017 1.57177 1 0 1 1 0 0 +EDGE2 1025 1006 -0.0463767 1.02288 1.60586 1 0 1 1 0 0 +EDGE2 1026 1025 -0.99945 0.0783502 -1.58232 1 0 1 1 0 0 +EDGE2 1026 945 -0.870795 -0.0686006 -1.57611 1 0 1 1 0 0 +EDGE2 1026 985 -0.981647 0.0843805 -1.58261 1 0 1 1 0 0 +EDGE2 1026 1005 -1.02235 0.0079509 -1.57221 1 0 1 1 0 0 +EDGE2 1026 987 1.06377 0.0643344 -0.0135968 1 0 1 1 0 0 +EDGE2 1026 986 0.0909136 0.00779592 -0.00860451 1 0 1 1 0 0 +EDGE2 1026 1006 0.0135915 -0.101508 0.0288164 1 0 1 1 0 0 +EDGE2 1026 1007 0.822912 0.0399959 -0.0172445 1 0 1 1 0 0 +EDGE2 1027 987 0.0301297 -0.0111361 -0.0334167 1 0 1 1 0 0 +EDGE2 1027 986 -0.976411 0.0199427 -0.0108125 1 0 1 1 0 0 +EDGE2 1027 1026 -0.936102 0.064112 -0.0147667 1 0 1 1 0 0 +EDGE2 1027 1006 -0.979875 0.0308329 -0.0198501 1 0 1 1 0 0 +EDGE2 1027 1007 -0.0263805 -0.0871881 0.00324842 1 0 1 1 0 0 +EDGE2 1027 988 0.97274 -0.0273723 -0.0301622 1 0 1 1 0 0 +EDGE2 1027 1008 1.08481 0.0319818 0.0128257 1 0 1 1 0 0 +EDGE2 1028 987 -0.993961 0.0203007 -0.0138591 1 0 1 1 0 0 +EDGE2 1028 1027 -0.935439 0.0194175 -0.0171018 1 0 1 1 0 0 +EDGE2 1028 1007 -1.00828 -0.0364726 0.0147682 1 0 1 1 0 0 +EDGE2 1028 988 0.026815 0.0498539 -0.0327486 1 0 1 1 0 0 +EDGE2 1028 1008 0.0642084 0.0635178 -0.0124198 1 0 1 1 0 0 +EDGE2 1028 989 0.987402 0.0562934 0.00670304 1 0 1 1 0 0 +EDGE2 1028 1009 1.06634 -0.00648252 -0.00848386 1 0 1 1 0 0 +EDGE2 1029 1028 -1.00992 -0.0160123 -0.0163771 1 0 1 1 0 0 +EDGE2 1029 988 -1.13214 0.0259112 -0.0148223 1 0 1 1 0 0 +EDGE2 1029 1008 -0.978058 -0.00593397 -0.0157687 1 0 1 1 0 0 +EDGE2 1029 989 -0.0256917 0.0700019 -0.00854434 1 0 1 1 0 0 +EDGE2 1029 1009 -0.0708843 0.0442537 0.0041158 1 0 1 1 0 0 +EDGE2 1029 1010 1.01174 0.0127568 -7.41563e-06 1 0 1 1 0 0 +EDGE2 1029 990 0.878244 -0.0183636 0.0175704 1 0 1 1 0 0 +EDGE2 1030 989 -0.967993 0.0327147 0.012276 1 0 1 1 0 0 +EDGE2 1030 1009 -0.937489 0.0736679 -0.0119411 1 0 1 1 0 0 +EDGE2 1030 1029 -1.04225 -0.0463066 -0.00178594 1 0 1 1 0 0 +EDGE2 1030 1010 0.0130686 0.00178729 0.0166506 1 0 1 1 0 0 +EDGE2 1030 1011 0.0243782 1.07164 1.57998 1 0 1 1 0 0 +EDGE2 1030 991 -0.00992736 1.04818 1.54164 1 0 1 1 0 0 +EDGE2 1030 990 -0.0728752 0.00414887 0.0239975 1 0 1 1 0 0 +EDGE2 1031 1010 -1.01674 -0.0402785 1.59342 1 0 1 1 0 0 +EDGE2 1031 1030 -1.0244 0.0493419 1.55017 1 0 1 1 0 0 +EDGE2 1031 990 -0.980553 -0.0237493 1.58892 1 0 1 1 0 0 +EDGE2 1032 1031 -1.00558 0.0447635 0.0138061 1 0 1 1 0 0 +EDGE2 1033 1032 -1.05335 0.0410064 0.01459 1 0 1 1 0 0 +EDGE2 1034 1033 -1.05513 0.0839897 0.0199007 1 0 1 1 0 0 +EDGE2 1035 1034 -0.947056 -0.0121421 0.026075 1 0 1 1 0 0 +EDGE2 1036 1035 -0.96334 0.0727271 -1.57394 1 0 1 1 0 0 +EDGE2 1037 1036 -0.943764 0.00138846 -0.00355015 1 0 1 1 0 0 +EDGE2 1038 1037 -1.04431 -0.00859947 -0.000520739 1 0 1 1 0 0 +EDGE2 1039 1038 -1.09333 0.0807222 -0.015424 1 0 1 1 0 0 +EDGE2 1040 1039 -0.986166 0.0360471 -0.0504076 1 0 1 1 0 0 +EDGE2 1041 1040 -1.00307 0.0484578 -1.56145 1 0 1 1 0 0 +EDGE2 1042 1041 -0.970566 0.0603995 0.0261469 1 0 1 1 0 0 +EDGE2 1043 1042 -0.965206 0.118057 0.00118929 1 0 1 1 0 0 +EDGE2 1044 1043 -0.981476 -0.0420124 0.0158303 1 0 1 1 0 0 +EDGE2 1045 1044 -1.00853 0.0148847 -0.0325634 1 0 1 1 0 0 +EDGE2 1046 1045 -0.921575 -0.102358 -1.59264 1 0 1 1 0 0 +EDGE2 1047 1046 -0.996778 -0.0172957 -0.00887872 1 0 1 1 0 0 +EDGE2 1048 1047 -1.06039 -0.0386055 0.0237857 1 0 1 1 0 0 +EDGE2 1049 1010 1.05581 0.0245894 -3.16306 1 0 1 1 0 0 +EDGE2 1049 1030 1.04055 0.00585336 -3.14849 1 0 1 1 0 0 +EDGE2 1049 990 1.0511 0.0498739 -3.1451 1 0 1 1 0 0 +EDGE2 1049 1048 -0.960037 -0.0179185 -0.00402692 1 0 1 1 0 0 +EDGE2 1050 989 0.952893 -0.0139339 -3.12575 1 0 1 1 0 0 +EDGE2 1050 1009 1.05125 -0.0360159 -3.08876 1 0 1 1 0 0 +EDGE2 1050 1029 0.914694 0.0712105 -3.1369 1 0 1 1 0 0 +EDGE2 1050 1010 0.0589132 0.0315604 -3.14193 1 0 1 1 0 0 +EDGE2 1050 1011 -0.0751629 -1.01013 -1.56596 1 0 1 1 0 0 +EDGE2 1050 991 -0.0577571 -0.984038 -1.55865 1 0 1 1 0 0 +EDGE2 1050 1030 0.0213334 0.0748341 -3.15553 1 0 1 1 0 0 +EDGE2 1050 1031 -0.0407718 1.03042 1.58536 1 0 1 1 0 0 +EDGE2 1050 990 0.0289468 -0.0664425 -3.14751 1 0 1 1 0 0 +EDGE2 1050 1049 -1.0071 0.0457972 0.00141871 1 0 1 1 0 0 +EDGE2 1051 992 0.931218 -0.0276294 0.0367234 1 0 1 1 0 0 +EDGE2 1051 1012 0.989006 -0.0242505 0.038484 1 0 1 1 0 0 +EDGE2 1051 1010 -1.04457 -0.0143469 -1.5773 1 0 1 1 0 0 +EDGE2 1051 1011 0.0147458 -0.0117398 0.0168582 1 0 1 1 0 0 +EDGE2 1051 991 0.0270961 -0.00154761 0.0069914 1 0 1 1 0 0 +EDGE2 1051 1050 -0.991023 -0.0242348 1.57992 1 0 1 1 0 0 +EDGE2 1051 1030 -0.994932 -0.0348607 -1.62516 1 0 1 1 0 0 +EDGE2 1051 990 -1.01227 0.0480276 -1.58302 1 0 1 1 0 0 +EDGE2 1052 992 -0.0325624 0.106584 -0.00641506 1 0 1 1 0 0 +EDGE2 1052 993 1.02662 0.0213131 -0.00883696 1 0 1 1 0 0 +EDGE2 1052 1013 0.996501 -0.0169042 0.0184249 1 0 1 1 0 0 +EDGE2 1052 1012 0.0157826 -0.121368 0.0110941 1 0 1 1 0 0 +EDGE2 1052 1011 -0.998868 -0.0141408 -0.00975918 1 0 1 1 0 0 +EDGE2 1052 1051 -0.955257 0.00366439 -0.0105638 1 0 1 1 0 0 +EDGE2 1052 991 -1.00275 0.0662239 0.0180915 1 0 1 1 0 0 +EDGE2 1053 1014 1.05688 0.0265671 -0.022724 1 0 1 1 0 0 +EDGE2 1053 994 1.046 -0.061232 -0.00332114 1 0 1 1 0 0 +EDGE2 1053 992 -0.998199 -0.0372258 0.0145398 1 0 1 1 0 0 +EDGE2 1053 993 -0.00615266 -0.0525688 -0.00518726 1 0 1 1 0 0 +EDGE2 1053 1013 -0.0679154 -0.0582047 -0.000563388 1 0 1 1 0 0 +EDGE2 1053 1052 -0.942377 0.0883199 -0.0170387 1 0 1 1 0 0 +EDGE2 1053 1012 -0.96206 0.0402721 -0.0127703 1 0 1 1 0 0 +EDGE2 1054 995 1.01276 0.0022468 0.00701521 1 0 1 1 0 0 +EDGE2 1054 1015 1.10554 0.0168843 -0.00107465 1 0 1 1 0 0 +EDGE2 1054 1014 -0.0138225 -0.0916124 0.0159678 1 0 1 1 0 0 +EDGE2 1054 994 -0.0582489 -0.00597715 -0.0247593 1 0 1 1 0 0 +EDGE2 1054 993 -1.00635 -0.0900722 0.0112426 1 0 1 1 0 0 +EDGE2 1054 1053 -0.919386 -0.00700205 -0.000385872 1 0 1 1 0 0 +EDGE2 1054 1013 -1.00519 0.0251149 -0.027932 1 0 1 1 0 0 +EDGE2 1055 1016 -0.028831 0.98498 1.56745 1 0 1 1 0 0 +EDGE2 1055 996 -0.0437478 0.973229 1.53004 1 0 1 1 0 0 +EDGE2 1055 995 -0.0129783 0.024684 -0.0215906 1 0 1 1 0 0 +EDGE2 1055 1015 0.126247 -0.0238476 0.00904253 1 0 1 1 0 0 +EDGE2 1055 1014 -0.978139 -0.0134194 0.0137069 1 0 1 1 0 0 +EDGE2 1055 1054 -0.995935 0.0181987 -0.0099862 1 0 1 1 0 0 +EDGE2 1055 994 -1.06594 0.00790993 0.00847648 1 0 1 1 0 0 +EDGE2 1056 997 0.931626 -0.0223277 0.0140797 1 0 1 1 0 0 +EDGE2 1056 1017 1.13628 -0.0638924 -0.0139652 1 0 1 1 0 0 +EDGE2 1056 1016 0.0408481 0.00462323 0.0274313 1 0 1 1 0 0 +EDGE2 1056 996 -0.0125919 -0.0297824 -0.0032825 1 0 1 1 0 0 +EDGE2 1056 995 -1.07542 -0.0593637 -1.61421 1 0 1 1 0 0 +EDGE2 1056 1015 -1.03028 -0.0272064 -1.58156 1 0 1 1 0 0 +EDGE2 1056 1055 -1.09141 0.0355252 -1.56007 1 0 1 1 0 0 +EDGE2 1057 998 1.02453 0.0732532 0.0059207 1 0 1 1 0 0 +EDGE2 1057 1018 1.01308 0.0510909 0.0101307 1 0 1 1 0 0 +EDGE2 1057 997 0.050836 0.0665394 -0.0117355 1 0 1 1 0 0 +EDGE2 1057 1017 -0.0166266 0.124174 -0.0148118 1 0 1 1 0 0 +EDGE2 1057 1016 -1.04381 -0.0773507 0.00577109 1 0 1 1 0 0 +EDGE2 1057 1056 -0.954194 -0.120995 -0.0273501 1 0 1 1 0 0 +EDGE2 1057 996 -0.967248 -0.0403861 -0.0094339 1 0 1 1 0 0 +EDGE2 1058 1019 1.04659 -0.0480755 -0.0177936 1 0 1 1 0 0 +EDGE2 1058 999 1.01227 0.000511504 -0.0260898 1 0 1 1 0 0 +EDGE2 1058 998 -0.0170363 0.0546673 -0.0124071 1 0 1 1 0 0 +EDGE2 1058 1018 -0.0535514 0.0478684 0.0137303 1 0 1 1 0 0 +EDGE2 1058 997 -0.850412 -0.0970359 -0.0436937 1 0 1 1 0 0 +EDGE2 1058 1057 -0.995044 -0.0403198 -0.0150928 1 0 1 1 0 0 +EDGE2 1058 1017 -0.979535 -0.0623762 -0.0140761 1 0 1 1 0 0 +EDGE2 1059 980 0.999945 0.00107163 -3.11585 1 0 1 1 0 0 +EDGE2 1059 1020 0.986329 -0.0237009 0.0026751 1 0 1 1 0 0 +EDGE2 1059 1000 1.02742 -0.014299 0.0368437 1 0 1 1 0 0 +EDGE2 1059 940 1.07479 0.00537245 -3.1452 1 0 1 1 0 0 +EDGE2 1059 1019 0.0294589 -0.000816517 -0.00209669 1 0 1 1 0 0 +EDGE2 1059 999 0.0398092 -0.0379324 0.0219234 1 0 1 1 0 0 +EDGE2 1059 998 -1.0451 0.0335285 -0.00491482 1 0 1 1 0 0 +EDGE2 1059 1018 -0.926181 0.0405656 0.0141637 1 0 1 1 0 0 +EDGE2 1059 1058 -0.960739 -0.016447 -0.00522564 1 0 1 1 0 0 +EDGE2 1060 979 1.03715 -0.0974519 -3.10537 1 0 1 1 0 0 +EDGE2 1060 939 1.05227 0.00578969 -3.11954 1 0 1 1 0 0 +EDGE2 1060 980 0.0321777 0.0475952 -3.17038 1 0 1 1 0 0 +EDGE2 1060 1020 0.0549921 0.0126464 -0.0232456 1 0 1 1 0 0 +EDGE2 1060 1000 -0.0555888 -0.0651641 0.000472558 1 0 1 1 0 0 +EDGE2 1060 1001 -0.041933 0.949036 1.592 1 0 1 1 0 0 +EDGE2 1060 940 0.0544187 0.0335306 -3.17925 1 0 1 1 0 0 +EDGE2 1060 1021 0.0355932 1.04802 1.56351 1 0 1 1 0 0 +EDGE2 1060 941 0.0308555 0.945238 1.55938 1 0 1 1 0 0 +EDGE2 1060 981 -0.0306901 0.95403 1.55954 1 0 1 1 0 0 +EDGE2 1060 1019 -0.959017 -0.0619414 0.0368373 1 0 1 1 0 0 +EDGE2 1060 1059 -1.00544 -0.0542943 -0.0192528 1 0 1 1 0 0 +EDGE2 1060 999 -0.985067 -0.00469769 -0.0175745 1 0 1 1 0 0 +EDGE2 1061 942 1.05931 0.0465422 0.0198675 1 0 1 1 0 0 +EDGE2 1061 1022 0.982409 -0.00126211 -0.0244773 1 0 1 1 0 0 +EDGE2 1061 980 -1.06224 0.0422935 1.52131 1 0 1 1 0 0 +EDGE2 1061 1020 -0.915619 -0.0406552 -1.5476 1 0 1 1 0 0 +EDGE2 1061 1060 -1.02603 -0.0519574 -1.56956 1 0 1 1 0 0 +EDGE2 1061 1000 -1.12533 -0.00497285 -1.58159 1 0 1 1 0 0 +EDGE2 1061 1001 0.0122199 0.0370432 0.0107592 1 0 1 1 0 0 +EDGE2 1061 940 -0.953543 0.0267307 1.55551 1 0 1 1 0 0 +EDGE2 1061 1021 -0.0660965 0.0210975 0.00908774 1 0 1 1 0 0 +EDGE2 1061 941 -0.00299844 0.0426951 0.0203029 1 0 1 1 0 0 +EDGE2 1061 981 -0.11837 0.0530549 -0.00444325 1 0 1 1 0 0 +EDGE2 1061 982 1.01493 0.0620364 0.0155927 1 0 1 1 0 0 +EDGE2 1061 1002 1.0572 0.0464287 0.0300072 1 0 1 1 0 0 +EDGE2 1062 942 0.0142086 0.0698627 0.0167046 1 0 1 1 0 0 +EDGE2 1062 1022 0.0281051 -0.0226547 -0.0284909 1 0 1 1 0 0 +EDGE2 1062 1001 -1.04197 0.0903647 -0.0627292 1 0 1 1 0 0 +EDGE2 1062 1061 -0.974417 0.0352929 0.0146066 1 0 1 1 0 0 +EDGE2 1062 1021 -0.983938 -0.0136018 -0.0451653 1 0 1 1 0 0 +EDGE2 1062 941 -0.981295 -0.0920884 0.0176425 1 0 1 1 0 0 +EDGE2 1062 981 -0.898286 -0.0480471 0.0105047 1 0 1 1 0 0 +EDGE2 1062 982 0.0744287 0.00408771 -0.0204356 1 0 1 1 0 0 +EDGE2 1062 1002 -0.0977625 -0.056056 0.00103255 1 0 1 1 0 0 +EDGE2 1062 983 0.988902 0.026583 0.000614258 1 0 1 1 0 0 +EDGE2 1062 1023 1.02445 0.0512015 -0.0228062 1 0 1 1 0 0 +EDGE2 1062 1003 0.932517 -0.0481134 0.0406478 1 0 1 1 0 0 +EDGE2 1062 943 0.969184 -0.0565945 0.0325942 1 0 1 1 0 0 +EDGE2 1063 942 -1.07769 0.0577802 0.00147318 1 0 1 1 0 0 +EDGE2 1063 1022 -1.02574 0.0164762 0.0265464 1 0 1 1 0 0 +EDGE2 1063 1062 -1.03494 0.0348922 -0.0358039 1 0 1 1 0 0 +EDGE2 1063 982 -0.948085 -0.0194664 -0.0136742 1 0 1 1 0 0 +EDGE2 1063 1002 -0.937098 0.0076519 -0.0155281 1 0 1 1 0 0 +EDGE2 1063 1004 0.930385 -0.0436074 -0.0144966 1 0 1 1 0 0 +EDGE2 1063 983 -0.0988181 -0.116508 -0.00241554 1 0 1 1 0 0 +EDGE2 1063 1023 0.0293286 -0.0401697 -0.00295472 1 0 1 1 0 0 +EDGE2 1063 1003 0.0286295 -0.026802 0.0120922 1 0 1 1 0 0 +EDGE2 1063 943 0.0487015 -0.0756494 0.0212512 1 0 1 1 0 0 +EDGE2 1063 1024 1.03735 -0.0840931 -0.000406475 1 0 1 1 0 0 +EDGE2 1063 944 0.977063 0.0218672 0.00246213 1 0 1 1 0 0 +EDGE2 1063 984 1.03885 -0.0552235 -0.0108615 1 0 1 1 0 0 +EDGE2 1064 1004 0.010377 0.00581721 -0.0108852 1 0 1 1 0 0 +EDGE2 1064 983 -1.02553 0.03442 -0.00798945 1 0 1 1 0 0 +EDGE2 1064 1023 -0.944734 0.0134972 0.0147927 1 0 1 1 0 0 +EDGE2 1064 1063 -1.07093 -0.0662578 -0.0129553 1 0 1 1 0 0 +EDGE2 1064 1003 -1.01758 -0.0162933 -0.0152383 1 0 1 1 0 0 +EDGE2 1064 943 -1.05854 -0.0610649 -0.00417071 1 0 1 1 0 0 +EDGE2 1064 1024 -0.0820726 0.0489591 -0.00412821 1 0 1 1 0 0 +EDGE2 1064 1025 0.963413 -0.0876176 0.0106264 1 0 1 1 0 0 +EDGE2 1064 944 -0.0160276 0.0280243 -0.000618529 1 0 1 1 0 0 +EDGE2 1064 984 -0.0309504 -0.0271456 -0.0299551 1 0 1 1 0 0 +EDGE2 1064 945 0.969048 -0.0776969 -0.020331 1 0 1 1 0 0 +EDGE2 1064 985 1.00399 -0.0766627 -0.00404938 1 0 1 1 0 0 +EDGE2 1064 1005 0.997376 -0.0120427 -0.0215007 1 0 1 1 0 0 +EDGE2 1065 946 -0.0776767 -0.985824 -1.53317 1 0 1 1 0 0 +EDGE2 1065 1004 -1.00753 0.00649623 -0.0128414 1 0 1 1 0 0 +EDGE2 1065 1064 -0.962069 0.0154567 -0.0165971 1 0 1 1 0 0 +EDGE2 1065 1024 -1.02829 -0.0433503 -0.0351855 1 0 1 1 0 0 +EDGE2 1065 1025 -0.0591486 0.0246372 0.010051 1 0 1 1 0 0 +EDGE2 1065 944 -0.958798 0.126478 0.0044691 1 0 1 1 0 0 +EDGE2 1065 984 -0.935308 -0.00860992 0.00600603 1 0 1 1 0 0 +EDGE2 1065 945 -0.0686543 -0.0239903 0.000105116 1 0 1 1 0 0 +EDGE2 1065 985 -0.0208583 -0.106547 0.00638786 1 0 1 1 0 0 +EDGE2 1065 1005 0.0595202 -0.000853624 0.0334572 1 0 1 1 0 0 +EDGE2 1065 986 -0.0885678 1.00426 1.56184 1 0 1 1 0 0 +EDGE2 1065 1026 0.0189754 1.08275 1.58343 1 0 1 1 0 0 +EDGE2 1065 1006 -0.0752023 0.937491 1.55935 1 0 1 1 0 0 +EDGE2 1066 1025 -1.01411 0.0893193 -1.53019 1 0 1 1 0 0 +EDGE2 1066 1065 -1.03369 0.00300743 -1.56226 1 0 1 1 0 0 +EDGE2 1066 945 -1.00223 0.0342196 -1.53324 1 0 1 1 0 0 +EDGE2 1066 985 -0.968583 -0.0221038 -1.57035 1 0 1 1 0 0 +EDGE2 1066 1005 -1.05174 -0.0414502 -1.55794 1 0 1 1 0 0 +EDGE2 1066 987 1.05731 0.0289389 -0.0454891 1 0 1 1 0 0 +EDGE2 1066 986 -0.0208231 0.0212768 0.0262145 1 0 1 1 0 0 +EDGE2 1066 1026 -0.0961368 -0.0171316 -0.00692551 1 0 1 1 0 0 +EDGE2 1066 1006 -0.0183553 -0.0297348 -0.00210775 1 0 1 1 0 0 +EDGE2 1066 1027 0.961031 -0.00433022 -0.00166999 1 0 1 1 0 0 +EDGE2 1066 1007 0.967146 0.00911287 -0.000590849 1 0 1 1 0 0 +EDGE2 1067 1028 1.00173 -0.0376519 0.00851124 1 0 1 1 0 0 +EDGE2 1067 987 0.0774535 0.00582349 0.0189478 1 0 1 1 0 0 +EDGE2 1067 986 -0.947196 -0.0478626 -0.0375648 1 0 1 1 0 0 +EDGE2 1067 1026 -0.992552 -0.0403379 -0.0223988 1 0 1 1 0 0 +EDGE2 1067 1066 -1.0007 0.00529877 -0.00461091 1 0 1 1 0 0 +EDGE2 1067 1006 -0.930863 -0.089873 -0.00918493 1 0 1 1 0 0 +EDGE2 1067 1027 -0.0100658 -0.0820327 0.00441176 1 0 1 1 0 0 +EDGE2 1067 1007 -0.105123 -0.010351 0.0114283 1 0 1 1 0 0 +EDGE2 1067 988 1.01787 0.0597328 0.0243515 1 0 1 1 0 0 +EDGE2 1067 1008 1.03173 0.0265831 0.00860431 1 0 1 1 0 0 +EDGE2 1068 1028 0.0624751 -0.0619691 -0.00418415 1 0 1 1 0 0 +EDGE2 1068 987 -1.02896 -0.0278188 0.00219228 1 0 1 1 0 0 +EDGE2 1068 1027 -1.00077 -0.00632839 0.00984175 1 0 1 1 0 0 +EDGE2 1068 1067 -0.949161 -0.059135 -0.0296668 1 0 1 1 0 0 +EDGE2 1068 1007 -1.01068 0.0113455 0.00948695 1 0 1 1 0 0 +EDGE2 1068 988 -0.0546044 -0.0270745 -0.0107443 1 0 1 1 0 0 +EDGE2 1068 1008 -0.0122852 0.0945689 -0.011486 1 0 1 1 0 0 +EDGE2 1068 989 1.02576 -0.000980161 0.00156206 1 0 1 1 0 0 +EDGE2 1068 1009 1.00727 -0.00580781 -0.0405884 1 0 1 1 0 0 +EDGE2 1068 1029 1.02135 -0.0450047 -0.0216466 1 0 1 1 0 0 +EDGE2 1069 1028 -0.987155 -0.0026152 -0.0199557 1 0 1 1 0 0 +EDGE2 1069 1068 -1.03919 -0.0487194 0.00701154 1 0 1 1 0 0 +EDGE2 1069 988 -1.09155 -0.0611221 0.0295885 1 0 1 1 0 0 +EDGE2 1069 1008 -0.986456 -0.0804835 -0.0261054 1 0 1 1 0 0 +EDGE2 1069 989 -0.115765 -0.033259 -0.0107029 1 0 1 1 0 0 +EDGE2 1069 1009 -0.059534 -0.0219465 -0.0258807 1 0 1 1 0 0 +EDGE2 1069 1029 0.0246743 0.0486575 -0.00267358 1 0 1 1 0 0 +EDGE2 1069 1010 0.977075 0.0266177 0.00925802 1 0 1 1 0 0 +EDGE2 1069 1050 1.03126 0.037131 -3.13473 1 0 1 1 0 0 +EDGE2 1069 1030 0.976609 0.00598033 0.0141115 1 0 1 1 0 0 +EDGE2 1069 990 0.97053 0.0284031 0.0241213 1 0 1 1 0 0 +EDGE2 1070 1069 -1.00374 0.130683 -0.0193324 1 0 1 1 0 0 +EDGE2 1070 989 -1.06632 0.034984 0.0143803 1 0 1 1 0 0 +EDGE2 1070 1009 -0.998827 -0.0279817 0.0046189 1 0 1 1 0 0 +EDGE2 1070 1029 -1.00699 -0.0246916 -0.00136701 1 0 1 1 0 0 +EDGE2 1070 1010 0.0202522 -0.00580549 0.00724647 1 0 1 1 0 0 +EDGE2 1070 1011 0.0695034 0.961314 1.54965 1 0 1 1 0 0 +EDGE2 1070 1051 -0.092872 0.958747 1.57056 1 0 1 1 0 0 +EDGE2 1070 991 -0.00318637 0.963838 1.56204 1 0 1 1 0 0 +EDGE2 1070 1050 -0.000392127 0.0320506 -3.12699 1 0 1 1 0 0 +EDGE2 1070 1030 0.0157867 0.0126187 0.0181152 1 0 1 1 0 0 +EDGE2 1070 1031 -0.0431499 -0.86673 -1.5574 1 0 1 1 0 0 +EDGE2 1070 990 0.0788171 -0.0378302 0.012775 1 0 1 1 0 0 +EDGE2 1070 1049 0.959155 -0.0193992 -3.14448 1 0 1 1 0 0 +EDGE2 1071 992 1.01101 -0.0134486 0.024731 1 0 1 1 0 0 +EDGE2 1071 1052 0.988089 -0.105815 -7.02791e-05 1 0 1 1 0 0 +EDGE2 1071 1012 0.92714 -0.0301622 -0.019532 1 0 1 1 0 0 +EDGE2 1071 1010 -0.989302 -0.12195 -1.54327 1 0 1 1 0 0 +EDGE2 1071 1011 -0.0843825 -0.0681112 0.00882589 1 0 1 1 0 0 +EDGE2 1071 1051 -0.0181575 0.0659377 0.00336544 1 0 1 1 0 0 +EDGE2 1071 991 0.00700843 0.0242473 -0.0402475 1 0 1 1 0 0 +EDGE2 1071 1050 -1.01677 -0.00764211 1.58143 1 0 1 1 0 0 +EDGE2 1071 1070 -0.983243 0.0490481 -1.57248 1 0 1 1 0 0 +EDGE2 1071 1030 -0.951597 -0.0649554 -1.55285 1 0 1 1 0 0 +EDGE2 1071 990 -0.940347 -0.0247192 -1.5508 1 0 1 1 0 0 +EDGE2 1072 992 -0.0384828 0.00750125 -0.00220428 1 0 1 1 0 0 +EDGE2 1072 993 1.03074 -0.135556 0.0128283 1 0 1 1 0 0 +EDGE2 1072 1053 0.994055 -0.0596873 -0.037039 1 0 1 1 0 0 +EDGE2 1072 1013 1.05599 -0.0749432 -0.00833985 1 0 1 1 0 0 +EDGE2 1072 1052 -0.0192932 -0.0433656 -0.0218323 1 0 1 1 0 0 +EDGE2 1072 1012 -0.0521044 0.00983492 0.0250003 1 0 1 1 0 0 +EDGE2 1072 1011 -0.99713 -0.0720318 -0.0308652 1 0 1 1 0 0 +EDGE2 1072 1051 -0.958734 -0.0451624 -0.0295889 1 0 1 1 0 0 +EDGE2 1072 1071 -1.01794 0.0459697 -0.0576234 1 0 1 1 0 0 +EDGE2 1072 991 -0.994815 0.0374461 -0.0260447 1 0 1 1 0 0 +EDGE2 1073 1014 0.902684 0.0159753 0.0188405 1 0 1 1 0 0 +EDGE2 1073 1054 0.946067 0.0319596 -0.0170226 1 0 1 1 0 0 +EDGE2 1073 994 1.01835 0.00847842 0.0417066 1 0 1 1 0 0 +EDGE2 1073 992 -0.939951 0.0112912 -0.0304571 1 0 1 1 0 0 +EDGE2 1073 993 0.0262498 -0.0263603 0.00824878 1 0 1 1 0 0 +EDGE2 1073 1053 -0.0810397 -0.0231415 -0.0377694 1 0 1 1 0 0 +EDGE2 1073 1013 0.0608257 -0.0299907 -0.0208805 1 0 1 1 0 0 +EDGE2 1073 1052 -1.03759 0.0103367 -0.0368066 1 0 1 1 0 0 +EDGE2 1073 1072 -0.992097 -0.0354054 0.00718856 1 0 1 1 0 0 +EDGE2 1073 1012 -1.01376 0.0672626 0.0269529 1 0 1 1 0 0 +EDGE2 1074 995 0.945023 -0.0397368 0.0284554 1 0 1 1 0 0 +EDGE2 1074 1015 0.982486 -0.0115206 -0.0307121 1 0 1 1 0 0 +EDGE2 1074 1055 0.961949 0.0342348 0.00344454 1 0 1 1 0 0 +EDGE2 1074 1014 0.0309822 0.0727599 -0.0209403 1 0 1 1 0 0 +EDGE2 1074 1054 0.148171 0.0229911 0.00606895 1 0 1 1 0 0 +EDGE2 1074 994 0.00702448 0.0436482 -0.0036852 1 0 1 1 0 0 +EDGE2 1074 993 -0.959972 0.0166627 -0.0116809 1 0 1 1 0 0 +EDGE2 1074 1053 -1.03054 -0.0555769 -0.0108636 1 0 1 1 0 0 +EDGE2 1074 1073 -0.920961 -0.0740239 0.000504567 1 0 1 1 0 0 +EDGE2 1074 1013 -0.968445 0.0101841 -0.0123218 1 0 1 1 0 0 +EDGE2 1075 1016 -0.00168789 1.01744 1.56124 1 0 1 1 0 0 +EDGE2 1075 1056 0.0475776 0.95985 1.56139 1 0 1 1 0 0 +EDGE2 1075 996 -0.0126655 0.857283 1.60892 1 0 1 1 0 0 +EDGE2 1075 1074 -0.986424 0.00725679 -0.0169577 1 0 1 1 0 0 +EDGE2 1075 995 0.107021 0.0583557 -0.00590859 1 0 1 1 0 0 +EDGE2 1075 1015 -0.0668398 -0.0403658 0.00114078 1 0 1 1 0 0 +EDGE2 1075 1055 0.010868 0.035844 0.0266746 1 0 1 1 0 0 +EDGE2 1075 1014 -1.02522 0.0158524 0.00597484 1 0 1 1 0 0 +EDGE2 1075 1054 -1.10132 0.0231667 0.0175332 1 0 1 1 0 0 +EDGE2 1075 994 -0.931152 0.0122868 0.0234074 1 0 1 1 0 0 +EDGE2 1076 1075 -1.00803 -0.0415834 1.58965 1 0 1 1 0 0 +EDGE2 1076 995 -0.969797 -0.0119702 1.55417 1 0 1 1 0 0 +EDGE2 1076 1015 -1.06066 -0.0173352 1.54049 1 0 1 1 0 0 +EDGE2 1076 1055 -1.04017 -0.0904978 1.60709 1 0 1 1 0 0 +EDGE2 1077 1076 -0.953819 -0.0469416 -0.0187363 1 0 1 1 0 0 +EDGE2 1078 1077 -1.00741 -0.0176012 -0.00939691 1 0 1 1 0 0 +EDGE2 1079 1078 -0.970195 0.0655073 -0.00972464 1 0 1 1 0 0 +EDGE2 1080 1079 -0.95435 -0.115668 0.00252989 1 0 1 1 0 0 +EDGE2 1081 1080 -1.00619 0.0802861 1.56939 1 0 1 1 0 0 +EDGE2 1082 1081 -0.991976 0.00579715 0.0144207 1 0 1 1 0 0 +EDGE2 1083 1082 -1.02915 0.0329474 0.021786 1 0 1 1 0 0 +EDGE2 1084 1083 -0.966243 0.00120752 0.00641523 1 0 1 1 0 0 +EDGE2 1084 1045 0.925997 0.00689346 -3.1576 1 0 1 1 0 0 +EDGE2 1085 1046 0.00757295 -1.08465 -1.55636 1 0 1 1 0 0 +EDGE2 1085 1084 -1.01483 -0.0268856 0.0062347 1 0 1 1 0 0 +EDGE2 1085 1045 -0.00146313 0.0442658 -3.16012 1 0 1 1 0 0 +EDGE2 1085 1044 0.958674 0.0153889 -3.1179 1 0 1 1 0 0 +EDGE2 1086 1045 -0.940156 0.0205519 1.56458 1 0 1 1 0 0 +EDGE2 1086 1085 -1.0009 -0.0227162 -1.60877 1 0 1 1 0 0 +EDGE2 1087 1086 -1.00951 0.0483465 0.0256346 1 0 1 1 0 0 +EDGE2 1088 1087 -0.90193 -0.00578616 -0.0288502 1 0 1 1 0 0 +EDGE2 1089 1088 -0.939811 -0.0128221 0.0235596 1 0 1 1 0 0 +EDGE2 1090 1089 -0.890474 -0.0401153 0.0212967 1 0 1 1 0 0 +EDGE2 1091 1090 -1.06638 -0.0649572 -1.54923 1 0 1 1 0 0 +EDGE2 1092 1091 -0.932372 -0.0543076 0.0145839 1 0 1 1 0 0 +EDGE2 1093 1092 -1.08019 0.0755822 -0.0150698 1 0 1 1 0 0 +EDGE2 1094 1093 -0.999189 0.0132399 -0.00329838 1 0 1 1 0 0 +EDGE2 1095 1094 -1.08372 0.0413435 -0.00791576 1 0 1 1 0 0 +EDGE2 1096 1095 -0.93381 -0.0412914 1.57155 1 0 1 1 0 0 +EDGE2 1097 1096 -0.99286 -0.0318585 0.0102865 1 0 1 1 0 0 +EDGE2 1098 1097 -0.996345 -0.0140266 0.00412922 1 0 1 1 0 0 +EDGE2 1099 1098 -0.977299 0.006911 0.000986264 1 0 1 1 0 0 +EDGE2 1100 1099 -1.09089 0.0650734 -0.0172227 1 0 1 1 0 0 +EDGE2 1101 1100 -0.962523 0.00753408 -1.52074 1 0 1 1 0 0 +EDGE2 1102 1101 -0.942763 -0.0555638 0.0157456 1 0 1 1 0 0 +EDGE2 1103 1102 -0.900352 -0.0163688 0.00843162 1 0 1 1 0 0 +EDGE2 1104 1103 -0.969199 0.0500178 0.00730102 1 0 1 1 0 0 +EDGE2 1105 1104 -1.03705 -0.0292763 -0.00959089 1 0 1 1 0 0 +EDGE2 1106 1105 -1.00182 0.0590847 -1.60646 1 0 1 1 0 0 +EDGE2 1107 1106 -1.04685 0.0368894 0.0165634 1 0 1 1 0 0 +EDGE2 1108 1107 -1.05095 0.0504131 -0.0204906 1 0 1 1 0 0 +EDGE2 1109 1108 -1.13039 -0.0312571 0.0293861 1 0 1 1 0 0 +EDGE2 1110 1109 -1.06438 -0.0689312 0.00499668 1 0 1 1 0 0 +EDGE2 1111 1110 -1.08188 0.0251012 -1.54218 1 0 1 1 0 0 +EDGE2 1112 1111 -1.00347 -0.0402016 -0.0173525 1 0 1 1 0 0 +EDGE2 1113 1112 -1.01692 -0.00174499 0.0448692 1 0 1 1 0 0 +EDGE2 1114 1113 -0.916426 -0.0770817 -0.00979002 1 0 1 1 0 0 +EDGE2 1114 1095 0.904907 0.0594226 -3.13393 1 0 1 1 0 0 +EDGE2 1115 1114 -1.01234 -0.0566104 -0.0309108 1 0 1 1 0 0 +EDGE2 1115 1095 0.0678551 -0.0146182 -3.15709 1 0 1 1 0 0 +EDGE2 1115 1094 1.05897 0.011605 -3.14302 1 0 1 1 0 0 +EDGE2 1115 1096 -0.0436361 0.960896 1.57953 1 0 1 1 0 0 +EDGE2 1116 1095 -0.938599 -0.0111146 1.59934 1 0 1 1 0 0 +EDGE2 1116 1115 -0.960169 0.0555473 -1.55733 1 0 1 1 0 0 +EDGE2 1116 1096 0.00537442 -0.0112035 0.0116015 1 0 1 1 0 0 +EDGE2 1116 1097 0.98613 -0.0542521 0.0156751 1 0 1 1 0 0 +EDGE2 1117 1116 -0.899864 -0.0289327 0.00198855 1 0 1 1 0 0 +EDGE2 1117 1096 -0.956105 -0.00509945 -0.00452015 1 0 1 1 0 0 +EDGE2 1117 1097 -0.0107355 0.0281841 0.000246855 1 0 1 1 0 0 +EDGE2 1117 1098 0.958747 -0.0840273 -0.00224167 1 0 1 1 0 0 +EDGE2 1118 1097 -0.959256 0.0485208 -0.0107393 1 0 1 1 0 0 +EDGE2 1118 1117 -0.981394 0.0233949 0.0234845 1 0 1 1 0 0 +EDGE2 1118 1098 0.0287857 0.0897 0.0376641 1 0 1 1 0 0 +EDGE2 1118 1099 0.895148 -0.0186909 -0.000892149 1 0 1 1 0 0 +EDGE2 1119 1118 -1.03106 0.0576954 0.00663081 1 0 1 1 0 0 +EDGE2 1119 1098 -1.02759 0.060341 0.0024341 1 0 1 1 0 0 +EDGE2 1119 1099 0.00570896 -0.00998899 -0.0317577 1 0 1 1 0 0 +EDGE2 1119 1100 1.06216 -0.0132563 0.038766 1 0 1 1 0 0 +EDGE2 1120 1099 -0.941444 -0.0663453 0.0219376 1 0 1 1 0 0 +EDGE2 1120 1119 -0.982529 0.041566 -0.00882843 1 0 1 1 0 0 +EDGE2 1120 1101 -0.00967019 1.03787 1.57966 1 0 1 1 0 0 +EDGE2 1120 1100 0.010995 0.0328634 -0.000733859 1 0 1 1 0 0 +EDGE2 1121 1102 1.04731 0.0139407 0.0028396 1 0 1 1 0 0 +EDGE2 1121 1101 0.0403751 0.0868196 0.0334372 1 0 1 1 0 0 +EDGE2 1121 1100 -0.968349 0.0376719 -1.58944 1 0 1 1 0 0 +EDGE2 1121 1120 -0.937387 0.0610169 -1.53881 1 0 1 1 0 0 +EDGE2 1122 1103 0.984597 -0.0141061 -0.0155566 1 0 1 1 0 0 +EDGE2 1122 1102 -0.0656816 -0.0391292 -0.0166919 1 0 1 1 0 0 +EDGE2 1122 1121 -0.94126 -0.0620068 0.0193185 1 0 1 1 0 0 +EDGE2 1122 1101 -1.0601 -0.0376588 -0.0141013 1 0 1 1 0 0 +EDGE2 1123 1104 1.04563 -0.040886 -0.000174131 1 0 1 1 0 0 +EDGE2 1123 1103 -0.0747477 -0.0734481 -0.00352109 1 0 1 1 0 0 +EDGE2 1123 1102 -1.04989 0.0583185 -0.00827815 1 0 1 1 0 0 +EDGE2 1123 1122 -0.933512 -0.0319038 -0.0125581 1 0 1 1 0 0 +EDGE2 1124 1123 -1.0277 0.0131069 -0.0282939 1 0 1 1 0 0 +EDGE2 1124 1105 1.00733 -0.0385507 0.0030704 1 0 1 1 0 0 +EDGE2 1124 1104 -0.0609983 -0.0543834 0.0156172 1 0 1 1 0 0 +EDGE2 1124 1103 -0.939783 -0.0381441 0.00549783 1 0 1 1 0 0 +EDGE2 1125 1106 0.0533246 0.949666 1.53388 1 0 1 1 0 0 +EDGE2 1125 1105 -0.000909019 0.020346 -0.0081364 1 0 1 1 0 0 +EDGE2 1125 1124 -1.01675 -0.0508575 -0.00752841 1 0 1 1 0 0 +EDGE2 1125 1104 -0.972817 -0.0465531 -0.00787353 1 0 1 1 0 0 +EDGE2 1126 1107 0.990879 0.0624939 0.0163638 1 0 1 1 0 0 +EDGE2 1126 1106 -0.0059113 -0.00590377 -0.022228 1 0 1 1 0 0 +EDGE2 1126 1105 -1.04759 -0.00277056 -1.57909 1 0 1 1 0 0 +EDGE2 1126 1125 -1.02548 0.0183902 -1.59843 1 0 1 1 0 0 +EDGE2 1127 1108 0.98522 0.0225679 0.0150926 1 0 1 1 0 0 +EDGE2 1127 1107 0.0297758 -0.0492515 -0.0247646 1 0 1 1 0 0 +EDGE2 1127 1126 -1.00823 0.139134 0.0148505 1 0 1 1 0 0 +EDGE2 1127 1106 -1.0692 -0.086646 0.0209877 1 0 1 1 0 0 +EDGE2 1128 1109 1.06805 -0.0282627 -0.0325225 1 0 1 1 0 0 +EDGE2 1128 1108 0.0544371 -0.0610827 0.0070346 1 0 1 1 0 0 +EDGE2 1128 1127 -0.92346 -0.0604935 -0.0138185 1 0 1 1 0 0 +EDGE2 1128 1107 -0.971294 0.0915143 0.013429 1 0 1 1 0 0 +EDGE2 1129 1110 1.03073 -0.0183164 -0.0192939 1 0 1 1 0 0 +EDGE2 1129 1109 -0.0159029 -0.0319165 0.00507987 1 0 1 1 0 0 +EDGE2 1129 1108 -1.00041 0.0563966 0.0355999 1 0 1 1 0 0 +EDGE2 1129 1128 -0.934468 -0.0163853 0.0344368 1 0 1 1 0 0 +EDGE2 1130 1110 0.114614 -0.00269332 0.0159919 1 0 1 1 0 0 +EDGE2 1130 1109 -1.04185 0.0202654 -0.0137773 1 0 1 1 0 0 +EDGE2 1130 1129 -0.978438 -0.044332 0.0050958 1 0 1 1 0 0 +EDGE2 1130 1111 0.0169614 1.02539 1.57949 1 0 1 1 0 0 +EDGE2 1131 1130 -0.967118 0.054647 -1.59435 1 0 1 1 0 0 +EDGE2 1131 1110 -0.96811 0.0116541 -1.59074 1 0 1 1 0 0 +EDGE2 1131 1111 -0.104431 0.0556877 0.00550616 1 0 1 1 0 0 +EDGE2 1131 1112 0.942067 0.0533407 -0.0039136 1 0 1 1 0 0 +EDGE2 1132 1111 -0.958164 0.0106155 -0.0224248 1 0 1 1 0 0 +EDGE2 1132 1131 -0.982379 0.0147166 -0.0135633 1 0 1 1 0 0 +EDGE2 1132 1112 0.042345 -0.00703821 -0.0533274 1 0 1 1 0 0 +EDGE2 1132 1113 1.06075 -0.0623827 -0.00515848 1 0 1 1 0 0 +EDGE2 1133 1112 -0.965263 -0.0373211 -0.015154 1 0 1 1 0 0 +EDGE2 1133 1132 -1.11163 -0.057891 -0.0075378 1 0 1 1 0 0 +EDGE2 1133 1113 0.0854185 -0.00834304 -0.00548103 1 0 1 1 0 0 +EDGE2 1133 1114 0.973353 -0.0280031 -0.00578557 1 0 1 1 0 0 +EDGE2 1134 1133 -1.0045 -0.0892585 -7.38604e-05 1 0 1 1 0 0 +EDGE2 1134 1113 -0.994537 0.0161688 0.0103343 1 0 1 1 0 0 +EDGE2 1134 1114 -0.0402821 -0.0262729 -0.00405525 1 0 1 1 0 0 +EDGE2 1134 1095 1.09525 0.00768595 -3.12552 1 0 1 1 0 0 +EDGE2 1134 1115 0.945602 0.0161562 -0.0655984 1 0 1 1 0 0 +EDGE2 1135 1134 -0.998892 0.00315411 0.0395276 1 0 1 1 0 0 +EDGE2 1135 1114 -0.997456 -0.0333468 -0.0450835 1 0 1 1 0 0 +EDGE2 1135 1095 0.0218115 -0.0729437 -3.15331 1 0 1 1 0 0 +EDGE2 1135 1115 -0.00535582 -0.0797579 -0.0376224 1 0 1 1 0 0 +EDGE2 1135 1094 0.985647 -0.0558872 -3.16933 1 0 1 1 0 0 +EDGE2 1135 1116 -0.0501301 0.971369 1.54113 1 0 1 1 0 0 +EDGE2 1135 1096 -0.04338 1.12124 1.56927 1 0 1 1 0 0 +EDGE2 1136 1095 -0.953979 0.0715125 1.58752 1 0 1 1 0 0 +EDGE2 1136 1115 -1.01397 -0.00467143 -1.58356 1 0 1 1 0 0 +EDGE2 1136 1135 -0.936159 -0.146096 -1.566 1 0 1 1 0 0 +EDGE2 1136 1116 0.0124607 0.0237998 -0.0071446 1 0 1 1 0 0 +EDGE2 1136 1096 0.0236016 -0.047047 0.0164513 1 0 1 1 0 0 +EDGE2 1136 1097 1.02805 -0.0575251 0.0235607 1 0 1 1 0 0 +EDGE2 1136 1117 1.09779 0.0376695 0.0109181 1 0 1 1 0 0 +EDGE2 1137 1118 1.06494 -0.014291 -0.0154031 1 0 1 1 0 0 +EDGE2 1137 1116 -1.0518 0.118192 0.0119549 1 0 1 1 0 0 +EDGE2 1137 1136 -0.975092 -0.0122212 -0.0105867 1 0 1 1 0 0 +EDGE2 1137 1096 -0.909883 -0.00169648 0.0172481 1 0 1 1 0 0 +EDGE2 1137 1097 0.0585994 0.0587597 -0.0297018 1 0 1 1 0 0 +EDGE2 1137 1117 0.0422932 -0.0452762 0.0069081 1 0 1 1 0 0 +EDGE2 1137 1098 1.07114 0.0727465 -0.000641124 1 0 1 1 0 0 +EDGE2 1138 1118 0.052475 0.0462268 -0.0219227 1 0 1 1 0 0 +EDGE2 1138 1097 -1.03404 0.0164157 -0.0284605 1 0 1 1 0 0 +EDGE2 1138 1137 -1.00867 -0.0391411 0.0109278 1 0 1 1 0 0 +EDGE2 1138 1117 -0.967355 0.0243253 -0.00379572 1 0 1 1 0 0 +EDGE2 1138 1098 0.0571055 0.0445796 0.0487149 1 0 1 1 0 0 +EDGE2 1138 1099 1.15181 -0.0162817 -0.00785981 1 0 1 1 0 0 +EDGE2 1138 1119 1.01084 -0.0244254 0.0293256 1 0 1 1 0 0 +EDGE2 1139 1118 -0.979962 -0.0596953 -0.00317481 1 0 1 1 0 0 +EDGE2 1139 1138 -1.0352 -0.0262567 0.00471076 1 0 1 1 0 0 +EDGE2 1139 1098 -1.1149 -0.0486301 0.00201304 1 0 1 1 0 0 +EDGE2 1139 1099 0.0423651 0.00389615 -0.0103157 1 0 1 1 0 0 +EDGE2 1139 1119 0.0267836 0.0514633 0.04317 1 0 1 1 0 0 +EDGE2 1139 1100 1.04958 -0.0300106 -0.0139576 1 0 1 1 0 0 +EDGE2 1139 1120 0.988692 0.098354 -0.00977337 1 0 1 1 0 0 +EDGE2 1140 1139 -0.995305 -0.0231821 -0.00527266 1 0 1 1 0 0 +EDGE2 1140 1099 -1.00226 -0.0927439 0.046111 1 0 1 1 0 0 +EDGE2 1140 1119 -0.95422 0.0621168 -0.014994 1 0 1 1 0 0 +EDGE2 1140 1121 -0.0558501 1.02332 1.59293 1 0 1 1 0 0 +EDGE2 1140 1101 -0.0180109 1.02577 1.5811 1 0 1 1 0 0 +EDGE2 1140 1100 -0.0164563 0.0403747 -0.0208042 1 0 1 1 0 0 +EDGE2 1140 1120 0.0443951 0.0592597 0.0307267 1 0 1 1 0 0 +EDGE2 1141 1102 0.961819 -0.0485854 -0.0411943 1 0 1 1 0 0 +EDGE2 1141 1122 1.04513 0.0312578 0.0201538 1 0 1 1 0 0 +EDGE2 1141 1121 -0.0658714 -0.0134749 0.0146594 1 0 1 1 0 0 +EDGE2 1141 1101 0.0798558 -0.0957195 -0.0320866 1 0 1 1 0 0 +EDGE2 1141 1100 -0.947437 -0.0358329 -1.62187 1 0 1 1 0 0 +EDGE2 1141 1140 -0.955745 0.0191591 -1.55392 1 0 1 1 0 0 +EDGE2 1141 1120 -0.92955 0.0192999 -1.55355 1 0 1 1 0 0 +EDGE2 1142 1123 1.02284 -0.0044966 -0.0460331 1 0 1 1 0 0 +EDGE2 1142 1103 0.97679 0.0789935 0.00634502 1 0 1 1 0 0 +EDGE2 1142 1102 0.0445142 -0.00295541 -0.0174022 1 0 1 1 0 0 +EDGE2 1142 1122 0.046706 -0.0471623 0.00777693 1 0 1 1 0 0 +EDGE2 1142 1121 -0.972523 0.0309401 -0.00242604 1 0 1 1 0 0 +EDGE2 1142 1141 -0.997398 0.0365095 -0.0117278 1 0 1 1 0 0 +EDGE2 1142 1101 -0.983383 0.118003 -0.00741169 1 0 1 1 0 0 +EDGE2 1143 1123 0.00748795 -0.046983 -0.0500494 1 0 1 1 0 0 +EDGE2 1143 1124 0.975119 0.0319138 0.0297646 1 0 1 1 0 0 +EDGE2 1143 1104 1.02282 -0.0320891 0.0160785 1 0 1 1 0 0 +EDGE2 1143 1103 0.00759767 -0.0275952 0.00981467 1 0 1 1 0 0 +EDGE2 1143 1102 -1.01927 0.00995095 0.00345524 1 0 1 1 0 0 +EDGE2 1143 1122 -0.994554 0.0468118 0.00716385 1 0 1 1 0 0 +EDGE2 1143 1142 -0.828525 -0.0382348 -0.0391907 1 0 1 1 0 0 +EDGE2 1144 1123 -1.02518 -0.0308602 -0.0343565 1 0 1 1 0 0 +EDGE2 1144 1105 0.945741 -0.0366624 0.00505111 1 0 1 1 0 0 +EDGE2 1144 1125 0.953029 -0.0326472 0.00117005 1 0 1 1 0 0 +EDGE2 1144 1124 -0.00988499 -0.116513 0.042657 1 0 1 1 0 0 +EDGE2 1144 1104 -0.0381126 -0.0107413 -0.0286765 1 0 1 1 0 0 +EDGE2 1144 1143 -0.982086 0.032428 -0.0145175 1 0 1 1 0 0 +EDGE2 1144 1103 -0.983652 0.0964151 0.000569466 1 0 1 1 0 0 +EDGE2 1145 1126 0.0334788 1.04603 1.58857 1 0 1 1 0 0 +EDGE2 1145 1106 -0.0826138 1.00375 1.57188 1 0 1 1 0 0 +EDGE2 1145 1105 -0.0365954 -0.0395735 4.387e-05 1 0 1 1 0 0 +EDGE2 1145 1125 -0.00421179 0.0697895 -0.000518276 1 0 1 1 0 0 +EDGE2 1145 1124 -0.968306 -0.0292691 -0.00508092 1 0 1 1 0 0 +EDGE2 1145 1144 -1.05295 -0.0253353 0.00473972 1 0 1 1 0 0 +EDGE2 1145 1104 -1.06469 -0.0438224 0.0164499 1 0 1 1 0 0 +EDGE2 1146 1127 0.974166 -0.00544734 0.00819975 1 0 1 1 0 0 +EDGE2 1146 1107 1.08282 0.00688928 -0.00561674 1 0 1 1 0 0 +EDGE2 1146 1126 -0.141504 -0.0418489 -0.0100605 1 0 1 1 0 0 +EDGE2 1146 1106 -0.0409138 -0.0560976 -0.0226649 1 0 1 1 0 0 +EDGE2 1146 1145 -0.911352 -0.09971 -1.58671 1 0 1 1 0 0 +EDGE2 1146 1105 -0.995959 0.0259286 -1.54314 1 0 1 1 0 0 +EDGE2 1146 1125 -0.962222 -0.0422354 -1.57573 1 0 1 1 0 0 +EDGE2 1147 1108 1.00333 0.00185959 0.00394245 1 0 1 1 0 0 +EDGE2 1147 1128 1.00331 -0.0167775 -0.0251704 1 0 1 1 0 0 +EDGE2 1147 1127 0.0285959 -0.0272884 -0.00528847 1 0 1 1 0 0 +EDGE2 1147 1107 -0.0194978 -0.0468263 0.0313715 1 0 1 1 0 0 +EDGE2 1147 1126 -1.03441 0.0312463 0.0170705 1 0 1 1 0 0 +EDGE2 1147 1146 -0.998958 -0.00167786 -0.0207311 1 0 1 1 0 0 +EDGE2 1147 1106 -1.0699 -0.0228176 -0.0138508 1 0 1 1 0 0 +EDGE2 1148 1109 1.03301 -0.00187769 0.02301 1 0 1 1 0 0 +EDGE2 1148 1129 0.901649 -0.0105334 -0.0251669 1 0 1 1 0 0 +EDGE2 1148 1108 -0.0555722 0.061161 0.00770113 1 0 1 1 0 0 +EDGE2 1148 1128 0.0784912 -0.0286635 0.00728633 1 0 1 1 0 0 +EDGE2 1148 1127 -1.02563 -0.00919771 0.00581445 1 0 1 1 0 0 +EDGE2 1148 1147 -0.935956 -0.0125124 0.0167638 1 0 1 1 0 0 +EDGE2 1148 1107 -0.988979 -0.0109133 0.0073717 1 0 1 1 0 0 +EDGE2 1149 1130 0.917824 -0.101376 0.00353755 1 0 1 1 0 0 +EDGE2 1149 1110 1.00166 0.0429431 -0.00694487 1 0 1 1 0 0 +EDGE2 1149 1109 -0.00117271 -0.000408451 -0.00453138 1 0 1 1 0 0 +EDGE2 1149 1129 0.0793386 -0.0316723 -0.0225647 1 0 1 1 0 0 +EDGE2 1149 1108 -0.985413 0.0342451 0.0351939 1 0 1 1 0 0 +EDGE2 1149 1128 -0.943183 0.0350964 -0.000225397 1 0 1 1 0 0 +EDGE2 1149 1148 -0.98653 0.0407083 -0.0153286 1 0 1 1 0 0 +EDGE2 1150 1130 -0.0260927 0.0878647 0.0109656 1 0 1 1 0 0 +EDGE2 1150 1110 0.0621785 -0.0589143 -0.0102605 1 0 1 1 0 0 +EDGE2 1150 1109 -1.03074 -0.0274325 0.00528673 1 0 1 1 0 0 +EDGE2 1150 1149 -1.03558 0.0180899 0.0241275 1 0 1 1 0 0 +EDGE2 1150 1129 -0.945725 -0.0547425 0.0134435 1 0 1 1 0 0 +EDGE2 1150 1111 0.0164758 1.05754 1.58216 1 0 1 1 0 0 +EDGE2 1150 1131 0.00149604 1.02204 1.56605 1 0 1 1 0 0 +EDGE2 1151 1130 -0.935446 -0.090309 1.543 1 0 1 1 0 0 +EDGE2 1151 1150 -1.08751 0.033144 1.56367 1 0 1 1 0 0 +EDGE2 1151 1110 -0.989272 0.0496541 1.56165 1 0 1 1 0 0 +EDGE2 1152 1151 -1.01847 -0.0362935 0.0226516 1 0 1 1 0 0 +EDGE2 1153 1152 -0.944532 0.138298 -0.00930584 1 0 1 1 0 0 +EDGE2 1154 1153 -0.885656 0.0618073 0.0141498 1 0 1 1 0 0 +EDGE2 1155 1154 -1.06447 -0.0301065 0.0260712 1 0 1 1 0 0 +EDGE2 1156 1155 -0.989886 -0.000214804 -1.55924 1 0 1 1 0 0 +EDGE2 1157 1156 -0.952207 0.00794755 -0.0151497 1 0 1 1 0 0 +EDGE2 1158 1157 -1.01724 -0.0452767 -0.0013415 1 0 1 1 0 0 +EDGE2 1159 900 1.01413 -0.0177949 -3.1286 1 0 1 1 0 0 +EDGE2 1159 840 0.986091 0.0260455 -3.16043 1 0 1 1 0 0 +EDGE2 1159 860 1.01127 0.0667956 -3.15888 1 0 1 1 0 0 +EDGE2 1159 1158 -0.997074 -0.00174962 0.00149081 1 0 1 1 0 0 +EDGE2 1160 839 0.973052 -0.0733101 -3.16261 1 0 1 1 0 0 +EDGE2 1160 899 0.93159 -0.0774525 -3.16865 1 0 1 1 0 0 +EDGE2 1160 859 0.920994 -0.0772195 -3.1515 1 0 1 1 0 0 +EDGE2 1160 841 -0.0324181 -0.961249 -1.55918 1 0 1 1 0 0 +EDGE2 1160 901 -0.00560131 -1.06051 -1.60354 1 0 1 1 0 0 +EDGE2 1160 861 -0.0312958 -0.995227 -1.57253 1 0 1 1 0 0 +EDGE2 1160 900 -0.0587365 0.0175844 -3.14348 1 0 1 1 0 0 +EDGE2 1160 840 -0.00897391 0.00332706 -3.11991 1 0 1 1 0 0 +EDGE2 1160 860 0.0167241 0.0547583 -3.13381 1 0 1 1 0 0 +EDGE2 1160 1159 -0.957164 0.00634945 -0.0438004 1 0 1 1 0 0 +EDGE2 1161 1160 -0.9034 0.136301 -1.56042 1 0 1 1 0 0 +EDGE2 1161 900 -0.950853 -0.0367001 1.54832 1 0 1 1 0 0 +EDGE2 1161 840 -0.966451 -0.0751241 1.56938 1 0 1 1 0 0 +EDGE2 1161 860 -0.98613 0.0273921 1.55659 1 0 1 1 0 0 +EDGE2 1162 1161 -1.02054 -0.0704776 0.0320188 1 0 1 1 0 0 +EDGE2 1163 1162 -1.05178 0.0418089 -0.00974198 1 0 1 1 0 0 +EDGE2 1164 1163 -1.03208 0.0349261 -0.0255557 1 0 1 1 0 0 +EDGE2 1165 1164 -0.983886 0.00220235 -0.00340825 1 0 1 1 0 0 +EDGE2 1166 1165 -1.04362 0.00884145 -1.56146 1 0 1 1 0 0 +EDGE2 1167 1166 -1.07066 -0.132083 -0.00552904 1 0 1 1 0 0 +EDGE2 1168 1167 -1.02015 -0.0304837 -0.0402924 1 0 1 1 0 0 +EDGE2 1169 1168 -1.02061 -0.078227 0.016502 1 0 1 1 0 0 +EDGE2 1169 1130 0.976149 -0.0561336 -3.1346 1 0 1 1 0 0 +EDGE2 1169 1150 1.00725 -0.00282408 -3.11643 1 0 1 1 0 0 +EDGE2 1169 1110 1.06385 0.104699 -3.129 1 0 1 1 0 0 +EDGE2 1170 1169 -1.01062 0.0381148 -0.0203573 1 0 1 1 0 0 +EDGE2 1170 1151 -0.0237317 1.03592 1.56764 1 0 1 1 0 0 +EDGE2 1170 1130 -0.0154803 0.00909483 -3.09945 1 0 1 1 0 0 +EDGE2 1170 1150 0.0277993 -0.0839234 -3.10681 1 0 1 1 0 0 +EDGE2 1170 1110 -0.00810487 -0.0307529 -3.16153 1 0 1 1 0 0 +EDGE2 1170 1109 0.939869 0.0807409 -3.14535 1 0 1 1 0 0 +EDGE2 1170 1149 0.947936 -0.0153382 -3.14829 1 0 1 1 0 0 +EDGE2 1170 1129 0.972968 -0.0378912 -3.12937 1 0 1 1 0 0 +EDGE2 1170 1111 -0.106065 -0.985363 -1.54482 1 0 1 1 0 0 +EDGE2 1170 1131 0.0867664 -0.956417 -1.56366 1 0 1 1 0 0 +EDGE2 1171 1152 0.9629 0.0298285 0.0513896 1 0 1 1 0 0 +EDGE2 1171 1151 -0.0414483 -0.00493765 0.0100949 1 0 1 1 0 0 +EDGE2 1171 1130 -0.937818 0.0113792 1.5828 1 0 1 1 0 0 +EDGE2 1171 1170 -1.05293 -0.050294 -1.60427 1 0 1 1 0 0 +EDGE2 1171 1150 -0.998687 -0.0131952 1.54897 1 0 1 1 0 0 +EDGE2 1171 1110 -1.05142 -0.0266488 1.58009 1 0 1 1 0 0 +EDGE2 1172 1153 1.0211 0.119291 0.0197522 1 0 1 1 0 0 +EDGE2 1172 1152 0.0598601 -0.0845316 0.0326005 1 0 1 1 0 0 +EDGE2 1172 1151 -1.0593 0.0317344 0.02046 1 0 1 1 0 0 +EDGE2 1172 1171 -1.05201 0.0847665 0.0259405 1 0 1 1 0 0 +EDGE2 1173 1154 0.954801 0.0449158 0.0158666 1 0 1 1 0 0 +EDGE2 1173 1153 0.00725146 0.0512952 0.0490788 1 0 1 1 0 0 +EDGE2 1173 1152 -0.893592 -0.0279991 0.00920244 1 0 1 1 0 0 +EDGE2 1173 1172 -1.0745 -0.0213327 -0.0360335 1 0 1 1 0 0 +EDGE2 1174 1173 -0.941029 0.00496247 -0.0445802 1 0 1 1 0 0 +EDGE2 1174 1155 1.03461 -0.00703766 -0.00553743 1 0 1 1 0 0 +EDGE2 1174 1154 0.047561 -0.0220463 0.0437265 1 0 1 1 0 0 +EDGE2 1174 1153 -0.981975 0.0288135 0.0181515 1 0 1 1 0 0 +EDGE2 1175 1156 0.0253885 1.00848 1.55247 1 0 1 1 0 0 +EDGE2 1175 1174 -1.06249 0.0309059 -0.0291859 1 0 1 1 0 0 +EDGE2 1175 1155 -0.0578378 0.0562336 -0.00754014 1 0 1 1 0 0 +EDGE2 1175 1154 -1.02248 0.0415008 -0.0172865 1 0 1 1 0 0 +EDGE2 1176 1157 0.983907 0.0194257 -0.012758 1 0 1 1 0 0 +EDGE2 1176 1156 0.0426759 -0.0494849 0.0248235 1 0 1 1 0 0 +EDGE2 1176 1175 -1.04867 0.00363956 -1.57506 1 0 1 1 0 0 +EDGE2 1176 1155 -1.06511 0.0198954 -1.53018 1 0 1 1 0 0 +EDGE2 1177 1158 1.0296 0.025894 0.0141262 1 0 1 1 0 0 +EDGE2 1177 1157 -0.028461 -0.0208609 0.00549574 1 0 1 1 0 0 +EDGE2 1177 1156 -0.913245 -0.0498746 0.00879702 1 0 1 1 0 0 +EDGE2 1177 1176 -1.00917 -0.0530424 -0.0144272 1 0 1 1 0 0 +EDGE2 1178 1159 1.10603 -0.0291 0.0187053 1 0 1 1 0 0 +EDGE2 1178 1158 0.026756 0.085763 -0.0295126 1 0 1 1 0 0 +EDGE2 1178 1177 -1.0676 0.0135854 -0.0178677 1 0 1 1 0 0 +EDGE2 1178 1157 -0.950283 0.0391696 -0.00280985 1 0 1 1 0 0 +EDGE2 1179 1160 0.966625 0.000734832 0.00478651 1 0 1 1 0 0 +EDGE2 1179 900 1.01962 -0.0485612 -3.1255 1 0 1 1 0 0 +EDGE2 1179 840 0.915552 -0.042012 -3.13125 1 0 1 1 0 0 +EDGE2 1179 860 0.99725 -0.0157316 -3.11923 1 0 1 1 0 0 +EDGE2 1179 1159 0.03008 0.0085912 -0.00554991 1 0 1 1 0 0 +EDGE2 1179 1178 -0.9353 0.00269256 0.0103557 1 0 1 1 0 0 +EDGE2 1179 1158 -1.00242 -0.038264 0.00127076 1 0 1 1 0 0 +EDGE2 1180 839 1.02596 -0.0218697 -3.13803 1 0 1 1 0 0 +EDGE2 1180 899 0.996102 -0.0551352 -3.14231 1 0 1 1 0 0 +EDGE2 1180 859 1.08836 -0.00318179 -3.12634 1 0 1 1 0 0 +EDGE2 1180 841 0.0216079 -0.913477 -1.54908 1 0 1 1 0 0 +EDGE2 1180 901 0.0107484 -0.966706 -1.56175 1 0 1 1 0 0 +EDGE2 1180 861 0.0311548 -0.984023 -1.55822 1 0 1 1 0 0 +EDGE2 1180 1160 -0.0126647 0.0024199 -0.0240405 1 0 1 1 0 0 +EDGE2 1180 900 0.0265312 -0.0563831 -3.16637 1 0 1 1 0 0 +EDGE2 1180 840 0.00861778 -0.0376559 -3.12108 1 0 1 1 0 0 +EDGE2 1180 860 0.0130697 -0.0962347 -3.13532 1 0 1 1 0 0 +EDGE2 1180 1161 0.0105248 1.05172 1.59752 1 0 1 1 0 0 +EDGE2 1180 1179 -1.01284 0.0538025 -0.0191527 1 0 1 1 0 0 +EDGE2 1180 1159 -0.959491 0.0596703 3.09844e-05 1 0 1 1 0 0 +EDGE2 1181 1160 -0.992061 -0.0548079 -1.5963 1 0 1 1 0 0 +EDGE2 1181 1180 -0.993269 0.0620203 -1.57942 1 0 1 1 0 0 +EDGE2 1181 900 -1.05407 -0.0289274 1.5577 1 0 1 1 0 0 +EDGE2 1181 840 -1.02324 0.0316341 1.54427 1 0 1 1 0 0 +EDGE2 1181 860 -1.02422 -0.0276308 1.60146 1 0 1 1 0 0 +EDGE2 1181 1161 -0.00990439 -0.0398719 -0.00996934 1 0 1 1 0 0 +EDGE2 1181 1162 1.01134 0.0335108 -0.0401446 1 0 1 1 0 0 +EDGE2 1182 1161 -0.935989 0.0357373 -0.029858 1 0 1 1 0 0 +EDGE2 1182 1181 -1.0337 -0.0575098 0.0266432 1 0 1 1 0 0 +EDGE2 1182 1162 -0.0565809 -0.0357298 -0.0409714 1 0 1 1 0 0 +EDGE2 1182 1163 1.0498 0.0809028 0.030922 1 0 1 1 0 0 +EDGE2 1183 1182 -0.988086 -0.0687255 -0.0209661 1 0 1 1 0 0 +EDGE2 1183 1162 -0.964942 -0.00085728 -0.0294386 1 0 1 1 0 0 +EDGE2 1183 1163 -0.0489278 -0.0508442 -0.017419 1 0 1 1 0 0 +EDGE2 1183 1164 0.947178 0.129591 -0.0307669 1 0 1 1 0 0 +EDGE2 1184 1163 -1.03525 -0.0510436 0.0119566 1 0 1 1 0 0 +EDGE2 1184 1183 -1.02579 -0.0378332 -0.0043413 1 0 1 1 0 0 +EDGE2 1184 1164 -0.0809172 0.12598 0.00257861 1 0 1 1 0 0 +EDGE2 1184 1165 1.00424 0.03471 -0.0281595 1 0 1 1 0 0 +EDGE2 1185 1184 -1.01964 0.0766591 -0.0050879 1 0 1 1 0 0 +EDGE2 1185 1164 -1.01683 0.0935253 -0.0323153 1 0 1 1 0 0 +EDGE2 1185 1165 0.0399324 -0.0638178 -0.00409528 1 0 1 1 0 0 +EDGE2 1185 1166 0.0267349 1.0037 1.55084 1 0 1 1 0 0 +EDGE2 1186 1185 -1.07325 0.0190383 -1.58055 1 0 1 1 0 0 +EDGE2 1186 1165 -0.897757 0.0139123 -1.54629 1 0 1 1 0 0 +EDGE2 1186 1166 0.0258285 -0.0167329 -0.000499041 1 0 1 1 0 0 +EDGE2 1186 1167 1.01235 0.054555 -0.00569283 1 0 1 1 0 0 +EDGE2 1187 1166 -0.983836 0.0406202 -0.000452344 1 0 1 1 0 0 +EDGE2 1187 1186 -0.976948 0.00826114 -0.016337 1 0 1 1 0 0 +EDGE2 1187 1167 0.0402373 0.00786856 0.00970219 1 0 1 1 0 0 +EDGE2 1187 1168 1.05703 0.0375864 0.00715448 1 0 1 1 0 0 +EDGE2 1188 1187 -1.08454 0.0197491 -0.0212402 1 0 1 1 0 0 +EDGE2 1188 1167 -1.01992 -0.0217607 -0.00337316 1 0 1 1 0 0 +EDGE2 1188 1168 0.0469766 -0.0311505 -0.00145998 1 0 1 1 0 0 +EDGE2 1188 1169 0.967318 0.0350832 -0.00892937 1 0 1 1 0 0 +EDGE2 1189 1188 -0.911109 -0.0527827 0.0137447 1 0 1 1 0 0 +EDGE2 1189 1168 -1.08612 -0.00707714 -0.0296185 1 0 1 1 0 0 +EDGE2 1189 1169 0.00498313 0.0316683 0.00129932 1 0 1 1 0 0 +EDGE2 1189 1130 0.940894 0.00345189 -3.11653 1 0 1 1 0 0 +EDGE2 1189 1170 1.0476 0.0736472 -0.0253732 1 0 1 1 0 0 +EDGE2 1189 1150 1.0483 -0.0136015 -3.16193 1 0 1 1 0 0 +EDGE2 1189 1110 1.0385 -0.00136009 -3.16746 1 0 1 1 0 0 +EDGE2 1190 1189 -1.03323 0.0547432 -0.0244021 1 0 1 1 0 0 +EDGE2 1190 1169 -1.00452 -0.0564465 0.00679477 1 0 1 1 0 0 +EDGE2 1190 1151 0.0604921 0.969632 1.59272 1 0 1 1 0 0 +EDGE2 1190 1171 0.0786549 1.05256 1.56644 1 0 1 1 0 0 +EDGE2 1190 1130 -0.0592529 0.00284728 -3.15801 1 0 1 1 0 0 +EDGE2 1190 1170 0.0723414 0.064608 0.00537523 1 0 1 1 0 0 +EDGE2 1190 1150 -0.0159348 0.00484851 -3.11839 1 0 1 1 0 0 +EDGE2 1190 1110 -0.0251869 0.0694775 -3.11774 1 0 1 1 0 0 +EDGE2 1190 1109 0.949958 0.088525 -3.1297 1 0 1 1 0 0 +EDGE2 1190 1149 1.00463 0.0647463 -3.16381 1 0 1 1 0 0 +EDGE2 1190 1129 0.95677 0.0573307 -3.13676 1 0 1 1 0 0 +EDGE2 1190 1111 0.0579658 -0.974121 -1.58141 1 0 1 1 0 0 +EDGE2 1190 1131 -0.013744 -0.959332 -1.57747 1 0 1 1 0 0 +EDGE2 1191 1152 0.988929 0.0971558 0.0167982 1 0 1 1 0 0 +EDGE2 1191 1172 0.932422 0.0635644 0.0130379 1 0 1 1 0 0 +EDGE2 1191 1151 0.0260974 0.0628829 -0.0141727 1 0 1 1 0 0 +EDGE2 1191 1171 -0.0088031 0.0729026 0.0109698 1 0 1 1 0 0 +EDGE2 1191 1130 -0.925192 0.033735 1.59697 1 0 1 1 0 0 +EDGE2 1191 1170 -0.946602 0.120641 -1.59062 1 0 1 1 0 0 +EDGE2 1191 1190 -0.979563 0.0344444 -1.57514 1 0 1 1 0 0 +EDGE2 1191 1150 -1.07797 0.0060621 1.5555 1 0 1 1 0 0 +EDGE2 1191 1110 -0.955038 0.0129174 1.57363 1 0 1 1 0 0 +EDGE2 1192 1173 0.872405 0.00799994 0.0227604 1 0 1 1 0 0 +EDGE2 1192 1153 0.97703 0.0497198 0.00388377 1 0 1 1 0 0 +EDGE2 1192 1152 -0.0349921 0.042559 -0.0170964 1 0 1 1 0 0 +EDGE2 1192 1172 -0.0525162 0.0168091 -0.0264719 1 0 1 1 0 0 +EDGE2 1192 1151 -1.01136 -0.00143342 -0.00358625 1 0 1 1 0 0 +EDGE2 1192 1191 -0.942077 0.0121125 0.000868138 1 0 1 1 0 0 +EDGE2 1192 1171 -1.01687 -0.0164469 0.01289 1 0 1 1 0 0 +EDGE2 1193 1173 -0.0581385 0.0214059 -0.0210999 1 0 1 1 0 0 +EDGE2 1193 1174 0.926347 -0.0192864 0.0259249 1 0 1 1 0 0 +EDGE2 1193 1154 0.930362 0.0520672 0.0152572 1 0 1 1 0 0 +EDGE2 1193 1153 -0.0283735 0.0114813 -0.00433252 1 0 1 1 0 0 +EDGE2 1193 1152 -0.937444 0.0239704 -0.0151644 1 0 1 1 0 0 +EDGE2 1193 1172 -0.96191 0.0705472 0.00319657 1 0 1 1 0 0 +EDGE2 1193 1192 -1.00802 -0.0578941 -0.0701231 1 0 1 1 0 0 +EDGE2 1194 1173 -1.00103 -0.0138098 -0.0284055 1 0 1 1 0 0 +EDGE2 1194 1174 0.00719316 0.0157824 0.0212927 1 0 1 1 0 0 +EDGE2 1194 1175 0.952063 0.0440049 0.0110513 1 0 1 1 0 0 +EDGE2 1194 1155 1.01557 0.02606 0.0502831 1 0 1 1 0 0 +EDGE2 1194 1154 0.0660777 0.0341599 -0.0194771 1 0 1 1 0 0 +EDGE2 1194 1193 -0.930811 -0.00630328 0.00775914 1 0 1 1 0 0 +EDGE2 1194 1153 -0.9115 -0.0123546 0.00301687 1 0 1 1 0 0 +EDGE2 1195 1156 -0.00985799 0.978909 1.57683 1 0 1 1 0 0 +EDGE2 1195 1176 -0.0519733 0.972911 1.58826 1 0 1 1 0 0 +EDGE2 1195 1174 -1.08033 0.0313249 0.00503886 1 0 1 1 0 0 +EDGE2 1195 1175 0.0392426 -0.0428098 -0.0195189 1 0 1 1 0 0 +EDGE2 1195 1155 -0.0275963 -0.100413 0.00315894 1 0 1 1 0 0 +EDGE2 1195 1194 -0.98689 0.0136092 -0.0341996 1 0 1 1 0 0 +EDGE2 1195 1154 -1.04105 0.0100976 -0.015566 1 0 1 1 0 0 +EDGE2 1196 1177 1.05317 0.00246495 -0.000820624 1 0 1 1 0 0 +EDGE2 1196 1157 1.03489 0.00544431 0.0178529 1 0 1 1 0 0 +EDGE2 1196 1156 -0.0260599 -0.045643 -0.0145567 1 0 1 1 0 0 +EDGE2 1196 1176 0.0127161 -0.00639225 -0.0110187 1 0 1 1 0 0 +EDGE2 1196 1175 -0.931389 -0.0739496 -1.55699 1 0 1 1 0 0 +EDGE2 1196 1195 -1.03536 -0.0653625 -1.52004 1 0 1 1 0 0 +EDGE2 1196 1155 -1.07635 -0.038679 -1.56401 1 0 1 1 0 0 +EDGE2 1197 1178 1.0154 0.0342623 -0.00446868 1 0 1 1 0 0 +EDGE2 1197 1158 0.932348 0.0416367 -0.0102302 1 0 1 1 0 0 +EDGE2 1197 1177 0.000369503 0.0329202 0.013355 1 0 1 1 0 0 +EDGE2 1197 1157 -0.00868907 -0.0577241 0.0130492 1 0 1 1 0 0 +EDGE2 1197 1196 -0.984239 -0.0822309 -0.000782977 1 0 1 1 0 0 +EDGE2 1197 1156 -0.964949 -0.0351826 0.0188813 1 0 1 1 0 0 +EDGE2 1197 1176 -0.979326 -0.0333592 0.00660933 1 0 1 1 0 0 +EDGE2 1198 1197 -0.981376 0.00817555 0.00431434 1 0 1 1 0 0 +EDGE2 1198 1179 0.956243 0.0120096 -0.0337386 1 0 1 1 0 0 +EDGE2 1198 1159 1.01579 -0.0278324 0.00793509 1 0 1 1 0 0 +EDGE2 1198 1178 -0.0717289 0.00919392 0.022565 1 0 1 1 0 0 +EDGE2 1198 1158 0.123417 -0.0151073 0.0384782 1 0 1 1 0 0 +EDGE2 1198 1177 -0.925289 0.0402583 0.0205986 1 0 1 1 0 0 +EDGE2 1198 1157 -0.968375 0.00936408 0.00871336 1 0 1 1 0 0 +EDGE2 1199 1160 0.939368 0.00329496 0.000679303 1 0 1 1 0 0 +EDGE2 1199 1180 1.00172 0.0423475 0.0435751 1 0 1 1 0 0 +EDGE2 1199 900 1.00413 0.0830321 -3.1435 1 0 1 1 0 0 +EDGE2 1199 840 1.00628 -0.0567556 -3.16601 1 0 1 1 0 0 +EDGE2 1199 860 1.01092 -0.0299405 -3.16665 1 0 1 1 0 0 +EDGE2 1199 1179 0.0768407 -0.00606305 0.0136534 1 0 1 1 0 0 +EDGE2 1199 1159 0.0147743 -0.0672847 -0.0067066 1 0 1 1 0 0 +EDGE2 1199 1178 -0.970375 0.0329349 0.0100241 1 0 1 1 0 0 +EDGE2 1199 1198 -0.967338 0.0104792 -0.0427058 1 0 1 1 0 0 +EDGE2 1199 1158 -0.998881 -0.00186241 0.0025615 1 0 1 1 0 0 +EDGE2 1200 839 1.05385 0.000636092 -3.16329 1 0 1 1 0 0 +EDGE2 1200 899 0.977931 0.0442219 -3.14775 1 0 1 1 0 0 +EDGE2 1200 859 1.00396 -0.0500624 -3.15502 1 0 1 1 0 0 +EDGE2 1200 841 0.0761787 -1.1146 -1.52572 1 0 1 1 0 0 +EDGE2 1200 901 0.0315086 -0.951674 -1.56216 1 0 1 1 0 0 +EDGE2 1200 861 -0.0311486 -0.969088 -1.55395 1 0 1 1 0 0 +EDGE2 1200 1160 -0.0487631 0.0630128 -0.00782963 1 0 1 1 0 0 +EDGE2 1200 1180 0.022297 -0.070963 0.0249577 1 0 1 1 0 0 +EDGE2 1200 900 0.0708977 0.0813618 -3.15781 1 0 1 1 0 0 +EDGE2 1200 840 -0.0413407 0.0827199 -3.16032 1 0 1 1 0 0 +EDGE2 1200 860 0.0361076 -0.0567568 -3.10337 1 0 1 1 0 0 +EDGE2 1200 1161 -0.0678133 1.08674 1.59444 1 0 1 1 0 0 +EDGE2 1200 1181 0.00857111 0.977986 1.54291 1 0 1 1 0 0 +EDGE2 1200 1179 -0.99874 0.0138441 -0.0235479 1 0 1 1 0 0 +EDGE2 1200 1199 -0.877005 -0.0153022 0.0122137 1 0 1 1 0 0 +EDGE2 1200 1159 -0.954953 0.0342476 -0.00373364 1 0 1 1 0 0 +EDGE2 1201 902 0.965023 0.0160967 0.0108749 1 0 1 1 0 0 +EDGE2 1201 842 0.955023 0.0750154 -0.000330985 1 0 1 1 0 0 +EDGE2 1201 862 1.05666 -0.0690953 0.0187579 1 0 1 1 0 0 +EDGE2 1201 841 0.00747102 -0.040172 0.00767508 1 0 1 1 0 0 +EDGE2 1201 901 -0.053002 0.0104632 -0.0220098 1 0 1 1 0 0 +EDGE2 1201 861 0.023435 0.0178716 0.0313492 1 0 1 1 0 0 +EDGE2 1201 1160 -0.933854 -0.0837926 1.5737 1 0 1 1 0 0 +EDGE2 1201 1200 -1.09254 0.0926322 1.59399 1 0 1 1 0 0 +EDGE2 1201 1180 -0.94782 -0.0225762 1.62918 1 0 1 1 0 0 +EDGE2 1201 900 -1.0349 -0.0290992 -1.57022 1 0 1 1 0 0 +EDGE2 1201 840 -1.06048 0.067082 -1.60144 1 0 1 1 0 0 +EDGE2 1201 860 -1.01755 0.00669806 -1.56318 1 0 1 1 0 0 +EDGE2 1202 863 1.04287 -0.0776635 0.0198956 1 0 1 1 0 0 +EDGE2 1202 903 0.983623 -0.0100431 0.0236346 1 0 1 1 0 0 +EDGE2 1202 843 0.971223 0.105905 -0.0253166 1 0 1 1 0 0 +EDGE2 1202 902 -0.0463424 -0.0272673 0.0222864 1 0 1 1 0 0 +EDGE2 1202 842 -0.0335439 -0.055347 -0.0098529 1 0 1 1 0 0 +EDGE2 1202 862 0.0237621 -0.0153109 -0.0348294 1 0 1 1 0 0 +EDGE2 1202 841 -1.04962 -0.00282735 -0.0337137 1 0 1 1 0 0 +EDGE2 1202 901 -0.947146 0.00498813 0.0123562 1 0 1 1 0 0 +EDGE2 1202 1201 -0.942714 0.107762 0.00630756 1 0 1 1 0 0 +EDGE2 1202 861 -0.91508 0.00762637 0.0111901 1 0 1 1 0 0 +EDGE2 1203 864 1.01246 -0.0300822 0.0196152 1 0 1 1 0 0 +EDGE2 1203 904 1.03039 -0.0434474 -0.00143917 1 0 1 1 0 0 +EDGE2 1203 844 1.03324 -0.0226024 0.0227594 1 0 1 1 0 0 +EDGE2 1203 863 0.00972062 -0.0745695 0.0202197 1 0 1 1 0 0 +EDGE2 1203 903 0.0987071 -0.0554281 -0.0224923 1 0 1 1 0 0 +EDGE2 1203 843 0.054069 -0.059671 0.0136409 1 0 1 1 0 0 +EDGE2 1203 902 -1.02562 -0.0380838 -0.0133717 1 0 1 1 0 0 +EDGE2 1203 1202 -0.982562 -0.104314 -0.027791 1 0 1 1 0 0 +EDGE2 1203 842 -1.05742 0.0655115 0.0024543 1 0 1 1 0 0 +EDGE2 1203 862 -0.978452 -0.103693 0.0541816 1 0 1 1 0 0 +EDGE2 1204 865 1.01038 -0.0502808 0.028921 1 0 1 1 0 0 +EDGE2 1204 905 0.994732 0.0248563 0.0289685 1 0 1 1 0 0 +EDGE2 1204 864 0.0446102 -0.0389932 -0.00685319 1 0 1 1 0 0 +EDGE2 1204 705 1.03296 0.0523754 -3.12296 1 0 1 1 0 0 +EDGE2 1204 825 1.0253 0.0498079 -3.13932 1 0 1 1 0 0 +EDGE2 1204 845 1.07318 -0.0608037 -0.0159436 1 0 1 1 0 0 +EDGE2 1204 904 -0.102606 0.0120838 0.00185651 1 0 1 1 0 0 +EDGE2 1204 844 -0.0142098 -0.0101479 0.0134005 1 0 1 1 0 0 +EDGE2 1204 863 -0.954272 0.0248137 -0.00238542 1 0 1 1 0 0 +EDGE2 1204 903 -1.02953 -0.0451765 -0.00491876 1 0 1 1 0 0 +EDGE2 1204 1203 -1.04352 -0.0523981 0.0193726 1 0 1 1 0 0 +EDGE2 1204 843 -0.904461 -0.0284807 -0.022222 1 0 1 1 0 0 +EDGE2 1205 824 0.9644 -0.0646534 -3.14341 1 0 1 1 0 0 +EDGE2 1205 704 0.969896 0.0331387 -3.11933 1 0 1 1 0 0 +EDGE2 1205 865 -0.0202909 0.00196541 -0.00203194 1 0 1 1 0 0 +EDGE2 1205 826 0.0867243 1.04067 1.614 1 0 1 1 0 0 +EDGE2 1205 866 0.0843953 0.991973 1.5858 1 0 1 1 0 0 +EDGE2 1205 906 -0.0235402 1.04002 1.56968 1 0 1 1 0 0 +EDGE2 1205 846 0.0406399 0.854825 1.54176 1 0 1 1 0 0 +EDGE2 1205 905 0.10225 0.0160863 0.0354145 1 0 1 1 0 0 +EDGE2 1205 864 -0.870077 0.0176715 -0.017572 1 0 1 1 0 0 +EDGE2 1205 705 0.0736525 -0.02964 -3.14504 1 0 1 1 0 0 +EDGE2 1205 825 0.0210271 -0.013964 -3.16634 1 0 1 1 0 0 +EDGE2 1205 845 -0.0647615 -0.0178973 0.0404592 1 0 1 1 0 0 +EDGE2 1205 1204 -0.998285 0.0227568 0.0123917 1 0 1 1 0 0 +EDGE2 1205 904 -1.0428 -0.00381185 -0.0164242 1 0 1 1 0 0 +EDGE2 1205 844 -0.986724 0.0576382 0.0110438 1 0 1 1 0 0 +EDGE2 1205 706 -0.0931865 -1.08234 -1.56459 1 0 1 1 0 0 +EDGE2 1206 865 -1.04621 -0.0605112 1.5168 1 0 1 1 0 0 +EDGE2 1206 1205 -0.98896 0.0369481 1.57553 1 0 1 1 0 0 +EDGE2 1206 905 -0.990436 0.0171944 1.57387 1 0 1 1 0 0 +EDGE2 1206 705 -0.916916 -0.0339761 -1.60515 1 0 1 1 0 0 +EDGE2 1206 825 -0.962377 0.0127444 -1.55486 1 0 1 1 0 0 +EDGE2 1206 845 -1.02171 0.0266939 1.54819 1 0 1 1 0 0 +EDGE2 1206 706 -0.0414703 0.00356656 -0.0198716 1 0 1 1 0 0 +EDGE2 1206 707 0.983398 -0.040721 -0.0280415 1 0 1 1 0 0 +EDGE2 1207 1206 -0.957552 -0.06616 0.0181065 1 0 1 1 0 0 +EDGE2 1207 706 -0.896585 -0.0267054 -0.0233504 1 0 1 1 0 0 +EDGE2 1207 707 0.0260419 -0.0249393 -0.00813253 1 0 1 1 0 0 +EDGE2 1207 708 0.916117 0.00566959 0.0179439 1 0 1 1 0 0 +EDGE2 1208 1207 -1.06293 0.00141453 -0.0200418 1 0 1 1 0 0 +EDGE2 1208 707 -0.976729 0.0065623 0.00468852 1 0 1 1 0 0 +EDGE2 1208 708 -0.0430081 0.111672 -0.0212195 1 0 1 1 0 0 +EDGE2 1208 709 1.0118 0.0478151 0.00525968 1 0 1 1 0 0 +EDGE2 1209 708 -1.02398 -0.05786 0.00819505 1 0 1 1 0 0 +EDGE2 1209 1208 -1.00635 0.037349 0.0322099 1 0 1 1 0 0 +EDGE2 1209 709 0.028738 -0.00436805 0.00882131 1 0 1 1 0 0 +EDGE2 1209 730 0.964419 0.0421057 -3.13542 1 0 1 1 0 0 +EDGE2 1209 710 1.03386 0.0179708 0.02211 1 0 1 1 0 0 +EDGE2 1210 711 -0.00736637 1.02003 1.56398 1 0 1 1 0 0 +EDGE2 1210 731 -0.0499744 1.01421 1.58219 1 0 1 1 0 0 +EDGE2 1210 1209 -0.953979 -0.0295495 0.0263917 1 0 1 1 0 0 +EDGE2 1210 709 -1.06227 -0.015838 -0.0249739 1 0 1 1 0 0 +EDGE2 1210 730 -0.0168699 -0.00414325 -3.12161 1 0 1 1 0 0 +EDGE2 1210 710 0.107995 -0.046419 0.0152759 1 0 1 1 0 0 +EDGE2 1210 729 1.05946 0.127402 -3.16021 1 0 1 1 0 0 +EDGE2 1211 732 0.983776 0.0109913 -0.0315732 1 0 1 1 0 0 +EDGE2 1211 712 0.980054 -0.026474 -0.0168355 1 0 1 1 0 0 +EDGE2 1211 711 -0.0753582 -0.0510743 0.000872924 1 0 1 1 0 0 +EDGE2 1211 731 -0.0231779 0.078167 -0.00177108 1 0 1 1 0 0 +EDGE2 1211 730 -1.07408 0.0638282 1.59478 1 0 1 1 0 0 +EDGE2 1211 1210 -0.984534 0.0366719 -1.57757 1 0 1 1 0 0 +EDGE2 1211 710 -0.9896 -0.00631405 -1.57981 1 0 1 1 0 0 +EDGE2 1212 732 0.0228577 -0.0230045 0.00861946 1 0 1 1 0 0 +EDGE2 1212 713 1.01608 -0.0181052 0.0212241 1 0 1 1 0 0 +EDGE2 1212 733 1.02846 0.0209257 0.0327517 1 0 1 1 0 0 +EDGE2 1212 1211 -0.926843 0.0750025 -0.0155459 1 0 1 1 0 0 +EDGE2 1212 712 0.0268585 -0.0321084 0.000501698 1 0 1 1 0 0 +EDGE2 1212 711 -1.03101 0.0414849 0.0133154 1 0 1 1 0 0 +EDGE2 1212 731 -0.95506 -0.0406714 -0.0014609 1 0 1 1 0 0 +EDGE2 1213 734 1.06889 -0.0318421 0.0157699 1 0 1 1 0 0 +EDGE2 1213 714 0.968855 0.0726148 -0.0107055 1 0 1 1 0 0 +EDGE2 1213 732 -1.01733 -0.0389879 -0.0120817 1 0 1 1 0 0 +EDGE2 1213 713 -0.0113563 0.0584184 0.0194304 1 0 1 1 0 0 +EDGE2 1213 733 -0.0555955 0.0843058 0.0300108 1 0 1 1 0 0 +EDGE2 1213 1212 -1.0148 -0.0899633 0.00637374 1 0 1 1 0 0 +EDGE2 1213 712 -1.01404 0.0124184 0.00862658 1 0 1 1 0 0 +EDGE2 1214 715 0.949428 0.0595407 -0.00898498 1 0 1 1 0 0 +EDGE2 1214 735 1.07082 0.0318285 -0.0207447 1 0 1 1 0 0 +EDGE2 1214 734 0.0157621 -0.046028 -0.00827101 1 0 1 1 0 0 +EDGE2 1214 714 0.0865754 -0.0048193 0.0301509 1 0 1 1 0 0 +EDGE2 1214 713 -1.07649 0.0443065 -0.0209691 1 0 1 1 0 0 +EDGE2 1214 1213 -1.02471 0.0948794 -0.00581881 1 0 1 1 0 0 +EDGE2 1214 733 -0.996348 0.0587418 0.0320128 1 0 1 1 0 0 +EDGE2 1215 736 -0.125513 1.00381 1.53308 1 0 1 1 0 0 +EDGE2 1215 715 -0.0282808 0.0486756 -0.0129348 1 0 1 1 0 0 +EDGE2 1215 735 0.0106551 -0.0413377 0.0128351 1 0 1 1 0 0 +EDGE2 1215 734 -1.09734 0.0306314 -0.015027 1 0 1 1 0 0 +EDGE2 1215 1214 -0.983838 -0.0276811 -0.00799445 1 0 1 1 0 0 +EDGE2 1215 714 -1.023 -0.0620491 -0.00772324 1 0 1 1 0 0 +EDGE2 1215 716 -0.0654519 -1.1091 -1.57381 1 0 1 1 0 0 +EDGE2 1216 715 -0.97735 0.0489631 1.58957 1 0 1 1 0 0 +EDGE2 1216 735 -0.986161 -0.0388575 1.56935 1 0 1 1 0 0 +EDGE2 1216 1215 -0.927931 -0.0286927 1.55271 1 0 1 1 0 0 +EDGE2 1216 716 -0.00974133 0.0354721 0.0177937 1 0 1 1 0 0 +EDGE2 1216 717 1.08063 0.0604315 0.00280502 1 0 1 1 0 0 +EDGE2 1217 1216 -0.954778 -0.0385421 0.000372732 1 0 1 1 0 0 +EDGE2 1217 716 -0.937689 -0.0331855 0.0345149 1 0 1 1 0 0 +EDGE2 1217 717 -0.00466761 0.0149718 0.0111016 1 0 1 1 0 0 +EDGE2 1217 718 1.02095 -0.00728376 -0.0273627 1 0 1 1 0 0 +EDGE2 1218 1217 -1.00666 -0.0467026 0.0112544 1 0 1 1 0 0 +EDGE2 1218 717 -0.986253 0.00512083 0.00164366 1 0 1 1 0 0 +EDGE2 1218 718 -0.0208088 0.0343748 0.0190977 1 0 1 1 0 0 +EDGE2 1218 719 0.958848 -0.0122527 -0.00481312 1 0 1 1 0 0 +EDGE2 1219 1218 -1.07093 0.108075 0.0135835 1 0 1 1 0 0 +EDGE2 1219 718 -0.970792 -0.00997616 -0.00644055 1 0 1 1 0 0 +EDGE2 1219 719 -0.0792663 0.00473221 -0.0119652 1 0 1 1 0 0 +EDGE2 1219 720 1.11295 -0.0352996 -0.035754 1 0 1 1 0 0 +EDGE2 1220 719 -1.08248 0.023902 -0.00302658 1 0 1 1 0 0 +EDGE2 1220 1219 -1.02413 -0.010249 -0.0100249 1 0 1 1 0 0 +EDGE2 1220 720 -0.0088893 0.0355056 -0.0172094 1 0 1 1 0 0 +EDGE2 1220 721 0.0337678 -0.996345 -1.58721 1 0 1 1 0 0 +EDGE2 1221 1220 -1.02726 0.0779541 -1.53486 1 0 1 1 0 0 +EDGE2 1221 720 -0.951297 -0.0196629 -1.5616 1 0 1 1 0 0 +EDGE2 1222 1221 -0.965533 -0.0200983 0.0235707 1 0 1 1 0 0 +EDGE2 1223 1222 -0.949825 0.013063 -0.00582171 1 0 1 1 0 0 +EDGE2 1224 1223 -1.00084 -0.0127336 -0.00950812 1 0 1 1 0 0 +EDGE2 1225 1224 -0.976818 -0.0738489 0.0115777 1 0 1 1 0 0 +EDGE2 1226 1225 -0.919396 -0.0238091 -1.59677 1 0 1 1 0 0 +EDGE2 1227 1226 -0.953632 -0.00560897 -0.00199413 1 0 1 1 0 0 +EDGE2 1228 1227 -1.05391 0.0928995 0.00480528 1 0 1 1 0 0 +EDGE2 1229 1228 -0.995469 -0.0402326 0.0197788 1 0 1 1 0 0 +EDGE2 1230 1229 -0.956068 -0.0359301 -0.0200028 1 0 1 1 0 0 +EDGE2 1231 1230 -1.00522 0.0144265 1.58084 1 0 1 1 0 0 +EDGE2 1232 1231 -1.02019 -0.00529826 0.00747219 1 0 1 1 0 0 +EDGE2 1233 1232 -0.987717 0.106755 -0.00771771 1 0 1 1 0 0 +EDGE2 1234 1233 -1.02603 0.104576 0.0166746 1 0 1 1 0 0 +EDGE2 1235 1234 -1.02459 0.00429574 -0.00735051 1 0 1 1 0 0 +EDGE2 1236 1235 -0.987815 0.0428412 -1.58036 1 0 1 1 0 0 +EDGE2 1237 1236 -0.921707 0.0463312 -0.0251561 1 0 1 1 0 0 +EDGE2 1238 1237 -1.06158 0.0587768 -0.0371789 1 0 1 1 0 0 +EDGE2 1239 1238 -0.958335 -0.0187039 -0.0168379 1 0 1 1 0 0 +EDGE2 1240 1239 -1.03491 -0.0416053 -0.0202818 1 0 1 1 0 0 +EDGE2 1241 1240 -1.02722 -0.0258531 -1.56659 1 0 1 1 0 0 +EDGE2 1242 1241 -1.00398 0.028799 0.00233828 1 0 1 1 0 0 +EDGE2 1243 1242 -0.998618 0.0201218 0.0114475 1 0 1 1 0 0 +EDGE2 1244 1243 -0.946784 -0.0498072 -0.0216779 1 0 1 1 0 0 +EDGE2 1244 785 0.923911 0.0049422 -3.1572 1 0 1 1 0 0 +EDGE2 1244 805 0.944005 0.0963412 -3.15383 1 0 1 1 0 0 +EDGE2 1244 745 1.05742 -0.0226408 -3.18555 1 0 1 1 0 0 +EDGE2 1244 765 0.96462 0.0377301 -3.15456 1 0 1 1 0 0 +EDGE2 1245 806 -0.0293562 -0.881239 -1.58751 1 0 1 1 0 0 +EDGE2 1245 766 0.0179169 -0.967211 -1.56561 1 0 1 1 0 0 +EDGE2 1245 786 -0.0526993 -1.03148 -1.58718 1 0 1 1 0 0 +EDGE2 1245 746 0.0268619 -1.06947 -1.57685 1 0 1 1 0 0 +EDGE2 1245 785 -0.0772941 -0.0318734 -3.14594 1 0 1 1 0 0 +EDGE2 1245 1244 -1.02022 -0.0165834 -0.0476381 1 0 1 1 0 0 +EDGE2 1245 805 0.00450729 -0.0391773 -3.1578 1 0 1 1 0 0 +EDGE2 1245 784 1.06558 -0.0875606 -3.12724 1 0 1 1 0 0 +EDGE2 1245 745 -0.0387961 0.0932772 -3.15754 1 0 1 1 0 0 +EDGE2 1245 765 0.0692255 0.0714386 -3.15321 1 0 1 1 0 0 +EDGE2 1245 804 0.97347 0.0166608 -3.13321 1 0 1 1 0 0 +EDGE2 1245 744 1.03641 -0.0481707 -3.17426 1 0 1 1 0 0 +EDGE2 1245 764 1.09649 -0.0679922 -3.14269 1 0 1 1 0 0 +EDGE2 1246 785 -0.955528 -0.0405685 1.55266 1 0 1 1 0 0 +EDGE2 1246 1245 -1.08362 0.0172066 -1.54933 1 0 1 1 0 0 +EDGE2 1246 805 -0.930254 0.0079152 1.57754 1 0 1 1 0 0 +EDGE2 1246 745 -1.14939 -0.014766 1.55072 1 0 1 1 0 0 +EDGE2 1246 765 -1.03277 0.0506184 1.56031 1 0 1 1 0 0 +EDGE2 1247 1246 -0.971231 0.0611377 0.0117009 1 0 1 1 0 0 +EDGE2 1248 1247 -0.981163 0.0534722 0.0260592 1 0 1 1 0 0 +EDGE2 1249 1248 -1.04105 -0.0354816 0.0123977 1 0 1 1 0 0 +EDGE2 1249 1230 0.981703 0.00306385 -3.15963 1 0 1 1 0 0 +EDGE2 1250 1249 -1.0407 -0.0118614 0.0167268 1 0 1 1 0 0 +EDGE2 1250 1231 0.0876401 1.02155 1.5644 1 0 1 1 0 0 +EDGE2 1250 1230 0.00955658 -0.107719 -3.11499 1 0 1 1 0 0 +EDGE2 1250 1229 1.05419 -0.0265379 -3.15084 1 0 1 1 0 0 +EDGE2 1251 1232 1.06051 -0.0636282 -0.0196603 1 0 1 1 0 0 +EDGE2 1251 1250 -0.958758 0.000533781 -1.54625 1 0 1 1 0 0 +EDGE2 1251 1231 0.0567422 0.0320722 0.020086 1 0 1 1 0 0 +EDGE2 1251 1230 -1.06013 -0.165135 1.53884 1 0 1 1 0 0 +EDGE2 1252 1233 0.956157 -0.00499519 -0.0157927 1 0 1 1 0 0 +EDGE2 1252 1232 -0.0785609 0.0734495 -0.00925372 1 0 1 1 0 0 +EDGE2 1252 1231 -1.09758 -0.00195688 0.025372 1 0 1 1 0 0 +EDGE2 1252 1251 -1.00576 0.000985731 -0.0131137 1 0 1 1 0 0 +EDGE2 1253 1234 1.01697 0.0549137 0.0176009 1 0 1 1 0 0 +EDGE2 1253 1233 0.103807 0.0163999 -0.00559272 1 0 1 1 0 0 +EDGE2 1253 1252 -1.0491 0.0217093 0.0111627 1 0 1 1 0 0 +EDGE2 1253 1232 -1.05303 -0.00923893 -0.0408745 1 0 1 1 0 0 +EDGE2 1254 1235 0.898496 -0.000739711 -0.0154572 1 0 1 1 0 0 +EDGE2 1254 1234 0.0277388 0.0429572 0.00374568 1 0 1 1 0 0 +EDGE2 1254 1233 -1.07563 -0.0384748 0.00415663 1 0 1 1 0 0 +EDGE2 1254 1253 -0.996194 -0.074808 0.00979893 1 0 1 1 0 0 +EDGE2 1255 1236 0.10556 1.00943 1.58875 1 0 1 1 0 0 +EDGE2 1255 1235 0.0328191 0.0291438 0.00515721 1 0 1 1 0 0 +EDGE2 1255 1254 -0.991398 0.00111205 0.0169022 1 0 1 1 0 0 +EDGE2 1255 1234 -0.931115 0.0631935 0.0194646 1 0 1 1 0 0 +EDGE2 1256 1235 -0.99466 0.0101579 1.5864 1 0 1 1 0 0 +EDGE2 1256 1255 -1.0928 -0.0253181 1.57606 1 0 1 1 0 0 +EDGE2 1257 1256 -0.993123 0.0177316 -0.00862068 1 0 1 1 0 0 +EDGE2 1258 1257 -1.06766 -0.0501905 -0.0236543 1 0 1 1 0 0 +EDGE2 1259 1258 -0.963731 0.0120464 -0.0103772 1 0 1 1 0 0 +EDGE2 1260 1259 -0.904082 0.0234269 0.00325525 1 0 1 1 0 0 +EDGE2 1261 1260 -1.02198 0.0219347 -1.58547 1 0 1 1 0 0 +EDGE2 1262 1261 -1.00848 -0.0376843 0.0036532 1 0 1 1 0 0 +EDGE2 1263 1262 -1.00909 -0.0869138 0.0120721 1 0 1 1 0 0 +EDGE2 1264 1263 -1.00886 -0.0112995 0.042789 1 0 1 1 0 0 +EDGE2 1265 1264 -1.06926 0.0465166 0.00325251 1 0 1 1 0 0 +EDGE2 1266 1265 -0.962662 0.0557897 1.59385 1 0 1 1 0 0 +EDGE2 1267 1266 -0.88301 -0.0426062 -0.00888307 1 0 1 1 0 0 +EDGE2 1268 1267 -0.913922 0.0252518 0.0218239 1 0 1 1 0 0 +EDGE2 1269 1268 -1.02281 -0.0159798 0.0206622 1 0 1 1 0 0 +EDGE2 1270 1269 -1.05562 -0.0371841 -0.0296889 1 0 1 1 0 0 +EDGE2 1271 1270 -0.947461 0.010245 1.59718 1 0 1 1 0 0 +EDGE2 1272 1271 -0.993213 0.0517024 -0.00232349 1 0 1 1 0 0 +EDGE2 1273 1272 -0.953877 -0.070659 -0.0269017 1 0 1 1 0 0 +EDGE2 1274 1273 -1.06434 0.0240494 0.0118004 1 0 1 1 0 0 +EDGE2 1275 1274 -1.01477 -0.0367259 -0.0125387 1 0 1 1 0 0 +EDGE2 1276 1275 -0.983829 0.101495 -1.60209 1 0 1 1 0 0 +EDGE2 1277 1276 -1.01347 0.0622532 0.0156585 1 0 1 1 0 0 +EDGE2 1278 1277 -1.0055 -0.0163052 -0.00412888 1 0 1 1 0 0 +EDGE2 1279 1278 -1.00166 -0.0262756 -0.00926237 1 0 1 1 0 0 +EDGE2 1280 1279 -1.00535 0.0668116 0.0295937 1 0 1 1 0 0 +EDGE2 1281 1280 -1.11317 -0.0564045 -1.56578 1 0 1 1 0 0 +EDGE2 1282 1281 -1.02591 -0.0221856 0.00609211 1 0 1 1 0 0 +EDGE2 1283 1282 -1.0265 0.0850324 -0.0251474 1 0 1 1 0 0 +EDGE2 1284 1283 -1.02846 -0.0124962 0.0148672 1 0 1 1 0 0 +EDGE2 1285 1284 -1.04499 0.0363279 -0.00407588 1 0 1 1 0 0 +EDGE2 1286 1285 -1.01605 0.0660389 -1.59129 1 0 1 1 0 0 +EDGE2 1287 1286 -1.01624 0.0560402 -0.0132879 1 0 1 1 0 0 +EDGE2 1288 1287 -0.984751 -0.0108849 0.0143504 1 0 1 1 0 0 +EDGE2 1289 1270 1.02562 -0.0657454 -3.17275 1 0 1 1 0 0 +EDGE2 1289 1288 -0.957668 -0.102919 0.00478266 1 0 1 1 0 0 +EDGE2 1290 1269 0.956249 -0.00928648 -3.15931 1 0 1 1 0 0 +EDGE2 1290 1270 -0.00838489 0.0181643 -3.15931 1 0 1 1 0 0 +EDGE2 1290 1271 -0.088188 1.04557 1.58024 1 0 1 1 0 0 +EDGE2 1290 1289 -1.03691 -0.00446685 0.0388916 1 0 1 1 0 0 +EDGE2 1291 1270 -1.02785 -0.0471841 1.53085 1 0 1 1 0 0 +EDGE2 1291 1290 -1.04285 -0.0591366 -1.55538 1 0 1 1 0 0 +EDGE2 1291 1271 -0.0765278 -0.0397412 0.0121767 1 0 1 1 0 0 +EDGE2 1291 1272 1.08194 -0.0947258 0.0221858 1 0 1 1 0 0 +EDGE2 1292 1273 1.03537 -0.0045628 -0.00014444 1 0 1 1 0 0 +EDGE2 1292 1291 -1.02101 -0.0615204 0.0280583 1 0 1 1 0 0 +EDGE2 1292 1271 -0.939642 0.0352233 0.0385476 1 0 1 1 0 0 +EDGE2 1292 1272 0.0279292 -0.0114218 0.012397 1 0 1 1 0 0 +EDGE2 1293 1273 -0.042922 0.0871251 -0.0134312 1 0 1 1 0 0 +EDGE2 1293 1292 -0.967931 0.0338533 -0.0408642 1 0 1 1 0 0 +EDGE2 1293 1272 -1.01974 0.111923 -0.00978702 1 0 1 1 0 0 +EDGE2 1293 1274 0.978731 -0.034913 -0.0117876 1 0 1 1 0 0 +EDGE2 1294 1273 -1.04603 0.0512521 0.0293677 1 0 1 1 0 0 +EDGE2 1294 1293 -1.02206 0.0821514 -0.00743214 1 0 1 1 0 0 +EDGE2 1294 1274 -0.000895846 -0.0704164 0.0159411 1 0 1 1 0 0 +EDGE2 1294 1275 1.02073 0.0251831 -0.00572445 1 0 1 1 0 0 +EDGE2 1295 1274 -1.01617 -0.0552393 -0.0125892 1 0 1 1 0 0 +EDGE2 1295 1294 -1.10367 0.0319705 0.0191134 1 0 1 1 0 0 +EDGE2 1295 1275 -0.0856354 0.0629875 -0.0104094 1 0 1 1 0 0 +EDGE2 1295 1276 -0.00481409 1.02011 1.5631 1 0 1 1 0 0 +EDGE2 1296 1295 -1.03498 0.0413666 -1.56218 1 0 1 1 0 0 +EDGE2 1296 1275 -1.01973 0.0210484 -1.56562 1 0 1 1 0 0 +EDGE2 1296 1276 0.0647043 0.041633 -0.0163977 1 0 1 1 0 0 +EDGE2 1296 1277 1.00947 0.0133073 -0.00942349 1 0 1 1 0 0 +EDGE2 1297 1296 -0.923379 0.0663967 0.0174796 1 0 1 1 0 0 +EDGE2 1297 1276 -0.895077 -0.00185955 0.0192734 1 0 1 1 0 0 +EDGE2 1297 1278 1.08446 -0.0441055 0.0144701 1 0 1 1 0 0 +EDGE2 1297 1277 -0.0152036 -0.130006 -0.0106248 1 0 1 1 0 0 +EDGE2 1298 1278 -0.0383894 -0.0175648 -0.0047295 1 0 1 1 0 0 +EDGE2 1298 1277 -1.03662 -0.00300422 -0.0124066 1 0 1 1 0 0 +EDGE2 1298 1297 -0.929933 -0.00770452 0.00514966 1 0 1 1 0 0 +EDGE2 1298 1279 0.972063 -0.00293766 -0.0198113 1 0 1 1 0 0 +EDGE2 1299 1278 -0.973071 -0.0148769 0.0100474 1 0 1 1 0 0 +EDGE2 1299 1298 -1.09466 -0.021354 0.0462745 1 0 1 1 0 0 +EDGE2 1299 1279 0.0162131 0.0664756 -0.0254896 1 0 1 1 0 0 +EDGE2 1299 1280 0.908116 -0.08319 0.0234634 1 0 1 1 0 0 +EDGE2 1300 1299 -1.05058 0.00504212 -0.0291127 1 0 1 1 0 0 +EDGE2 1300 1279 -1.05432 0.0884407 0.00186975 1 0 1 1 0 0 +EDGE2 1300 1281 0.11511 0.990294 1.54535 1 0 1 1 0 0 +EDGE2 1300 1280 0.0177556 0.00145577 0.0142503 1 0 1 1 0 0 +EDGE2 1301 1282 1.00029 -0.0304358 -0.0103006 1 0 1 1 0 0 +EDGE2 1301 1281 -0.0238066 -0.0506135 0.00522814 1 0 1 1 0 0 +EDGE2 1301 1300 -1.06437 -0.0130464 -1.56672 1 0 1 1 0 0 +EDGE2 1301 1280 -0.997234 0.0165766 -1.55265 1 0 1 1 0 0 +EDGE2 1302 1283 0.902533 -0.0606606 -0.00588698 1 0 1 1 0 0 +EDGE2 1302 1282 0.0912985 0.0245243 0.00708679 1 0 1 1 0 0 +EDGE2 1302 1281 -1.01152 -0.0229933 -0.0049624 1 0 1 1 0 0 +EDGE2 1302 1301 -1.03722 -0.0490094 -1.70037e-05 1 0 1 1 0 0 +EDGE2 1303 1284 0.98082 -0.0289642 0.00837949 1 0 1 1 0 0 +EDGE2 1303 1302 -0.953318 -0.0520686 0.0131677 1 0 1 1 0 0 +EDGE2 1303 1283 -0.025674 -0.0413467 0.0262033 1 0 1 1 0 0 +EDGE2 1303 1282 -1.1085 0.0183149 -0.00157826 1 0 1 1 0 0 +EDGE2 1304 1303 -0.877227 0.00561841 0.00286066 1 0 1 1 0 0 +EDGE2 1304 1285 0.995133 -0.0231667 0.0354908 1 0 1 1 0 0 +EDGE2 1304 1284 0.0271038 0.127426 0.0107461 1 0 1 1 0 0 +EDGE2 1304 1283 -1.03006 0.026649 0.00520358 1 0 1 1 0 0 +EDGE2 1305 1304 -1.0447 -0.0208013 -0.0140763 1 0 1 1 0 0 +EDGE2 1305 1286 0.00437427 0.944903 1.56751 1 0 1 1 0 0 +EDGE2 1305 1285 0.00346995 -0.0932063 0.0113121 1 0 1 1 0 0 +EDGE2 1305 1284 -0.995703 0.0479902 -0.0177929 1 0 1 1 0 0 +EDGE2 1306 1285 -1.05958 0.0738314 1.58389 1 0 1 1 0 0 +EDGE2 1306 1305 -1.01689 0.0280222 1.54481 1 0 1 1 0 0 +EDGE2 1307 1306 -0.998002 0.0258337 0.00705902 1 0 1 1 0 0 +EDGE2 1308 1307 -0.913524 0.036245 -0.0253566 1 0 1 1 0 0 +EDGE2 1309 1308 -1.0792 -0.0219855 -0.0386577 1 0 1 1 0 0 +EDGE2 1310 1309 -0.900168 0.0105322 -0.00773817 1 0 1 1 0 0 +EDGE2 1311 1310 -1.07678 0.0558806 -1.59561 1 0 1 1 0 0 +EDGE2 1312 1311 -1.00556 0.0386834 -0.0125337 1 0 1 1 0 0 +EDGE2 1313 1312 -1.02178 0.00991733 0.0270311 1 0 1 1 0 0 +EDGE2 1314 1313 -0.953064 0.00457294 -0.00378178 1 0 1 1 0 0 +EDGE2 1315 1314 -1.02659 -0.00334088 0.00358176 1 0 1 1 0 0 +EDGE2 1316 1315 -1.0129 -0.0081812 -1.57679 1 0 1 1 0 0 +EDGE2 1317 1316 -1.01794 -0.0166643 -0.0306864 1 0 1 1 0 0 +EDGE2 1318 1317 -1.00807 0.0225211 -0.0201849 1 0 1 1 0 0 +EDGE2 1319 1318 -0.934565 -0.00490922 -0.0149655 1 0 1 1 0 0 +EDGE2 1320 1319 -0.973219 0.0177417 -0.0175316 1 0 1 1 0 0 +EDGE2 1321 1320 -1.04061 0.0242679 1.56943 1 0 1 1 0 0 +EDGE2 1322 1321 -1.01395 0.0348408 0.01551 1 0 1 1 0 0 +EDGE2 1323 1322 -1.01518 -0.020291 -0.00543139 1 0 1 1 0 0 +EDGE2 1324 1323 -0.929009 0.0474709 -0.0379966 1 0 1 1 0 0 +EDGE2 1325 1324 -0.986292 0.0309375 0.0120332 1 0 1 1 0 0 +EDGE2 1326 1325 -1.04808 -0.0388319 1.58762 1 0 1 1 0 0 +EDGE2 1327 1326 -1.04096 -0.0647614 -0.016395 1 0 1 1 0 0 +EDGE2 1328 1327 -0.998002 0.0185409 0.015181 1 0 1 1 0 0 +EDGE2 1329 1328 -0.880581 0.0713252 -0.0063803 1 0 1 1 0 0 +EDGE2 1330 1329 -0.949889 -0.0256134 0.0107546 1 0 1 1 0 0 +EDGE2 1331 1330 -1.07245 -0.00287284 -1.56439 1 0 1 1 0 0 +EDGE2 1332 1331 -1.06003 -0.0351636 0.00481686 1 0 1 1 0 0 +EDGE2 1333 1332 -0.934493 0.0143094 -0.00329225 1 0 1 1 0 0 +EDGE2 1334 1333 -1.08852 -0.0439092 0.0383159 1 0 1 1 0 0 +EDGE2 1335 1334 -0.978056 -0.0828671 0.012717 1 0 1 1 0 0 +EDGE2 1336 1335 -1.03952 0.021556 -1.59663 1 0 1 1 0 0 +EDGE2 1337 1336 -0.982531 -0.0696169 0.0118796 1 0 1 1 0 0 +EDGE2 1338 1337 -1.04294 0.0208141 -0.0405447 1 0 1 1 0 0 +EDGE2 1339 1338 -1.00319 0.0106848 0.00172351 1 0 1 1 0 0 +EDGE2 1340 1339 -0.97579 -0.011836 0.0077563 1 0 1 1 0 0 +EDGE2 1341 1340 -0.994057 -0.0075998 -1.59024 1 0 1 1 0 0 +EDGE2 1342 1341 -0.974226 -0.0250961 0.02775 1 0 1 1 0 0 +EDGE2 1343 1342 -1.03154 0.0546996 0.0148903 1 0 1 1 0 0 +EDGE2 1344 1343 -0.996771 0.0394928 -0.00154414 1 0 1 1 0 0 +EDGE2 1344 1325 1.04822 -0.0392246 -3.13049 1 0 1 1 0 0 +EDGE2 1345 1344 -1.03573 0.0229721 0.00352092 1 0 1 1 0 0 +EDGE2 1345 1325 0.0501157 -0.133333 -3.15242 1 0 1 1 0 0 +EDGE2 1345 1324 1.04854 -0.041186 -3.15314 1 0 1 1 0 0 +EDGE2 1345 1326 -0.0197953 0.921164 1.55266 1 0 1 1 0 0 +EDGE2 1346 1345 -0.995624 -0.0389939 -1.58237 1 0 1 1 0 0 +EDGE2 1346 1325 -1.01243 -0.126872 1.59091 1 0 1 1 0 0 +EDGE2 1346 1327 0.963695 0.0114909 -0.0190989 1 0 1 1 0 0 +EDGE2 1346 1326 0.0249382 -0.0427409 -0.000707319 1 0 1 1 0 0 +EDGE2 1347 1327 0.059019 0.0460568 0.00270853 1 0 1 1 0 0 +EDGE2 1347 1326 -0.927082 -0.0163373 -0.00800912 1 0 1 1 0 0 +EDGE2 1347 1346 -1.02247 0.0777766 -0.0290529 1 0 1 1 0 0 +EDGE2 1347 1328 1.07449 0.0561931 -0.020526 1 0 1 1 0 0 +EDGE2 1348 1327 -1.04603 0.0342391 -0.0193265 1 0 1 1 0 0 +EDGE2 1348 1347 -0.959718 0.00915572 -0.00817475 1 0 1 1 0 0 +EDGE2 1348 1328 -0.0236457 -0.0469175 0.00233462 1 0 1 1 0 0 +EDGE2 1348 1329 0.97967 0.0369753 -0.0134402 1 0 1 1 0 0 +EDGE2 1349 1348 -1.04546 -0.0228939 -0.0169614 1 0 1 1 0 0 +EDGE2 1349 1328 -0.94586 -0.0100832 0.00104271 1 0 1 1 0 0 +EDGE2 1349 1329 0.00733568 -0.00352353 0.00889541 1 0 1 1 0 0 +EDGE2 1349 1330 1.04602 -0.0039329 0.00197006 1 0 1 1 0 0 +EDGE2 1350 1349 -0.937378 0.0811747 0.0201027 1 0 1 1 0 0 +EDGE2 1350 1329 -0.998397 -0.0592215 0.00748063 1 0 1 1 0 0 +EDGE2 1350 1331 -0.0577339 0.951047 1.58865 1 0 1 1 0 0 +EDGE2 1350 1330 0.0751998 0.042378 0.00918842 1 0 1 1 0 0 +EDGE2 1351 1332 1.00559 0.0314839 0.0350335 1 0 1 1 0 0 +EDGE2 1351 1331 0.00569124 0.000593134 0.0128801 1 0 1 1 0 0 +EDGE2 1351 1330 -0.947401 0.0446627 -1.52908 1 0 1 1 0 0 +EDGE2 1351 1350 -1.00275 0.0343804 -1.56712 1 0 1 1 0 0 +EDGE2 1352 1333 0.944919 -0.0231685 -0.0139634 1 0 1 1 0 0 +EDGE2 1352 1332 -0.135432 -0.0300424 -0.0074848 1 0 1 1 0 0 +EDGE2 1352 1331 -0.943396 -0.0296817 -0.00542777 1 0 1 1 0 0 +EDGE2 1352 1351 -1.04029 0.00126786 -0.0513892 1 0 1 1 0 0 +EDGE2 1353 1333 -0.0728487 0.0176585 -0.0277569 1 0 1 1 0 0 +EDGE2 1353 1334 0.952166 -0.0210342 -0.0257619 1 0 1 1 0 0 +EDGE2 1353 1352 -0.956735 0.0802878 -0.00479265 1 0 1 1 0 0 +EDGE2 1353 1332 -1.04113 -0.0269612 -0.0044539 1 0 1 1 0 0 +EDGE2 1354 1333 -0.919576 -0.00719264 0.0235486 1 0 1 1 0 0 +EDGE2 1354 1335 0.980334 0.0280101 -0.0162286 1 0 1 1 0 0 +EDGE2 1354 1334 -0.0160647 0.0594651 -0.0107289 1 0 1 1 0 0 +EDGE2 1354 1353 -1.00603 0.0602598 -0.019145 1 0 1 1 0 0 +EDGE2 1355 1336 0.0856151 0.953179 1.59341 1 0 1 1 0 0 +EDGE2 1355 1335 0.0750055 -0.0141627 -0.0199108 1 0 1 1 0 0 +EDGE2 1355 1334 -0.930388 0.0072835 0.0140821 1 0 1 1 0 0 +EDGE2 1355 1354 -1.0504 -0.0178273 -0.0138611 1 0 1 1 0 0 +EDGE2 1356 1336 0.0236094 -0.0140295 0.0202114 1 0 1 1 0 0 +EDGE2 1356 1337 0.990918 0.0442237 0.0108398 1 0 1 1 0 0 +EDGE2 1356 1355 -1.00911 0.0407671 -1.54886 1 0 1 1 0 0 +EDGE2 1356 1335 -1.0451 -0.0906945 -1.56966 1 0 1 1 0 0 +EDGE2 1357 1336 -0.907753 -0.0621581 0.00164152 1 0 1 1 0 0 +EDGE2 1357 1338 1.08187 0.0448476 0.0227921 1 0 1 1 0 0 +EDGE2 1357 1337 -0.0633525 0.0624514 -0.00135408 1 0 1 1 0 0 +EDGE2 1357 1356 -1.06332 0.0238446 -0.0279529 1 0 1 1 0 0 +EDGE2 1358 1339 0.98042 -0.0304644 0.00126019 1 0 1 1 0 0 +EDGE2 1358 1338 -0.0255201 -0.0149754 -0.0149456 1 0 1 1 0 0 +EDGE2 1358 1357 -0.876029 0.0402264 -0.00447355 1 0 1 1 0 0 +EDGE2 1358 1337 -1.05511 0.115566 0.00231503 1 0 1 1 0 0 +EDGE2 1359 1340 0.969493 0.079968 -0.0175553 1 0 1 1 0 0 +EDGE2 1359 1339 0.0982374 0.116912 -0.0260436 1 0 1 1 0 0 +EDGE2 1359 1358 -1.06755 0.0167541 -0.0130485 1 0 1 1 0 0 +EDGE2 1359 1338 -1.02105 0.039925 -0.00384795 1 0 1 1 0 0 +EDGE2 1360 1340 0.0135307 0.0671947 -0.000154066 1 0 1 1 0 0 +EDGE2 1360 1341 -0.00412353 1.03662 1.55529 1 0 1 1 0 0 +EDGE2 1360 1359 -0.978527 -0.00440941 0.00195384 1 0 1 1 0 0 +EDGE2 1360 1339 -0.874904 0.0642204 -0.0124994 1 0 1 1 0 0 +EDGE2 1361 1360 -0.95865 -0.0279406 -1.59054 1 0 1 1 0 0 +EDGE2 1361 1340 -0.999718 -0.0126395 -1.56696 1 0 1 1 0 0 +EDGE2 1361 1341 -0.0468171 -0.0647529 -0.0217002 1 0 1 1 0 0 +EDGE2 1361 1342 1.07777 -0.0100965 -0.0235072 1 0 1 1 0 0 +EDGE2 1362 1341 -1.02101 0.015146 -0.0268308 1 0 1 1 0 0 +EDGE2 1362 1361 -0.937815 0.055212 0.00541863 1 0 1 1 0 0 +EDGE2 1362 1342 -0.019019 -0.0036166 0.0150366 1 0 1 1 0 0 +EDGE2 1362 1343 0.967714 0.0579941 -0.0152468 1 0 1 1 0 0 +EDGE2 1363 1342 -0.9068 0.0588464 -0.0320384 1 0 1 1 0 0 +EDGE2 1363 1362 -1.00118 -0.0696141 0.0290736 1 0 1 1 0 0 +EDGE2 1363 1343 -0.0414892 0.0165952 0.0279354 1 0 1 1 0 0 +EDGE2 1363 1344 0.944044 0.0587566 -0.0307836 1 0 1 1 0 0 +EDGE2 1364 1345 0.977588 0.00453713 0.0223072 1 0 1 1 0 0 +EDGE2 1364 1363 -0.976966 0.00400062 -0.0124806 1 0 1 1 0 0 +EDGE2 1364 1343 -1.08433 -0.0425973 0.0187873 1 0 1 1 0 0 +EDGE2 1364 1344 0.0372683 -0.00744931 0.0150595 1 0 1 1 0 0 +EDGE2 1364 1325 0.9639 0.102991 -3.11879 1 0 1 1 0 0 +EDGE2 1365 1345 -0.0325098 0.00240627 -0.00189106 1 0 1 1 0 0 +EDGE2 1365 1344 -0.935776 0.0502503 -0.0164652 1 0 1 1 0 0 +EDGE2 1365 1364 -1.00152 -0.00777685 -0.0321487 1 0 1 1 0 0 +EDGE2 1365 1325 0.0309097 -0.0082156 -3.09045 1 0 1 1 0 0 +EDGE2 1365 1324 0.94348 0.0150096 -3.17209 1 0 1 1 0 0 +EDGE2 1365 1326 0.0753759 1.03153 1.57787 1 0 1 1 0 0 +EDGE2 1365 1346 0.0428676 0.953898 1.55087 1 0 1 1 0 0 +EDGE2 1366 1345 -1.0705 0.0232024 1.54844 1 0 1 1 0 0 +EDGE2 1366 1365 -1.00715 -0.0215865 1.58189 1 0 1 1 0 0 +EDGE2 1366 1325 -1.05393 0.0313154 -1.57588 1 0 1 1 0 0 +EDGE2 1367 1366 -0.988482 -0.0692858 0.0379232 1 0 1 1 0 0 +EDGE2 1368 1367 -0.948032 -0.0155759 0.00909279 1 0 1 1 0 0 +EDGE2 1369 1368 -1.07398 -0.0775139 -0.0259039 1 0 1 1 0 0 +EDGE2 1370 1369 -0.963019 -0.0233238 -0.0138377 1 0 1 1 0 0 +EDGE2 1371 1370 -1.05918 -0.0720216 -1.5203 1 0 1 1 0 0 +EDGE2 1372 1371 -1.00661 -0.0148252 -0.0188618 1 0 1 1 0 0 +EDGE2 1373 1372 -1.02922 0.0383245 -0.0357035 1 0 1 1 0 0 +EDGE2 1374 1373 -0.987145 -0.00322017 -0.0113097 1 0 1 1 0 0 +EDGE2 1375 1374 -0.9856 0.0191343 0.00434768 1 0 1 1 0 0 +EDGE2 1376 1375 -1.04229 -0.0103536 1.62253 1 0 1 1 0 0 +EDGE2 1377 1376 -0.97322 -0.146426 -0.056472 1 0 1 1 0 0 +EDGE2 1378 1377 -0.951448 0.0619607 0.012181 1 0 1 1 0 0 +EDGE2 1379 1378 -1.0052 0.0269726 -0.0249931 1 0 1 1 0 0 +EDGE2 1380 1379 -1.00242 -0.0397082 0.0202346 1 0 1 1 0 0 +EDGE2 1381 1380 -1.03778 0.0585509 1.58863 1 0 1 1 0 0 +EDGE2 1382 1381 -0.978873 -0.100375 -0.0436636 1 0 1 1 0 0 +EDGE2 1383 1382 -0.963163 -0.00820939 0.00938163 1 0 1 1 0 0 +EDGE2 1384 1383 -1.0966 0.0259232 0.0292737 1 0 1 1 0 0 +EDGE2 1385 1384 -1.04202 0.0102956 0.0215729 1 0 1 1 0 0 +EDGE2 1386 1385 -0.972017 0.000931471 -1.56483 1 0 1 1 0 0 +EDGE2 1387 1386 -0.941773 0.0533096 -0.0108815 1 0 1 1 0 0 +EDGE2 1388 1387 -1.05946 -0.0935919 -0.0471441 1 0 1 1 0 0 +EDGE2 1389 1388 -1.02696 0.0142874 0.0226167 1 0 1 1 0 0 +EDGE2 1390 1389 -0.969166 0.0577507 -0.00360282 1 0 1 1 0 0 +EDGE2 1391 1390 -0.994529 0.0167784 1.5839 1 0 1 1 0 0 +EDGE2 1392 1391 -0.941035 -0.000869934 -0.0123756 1 0 1 1 0 0 +EDGE2 1393 1392 -0.98814 0.0311047 0.017603 1 0 1 1 0 0 +EDGE2 1394 1393 -1.03987 -0.0556172 -0.036493 1 0 1 1 0 0 +EDGE2 1395 1394 -1.03678 -0.0668154 -0.0015821 1 0 1 1 0 0 +EDGE2 1396 1395 -1.01845 -0.0397121 -1.57863 1 0 1 1 0 0 +EDGE2 1397 1396 -1.02852 -0.0139834 -0.0150747 1 0 1 1 0 0 +EDGE2 1398 1397 -0.950331 -0.0218189 -0.000791031 1 0 1 1 0 0 +EDGE2 1399 1398 -0.981681 0.0242888 0.0043108 1 0 1 1 0 0 +EDGE2 1400 1399 -0.944484 -0.00485922 -0.0058725 1 0 1 1 0 0 +EDGE2 1401 1400 -1.05207 -0.0591262 -1.56514 1 0 1 1 0 0 +EDGE2 1402 1401 -1.06099 0.0289075 0.00586313 1 0 1 1 0 0 +EDGE2 1403 1402 -1.0522 -0.00112635 0.00614812 1 0 1 1 0 0 +EDGE2 1404 1403 -0.943919 -0.0784776 -0.000224858 1 0 1 1 0 0 +EDGE2 1405 1404 -1.00607 0.114993 -0.0104835 1 0 1 1 0 0 +EDGE2 1406 1405 -0.999647 -0.0212516 -1.55289 1 0 1 1 0 0 +EDGE2 1407 1406 -0.943968 0.0301946 -0.0266111 1 0 1 1 0 0 +EDGE2 1408 1407 -1.0032 -0.0230962 0.00186317 1 0 1 1 0 0 +EDGE2 1409 1408 -1.06701 0.0361972 -0.0172226 1 0 1 1 0 0 +EDGE2 1409 1390 0.944767 -0.0367235 -3.14664 1 0 1 1 0 0 +EDGE2 1410 1409 -0.927642 -0.0147163 -0.0111467 1 0 1 1 0 0 +EDGE2 1410 1391 -0.123433 0.961469 1.55341 1 0 1 1 0 0 +EDGE2 1410 1390 -0.0472256 0.107962 -3.11276 1 0 1 1 0 0 +EDGE2 1410 1389 0.997338 0.0486915 -3.13651 1 0 1 1 0 0 +EDGE2 1411 1392 0.996841 -0.0344636 -0.000122099 1 0 1 1 0 0 +EDGE2 1411 1391 0.0704502 -0.026375 0.0113458 1 0 1 1 0 0 +EDGE2 1411 1390 -1.07727 -0.118589 1.52618 1 0 1 1 0 0 +EDGE2 1411 1410 -1.05865 -0.0584611 -1.54294 1 0 1 1 0 0 +EDGE2 1412 1393 1.02186 0.00390471 -0.0194022 1 0 1 1 0 0 +EDGE2 1412 1392 0.0475201 0.0391997 0.00995014 1 0 1 1 0 0 +EDGE2 1412 1391 -1.01796 -0.0314441 -0.0478106 1 0 1 1 0 0 +EDGE2 1412 1411 -1.00927 0.0308382 -0.0194501 1 0 1 1 0 0 +EDGE2 1413 1394 1.06972 -0.041274 0.0283313 1 0 1 1 0 0 +EDGE2 1413 1393 0.0180982 0.0220153 -0.012737 1 0 1 1 0 0 +EDGE2 1413 1392 -1.04545 -0.0337083 -0.00430344 1 0 1 1 0 0 +EDGE2 1413 1412 -1.06394 -0.05382 0.0022654 1 0 1 1 0 0 +EDGE2 1414 1395 0.954364 -0.0221866 -0.00782713 1 0 1 1 0 0 +EDGE2 1414 1394 0.0571956 0.0140559 0.0054142 1 0 1 1 0 0 +EDGE2 1414 1393 -1.0216 0.0821867 0.0283721 1 0 1 1 0 0 +EDGE2 1414 1413 -0.984621 -0.050949 -0.00740644 1 0 1 1 0 0 +EDGE2 1415 1396 0.0302759 1.02703 1.56547 1 0 1 1 0 0 +EDGE2 1415 1395 -0.0312893 0.0379327 0.0132925 1 0 1 1 0 0 +EDGE2 1415 1394 -1.07302 -0.0421265 0.0311092 1 0 1 1 0 0 +EDGE2 1415 1414 -1.03723 -0.0308033 -0.00799769 1 0 1 1 0 0 +EDGE2 1416 1397 0.989796 -0.0283192 0.029782 1 0 1 1 0 0 +EDGE2 1416 1396 -0.0621585 0.000816006 -0.0410375 1 0 1 1 0 0 +EDGE2 1416 1395 -1.04961 0.0288564 -1.60932 1 0 1 1 0 0 +EDGE2 1416 1415 -0.993021 0.0305793 -1.5272 1 0 1 1 0 0 +EDGE2 1417 1398 1.08587 -0.0337934 0.00534367 1 0 1 1 0 0 +EDGE2 1417 1416 -0.972662 -0.0193098 0.0353256 1 0 1 1 0 0 +EDGE2 1417 1397 0.041372 -0.0496154 -0.0111693 1 0 1 1 0 0 +EDGE2 1417 1396 -0.908292 0.0257168 -0.000779434 1 0 1 1 0 0 +EDGE2 1418 1417 -0.96216 0.0307232 -0.00114849 1 0 1 1 0 0 +EDGE2 1418 1399 1.05869 0.0412261 0.00580127 1 0 1 1 0 0 +EDGE2 1418 1398 0.00171288 -0.106843 0.00948127 1 0 1 1 0 0 +EDGE2 1418 1397 -0.970813 -0.08622 -0.0303142 1 0 1 1 0 0 +EDGE2 1419 1400 0.947322 0.00721523 -0.0275982 1 0 1 1 0 0 +EDGE2 1419 1399 0.00898819 -0.0948318 -0.0326965 1 0 1 1 0 0 +EDGE2 1419 1398 -1.02109 0.0157848 -0.0258109 1 0 1 1 0 0 +EDGE2 1419 1418 -0.888345 -0.0342643 0.0149746 1 0 1 1 0 0 +EDGE2 1420 1400 0.0179432 -0.0294689 0.0195101 1 0 1 1 0 0 +EDGE2 1420 1401 -0.0737493 1.05823 1.59391 1 0 1 1 0 0 +EDGE2 1420 1419 -0.948091 0.0391133 -0.00307353 1 0 1 1 0 0 +EDGE2 1420 1399 -0.988484 -0.125854 0.0216857 1 0 1 1 0 0 +EDGE2 1421 1420 -0.902021 0.000994707 -1.60465 1 0 1 1 0 0 +EDGE2 1421 1400 -0.95056 0.0604537 -1.57474 1 0 1 1 0 0 +EDGE2 1421 1401 0.00875136 -0.00677837 0.000414187 1 0 1 1 0 0 +EDGE2 1421 1402 0.944908 0.050263 0.0271172 1 0 1 1 0 0 +EDGE2 1422 1421 -1.07596 0.0131098 -0.0353202 1 0 1 1 0 0 +EDGE2 1422 1401 -1.04881 0.0688295 0.0243572 1 0 1 1 0 0 +EDGE2 1422 1402 0.0218581 -0.076914 0.00666758 1 0 1 1 0 0 +EDGE2 1422 1403 0.916945 -0.110691 -0.0125234 1 0 1 1 0 0 +EDGE2 1423 1422 -1.07233 -0.0371105 -0.00594416 1 0 1 1 0 0 +EDGE2 1423 1402 -1.06311 0.0477995 -0.0147959 1 0 1 1 0 0 +EDGE2 1423 1403 -0.0607796 0.0703621 -0.00907161 1 0 1 1 0 0 +EDGE2 1423 1404 0.92779 -0.0603331 0.00909589 1 0 1 1 0 0 +EDGE2 1424 1423 -1.05177 -0.0294616 0.0150152 1 0 1 1 0 0 +EDGE2 1424 1403 -1.07714 0.0213732 0.0165281 1 0 1 1 0 0 +EDGE2 1424 1404 -0.110418 0.0103907 -0.00462103 1 0 1 1 0 0 +EDGE2 1424 1405 1.04536 -0.114819 0.0563655 1 0 1 1 0 0 +EDGE2 1425 1424 -1.08063 0.13883 0.0438057 1 0 1 1 0 0 +EDGE2 1425 1404 -0.997207 -0.062562 0.0134781 1 0 1 1 0 0 +EDGE2 1425 1405 0.00506186 0.0370806 0.0142071 1 0 1 1 0 0 +EDGE2 1425 1406 0.0373999 1.05798 1.58722 1 0 1 1 0 0 +EDGE2 1426 1425 -0.917228 -0.0371072 -1.54197 1 0 1 1 0 0 +EDGE2 1426 1405 -0.952534 -0.0119537 -1.59986 1 0 1 1 0 0 +EDGE2 1426 1406 0.0580174 0.00907748 -0.00170692 1 0 1 1 0 0 +EDGE2 1426 1407 1.04253 -0.0953457 -0.052206 1 0 1 1 0 0 +EDGE2 1427 1426 -1.01072 0.0669964 -0.003476 1 0 1 1 0 0 +EDGE2 1427 1406 -0.952187 -0.0136245 -0.0512969 1 0 1 1 0 0 +EDGE2 1427 1407 0.0266039 -0.0349699 0.0402138 1 0 1 1 0 0 +EDGE2 1427 1408 1.01231 0.0595043 0.016695 1 0 1 1 0 0 +EDGE2 1428 1427 -1.09557 0.0862934 0.0038267 1 0 1 1 0 0 +EDGE2 1428 1407 -1.0687 0.00415598 -0.00153509 1 0 1 1 0 0 +EDGE2 1428 1408 -0.0412662 0.0255022 -0.0244777 1 0 1 1 0 0 +EDGE2 1428 1409 1.04809 -0.0880203 -0.0287118 1 0 1 1 0 0 +EDGE2 1429 1428 -1.00597 0.0666684 0.00447724 1 0 1 1 0 0 +EDGE2 1429 1408 -0.971979 0.00639482 -0.0269593 1 0 1 1 0 0 +EDGE2 1429 1409 0.015765 -0.0698861 -0.028796 1 0 1 1 0 0 +EDGE2 1429 1390 0.949844 0.0817035 -3.12115 1 0 1 1 0 0 +EDGE2 1429 1410 1.00944 -0.0262732 -0.0193393 1 0 1 1 0 0 +EDGE2 1430 1429 -1.02699 0.0529341 0.020478 1 0 1 1 0 0 +EDGE2 1430 1409 -1.10325 -0.0166073 -0.0355365 1 0 1 1 0 0 +EDGE2 1430 1391 0.129183 0.932736 1.55083 1 0 1 1 0 0 +EDGE2 1430 1411 0.122019 1.04511 1.5561 1 0 1 1 0 0 +EDGE2 1430 1390 -0.0931846 0.00903895 -3.11528 1 0 1 1 0 0 +EDGE2 1430 1410 0.03029 0.0581652 0.0268903 1 0 1 1 0 0 +EDGE2 1430 1389 0.870844 -0.0610926 -3.13091 1 0 1 1 0 0 +EDGE2 1431 1392 0.917702 0.0430793 0.0124016 1 0 1 1 0 0 +EDGE2 1431 1412 1.0362 -0.0423208 0.00306961 1 0 1 1 0 0 +EDGE2 1431 1391 0.0764833 -0.0439417 0.0219651 1 0 1 1 0 0 +EDGE2 1431 1411 0.0406721 0.0908839 -0.0265842 1 0 1 1 0 0 +EDGE2 1431 1390 -0.911523 -0.104346 1.56287 1 0 1 1 0 0 +EDGE2 1431 1410 -1.03622 -0.0325102 -1.60142 1 0 1 1 0 0 +EDGE2 1431 1430 -0.958509 0.0152587 -1.56831 1 0 1 1 0 0 +EDGE2 1432 1393 1.04074 0.086363 -0.00579808 1 0 1 1 0 0 +EDGE2 1432 1413 1.04406 -0.0464985 -0.00739889 1 0 1 1 0 0 +EDGE2 1432 1392 0.0984707 0.0562948 0.0191231 1 0 1 1 0 0 +EDGE2 1432 1412 -0.0642717 -0.053982 -0.0134026 1 0 1 1 0 0 +EDGE2 1432 1391 -1.09252 -0.0421273 0.00788659 1 0 1 1 0 0 +EDGE2 1432 1411 -1.01774 -0.0850906 0.0173714 1 0 1 1 0 0 +EDGE2 1432 1431 -0.892495 0.00469868 -0.0114108 1 0 1 1 0 0 +EDGE2 1433 1394 1.08645 -0.0414362 -0.0081335 1 0 1 1 0 0 +EDGE2 1433 1414 0.953066 -0.0719693 -0.00189212 1 0 1 1 0 0 +EDGE2 1433 1432 -0.999421 0.0568748 -0.00949472 1 0 1 1 0 0 +EDGE2 1433 1393 0.0214907 0.0316983 0.00371922 1 0 1 1 0 0 +EDGE2 1433 1413 0.0157398 -0.00391103 0.0118984 1 0 1 1 0 0 +EDGE2 1433 1392 -0.893914 -0.049281 -0.010336 1 0 1 1 0 0 +EDGE2 1433 1412 -1.04601 -0.000208887 0.0213236 1 0 1 1 0 0 +EDGE2 1434 1433 -1.04012 -0.0355851 -0.0149737 1 0 1 1 0 0 +EDGE2 1434 1395 1.0556 0.0397592 -0.0123556 1 0 1 1 0 0 +EDGE2 1434 1415 0.99812 -0.0222638 -0.0221763 1 0 1 1 0 0 +EDGE2 1434 1394 0.0527497 -0.0638121 0.00759312 1 0 1 1 0 0 +EDGE2 1434 1414 0.043526 0.105016 0.0122982 1 0 1 1 0 0 +EDGE2 1434 1393 -1.00873 -0.00230292 0.0208638 1 0 1 1 0 0 +EDGE2 1434 1413 -0.984007 0.0583332 0.0124564 1 0 1 1 0 0 +EDGE2 1435 1416 -0.0696512 1.02483 1.54463 1 0 1 1 0 0 +EDGE2 1435 1396 -0.0330313 0.957257 1.57418 1 0 1 1 0 0 +EDGE2 1435 1434 -0.978669 0.0162581 -0.0221339 1 0 1 1 0 0 +EDGE2 1435 1395 0.0262498 0.102004 -0.0130479 1 0 1 1 0 0 +EDGE2 1435 1415 0.0923454 -0.0579428 -0.00989165 1 0 1 1 0 0 +EDGE2 1435 1394 -1.03552 0.00500888 0.00222638 1 0 1 1 0 0 +EDGE2 1435 1414 -0.959028 0.0116371 -0.030827 1 0 1 1 0 0 +EDGE2 1436 1417 0.936879 0.0721455 -0.0156758 1 0 1 1 0 0 +EDGE2 1436 1435 -0.947618 -0.0558031 -1.55739 1 0 1 1 0 0 +EDGE2 1436 1416 -0.0524748 -0.0265368 0.00416359 1 0 1 1 0 0 +EDGE2 1436 1397 1.00456 0.0382765 -0.0178174 1 0 1 1 0 0 +EDGE2 1436 1396 0.0264257 0.0221418 -0.00817294 1 0 1 1 0 0 +EDGE2 1436 1395 -1.02947 -0.0355655 -1.61942 1 0 1 1 0 0 +EDGE2 1436 1415 -1.00143 0.0200883 -1.60356 1 0 1 1 0 0 +EDGE2 1437 1417 0.0468833 0.0937302 -0.00215076 1 0 1 1 0 0 +EDGE2 1437 1398 1.06362 -0.132037 -0.0219956 1 0 1 1 0 0 +EDGE2 1437 1418 1.00995 -0.103521 0.0325923 1 0 1 1 0 0 +EDGE2 1437 1416 -1.00987 -0.0233992 0.00403165 1 0 1 1 0 0 +EDGE2 1437 1397 0.0438405 0.0732055 0.00828089 1 0 1 1 0 0 +EDGE2 1437 1436 -0.958355 -0.0400843 0.0239915 1 0 1 1 0 0 +EDGE2 1437 1396 -1.01411 0.0284715 0.0151197 1 0 1 1 0 0 +EDGE2 1438 1417 -1.01238 -0.0434399 0.0203436 1 0 1 1 0 0 +EDGE2 1438 1419 0.963762 -0.0398303 -0.00138025 1 0 1 1 0 0 +EDGE2 1438 1399 0.9761 -0.0077305 -0.00969676 1 0 1 1 0 0 +EDGE2 1438 1398 0.0265989 0.0652574 -0.0361125 1 0 1 1 0 0 +EDGE2 1438 1418 -0.0406613 0.00527645 0.00606838 1 0 1 1 0 0 +EDGE2 1438 1437 -1.03318 -0.0501932 0.00547655 1 0 1 1 0 0 +EDGE2 1438 1397 -1.03569 0.053879 0.0206183 1 0 1 1 0 0 +EDGE2 1439 1420 0.934352 -0.0143428 -0.00244171 1 0 1 1 0 0 +EDGE2 1439 1400 1.0336 0.0715235 -0.011632 1 0 1 1 0 0 +EDGE2 1439 1419 0.0321902 0.075002 -0.0133982 1 0 1 1 0 0 +EDGE2 1439 1399 -0.00202495 -0.0654425 0.00355319 1 0 1 1 0 0 +EDGE2 1439 1398 -1.01681 0.0146615 -0.00506847 1 0 1 1 0 0 +EDGE2 1439 1438 -0.990099 -0.0131808 -0.00493333 1 0 1 1 0 0 +EDGE2 1439 1418 -1.06558 -0.0106914 -0.0209555 1 0 1 1 0 0 +EDGE2 1440 1420 0.0610393 0.100228 -0.00422258 1 0 1 1 0 0 +EDGE2 1440 1400 0.0053484 -0.0331247 0.00392034 1 0 1 1 0 0 +EDGE2 1440 1421 0.0144177 0.950941 1.58763 1 0 1 1 0 0 +EDGE2 1440 1401 0.0268327 0.96357 1.56208 1 0 1 1 0 0 +EDGE2 1440 1419 -0.951733 0.0764858 -0.000484885 1 0 1 1 0 0 +EDGE2 1440 1439 -0.993694 0.0061807 -0.0193929 1 0 1 1 0 0 +EDGE2 1440 1399 -1.00402 0.00662138 -0.0106126 1 0 1 1 0 0 +EDGE2 1441 1422 1.00761 -0.0793607 -0.0183926 1 0 1 1 0 0 +EDGE2 1441 1420 -0.959345 -0.0302215 -1.57421 1 0 1 1 0 0 +EDGE2 1441 1440 -0.966801 0.0641459 -1.5747 1 0 1 1 0 0 +EDGE2 1441 1400 -1.00563 0.00691543 -1.58316 1 0 1 1 0 0 +EDGE2 1441 1421 0.0145529 0.00963328 -0.0371885 1 0 1 1 0 0 +EDGE2 1441 1401 0.00383964 -0.0250168 -0.0203657 1 0 1 1 0 0 +EDGE2 1441 1402 0.991091 -0.0243981 0.0376495 1 0 1 1 0 0 +EDGE2 1442 1422 0.0016409 -0.0109985 -0.0106503 1 0 1 1 0 0 +EDGE2 1442 1421 -1.02305 0.0740068 0.0107457 1 0 1 1 0 0 +EDGE2 1442 1441 -1.01773 -0.0148015 -0.0351793 1 0 1 1 0 0 +EDGE2 1442 1401 -1.01783 0.00544769 0.00625273 1 0 1 1 0 0 +EDGE2 1442 1423 1.09905 0.0639859 -0.00827853 1 0 1 1 0 0 +EDGE2 1442 1402 -0.0418372 0.0257429 -0.0115882 1 0 1 1 0 0 +EDGE2 1442 1403 1.01829 0.0200915 -0.0515216 1 0 1 1 0 0 +EDGE2 1443 1422 -0.94146 0.0594625 -0.00418781 1 0 1 1 0 0 +EDGE2 1443 1442 -1.05926 -0.051974 -0.00985434 1 0 1 1 0 0 +EDGE2 1443 1423 0.00998992 -0.0705581 -0.00582875 1 0 1 1 0 0 +EDGE2 1443 1402 -1.01725 0.0418858 -0.00058508 1 0 1 1 0 0 +EDGE2 1443 1424 1.01025 -0.0197274 -0.0206359 1 0 1 1 0 0 +EDGE2 1443 1403 -0.00836615 -0.0206752 -0.000790697 1 0 1 1 0 0 +EDGE2 1443 1404 0.999804 0.030764 -0.00217182 1 0 1 1 0 0 +EDGE2 1444 1423 -0.990644 0.0573816 -0.0147483 1 0 1 1 0 0 +EDGE2 1444 1443 -0.951547 -0.0368273 0.0113029 1 0 1 1 0 0 +EDGE2 1444 1425 1.02407 0.0517736 0.00122166 1 0 1 1 0 0 +EDGE2 1444 1424 -0.0357991 -0.0451129 0.0277591 1 0 1 1 0 0 +EDGE2 1444 1403 -1.06242 0.0312884 0.00495345 1 0 1 1 0 0 +EDGE2 1444 1404 -0.0383649 0.00593117 0.0117277 1 0 1 1 0 0 +EDGE2 1444 1405 0.96633 -0.0495388 0.0146108 1 0 1 1 0 0 +EDGE2 1445 1425 -0.039544 -0.00392778 -0.0170054 1 0 1 1 0 0 +EDGE2 1445 1424 -1.03837 0.048822 0.00245508 1 0 1 1 0 0 +EDGE2 1445 1444 -0.970755 -0.00514329 0.0216378 1 0 1 1 0 0 +EDGE2 1445 1404 -0.953685 -0.0129753 -0.0373018 1 0 1 1 0 0 +EDGE2 1445 1405 0.130496 -0.00628971 -0.0216959 1 0 1 1 0 0 +EDGE2 1445 1426 0.00226478 1.02787 1.60333 1 0 1 1 0 0 +EDGE2 1445 1406 0.0359525 0.979474 1.57403 1 0 1 1 0 0 +EDGE2 1446 1425 -1.09221 0.0738035 -1.58195 1 0 1 1 0 0 +EDGE2 1446 1445 -1.03228 0.0282603 -1.58961 1 0 1 1 0 0 +EDGE2 1446 1405 -0.97903 -0.00767078 -1.57669 1 0 1 1 0 0 +EDGE2 1446 1426 -0.0466636 -0.0644427 -0.046166 1 0 1 1 0 0 +EDGE2 1446 1406 0.0219177 0.0778148 0.0156409 1 0 1 1 0 0 +EDGE2 1446 1427 1.03002 -0.00908111 -0.000255576 1 0 1 1 0 0 +EDGE2 1446 1407 0.98644 0.0750513 0.00201343 1 0 1 1 0 0 +EDGE2 1447 1426 -1.00175 0.0270809 0.00268331 1 0 1 1 0 0 +EDGE2 1447 1446 -1.02515 -0.104543 -0.00595696 1 0 1 1 0 0 +EDGE2 1447 1406 -1.01613 -0.0322862 -0.0017824 1 0 1 1 0 0 +EDGE2 1447 1427 0.00839241 0.0290578 0.0310686 1 0 1 1 0 0 +EDGE2 1447 1407 -0.0533239 0.0234152 0.0337634 1 0 1 1 0 0 +EDGE2 1447 1428 0.976701 -0.00971964 0.00843971 1 0 1 1 0 0 +EDGE2 1447 1408 1.04934 -0.0619349 -0.0334817 1 0 1 1 0 0 +EDGE2 1448 1427 -1.0235 -0.0115406 0.00284483 1 0 1 1 0 0 +EDGE2 1448 1447 -1.0258 -0.121594 -0.00256067 1 0 1 1 0 0 +EDGE2 1448 1407 -1.02679 -0.0599981 -0.0200526 1 0 1 1 0 0 +EDGE2 1448 1428 -0.133699 -0.00269992 -0.0295002 1 0 1 1 0 0 +EDGE2 1448 1408 -0.0521084 0.0263955 -0.00974242 1 0 1 1 0 0 +EDGE2 1448 1429 1.01133 0.0377233 0.00599614 1 0 1 1 0 0 +EDGE2 1448 1409 1.02124 -0.0384333 -0.0241879 1 0 1 1 0 0 +EDGE2 1449 1428 -0.966149 0.0121067 0.0193942 1 0 1 1 0 0 +EDGE2 1449 1448 -0.93826 -0.0580755 -0.00568555 1 0 1 1 0 0 +EDGE2 1449 1408 -0.985445 -0.0176348 -0.0214872 1 0 1 1 0 0 +EDGE2 1449 1429 -0.0606425 0.0353216 0.0135928 1 0 1 1 0 0 +EDGE2 1449 1409 0.058242 -0.0348412 -0.00709394 1 0 1 1 0 0 +EDGE2 1449 1390 1.0875 0.0538165 -3.1343 1 0 1 1 0 0 +EDGE2 1449 1410 1.02833 0.094118 -0.00177337 1 0 1 1 0 0 +EDGE2 1449 1430 0.981959 -0.0574138 -0.00541794 1 0 1 1 0 0 +EDGE2 1450 1429 -0.994057 -0.0127088 0.00877562 1 0 1 1 0 0 +EDGE2 1450 1449 -1.0545 0.00369397 -0.0145408 1 0 1 1 0 0 +EDGE2 1450 1409 -1.00664 -0.0576477 0.0096285 1 0 1 1 0 0 +EDGE2 1450 1391 -0.0144596 1.07443 1.5588 1 0 1 1 0 0 +EDGE2 1450 1411 -0.0102173 0.997255 1.58788 1 0 1 1 0 0 +EDGE2 1450 1431 -0.0603176 0.923885 1.60186 1 0 1 1 0 0 +EDGE2 1450 1390 -0.0939015 -0.0170977 -3.15271 1 0 1 1 0 0 +EDGE2 1450 1410 0.00272003 -0.0445664 0.00733956 1 0 1 1 0 0 +EDGE2 1450 1430 0.188776 -0.00547713 0.00831065 1 0 1 1 0 0 +EDGE2 1450 1389 1.04346 -0.0690771 -3.13711 1 0 1 1 0 0 +EDGE2 1451 1432 1.01112 0.0158725 0.00206386 1 0 1 1 0 0 +EDGE2 1451 1392 1.00372 0.00178802 0.0098921 1 0 1 1 0 0 +EDGE2 1451 1412 0.975696 -0.0408669 0.0187743 1 0 1 1 0 0 +EDGE2 1451 1450 -0.979951 -0.0370772 -1.54764 1 0 1 1 0 0 +EDGE2 1451 1391 -0.0380789 -0.0189009 -0.0193612 1 0 1 1 0 0 +EDGE2 1451 1411 -0.0945491 -0.0632134 -0.0195496 1 0 1 1 0 0 +EDGE2 1451 1431 0.0639935 -0.041385 -0.0346729 1 0 1 1 0 0 +EDGE2 1451 1390 -1.00092 0.0452582 1.54288 1 0 1 1 0 0 +EDGE2 1451 1410 -1.11316 -0.0141491 -1.58235 1 0 1 1 0 0 +EDGE2 1451 1430 -0.964461 -0.00996794 -1.55728 1 0 1 1 0 0 +EDGE2 1452 1451 -0.963168 0.0642619 -0.00298169 1 0 1 1 0 0 +EDGE2 1452 1433 1.16092 -0.0257638 -0.0138811 1 0 1 1 0 0 +EDGE2 1452 1432 0.0595954 0.0242095 0.025111 1 0 1 1 0 0 +EDGE2 1452 1393 0.95748 -0.107475 -0.0178845 1 0 1 1 0 0 +EDGE2 1452 1413 1.0051 0.037234 0.00823419 1 0 1 1 0 0 +EDGE2 1452 1392 -0.0809704 0.0259018 -0.0460732 1 0 1 1 0 0 +EDGE2 1452 1412 0.0251018 -0.0045393 0.0128932 1 0 1 1 0 0 +EDGE2 1452 1391 -1.01649 0.0261694 -0.0145 1 0 1 1 0 0 +EDGE2 1452 1411 -1.00513 -0.0466797 -0.00270675 1 0 1 1 0 0 +EDGE2 1452 1431 -1.0266 -0.101842 0.043689 1 0 1 1 0 0 +EDGE2 1453 1433 -0.0653559 0.0123233 0.0136941 1 0 1 1 0 0 +EDGE2 1453 1434 0.999952 -0.0674294 0.00488594 1 0 1 1 0 0 +EDGE2 1453 1394 0.968669 -0.0317601 0.00486547 1 0 1 1 0 0 +EDGE2 1453 1414 1.061 -0.0255017 0.0462007 1 0 1 1 0 0 +EDGE2 1453 1432 -1.00518 -0.0721908 0.00877087 1 0 1 1 0 0 +EDGE2 1453 1393 0.0335128 -0.0397498 -0.00966472 1 0 1 1 0 0 +EDGE2 1453 1413 0.0793236 0.0072354 0.000727376 1 0 1 1 0 0 +EDGE2 1453 1452 -0.976097 0.0163926 0.0366382 1 0 1 1 0 0 +EDGE2 1453 1392 -1.06543 0.0626283 -0.0325124 1 0 1 1 0 0 +EDGE2 1453 1412 -1.06422 0.015575 0.00312972 1 0 1 1 0 0 +EDGE2 1454 1435 0.98579 0.00323905 0.00277697 1 0 1 1 0 0 +EDGE2 1454 1433 -1.10612 -0.0165811 0.00127847 1 0 1 1 0 0 +EDGE2 1454 1434 0.0263016 -0.0598339 0.0188309 1 0 1 1 0 0 +EDGE2 1454 1395 1.05013 -0.0462893 0.0252744 1 0 1 1 0 0 +EDGE2 1454 1415 0.880036 0.0525337 0.021577 1 0 1 1 0 0 +EDGE2 1454 1394 -0.0015872 -0.0121929 -0.00949182 1 0 1 1 0 0 +EDGE2 1454 1414 0.0362545 -0.00959178 0.0268519 1 0 1 1 0 0 +EDGE2 1454 1453 -0.923971 -0.0405206 -0.0252663 1 0 1 1 0 0 +EDGE2 1454 1393 -1.17012 -0.14967 0.0388214 1 0 1 1 0 0 +EDGE2 1454 1413 -1.01516 -0.0221861 0.00803145 1 0 1 1 0 0 +EDGE2 1455 1435 0.0451709 -0.00968431 0.00492025 1 0 1 1 0 0 +EDGE2 1455 1416 0.0198009 1.08985 1.57581 1 0 1 1 0 0 +EDGE2 1455 1436 0.0327616 1.16443 1.54337 1 0 1 1 0 0 +EDGE2 1455 1396 0.0147145 1.02118 1.56011 1 0 1 1 0 0 +EDGE2 1455 1434 -1.008 0.0719912 0.015671 1 0 1 1 0 0 +EDGE2 1455 1395 0.0261442 -0.0103065 -0.0206529 1 0 1 1 0 0 +EDGE2 1455 1415 0.0213857 -0.0817363 -0.0156583 1 0 1 1 0 0 +EDGE2 1455 1454 -0.976802 0.0131998 -0.0194688 1 0 1 1 0 0 +EDGE2 1455 1394 -1.0707 -0.000889939 -0.0172369 1 0 1 1 0 0 +EDGE2 1455 1414 -0.989037 -0.0205396 0.0116914 1 0 1 1 0 0 +EDGE2 1456 1435 -1.01033 -0.06476 1.55398 1 0 1 1 0 0 +EDGE2 1456 1455 -0.925906 0.0041833 1.57752 1 0 1 1 0 0 +EDGE2 1456 1395 -1.00605 -0.0169842 1.55414 1 0 1 1 0 0 +EDGE2 1456 1415 -0.946212 0.082494 1.5543 1 0 1 1 0 0 +EDGE2 1457 1456 -0.934021 0.0411462 0.0240927 1 0 1 1 0 0 +EDGE2 1458 1457 -1.00197 -0.053531 -0.0501063 1 0 1 1 0 0 +EDGE2 1459 1458 -1.00651 0.0423305 -0.0109674 1 0 1 1 0 0 +EDGE2 1460 1459 -1.10742 0.029416 0.00997911 1 0 1 1 0 0 +EDGE2 1461 1460 -0.975895 -0.0638793 1.57495 1 0 1 1 0 0 +EDGE2 1462 1461 -1.03826 0.0330489 -0.0146662 1 0 1 1 0 0 +EDGE2 1463 1462 -0.990055 0.00411477 -0.00710688 1 0 1 1 0 0 +EDGE2 1464 1463 -0.948641 0.0441538 -0.0330818 1 0 1 1 0 0 +EDGE2 1464 1385 0.998296 -0.00126853 -3.14649 1 0 1 1 0 0 +EDGE2 1465 1386 -0.135297 -1.00182 -1.58095 1 0 1 1 0 0 +EDGE2 1465 1464 -1.00043 -0.097872 0.0269186 1 0 1 1 0 0 +EDGE2 1465 1385 0.0162934 -0.0451138 -3.14271 1 0 1 1 0 0 +EDGE2 1465 1384 0.978255 -0.0323176 -3.17623 1 0 1 1 0 0 +EDGE2 1466 1385 -0.978773 -0.0156858 1.57299 1 0 1 1 0 0 +EDGE2 1466 1465 -1.0008 0.0061414 -1.55412 1 0 1 1 0 0 +EDGE2 1467 1466 -0.982991 -0.00642121 -0.00846475 1 0 1 1 0 0 +EDGE2 1468 1467 -0.935436 -0.0985475 -0.0171448 1 0 1 1 0 0 +EDGE2 1469 1468 -1.01442 0.103587 0.0217626 1 0 1 1 0 0 +EDGE2 1469 1370 1.12327 -0.0542387 -3.14604 1 0 1 1 0 0 +EDGE2 1470 1469 -1.06557 0.0516219 0.0139888 1 0 1 1 0 0 +EDGE2 1470 1370 -0.00931647 -0.125727 -3.14938 1 0 1 1 0 0 +EDGE2 1470 1371 -0.0493432 -0.966014 -1.55415 1 0 1 1 0 0 +EDGE2 1470 1369 1.01137 0.136325 -3.15014 1 0 1 1 0 0 +EDGE2 1471 1470 -1.15729 0.0402897 -1.59325 1 0 1 1 0 0 +EDGE2 1471 1370 -0.912769 0.0532937 1.60857 1 0 1 1 0 0 +EDGE2 1472 1471 -0.997481 0.0769557 -0.0225578 1 0 1 1 0 0 +EDGE2 1473 1472 -1.02694 0.0392098 0.00184765 1 0 1 1 0 0 +EDGE2 1474 1473 -0.995158 0.0270905 0.00290354 1 0 1 1 0 0 +EDGE2 1475 1474 -0.917806 -0.0729607 -0.0118978 1 0 1 1 0 0 +EDGE2 1476 1475 -0.940316 -0.0602826 1.57592 1 0 1 1 0 0 +EDGE2 1477 1476 -1.00532 0.0467327 -0.00914547 1 0 1 1 0 0 +EDGE2 1478 1477 -0.941142 -0.0297715 0.0310275 1 0 1 1 0 0 +EDGE2 1479 1478 -0.989199 0.0328251 0.0106019 1 0 1 1 0 0 +EDGE2 1479 1360 1.03465 0.0485249 -3.11663 1 0 1 1 0 0 +EDGE2 1479 1340 0.864841 -0.0499372 -3.14668 1 0 1 1 0 0 +EDGE2 1480 1360 0.0881081 0.00732066 -3.11534 1 0 1 1 0 0 +EDGE2 1480 1479 -0.996629 0.00654223 0.0107694 1 0 1 1 0 0 +EDGE2 1480 1340 -0.0475778 -0.0268024 -3.13994 1 0 1 1 0 0 +EDGE2 1480 1341 -0.0238054 -0.953005 -1.58377 1 0 1 1 0 0 +EDGE2 1480 1361 -0.031133 -0.999395 -1.58051 1 0 1 1 0 0 +EDGE2 1480 1359 1.06286 -0.0971957 -3.1371 1 0 1 1 0 0 +EDGE2 1480 1339 0.922558 0.0279759 -3.13693 1 0 1 1 0 0 +EDGE2 1481 1360 -1.02619 0.00667421 -1.58607 1 0 1 1 0 0 +EDGE2 1481 1480 -0.95742 -0.0699437 1.59137 1 0 1 1 0 0 +EDGE2 1481 1340 -1.04578 -0.0516835 -1.55078 1 0 1 1 0 0 +EDGE2 1481 1341 0.0877786 0.0214267 0.0485011 1 0 1 1 0 0 +EDGE2 1481 1361 0.0405758 -0.0278559 0.0144046 1 0 1 1 0 0 +EDGE2 1481 1342 0.984593 0.029347 -0.00595053 1 0 1 1 0 0 +EDGE2 1481 1362 0.888675 -0.110708 0.00711509 1 0 1 1 0 0 +EDGE2 1482 1481 -0.91361 -0.0147872 -0.0149159 1 0 1 1 0 0 +EDGE2 1482 1341 -1.04603 0.021455 0.0238936 1 0 1 1 0 0 +EDGE2 1482 1361 -0.986815 -0.0672935 0.00707003 1 0 1 1 0 0 +EDGE2 1482 1342 0.0719496 0.0305393 -0.00313778 1 0 1 1 0 0 +EDGE2 1482 1362 -0.0129005 -0.0540676 -0.0100062 1 0 1 1 0 0 +EDGE2 1482 1363 0.961012 0.0116366 -0.0350238 1 0 1 1 0 0 +EDGE2 1482 1343 1.02497 0.0440075 0.0167483 1 0 1 1 0 0 +EDGE2 1483 1342 -0.996979 0.0187549 -0.0408229 1 0 1 1 0 0 +EDGE2 1483 1362 -1.05038 -0.0257098 -0.0209761 1 0 1 1 0 0 +EDGE2 1483 1482 -1.04089 -0.0767666 0.0161934 1 0 1 1 0 0 +EDGE2 1483 1363 -0.0499466 -0.0368713 -0.00147964 1 0 1 1 0 0 +EDGE2 1483 1343 0.04333 0.00274031 0.0154039 1 0 1 1 0 0 +EDGE2 1483 1344 0.995913 -0.0911829 0.0333302 1 0 1 1 0 0 +EDGE2 1483 1364 1.00275 0.044654 0.0190997 1 0 1 1 0 0 +EDGE2 1484 1345 0.924374 -0.0327527 -0.000457382 1 0 1 1 0 0 +EDGE2 1484 1363 -0.978037 -0.0353071 0.0159152 1 0 1 1 0 0 +EDGE2 1484 1483 -0.92903 0.0268831 -0.0201811 1 0 1 1 0 0 +EDGE2 1484 1343 -0.998358 0.0590811 0.0135277 1 0 1 1 0 0 +EDGE2 1484 1344 -0.071825 0.0337738 -0.0229687 1 0 1 1 0 0 +EDGE2 1484 1364 -0.0263768 0.00692072 -0.00287641 1 0 1 1 0 0 +EDGE2 1484 1365 0.978305 -0.0523701 0.00784062 1 0 1 1 0 0 +EDGE2 1484 1325 0.968239 0.099999 -3.13308 1 0 1 1 0 0 +EDGE2 1485 1345 -0.0148392 -0.0373513 0.000294961 1 0 1 1 0 0 +EDGE2 1485 1366 0.133906 -0.947632 -1.5602 1 0 1 1 0 0 +EDGE2 1485 1344 -0.981517 -0.0687294 0.00186234 1 0 1 1 0 0 +EDGE2 1485 1484 -1.02717 0.0437295 0.014048 1 0 1 1 0 0 +EDGE2 1485 1364 -0.996191 0.0903753 0.0137956 1 0 1 1 0 0 +EDGE2 1485 1365 -0.0677235 -0.0175548 -0.0510388 1 0 1 1 0 0 +EDGE2 1485 1325 0.0392124 -0.0261567 -3.15894 1 0 1 1 0 0 +EDGE2 1485 1324 1.09134 -0.0483739 -3.14697 1 0 1 1 0 0 +EDGE2 1485 1326 -0.0151049 0.976352 1.56762 1 0 1 1 0 0 +EDGE2 1485 1346 0.0836309 0.901271 1.56353 1 0 1 1 0 0 +EDGE2 1486 1345 -0.955553 0.0358454 -1.56577 1 0 1 1 0 0 +EDGE2 1486 1485 -1.02155 -0.0215253 -1.59164 1 0 1 1 0 0 +EDGE2 1486 1365 -1.03523 -0.0421213 -1.53225 1 0 1 1 0 0 +EDGE2 1486 1325 -1.06877 0.00230485 1.55366 1 0 1 1 0 0 +EDGE2 1486 1327 0.981786 -0.00526716 -0.0404644 1 0 1 1 0 0 +EDGE2 1486 1326 0.0159369 0.0348503 -0.00800128 1 0 1 1 0 0 +EDGE2 1486 1346 -0.00520987 0.000500701 0.0142329 1 0 1 1 0 0 +EDGE2 1486 1347 1.02565 -0.0113978 0.00106761 1 0 1 1 0 0 +EDGE2 1487 1327 0.0359206 -0.00884684 -0.000398893 1 0 1 1 0 0 +EDGE2 1487 1486 -0.888348 0.0798109 0.00805023 1 0 1 1 0 0 +EDGE2 1487 1326 -0.97444 -0.0221509 0.0204537 1 0 1 1 0 0 +EDGE2 1487 1346 -1.04768 0.0470469 -0.0128215 1 0 1 1 0 0 +EDGE2 1487 1347 -0.00294071 0.0905017 0.0171303 1 0 1 1 0 0 +EDGE2 1487 1348 1.0069 -0.00352116 0.0164423 1 0 1 1 0 0 +EDGE2 1487 1328 1.02483 -0.00216996 -0.0286887 1 0 1 1 0 0 +EDGE2 1488 1327 -0.920626 0.0191356 -0.0126988 1 0 1 1 0 0 +EDGE2 1488 1487 -0.936826 -0.0023147 -0.0186652 1 0 1 1 0 0 +EDGE2 1488 1347 -0.983847 0.0743785 0.0634151 1 0 1 1 0 0 +EDGE2 1488 1348 -0.0616318 -0.00825476 0.0355534 1 0 1 1 0 0 +EDGE2 1488 1328 0.0423008 0.0320478 0.0101801 1 0 1 1 0 0 +EDGE2 1488 1349 1.07888 0.0228671 0.00897162 1 0 1 1 0 0 +EDGE2 1488 1329 0.966647 -0.0245744 -0.00267182 1 0 1 1 0 0 +EDGE2 1489 1348 -1.09413 -0.00821366 -0.0232869 1 0 1 1 0 0 +EDGE2 1489 1488 -0.912992 0.0550606 -0.0117738 1 0 1 1 0 0 +EDGE2 1489 1328 -0.998652 0.0669824 0.00103163 1 0 1 1 0 0 +EDGE2 1489 1349 0.00555756 -0.0930914 -0.00412938 1 0 1 1 0 0 +EDGE2 1489 1329 0.0125033 -0.0233323 -0.0268922 1 0 1 1 0 0 +EDGE2 1489 1330 0.955778 -0.0698191 -0.0184421 1 0 1 1 0 0 +EDGE2 1489 1350 0.931622 -0.070517 -0.0233207 1 0 1 1 0 0 +EDGE2 1490 1349 -0.959938 0.0207453 -0.0310064 1 0 1 1 0 0 +EDGE2 1490 1489 -1.02207 -0.0210836 0.016373 1 0 1 1 0 0 +EDGE2 1490 1329 -1.10368 -0.0540824 0.0264731 1 0 1 1 0 0 +EDGE2 1490 1331 0.0067316 1.03047 1.59226 1 0 1 1 0 0 +EDGE2 1490 1351 -0.0335636 0.9118 1.60751 1 0 1 1 0 0 +EDGE2 1490 1330 0.0164201 -0.0217046 -0.0160382 1 0 1 1 0 0 +EDGE2 1490 1350 0.0130894 -0.0361681 0.00193 1 0 1 1 0 0 +EDGE2 1491 1352 0.958482 -0.0653974 0.0121837 1 0 1 1 0 0 +EDGE2 1491 1332 1.06832 0.0870172 -0.0205165 1 0 1 1 0 0 +EDGE2 1491 1331 -0.0477742 -0.0789088 0.0168827 1 0 1 1 0 0 +EDGE2 1491 1351 -0.0156028 -0.0497276 0.0231173 1 0 1 1 0 0 +EDGE2 1491 1330 -0.965963 0.127309 -1.54301 1 0 1 1 0 0 +EDGE2 1491 1350 -0.999658 -0.064361 -1.60192 1 0 1 1 0 0 +EDGE2 1491 1490 -0.939311 0.0469591 -1.55539 1 0 1 1 0 0 +EDGE2 1492 1333 1.05167 -0.0616073 0.0465015 1 0 1 1 0 0 +EDGE2 1492 1353 0.975749 -0.0167683 -0.00336271 1 0 1 1 0 0 +EDGE2 1492 1352 -0.0355625 -0.0261774 0.0225897 1 0 1 1 0 0 +EDGE2 1492 1332 0.0233501 -0.0581717 -0.0261522 1 0 1 1 0 0 +EDGE2 1492 1331 -0.932736 0.0446262 0.0200266 1 0 1 1 0 0 +EDGE2 1492 1351 -0.98367 0.0675931 -0.021885 1 0 1 1 0 0 +EDGE2 1492 1491 -1.00512 0.0639153 -0.00606975 1 0 1 1 0 0 +EDGE2 1493 1333 -0.0376768 0.00681894 0.00810843 1 0 1 1 0 0 +EDGE2 1493 1334 0.980552 -0.0179406 0.0378755 1 0 1 1 0 0 +EDGE2 1493 1354 1.05156 -0.0655653 0.00578074 1 0 1 1 0 0 +EDGE2 1493 1353 -0.0301483 0.0337579 -0.0141994 1 0 1 1 0 0 +EDGE2 1493 1352 -0.996734 -0.0172622 0.0124988 1 0 1 1 0 0 +EDGE2 1493 1492 -1.01111 0.0263373 0.0126501 1 0 1 1 0 0 +EDGE2 1493 1332 -0.987738 0.0497119 0.00501922 1 0 1 1 0 0 +EDGE2 1494 1333 -1.05693 0.0270731 0.0326382 1 0 1 1 0 0 +EDGE2 1494 1493 -1.03967 0.0813074 -0.000268309 1 0 1 1 0 0 +EDGE2 1494 1355 0.918136 -0.0149375 -0.0252615 1 0 1 1 0 0 +EDGE2 1494 1335 1.01501 0.0380009 -0.0173773 1 0 1 1 0 0 +EDGE2 1494 1334 0.0269822 -0.036596 -0.0132978 1 0 1 1 0 0 +EDGE2 1494 1354 0.0224767 0.0686616 -0.00576691 1 0 1 1 0 0 +EDGE2 1494 1353 -1.01825 0.039288 -0.00636481 1 0 1 1 0 0 +EDGE2 1495 1336 -0.0477545 0.926352 1.58237 1 0 1 1 0 0 +EDGE2 1495 1356 -0.049979 1.00646 1.58513 1 0 1 1 0 0 +EDGE2 1495 1355 0.102724 0.0222962 0.0423483 1 0 1 1 0 0 +EDGE2 1495 1335 -0.0166103 0.0225727 0.036262 1 0 1 1 0 0 +EDGE2 1495 1334 -1.03644 -0.0528309 0.0334762 1 0 1 1 0 0 +EDGE2 1495 1354 -1.11433 0.068033 0.0122736 1 0 1 1 0 0 +EDGE2 1495 1494 -0.980752 0.0875295 -0.00686417 1 0 1 1 0 0 +EDGE2 1496 1336 -0.0260534 0.0352746 -0.00972498 1 0 1 1 0 0 +EDGE2 1496 1357 0.98505 -0.0245662 0.00772981 1 0 1 1 0 0 +EDGE2 1496 1337 1.0745 0.104818 0.00615317 1 0 1 1 0 0 +EDGE2 1496 1356 -0.047732 -0.0873635 -0.0356753 1 0 1 1 0 0 +EDGE2 1496 1355 -1.0333 0.079494 -1.56047 1 0 1 1 0 0 +EDGE2 1496 1495 -1.03506 -0.027641 -1.57802 1 0 1 1 0 0 +EDGE2 1496 1335 -0.989876 -0.0654147 -1.54963 1 0 1 1 0 0 +EDGE2 1497 1336 -0.973776 0.0463971 -0.00368008 1 0 1 1 0 0 +EDGE2 1497 1358 1.02134 0.0314591 0.00570226 1 0 1 1 0 0 +EDGE2 1497 1338 1.006 0.00234409 -0.000166383 1 0 1 1 0 0 +EDGE2 1497 1357 -0.141503 0.00509374 -0.0286266 1 0 1 1 0 0 +EDGE2 1497 1337 0.00572465 -0.0230369 -0.0101363 1 0 1 1 0 0 +EDGE2 1497 1496 -1.00932 0.0471224 -0.00538576 1 0 1 1 0 0 +EDGE2 1497 1356 -0.974671 0.0485606 0.0215234 1 0 1 1 0 0 +EDGE2 1498 1359 0.966864 0.00429312 0.00759932 1 0 1 1 0 0 +EDGE2 1498 1339 1.08369 -0.103074 0.00284703 1 0 1 1 0 0 +EDGE2 1498 1358 -0.0608617 0.0194759 -0.00283589 1 0 1 1 0 0 +EDGE2 1498 1338 0.0217097 0.102207 0.0159411 1 0 1 1 0 0 +EDGE2 1498 1357 -0.90733 -0.0311293 0.0426723 1 0 1 1 0 0 +EDGE2 1498 1497 -1.03306 -0.0422975 -0.0245196 1 0 1 1 0 0 +EDGE2 1498 1337 -0.973401 0.0133753 0.0289678 1 0 1 1 0 0 +EDGE2 1499 1360 0.965155 0.0486708 0.0133557 1 0 1 1 0 0 +EDGE2 1499 1480 0.943156 -0.0601599 -3.14017 1 0 1 1 0 0 +EDGE2 1499 1340 1.02552 -0.0535392 -0.00497061 1 0 1 1 0 0 +EDGE2 1499 1359 -0.0363009 -0.0615293 0.00792173 1 0 1 1 0 0 +EDGE2 1499 1339 0.00215867 -0.0985262 -0.0112006 1 0 1 1 0 0 +EDGE2 1499 1358 -1.04795 -0.0748567 -0.0412958 1 0 1 1 0 0 +EDGE2 1499 1498 -0.981609 -0.0285085 -0.00770723 1 0 1 1 0 0 +EDGE2 1499 1338 -0.994569 -0.0737452 -0.00530188 1 0 1 1 0 0 +EDGE2 1500 1360 0.0940535 0.0283402 -0.00344168 1 0 1 1 0 0 +EDGE2 1500 1479 1.01143 0.0226888 -3.12088 1 0 1 1 0 0 +EDGE2 1500 1480 -0.0708359 -0.060186 -3.1487 1 0 1 1 0 0 +EDGE2 1500 1481 0.00640743 0.936497 1.56124 1 0 1 1 0 0 +EDGE2 1500 1340 -0.0147448 0.0432959 -0.00578344 1 0 1 1 0 0 +EDGE2 1500 1341 0.0362334 1.04743 1.56817 1 0 1 1 0 0 +EDGE2 1500 1361 -0.0728754 0.920944 1.54224 1 0 1 1 0 0 +EDGE2 1500 1359 -1.05061 -0.0551713 -0.0285484 1 0 1 1 0 0 +EDGE2 1500 1499 -1.00937 0.000769307 -0.0287457 1 0 1 1 0 0 +EDGE2 1500 1339 -1.11738 0.0217309 -0.011516 1 0 1 1 0 0 +EDGE2 1501 1360 -1.07751 -0.00720671 -1.53271 1 0 1 1 0 0 +EDGE2 1501 1500 -1.00389 0.00644942 -1.55994 1 0 1 1 0 0 +EDGE2 1501 1480 -1.00881 0.00496088 1.56066 1 0 1 1 0 0 +EDGE2 1501 1481 -0.00814676 -0.08553 0.022699 1 0 1 1 0 0 +EDGE2 1501 1340 -0.994072 0.0179393 -1.58852 1 0 1 1 0 0 +EDGE2 1501 1341 0.110726 -0.0195533 -0.00431811 1 0 1 1 0 0 +EDGE2 1501 1361 0.0343326 -0.0181183 0.0366241 1 0 1 1 0 0 +EDGE2 1501 1342 0.962596 0.0240717 0.0200572 1 0 1 1 0 0 +EDGE2 1501 1362 0.932447 0.0500748 -0.0028643 1 0 1 1 0 0 +EDGE2 1501 1482 0.916326 -0.00979606 -0.00912266 1 0 1 1 0 0 +EDGE2 1502 1481 -1.05443 -0.0502985 -0.00284885 1 0 1 1 0 0 +EDGE2 1502 1501 -0.92481 0.0563628 0.0505267 1 0 1 1 0 0 +EDGE2 1502 1341 -1.00706 -0.0229934 0.0153553 1 0 1 1 0 0 +EDGE2 1502 1361 -0.936004 -0.0632356 -0.0115893 1 0 1 1 0 0 +EDGE2 1502 1342 0.00388723 0.0218902 0.0123619 1 0 1 1 0 0 +EDGE2 1502 1362 -0.0411176 -0.0283064 6.47829e-05 1 0 1 1 0 0 +EDGE2 1502 1482 -0.012078 0.0239517 -0.0178174 1 0 1 1 0 0 +EDGE2 1502 1363 1.02585 0.0738546 -0.0374478 1 0 1 1 0 0 +EDGE2 1502 1483 0.925561 -0.0876588 -0.0267192 1 0 1 1 0 0 +EDGE2 1502 1343 1.04244 0.00167137 0.00937003 1 0 1 1 0 0 +EDGE2 1503 1502 -0.935115 0.0428508 0.0347835 1 0 1 1 0 0 +EDGE2 1503 1342 -1.002 -0.0222081 0.00557633 1 0 1 1 0 0 +EDGE2 1503 1362 -0.934706 -0.000253619 0.00497152 1 0 1 1 0 0 +EDGE2 1503 1482 -1.00277 0.0645663 -0.00582145 1 0 1 1 0 0 +EDGE2 1503 1363 -0.0102794 -0.000824727 0.00522998 1 0 1 1 0 0 +EDGE2 1503 1483 -0.00206825 -0.0164495 -0.0235056 1 0 1 1 0 0 +EDGE2 1503 1343 -0.0168369 0.0237579 -0.00679215 1 0 1 1 0 0 +EDGE2 1503 1344 0.962018 0.0189651 0.00790145 1 0 1 1 0 0 +EDGE2 1503 1484 1.0389 0.0392381 -0.0157686 1 0 1 1 0 0 +EDGE2 1503 1364 0.95638 0.0211102 0.0178891 1 0 1 1 0 0 +EDGE2 1504 1345 0.981902 0.0302395 -0.0196893 1 0 1 1 0 0 +EDGE2 1504 1363 -1.00411 0.0798513 -0.0138276 1 0 1 1 0 0 +EDGE2 1504 1483 -0.956395 0.00812948 0.0249197 1 0 1 1 0 0 +EDGE2 1504 1503 -1.01328 0.0318347 0.0108241 1 0 1 1 0 0 +EDGE2 1504 1343 -1.00184 -0.00364298 0.0120982 1 0 1 1 0 0 +EDGE2 1504 1344 -0.0814656 -0.0654313 -0.0137848 1 0 1 1 0 0 +EDGE2 1504 1484 -0.0174148 -0.000232011 0.02669 1 0 1 1 0 0 +EDGE2 1504 1364 -0.0901814 0.0135903 -0.0181016 1 0 1 1 0 0 +EDGE2 1504 1485 1.0559 0.0725422 -0.00169174 1 0 1 1 0 0 +EDGE2 1504 1365 1.0239 -0.0532863 0.0172962 1 0 1 1 0 0 +EDGE2 1504 1325 1.01199 0.0223378 -3.13477 1 0 1 1 0 0 +EDGE2 1505 1345 0.0221429 -0.055176 -0.00713296 1 0 1 1 0 0 +EDGE2 1505 1366 0.0491638 -1.03114 -1.57237 1 0 1 1 0 0 +EDGE2 1505 1344 -1.02543 0.0183303 -0.0110473 1 0 1 1 0 0 +EDGE2 1505 1484 -1.08978 -0.0136375 -0.0125342 1 0 1 1 0 0 +EDGE2 1505 1504 -0.994451 0.0212436 0.00626249 1 0 1 1 0 0 +EDGE2 1505 1364 -1.00022 -0.0315597 -0.00344204 1 0 1 1 0 0 +EDGE2 1505 1485 -0.012467 0.0190882 0.0402627 1 0 1 1 0 0 +EDGE2 1505 1365 0.0535655 -0.0609963 0.0121269 1 0 1 1 0 0 +EDGE2 1505 1325 0.0603812 -0.00415469 -3.14541 1 0 1 1 0 0 +EDGE2 1505 1324 1.0211 0.043827 -3.14647 1 0 1 1 0 0 +EDGE2 1505 1486 -0.0262201 1.03055 1.5861 1 0 1 1 0 0 +EDGE2 1505 1326 -0.0121192 1.04856 1.57068 1 0 1 1 0 0 +EDGE2 1505 1346 -0.0107154 1.03463 1.58316 1 0 1 1 0 0 +EDGE2 1506 1345 -1.07433 0.066254 1.56501 1 0 1 1 0 0 +EDGE2 1506 1367 1.01516 0.0373237 -0.0359723 1 0 1 1 0 0 +EDGE2 1506 1366 0.0080196 0.0566254 -0.0165966 1 0 1 1 0 0 +EDGE2 1506 1485 -0.960652 -0.0708724 1.59374 1 0 1 1 0 0 +EDGE2 1506 1505 -0.915255 -0.0153683 1.57964 1 0 1 1 0 0 +EDGE2 1506 1365 -0.995769 0.018498 1.57944 1 0 1 1 0 0 +EDGE2 1506 1325 -0.97048 0.072439 -1.54808 1 0 1 1 0 0 +EDGE2 1507 1368 0.951465 0.0219947 -0.0208616 1 0 1 1 0 0 +EDGE2 1507 1367 -0.0191345 0.106233 0.00609005 1 0 1 1 0 0 +EDGE2 1507 1366 -0.991659 -0.0235348 0.01272 1 0 1 1 0 0 +EDGE2 1507 1506 -1.00598 -0.0200634 -0.00131176 1 0 1 1 0 0 +EDGE2 1508 1369 0.990115 -0.00247705 -0.0238508 1 0 1 1 0 0 +EDGE2 1508 1368 -0.061406 0.0327937 0.00176321 1 0 1 1 0 0 +EDGE2 1508 1507 -0.99147 0.0188488 -0.00613596 1 0 1 1 0 0 +EDGE2 1508 1367 -1.04616 0.0579992 0.0146231 1 0 1 1 0 0 +EDGE2 1509 1470 1.04338 0.00189917 -3.143 1 0 1 1 0 0 +EDGE2 1509 1370 0.988178 -0.0131228 0.0174036 1 0 1 1 0 0 +EDGE2 1509 1369 0.0196663 -0.00117102 0.0307854 1 0 1 1 0 0 +EDGE2 1509 1368 -1.03256 -0.0254619 -0.0169731 1 0 1 1 0 0 +EDGE2 1509 1508 -0.990265 -0.0212123 0.0072172 1 0 1 1 0 0 +EDGE2 1510 1469 1.01867 -0.0127654 -3.15198 1 0 1 1 0 0 +EDGE2 1510 1471 0.00677882 -0.883929 -1.53711 1 0 1 1 0 0 +EDGE2 1510 1470 0.0490684 -0.0247903 -3.15756 1 0 1 1 0 0 +EDGE2 1510 1370 0.0372206 -0.0144359 0.0150519 1 0 1 1 0 0 +EDGE2 1510 1371 0.0638504 0.994942 1.57213 1 0 1 1 0 0 +EDGE2 1510 1509 -0.982784 0.0731365 0.00125014 1 0 1 1 0 0 +EDGE2 1510 1369 -0.967103 -0.0227948 0.0014741 1 0 1 1 0 0 +EDGE2 1511 1470 -1.01836 0.00317883 1.56301 1 0 1 1 0 0 +EDGE2 1511 1510 -0.97056 0.0678099 -1.58629 1 0 1 1 0 0 +EDGE2 1511 1370 -1.01502 -0.00263134 -1.574 1 0 1 1 0 0 +EDGE2 1511 1371 0.116009 -0.0425554 0.0148651 1 0 1 1 0 0 +EDGE2 1511 1372 1.02508 0.052457 -0.0482738 1 0 1 1 0 0 +EDGE2 1512 1371 -0.985809 0.00826469 -0.0205149 1 0 1 1 0 0 +EDGE2 1512 1511 -0.998266 -0.0228744 -0.0205707 1 0 1 1 0 0 +EDGE2 1512 1372 0.0509984 0.0419521 0.0412694 1 0 1 1 0 0 +EDGE2 1512 1373 1.03041 0.0478532 -0.0213181 1 0 1 1 0 0 +EDGE2 1513 1512 -0.941254 0.0512129 -1.53677e-05 1 0 1 1 0 0 +EDGE2 1513 1372 -0.958624 0.00409056 0.0447348 1 0 1 1 0 0 +EDGE2 1513 1373 0.0410752 0.0867794 -0.00256762 1 0 1 1 0 0 +EDGE2 1513 1374 1.0906 -0.00252837 0.000636272 1 0 1 1 0 0 +EDGE2 1514 1513 -1.04459 -0.0123558 -0.0204152 1 0 1 1 0 0 +EDGE2 1514 1373 -1.0957 -0.0104689 -0.0107647 1 0 1 1 0 0 +EDGE2 1514 1374 0.069011 0.102437 -0.0108635 1 0 1 1 0 0 +EDGE2 1514 1375 0.992392 -0.055003 0.0470783 1 0 1 1 0 0 +EDGE2 1515 1376 0.024495 -1.05402 -1.58285 1 0 1 1 0 0 +EDGE2 1515 1514 -0.975755 -0.128026 -0.0281808 1 0 1 1 0 0 +EDGE2 1515 1374 -1.10135 -0.0119401 0.0061743 1 0 1 1 0 0 +EDGE2 1515 1375 0.0015285 0.0283168 0.0113172 1 0 1 1 0 0 +EDGE2 1516 1375 -1.0479 -0.0883353 -1.57317 1 0 1 1 0 0 +EDGE2 1516 1515 -0.999956 -0.0385793 -1.55566 1 0 1 1 0 0 +EDGE2 1517 1516 -0.977512 0.00882926 -0.0034214 1 0 1 1 0 0 +EDGE2 1518 1517 -0.914197 -0.00773293 0.0100587 1 0 1 1 0 0 +EDGE2 1519 1518 -1.02851 0.0408228 -0.0146325 1 0 1 1 0 0 +EDGE2 1519 1320 0.990267 0.021558 -3.14036 1 0 1 1 0 0 +EDGE2 1520 1519 -1.00456 0.0403394 0.0390831 1 0 1 1 0 0 +EDGE2 1520 1321 0.00524749 1.0098 1.5383 1 0 1 1 0 0 +EDGE2 1520 1320 -0.0282394 -0.0276833 -3.14439 1 0 1 1 0 0 +EDGE2 1520 1319 0.938908 -0.0363837 -3.14333 1 0 1 1 0 0 +EDGE2 1521 1322 0.982557 0.0306852 -0.023203 1 0 1 1 0 0 +EDGE2 1521 1321 0.066982 0.0998144 0.0250399 1 0 1 1 0 0 +EDGE2 1521 1520 -1.04448 -0.0185516 -1.54253 1 0 1 1 0 0 +EDGE2 1521 1320 -1.01523 -0.0232885 1.54768 1 0 1 1 0 0 +EDGE2 1522 1323 0.95834 -0.075258 0.0074613 1 0 1 1 0 0 +EDGE2 1522 1322 -0.0572986 -0.0703495 0.0411268 1 0 1 1 0 0 +EDGE2 1522 1521 -0.977804 0.0590263 -0.0172258 1 0 1 1 0 0 +EDGE2 1522 1321 -1.1033 -0.0535047 0.0113406 1 0 1 1 0 0 +EDGE2 1523 1324 0.959414 0.0665134 -0.0343772 1 0 1 1 0 0 +EDGE2 1523 1323 -0.0443279 -0.00596574 -0.00481337 1 0 1 1 0 0 +EDGE2 1523 1322 -0.963096 -0.0346723 -0.00827909 1 0 1 1 0 0 +EDGE2 1523 1522 -0.963416 0.0709033 -0.0178535 1 0 1 1 0 0 +EDGE2 1524 1345 0.951752 0.0534083 -3.13151 1 0 1 1 0 0 +EDGE2 1524 1485 1.0157 -0.0229023 -3.17204 1 0 1 1 0 0 +EDGE2 1524 1505 0.94308 0.0340732 -3.14533 1 0 1 1 0 0 +EDGE2 1524 1365 0.994822 0.0753471 -3.12246 1 0 1 1 0 0 +EDGE2 1524 1325 1.09977 -0.00381359 0.00858704 1 0 1 1 0 0 +EDGE2 1524 1324 -0.0244919 -0.0149456 -0.00375653 1 0 1 1 0 0 +EDGE2 1524 1323 -1.00494 -0.00465708 0.000334254 1 0 1 1 0 0 +EDGE2 1524 1523 -0.956868 -0.106598 -0.01005 1 0 1 1 0 0 +EDGE2 1525 1345 0.0363695 -0.0549527 -3.14776 1 0 1 1 0 0 +EDGE2 1525 1366 -0.017025 0.938846 1.5474 1 0 1 1 0 0 +EDGE2 1525 1506 -0.0112932 1.00549 1.53718 1 0 1 1 0 0 +EDGE2 1525 1344 1.06701 -0.0220082 -3.16597 1 0 1 1 0 0 +EDGE2 1525 1484 0.972206 0.010041 -3.15952 1 0 1 1 0 0 +EDGE2 1525 1504 0.925764 -0.0635743 -3.15599 1 0 1 1 0 0 +EDGE2 1525 1364 1.00768 0.0751415 -3.13235 1 0 1 1 0 0 +EDGE2 1525 1485 0.0724216 -0.0418176 -3.132 1 0 1 1 0 0 +EDGE2 1525 1505 0.0435576 -5.63273e-05 -3.12828 1 0 1 1 0 0 +EDGE2 1525 1365 -0.023397 -0.045412 -3.15538 1 0 1 1 0 0 +EDGE2 1525 1325 -0.041704 0.030912 -0.00870859 1 0 1 1 0 0 +EDGE2 1525 1524 -1.03954 -0.0299968 0.00311977 1 0 1 1 0 0 +EDGE2 1525 1324 -0.990712 -0.0085255 -0.0233706 1 0 1 1 0 0 +EDGE2 1525 1486 -0.0756336 -1.06502 -1.54822 1 0 1 1 0 0 +EDGE2 1525 1326 -0.0278692 -0.920374 -1.60009 1 0 1 1 0 0 +EDGE2 1525 1346 0.0485097 -1.12721 -1.58891 1 0 1 1 0 0 +EDGE2 1526 1345 -0.938481 0.010962 1.55745 1 0 1 1 0 0 +EDGE2 1526 1507 0.949122 0.0138954 0.0363385 1 0 1 1 0 0 +EDGE2 1526 1367 1.02545 -0.00147962 -0.0369418 1 0 1 1 0 0 +EDGE2 1526 1366 -0.027827 0.050695 -0.0424398 1 0 1 1 0 0 +EDGE2 1526 1506 0.0598687 -0.0857334 -0.0131576 1 0 1 1 0 0 +EDGE2 1526 1525 -0.972444 0.181138 -1.55165 1 0 1 1 0 0 +EDGE2 1526 1485 -1.02121 0.000619006 1.58025 1 0 1 1 0 0 +EDGE2 1526 1505 -1.00995 -0.0220222 1.55756 1 0 1 1 0 0 +EDGE2 1526 1365 -0.982019 -0.00728277 1.62161 1 0 1 1 0 0 +EDGE2 1526 1325 -0.9808 0.0433953 -1.55117 1 0 1 1 0 0 +EDGE2 1527 1368 1.01276 0.0259672 0.00573525 1 0 1 1 0 0 +EDGE2 1527 1508 1.03276 0.0169914 -0.0277222 1 0 1 1 0 0 +EDGE2 1527 1526 -1.03929 0.0355641 0.0145388 1 0 1 1 0 0 +EDGE2 1527 1507 0.0129584 -0.019754 0.0098632 1 0 1 1 0 0 +EDGE2 1527 1367 -0.0377452 -0.0129063 -0.0202247 1 0 1 1 0 0 +EDGE2 1527 1366 -1.08206 0.0896748 0.00986254 1 0 1 1 0 0 +EDGE2 1527 1506 -0.985029 -0.027294 -0.00334168 1 0 1 1 0 0 +EDGE2 1528 1509 1.01763 0.0722001 -0.0370166 1 0 1 1 0 0 +EDGE2 1528 1369 1.01023 0.0192341 0.0105523 1 0 1 1 0 0 +EDGE2 1528 1368 -0.0274562 0.0767992 0.0118077 1 0 1 1 0 0 +EDGE2 1528 1508 -0.0137565 0.00425765 -0.00906579 1 0 1 1 0 0 +EDGE2 1528 1507 -1.06312 0.0616479 -0.0383418 1 0 1 1 0 0 +EDGE2 1528 1527 -1.00538 0.0321025 0.0263502 1 0 1 1 0 0 +EDGE2 1528 1367 -0.931129 -0.0786885 0.030679 1 0 1 1 0 0 +EDGE2 1529 1470 0.989542 -0.027435 -3.13941 1 0 1 1 0 0 +EDGE2 1529 1510 1.03114 0.111102 0.00522162 1 0 1 1 0 0 +EDGE2 1529 1370 0.950028 -0.0550404 0.0091586 1 0 1 1 0 0 +EDGE2 1529 1509 -0.00140461 0.110804 -0.021065 1 0 1 1 0 0 +EDGE2 1529 1369 -0.0485119 0.0198971 -0.021734 1 0 1 1 0 0 +EDGE2 1529 1368 -1.03227 -0.11332 0.00786906 1 0 1 1 0 0 +EDGE2 1529 1508 -0.963209 0.140324 0.0313308 1 0 1 1 0 0 +EDGE2 1529 1528 -0.985545 0.0807875 0.00723963 1 0 1 1 0 0 +EDGE2 1530 1469 0.922275 -0.00487102 -3.1503 1 0 1 1 0 0 +EDGE2 1530 1471 0.0342868 -1.00771 -1.57814 1 0 1 1 0 0 +EDGE2 1530 1470 -0.0543989 0.0212323 -3.13713 1 0 1 1 0 0 +EDGE2 1530 1510 0.010523 -0.0207864 -0.0130595 1 0 1 1 0 0 +EDGE2 1530 1370 -0.0298415 0.0723204 -0.00465531 1 0 1 1 0 0 +EDGE2 1530 1371 -0.00473549 0.990559 1.57292 1 0 1 1 0 0 +EDGE2 1530 1511 -0.0190854 0.998478 1.56698 1 0 1 1 0 0 +EDGE2 1530 1509 -1.02745 0.152772 0.01046 1 0 1 1 0 0 +EDGE2 1530 1529 -0.930382 0.0393703 -0.0199647 1 0 1 1 0 0 +EDGE2 1530 1369 -1.06823 0.0791159 0.00788486 1 0 1 1 0 0 +EDGE2 1531 1470 -0.989607 0.0480515 1.55811 1 0 1 1 0 0 +EDGE2 1531 1510 -0.977897 -0.028415 -1.5466 1 0 1 1 0 0 +EDGE2 1531 1530 -1.04265 0.0511875 -1.56509 1 0 1 1 0 0 +EDGE2 1531 1370 -1.07552 -0.0664256 -1.56316 1 0 1 1 0 0 +EDGE2 1531 1371 -0.0259463 0.0599051 0.00327201 1 0 1 1 0 0 +EDGE2 1531 1511 0.0513008 0.0402723 -0.0158861 1 0 1 1 0 0 +EDGE2 1531 1512 0.948428 -0.0394089 -0.000934406 1 0 1 1 0 0 +EDGE2 1531 1372 0.99853 0.0816466 -0.0222803 1 0 1 1 0 0 +EDGE2 1532 1371 -0.998538 -0.0754161 -0.00441322 1 0 1 1 0 0 +EDGE2 1532 1531 -0.957859 0.0321765 0.0178802 1 0 1 1 0 0 +EDGE2 1532 1511 -1.01376 0.0495915 -0.024126 1 0 1 1 0 0 +EDGE2 1532 1512 0.0801459 -0.134542 0.0087022 1 0 1 1 0 0 +EDGE2 1532 1372 0.0839091 0.0548235 -0.0181382 1 0 1 1 0 0 +EDGE2 1532 1513 1.04808 0.107932 -0.0229273 1 0 1 1 0 0 +EDGE2 1532 1373 0.998235 -0.0114001 0.00902718 1 0 1 1 0 0 +EDGE2 1533 1512 -0.996246 -0.0678177 -0.0115736 1 0 1 1 0 0 +EDGE2 1533 1532 -0.994874 -0.00429691 0.039603 1 0 1 1 0 0 +EDGE2 1533 1372 -0.99915 0.0147318 -0.00892969 1 0 1 1 0 0 +EDGE2 1533 1513 0.0257813 -0.0251059 0.0498592 1 0 1 1 0 0 +EDGE2 1533 1373 0.0559517 -0.0863514 0.0112033 1 0 1 1 0 0 +EDGE2 1533 1514 0.969661 -0.0368467 -0.0497023 1 0 1 1 0 0 +EDGE2 1533 1374 0.894187 0.0481043 -0.00328641 1 0 1 1 0 0 +EDGE2 1534 1513 -0.935012 0.0569446 -0.0239115 1 0 1 1 0 0 +EDGE2 1534 1533 -0.958357 0.0112787 0.0201246 1 0 1 1 0 0 +EDGE2 1534 1373 -0.969629 0.0678964 -0.00633318 1 0 1 1 0 0 +EDGE2 1534 1514 0.037258 0.00345783 0.00470081 1 0 1 1 0 0 +EDGE2 1534 1374 -0.0498703 0.107827 -0.0316547 1 0 1 1 0 0 +EDGE2 1534 1375 0.980674 0.013524 -0.0388074 1 0 1 1 0 0 +EDGE2 1534 1515 1.02658 0.0180557 -0.029653 1 0 1 1 0 0 +EDGE2 1535 1376 0.0299742 -1.01156 -1.56321 1 0 1 1 0 0 +EDGE2 1535 1514 -0.886671 0.0248011 -0.0229196 1 0 1 1 0 0 +EDGE2 1535 1534 -0.944678 0.0132322 0.00614075 1 0 1 1 0 0 +EDGE2 1535 1374 -0.973255 -0.0843277 -0.00945096 1 0 1 1 0 0 +EDGE2 1535 1375 0.0385851 -0.0500797 -0.0156681 1 0 1 1 0 0 +EDGE2 1535 1515 0.0145328 -0.121514 -0.00753622 1 0 1 1 0 0 +EDGE2 1535 1516 -0.0481297 1.01777 1.60571 1 0 1 1 0 0 +EDGE2 1536 1377 0.993927 0.00672776 0.020989 1 0 1 1 0 0 +EDGE2 1536 1376 0.0768938 -0.0776289 -0.00552338 1 0 1 1 0 0 +EDGE2 1536 1535 -1.03293 -0.049924 1.59843 1 0 1 1 0 0 +EDGE2 1536 1375 -0.978147 0.00494625 1.56949 1 0 1 1 0 0 +EDGE2 1536 1515 -0.936429 0.0179082 1.59161 1 0 1 1 0 0 +EDGE2 1537 1378 1.05959 -0.00712989 -0.0189265 1 0 1 1 0 0 +EDGE2 1537 1377 -0.023744 -0.0130504 0.0049208 1 0 1 1 0 0 +EDGE2 1537 1536 -0.984334 0.0672913 0.0124089 1 0 1 1 0 0 +EDGE2 1537 1376 -0.970841 -0.0364452 0.0056398 1 0 1 1 0 0 +EDGE2 1538 1378 0.0591841 -0.0442636 0.034056 1 0 1 1 0 0 +EDGE2 1538 1379 0.952136 0.0939081 0.0360684 1 0 1 1 0 0 +EDGE2 1538 1537 -0.904382 0.0575038 0.00775273 1 0 1 1 0 0 +EDGE2 1538 1377 -1.02234 -0.0322821 -0.0261255 1 0 1 1 0 0 +EDGE2 1539 1380 0.989267 0.0677739 -0.0120794 1 0 1 1 0 0 +EDGE2 1539 1378 -1.06161 -0.0586363 -0.0075404 1 0 1 1 0 0 +EDGE2 1539 1379 0.0199698 -0.0219476 -0.0188085 1 0 1 1 0 0 +EDGE2 1539 1538 -1.01622 -0.0376782 -0.0281139 1 0 1 1 0 0 +EDGE2 1540 1381 -0.0987679 -0.96395 -1.57449 1 0 1 1 0 0 +EDGE2 1540 1380 0.090934 -0.00563287 0.0253988 1 0 1 1 0 0 +EDGE2 1540 1379 -1.02073 -0.020861 -0.0282136 1 0 1 1 0 0 +EDGE2 1540 1539 -0.917077 0.0304177 0.00442418 1 0 1 1 0 0 +EDGE2 1541 1540 -0.986293 0.0335579 -1.56952 1 0 1 1 0 0 +EDGE2 1541 1380 -0.97477 -0.056852 -1.58034 1 0 1 1 0 0 +EDGE2 1542 1541 -0.997324 0.0297301 -0.0328498 1 0 1 1 0 0 +EDGE2 1543 1542 -0.966953 0.0234021 -0.00617276 1 0 1 1 0 0 +EDGE2 1544 1543 -1.07372 0.0538354 0.0152759 1 0 1 1 0 0 +EDGE2 1544 1265 1.02397 -0.0221384 -3.15893 1 0 1 1 0 0 +EDGE2 1545 1544 -0.897591 0.0353678 -0.041832 1 0 1 1 0 0 +EDGE2 1545 1265 0.0488156 0.0287218 -3.14375 1 0 1 1 0 0 +EDGE2 1545 1264 1.0117 -0.000364189 -3.15517 1 0 1 1 0 0 +EDGE2 1545 1266 -0.0554037 0.961205 1.56608 1 0 1 1 0 0 +EDGE2 1546 1265 -0.95377 -0.037038 -1.56897 1 0 1 1 0 0 +EDGE2 1546 1545 -0.990523 -0.0108807 1.56969 1 0 1 1 0 0 +EDGE2 1547 1546 -0.967411 0.102969 -0.0152053 1 0 1 1 0 0 +EDGE2 1548 1547 -0.970927 -0.0203463 -0.013711 1 0 1 1 0 0 +EDGE2 1549 1548 -1.00365 0.00238775 -0.0107602 1 0 1 1 0 0 +EDGE2 1550 1549 -1.0172 0.0355309 0.0145891 1 0 1 1 0 0 +EDGE2 1551 1550 -1.13994 -0.0493901 1.54187 1 0 1 1 0 0 +EDGE2 1552 1551 -0.997973 0.118287 -0.0346207 1 0 1 1 0 0 +EDGE2 1553 1552 -0.998942 0.0409519 0.00305164 1 0 1 1 0 0 +EDGE2 1554 1553 -0.953708 -0.107032 -0.0268156 1 0 1 1 0 0 +EDGE2 1555 1554 -1.08093 -0.0234978 -0.00641012 1 0 1 1 0 0 +EDGE2 1556 1555 -1.00401 -0.0524975 1.54253 1 0 1 1 0 0 +EDGE2 1557 1556 -1.04282 0.0207868 -0.0294613 1 0 1 1 0 0 +EDGE2 1558 1557 -0.962736 -0.0127187 0.00382453 1 0 1 1 0 0 +EDGE2 1559 1558 -1.05198 0.0425601 0.0580416 1 0 1 1 0 0 +EDGE2 1559 1540 0.943279 0.105075 -3.15834 1 0 1 1 0 0 +EDGE2 1559 1380 1.00694 0.0347308 -3.12603 1 0 1 1 0 0 +EDGE2 1560 1559 -1.06383 0.128019 0.0206437 1 0 1 1 0 0 +EDGE2 1560 1540 0.00832713 -0.0627341 -3.11195 1 0 1 1 0 0 +EDGE2 1560 1381 -0.000858121 1.05644 1.58174 1 0 1 1 0 0 +EDGE2 1560 1380 -0.0691283 -0.0152813 -3.14939 1 0 1 1 0 0 +EDGE2 1560 1541 0.018928 -1.04595 -1.57268 1 0 1 1 0 0 +EDGE2 1560 1379 0.983513 -0.031097 -3.16892 1 0 1 1 0 0 +EDGE2 1560 1539 1.07243 -0.0796315 -3.19602 1 0 1 1 0 0 +EDGE2 1561 1540 -0.97351 -0.013635 -1.57048 1 0 1 1 0 0 +EDGE2 1561 1560 -0.923969 -0.00472079 1.55802 1 0 1 1 0 0 +EDGE2 1561 1380 -0.997743 0.0087833 -1.57221 1 0 1 1 0 0 +EDGE2 1561 1541 0.032306 -0.0216921 0.0150207 1 0 1 1 0 0 +EDGE2 1561 1542 0.950801 -0.0105196 -0.0191069 1 0 1 1 0 0 +EDGE2 1562 1543 0.964484 0.00862364 0.0318284 1 0 1 1 0 0 +EDGE2 1562 1541 -1.04975 -0.0595355 -0.0172012 1 0 1 1 0 0 +EDGE2 1562 1561 -1.09886 -0.0367361 -6.32336e-05 1 0 1 1 0 0 +EDGE2 1562 1542 0.0784394 0.11942 -0.00930195 1 0 1 1 0 0 +EDGE2 1563 1543 0.0543342 -0.0345436 0.0250634 1 0 1 1 0 0 +EDGE2 1563 1542 -1.01519 0.0335638 -0.00983081 1 0 1 1 0 0 +EDGE2 1563 1562 -0.951351 0.0880205 -0.0160933 1 0 1 1 0 0 +EDGE2 1563 1544 1.0806 -0.0268779 -0.00018521 1 0 1 1 0 0 +EDGE2 1564 1543 -0.945249 0.00662202 -0.019002 1 0 1 1 0 0 +EDGE2 1564 1563 -0.924095 -0.00692859 0.00199167 1 0 1 1 0 0 +EDGE2 1564 1544 0.0794567 -0.0619636 0.0316608 1 0 1 1 0 0 +EDGE2 1564 1265 0.979542 -0.0275903 -3.14528 1 0 1 1 0 0 +EDGE2 1564 1545 1.10364 0.0391505 0.00425081 1 0 1 1 0 0 +EDGE2 1565 1564 -0.980756 -0.0778799 0.0274253 1 0 1 1 0 0 +EDGE2 1565 1544 -0.996651 0.0307349 0.0340727 1 0 1 1 0 0 +EDGE2 1565 1546 -0.000796522 -1.00582 -1.56728 1 0 1 1 0 0 +EDGE2 1565 1265 0.0124692 0.0306462 -3.0992 1 0 1 1 0 0 +EDGE2 1565 1545 0.0426569 0.0255532 -0.0150675 1 0 1 1 0 0 +EDGE2 1565 1264 0.971843 0.0222347 -3.16325 1 0 1 1 0 0 +EDGE2 1565 1266 0.0166349 1.11432 1.56466 1 0 1 1 0 0 +EDGE2 1566 1265 -1.08515 -0.0612297 1.59771 1 0 1 1 0 0 +EDGE2 1566 1565 -0.991336 -0.0619448 -1.57218 1 0 1 1 0 0 +EDGE2 1566 1545 -0.959735 -0.0221706 -1.60964 1 0 1 1 0 0 +EDGE2 1566 1266 0.0478685 -0.0153978 0.00694392 1 0 1 1 0 0 +EDGE2 1566 1267 1.02834 -0.0248816 0.00710534 1 0 1 1 0 0 +EDGE2 1567 1566 -0.930324 -0.102068 -0.00620404 1 0 1 1 0 0 +EDGE2 1567 1266 -1.027 0.0265736 -0.00241729 1 0 1 1 0 0 +EDGE2 1567 1267 0.0054549 -0.0257946 -0.017053 1 0 1 1 0 0 +EDGE2 1567 1268 0.971122 -0.079396 -0.00164197 1 0 1 1 0 0 +EDGE2 1568 1567 -1.03537 0.0483907 0.00302998 1 0 1 1 0 0 +EDGE2 1568 1267 -1.04882 -0.0430421 0.00947773 1 0 1 1 0 0 +EDGE2 1568 1268 0.0262047 -0.0800605 -0.00239821 1 0 1 1 0 0 +EDGE2 1568 1269 0.933022 -0.0717543 -0.0237159 1 0 1 1 0 0 +EDGE2 1569 1268 -1.00237 -0.0133558 0.00411017 1 0 1 1 0 0 +EDGE2 1569 1568 -0.988428 -0.00232952 0.00449877 1 0 1 1 0 0 +EDGE2 1569 1269 0.000393326 0.0597871 0.00841404 1 0 1 1 0 0 +EDGE2 1569 1270 1.03221 -0.0072949 0.020801 1 0 1 1 0 0 +EDGE2 1569 1290 0.933404 -0.0116882 -3.13915 1 0 1 1 0 0 +EDGE2 1570 1569 -0.990557 0.00614659 -0.021092 1 0 1 1 0 0 +EDGE2 1570 1269 -1.0118 0.0478137 0.0263046 1 0 1 1 0 0 +EDGE2 1570 1291 -0.0597051 -0.982741 -1.59161 1 0 1 1 0 0 +EDGE2 1570 1270 -0.0108401 -0.0724633 0.00324936 1 0 1 1 0 0 +EDGE2 1570 1290 0.028248 -0.0541128 -3.17924 1 0 1 1 0 0 +EDGE2 1570 1271 0.0210134 -0.915779 -1.57266 1 0 1 1 0 0 +EDGE2 1570 1289 0.999105 0.0728339 -3.13622 1 0 1 1 0 0 +EDGE2 1571 1270 -0.947387 0.00346885 -1.57016 1 0 1 1 0 0 +EDGE2 1571 1290 -1.01457 -0.0651768 1.56805 1 0 1 1 0 0 +EDGE2 1571 1570 -1.01295 -0.00712875 -1.57749 1 0 1 1 0 0 +EDGE2 1572 1571 -0.969273 -0.025005 0.0149398 1 0 1 1 0 0 +EDGE2 1573 1572 -0.950246 0.0520635 -0.000377807 1 0 1 1 0 0 +EDGE2 1574 1535 1.07369 -0.0305889 -3.17608 1 0 1 1 0 0 +EDGE2 1574 1375 0.958285 -0.047978 -3.15079 1 0 1 1 0 0 +EDGE2 1574 1515 0.920591 0.031208 -3.16479 1 0 1 1 0 0 +EDGE2 1574 1573 -1.01059 0.00801164 0.00781292 1 0 1 1 0 0 +EDGE2 1575 1536 0.0467751 1.02992 1.52577 1 0 1 1 0 0 +EDGE2 1575 1376 0.0427412 0.936497 1.55621 1 0 1 1 0 0 +EDGE2 1575 1535 -0.0769185 -0.0357678 -3.09041 1 0 1 1 0 0 +EDGE2 1575 1514 0.946363 0.0701604 -3.14925 1 0 1 1 0 0 +EDGE2 1575 1534 1.05804 -0.0508353 -3.12869 1 0 1 1 0 0 +EDGE2 1575 1374 0.986858 0.0380591 -3.15107 1 0 1 1 0 0 +EDGE2 1575 1375 -0.0196651 0.0335944 -3.13633 1 0 1 1 0 0 +EDGE2 1575 1515 0.0235777 -0.00492734 -3.18678 1 0 1 1 0 0 +EDGE2 1575 1574 -0.99125 0.0458419 -0.00353757 1 0 1 1 0 0 +EDGE2 1575 1516 0.0680623 -0.997716 -1.53665 1 0 1 1 0 0 +EDGE2 1576 1537 0.97205 -0.0254029 0.00816327 1 0 1 1 0 0 +EDGE2 1576 1377 1.09317 0.0242658 -0.0165043 1 0 1 1 0 0 +EDGE2 1576 1536 -0.0389871 0.105831 0.0239523 1 0 1 1 0 0 +EDGE2 1576 1376 -0.0527492 -0.0137462 0.0185031 1 0 1 1 0 0 +EDGE2 1576 1535 -0.970571 0.000783456 1.58173 1 0 1 1 0 0 +EDGE2 1576 1575 -1.01421 0.0595228 -1.557 1 0 1 1 0 0 +EDGE2 1576 1375 -1.10616 -0.115187 1.58331 1 0 1 1 0 0 +EDGE2 1576 1515 -0.940275 -0.0540962 1.54505 1 0 1 1 0 0 +EDGE2 1577 1378 0.984443 -0.0141387 -0.0135195 1 0 1 1 0 0 +EDGE2 1577 1538 1.01707 0.0135644 0.0020957 1 0 1 1 0 0 +EDGE2 1577 1537 0.0909074 0.00988348 -0.031346 1 0 1 1 0 0 +EDGE2 1577 1377 0.0873439 0.0486424 0.0347546 1 0 1 1 0 0 +EDGE2 1577 1536 -1.05031 -0.0253183 -0.0234897 1 0 1 1 0 0 +EDGE2 1577 1576 -1.04789 -0.0103114 -0.0262623 1 0 1 1 0 0 +EDGE2 1577 1376 -0.985575 0.0624761 0.00343147 1 0 1 1 0 0 +EDGE2 1578 1378 -0.0319134 -0.0725017 0.0328907 1 0 1 1 0 0 +EDGE2 1578 1379 0.896946 0.0128243 0.000619975 1 0 1 1 0 0 +EDGE2 1578 1539 1.04138 0.0352528 0.0173291 1 0 1 1 0 0 +EDGE2 1578 1538 0.00424228 0.0106367 -0.0033628 1 0 1 1 0 0 +EDGE2 1578 1537 -0.942709 -0.01073 0.0207947 1 0 1 1 0 0 +EDGE2 1578 1577 -1.0402 -0.000115518 -0.00529507 1 0 1 1 0 0 +EDGE2 1578 1377 -1.07956 -0.00383602 -0.0230854 1 0 1 1 0 0 +EDGE2 1579 1540 1.09357 0.0181946 0.00246861 1 0 1 1 0 0 +EDGE2 1579 1560 0.950913 0.114619 -3.16778 1 0 1 1 0 0 +EDGE2 1579 1380 1.00506 -0.0305701 -0.0151363 1 0 1 1 0 0 +EDGE2 1579 1378 -0.960938 -0.0814831 -0.0102066 1 0 1 1 0 0 +EDGE2 1579 1379 -0.0155053 0.0485556 0.0261837 1 0 1 1 0 0 +EDGE2 1579 1539 0.0264058 0.0527659 -0.0418415 1 0 1 1 0 0 +EDGE2 1579 1578 -1.03061 0.0474269 0.00768551 1 0 1 1 0 0 +EDGE2 1579 1538 -0.972384 -0.101286 0.02387 1 0 1 1 0 0 +EDGE2 1580 1559 0.992714 0.0426245 -3.1568 1 0 1 1 0 0 +EDGE2 1580 1540 -0.146546 0.0169367 0.0109865 1 0 1 1 0 0 +EDGE2 1580 1381 -0.0297205 -1.01971 -1.55366 1 0 1 1 0 0 +EDGE2 1580 1560 -0.0246134 0.0149363 -3.12909 1 0 1 1 0 0 +EDGE2 1580 1380 -0.0546935 0.032977 0.0115675 1 0 1 1 0 0 +EDGE2 1580 1541 -0.0925749 1.10727 1.56022 1 0 1 1 0 0 +EDGE2 1580 1561 -0.058619 0.969065 1.57526 1 0 1 1 0 0 +EDGE2 1580 1579 -1.02217 -0.00609928 -0.00339922 1 0 1 1 0 0 +EDGE2 1580 1379 -1.06505 0.0187621 -0.0136926 1 0 1 1 0 0 +EDGE2 1580 1539 -0.96985 0.0889473 -0.0243913 1 0 1 1 0 0 +EDGE2 1581 1540 -0.923336 0.0289265 -1.57457 1 0 1 1 0 0 +EDGE2 1581 1580 -1.0323 -0.062877 -1.58177 1 0 1 1 0 0 +EDGE2 1581 1560 -1.00597 0.0284202 1.55385 1 0 1 1 0 0 +EDGE2 1581 1380 -1.08446 -0.0559931 -1.59355 1 0 1 1 0 0 +EDGE2 1581 1541 0.0747049 0.018459 -0.0295766 1 0 1 1 0 0 +EDGE2 1581 1561 -0.0144857 -0.0682208 0.0182426 1 0 1 1 0 0 +EDGE2 1581 1542 0.980056 -0.0286669 0.0110755 1 0 1 1 0 0 +EDGE2 1581 1562 1.02153 0.00691188 -0.0114141 1 0 1 1 0 0 +EDGE2 1582 1543 1.03338 0.0157025 -0.0198944 1 0 1 1 0 0 +EDGE2 1582 1581 -0.940471 0.000855629 -0.0118204 1 0 1 1 0 0 +EDGE2 1582 1541 -1.05732 0.101412 0.00556449 1 0 1 1 0 0 +EDGE2 1582 1561 -1.05734 -0.0142202 0.00397282 1 0 1 1 0 0 +EDGE2 1582 1542 0.0609308 0.0309382 0.0152844 1 0 1 1 0 0 +EDGE2 1582 1562 0.035971 0.00684082 -0.0288598 1 0 1 1 0 0 +EDGE2 1582 1563 0.979021 0.00845721 -0.00849208 1 0 1 1 0 0 +EDGE2 1583 1543 0.104589 -0.0277985 0.0301864 1 0 1 1 0 0 +EDGE2 1583 1542 -1.06108 -0.154677 -0.000181687 1 0 1 1 0 0 +EDGE2 1583 1562 -0.929336 0.123511 0.0046069 1 0 1 1 0 0 +EDGE2 1583 1582 -0.994919 0.0184751 -0.00202844 1 0 1 1 0 0 +EDGE2 1583 1563 -0.0228506 0.0230823 -0.0288065 1 0 1 1 0 0 +EDGE2 1583 1564 0.95911 -0.00969564 0.0440612 1 0 1 1 0 0 +EDGE2 1583 1544 0.991132 0.00276944 0.00795167 1 0 1 1 0 0 +EDGE2 1584 1543 -0.96483 -0.0468803 -0.0242083 1 0 1 1 0 0 +EDGE2 1584 1583 -1.05729 -0.0189942 -0.0117119 1 0 1 1 0 0 +EDGE2 1584 1563 -1.02991 0.019565 0.0144663 1 0 1 1 0 0 +EDGE2 1584 1564 0.0617901 -0.00302118 -0.0286058 1 0 1 1 0 0 +EDGE2 1584 1544 0.0136698 -0.0413149 0.0180527 1 0 1 1 0 0 +EDGE2 1584 1265 1.06549 -0.0131322 -3.16325 1 0 1 1 0 0 +EDGE2 1584 1565 1.0221 0.0211559 -0.00918689 1 0 1 1 0 0 +EDGE2 1584 1545 0.982346 -0.0676358 -0.0254559 1 0 1 1 0 0 +EDGE2 1585 1564 -0.886083 0.028759 -0.00708903 1 0 1 1 0 0 +EDGE2 1585 1584 -0.970488 0.0237527 -0.00383226 1 0 1 1 0 0 +EDGE2 1585 1544 -0.913188 -0.0232795 -0.00795966 1 0 1 1 0 0 +EDGE2 1585 1546 0.0231243 -1.08217 -1.55976 1 0 1 1 0 0 +EDGE2 1585 1265 -0.0569658 0.0365229 -3.14525 1 0 1 1 0 0 +EDGE2 1585 1565 -0.0290219 0.0479039 0.0317619 1 0 1 1 0 0 +EDGE2 1585 1545 -0.021251 -0.0600933 -0.0147056 1 0 1 1 0 0 +EDGE2 1585 1264 0.98673 0.0841298 -3.12746 1 0 1 1 0 0 +EDGE2 1585 1566 -0.0137251 1.01364 1.57993 1 0 1 1 0 0 +EDGE2 1585 1266 -0.0114419 0.963215 1.56585 1 0 1 1 0 0 +EDGE2 1586 1265 -1.0134 0.0454527 1.54209 1 0 1 1 0 0 +EDGE2 1586 1565 -1.06058 0.0377854 -1.59454 1 0 1 1 0 0 +EDGE2 1586 1585 -0.989226 0.0552506 -1.59523 1 0 1 1 0 0 +EDGE2 1586 1545 -1.00957 0.0333521 -1.58432 1 0 1 1 0 0 +EDGE2 1586 1567 1.02036 0.0072956 -0.013464 1 0 1 1 0 0 +EDGE2 1586 1566 0.0663643 -0.0383064 -0.0041537 1 0 1 1 0 0 +EDGE2 1586 1266 0.0216786 -0.0430941 -0.01063 1 0 1 1 0 0 +EDGE2 1586 1267 0.941789 0.0720361 0.00480705 1 0 1 1 0 0 +EDGE2 1587 1567 -0.00370613 0.0280019 -0.0477553 1 0 1 1 0 0 +EDGE2 1587 1566 -0.94312 -0.00260862 0.00788809 1 0 1 1 0 0 +EDGE2 1587 1586 -1.01486 -0.0535984 0.0123773 1 0 1 1 0 0 +EDGE2 1587 1266 -0.975094 -0.0538486 0.0363392 1 0 1 1 0 0 +EDGE2 1587 1267 -0.00724188 0.0538497 -0.0205661 1 0 1 1 0 0 +EDGE2 1587 1268 0.919504 0.0451571 -0.00308389 1 0 1 1 0 0 +EDGE2 1587 1568 1.01628 0.0229681 0.0152766 1 0 1 1 0 0 +EDGE2 1588 1567 -1.06855 -0.0344215 0.00332796 1 0 1 1 0 0 +EDGE2 1588 1587 -0.973197 0.0341305 0.0188395 1 0 1 1 0 0 +EDGE2 1588 1267 -1.05039 0.0297612 0.0222635 1 0 1 1 0 0 +EDGE2 1588 1268 0.0323642 -0.0107766 0.0221099 1 0 1 1 0 0 +EDGE2 1588 1568 -0.0108455 -0.00956403 -0.0158575 1 0 1 1 0 0 +EDGE2 1588 1569 0.952921 -0.0612923 -0.0230997 1 0 1 1 0 0 +EDGE2 1588 1269 0.96118 -0.0825878 0.00641881 1 0 1 1 0 0 +EDGE2 1589 1588 -0.922362 0.0177805 0.00705552 1 0 1 1 0 0 +EDGE2 1589 1268 -1.00491 0.00697699 -0.0108031 1 0 1 1 0 0 +EDGE2 1589 1568 -0.975954 0.0344061 -0.00516902 1 0 1 1 0 0 +EDGE2 1589 1569 -0.00990128 0.0365555 0.00606394 1 0 1 1 0 0 +EDGE2 1589 1269 0.0904051 0.0459621 -0.011066 1 0 1 1 0 0 +EDGE2 1589 1270 1.01871 -0.0317899 0.00219733 1 0 1 1 0 0 +EDGE2 1589 1290 1.03701 -0.0798342 -3.11138 1 0 1 1 0 0 +EDGE2 1589 1570 1.06747 0.0713127 0.00817498 1 0 1 1 0 0 +EDGE2 1590 1571 -0.0206362 1.03526 1.54943 1 0 1 1 0 0 +EDGE2 1590 1569 -1.02112 0.0427806 -0.0223931 1 0 1 1 0 0 +EDGE2 1590 1589 -1.0025 0.0767175 0.0420111 1 0 1 1 0 0 +EDGE2 1590 1269 -0.94222 0.0499369 0.00221005 1 0 1 1 0 0 +EDGE2 1590 1291 0.0905069 -1.04366 -1.57683 1 0 1 1 0 0 +EDGE2 1590 1270 -0.0143602 -0.0184412 0.00356429 1 0 1 1 0 0 +EDGE2 1590 1290 -0.0048563 -0.0363301 -3.12325 1 0 1 1 0 0 +EDGE2 1590 1570 -0.0219315 -0.0825649 0.0250344 1 0 1 1 0 0 +EDGE2 1590 1271 -0.0113878 -0.973006 -1.61018 1 0 1 1 0 0 +EDGE2 1590 1289 1.02301 0.0608648 -3.129 1 0 1 1 0 0 +EDGE2 1591 1572 1.02118 0.0715328 0.0561255 1 0 1 1 0 0 +EDGE2 1591 1571 -0.0404198 0.0262469 0.0202422 1 0 1 1 0 0 +EDGE2 1591 1590 -0.977759 0.00257338 -1.5797 1 0 1 1 0 0 +EDGE2 1591 1270 -0.896711 0.0486628 -1.54198 1 0 1 1 0 0 +EDGE2 1591 1290 -1.04054 -0.0145952 1.51445 1 0 1 1 0 0 +EDGE2 1591 1570 -0.999703 0.0840214 -1.57667 1 0 1 1 0 0 +EDGE2 1592 1573 1.00888 -0.000328791 0.0124622 1 0 1 1 0 0 +EDGE2 1592 1572 -0.0461863 0.0348143 0.0434131 1 0 1 1 0 0 +EDGE2 1592 1571 -1.03023 -0.0568488 0.00969918 1 0 1 1 0 0 +EDGE2 1592 1591 -0.984872 -0.00799931 -0.0204658 1 0 1 1 0 0 +EDGE2 1593 1574 1.02149 0.0153378 0.0208649 1 0 1 1 0 0 +EDGE2 1593 1573 -0.052736 -0.0881248 0.00361073 1 0 1 1 0 0 +EDGE2 1593 1572 -0.997335 0.0210049 0.0233959 1 0 1 1 0 0 +EDGE2 1593 1592 -0.959754 0.00588165 0.0158964 1 0 1 1 0 0 +EDGE2 1594 1535 1.01732 -0.0196311 -3.13378 1 0 1 1 0 0 +EDGE2 1594 1575 1.04234 -0.0543668 0.0542082 1 0 1 1 0 0 +EDGE2 1594 1375 1.0517 0.00214967 -3.15519 1 0 1 1 0 0 +EDGE2 1594 1515 0.980248 0.0442265 -3.14626 1 0 1 1 0 0 +EDGE2 1594 1574 0.0403723 -0.0629767 0.0159347 1 0 1 1 0 0 +EDGE2 1594 1573 -0.912429 -0.0137949 -0.0242331 1 0 1 1 0 0 +EDGE2 1594 1593 -1.07313 -0.00517169 0.0446036 1 0 1 1 0 0 +EDGE2 1595 1536 -0.00260473 0.996343 1.55778 1 0 1 1 0 0 +EDGE2 1595 1576 0.0315809 1.00731 1.57919 1 0 1 1 0 0 +EDGE2 1595 1376 0.0339841 1.0723 1.59008 1 0 1 1 0 0 +EDGE2 1595 1535 -0.0733642 -0.0329133 -3.1224 1 0 1 1 0 0 +EDGE2 1595 1514 0.951268 -0.0254799 -3.12764 1 0 1 1 0 0 +EDGE2 1595 1534 1.02424 0.028912 -3.15993 1 0 1 1 0 0 +EDGE2 1595 1374 0.965771 -0.0139057 -3.12173 1 0 1 1 0 0 +EDGE2 1595 1575 0.0802838 0.0146524 0.0158563 1 0 1 1 0 0 +EDGE2 1595 1375 0.066618 -0.164985 -3.12012 1 0 1 1 0 0 +EDGE2 1595 1515 0.0847022 0.0146082 -3.13645 1 0 1 1 0 0 +EDGE2 1595 1574 -0.974262 -0.0259626 -0.00815266 1 0 1 1 0 0 +EDGE2 1595 1594 -1.01245 0.0170883 0.0131175 1 0 1 1 0 0 +EDGE2 1595 1516 -0.0398571 -1.00081 -1.60441 1 0 1 1 0 0 +EDGE2 1596 1535 -0.9861 0.0135499 -1.61888 1 0 1 1 0 0 +EDGE2 1596 1595 -0.971382 0.0431656 1.57948 1 0 1 1 0 0 +EDGE2 1596 1575 -1.02158 0.0570501 1.5474 1 0 1 1 0 0 +EDGE2 1596 1375 -0.918617 -0.0299496 -1.57459 1 0 1 1 0 0 +EDGE2 1596 1515 -1.10936 0.00318421 -1.53486 1 0 1 1 0 0 +EDGE2 1596 1516 0.0207464 0.0349544 -0.0356443 1 0 1 1 0 0 +EDGE2 1596 1517 0.970484 -0.0163003 -0.00956165 1 0 1 1 0 0 +EDGE2 1597 1516 -1.05919 0.0429477 -0.0296523 1 0 1 1 0 0 +EDGE2 1597 1596 -0.89685 0.0124917 -0.00757807 1 0 1 1 0 0 +EDGE2 1597 1517 -0.00269626 -0.0527999 -0.00566491 1 0 1 1 0 0 +EDGE2 1597 1518 0.947336 -0.0587779 -0.00875934 1 0 1 1 0 0 +EDGE2 1598 1597 -0.997568 -0.00658319 -0.000344372 1 0 1 1 0 0 +EDGE2 1598 1517 -0.839753 0.0856651 0.0512814 1 0 1 1 0 0 +EDGE2 1598 1518 0.00819214 0.0612391 0.0342922 1 0 1 1 0 0 +EDGE2 1598 1519 1.02795 0.0273694 -0.0027864 1 0 1 1 0 0 +EDGE2 1599 1598 -0.959165 0.00417581 -0.0173368 1 0 1 1 0 0 +EDGE2 1599 1518 -1.00939 0.025257 0.01765 1 0 1 1 0 0 +EDGE2 1599 1519 0.0121901 0.0282868 0.00668403 1 0 1 1 0 0 +EDGE2 1599 1520 1.05911 0.0255184 0.0151633 1 0 1 1 0 0 +EDGE2 1599 1320 1.04498 -0.0217478 -3.15308 1 0 1 1 0 0 +EDGE2 1600 1599 -0.923989 -0.0405822 0.00964956 1 0 1 1 0 0 +EDGE2 1600 1519 -1.02938 -0.0808119 -0.013963 1 0 1 1 0 0 +EDGE2 1600 1521 -0.0966594 0.981371 1.57022 1 0 1 1 0 0 +EDGE2 1600 1321 0.018802 1.01399 1.56032 1 0 1 1 0 0 +EDGE2 1600 1520 -0.0125332 -0.0564813 0.00494674 1 0 1 1 0 0 +EDGE2 1600 1320 -0.024782 0.0243645 -3.14244 1 0 1 1 0 0 +EDGE2 1600 1319 0.981408 0.0140957 -3.13538 1 0 1 1 0 0 +EDGE2 1601 1520 -1.00444 -0.0293968 1.57148 1 0 1 1 0 0 +EDGE2 1601 1600 -0.946618 -0.00327489 1.54767 1 0 1 1 0 0 +EDGE2 1601 1320 -0.914811 -0.0472765 -1.55992 1 0 1 1 0 0 +EDGE2 1602 1601 -1.04562 0.0135212 0.00742855 1 0 1 1 0 0 +EDGE2 1603 1602 -0.95986 -0.049322 -0.0149249 1 0 1 1 0 0 +EDGE2 1604 1603 -1.00899 0.0530905 -0.0228563 1 0 1 1 0 0 +EDGE2 1604 1285 0.999027 0.0346185 -3.16442 1 0 1 1 0 0 +EDGE2 1604 1305 1.0703 0.0348399 -3.17158 1 0 1 1 0 0 +EDGE2 1605 1604 -1.01776 0.0128165 0.0352993 1 0 1 1 0 0 +EDGE2 1605 1304 0.908138 -0.0111781 -3.11423 1 0 1 1 0 0 +EDGE2 1605 1286 0.0369958 -0.96187 -1.5996 1 0 1 1 0 0 +EDGE2 1605 1285 -0.0835396 0.00894127 -3.15322 1 0 1 1 0 0 +EDGE2 1605 1305 0.0291716 0.0113967 -3.14361 1 0 1 1 0 0 +EDGE2 1605 1284 1.01866 -0.0367441 -3.15893 1 0 1 1 0 0 +EDGE2 1605 1306 -0.0138039 0.95224 1.54761 1 0 1 1 0 0 +EDGE2 1606 1285 -1.00876 0.0198849 1.55472 1 0 1 1 0 0 +EDGE2 1606 1305 -0.989861 0.0765128 1.57358 1 0 1 1 0 0 +EDGE2 1606 1605 -1.02203 0.0146046 -1.58407 1 0 1 1 0 0 +EDGE2 1606 1306 0.0706319 0.069377 0.0319261 1 0 1 1 0 0 +EDGE2 1606 1307 0.953249 -0.0351506 0.0346104 1 0 1 1 0 0 +EDGE2 1607 1606 -0.989634 0.0356497 0.00357177 1 0 1 1 0 0 +EDGE2 1607 1306 -0.999881 0.0636562 0.00801241 1 0 1 1 0 0 +EDGE2 1607 1307 0.0397367 0.0499318 0.0150518 1 0 1 1 0 0 +EDGE2 1607 1308 0.953026 -0.0383766 -0.0116329 1 0 1 1 0 0 +EDGE2 1608 1607 -0.950854 -0.0371873 0.00472649 1 0 1 1 0 0 +EDGE2 1608 1307 -0.959585 0.0220469 0.00640002 1 0 1 1 0 0 +EDGE2 1608 1308 0.0174585 -0.0874588 -0.00117845 1 0 1 1 0 0 +EDGE2 1608 1309 1.06456 0.060341 0.0112295 1 0 1 1 0 0 +EDGE2 1609 1308 -0.955001 0.0586282 0.0493958 1 0 1 1 0 0 +EDGE2 1609 1608 -0.991212 -0.0256484 -0.013711 1 0 1 1 0 0 +EDGE2 1609 1309 -0.0304246 -0.0659111 0.0496198 1 0 1 1 0 0 +EDGE2 1609 1310 1.10723 -0.0083176 0.0122814 1 0 1 1 0 0 +EDGE2 1610 1609 -1.05389 -0.11482 0.0106612 1 0 1 1 0 0 +EDGE2 1610 1309 -1.08465 0.0198379 -0.00196858 1 0 1 1 0 0 +EDGE2 1610 1311 -0.00498878 0.919738 1.58348 1 0 1 1 0 0 +EDGE2 1610 1310 -0.0129731 0.0272523 0.018648 1 0 1 1 0 0 +EDGE2 1611 1312 0.908253 -0.00895117 0.00164015 1 0 1 1 0 0 +EDGE2 1611 1311 -0.0048247 0.0418877 0.0141045 1 0 1 1 0 0 +EDGE2 1611 1610 -0.937016 0.00402919 -1.56498 1 0 1 1 0 0 +EDGE2 1611 1310 -1.07317 0.000901116 -1.5796 1 0 1 1 0 0 +EDGE2 1612 1313 1.04429 -0.0789496 -0.0213236 1 0 1 1 0 0 +EDGE2 1612 1611 -1.06031 0.0299292 0.0156017 1 0 1 1 0 0 +EDGE2 1612 1312 0.00279988 -0.0253004 -0.000230509 1 0 1 1 0 0 +EDGE2 1612 1311 -0.996031 -0.0466933 0.00359547 1 0 1 1 0 0 +EDGE2 1613 1314 1.01561 0.0480295 -0.00312836 1 0 1 1 0 0 +EDGE2 1613 1612 -1.12779 0.0522755 0.0146068 1 0 1 1 0 0 +EDGE2 1613 1313 0.0451869 -0.0113797 -0.0160222 1 0 1 1 0 0 +EDGE2 1613 1312 -1.02417 0.0413036 0.00251255 1 0 1 1 0 0 +EDGE2 1614 1314 0.0022987 0.019051 -0.0209346 1 0 1 1 0 0 +EDGE2 1614 1315 1.04657 0.106364 -0.0117313 1 0 1 1 0 0 +EDGE2 1614 1313 -1.03194 0.0349942 -0.00643938 1 0 1 1 0 0 +EDGE2 1614 1613 -1.09686 -0.0372694 0.0110831 1 0 1 1 0 0 +EDGE2 1615 1316 -0.029203 1.01041 1.57296 1 0 1 1 0 0 +EDGE2 1615 1314 -0.950914 -0.0274035 0.0157671 1 0 1 1 0 0 +EDGE2 1615 1315 0.00815083 -0.00810061 0.0193771 1 0 1 1 0 0 +EDGE2 1615 1614 -0.945884 0.0586748 0.0119063 1 0 1 1 0 0 +EDGE2 1616 1317 0.985358 0.00373158 0.01459 1 0 1 1 0 0 +EDGE2 1616 1316 0.0239635 -0.00604969 -0.0052593 1 0 1 1 0 0 +EDGE2 1616 1315 -0.99372 0.0716838 -1.53642 1 0 1 1 0 0 +EDGE2 1616 1615 -0.948482 0.0199059 -1.56999 1 0 1 1 0 0 +EDGE2 1617 1318 0.894013 -0.0812967 -0.0123561 1 0 1 1 0 0 +EDGE2 1617 1317 -0.002884 -0.0101384 0.0150852 1 0 1 1 0 0 +EDGE2 1617 1316 -0.954654 0.0496996 -0.00193943 1 0 1 1 0 0 +EDGE2 1617 1616 -1.00367 -0.048098 -0.0109529 1 0 1 1 0 0 +EDGE2 1618 1319 1.02952 -0.0883008 0.0274562 1 0 1 1 0 0 +EDGE2 1618 1318 -0.0254402 -0.0312806 -0.00755312 1 0 1 1 0 0 +EDGE2 1618 1617 -1.06167 -0.0172683 0.0305058 1 0 1 1 0 0 +EDGE2 1618 1317 -1.00719 0.00651844 -0.00897972 1 0 1 1 0 0 +EDGE2 1619 1520 0.878609 -0.019092 -3.12292 1 0 1 1 0 0 +EDGE2 1619 1600 1.08153 0.127723 -3.14382 1 0 1 1 0 0 +EDGE2 1619 1320 0.963471 0.00194926 0.00861743 1 0 1 1 0 0 +EDGE2 1619 1319 -0.000234003 0.0325795 -0.00183761 1 0 1 1 0 0 +EDGE2 1619 1618 -1.04272 -0.0119224 -0.0366441 1 0 1 1 0 0 +EDGE2 1619 1318 -0.999898 -0.078749 -0.0239429 1 0 1 1 0 0 +EDGE2 1620 1599 1.01673 0.0258962 -3.1512 1 0 1 1 0 0 +EDGE2 1620 1519 0.981192 0.0625997 -3.09472 1 0 1 1 0 0 +EDGE2 1620 1521 -0.0053469 -0.863814 -1.58389 1 0 1 1 0 0 +EDGE2 1620 1321 0.0370372 -0.972584 -1.58786 1 0 1 1 0 0 +EDGE2 1620 1520 -0.0740498 0.070403 -3.15 1 0 1 1 0 0 +EDGE2 1620 1600 0.00711809 0.00880487 -3.15192 1 0 1 1 0 0 +EDGE2 1620 1320 -0.0484777 0.00613673 0.00586072 1 0 1 1 0 0 +EDGE2 1620 1601 -0.0160208 1.05851 1.59868 1 0 1 1 0 0 +EDGE2 1620 1619 -1.00602 -0.0150449 -0.0144674 1 0 1 1 0 0 +EDGE2 1620 1319 -0.990158 -0.0319351 -0.0371256 1 0 1 1 0 0 +EDGE2 1621 1520 -0.963003 0.0474132 1.5697 1 0 1 1 0 0 +EDGE2 1621 1620 -1.03 -0.0425094 -1.6016 1 0 1 1 0 0 +EDGE2 1621 1600 -0.998273 -0.0386675 1.58736 1 0 1 1 0 0 +EDGE2 1621 1320 -1.00084 -0.0213352 -1.5805 1 0 1 1 0 0 +EDGE2 1621 1601 0.0234227 -0.0497801 0.0118788 1 0 1 1 0 0 +EDGE2 1621 1602 1.01915 -0.0304016 0.0356016 1 0 1 1 0 0 +EDGE2 1622 1621 -0.989931 0.0980639 -0.0205722 1 0 1 1 0 0 +EDGE2 1622 1601 -1.08052 0.0835642 0.0151448 1 0 1 1 0 0 +EDGE2 1622 1603 1.08639 -0.0324819 -0.0114645 1 0 1 1 0 0 +EDGE2 1622 1602 0.0369932 -0.0522769 0.00836928 1 0 1 1 0 0 +EDGE2 1623 1603 0.0610245 -0.037187 -0.0310452 1 0 1 1 0 0 +EDGE2 1623 1602 -0.937111 -0.0252802 -0.0162373 1 0 1 1 0 0 +EDGE2 1623 1622 -1.00919 -0.0461108 0.00962802 1 0 1 1 0 0 +EDGE2 1623 1604 0.942808 -0.0206905 0.00695622 1 0 1 1 0 0 +EDGE2 1624 1603 -0.997135 -0.0708418 0.0189924 1 0 1 1 0 0 +EDGE2 1624 1623 -1.00158 0.00782766 -0.0182102 1 0 1 1 0 0 +EDGE2 1624 1604 0.136236 -0.0374852 -0.000482381 1 0 1 1 0 0 +EDGE2 1624 1285 0.93908 -0.000154052 -3.11446 1 0 1 1 0 0 +EDGE2 1624 1305 0.969686 0.0280776 -3.17049 1 0 1 1 0 0 +EDGE2 1624 1605 0.987409 0.041138 -0.00117055 1 0 1 1 0 0 +EDGE2 1625 1624 -0.992671 -0.0370447 -0.0221206 1 0 1 1 0 0 +EDGE2 1625 1604 -0.984949 0.121455 -0.0026487 1 0 1 1 0 0 +EDGE2 1625 1304 1.025 -0.00314103 -3.1742 1 0 1 1 0 0 +EDGE2 1625 1286 -0.0483567 -0.899084 -1.57666 1 0 1 1 0 0 +EDGE2 1625 1285 0.000153546 0.0537582 -3.18306 1 0 1 1 0 0 +EDGE2 1625 1305 -0.045038 -0.0462829 -3.129 1 0 1 1 0 0 +EDGE2 1625 1605 0.0144592 0.117102 -0.0152928 1 0 1 1 0 0 +EDGE2 1625 1284 0.944524 0.0813845 -3.11767 1 0 1 1 0 0 +EDGE2 1625 1606 0.063646 1.02889 1.57662 1 0 1 1 0 0 +EDGE2 1625 1306 -0.00595172 0.973877 1.57205 1 0 1 1 0 0 +EDGE2 1626 1625 -1.03151 -0.0109989 -1.61183 1 0 1 1 0 0 +EDGE2 1626 1285 -0.940519 -0.0355687 1.56699 1 0 1 1 0 0 +EDGE2 1626 1305 -1.01174 -0.01378 1.58323 1 0 1 1 0 0 +EDGE2 1626 1605 -1.00569 -0.0510569 -1.56963 1 0 1 1 0 0 +EDGE2 1626 1606 0.0395925 -0.00644632 -0.00163448 1 0 1 1 0 0 +EDGE2 1626 1306 0.000248395 0.100896 -0.000935972 1 0 1 1 0 0 +EDGE2 1626 1607 1.0493 -0.0240224 -0.00364625 1 0 1 1 0 0 +EDGE2 1626 1307 1.03287 0.059511 -0.0034698 1 0 1 1 0 0 +EDGE2 1627 1606 -1.05891 -0.0117809 -0.027113 1 0 1 1 0 0 +EDGE2 1627 1626 -1.04631 0.0264587 0.00897071 1 0 1 1 0 0 +EDGE2 1627 1306 -1.00012 -0.0522813 0.0370744 1 0 1 1 0 0 +EDGE2 1627 1607 0.0819122 -0.00447614 -0.0131441 1 0 1 1 0 0 +EDGE2 1627 1307 0.0513903 -0.0332111 0.0183045 1 0 1 1 0 0 +EDGE2 1627 1308 0.958841 0.0381741 -0.0210549 1 0 1 1 0 0 +EDGE2 1627 1608 1.07026 -0.12849 0.0223818 1 0 1 1 0 0 +EDGE2 1628 1607 -0.986156 0.0267067 -0.037843 1 0 1 1 0 0 +EDGE2 1628 1627 -0.976695 0.0197826 0.0151526 1 0 1 1 0 0 +EDGE2 1628 1307 -0.962917 -0.0267194 0.0357442 1 0 1 1 0 0 +EDGE2 1628 1609 0.966216 -0.0231165 -0.00304434 1 0 1 1 0 0 +EDGE2 1628 1308 -0.0540575 -0.0147217 0.00762955 1 0 1 1 0 0 +EDGE2 1628 1608 0.0222547 -0.062415 0.0209593 1 0 1 1 0 0 +EDGE2 1628 1309 1.00913 -0.00280347 -0.00676518 1 0 1 1 0 0 +EDGE2 1629 1609 0.0309071 -0.00202461 -0.0239603 1 0 1 1 0 0 +EDGE2 1629 1308 -1.02163 0.0504479 -0.0242733 1 0 1 1 0 0 +EDGE2 1629 1608 -1.00712 -0.0244914 0.0192678 1 0 1 1 0 0 +EDGE2 1629 1628 -1.06427 0.0611028 0.0415672 1 0 1 1 0 0 +EDGE2 1629 1309 0.0916664 -0.0048312 -0.00669274 1 0 1 1 0 0 +EDGE2 1629 1610 0.944574 -0.0496442 -0.00068335 1 0 1 1 0 0 +EDGE2 1629 1310 0.974196 -0.0379939 -0.00999963 1 0 1 1 0 0 +EDGE2 1630 1609 -1.02881 -0.0682493 -0.0205833 1 0 1 1 0 0 +EDGE2 1630 1629 -0.974294 0.034264 -0.0205262 1 0 1 1 0 0 +EDGE2 1630 1309 -1.05897 -0.0793468 -0.00911742 1 0 1 1 0 0 +EDGE2 1630 1611 0.0525539 0.955256 1.59447 1 0 1 1 0 0 +EDGE2 1630 1311 0.0365542 1.04627 1.57484 1 0 1 1 0 0 +EDGE2 1630 1610 -0.0213859 -0.0527692 -0.0114188 1 0 1 1 0 0 +EDGE2 1630 1310 0.0283301 -0.0248729 -0.0101272 1 0 1 1 0 0 +EDGE2 1631 1612 0.999852 0.0286347 0.0174447 1 0 1 1 0 0 +EDGE2 1631 1611 -0.0227019 0.0338522 0.0225095 1 0 1 1 0 0 +EDGE2 1631 1312 1.06438 0.0390513 0.0120383 1 0 1 1 0 0 +EDGE2 1631 1311 0.0542182 0.0207649 0.020844 1 0 1 1 0 0 +EDGE2 1631 1610 -0.992991 -0.0161134 -1.58235 1 0 1 1 0 0 +EDGE2 1631 1630 -0.967424 0.0534863 -1.59281 1 0 1 1 0 0 +EDGE2 1631 1310 -0.969446 -0.0324859 -1.55168 1 0 1 1 0 0 +EDGE2 1632 1612 -0.0204631 0.0140457 0.0226559 1 0 1 1 0 0 +EDGE2 1632 1313 0.964793 -0.0111321 0.00109514 1 0 1 1 0 0 +EDGE2 1632 1613 1.01579 0.116947 0.00258262 1 0 1 1 0 0 +EDGE2 1632 1611 -0.958809 0.0750882 -0.0389354 1 0 1 1 0 0 +EDGE2 1632 1631 -0.994237 0.0501949 0.010079 1 0 1 1 0 0 +EDGE2 1632 1312 -0.00143849 0.00972271 -0.0149959 1 0 1 1 0 0 +EDGE2 1632 1311 -0.995754 -0.0981236 -0.0291946 1 0 1 1 0 0 +EDGE2 1633 1314 0.952188 0.0187662 0.0304267 1 0 1 1 0 0 +EDGE2 1633 1614 0.984312 -0.0818593 -0.0212657 1 0 1 1 0 0 +EDGE2 1633 1612 -1.08517 -0.0208003 -0.00594321 1 0 1 1 0 0 +EDGE2 1633 1313 -0.0544111 0.00539292 -0.0321823 1 0 1 1 0 0 +EDGE2 1633 1613 -0.0446563 -0.0467626 -0.00931591 1 0 1 1 0 0 +EDGE2 1633 1632 -1.01582 0.0554477 0.0346391 1 0 1 1 0 0 +EDGE2 1633 1312 -1.1096 0.0279508 0.00758014 1 0 1 1 0 0 +EDGE2 1634 1314 -0.0806684 -0.0318738 0.0100973 1 0 1 1 0 0 +EDGE2 1634 1315 1.01403 0.00883096 -0.00738123 1 0 1 1 0 0 +EDGE2 1634 1615 0.963282 0.0854146 -0.0151082 1 0 1 1 0 0 +EDGE2 1634 1614 -0.0142417 0.00311057 0.0142365 1 0 1 1 0 0 +EDGE2 1634 1313 -1.00165 0.0723355 0.0134921 1 0 1 1 0 0 +EDGE2 1634 1613 -1.02033 -0.00181217 0.00715645 1 0 1 1 0 0 +EDGE2 1634 1633 -1.09527 0.0408291 0.0305015 1 0 1 1 0 0 +EDGE2 1635 1316 0.017234 1.09017 1.5864 1 0 1 1 0 0 +EDGE2 1635 1616 -0.00855584 1.04421 1.53953 1 0 1 1 0 0 +EDGE2 1635 1314 -1.04137 -0.0792534 -0.0133265 1 0 1 1 0 0 +EDGE2 1635 1634 -1.08711 -0.0744749 0.0286048 1 0 1 1 0 0 +EDGE2 1635 1315 0.0259802 -0.049066 0.00402127 1 0 1 1 0 0 +EDGE2 1635 1615 0.0145412 -0.0039525 -0.00693511 1 0 1 1 0 0 +EDGE2 1635 1614 -1.00677 -0.0525132 -0.0107631 1 0 1 1 0 0 +EDGE2 1636 1635 -1.02998 0.0268397 -1.61205 1 0 1 1 0 0 +EDGE2 1636 1617 1.03967 -0.0468483 0.0148104 1 0 1 1 0 0 +EDGE2 1636 1317 0.933765 -0.00576809 0.00576687 1 0 1 1 0 0 +EDGE2 1636 1316 -0.0267424 -0.0953566 -0.0159807 1 0 1 1 0 0 +EDGE2 1636 1616 -0.00126627 0.0123791 0.0214618 1 0 1 1 0 0 +EDGE2 1636 1315 -1.03044 0.128335 -1.58136 1 0 1 1 0 0 +EDGE2 1636 1615 -0.956471 -0.0884103 -1.58388 1 0 1 1 0 0 +EDGE2 1637 1618 1.05365 0.0523746 -0.0152222 1 0 1 1 0 0 +EDGE2 1637 1318 1.06919 0.00503473 -0.0155387 1 0 1 1 0 0 +EDGE2 1637 1617 -0.0324907 0.0523524 0.0157019 1 0 1 1 0 0 +EDGE2 1637 1317 -0.0215162 -0.112674 0.00742103 1 0 1 1 0 0 +EDGE2 1637 1316 -1.02315 -0.0478965 0.0463034 1 0 1 1 0 0 +EDGE2 1637 1616 -0.978775 -0.0267656 0.00498746 1 0 1 1 0 0 +EDGE2 1637 1636 -0.990818 0.0433057 0.0168563 1 0 1 1 0 0 +EDGE2 1638 1619 0.928491 -0.0040853 -0.0344238 1 0 1 1 0 0 +EDGE2 1638 1319 1.02434 -0.0260013 -0.00807287 1 0 1 1 0 0 +EDGE2 1638 1618 0.0171819 0.0341222 -0.0191518 1 0 1 1 0 0 +EDGE2 1638 1318 0.140781 -0.102416 0.0160815 1 0 1 1 0 0 +EDGE2 1638 1617 -0.946313 -0.011321 -0.00326487 1 0 1 1 0 0 +EDGE2 1638 1637 -1.0684 -0.0533231 0.0518837 1 0 1 1 0 0 +EDGE2 1638 1317 -0.926749 -0.088329 0.00900316 1 0 1 1 0 0 +EDGE2 1639 1520 0.997486 0.00204753 -3.14907 1 0 1 1 0 0 +EDGE2 1639 1620 1.03781 -0.0436231 -0.0163936 1 0 1 1 0 0 +EDGE2 1639 1600 1.0095 0.0382441 -3.17421 1 0 1 1 0 0 +EDGE2 1639 1320 1.0362 0.00959185 0.0383226 1 0 1 1 0 0 +EDGE2 1639 1619 -0.0720977 0.00405986 -0.0261705 1 0 1 1 0 0 +EDGE2 1639 1319 0.0709821 -0.0512392 0.018147 1 0 1 1 0 0 +EDGE2 1639 1618 -1.0744 -0.0390878 -0.00580143 1 0 1 1 0 0 +EDGE2 1639 1638 -0.912519 0.0232774 -0.00877687 1 0 1 1 0 0 +EDGE2 1639 1318 -1.00435 -0.0223352 -0.0147487 1 0 1 1 0 0 +EDGE2 1640 1599 0.945025 0.0916639 -3.13838 1 0 1 1 0 0 +EDGE2 1640 1519 1.0293 -0.0409119 -3.14091 1 0 1 1 0 0 +EDGE2 1640 1521 0.0752815 -0.939091 -1.5713 1 0 1 1 0 0 +EDGE2 1640 1321 0.00946703 -1.00107 -1.57425 1 0 1 1 0 0 +EDGE2 1640 1520 -0.0241188 -0.047693 -3.16395 1 0 1 1 0 0 +EDGE2 1640 1620 -0.034985 0.0263694 0.00991467 1 0 1 1 0 0 +EDGE2 1640 1600 -0.102056 0.100439 -3.17336 1 0 1 1 0 0 +EDGE2 1640 1621 0.00153387 1.00361 1.56437 1 0 1 1 0 0 +EDGE2 1640 1320 0.00602425 -0.0311119 -0.0500597 1 0 1 1 0 0 +EDGE2 1640 1601 0.0287667 0.95522 1.56083 1 0 1 1 0 0 +EDGE2 1640 1619 -1.00491 0.0220227 -0.00940384 1 0 1 1 0 0 +EDGE2 1640 1639 -0.997782 0.0188614 -0.016972 1 0 1 1 0 0 +EDGE2 1640 1319 -1.01778 -0.00222988 0.0276787 1 0 1 1 0 0 +EDGE2 1641 1322 0.903389 0.0422429 -0.0217257 1 0 1 1 0 0 +EDGE2 1641 1522 0.922677 -0.0803943 0.0553488 1 0 1 1 0 0 +EDGE2 1641 1521 0.116841 0.0493664 -0.028709 1 0 1 1 0 0 +EDGE2 1641 1321 0.0126967 0.0163337 0.000777103 1 0 1 1 0 0 +EDGE2 1641 1520 -0.964085 -0.0361686 -1.5445 1 0 1 1 0 0 +EDGE2 1641 1620 -0.970334 0.00592546 1.59432 1 0 1 1 0 0 +EDGE2 1641 1640 -1.01693 -0.0381593 1.56217 1 0 1 1 0 0 +EDGE2 1641 1600 -0.997867 0.0251219 -1.58996 1 0 1 1 0 0 +EDGE2 1641 1320 -0.983573 0.00144335 1.5814 1 0 1 1 0 0 +EDGE2 1642 1323 0.99659 0.0226236 -0.00358541 1 0 1 1 0 0 +EDGE2 1642 1523 1.07838 0.043481 -0.00234416 1 0 1 1 0 0 +EDGE2 1642 1322 0.0241612 -0.0449499 -0.0119563 1 0 1 1 0 0 +EDGE2 1642 1522 0.0912598 -0.0410435 -0.0286664 1 0 1 1 0 0 +EDGE2 1642 1521 -0.896061 0.000110077 -0.00215465 1 0 1 1 0 0 +EDGE2 1642 1641 -0.97554 -0.0345444 0.00330745 1 0 1 1 0 0 +EDGE2 1642 1321 -1.04526 0.0439882 -0.00057724 1 0 1 1 0 0 +EDGE2 1643 1524 0.988429 0.0393282 0.000625374 1 0 1 1 0 0 +EDGE2 1643 1324 0.948423 0.0541887 0.029315 1 0 1 1 0 0 +EDGE2 1643 1323 -0.042292 0.0440796 0.0374554 1 0 1 1 0 0 +EDGE2 1643 1523 0.0354452 -0.0316976 0.0167606 1 0 1 1 0 0 +EDGE2 1643 1322 -1.02519 0.0545389 -0.0117639 1 0 1 1 0 0 +EDGE2 1643 1642 -1.06365 0.0263953 -0.0343142 1 0 1 1 0 0 +EDGE2 1643 1522 -0.939491 -0.0628232 -0.0148213 1 0 1 1 0 0 +EDGE2 1644 1345 0.988499 0.0147736 -3.16425 1 0 1 1 0 0 +EDGE2 1644 1525 1.05004 0.0524565 -0.00916659 1 0 1 1 0 0 +EDGE2 1644 1485 1.08038 0.0859782 -3.17901 1 0 1 1 0 0 +EDGE2 1644 1505 1.04485 -0.0168207 -3.14939 1 0 1 1 0 0 +EDGE2 1644 1365 1.00975 0.0441353 -3.15194 1 0 1 1 0 0 +EDGE2 1644 1325 1.05549 -0.0322014 -0.0309649 1 0 1 1 0 0 +EDGE2 1644 1524 0.0335684 0.0271821 0.0138741 1 0 1 1 0 0 +EDGE2 1644 1324 -0.00913993 0.00872453 0.00962923 1 0 1 1 0 0 +EDGE2 1644 1323 -0.972734 0.0515954 -0.00521913 1 0 1 1 0 0 +EDGE2 1644 1643 -0.99081 0.0097156 0.00345114 1 0 1 1 0 0 +EDGE2 1644 1523 -1.07289 0.042588 -0.0453491 1 0 1 1 0 0 +EDGE2 1645 1345 0.0230485 -0.0370086 -3.14022 1 0 1 1 0 0 +EDGE2 1645 1526 0.0617404 0.989111 1.57802 1 0 1 1 0 0 +EDGE2 1645 1366 0.0638675 1.05975 1.57174 1 0 1 1 0 0 +EDGE2 1645 1506 0.0470736 1.06287 1.61956 1 0 1 1 0 0 +EDGE2 1645 1344 0.939908 0.0531478 -3.16323 1 0 1 1 0 0 +EDGE2 1645 1484 1.01587 -0.0252931 -3.1647 1 0 1 1 0 0 +EDGE2 1645 1504 0.974138 0.0517561 -3.14966 1 0 1 1 0 0 +EDGE2 1645 1364 1.00039 -0.0471777 -3.16848 1 0 1 1 0 0 +EDGE2 1645 1525 0.00400493 0.0114378 0.0188184 1 0 1 1 0 0 +EDGE2 1645 1485 -0.0142167 -0.047065 -3.13903 1 0 1 1 0 0 +EDGE2 1645 1505 0.0491068 0.0113157 -3.11946 1 0 1 1 0 0 +EDGE2 1645 1365 0.0452446 -0.00677487 -3.14632 1 0 1 1 0 0 +EDGE2 1645 1325 0.00518966 0.028395 -0.0300411 1 0 1 1 0 0 +EDGE2 1645 1524 -0.974694 0.0685774 0.0194154 1 0 1 1 0 0 +EDGE2 1645 1644 -1.02188 0.0253928 -0.00970953 1 0 1 1 0 0 +EDGE2 1645 1324 -0.964774 -0.0645348 0.0351594 1 0 1 1 0 0 +EDGE2 1645 1486 0.0569053 -1.02447 -1.57768 1 0 1 1 0 0 +EDGE2 1645 1326 -0.0617616 -1.00405 -1.58012 1 0 1 1 0 0 +EDGE2 1645 1346 0.070123 -0.950912 -1.5843 1 0 1 1 0 0 +EDGE2 1646 1345 -1.04309 -0.0302751 1.55962 1 0 1 1 0 0 +EDGE2 1646 1526 0.00547904 0.0697215 -0.0153318 1 0 1 1 0 0 +EDGE2 1646 1507 1.03234 0.0723245 -0.00961771 1 0 1 1 0 0 +EDGE2 1646 1527 0.889563 0.00219624 0.0124818 1 0 1 1 0 0 +EDGE2 1646 1367 0.879982 0.0328065 -0.0114255 1 0 1 1 0 0 +EDGE2 1646 1366 0.0621861 0.000104194 -0.0223063 1 0 1 1 0 0 +EDGE2 1646 1506 -0.0176282 0.097733 -0.00765692 1 0 1 1 0 0 +EDGE2 1646 1525 -0.992767 -0.0704168 -1.56762 1 0 1 1 0 0 +EDGE2 1646 1645 -1.04082 -0.00879628 -1.55302 1 0 1 1 0 0 +EDGE2 1646 1485 -0.974855 -0.0160973 1.57256 1 0 1 1 0 0 +EDGE2 1646 1505 -0.956639 0.0871685 1.57136 1 0 1 1 0 0 +EDGE2 1646 1365 -1.01087 -0.0708811 1.55114 1 0 1 1 0 0 +EDGE2 1646 1325 -0.968222 -0.0375185 -1.57775 1 0 1 1 0 0 +EDGE2 1647 1368 0.948405 0.00765425 0.0200501 1 0 1 1 0 0 +EDGE2 1647 1508 0.928772 0.0477742 0.00100871 1 0 1 1 0 0 +EDGE2 1647 1528 1.01949 0.0356041 -0.0100408 1 0 1 1 0 0 +EDGE2 1647 1526 -0.946059 -0.0771333 -0.000585571 1 0 1 1 0 0 +EDGE2 1647 1507 0.0345513 0.0615782 0.00355154 1 0 1 1 0 0 +EDGE2 1647 1527 0.0503094 -0.0231311 0.00443835 1 0 1 1 0 0 +EDGE2 1647 1367 0.0295602 0.00727191 0.0241065 1 0 1 1 0 0 +EDGE2 1647 1646 -0.990501 0.0301404 -0.00457963 1 0 1 1 0 0 +EDGE2 1647 1366 -1.02189 0.100873 0.0104816 1 0 1 1 0 0 +EDGE2 1647 1506 -1.04258 0.024515 0.014306 1 0 1 1 0 0 +EDGE2 1648 1509 1.0268 -0.105248 0.0131284 1 0 1 1 0 0 +EDGE2 1648 1529 1.01193 0.00825199 0.00138849 1 0 1 1 0 0 +EDGE2 1648 1369 1.03364 0.0647476 0.0330955 1 0 1 1 0 0 +EDGE2 1648 1368 -0.140565 0.0346326 0.0149108 1 0 1 1 0 0 +EDGE2 1648 1508 -0.0429968 0.00354677 0.0243058 1 0 1 1 0 0 +EDGE2 1648 1528 -0.00643563 0.00442938 0.00973222 1 0 1 1 0 0 +EDGE2 1648 1507 -1.03744 -0.0124225 -0.0172622 1 0 1 1 0 0 +EDGE2 1648 1527 -1.05786 -0.0144313 0.0110745 1 0 1 1 0 0 +EDGE2 1648 1647 -0.937731 -0.0125895 -0.0177582 1 0 1 1 0 0 +EDGE2 1648 1367 -0.999623 0.0114231 0.0185544 1 0 1 1 0 0 +EDGE2 1649 1470 0.950676 -0.0671104 -3.15897 1 0 1 1 0 0 +EDGE2 1649 1510 1.0206 0.093823 0.0117954 1 0 1 1 0 0 +EDGE2 1649 1530 1.00518 0.00612942 -0.0221265 1 0 1 1 0 0 +EDGE2 1649 1370 1.028 0.027886 0.0210813 1 0 1 1 0 0 +EDGE2 1649 1509 0.164411 -0.104946 0.0354529 1 0 1 1 0 0 +EDGE2 1649 1529 -0.0231721 -0.110512 -0.013128 1 0 1 1 0 0 +EDGE2 1649 1369 -0.0158394 -0.127289 0.0140374 1 0 1 1 0 0 +EDGE2 1649 1648 -1.00727 0.0264383 0.00567339 1 0 1 1 0 0 +EDGE2 1649 1368 -1.00268 0.00852951 0.0169043 1 0 1 1 0 0 +EDGE2 1649 1508 -1.02168 -0.0165923 0.0219664 1 0 1 1 0 0 +EDGE2 1649 1528 -1.13968 0.0142142 -0.0467061 1 0 1 1 0 0 +EDGE2 1650 1469 0.951866 0.027325 -3.12396 1 0 1 1 0 0 +EDGE2 1650 1471 0.0232766 -1.0412 -1.57176 1 0 1 1 0 0 +EDGE2 1650 1470 -0.0550515 0.0609424 -3.1373 1 0 1 1 0 0 +EDGE2 1650 1510 0.0108944 0.00218453 -0.00112569 1 0 1 1 0 0 +EDGE2 1650 1530 -0.0420554 -0.0303945 0.0032948 1 0 1 1 0 0 +EDGE2 1650 1370 -0.041332 -0.0659239 -0.000822438 1 0 1 1 0 0 +EDGE2 1650 1371 0.090277 0.94397 1.55766 1 0 1 1 0 0 +EDGE2 1650 1531 -0.0414104 0.991142 1.54818 1 0 1 1 0 0 +EDGE2 1650 1511 0.0588156 1.06817 1.56812 1 0 1 1 0 0 +EDGE2 1650 1509 -0.960645 0.0146301 0.0301096 1 0 1 1 0 0 +EDGE2 1650 1649 -1.02926 -0.0359754 -0.0217906 1 0 1 1 0 0 +EDGE2 1650 1529 -0.967409 -0.0519583 -0.00852305 1 0 1 1 0 0 +EDGE2 1650 1369 -0.967926 0.026599 -0.00508503 1 0 1 1 0 0 +EDGE2 1651 1650 -1.02269 0.0435178 -1.54369 1 0 1 1 0 0 +EDGE2 1651 1470 -1.10199 0.0249127 1.57394 1 0 1 1 0 0 +EDGE2 1651 1510 -1.00104 -0.0117375 -1.5693 1 0 1 1 0 0 +EDGE2 1651 1530 -1.0726 -0.0296264 -1.56113 1 0 1 1 0 0 +EDGE2 1651 1370 -0.99002 -0.0370232 -1.53811 1 0 1 1 0 0 +EDGE2 1651 1371 0.0286009 -0.0189468 0.025639 1 0 1 1 0 0 +EDGE2 1651 1531 -0.0590218 -0.0389323 -0.00383802 1 0 1 1 0 0 +EDGE2 1651 1511 -0.00576976 -0.00802555 -0.00826819 1 0 1 1 0 0 +EDGE2 1651 1512 1.09081 0.0131463 -0.00778403 1 0 1 1 0 0 +EDGE2 1651 1532 0.997606 -0.0406402 0.0157338 1 0 1 1 0 0 +EDGE2 1651 1372 1.0644 -0.0291423 0.00101253 1 0 1 1 0 0 +EDGE2 1652 1371 -1.1099 0.050766 -0.022306 1 0 1 1 0 0 +EDGE2 1652 1531 -1.01616 0.0327394 -0.0228776 1 0 1 1 0 0 +EDGE2 1652 1651 -0.921563 -0.00109132 -0.0149906 1 0 1 1 0 0 +EDGE2 1652 1511 -1.06785 -0.0351711 -0.0112061 1 0 1 1 0 0 +EDGE2 1652 1512 0.0223434 -0.0185734 -0.00841309 1 0 1 1 0 0 +EDGE2 1652 1532 0.0113292 0.00442265 0.0137341 1 0 1 1 0 0 +EDGE2 1652 1372 0.0111725 -0.0469858 0.0367002 1 0 1 1 0 0 +EDGE2 1652 1513 1.06238 0.0177325 -0.0151123 1 0 1 1 0 0 +EDGE2 1652 1533 1.04262 0.0229882 -0.00984102 1 0 1 1 0 0 +EDGE2 1652 1373 1.02749 0.0919467 -0.0139428 1 0 1 1 0 0 +EDGE2 1653 1512 -1.08019 0.00226306 0.0017451 1 0 1 1 0 0 +EDGE2 1653 1652 -1.06198 -0.0382007 0.0251548 1 0 1 1 0 0 +EDGE2 1653 1532 -1.03599 0.060361 0.000113509 1 0 1 1 0 0 +EDGE2 1653 1372 -1.01838 0.00240443 0.00503989 1 0 1 1 0 0 +EDGE2 1653 1513 0.0549058 -0.0628144 -0.0192923 1 0 1 1 0 0 +EDGE2 1653 1533 0.0116799 0.023934 0.0128743 1 0 1 1 0 0 +EDGE2 1653 1373 -0.0312055 0.0738497 -0.0167385 1 0 1 1 0 0 +EDGE2 1653 1514 0.976706 0.0865758 0.00295527 1 0 1 1 0 0 +EDGE2 1653 1534 0.988721 0.0435273 0.0281618 1 0 1 1 0 0 +EDGE2 1653 1374 0.989204 -0.0277793 0.0169305 1 0 1 1 0 0 +EDGE2 1654 1535 0.955157 0.00651774 0.0266706 1 0 1 1 0 0 +EDGE2 1654 1513 -1.02903 0.00359335 0.0219724 1 0 1 1 0 0 +EDGE2 1654 1653 -0.952525 0.0670643 -0.0135454 1 0 1 1 0 0 +EDGE2 1654 1533 -0.975694 -0.0635169 0.0285196 1 0 1 1 0 0 +EDGE2 1654 1373 -0.991173 -0.00133465 -0.0418016 1 0 1 1 0 0 +EDGE2 1654 1514 0.0680466 -0.0215614 -0.0199551 1 0 1 1 0 0 +EDGE2 1654 1534 -0.000599194 0.00628671 -0.0253752 1 0 1 1 0 0 +EDGE2 1654 1374 0.0401506 -0.0581243 -0.00514325 1 0 1 1 0 0 +EDGE2 1654 1595 1.04193 -0.0226353 -3.16149 1 0 1 1 0 0 +EDGE2 1654 1575 0.939264 -0.0244151 -3.14372 1 0 1 1 0 0 +EDGE2 1654 1375 1.07576 -0.0330437 0.00715361 1 0 1 1 0 0 +EDGE2 1654 1515 1.02807 -0.0197469 0.0122875 1 0 1 1 0 0 +EDGE2 1655 1536 0.0144628 -1.08241 -1.57988 1 0 1 1 0 0 +EDGE2 1655 1576 0.0482069 -0.965093 -1.56941 1 0 1 1 0 0 +EDGE2 1655 1376 -0.0376512 -0.97755 -1.57968 1 0 1 1 0 0 +EDGE2 1655 1535 0.0813806 -0.00541617 0.0156823 1 0 1 1 0 0 +EDGE2 1655 1514 -0.985489 -0.0810402 -0.0138542 1 0 1 1 0 0 +EDGE2 1655 1654 -1.0316 0.0391953 0.0216909 1 0 1 1 0 0 +EDGE2 1655 1534 -1.08268 -0.0286286 -0.0127092 1 0 1 1 0 0 +EDGE2 1655 1374 -1.04066 0.0806919 -0.0119007 1 0 1 1 0 0 +EDGE2 1655 1595 -0.00463964 0.000478161 -3.17282 1 0 1 1 0 0 +EDGE2 1655 1575 0.01145 -0.0699801 -3.10944 1 0 1 1 0 0 +EDGE2 1655 1375 0.0608588 0.122622 0.0182199 1 0 1 1 0 0 +EDGE2 1655 1515 -0.0136591 0.00181202 0.00343092 1 0 1 1 0 0 +EDGE2 1655 1574 1.04186 0.00380927 -3.13917 1 0 1 1 0 0 +EDGE2 1655 1594 1.03761 0.0327048 -3.16561 1 0 1 1 0 0 +EDGE2 1655 1516 -0.0147154 1.02854 1.57911 1 0 1 1 0 0 +EDGE2 1655 1596 -0.0687364 0.987749 1.58137 1 0 1 1 0 0 +EDGE2 1656 1537 1.06707 0.0272793 0.00965205 1 0 1 1 0 0 +EDGE2 1656 1577 1.0126 0.0307176 0.0387542 1 0 1 1 0 0 +EDGE2 1656 1377 0.972972 -0.0292756 -0.0178643 1 0 1 1 0 0 +EDGE2 1656 1536 -0.00965616 -0.127306 -0.0333371 1 0 1 1 0 0 +EDGE2 1656 1576 -0.0371899 -0.00842524 -0.010308 1 0 1 1 0 0 +EDGE2 1656 1376 0.0561564 -0.0187816 -0.0191484 1 0 1 1 0 0 +EDGE2 1656 1535 -1.04982 -0.0684614 1.58505 1 0 1 1 0 0 +EDGE2 1656 1595 -1.06141 -0.0104656 -1.59432 1 0 1 1 0 0 +EDGE2 1656 1655 -0.965776 -0.0069592 1.58401 1 0 1 1 0 0 +EDGE2 1656 1575 -0.988318 -0.0952976 -1.56455 1 0 1 1 0 0 +EDGE2 1656 1375 -0.979624 0.0571002 1.57311 1 0 1 1 0 0 +EDGE2 1656 1515 -0.983996 0.00257152 1.57641 1 0 1 1 0 0 +EDGE2 1657 1378 0.989351 -0.0462835 -0.0312459 1 0 1 1 0 0 +EDGE2 1657 1578 1.06812 -0.0531985 0.01483 1 0 1 1 0 0 +EDGE2 1657 1538 1.05894 0.0819718 -0.0367063 1 0 1 1 0 0 +EDGE2 1657 1537 -0.00712407 -0.042891 -0.00879898 1 0 1 1 0 0 +EDGE2 1657 1577 0.0415587 0.0521806 -0.0292933 1 0 1 1 0 0 +EDGE2 1657 1656 -1.11694 -0.0266108 -0.00735343 1 0 1 1 0 0 +EDGE2 1657 1377 -0.0209915 0.00925333 -0.0375458 1 0 1 1 0 0 +EDGE2 1657 1536 -0.985662 -0.00399423 0.02293 1 0 1 1 0 0 +EDGE2 1657 1576 -1.00617 -0.114944 -0.0368288 1 0 1 1 0 0 +EDGE2 1657 1376 -1.00227 0.0151055 -0.0265297 1 0 1 1 0 0 +EDGE2 1658 1378 0.0400483 0.0130843 0.00840358 1 0 1 1 0 0 +EDGE2 1658 1579 1.0583 0.0321538 -0.00610184 1 0 1 1 0 0 +EDGE2 1658 1379 0.950697 -0.0647519 0.000740012 1 0 1 1 0 0 +EDGE2 1658 1539 0.99355 -0.0529336 -0.00484373 1 0 1 1 0 0 +EDGE2 1658 1578 0.060859 0.0462338 -0.00576692 1 0 1 1 0 0 +EDGE2 1658 1538 0.0233999 -0.051762 -0.0117028 1 0 1 1 0 0 +EDGE2 1658 1537 -0.99815 -0.00784495 0.00207348 1 0 1 1 0 0 +EDGE2 1658 1577 -0.982982 -0.0209198 -0.00186013 1 0 1 1 0 0 +EDGE2 1658 1657 -0.992322 0.0446576 -0.0284125 1 0 1 1 0 0 +EDGE2 1658 1377 -0.930148 0.068385 -0.0572098 1 0 1 1 0 0 +EDGE2 1659 1540 0.953738 0.00719711 -0.0302548 1 0 1 1 0 0 +EDGE2 1659 1580 0.985728 -0.00193594 -0.0228046 1 0 1 1 0 0 +EDGE2 1659 1560 0.999572 -0.0105569 -3.17593 1 0 1 1 0 0 +EDGE2 1659 1380 0.9991 -0.0353716 -0.0175976 1 0 1 1 0 0 +EDGE2 1659 1378 -1.08997 0.00412903 -0.0143839 1 0 1 1 0 0 +EDGE2 1659 1579 0.0473665 0.0451716 -0.00665468 1 0 1 1 0 0 +EDGE2 1659 1379 -0.0281696 -0.0516987 0.0452357 1 0 1 1 0 0 +EDGE2 1659 1539 -0.047847 0.0666641 0.0130048 1 0 1 1 0 0 +EDGE2 1659 1578 -0.96924 -0.0141717 0.00286864 1 0 1 1 0 0 +EDGE2 1659 1658 -0.990475 0.0463567 0.0173953 1 0 1 1 0 0 +EDGE2 1659 1538 -0.966105 -0.0441351 -0.0496573 1 0 1 1 0 0 +EDGE2 1660 1559 1.03231 0.100643 -3.1327 1 0 1 1 0 0 +EDGE2 1660 1540 0.0120526 0.0514138 -0.00404476 1 0 1 1 0 0 +EDGE2 1660 1381 0.00778069 -1.06666 -1.59875 1 0 1 1 0 0 +EDGE2 1660 1580 -0.0195828 -0.050681 -0.00471934 1 0 1 1 0 0 +EDGE2 1660 1560 0.0458424 0.0334858 -3.1308 1 0 1 1 0 0 +EDGE2 1660 1581 -0.0420815 1.06768 1.54802 1 0 1 1 0 0 +EDGE2 1660 1380 -0.029873 -0.00369341 -0.00039689 1 0 1 1 0 0 +EDGE2 1660 1541 -0.0583239 0.969746 1.56348 1 0 1 1 0 0 +EDGE2 1660 1561 0.0965025 1.02022 1.5616 1 0 1 1 0 0 +EDGE2 1660 1579 -0.982807 0.0471452 -0.0178547 1 0 1 1 0 0 +EDGE2 1660 1659 -1.03109 0.0014085 -0.0266198 1 0 1 1 0 0 +EDGE2 1660 1379 -0.98295 0.0226743 -0.0607296 1 0 1 1 0 0 +EDGE2 1660 1539 -0.936275 -0.0840579 -0.00328577 1 0 1 1 0 0 +EDGE2 1661 1540 -0.971459 -0.0345682 1.6036 1 0 1 1 0 0 +EDGE2 1661 1382 0.904696 0.034826 0.0376123 1 0 1 1 0 0 +EDGE2 1661 1381 -0.0485362 -0.00718458 -0.00917177 1 0 1 1 0 0 +EDGE2 1661 1580 -1.02212 0.00712657 1.57612 1 0 1 1 0 0 +EDGE2 1661 1660 -0.976792 0.0196623 1.55846 1 0 1 1 0 0 +EDGE2 1661 1560 -1.01132 0.0479461 -1.56832 1 0 1 1 0 0 +EDGE2 1661 1380 -0.98115 0.0493036 1.54273 1 0 1 1 0 0 +EDGE2 1662 1383 1.00738 -0.124571 -0.0091251 1 0 1 1 0 0 +EDGE2 1662 1382 0.0440752 -0.0205766 0.0242754 1 0 1 1 0 0 +EDGE2 1662 1381 -1.05613 -0.0537507 -0.00177715 1 0 1 1 0 0 +EDGE2 1662 1661 -0.986381 0.0392927 0.0150311 1 0 1 1 0 0 +EDGE2 1663 1384 1.01611 -0.0672361 -0.00732126 1 0 1 1 0 0 +EDGE2 1663 1662 -1.04188 0.0435012 0.000222597 1 0 1 1 0 0 +EDGE2 1663 1383 0.00310481 -0.00847256 -0.00573274 1 0 1 1 0 0 +EDGE2 1663 1382 -1.03304 -0.070404 0.0138595 1 0 1 1 0 0 +EDGE2 1664 1385 0.943481 -0.047532 -0.00610128 1 0 1 1 0 0 +EDGE2 1664 1465 0.93136 -0.00681998 -3.18583 1 0 1 1 0 0 +EDGE2 1664 1663 -0.987829 0.0179536 -0.00593102 1 0 1 1 0 0 +EDGE2 1664 1384 0.00981311 0.0604731 0.00351453 1 0 1 1 0 0 +EDGE2 1664 1383 -1.02775 0.0383356 0.00432782 1 0 1 1 0 0 +EDGE2 1665 1386 0.00878857 0.920413 1.57346 1 0 1 1 0 0 +EDGE2 1665 1464 0.968622 0.0108367 -3.17452 1 0 1 1 0 0 +EDGE2 1665 1385 0.0385595 -0.00276127 -0.00926675 1 0 1 1 0 0 +EDGE2 1665 1465 0.0965048 0.024905 -3.14293 1 0 1 1 0 0 +EDGE2 1665 1466 -0.0364301 -0.945978 -1.57733 1 0 1 1 0 0 +EDGE2 1665 1384 -0.950458 -0.0481411 -0.0110074 1 0 1 1 0 0 +EDGE2 1665 1664 -0.951033 -0.102543 0.00799039 1 0 1 1 0 0 +EDGE2 1666 1665 -0.991785 0.0396038 1.57209 1 0 1 1 0 0 +EDGE2 1666 1385 -0.957447 0.0180209 1.58441 1 0 1 1 0 0 +EDGE2 1666 1465 -1.02874 -0.0395801 -1.56427 1 0 1 1 0 0 +EDGE2 1666 1466 0.023104 -0.00505015 0.00312301 1 0 1 1 0 0 +EDGE2 1666 1467 1.01072 0.00358259 -0.0218026 1 0 1 1 0 0 +EDGE2 1667 1468 1.01542 0.0425163 -0.00497521 1 0 1 1 0 0 +EDGE2 1667 1666 -0.935481 -0.033241 -0.0142818 1 0 1 1 0 0 +EDGE2 1667 1466 -0.939846 0.0220635 -0.00918821 1 0 1 1 0 0 +EDGE2 1667 1467 0.0212495 -0.0116234 0.0136194 1 0 1 1 0 0 +EDGE2 1668 1468 -0.0712344 -0.0612789 0.00949023 1 0 1 1 0 0 +EDGE2 1668 1667 -1.09085 0.0202365 0.0252597 1 0 1 1 0 0 +EDGE2 1668 1467 -1.03756 0.017055 0.0160139 1 0 1 1 0 0 +EDGE2 1668 1469 1.04812 0.0349201 0.019555 1 0 1 1 0 0 +EDGE2 1669 1468 -0.937909 0.0369129 0.0169289 1 0 1 1 0 0 +EDGE2 1669 1668 -0.966102 0.00346807 0.00639633 1 0 1 1 0 0 +EDGE2 1669 1469 -0.0289711 0.0015371 -0.0229876 1 0 1 1 0 0 +EDGE2 1669 1650 1.04021 0.064755 -3.13337 1 0 1 1 0 0 +EDGE2 1669 1470 1.04543 -0.0505626 -0.0148085 1 0 1 1 0 0 +EDGE2 1669 1510 0.985185 -0.0273292 -3.14219 1 0 1 1 0 0 +EDGE2 1669 1530 1.04046 -0.0683205 -3.14083 1 0 1 1 0 0 +EDGE2 1669 1370 0.932829 -0.053049 -3.13593 1 0 1 1 0 0 +EDGE2 1670 1669 -0.993026 -0.000968192 -0.0468824 1 0 1 1 0 0 +EDGE2 1670 1469 -1.00168 -0.0168238 0.0249233 1 0 1 1 0 0 +EDGE2 1670 1471 -0.0215114 1.02159 1.55519 1 0 1 1 0 0 +EDGE2 1670 1650 0.0467845 -0.0713583 -3.16683 1 0 1 1 0 0 +EDGE2 1670 1470 0.065296 -0.0308679 0.0104761 1 0 1 1 0 0 +EDGE2 1670 1510 -0.01408 -0.0768072 -3.13479 1 0 1 1 0 0 +EDGE2 1670 1530 0.050612 -0.0292756 -3.15128 1 0 1 1 0 0 +EDGE2 1670 1370 -0.00521331 -0.11553 -3.14627 1 0 1 1 0 0 +EDGE2 1670 1371 -0.00230802 -1.03252 -1.58874 1 0 1 1 0 0 +EDGE2 1670 1531 0.0270033 -1.05948 -1.54444 1 0 1 1 0 0 +EDGE2 1670 1651 0.0527061 -0.984694 -1.53069 1 0 1 1 0 0 +EDGE2 1670 1511 0.0605238 -1.01198 -1.57468 1 0 1 1 0 0 +EDGE2 1670 1509 0.896262 0.0316147 -3.14932 1 0 1 1 0 0 +EDGE2 1670 1649 1.00527 -0.0206279 -3.15216 1 0 1 1 0 0 +EDGE2 1670 1529 1.03116 -0.0433283 -3.11087 1 0 1 1 0 0 +EDGE2 1670 1369 0.960481 -0.022489 -3.13377 1 0 1 1 0 0 +EDGE2 1671 1472 0.958747 0.0686675 0.0160433 1 0 1 1 0 0 +EDGE2 1671 1471 -0.0188549 -0.0247653 0.0145173 1 0 1 1 0 0 +EDGE2 1671 1650 -0.982666 -0.143184 1.57662 1 0 1 1 0 0 +EDGE2 1671 1670 -0.957329 0.0149475 -1.53768 1 0 1 1 0 0 +EDGE2 1671 1470 -0.955979 0.0181639 -1.6094 1 0 1 1 0 0 +EDGE2 1671 1510 -0.993793 0.0381683 1.56703 1 0 1 1 0 0 +EDGE2 1671 1530 -0.926566 -0.0456411 1.58408 1 0 1 1 0 0 +EDGE2 1671 1370 -1.11354 0.0109404 1.55211 1 0 1 1 0 0 +EDGE2 1672 1473 0.891152 0.0512546 0.00618327 1 0 1 1 0 0 +EDGE2 1672 1472 0.0694709 0.0751838 0.0179245 1 0 1 1 0 0 +EDGE2 1672 1671 -1.05652 0.00996902 -0.0259609 1 0 1 1 0 0 +EDGE2 1672 1471 -1.03206 -0.0369534 -0.0123292 1 0 1 1 0 0 +EDGE2 1673 1474 0.855157 -0.0487676 0.0437437 1 0 1 1 0 0 +EDGE2 1673 1473 0.026395 0.0107844 -0.00586486 1 0 1 1 0 0 +EDGE2 1673 1672 -1.03689 -0.041013 -0.00490431 1 0 1 1 0 0 +EDGE2 1673 1472 -0.977432 0.0622424 -0.0342156 1 0 1 1 0 0 +EDGE2 1674 1475 0.904825 0.0076384 0.0292324 1 0 1 1 0 0 +EDGE2 1674 1474 0.00620301 0.0290023 0.0434319 1 0 1 1 0 0 +EDGE2 1674 1473 -0.986529 0.00622346 -0.00790602 1 0 1 1 0 0 +EDGE2 1674 1673 -1.00212 -0.0223055 0.0253866 1 0 1 1 0 0 +EDGE2 1675 1475 0.0664613 0.0432944 -0.00212919 1 0 1 1 0 0 +EDGE2 1675 1474 -1.07288 0.0692385 0.00664348 1 0 1 1 0 0 +EDGE2 1675 1674 -0.990509 0.0654322 -0.00489659 1 0 1 1 0 0 +EDGE2 1675 1476 0.0821108 -1.07119 -1.55894 1 0 1 1 0 0 +EDGE2 1676 1475 -1.0162 0.0575425 1.59133 1 0 1 1 0 0 +EDGE2 1676 1675 -1.02067 0.0548529 1.58061 1 0 1 1 0 0 +EDGE2 1676 1476 0.0121001 0.0365854 0.00910663 1 0 1 1 0 0 +EDGE2 1676 1477 1.12096 0.00299136 0.014578 1 0 1 1 0 0 +EDGE2 1677 1676 -1.11315 -0.0410359 -0.0130999 1 0 1 1 0 0 +EDGE2 1677 1476 -0.985653 0.00446199 -0.0381262 1 0 1 1 0 0 +EDGE2 1677 1477 -0.0373583 0.00271603 -0.0307275 1 0 1 1 0 0 +EDGE2 1677 1478 0.99567 -0.0661116 0.00421266 1 0 1 1 0 0 +EDGE2 1678 1677 -1.07493 0.0304263 -0.00380064 1 0 1 1 0 0 +EDGE2 1678 1477 -0.982051 0.0435613 0.0147138 1 0 1 1 0 0 +EDGE2 1678 1478 0.00292866 0.0260704 -0.0325045 1 0 1 1 0 0 +EDGE2 1678 1479 0.994631 -0.0118808 0.00229976 1 0 1 1 0 0 +EDGE2 1679 1678 -1.00172 -0.0126161 0.00405577 1 0 1 1 0 0 +EDGE2 1679 1478 -1.03921 -0.0225026 -0.00436515 1 0 1 1 0 0 +EDGE2 1679 1360 0.868377 -0.117457 -3.15988 1 0 1 1 0 0 +EDGE2 1679 1479 -0.0454503 0.024397 0.00796636 1 0 1 1 0 0 +EDGE2 1679 1500 0.997337 -0.00484764 -3.13292 1 0 1 1 0 0 +EDGE2 1679 1480 1.09093 -0.0369132 0.00755057 1 0 1 1 0 0 +EDGE2 1679 1340 1.09876 -0.00211819 -3.16767 1 0 1 1 0 0 +EDGE2 1680 1360 -0.0405272 0.0953423 -3.12044 1 0 1 1 0 0 +EDGE2 1680 1679 -1.01522 -0.026121 0.00253147 1 0 1 1 0 0 +EDGE2 1680 1479 -0.962724 -0.0544145 0.00365367 1 0 1 1 0 0 +EDGE2 1680 1500 0.0256893 -0.00432218 -3.12523 1 0 1 1 0 0 +EDGE2 1680 1480 0.0478867 0.0143478 0.00770106 1 0 1 1 0 0 +EDGE2 1680 1481 -0.0187709 -0.998732 -1.56822 1 0 1 1 0 0 +EDGE2 1680 1340 0.0142515 0.00561371 -3.10848 1 0 1 1 0 0 +EDGE2 1680 1501 -0.00818043 -0.983906 -1.52646 1 0 1 1 0 0 +EDGE2 1680 1341 -0.00446725 -1.0675 -1.59532 1 0 1 1 0 0 +EDGE2 1680 1361 0.0335802 -1.01548 -1.57602 1 0 1 1 0 0 +EDGE2 1680 1359 1.00005 -0.0103876 -3.17772 1 0 1 1 0 0 +EDGE2 1680 1499 1.12367 0.0750905 -3.12663 1 0 1 1 0 0 +EDGE2 1680 1339 1.05638 0.05645 -3.15622 1 0 1 1 0 0 +EDGE2 1681 1360 -0.97023 0.025983 1.55937 1 0 1 1 0 0 +EDGE2 1681 1500 -0.994155 0.00542635 1.54898 1 0 1 1 0 0 +EDGE2 1681 1680 -1.07039 0.0279771 -1.5599 1 0 1 1 0 0 +EDGE2 1681 1480 -0.939317 0.0683763 -1.57705 1 0 1 1 0 0 +EDGE2 1681 1340 -1.06262 -0.0555264 1.54891 1 0 1 1 0 0 +EDGE2 1682 1681 -1.04756 0.0153988 -0.0239518 1 0 1 1 0 0 +EDGE2 1683 1682 -1.00609 0.0142039 0.021239 1 0 1 1 0 0 +EDGE2 1684 1683 -0.983967 -0.0555853 -0.00338785 1 0 1 1 0 0 +EDGE2 1685 1684 -1.01855 0.0218844 0.00965785 1 0 1 1 0 0 +EDGE2 1686 1685 -0.922347 -0.0271618 -1.56115 1 0 1 1 0 0 +EDGE2 1687 1686 -0.954508 -0.028872 0.00515418 1 0 1 1 0 0 +EDGE2 1688 1687 -1.03018 0.032646 0.00570482 1 0 1 1 0 0 +EDGE2 1689 1688 -1.00113 -0.025312 -0.00123617 1 0 1 1 0 0 +EDGE2 1690 1689 -0.988311 -0.0850289 -0.0146286 1 0 1 1 0 0 +EDGE2 1691 1690 -0.942697 -0.109891 -1.56121 1 0 1 1 0 0 +EDGE2 1692 1691 -0.972323 0.0290407 -0.000745383 1 0 1 1 0 0 +EDGE2 1693 1692 -1.06833 0.042365 0.0362044 1 0 1 1 0 0 +EDGE2 1694 1693 -1.03463 -0.0540186 -0.0337268 1 0 1 1 0 0 +EDGE2 1694 1475 1.07145 0.0396781 -3.11899 1 0 1 1 0 0 +EDGE2 1694 1675 0.958752 0.03653 -3.10747 1 0 1 1 0 0 +EDGE2 1695 1694 -1.01584 -0.0620422 -0.0262693 1 0 1 1 0 0 +EDGE2 1695 1475 0.0515816 0.0186382 -3.14293 1 0 1 1 0 0 +EDGE2 1695 1675 -0.0287831 -0.0423771 -3.13311 1 0 1 1 0 0 +EDGE2 1695 1474 1.01684 0.0834139 -3.1271 1 0 1 1 0 0 +EDGE2 1695 1674 1.00257 -0.00201711 -3.13791 1 0 1 1 0 0 +EDGE2 1695 1676 0.014436 0.973007 1.59103 1 0 1 1 0 0 +EDGE2 1695 1476 -0.0285808 0.913425 1.56864 1 0 1 1 0 0 +EDGE2 1696 1475 -1.05893 0.0317048 -1.54479 1 0 1 1 0 0 +EDGE2 1696 1675 -1.06127 -0.126531 -1.59412 1 0 1 1 0 0 +EDGE2 1696 1695 -1.07617 0.136365 1.605 1 0 1 1 0 0 +EDGE2 1697 1696 -0.98496 -0.0250464 0.00785228 1 0 1 1 0 0 +EDGE2 1698 1697 -1.01213 -0.0345911 -0.0601122 1 0 1 1 0 0 +EDGE2 1699 1460 0.992458 -0.000816359 -3.11183 1 0 1 1 0 0 +EDGE2 1699 1698 -0.996513 -0.0951151 0.012445 1 0 1 1 0 0 +EDGE2 1700 1459 0.98779 0.0547944 -3.13002 1 0 1 1 0 0 +EDGE2 1700 1460 0.00628238 -0.0314443 -3.13365 1 0 1 1 0 0 +EDGE2 1700 1461 0.0157798 0.966515 1.55169 1 0 1 1 0 0 +EDGE2 1700 1699 -1.01439 0.0153828 -0.026812 1 0 1 1 0 0 +EDGE2 1701 1700 -0.944915 -0.0170281 -1.57877 1 0 1 1 0 0 +EDGE2 1701 1460 -0.964178 -0.0910832 1.57515 1 0 1 1 0 0 +EDGE2 1701 1462 0.959398 -0.017691 -0.00461716 1 0 1 1 0 0 +EDGE2 1701 1461 0.00858063 0.0404255 -0.0575135 1 0 1 1 0 0 +EDGE2 1702 1701 -0.969694 0.0110107 -0.00266821 1 0 1 1 0 0 +EDGE2 1702 1463 1.02872 -0.0103369 -0.0197271 1 0 1 1 0 0 +EDGE2 1702 1462 -0.00196191 -0.0834074 -0.00182904 1 0 1 1 0 0 +EDGE2 1702 1461 -0.931555 -0.00804872 -0.0313168 1 0 1 1 0 0 +EDGE2 1703 1463 0.059993 0.130921 -0.034219 1 0 1 1 0 0 +EDGE2 1703 1462 -0.917434 0.0276886 0.0277932 1 0 1 1 0 0 +EDGE2 1703 1702 -1.01475 -0.00848573 0.0366302 1 0 1 1 0 0 +EDGE2 1703 1464 0.990628 0.00737912 -0.0064231 1 0 1 1 0 0 +EDGE2 1704 1665 1.08699 0.070021 -3.13011 1 0 1 1 0 0 +EDGE2 1704 1463 -0.970606 0.0103332 0.0134675 1 0 1 1 0 0 +EDGE2 1704 1703 -0.949537 -0.0712182 -0.0206881 1 0 1 1 0 0 +EDGE2 1704 1464 0.0332514 0.0174963 0.0116456 1 0 1 1 0 0 +EDGE2 1704 1385 0.897265 0.0357343 -3.14486 1 0 1 1 0 0 +EDGE2 1704 1465 1.04246 -0.0589156 0.0107727 1 0 1 1 0 0 +EDGE2 1705 1386 -0.0893558 -0.978269 -1.54265 1 0 1 1 0 0 +EDGE2 1705 1665 -0.0608443 -0.00101728 -3.12052 1 0 1 1 0 0 +EDGE2 1705 1464 -1.01554 -0.009813 -0.0311121 1 0 1 1 0 0 +EDGE2 1705 1704 -1.02661 -0.0313076 -0.0236301 1 0 1 1 0 0 +EDGE2 1705 1385 0.0818596 -0.0445983 -3.15534 1 0 1 1 0 0 +EDGE2 1705 1465 -0.0100547 0.00601945 -0.0271071 1 0 1 1 0 0 +EDGE2 1705 1666 -0.0117211 0.981144 1.5806 1 0 1 1 0 0 +EDGE2 1705 1466 0.0331466 1.03656 1.58125 1 0 1 1 0 0 +EDGE2 1705 1384 1.01498 -0.0280921 -3.16229 1 0 1 1 0 0 +EDGE2 1705 1664 0.898933 -0.00680103 -3.16609 1 0 1 1 0 0 +EDGE2 1706 1665 -0.95011 0.0265001 1.53764 1 0 1 1 0 0 +EDGE2 1706 1705 -0.995217 0.114106 -1.56038 1 0 1 1 0 0 +EDGE2 1706 1385 -1.01401 -0.0248586 1.56974 1 0 1 1 0 0 +EDGE2 1706 1465 -0.991968 0.0215617 -1.56925 1 0 1 1 0 0 +EDGE2 1706 1666 -0.0399199 -0.00915928 -0.0264005 1 0 1 1 0 0 +EDGE2 1706 1466 0.00386859 0.0296542 -0.0094682 1 0 1 1 0 0 +EDGE2 1706 1667 1.03015 -0.0384024 -0.0193362 1 0 1 1 0 0 +EDGE2 1706 1467 0.917048 -0.024729 -0.0173025 1 0 1 1 0 0 +EDGE2 1707 1468 1.03539 0.0144518 -0.0136667 1 0 1 1 0 0 +EDGE2 1707 1666 -1.00798 -0.0159125 -0.0228699 1 0 1 1 0 0 +EDGE2 1707 1706 -0.942643 0.0926023 -0.0313075 1 0 1 1 0 0 +EDGE2 1707 1466 -0.982507 -0.0144504 0.00422717 1 0 1 1 0 0 +EDGE2 1707 1667 -0.0407017 -0.00909076 0.00390143 1 0 1 1 0 0 +EDGE2 1707 1467 -0.00661715 -0.0387627 -0.0192157 1 0 1 1 0 0 +EDGE2 1707 1668 0.998437 0.0376231 0.000887619 1 0 1 1 0 0 +EDGE2 1708 1468 -0.0193327 -0.105905 -0.00299637 1 0 1 1 0 0 +EDGE2 1708 1667 -0.960872 -0.0878309 -0.0348958 1 0 1 1 0 0 +EDGE2 1708 1707 -0.917603 -0.0341034 0.00857691 1 0 1 1 0 0 +EDGE2 1708 1467 -1.06283 -0.0372177 -0.00510135 1 0 1 1 0 0 +EDGE2 1708 1668 0.0248843 -0.0164381 -0.00507249 1 0 1 1 0 0 +EDGE2 1708 1669 1.01396 0.00279288 -0.016681 1 0 1 1 0 0 +EDGE2 1708 1469 0.979279 -0.0160391 -0.0224195 1 0 1 1 0 0 +EDGE2 1709 1468 -0.98729 -0.0432689 0.0292945 1 0 1 1 0 0 +EDGE2 1709 1668 -0.920244 0.0291881 -0.0267743 1 0 1 1 0 0 +EDGE2 1709 1708 -0.974703 0.0233527 0.00104704 1 0 1 1 0 0 +EDGE2 1709 1669 -0.0791277 -0.013287 -0.00697651 1 0 1 1 0 0 +EDGE2 1709 1469 -0.0326168 -0.0498431 0.0322929 1 0 1 1 0 0 +EDGE2 1709 1650 1.0103 -0.000418205 -3.11886 1 0 1 1 0 0 +EDGE2 1709 1670 1.0447 0.0126031 -0.00751387 1 0 1 1 0 0 +EDGE2 1709 1470 1.0152 -0.0143505 -0.00934201 1 0 1 1 0 0 +EDGE2 1709 1510 1.05024 -0.0224763 -3.10909 1 0 1 1 0 0 +EDGE2 1709 1530 1.02524 -0.111783 -3.10809 1 0 1 1 0 0 +EDGE2 1709 1370 0.939634 0.0441125 -3.10436 1 0 1 1 0 0 +EDGE2 1710 1669 -1.00949 0.088407 -0.00436347 1 0 1 1 0 0 +EDGE2 1710 1709 -0.847625 -0.0297336 0.00367361 1 0 1 1 0 0 +EDGE2 1710 1469 -1.01797 -0.000261182 0.0109831 1 0 1 1 0 0 +EDGE2 1710 1671 -0.0521991 0.992093 1.61043 1 0 1 1 0 0 +EDGE2 1710 1471 0.00508492 0.994602 1.55422 1 0 1 1 0 0 +EDGE2 1710 1650 0.0209116 -0.101125 -3.13392 1 0 1 1 0 0 +EDGE2 1710 1670 0.0925755 0.00283529 -0.0391523 1 0 1 1 0 0 +EDGE2 1710 1470 -0.0824985 -0.00984156 0.00732718 1 0 1 1 0 0 +EDGE2 1710 1510 0.000959947 0.100678 -3.13706 1 0 1 1 0 0 +EDGE2 1710 1530 0.0633025 -0.0257767 -3.12645 1 0 1 1 0 0 +EDGE2 1710 1370 -0.0190316 0.015268 -3.14776 1 0 1 1 0 0 +EDGE2 1710 1371 0.0579365 -1.03824 -1.58454 1 0 1 1 0 0 +EDGE2 1710 1531 -0.0171104 -1.0735 -1.57373 1 0 1 1 0 0 +EDGE2 1710 1651 0.105938 -1.09286 -1.57553 1 0 1 1 0 0 +EDGE2 1710 1511 -0.0195286 -0.982148 -1.59405 1 0 1 1 0 0 +EDGE2 1710 1509 1.00838 0.0515301 -3.14412 1 0 1 1 0 0 +EDGE2 1710 1649 0.999809 -0.073883 -3.15263 1 0 1 1 0 0 +EDGE2 1710 1529 1.04815 -0.00209461 -3.14277 1 0 1 1 0 0 +EDGE2 1710 1369 0.956018 0.0681084 -3.12894 1 0 1 1 0 0 +EDGE2 1711 1672 1.00975 0.0859968 -0.0012973 1 0 1 1 0 0 +EDGE2 1711 1472 1.11511 0.0303882 0.00603277 1 0 1 1 0 0 +EDGE2 1711 1671 -0.14599 0.0768709 -0.0145152 1 0 1 1 0 0 +EDGE2 1711 1471 0.0548964 0.0312573 -0.0118417 1 0 1 1 0 0 +EDGE2 1711 1650 -1.00947 0.0130487 1.5664 1 0 1 1 0 0 +EDGE2 1711 1710 -0.948243 0.0658947 -1.55045 1 0 1 1 0 0 +EDGE2 1711 1670 -1.05083 -0.0860721 -1.58316 1 0 1 1 0 0 +EDGE2 1711 1470 -0.947283 -0.0365125 -1.63302 1 0 1 1 0 0 +EDGE2 1711 1510 -0.947664 0.0312153 1.58579 1 0 1 1 0 0 +EDGE2 1711 1530 -1.07286 -0.0232596 1.56535 1 0 1 1 0 0 +EDGE2 1711 1370 -1.01032 0.0454676 1.5556 1 0 1 1 0 0 +EDGE2 1712 1473 1.01037 -0.0791901 -0.0103254 1 0 1 1 0 0 +EDGE2 1712 1673 0.992401 -0.0276751 0.00180124 1 0 1 1 0 0 +EDGE2 1712 1672 0.0220343 -0.0339555 0.00768293 1 0 1 1 0 0 +EDGE2 1712 1472 0.0722145 -0.0336128 -0.0348601 1 0 1 1 0 0 +EDGE2 1712 1671 -1.02812 0.0715213 0.0236353 1 0 1 1 0 0 +EDGE2 1712 1711 -1.06607 0.0808474 0.0130654 1 0 1 1 0 0 +EDGE2 1712 1471 -1.03677 -0.0141107 0.012739 1 0 1 1 0 0 +EDGE2 1713 1474 0.975488 -0.0228544 -0.0373391 1 0 1 1 0 0 +EDGE2 1713 1674 1.1421 0.0226315 -0.0382227 1 0 1 1 0 0 +EDGE2 1713 1473 -0.0204815 0.0353151 0.0137669 1 0 1 1 0 0 +EDGE2 1713 1673 -0.0269967 -0.10199 -0.0250946 1 0 1 1 0 0 +EDGE2 1713 1672 -0.944816 0.0129053 0.00971609 1 0 1 1 0 0 +EDGE2 1713 1712 -0.955961 -0.0368553 -0.0202125 1 0 1 1 0 0 +EDGE2 1713 1472 -0.948936 0.00364312 -0.0213692 1 0 1 1 0 0 +EDGE2 1714 1475 1.03236 -0.0402238 -0.015231 1 0 1 1 0 0 +EDGE2 1714 1675 1.03425 0.0383322 0.00987473 1 0 1 1 0 0 +EDGE2 1714 1695 0.982155 0.0483719 -3.14453 1 0 1 1 0 0 +EDGE2 1714 1474 -0.0156002 0.0366455 0.0363715 1 0 1 1 0 0 +EDGE2 1714 1674 0.016927 0.0150712 -0.0264534 1 0 1 1 0 0 +EDGE2 1714 1473 -1.03909 -0.0262446 -0.0105507 1 0 1 1 0 0 +EDGE2 1714 1673 -1.0324 -0.000666586 0.00492835 1 0 1 1 0 0 +EDGE2 1714 1713 -1.04108 0.0576398 0.0110476 1 0 1 1 0 0 +EDGE2 1715 1694 0.978976 0.0225822 -3.17246 1 0 1 1 0 0 +EDGE2 1715 1696 0.0313023 0.903879 1.57692 1 0 1 1 0 0 +EDGE2 1715 1475 0.0196595 0.0698572 -0.032827 1 0 1 1 0 0 +EDGE2 1715 1675 0.0333427 0.0207781 0.0253928 1 0 1 1 0 0 +EDGE2 1715 1695 0.0936996 -0.0453172 -3.16184 1 0 1 1 0 0 +EDGE2 1715 1474 -1.05316 -0.0678102 -0.00745565 1 0 1 1 0 0 +EDGE2 1715 1674 -0.952465 -0.0115097 -0.0338474 1 0 1 1 0 0 +EDGE2 1715 1714 -0.928789 0.0485623 0.00656821 1 0 1 1 0 0 +EDGE2 1715 1676 -0.0242872 -1.04619 -1.57281 1 0 1 1 0 0 +EDGE2 1715 1476 -0.0332441 -0.881316 -1.57927 1 0 1 1 0 0 +EDGE2 1716 1697 0.889828 0.0271098 -0.00831154 1 0 1 1 0 0 +EDGE2 1716 1715 -0.954272 0.0748673 -1.55004 1 0 1 1 0 0 +EDGE2 1716 1696 0.0343976 0.0457179 0.00495177 1 0 1 1 0 0 +EDGE2 1716 1475 -1.12921 0.0214726 -1.6136 1 0 1 1 0 0 +EDGE2 1716 1675 -0.988155 0.0153992 -1.55899 1 0 1 1 0 0 +EDGE2 1716 1695 -0.973689 0.0177774 1.57203 1 0 1 1 0 0 +EDGE2 1717 1697 0.0135847 -0.0727946 -0.00945506 1 0 1 1 0 0 +EDGE2 1717 1698 0.948304 -0.0533905 -0.0185046 1 0 1 1 0 0 +EDGE2 1717 1716 -0.985711 -0.00747774 -0.0106678 1 0 1 1 0 0 +EDGE2 1717 1696 -0.978555 0.0937579 -0.00252555 1 0 1 1 0 0 +EDGE2 1718 1697 -1.02163 0.00318612 0.0161422 1 0 1 1 0 0 +EDGE2 1718 1699 0.969641 -0.0806915 -0.00644086 1 0 1 1 0 0 +EDGE2 1718 1698 -0.153748 0.00896689 0.00534623 1 0 1 1 0 0 +EDGE2 1718 1717 -1.06524 0.129855 -0.00154185 1 0 1 1 0 0 +EDGE2 1719 1700 1.03195 0.0790089 -0.0153438 1 0 1 1 0 0 +EDGE2 1719 1460 1.04034 -0.00893325 -3.13425 1 0 1 1 0 0 +EDGE2 1719 1699 0.0328523 -0.0507079 0.00437449 1 0 1 1 0 0 +EDGE2 1719 1698 -0.9937 0.0302729 0.0160123 1 0 1 1 0 0 +EDGE2 1719 1718 -0.887165 -0.0493707 -0.016478 1 0 1 1 0 0 +EDGE2 1720 1459 0.975337 0.0778401 -3.13177 1 0 1 1 0 0 +EDGE2 1720 1701 -0.01626 0.955322 1.54472 1 0 1 1 0 0 +EDGE2 1720 1700 -0.0153994 0.0499125 -0.00402537 1 0 1 1 0 0 +EDGE2 1720 1460 0.0055812 -0.0292477 -3.13223 1 0 1 1 0 0 +EDGE2 1720 1461 0.0463234 1.01448 1.57424 1 0 1 1 0 0 +EDGE2 1720 1719 -1.12781 -0.0231259 0.00851536 1 0 1 1 0 0 +EDGE2 1720 1699 -1.0536 0.0165756 0.0196879 1 0 1 1 0 0 +EDGE2 1721 1700 -1.04052 -0.000500321 1.57075 1 0 1 1 0 0 +EDGE2 1721 1720 -0.90381 -0.0062244 1.5956 1 0 1 1 0 0 +EDGE2 1721 1460 -0.835971 0.0358078 -1.57334 1 0 1 1 0 0 +EDGE2 1722 1721 -1.01351 -0.0105791 0.00653074 1 0 1 1 0 0 +EDGE2 1723 1722 -1.06103 0.0189213 0.0378219 1 0 1 1 0 0 +EDGE2 1724 1723 -0.953809 -0.0859451 -0.012152 1 0 1 1 0 0 +EDGE2 1725 1724 -0.966531 0.0217708 -0.0197067 1 0 1 1 0 0 +EDGE2 1726 1725 -0.925087 0.0175235 -1.56596 1 0 1 1 0 0 +EDGE2 1727 1726 -0.962707 -0.0181979 0.0204686 1 0 1 1 0 0 +EDGE2 1728 1727 -0.848172 0.00612076 -0.00971558 1 0 1 1 0 0 +EDGE2 1729 1728 -0.973756 -0.108032 0.0145812 1 0 1 1 0 0 +EDGE2 1730 1729 -0.920458 0.019168 -0.0204795 1 0 1 1 0 0 +EDGE2 1731 1730 -1.02184 0.00696869 -1.53093 1 0 1 1 0 0 +EDGE2 1732 1731 -0.961321 0.0358816 -0.00723911 1 0 1 1 0 0 +EDGE2 1733 1732 -0.895199 -0.102786 0.00913009 1 0 1 1 0 0 +EDGE2 1734 1733 -0.952735 -0.0330041 -0.0130295 1 0 1 1 0 0 +EDGE2 1734 1435 1.09226 0.145635 -3.12459 1 0 1 1 0 0 +EDGE2 1734 1455 0.997121 0.138473 -3.12614 1 0 1 1 0 0 +EDGE2 1734 1395 0.96046 0.0250838 -3.19178 1 0 1 1 0 0 +EDGE2 1734 1415 0.841459 -0.0120961 -3.11335 1 0 1 1 0 0 +EDGE2 1735 1734 -1.01916 -0.0136621 0.0295642 1 0 1 1 0 0 +EDGE2 1735 1435 -0.0761909 0.0486891 -3.11398 1 0 1 1 0 0 +EDGE2 1735 1455 -0.0366189 -0.0482753 -3.15843 1 0 1 1 0 0 +EDGE2 1735 1416 0.0526787 -1.02415 -1.55948 1 0 1 1 0 0 +EDGE2 1735 1436 0.0416842 -1.08321 -1.53978 1 0 1 1 0 0 +EDGE2 1735 1396 0.00368405 -0.966646 -1.52511 1 0 1 1 0 0 +EDGE2 1735 1434 1.03892 -0.0695688 -3.1041 1 0 1 1 0 0 +EDGE2 1735 1395 0.00367013 0.0083803 -3.15233 1 0 1 1 0 0 +EDGE2 1735 1415 -0.0857404 -0.00196628 -3.15883 1 0 1 1 0 0 +EDGE2 1735 1454 1.04315 0.0537834 -3.13487 1 0 1 1 0 0 +EDGE2 1735 1394 0.960575 -0.0054366 -3.13904 1 0 1 1 0 0 +EDGE2 1735 1414 1.0288 0.0287359 -3.15393 1 0 1 1 0 0 +EDGE2 1735 1456 -0.0226973 0.992062 1.58873 1 0 1 1 0 0 +EDGE2 1736 1435 -0.929119 -0.0324927 1.5475 1 0 1 1 0 0 +EDGE2 1736 1455 -0.987755 0.0169966 1.56586 1 0 1 1 0 0 +EDGE2 1736 1735 -0.986576 -0.0351779 -1.58786 1 0 1 1 0 0 +EDGE2 1736 1395 -0.913641 -0.0565734 1.57236 1 0 1 1 0 0 +EDGE2 1736 1415 -1.04517 0.0115941 1.5974 1 0 1 1 0 0 +EDGE2 1736 1456 -0.107704 0.00441206 0.0267005 1 0 1 1 0 0 +EDGE2 1736 1457 0.974304 0.010426 -0.040006 1 0 1 1 0 0 +EDGE2 1737 1456 -0.954452 0.000185428 -0.0363888 1 0 1 1 0 0 +EDGE2 1737 1736 -0.990856 0.00526393 -0.00664286 1 0 1 1 0 0 +EDGE2 1737 1457 -0.0810215 -0.0608003 -0.0134799 1 0 1 1 0 0 +EDGE2 1737 1458 0.978298 0.0916338 -0.0101352 1 0 1 1 0 0 +EDGE2 1738 1457 -0.988258 -0.0392665 -0.0181782 1 0 1 1 0 0 +EDGE2 1738 1737 -0.96864 -0.0352487 -0.00165071 1 0 1 1 0 0 +EDGE2 1738 1458 0.0551195 -0.0883081 0.0221466 1 0 1 1 0 0 +EDGE2 1738 1459 1.03699 -0.010299 -0.0205172 1 0 1 1 0 0 +EDGE2 1739 1738 -1.0083 -0.0779575 0.0117439 1 0 1 1 0 0 +EDGE2 1739 1458 -0.940954 -0.045744 -0.00027824 1 0 1 1 0 0 +EDGE2 1739 1459 0.00499884 0.0352563 -0.0261503 1 0 1 1 0 0 +EDGE2 1739 1700 1.00719 -0.0208248 -3.12619 1 0 1 1 0 0 +EDGE2 1739 1720 0.977476 0.0425138 -3.13876 1 0 1 1 0 0 +EDGE2 1739 1460 0.979832 -0.0417847 0.00656358 1 0 1 1 0 0 +EDGE2 1740 1739 -0.986578 -0.0312301 0.0132728 1 0 1 1 0 0 +EDGE2 1740 1459 -0.939769 -0.100187 -0.0179547 1 0 1 1 0 0 +EDGE2 1740 1701 0.0220657 -0.998982 -1.60213 1 0 1 1 0 0 +EDGE2 1740 1721 -0.0429028 0.994135 1.55976 1 0 1 1 0 0 +EDGE2 1740 1700 0.0468383 -0.00481849 -3.1628 1 0 1 1 0 0 +EDGE2 1740 1720 0.015836 -0.0715705 -3.17474 1 0 1 1 0 0 +EDGE2 1740 1460 0.00690364 0.0626093 -0.00748114 1 0 1 1 0 0 +EDGE2 1740 1461 -0.0595777 -0.950148 -1.58447 1 0 1 1 0 0 +EDGE2 1740 1719 0.964812 -0.0236322 -3.13235 1 0 1 1 0 0 +EDGE2 1740 1699 1.04258 -0.00881925 -3.11213 1 0 1 1 0 0 +EDGE2 1741 1722 0.977794 0.00254628 -0.0148835 1 0 1 1 0 0 +EDGE2 1741 1721 -0.0685973 0.0521723 -0.00324089 1 0 1 1 0 0 +EDGE2 1741 1700 -1.04407 -0.0990192 1.6178 1 0 1 1 0 0 +EDGE2 1741 1720 -1.02436 -0.0227093 1.58719 1 0 1 1 0 0 +EDGE2 1741 1740 -1.00106 0.0262555 -1.56184 1 0 1 1 0 0 +EDGE2 1741 1460 -1.01408 -0.0569288 -1.56742 1 0 1 1 0 0 +EDGE2 1742 1723 0.952535 -0.0384179 -0.032069 1 0 1 1 0 0 +EDGE2 1742 1741 -0.92379 -0.0318466 -0.00901759 1 0 1 1 0 0 +EDGE2 1742 1722 -0.0221907 0.0172027 -0.00387114 1 0 1 1 0 0 +EDGE2 1742 1721 -0.970998 0.00997003 -0.00508154 1 0 1 1 0 0 +EDGE2 1743 1742 -0.94104 -0.0604458 -0.00372477 1 0 1 1 0 0 +EDGE2 1743 1724 1.04382 -0.0308953 -0.0249906 1 0 1 1 0 0 +EDGE2 1743 1723 -0.0235884 -0.0314415 0.00946307 1 0 1 1 0 0 +EDGE2 1743 1722 -0.969631 0.0260183 0.0150551 1 0 1 1 0 0 +EDGE2 1744 1725 1.0581 0.0202833 -0.0247566 1 0 1 1 0 0 +EDGE2 1744 1724 -0.0596084 0.0531418 -0.0046911 1 0 1 1 0 0 +EDGE2 1744 1723 -1.06726 -0.113585 -0.000503498 1 0 1 1 0 0 +EDGE2 1744 1743 -1.03186 -0.030678 -0.00707704 1 0 1 1 0 0 +EDGE2 1745 1726 0.0394848 0.989234 1.58248 1 0 1 1 0 0 +EDGE2 1745 1744 -0.983434 -0.0273915 0.0218821 1 0 1 1 0 0 +EDGE2 1745 1725 0.00980626 -0.0916809 0.0226112 1 0 1 1 0 0 +EDGE2 1745 1724 -1.00102 0.0253634 -0.0113758 1 0 1 1 0 0 +EDGE2 1746 1727 1.06611 -0.0904445 -0.0100513 1 0 1 1 0 0 +EDGE2 1746 1726 -0.0470343 0.0427941 0.000145724 1 0 1 1 0 0 +EDGE2 1746 1745 -1.02204 -0.022817 -1.5597 1 0 1 1 0 0 +EDGE2 1746 1725 -0.948606 -0.063554 -1.54393 1 0 1 1 0 0 +EDGE2 1747 1727 0.0441845 -0.00721912 -0.000998539 1 0 1 1 0 0 +EDGE2 1747 1728 1.0077 0.0429387 -0.00503922 1 0 1 1 0 0 +EDGE2 1747 1746 -1.0561 0.0462622 0.023867 1 0 1 1 0 0 +EDGE2 1747 1726 -1.04039 0.0112284 0.0442614 1 0 1 1 0 0 +EDGE2 1748 1729 0.952496 -0.0427048 -0.0290358 1 0 1 1 0 0 +EDGE2 1748 1727 -0.957718 -0.0433175 -0.00408708 1 0 1 1 0 0 +EDGE2 1748 1728 0.0506513 0.0054087 -0.00329642 1 0 1 1 0 0 +EDGE2 1748 1747 -1.05538 0.0435047 0.0311514 1 0 1 1 0 0 +EDGE2 1749 1730 1.06807 -0.0183539 -0.00460339 1 0 1 1 0 0 +EDGE2 1749 1729 -0.00334573 -0.0693601 0.00660514 1 0 1 1 0 0 +EDGE2 1749 1728 -1.00637 -0.0155023 0.0125204 1 0 1 1 0 0 +EDGE2 1749 1748 -0.981729 -0.0305076 0.0388075 1 0 1 1 0 0 +EDGE2 1750 1730 0.0164425 -0.0131687 -0.0154104 1 0 1 1 0 0 +EDGE2 1750 1731 -0.0268117 1.0315 1.58643 1 0 1 1 0 0 +EDGE2 1750 1749 -0.972737 0.0531262 0.000754353 1 0 1 1 0 0 +EDGE2 1750 1729 -0.985051 0.00743412 0.00562015 1 0 1 1 0 0 +EDGE2 1751 1750 -0.994874 0.0788926 -1.57951 1 0 1 1 0 0 +EDGE2 1751 1730 -0.926477 -0.0525958 -1.55991 1 0 1 1 0 0 +EDGE2 1751 1731 -0.0426429 -0.0353546 -0.00139997 1 0 1 1 0 0 +EDGE2 1751 1732 1.08209 0.0543339 -0.0228801 1 0 1 1 0 0 +EDGE2 1752 1731 -0.947559 -0.0456012 0.0181589 1 0 1 1 0 0 +EDGE2 1752 1751 -1.00051 -0.06153 0.025133 1 0 1 1 0 0 +EDGE2 1752 1732 -0.0297022 0.0647418 -0.00282238 1 0 1 1 0 0 +EDGE2 1752 1733 1.01524 0.019508 -0.0274406 1 0 1 1 0 0 +EDGE2 1753 1734 0.978419 -0.0487163 0.00785314 1 0 1 1 0 0 +EDGE2 1753 1752 -1.02155 -0.038644 0.00722513 1 0 1 1 0 0 +EDGE2 1753 1732 -0.942703 0.0140154 0.0157944 1 0 1 1 0 0 +EDGE2 1753 1733 -0.0716454 -0.010519 0.0240197 1 0 1 1 0 0 +EDGE2 1754 1734 0.0296803 -0.130899 0.00492835 1 0 1 1 0 0 +EDGE2 1754 1753 -1.02342 0.0836671 -0.0156657 1 0 1 1 0 0 +EDGE2 1754 1733 -0.969413 -0.0178785 0.0118955 1 0 1 1 0 0 +EDGE2 1754 1435 0.983068 -0.0119193 -3.13769 1 0 1 1 0 0 +EDGE2 1754 1455 0.847609 0.00314876 -3.11771 1 0 1 1 0 0 +EDGE2 1754 1735 1.00894 -0.0683804 -0.00833777 1 0 1 1 0 0 +EDGE2 1754 1395 0.970984 0.0150838 -3.12712 1 0 1 1 0 0 +EDGE2 1754 1415 0.979411 -0.00977544 -3.1697 1 0 1 1 0 0 +EDGE2 1755 1734 -0.986219 0.0508284 0.0152933 1 0 1 1 0 0 +EDGE2 1755 1754 -1.00471 0.0433731 -0.0158943 1 0 1 1 0 0 +EDGE2 1755 1435 -0.0301904 0.0652932 -3.12131 1 0 1 1 0 0 +EDGE2 1755 1455 0.0400519 0.00410355 -3.11557 1 0 1 1 0 0 +EDGE2 1755 1416 -0.0852544 -0.974534 -1.54571 1 0 1 1 0 0 +EDGE2 1755 1436 0.0492138 -0.977108 -1.5793 1 0 1 1 0 0 +EDGE2 1755 1396 -0.0249719 -0.979908 -1.57283 1 0 1 1 0 0 +EDGE2 1755 1735 0.0295669 -0.00728954 0.0382418 1 0 1 1 0 0 +EDGE2 1755 1434 0.922354 -0.042621 -3.18316 1 0 1 1 0 0 +EDGE2 1755 1395 0.0665227 -0.118274 -3.13677 1 0 1 1 0 0 +EDGE2 1755 1415 0.0302487 -0.0514111 -3.14339 1 0 1 1 0 0 +EDGE2 1755 1454 1.06109 0.0155599 -3.13348 1 0 1 1 0 0 +EDGE2 1755 1394 0.983073 -0.0133484 -3.1239 1 0 1 1 0 0 +EDGE2 1755 1414 1.00405 -0.00833904 -3.10087 1 0 1 1 0 0 +EDGE2 1755 1456 -0.0547316 1.05964 1.56471 1 0 1 1 0 0 +EDGE2 1755 1736 0.0425472 1.05929 1.56626 1 0 1 1 0 0 +EDGE2 1756 1417 1.03869 -0.0455756 0.0118797 1 0 1 1 0 0 +EDGE2 1756 1437 1.03921 -0.00542353 0.0180696 1 0 1 1 0 0 +EDGE2 1756 1435 -0.929832 0.0472195 -1.60982 1 0 1 1 0 0 +EDGE2 1756 1455 -1.00892 0.0438835 -1.56357 1 0 1 1 0 0 +EDGE2 1756 1416 0.00368062 0.0259908 -0.0162995 1 0 1 1 0 0 +EDGE2 1756 1397 0.970294 -0.0476115 0.044127 1 0 1 1 0 0 +EDGE2 1756 1436 0.0416186 0.00865094 0.00264478 1 0 1 1 0 0 +EDGE2 1756 1755 -0.924521 -0.0506806 1.58976 1 0 1 1 0 0 +EDGE2 1756 1396 0.0324749 0.0346219 0.00427853 1 0 1 1 0 0 +EDGE2 1756 1735 -0.994455 0.0313884 1.55866 1 0 1 1 0 0 +EDGE2 1756 1395 -0.978591 0.04553 -1.57032 1 0 1 1 0 0 +EDGE2 1756 1415 -0.98294 0.018394 -1.55129 1 0 1 1 0 0 +EDGE2 1757 1417 -0.0363955 -0.00399282 0.0145003 1 0 1 1 0 0 +EDGE2 1757 1398 0.947051 0.0145561 0.0118459 1 0 1 1 0 0 +EDGE2 1757 1438 1.04122 -0.0213953 -0.0127666 1 0 1 1 0 0 +EDGE2 1757 1418 1.10155 0.0518909 -0.008761 1 0 1 1 0 0 +EDGE2 1757 1437 -0.0450822 0.0338031 -0.0235222 1 0 1 1 0 0 +EDGE2 1757 1416 -1.03554 0.024876 -0.0228613 1 0 1 1 0 0 +EDGE2 1757 1756 -0.929091 -0.0580911 -0.0168028 1 0 1 1 0 0 +EDGE2 1757 1397 -0.032154 0.0104569 0.00384149 1 0 1 1 0 0 +EDGE2 1757 1436 -0.969659 -0.0214452 -0.0282365 1 0 1 1 0 0 +EDGE2 1757 1396 -0.994181 0.0107796 -0.0147396 1 0 1 1 0 0 +EDGE2 1758 1417 -0.966233 0.123183 -0.00898175 1 0 1 1 0 0 +EDGE2 1758 1419 1.01218 0.0240166 -0.00618159 1 0 1 1 0 0 +EDGE2 1758 1439 0.951326 0.0926088 0.0028164 1 0 1 1 0 0 +EDGE2 1758 1399 0.929451 0.0557562 -0.0161013 1 0 1 1 0 0 +EDGE2 1758 1398 -0.0215533 0.0403033 0.0125407 1 0 1 1 0 0 +EDGE2 1758 1438 -0.0241785 0.023467 0.000685383 1 0 1 1 0 0 +EDGE2 1758 1418 -0.073771 -0.0430769 -0.00952807 1 0 1 1 0 0 +EDGE2 1758 1757 -1.02573 0.0407081 0.0256324 1 0 1 1 0 0 +EDGE2 1758 1437 -1.03751 0.0126459 -0.00183303 1 0 1 1 0 0 +EDGE2 1758 1397 -1.06987 -0.0567116 -0.011078 1 0 1 1 0 0 +EDGE2 1759 1420 0.953937 -0.00883027 0.0181797 1 0 1 1 0 0 +EDGE2 1759 1440 1.00305 -0.0860679 0.000883561 1 0 1 1 0 0 +EDGE2 1759 1400 0.971983 -0.00622008 -0.000881174 1 0 1 1 0 0 +EDGE2 1759 1758 -0.991982 -0.0131932 -0.0119794 1 0 1 1 0 0 +EDGE2 1759 1419 0.0387577 0.00172778 -0.030334 1 0 1 1 0 0 +EDGE2 1759 1439 -0.000151747 0.0773407 0.00763936 1 0 1 1 0 0 +EDGE2 1759 1399 0.00986664 -0.085379 -0.0285671 1 0 1 1 0 0 +EDGE2 1759 1398 -1.03734 -0.000705074 -0.0081091 1 0 1 1 0 0 +EDGE2 1759 1438 -1.00991 0.0401524 0.0410316 1 0 1 1 0 0 +EDGE2 1759 1418 -1.06479 -0.0109514 0.00744985 1 0 1 1 0 0 +EDGE2 1760 1420 0.00722047 0.0625341 -0.0135427 1 0 1 1 0 0 +EDGE2 1760 1440 0.0519206 -0.109328 -0.021476 1 0 1 1 0 0 +EDGE2 1760 1400 -0.00654235 0.00295744 -0.0312855 1 0 1 1 0 0 +EDGE2 1760 1421 -0.0289012 0.976646 1.56376 1 0 1 1 0 0 +EDGE2 1760 1441 -0.0710696 0.990354 1.55849 1 0 1 1 0 0 +EDGE2 1760 1401 0.0201362 0.977209 1.53792 1 0 1 1 0 0 +EDGE2 1760 1419 -1.03983 -0.00837059 0.00750489 1 0 1 1 0 0 +EDGE2 1760 1759 -0.98537 -0.0251281 -0.00814901 1 0 1 1 0 0 +EDGE2 1760 1439 -0.94444 -0.0654075 -0.00701959 1 0 1 1 0 0 +EDGE2 1760 1399 -1.01638 0.000633325 0.00867832 1 0 1 1 0 0 +EDGE2 1761 1420 -1.01878 0.0295263 1.54553 1 0 1 1 0 0 +EDGE2 1761 1440 -1.03075 0.0269113 1.56999 1 0 1 1 0 0 +EDGE2 1761 1760 -0.965747 0.0825667 1.55213 1 0 1 1 0 0 +EDGE2 1761 1400 -0.985987 -0.0162509 1.6039 1 0 1 1 0 0 +EDGE2 1762 1761 -1.06414 0.0358796 0.0246496 1 0 1 1 0 0 +EDGE2 1763 1762 -1.02982 0.00311456 -0.0157439 1 0 1 1 0 0 +EDGE2 1764 1763 -0.958786 -0.0211756 0.00154463 1 0 1 1 0 0 +EDGE2 1765 1764 -1.04226 0.041719 -0.0203671 1 0 1 1 0 0 +EDGE2 1766 1765 -1.05419 0.00552114 -1.56861 1 0 1 1 0 0 +EDGE2 1767 1766 -0.890442 -0.0448705 0.0332973 1 0 1 1 0 0 +EDGE2 1768 1767 -1.01911 -0.0326281 0.0364023 1 0 1 1 0 0 +EDGE2 1769 1768 -0.986585 -0.0688984 -0.0282087 1 0 1 1 0 0 +EDGE2 1770 1769 -1.02578 0.0510036 0.0248669 1 0 1 1 0 0 +EDGE2 1771 1770 -1.00571 0.0996475 -1.56775 1 0 1 1 0 0 +EDGE2 1772 1771 -0.941326 -0.0109818 0.00980481 1 0 1 1 0 0 +EDGE2 1773 1772 -1.00015 0.0706337 -0.00122474 1 0 1 1 0 0 +EDGE2 1774 1773 -1.05167 0.0222706 0.0417447 1 0 1 1 0 0 +EDGE2 1775 1774 -1.00043 -0.0834554 0.00354699 1 0 1 1 0 0 +EDGE2 1776 1775 -0.936593 0.0257475 1.5563 1 0 1 1 0 0 +EDGE2 1777 1776 -1.06192 -0.0378385 0.00291171 1 0 1 1 0 0 +EDGE2 1778 1777 -1.03587 0.00957418 -0.0147598 1 0 1 1 0 0 +EDGE2 1779 1778 -0.980431 -0.0726444 0.0208313 1 0 1 1 0 0 +EDGE2 1780 1779 -0.979741 0.0584931 -0.0203344 1 0 1 1 0 0 +EDGE2 1781 1780 -1.08911 0.0116695 -1.54279 1 0 1 1 0 0 +EDGE2 1782 1781 -1.00329 -0.0104042 0.0467171 1 0 1 1 0 0 +EDGE2 1783 1782 -0.913191 -0.000209996 0.0147564 1 0 1 1 0 0 +EDGE2 1784 1783 -1.06532 0.017519 0.00480274 1 0 1 1 0 0 +EDGE2 1785 1784 -0.999118 0.0190973 0.0347354 1 0 1 1 0 0 +EDGE2 1786 1785 -1.00108 -0.0592665 -1.5904 1 0 1 1 0 0 +EDGE2 1787 1786 -1.03097 0.0194396 -0.00796239 1 0 1 1 0 0 +EDGE2 1788 1787 -0.958425 -0.0203202 -0.0119737 1 0 1 1 0 0 +EDGE2 1789 1788 -1.00863 0.0734663 0.0226284 1 0 1 1 0 0 +EDGE2 1790 1789 -0.983744 -0.0583527 0.0112796 1 0 1 1 0 0 +EDGE2 1791 1790 -0.992059 -0.00338365 1.56025 1 0 1 1 0 0 +EDGE2 1792 1791 -1.02872 0.0984246 -0.0129905 1 0 1 1 0 0 +EDGE2 1793 1792 -0.946384 0.0293469 -0.000100013 1 0 1 1 0 0 +EDGE2 1794 1793 -1.0169 -0.0787635 0.0231304 1 0 1 1 0 0 +EDGE2 1795 1794 -0.917768 0.0438206 0.00368484 1 0 1 1 0 0 +EDGE2 1796 1795 -1.01809 -0.0290006 -1.55935 1 0 1 1 0 0 +EDGE2 1797 1796 -0.956898 -0.0292088 0.0163033 1 0 1 1 0 0 +EDGE2 1798 1797 -1.07327 0.0873902 -0.00941638 1 0 1 1 0 0 +EDGE2 1799 1798 -0.941449 0.00258215 0.00363096 1 0 1 1 0 0 +EDGE2 1800 1799 -0.993449 0.0482699 0.0298521 1 0 1 1 0 0 +EDGE2 1801 1800 -0.98474 0.0201617 1.60871 1 0 1 1 0 0 +EDGE2 1802 1801 -1.06605 -0.0449889 0.026951 1 0 1 1 0 0 +EDGE2 1803 1802 -0.985242 -0.0795706 0.0126441 1 0 1 1 0 0 +EDGE2 1804 1803 -0.953381 -0.0430394 0.0224042 1 0 1 1 0 0 +EDGE2 1805 1804 -0.984574 0.0174869 -0.00201194 1 0 1 1 0 0 +EDGE2 1806 1805 -1.03376 0.018441 1.55898 1 0 1 1 0 0 +EDGE2 1807 1806 -0.985644 -0.0636222 -0.0192788 1 0 1 1 0 0 +EDGE2 1808 1807 -0.992907 -0.00308542 0.0143267 1 0 1 1 0 0 +EDGE2 1809 1808 -0.976808 0.0422245 0.0465524 1 0 1 1 0 0 +EDGE2 1810 1809 -0.95447 -0.053218 -0.0484707 1 0 1 1 0 0 +EDGE2 1811 1810 -1.02369 -0.00409252 -1.56315 1 0 1 1 0 0 +EDGE2 1812 1811 -1.06865 0.0679294 0.0237491 1 0 1 1 0 0 +EDGE2 1813 1812 -0.969226 0.0718063 -0.00062935 1 0 1 1 0 0 +EDGE2 1814 1813 -1.05726 0.0651111 -0.00776797 1 0 1 1 0 0 +EDGE2 1815 1814 -0.977047 -0.0502861 0.00490413 1 0 1 1 0 0 +EDGE2 1816 1815 -0.980208 0.0144712 -1.54595 1 0 1 1 0 0 +EDGE2 1817 1816 -0.933921 -0.0168769 -0.0139943 1 0 1 1 0 0 +EDGE2 1818 1817 -1.05422 -0.00992057 -0.0058032 1 0 1 1 0 0 +EDGE2 1819 1818 -1.09568 0.00338542 0.0157961 1 0 1 1 0 0 +EDGE2 1819 1240 1.02754 -0.00458761 -3.16858 1 0 1 1 0 0 +EDGE2 1820 1819 -0.989484 0.0541617 0.00253305 1 0 1 1 0 0 +EDGE2 1820 1240 -0.0291675 0.0283962 -3.13204 1 0 1 1 0 0 +EDGE2 1820 1241 -0.00268493 -1.08427 -1.55779 1 0 1 1 0 0 +EDGE2 1820 1239 1.03117 -0.033865 -3.12304 1 0 1 1 0 0 +EDGE2 1821 1820 -1.07258 -0.0173016 -1.56428 1 0 1 1 0 0 +EDGE2 1821 1240 -0.978654 0.021683 1.61878 1 0 1 1 0 0 +EDGE2 1822 1821 -1.00557 0.0666826 -0.0226608 1 0 1 1 0 0 +EDGE2 1823 1822 -1.12813 0.045157 0.0337651 1 0 1 1 0 0 +EDGE2 1824 1805 0.999176 0.0744814 -3.19913 1 0 1 1 0 0 +EDGE2 1824 1823 -1.09756 -0.0128835 -0.0227179 1 0 1 1 0 0 +EDGE2 1825 1805 -0.102324 0.00750036 -3.1768 1 0 1 1 0 0 +EDGE2 1825 1806 0.0119736 0.952701 1.5781 1 0 1 1 0 0 +EDGE2 1825 1804 0.953964 -0.0289958 -3.1462 1 0 1 1 0 0 +EDGE2 1825 1824 -1.03057 0.0414847 0.0219241 1 0 1 1 0 0 +EDGE2 1826 1805 -1.01856 -0.0544771 -1.58356 1 0 1 1 0 0 +EDGE2 1826 1825 -0.90666 0.0638844 1.58 1 0 1 1 0 0 +EDGE2 1827 1826 -0.94268 -0.0475434 0.0156346 1 0 1 1 0 0 +EDGE2 1828 1827 -1.0699 -0.0375872 -0.0350514 1 0 1 1 0 0 +EDGE2 1829 1828 -0.965227 -0.00421246 0.0315346 1 0 1 1 0 0 +EDGE2 1829 1550 1.00695 0.0115789 -3.15673 1 0 1 1 0 0 +EDGE2 1830 1829 -1.0494 -0.0013746 0.00726546 1 0 1 1 0 0 +EDGE2 1830 1551 -0.060495 1.02571 1.55403 1 0 1 1 0 0 +EDGE2 1830 1550 -0.00693375 -0.0346213 -3.13176 1 0 1 1 0 0 +EDGE2 1830 1549 1.08624 0.0092139 -3.12265 1 0 1 1 0 0 +EDGE2 1831 1552 1.0064 0.0169061 0.00584278 1 0 1 1 0 0 +EDGE2 1831 1551 -0.053709 0.00375646 0.0155941 1 0 1 1 0 0 +EDGE2 1831 1550 -0.934917 0.000339262 1.58727 1 0 1 1 0 0 +EDGE2 1831 1830 -0.956445 -0.0104551 -1.56429 1 0 1 1 0 0 +EDGE2 1832 1553 0.95767 0.139311 0.00310845 1 0 1 1 0 0 +EDGE2 1832 1831 -0.930243 0.0318859 -0.0218538 1 0 1 1 0 0 +EDGE2 1832 1552 -0.0535843 -0.0439395 0.0216301 1 0 1 1 0 0 +EDGE2 1832 1551 -0.952169 -0.0397966 0.00072455 1 0 1 1 0 0 +EDGE2 1833 1553 0.0461927 0.00281975 0.0281081 1 0 1 1 0 0 +EDGE2 1833 1554 0.91474 0.00617235 -0.0136204 1 0 1 1 0 0 +EDGE2 1833 1552 -1.02021 -0.02697 -0.0207838 1 0 1 1 0 0 +EDGE2 1833 1832 -1.03581 0.0673291 -0.000746802 1 0 1 1 0 0 +EDGE2 1834 1553 -1.13117 0.00934277 0.0340973 1 0 1 1 0 0 +EDGE2 1834 1554 0.0230355 -0.0554773 0.0100709 1 0 1 1 0 0 +EDGE2 1834 1555 1.03275 -0.0840839 0.0146116 1 0 1 1 0 0 +EDGE2 1834 1833 -0.992306 0.0463948 -0.00790176 1 0 1 1 0 0 +EDGE2 1835 1554 -0.961879 0.0783419 -0.00331369 1 0 1 1 0 0 +EDGE2 1835 1834 -1.02791 0.0349251 -0.0122877 1 0 1 1 0 0 +EDGE2 1835 1555 0.00667194 0.0382393 0.0394659 1 0 1 1 0 0 +EDGE2 1835 1556 -0.0497783 -0.968986 -1.5748 1 0 1 1 0 0 +EDGE2 1836 1835 -1.04262 0.0432454 1.52773 1 0 1 1 0 0 +EDGE2 1836 1555 -0.966582 -0.0247982 1.5337 1 0 1 1 0 0 +EDGE2 1836 1556 -0.0851726 -0.0772884 -0.0114017 1 0 1 1 0 0 +EDGE2 1836 1557 0.915797 0.0198569 0.00996152 1 0 1 1 0 0 +EDGE2 1837 1556 -0.912622 0.029063 0.0111826 1 0 1 1 0 0 +EDGE2 1837 1836 -1.01659 -0.0182153 -0.0144029 1 0 1 1 0 0 +EDGE2 1837 1557 0.0233659 -0.0405956 0.000417774 1 0 1 1 0 0 +EDGE2 1837 1558 0.982992 -0.020732 0.0140981 1 0 1 1 0 0 +EDGE2 1838 1837 -0.991547 -0.0811422 -0.0115465 1 0 1 1 0 0 +EDGE2 1838 1557 -1.01906 -0.0460387 0.0163711 1 0 1 1 0 0 +EDGE2 1838 1558 0.0702821 -0.0228148 -0.00530333 1 0 1 1 0 0 +EDGE2 1838 1559 1.05277 -0.00799026 0.0378259 1 0 1 1 0 0 +EDGE2 1839 1838 -0.995524 -0.01582 0.00152201 1 0 1 1 0 0 +EDGE2 1839 1558 -1.04816 0.0458107 -0.010932 1 0 1 1 0 0 +EDGE2 1839 1559 -0.0857284 0.0499565 -0.0154501 1 0 1 1 0 0 +EDGE2 1839 1540 1.05316 0.00079117 -3.13181 1 0 1 1 0 0 +EDGE2 1839 1580 1.0087 0.0138343 -3.14335 1 0 1 1 0 0 +EDGE2 1839 1660 0.957279 -0.0396038 -3.13792 1 0 1 1 0 0 +EDGE2 1839 1560 0.985222 0.0769259 0.0163295 1 0 1 1 0 0 +EDGE2 1839 1380 1.03097 -0.0273588 -3.1095 1 0 1 1 0 0 +EDGE2 1840 1839 -1.04091 -0.00995429 -0.00860943 1 0 1 1 0 0 +EDGE2 1840 1559 -0.996814 -0.00110505 -0.00428874 1 0 1 1 0 0 +EDGE2 1840 1540 0.0109393 -0.0406461 -3.15844 1 0 1 1 0 0 +EDGE2 1840 1381 -0.0553239 0.938736 1.56671 1 0 1 1 0 0 +EDGE2 1840 1661 0.0210331 1.02789 1.56416 1 0 1 1 0 0 +EDGE2 1840 1580 -0.0380002 -0.0763625 -3.12448 1 0 1 1 0 0 +EDGE2 1840 1660 0.0196063 0.0406822 -3.15495 1 0 1 1 0 0 +EDGE2 1840 1560 -0.0193059 -0.0472755 -0.00726537 1 0 1 1 0 0 +EDGE2 1840 1581 -0.00834975 -1.11168 -1.60008 1 0 1 1 0 0 +EDGE2 1840 1380 0.00475606 -0.00221196 -3.17517 1 0 1 1 0 0 +EDGE2 1840 1541 0.0140365 -0.991458 -1.59252 1 0 1 1 0 0 +EDGE2 1840 1561 0.0419368 -0.989957 -1.58502 1 0 1 1 0 0 +EDGE2 1840 1579 0.995887 -0.0822768 -3.15898 1 0 1 1 0 0 +EDGE2 1840 1659 1.08904 0.00687002 -3.16861 1 0 1 1 0 0 +EDGE2 1840 1379 0.944643 0.0991976 -3.13518 1 0 1 1 0 0 +EDGE2 1840 1539 1.00563 0.0259304 -3.13797 1 0 1 1 0 0 +EDGE2 1841 1540 -0.918513 -0.105738 -1.5427 1 0 1 1 0 0 +EDGE2 1841 1580 -0.94633 0.0209167 -1.55036 1 0 1 1 0 0 +EDGE2 1841 1660 -0.885542 -0.0366506 -1.58424 1 0 1 1 0 0 +EDGE2 1841 1840 -0.940895 0.0225156 1.57605 1 0 1 1 0 0 +EDGE2 1841 1560 -1.02455 -0.0237381 1.56858 1 0 1 1 0 0 +EDGE2 1841 1581 0.00516278 0.0407763 -0.0318295 1 0 1 1 0 0 +EDGE2 1841 1380 -1.00188 -0.011373 -1.53459 1 0 1 1 0 0 +EDGE2 1841 1541 -0.000365119 0.0502111 -0.00964153 1 0 1 1 0 0 +EDGE2 1841 1561 0.080164 -0.058686 -0.0115544 1 0 1 1 0 0 +EDGE2 1841 1542 1.04307 0.0256763 0.00441615 1 0 1 1 0 0 +EDGE2 1841 1562 1.00468 -0.00874671 0.00951185 1 0 1 1 0 0 +EDGE2 1841 1582 0.973164 -0.0132659 0.00539355 1 0 1 1 0 0 +EDGE2 1842 1543 0.936918 0.0181662 -0.0343955 1 0 1 1 0 0 +EDGE2 1842 1581 -1.09127 -0.00122315 0.00896923 1 0 1 1 0 0 +EDGE2 1842 1841 -1.07358 -0.0486141 -0.0308208 1 0 1 1 0 0 +EDGE2 1842 1541 -0.955834 0.0351923 0.0253584 1 0 1 1 0 0 +EDGE2 1842 1561 -0.938015 1.85062e-05 -0.00297624 1 0 1 1 0 0 +EDGE2 1842 1542 0.0380643 -0.0315712 -0.0206277 1 0 1 1 0 0 +EDGE2 1842 1562 0.0147068 -0.046848 0.0300195 1 0 1 1 0 0 +EDGE2 1842 1582 -0.0132782 0.0861021 0.0207302 1 0 1 1 0 0 +EDGE2 1842 1583 0.978335 -0.0227218 -0.00724177 1 0 1 1 0 0 +EDGE2 1842 1563 1.00711 0.0102407 0.00777992 1 0 1 1 0 0 +EDGE2 1843 1543 -0.032702 -0.0165485 0.0333736 1 0 1 1 0 0 +EDGE2 1843 1842 -0.934651 -0.0239881 0.0185926 1 0 1 1 0 0 +EDGE2 1843 1542 -0.959052 0.00394788 -0.0140583 1 0 1 1 0 0 +EDGE2 1843 1562 -0.880643 0.032085 -0.00210908 1 0 1 1 0 0 +EDGE2 1843 1582 -1.01779 -0.0125494 0.00243276 1 0 1 1 0 0 +EDGE2 1843 1583 -0.0662673 -0.0669446 -0.0142811 1 0 1 1 0 0 +EDGE2 1843 1563 -0.116534 -0.0753912 -0.0247328 1 0 1 1 0 0 +EDGE2 1843 1564 0.864381 -0.0496131 0.0320176 1 0 1 1 0 0 +EDGE2 1843 1584 1.03267 0.00727893 0.00606454 1 0 1 1 0 0 +EDGE2 1843 1544 1.01336 -0.0415886 0.0304835 1 0 1 1 0 0 +EDGE2 1844 1543 -0.983049 0.0301974 -0.0162543 1 0 1 1 0 0 +EDGE2 1844 1583 -1.04223 0.0143546 0.0186046 1 0 1 1 0 0 +EDGE2 1844 1843 -0.914828 0.0293216 0.00688225 1 0 1 1 0 0 +EDGE2 1844 1563 -0.939559 0.0427671 -0.00861096 1 0 1 1 0 0 +EDGE2 1844 1564 -0.0030454 -0.114887 -0.00394196 1 0 1 1 0 0 +EDGE2 1844 1584 0.0568292 -0.00874554 0.00717312 1 0 1 1 0 0 +EDGE2 1844 1544 -0.0359837 0.0659724 -0.0340769 1 0 1 1 0 0 +EDGE2 1844 1265 1.01736 0.0193334 -3.13983 1 0 1 1 0 0 +EDGE2 1844 1565 1.01917 0.0580885 0.0143582 1 0 1 1 0 0 +EDGE2 1844 1585 0.977996 0.00838258 -0.0067849 1 0 1 1 0 0 +EDGE2 1844 1545 1.04795 0.0334212 0.00633931 1 0 1 1 0 0 +EDGE2 1845 1564 -0.980295 -0.0233677 0.0253491 1 0 1 1 0 0 +EDGE2 1845 1844 -1.05851 -0.0474599 0.0404748 1 0 1 1 0 0 +EDGE2 1845 1584 -1.08527 -0.00221443 -0.00777359 1 0 1 1 0 0 +EDGE2 1845 1544 -1.07076 0.027982 0.00836323 1 0 1 1 0 0 +EDGE2 1845 1546 0.00245245 -0.926646 -1.5764 1 0 1 1 0 0 +EDGE2 1845 1265 -0.0287193 0.0624284 -3.14845 1 0 1 1 0 0 +EDGE2 1845 1565 0.0422954 -0.00784214 -0.00647506 1 0 1 1 0 0 +EDGE2 1845 1585 -0.0104678 -0.00491132 -0.0128561 1 0 1 1 0 0 +EDGE2 1845 1545 0.0976677 0.0210641 0.0165269 1 0 1 1 0 0 +EDGE2 1845 1264 1.03246 -0.0429349 -3.12407 1 0 1 1 0 0 +EDGE2 1845 1566 0.0180115 1.05382 1.59157 1 0 1 1 0 0 +EDGE2 1845 1586 0.0246011 1.03495 1.58898 1 0 1 1 0 0 +EDGE2 1845 1266 -0.0114106 1.03138 1.58593 1 0 1 1 0 0 +EDGE2 1846 1265 -1.03974 -0.0053552 1.57232 1 0 1 1 0 0 +EDGE2 1846 1565 -0.981566 0.0928217 -1.60193 1 0 1 1 0 0 +EDGE2 1846 1585 -1.0674 -0.044284 -1.59294 1 0 1 1 0 0 +EDGE2 1846 1845 -0.996936 0.0153628 -1.56701 1 0 1 1 0 0 +EDGE2 1846 1545 -1.03295 -0.0126195 -1.55652 1 0 1 1 0 0 +EDGE2 1846 1567 0.993874 -0.0132321 -0.0130054 1 0 1 1 0 0 +EDGE2 1846 1587 0.990848 -0.0751477 0.00633755 1 0 1 1 0 0 +EDGE2 1846 1566 -0.0443704 -0.0257379 -0.0426255 1 0 1 1 0 0 +EDGE2 1846 1586 0.0549074 0.0672338 0.00681567 1 0 1 1 0 0 +EDGE2 1846 1266 -0.0104559 0.0247954 0.00723361 1 0 1 1 0 0 +EDGE2 1846 1267 0.932071 -0.0108854 -0.0188023 1 0 1 1 0 0 +EDGE2 1847 1567 0.00329178 0.0750598 -0.00693233 1 0 1 1 0 0 +EDGE2 1847 1587 0.0332957 -0.0831819 -0.008481 1 0 1 1 0 0 +EDGE2 1847 1566 -0.962778 -0.0372946 0.0222982 1 0 1 1 0 0 +EDGE2 1847 1846 -0.995073 -0.109649 -0.0360952 1 0 1 1 0 0 +EDGE2 1847 1586 -0.92294 -0.0494611 -0.0345836 1 0 1 1 0 0 +EDGE2 1847 1266 -0.949573 -0.0609456 0.0162417 1 0 1 1 0 0 +EDGE2 1847 1588 0.97343 -0.00201425 0.00116469 1 0 1 1 0 0 +EDGE2 1847 1267 0.041077 0.036274 -0.00983392 1 0 1 1 0 0 +EDGE2 1847 1268 0.986856 0.0887638 -0.00450295 1 0 1 1 0 0 +EDGE2 1847 1568 1.01971 0.0469114 0.00930247 1 0 1 1 0 0 +EDGE2 1848 1567 -0.961098 0.046775 0.0158919 1 0 1 1 0 0 +EDGE2 1848 1587 -1.02448 0.0550488 -0.0244326 1 0 1 1 0 0 +EDGE2 1848 1847 -0.942677 -0.0533586 0.0177988 1 0 1 1 0 0 +EDGE2 1848 1588 0.000793431 -0.00617221 0.010677 1 0 1 1 0 0 +EDGE2 1848 1267 -0.991783 0.00740079 -0.0102024 1 0 1 1 0 0 +EDGE2 1848 1268 0.00583321 -0.00950397 0.0238714 1 0 1 1 0 0 +EDGE2 1848 1568 0.0464653 -0.0720025 0.00438823 1 0 1 1 0 0 +EDGE2 1848 1569 1.0898 0.0445177 -0.0195553 1 0 1 1 0 0 +EDGE2 1848 1589 0.96376 0.00459661 0.00233809 1 0 1 1 0 0 +EDGE2 1848 1269 0.970159 -0.0239527 -0.00824734 1 0 1 1 0 0 +EDGE2 1849 1588 -0.989281 0.045325 -0.0139961 1 0 1 1 0 0 +EDGE2 1849 1848 -0.998326 0.0426785 0.0114635 1 0 1 1 0 0 +EDGE2 1849 1268 -0.974514 0.0163349 -0.00501742 1 0 1 1 0 0 +EDGE2 1849 1568 -0.977565 0.0427885 -0.0168542 1 0 1 1 0 0 +EDGE2 1849 1569 -0.0155549 -0.00579784 -0.0220447 1 0 1 1 0 0 +EDGE2 1849 1589 -0.0428342 -0.00499485 0.00613491 1 0 1 1 0 0 +EDGE2 1849 1269 0.0555027 0.00705857 0.0104593 1 0 1 1 0 0 +EDGE2 1849 1590 0.96271 0.00092184 -0.0156373 1 0 1 1 0 0 +EDGE2 1849 1270 1.06362 0.138203 -0.00361022 1 0 1 1 0 0 +EDGE2 1849 1290 0.931747 0.0515371 -3.11604 1 0 1 1 0 0 +EDGE2 1849 1570 0.885217 0.00778672 0.0126495 1 0 1 1 0 0 +EDGE2 1850 1571 -0.102078 1.10234 1.58612 1 0 1 1 0 0 +EDGE2 1850 1591 -0.111519 1.00646 1.57587 1 0 1 1 0 0 +EDGE2 1850 1849 -1.02353 0.0302037 -0.00922779 1 0 1 1 0 0 +EDGE2 1850 1569 -0.976459 0.0212079 -0.00181894 1 0 1 1 0 0 +EDGE2 1850 1589 -0.975196 0.0898924 -0.0225773 1 0 1 1 0 0 +EDGE2 1850 1269 -1.13281 0.00901857 0.02441 1 0 1 1 0 0 +EDGE2 1850 1291 -0.018063 -0.965134 -1.57287 1 0 1 1 0 0 +EDGE2 1850 1590 -0.0140785 0.0222596 0.0234546 1 0 1 1 0 0 +EDGE2 1850 1270 0.019778 -0.0123199 -0.0204253 1 0 1 1 0 0 +EDGE2 1850 1290 -0.0317595 0.0122443 -3.1459 1 0 1 1 0 0 +EDGE2 1850 1570 -0.0360341 -0.0563959 0.00645196 1 0 1 1 0 0 +EDGE2 1850 1271 0.124372 -1.06294 -1.57338 1 0 1 1 0 0 +EDGE2 1850 1289 1.00642 -0.0851859 -3.12293 1 0 1 1 0 0 +EDGE2 1851 1572 0.983022 0.0675087 0.0388214 1 0 1 1 0 0 +EDGE2 1851 1592 0.968976 -0.0294603 0.0163143 1 0 1 1 0 0 +EDGE2 1851 1571 0.0610465 -0.108598 -0.021643 1 0 1 1 0 0 +EDGE2 1851 1591 -0.0167764 -0.038794 -0.0125274 1 0 1 1 0 0 +EDGE2 1851 1590 -1.02794 -0.029401 -1.56193 1 0 1 1 0 0 +EDGE2 1851 1850 -0.992256 0.0364166 -1.60565 1 0 1 1 0 0 +EDGE2 1851 1270 -0.974846 -0.0515983 -1.59005 1 0 1 1 0 0 +EDGE2 1851 1290 -0.957378 -0.00842469 1.57643 1 0 1 1 0 0 +EDGE2 1851 1570 -0.968746 -0.0541305 -1.59523 1 0 1 1 0 0 +EDGE2 1852 1851 -0.993372 0.00188867 -0.00697929 1 0 1 1 0 0 +EDGE2 1852 1573 0.95723 -0.0250576 0.0107473 1 0 1 1 0 0 +EDGE2 1852 1593 0.964854 0.0704673 0.0251062 1 0 1 1 0 0 +EDGE2 1852 1572 -0.109714 -0.0171784 0.0235528 1 0 1 1 0 0 +EDGE2 1852 1592 -0.00905406 -0.0167579 0.0248938 1 0 1 1 0 0 +EDGE2 1852 1571 -1.036 -0.00174212 -0.0169282 1 0 1 1 0 0 +EDGE2 1852 1591 -0.998413 0.0864167 -0.0325973 1 0 1 1 0 0 +EDGE2 1853 1574 1.02765 -0.0789233 0.0334493 1 0 1 1 0 0 +EDGE2 1853 1594 1.06074 -0.0139275 -0.0258019 1 0 1 1 0 0 +EDGE2 1853 1852 -0.961345 0.0652038 0.00187372 1 0 1 1 0 0 +EDGE2 1853 1573 -0.128551 0.0222769 -0.0386553 1 0 1 1 0 0 +EDGE2 1853 1593 -0.0280147 0.0170815 -0.0277765 1 0 1 1 0 0 +EDGE2 1853 1572 -0.99485 0.0264579 0.0070852 1 0 1 1 0 0 +EDGE2 1853 1592 -0.991551 -0.0222593 0.00684877 1 0 1 1 0 0 +EDGE2 1854 1535 1.03715 -0.0833603 -3.11505 1 0 1 1 0 0 +EDGE2 1854 1595 1.05505 -0.0514901 -0.00773579 1 0 1 1 0 0 +EDGE2 1854 1655 1.08623 -0.0670245 -3.13727 1 0 1 1 0 0 +EDGE2 1854 1575 1.04427 -0.049145 0.0121348 1 0 1 1 0 0 +EDGE2 1854 1853 -1.05752 -0.0867821 -0.0118541 1 0 1 1 0 0 +EDGE2 1854 1375 1.01204 0.044313 -3.12914 1 0 1 1 0 0 +EDGE2 1854 1515 0.920631 -0.0599501 -3.15085 1 0 1 1 0 0 +EDGE2 1854 1574 -0.0810433 0.0468572 -0.0149181 1 0 1 1 0 0 +EDGE2 1854 1594 -0.0554327 -0.0280195 -0.0102848 1 0 1 1 0 0 +EDGE2 1854 1573 -0.904814 0.00321352 0.0272847 1 0 1 1 0 0 +EDGE2 1854 1593 -1.03246 0.0717936 -0.0269556 1 0 1 1 0 0 +EDGE2 1855 1656 -0.00251381 0.897752 1.58507 1 0 1 1 0 0 +EDGE2 1855 1536 0.0735972 1.01062 1.59748 1 0 1 1 0 0 +EDGE2 1855 1576 0.0117634 1.09982 1.58885 1 0 1 1 0 0 +EDGE2 1855 1376 -0.0160692 0.901659 1.56919 1 0 1 1 0 0 +EDGE2 1855 1535 -0.0541173 0.0256098 -3.12886 1 0 1 1 0 0 +EDGE2 1855 1514 1.05523 -0.0255513 -3.11054 1 0 1 1 0 0 +EDGE2 1855 1654 0.996733 -0.0613712 -3.12065 1 0 1 1 0 0 +EDGE2 1855 1534 1.02196 0.0421986 -3.11129 1 0 1 1 0 0 +EDGE2 1855 1374 1.00326 0.0249665 -3.16581 1 0 1 1 0 0 +EDGE2 1855 1595 -0.00972231 -0.0238908 0.0174594 1 0 1 1 0 0 +EDGE2 1855 1655 -0.0416076 -0.0220697 -3.12798 1 0 1 1 0 0 +EDGE2 1855 1575 -0.0656843 -0.0593751 -0.014308 1 0 1 1 0 0 +EDGE2 1855 1854 -1.02292 0.0185846 0.0200665 1 0 1 1 0 0 +EDGE2 1855 1375 -0.0412334 -0.083985 -3.15742 1 0 1 1 0 0 +EDGE2 1855 1515 -0.00162717 -0.00569471 -3.13398 1 0 1 1 0 0 +EDGE2 1855 1574 -0.944245 -0.0496047 0.0456031 1 0 1 1 0 0 +EDGE2 1855 1594 -1.05802 0.054329 0.010288 1 0 1 1 0 0 +EDGE2 1855 1516 -0.00889856 -1.08463 -1.52759 1 0 1 1 0 0 +EDGE2 1855 1596 0.00221248 -1.07773 -1.58293 1 0 1 1 0 0 +EDGE2 1856 1537 1.00049 0.0478364 0.00305523 1 0 1 1 0 0 +EDGE2 1856 1577 0.963811 -0.0211933 0.0134821 1 0 1 1 0 0 +EDGE2 1856 1657 0.965301 0.042594 0.00763333 1 0 1 1 0 0 +EDGE2 1856 1656 0.007226 -0.0595336 0.024262 1 0 1 1 0 0 +EDGE2 1856 1377 0.836409 0.100429 0.0118492 1 0 1 1 0 0 +EDGE2 1856 1536 0.0695772 0.000314033 -0.00859828 1 0 1 1 0 0 +EDGE2 1856 1576 -0.0254516 0.0505011 -0.0144829 1 0 1 1 0 0 +EDGE2 1856 1376 -0.0557375 0.00923563 0.0231962 1 0 1 1 0 0 +EDGE2 1856 1535 -0.987433 0.00939854 1.55882 1 0 1 1 0 0 +EDGE2 1856 1855 -1.00806 -0.0218593 -1.5633 1 0 1 1 0 0 +EDGE2 1856 1595 -1.03933 0.000109717 -1.51324 1 0 1 1 0 0 +EDGE2 1856 1655 -0.997082 -0.0431431 1.55395 1 0 1 1 0 0 +EDGE2 1856 1575 -0.995979 0.0661448 -1.57924 1 0 1 1 0 0 +EDGE2 1856 1375 -1.05831 0.0189589 1.56082 1 0 1 1 0 0 +EDGE2 1856 1515 -1.00362 -0.00778524 1.57376 1 0 1 1 0 0 +EDGE2 1857 1378 0.957542 0.0547013 0.0177423 1 0 1 1 0 0 +EDGE2 1857 1578 1.06352 -0.0177309 -0.0118178 1 0 1 1 0 0 +EDGE2 1857 1658 1.02607 -0.0210644 -0.0116525 1 0 1 1 0 0 +EDGE2 1857 1538 0.902226 0.000734294 -0.0117302 1 0 1 1 0 0 +EDGE2 1857 1537 -0.0320699 -0.00293952 -0.00552311 1 0 1 1 0 0 +EDGE2 1857 1577 0.126507 0.00525199 0.021598 1 0 1 1 0 0 +EDGE2 1857 1657 0.0289176 -0.00367912 0.0125488 1 0 1 1 0 0 +EDGE2 1857 1656 -1.02105 -0.0795422 -0.0177023 1 0 1 1 0 0 +EDGE2 1857 1377 0.0308658 0.0564364 0.0119501 1 0 1 1 0 0 +EDGE2 1857 1856 -0.97379 0.0593877 0.0163635 1 0 1 1 0 0 +EDGE2 1857 1536 -0.913881 0.132903 -0.0109358 1 0 1 1 0 0 +EDGE2 1857 1576 -1.02382 -0.0311217 0.0294866 1 0 1 1 0 0 +EDGE2 1857 1376 -1.00552 0.00301907 -0.0280279 1 0 1 1 0 0 +EDGE2 1858 1378 -0.0434514 0.0916069 -0.018364 1 0 1 1 0 0 +EDGE2 1858 1579 1.07875 0.0821788 -0.0128725 1 0 1 1 0 0 +EDGE2 1858 1659 0.958387 -0.0345512 -0.0148857 1 0 1 1 0 0 +EDGE2 1858 1379 1.08819 -0.110785 -0.0362781 1 0 1 1 0 0 +EDGE2 1858 1539 0.989627 -0.0116234 -0.0381095 1 0 1 1 0 0 +EDGE2 1858 1578 0.0329558 0.0325223 -0.00653812 1 0 1 1 0 0 +EDGE2 1858 1658 0.0125067 -0.0348455 -0.00949993 1 0 1 1 0 0 +EDGE2 1858 1538 0.0796212 0.0358197 0.0139449 1 0 1 1 0 0 +EDGE2 1858 1537 -1.02615 0.114103 -0.0407959 1 0 1 1 0 0 +EDGE2 1858 1577 -1.00527 0.0394906 -0.0228938 1 0 1 1 0 0 +EDGE2 1858 1857 -1.05718 0.0500496 0.00776668 1 0 1 1 0 0 +EDGE2 1858 1657 -1.06135 0.133255 0.0169609 1 0 1 1 0 0 +EDGE2 1858 1377 -1.02931 0.00124414 -0.025298 1 0 1 1 0 0 +EDGE2 1859 1540 0.982721 0.0203357 -0.0242638 1 0 1 1 0 0 +EDGE2 1859 1580 1.03202 -0.0295673 -0.0135363 1 0 1 1 0 0 +EDGE2 1859 1660 1.04647 0.0347442 -0.0391969 1 0 1 1 0 0 +EDGE2 1859 1840 1.00556 -0.0141465 -3.116 1 0 1 1 0 0 +EDGE2 1859 1560 1.0134 0.0290453 -3.15413 1 0 1 1 0 0 +EDGE2 1859 1380 0.930944 -0.0375019 -0.00548376 1 0 1 1 0 0 +EDGE2 1859 1378 -1.00607 -0.0408665 0.0114891 1 0 1 1 0 0 +EDGE2 1859 1858 -1.03589 0.0518924 -0.0074357 1 0 1 1 0 0 +EDGE2 1859 1579 0.0356025 -0.0289843 -0.0401353 1 0 1 1 0 0 +EDGE2 1859 1659 -0.0323817 -0.0216723 -0.00735806 1 0 1 1 0 0 +EDGE2 1859 1379 -0.0352651 -0.0171819 -0.0172051 1 0 1 1 0 0 +EDGE2 1859 1539 0.000412169 0.0469507 -0.0247828 1 0 1 1 0 0 +EDGE2 1859 1578 -1.05141 0.0195608 0.00189707 1 0 1 1 0 0 +EDGE2 1859 1658 -0.944097 -0.0363249 -0.00882897 1 0 1 1 0 0 +EDGE2 1859 1538 -0.99274 -0.0412683 -0.0441188 1 0 1 1 0 0 +EDGE2 1860 1839 0.999716 -0.01428 -3.15231 1 0 1 1 0 0 +EDGE2 1860 1559 1.0531 0.00310745 -3.12933 1 0 1 1 0 0 +EDGE2 1860 1540 -0.0153616 -0.0428188 -0.0204084 1 0 1 1 0 0 +EDGE2 1860 1381 0.0625866 -0.895797 -1.57074 1 0 1 1 0 0 +EDGE2 1860 1661 0.0186205 -0.991961 -1.57632 1 0 1 1 0 0 +EDGE2 1860 1580 0.0282861 -0.10066 -0.00533014 1 0 1 1 0 0 +EDGE2 1860 1660 -0.0265334 -0.0724486 -0.00149381 1 0 1 1 0 0 +EDGE2 1860 1840 -0.0114574 0.0794791 -3.12551 1 0 1 1 0 0 +EDGE2 1860 1560 0.012183 -0.0628413 -3.15175 1 0 1 1 0 0 +EDGE2 1860 1581 0.0258245 0.990695 1.58652 1 0 1 1 0 0 +EDGE2 1860 1380 0.0449796 -0.0820296 0.00747141 1 0 1 1 0 0 +EDGE2 1860 1841 0.067055 0.918148 1.58029 1 0 1 1 0 0 +EDGE2 1860 1541 0.0256496 1.00815 1.5763 1 0 1 1 0 0 +EDGE2 1860 1561 -0.0312211 0.992418 1.58147 1 0 1 1 0 0 +EDGE2 1860 1579 -1.00748 0.02016 -0.0159179 1 0 1 1 0 0 +EDGE2 1860 1859 -1.06544 0.105531 0.0152794 1 0 1 1 0 0 +EDGE2 1860 1659 -1.03527 0.0126371 0.0560873 1 0 1 1 0 0 +EDGE2 1860 1379 -1.03983 -0.0286122 -0.00565348 1 0 1 1 0 0 +EDGE2 1860 1539 -1.04577 0.080454 0.0371526 1 0 1 1 0 0 +EDGE2 1861 1540 -0.947841 -0.025265 1.574 1 0 1 1 0 0 +EDGE2 1861 1662 0.989249 -0.115698 0.0445495 1 0 1 1 0 0 +EDGE2 1861 1382 1.07167 0.0397341 0.0139681 1 0 1 1 0 0 +EDGE2 1861 1860 -0.980342 -0.017495 1.57011 1 0 1 1 0 0 +EDGE2 1861 1381 0.144929 -0.126877 -0.0156529 1 0 1 1 0 0 +EDGE2 1861 1661 -0.0452709 -0.0318623 0.00352302 1 0 1 1 0 0 +EDGE2 1861 1580 -0.958794 -0.0714379 1.60479 1 0 1 1 0 0 +EDGE2 1861 1660 -1.01394 -0.0954709 1.60415 1 0 1 1 0 0 +EDGE2 1861 1840 -1.07262 0.00438499 -1.55238 1 0 1 1 0 0 +EDGE2 1861 1560 -1.00554 -0.00611692 -1.54451 1 0 1 1 0 0 +EDGE2 1861 1380 -1.09091 -0.013192 1.57172 1 0 1 1 0 0 +EDGE2 1862 1861 -0.960317 0.107115 0.024251 1 0 1 1 0 0 +EDGE2 1862 1663 1.0226 -0.0342615 -0.032342 1 0 1 1 0 0 +EDGE2 1862 1662 -0.0745043 -0.097562 -0.0260048 1 0 1 1 0 0 +EDGE2 1862 1383 0.974705 0.0160442 -0.00175295 1 0 1 1 0 0 +EDGE2 1862 1382 -0.00350574 0.0114831 -0.00495718 1 0 1 1 0 0 +EDGE2 1862 1381 -1.06812 0.0658491 -0.0107244 1 0 1 1 0 0 +EDGE2 1862 1661 -1.00335 0.0685799 0.0134195 1 0 1 1 0 0 +EDGE2 1863 1663 0.00316345 0.0232278 0.0226405 1 0 1 1 0 0 +EDGE2 1863 1384 1.04128 -0.0700233 -0.0163782 1 0 1 1 0 0 +EDGE2 1863 1664 1.04742 -0.0176801 -0.00498765 1 0 1 1 0 0 +EDGE2 1863 1662 -1.11608 -0.0156545 -0.00207484 1 0 1 1 0 0 +EDGE2 1863 1862 -0.973637 -0.00525541 -0.0120268 1 0 1 1 0 0 +EDGE2 1863 1383 0.0133684 0.09154 0.00688986 1 0 1 1 0 0 +EDGE2 1863 1382 -0.936106 0.0816108 -0.0147482 1 0 1 1 0 0 +EDGE2 1864 1665 1.00083 0.0495689 0.0216308 1 0 1 1 0 0 +EDGE2 1864 1705 1.08873 0.034001 -3.1277 1 0 1 1 0 0 +EDGE2 1864 1385 1.02532 0.0334736 -0.0102219 1 0 1 1 0 0 +EDGE2 1864 1465 0.942952 0.028284 -3.14497 1 0 1 1 0 0 +EDGE2 1864 1663 -0.836641 -0.0325496 -0.0205787 1 0 1 1 0 0 +EDGE2 1864 1384 -0.0457942 0.0462903 -0.00623033 1 0 1 1 0 0 +EDGE2 1864 1664 -0.105647 -0.023247 -0.0303848 1 0 1 1 0 0 +EDGE2 1864 1863 -0.977125 0.0609437 0.00353448 1 0 1 1 0 0 +EDGE2 1864 1383 -0.970832 0.0556185 -0.00792572 1 0 1 1 0 0 +EDGE2 1865 1386 -0.0235276 0.990527 1.55156 1 0 1 1 0 0 +EDGE2 1865 1665 0.00113215 -0.0607221 0.0214288 1 0 1 1 0 0 +EDGE2 1865 1464 1.00213 0.0485791 -3.14631 1 0 1 1 0 0 +EDGE2 1865 1704 0.933017 0.0729576 -3.11296 1 0 1 1 0 0 +EDGE2 1865 1705 0.0338518 -0.0154532 -3.16166 1 0 1 1 0 0 +EDGE2 1865 1385 -0.0695257 0.0112903 0.0363455 1 0 1 1 0 0 +EDGE2 1865 1465 -0.0328261 0.0396209 -3.18502 1 0 1 1 0 0 +EDGE2 1865 1666 0.0323956 -1.05374 -1.56075 1 0 1 1 0 0 +EDGE2 1865 1706 -0.00108135 -0.993369 -1.58207 1 0 1 1 0 0 +EDGE2 1865 1466 -0.0600003 -1.00701 -1.56893 1 0 1 1 0 0 +EDGE2 1865 1384 -0.96025 -0.0296025 -0.0197114 1 0 1 1 0 0 +EDGE2 1865 1664 -1.03812 -0.00150767 0.0355842 1 0 1 1 0 0 +EDGE2 1865 1864 -1.04094 -0.0526429 0.0253199 1 0 1 1 0 0 +EDGE2 1866 1665 -0.944201 0.0977973 1.60281 1 0 1 1 0 0 +EDGE2 1866 1865 -0.991235 0.0427716 1.56227 1 0 1 1 0 0 +EDGE2 1866 1705 -1.02653 -0.0185215 -1.58996 1 0 1 1 0 0 +EDGE2 1866 1385 -0.936059 0.00125656 1.5845 1 0 1 1 0 0 +EDGE2 1866 1465 -0.960841 0.0141267 -1.52879 1 0 1 1 0 0 +EDGE2 1866 1666 -0.00766574 -0.0764504 0.0232638 1 0 1 1 0 0 +EDGE2 1866 1706 -0.0179972 0.010009 0.00406508 1 0 1 1 0 0 +EDGE2 1866 1466 -0.129122 0.0840185 -0.00846705 1 0 1 1 0 0 +EDGE2 1866 1667 0.911664 0.0746059 0.00447383 1 0 1 1 0 0 +EDGE2 1866 1707 0.966794 -0.0245127 -0.00749821 1 0 1 1 0 0 +EDGE2 1866 1467 1.00394 -0.0160103 0.00925617 1 0 1 1 0 0 +EDGE2 1867 1468 1.00157 -0.00444715 -0.00782044 1 0 1 1 0 0 +EDGE2 1867 1666 -0.92697 0.00226057 -0.0144243 1 0 1 1 0 0 +EDGE2 1867 1706 -0.986366 0.00637233 0.0234935 1 0 1 1 0 0 +EDGE2 1867 1866 -1.0597 -0.0479154 -0.000756825 1 0 1 1 0 0 +EDGE2 1867 1466 -0.962032 -0.0253453 0.035626 1 0 1 1 0 0 +EDGE2 1867 1667 -0.039706 0.0510128 -0.0592839 1 0 1 1 0 0 +EDGE2 1867 1707 -0.0272126 -0.0389185 -0.000352117 1 0 1 1 0 0 +EDGE2 1867 1467 0.0304237 -0.00446088 0.0228756 1 0 1 1 0 0 +EDGE2 1867 1668 0.918502 -0.0215329 -0.0135156 1 0 1 1 0 0 +EDGE2 1867 1708 1.09309 0.0377381 -0.0145779 1 0 1 1 0 0 +EDGE2 1868 1468 -0.0115121 0.0413869 0.00330109 1 0 1 1 0 0 +EDGE2 1868 1867 -0.911234 0.0269444 -0.0259375 1 0 1 1 0 0 +EDGE2 1868 1667 -1.00069 0.00915725 -0.00582483 1 0 1 1 0 0 +EDGE2 1868 1707 -1.10679 -0.031379 0.0247105 1 0 1 1 0 0 +EDGE2 1868 1467 -0.931467 -0.019578 0.0125217 1 0 1 1 0 0 +EDGE2 1868 1668 0.0141303 -0.0197726 -0.0209058 1 0 1 1 0 0 +EDGE2 1868 1708 -0.0492632 0.0136256 0.017664 1 0 1 1 0 0 +EDGE2 1868 1669 0.990685 0.072112 0.0377727 1 0 1 1 0 0 +EDGE2 1868 1709 1.01696 -0.0309936 -0.0208302 1 0 1 1 0 0 +EDGE2 1868 1469 1.00161 -0.0015395 0.0156968 1 0 1 1 0 0 +EDGE2 1869 1468 -0.957698 -0.0525579 -0.0281741 1 0 1 1 0 0 +EDGE2 1869 1668 -1.00614 0.076522 -0.00972092 1 0 1 1 0 0 +EDGE2 1869 1708 -1.04699 0.0152561 0.0070788 1 0 1 1 0 0 +EDGE2 1869 1868 -0.952055 0.0936132 0.0375035 1 0 1 1 0 0 +EDGE2 1869 1669 -0.0165761 0.0965821 -0.0311711 1 0 1 1 0 0 +EDGE2 1869 1709 -0.0264506 -0.0290805 -0.0180161 1 0 1 1 0 0 +EDGE2 1869 1469 0.028684 0.0406039 0.0145903 1 0 1 1 0 0 +EDGE2 1869 1650 0.948749 -0.120375 -3.10936 1 0 1 1 0 0 +EDGE2 1869 1710 0.975276 -0.0154303 0.0225341 1 0 1 1 0 0 +EDGE2 1869 1670 0.95917 0.00594354 -0.00452563 1 0 1 1 0 0 +EDGE2 1869 1470 0.998445 -0.070051 0.0147008 1 0 1 1 0 0 +EDGE2 1869 1510 1.05035 -0.0454702 -3.16809 1 0 1 1 0 0 +EDGE2 1869 1530 1.03787 0.0183909 -3.13838 1 0 1 1 0 0 +EDGE2 1869 1370 1.03816 0.0477929 -3.16509 1 0 1 1 0 0 +EDGE2 1870 1669 -1.09049 -0.0347881 0.00981755 1 0 1 1 0 0 +EDGE2 1870 1709 -1.01251 0.0429645 -0.0170652 1 0 1 1 0 0 +EDGE2 1870 1869 -1.02507 -0.0423457 0.00728725 1 0 1 1 0 0 +EDGE2 1870 1469 -1.03675 0.0257908 0.00667109 1 0 1 1 0 0 +EDGE2 1870 1671 0.0532973 1.01261 1.58303 1 0 1 1 0 0 +EDGE2 1870 1711 0.0103487 1.0612 1.57483 1 0 1 1 0 0 +EDGE2 1870 1471 0.0167495 0.997188 1.5632 1 0 1 1 0 0 +EDGE2 1870 1650 0.134389 0.00814119 -3.14281 1 0 1 1 0 0 +EDGE2 1870 1710 0.00713784 0.0695956 -0.0154536 1 0 1 1 0 0 +EDGE2 1870 1670 0.0983772 0.0227988 0.0146449 1 0 1 1 0 0 +EDGE2 1870 1470 0.0499556 0.0266077 -0.0141751 1 0 1 1 0 0 +EDGE2 1870 1510 0.0395715 -0.0369922 -3.122 1 0 1 1 0 0 +EDGE2 1870 1530 -0.0885191 -0.0535681 -3.12528 1 0 1 1 0 0 +EDGE2 1870 1370 0.00483162 0.161824 -3.15159 1 0 1 1 0 0 +EDGE2 1870 1371 -0.0650023 -1.0302 -1.51542 1 0 1 1 0 0 +EDGE2 1870 1531 0.0423845 -1.11101 -1.57692 1 0 1 1 0 0 +EDGE2 1870 1651 0.014134 -0.932778 -1.57658 1 0 1 1 0 0 +EDGE2 1870 1511 0.0633869 -0.932949 -1.58173 1 0 1 1 0 0 +EDGE2 1870 1509 0.959755 -0.00972655 -3.17186 1 0 1 1 0 0 +EDGE2 1870 1649 0.941503 0.0156704 -3.13253 1 0 1 1 0 0 +EDGE2 1870 1529 1.04747 0.00550378 -3.10685 1 0 1 1 0 0 +EDGE2 1870 1369 1.07856 0.01796 -3.12286 1 0 1 1 0 0 +EDGE2 1871 1672 1.02156 -0.0566066 -0.00543366 1 0 1 1 0 0 +EDGE2 1871 1712 1.05603 0.0981161 0.0301131 1 0 1 1 0 0 +EDGE2 1871 1472 1.03711 -0.0447046 -0.0045173 1 0 1 1 0 0 +EDGE2 1871 1671 -0.0831891 0.0690795 -0.0276093 1 0 1 1 0 0 +EDGE2 1871 1711 -0.0480038 -0.0472705 0.00582883 1 0 1 1 0 0 +EDGE2 1871 1471 -0.0547439 -0.0391059 0.0245802 1 0 1 1 0 0 +EDGE2 1871 1650 -1.07175 0.0581521 1.60485 1 0 1 1 0 0 +EDGE2 1871 1710 -0.982822 -0.0306757 -1.57719 1 0 1 1 0 0 +EDGE2 1871 1870 -1.07279 0.112251 -1.60754 1 0 1 1 0 0 +EDGE2 1871 1670 -0.909432 0.0309468 -1.54709 1 0 1 1 0 0 +EDGE2 1871 1470 -1.03847 -0.0954324 -1.59948 1 0 1 1 0 0 +EDGE2 1871 1510 -1.00589 -0.0501958 1.59329 1 0 1 1 0 0 +EDGE2 1871 1530 -1.03337 -0.0133385 1.57902 1 0 1 1 0 0 +EDGE2 1871 1370 -0.995726 0.0288622 1.57178 1 0 1 1 0 0 +EDGE2 1872 1473 1.05381 0.0274587 -0.0107446 1 0 1 1 0 0 +EDGE2 1872 1673 0.978033 -0.0109223 -0.00535797 1 0 1 1 0 0 +EDGE2 1872 1713 0.984867 -0.00882377 0.00460359 1 0 1 1 0 0 +EDGE2 1872 1672 -0.0381526 0.0125341 -0.0183247 1 0 1 1 0 0 +EDGE2 1872 1712 0.0607236 0.0772223 0.00412958 1 0 1 1 0 0 +EDGE2 1872 1472 -0.0405882 0.0300488 -0.00215947 1 0 1 1 0 0 +EDGE2 1872 1671 -0.988838 0.0276405 -0.00973415 1 0 1 1 0 0 +EDGE2 1872 1711 -1.01944 -0.000122641 0.0311416 1 0 1 1 0 0 +EDGE2 1872 1871 -0.948505 0.104121 -0.00361087 1 0 1 1 0 0 +EDGE2 1872 1471 -0.853381 -0.0333231 -0.027981 1 0 1 1 0 0 +EDGE2 1873 1474 1.10244 -0.0783347 -0.0056528 1 0 1 1 0 0 +EDGE2 1873 1674 1.0172 0.0434031 0.00958939 1 0 1 1 0 0 +EDGE2 1873 1714 0.930966 -0.0198029 -0.0145831 1 0 1 1 0 0 +EDGE2 1873 1872 -0.950468 -0.0104991 0.00529731 1 0 1 1 0 0 +EDGE2 1873 1473 0.0151591 -0.0424398 -0.00729276 1 0 1 1 0 0 +EDGE2 1873 1673 -0.0586579 0.00238692 -0.0329452 1 0 1 1 0 0 +EDGE2 1873 1713 -0.0196715 0.121287 -0.0237862 1 0 1 1 0 0 +EDGE2 1873 1672 -0.995023 0.00181645 0.0556351 1 0 1 1 0 0 +EDGE2 1873 1712 -0.940937 0.0136242 0.0298446 1 0 1 1 0 0 +EDGE2 1873 1472 -1.00989 -0.0656599 -0.0423247 1 0 1 1 0 0 +EDGE2 1874 1715 0.99866 0.0773303 0.0459534 1 0 1 1 0 0 +EDGE2 1874 1873 -1.03501 -0.00867377 0.0199933 1 0 1 1 0 0 +EDGE2 1874 1475 0.964667 0.0475014 -4.62987e-05 1 0 1 1 0 0 +EDGE2 1874 1675 1.01747 -0.0282103 -0.00525959 1 0 1 1 0 0 +EDGE2 1874 1695 0.990067 -0.0226052 -3.1884 1 0 1 1 0 0 +EDGE2 1874 1474 -0.0661506 0.0671187 -0.00468931 1 0 1 1 0 0 +EDGE2 1874 1674 0.052745 0.0109423 -0.00295708 1 0 1 1 0 0 +EDGE2 1874 1714 -0.0352432 0.0150568 -0.00895816 1 0 1 1 0 0 +EDGE2 1874 1473 -1.03431 -0.0159282 0.00464737 1 0 1 1 0 0 +EDGE2 1874 1673 -0.993851 -0.0753085 -0.0496797 1 0 1 1 0 0 +EDGE2 1874 1713 -1.03801 -0.059425 0.0107744 1 0 1 1 0 0 +EDGE2 1875 1715 0.010791 0.0599869 0.00509533 1 0 1 1 0 0 +EDGE2 1875 1694 0.954523 0.0329341 -3.13686 1 0 1 1 0 0 +EDGE2 1875 1716 0.0299968 1.01707 1.53172 1 0 1 1 0 0 +EDGE2 1875 1696 0.0161272 1.01107 1.56832 1 0 1 1 0 0 +EDGE2 1875 1874 -1.0914 0.0685111 -0.0547278 1 0 1 1 0 0 +EDGE2 1875 1475 0.0926919 0.0241574 -0.00886854 1 0 1 1 0 0 +EDGE2 1875 1675 -0.010917 0.0674368 -0.0071736 1 0 1 1 0 0 +EDGE2 1875 1695 -0.0409373 -0.066094 -3.14065 1 0 1 1 0 0 +EDGE2 1875 1474 -1.0531 -0.0655329 0.0077605 1 0 1 1 0 0 +EDGE2 1875 1674 -1.0722 0.0201561 0.0259097 1 0 1 1 0 0 +EDGE2 1875 1714 -0.995085 -0.0176456 0.0190283 1 0 1 1 0 0 +EDGE2 1875 1676 -0.0550981 -0.981882 -1.56375 1 0 1 1 0 0 +EDGE2 1875 1476 -0.0084526 -1.01394 -1.55854 1 0 1 1 0 0 +EDGE2 1876 1715 -0.965601 -0.0455158 1.54363 1 0 1 1 0 0 +EDGE2 1876 1875 -0.966863 -0.0535332 1.55642 1 0 1 1 0 0 +EDGE2 1876 1475 -1.10331 -0.0587764 1.57769 1 0 1 1 0 0 +EDGE2 1876 1675 -0.957235 0.0319771 1.55186 1 0 1 1 0 0 +EDGE2 1876 1695 -0.97638 0.00613395 -1.56403 1 0 1 1 0 0 +EDGE2 1876 1676 0.00526169 0.0217062 0.00583998 1 0 1 1 0 0 +EDGE2 1876 1476 0.0647258 -0.0254436 -0.0231493 1 0 1 1 0 0 +EDGE2 1876 1677 1.00854 -0.057791 -0.0063746 1 0 1 1 0 0 +EDGE2 1876 1477 1.00635 0.0573916 0.0515605 1 0 1 1 0 0 +EDGE2 1877 1676 -0.960549 -0.013006 -0.0189578 1 0 1 1 0 0 +EDGE2 1877 1876 -0.977749 0.158078 -0.0022528 1 0 1 1 0 0 +EDGE2 1877 1476 -0.998178 0.0307309 0.00421687 1 0 1 1 0 0 +EDGE2 1877 1677 -0.0145258 0.0287662 -0.0262434 1 0 1 1 0 0 +EDGE2 1877 1477 0.0242115 0.0078866 0.00393758 1 0 1 1 0 0 +EDGE2 1877 1678 1.06878 -0.0020559 0.0298236 1 0 1 1 0 0 +EDGE2 1877 1478 0.999434 -0.0181454 0.00560009 1 0 1 1 0 0 +EDGE2 1878 1677 -1.02022 -0.0262144 0.00144612 1 0 1 1 0 0 +EDGE2 1878 1877 -1.02961 0.0330304 0.0262339 1 0 1 1 0 0 +EDGE2 1878 1477 -1.12027 -0.0602932 0.00306279 1 0 1 1 0 0 +EDGE2 1878 1678 0.0342103 0.0998852 -0.0104891 1 0 1 1 0 0 +EDGE2 1878 1478 0.118267 -0.0399514 0.0218695 1 0 1 1 0 0 +EDGE2 1878 1679 0.949868 -0.0213037 0.0477391 1 0 1 1 0 0 +EDGE2 1878 1479 0.966641 -0.072816 0.0298572 1 0 1 1 0 0 +EDGE2 1879 1678 -1.07449 0.0199033 0.0251897 1 0 1 1 0 0 +EDGE2 1879 1878 -1.04524 0.0515023 0.0232411 1 0 1 1 0 0 +EDGE2 1879 1478 -0.975465 -0.0121166 0.00943856 1 0 1 1 0 0 +EDGE2 1879 1360 0.954734 -0.0605826 -3.1276 1 0 1 1 0 0 +EDGE2 1879 1679 -0.0842558 -0.0403958 -0.011988 1 0 1 1 0 0 +EDGE2 1879 1479 0.0748822 0.0999593 0.0306313 1 0 1 1 0 0 +EDGE2 1879 1500 1.10688 0.0179888 -3.12074 1 0 1 1 0 0 +EDGE2 1879 1680 0.979372 -0.0252568 0.0300307 1 0 1 1 0 0 +EDGE2 1879 1480 1.06084 0.0169609 0.0266483 1 0 1 1 0 0 +EDGE2 1879 1340 1.06155 0.101829 -3.14265 1 0 1 1 0 0 +EDGE2 1880 1360 -0.0125226 0.0279514 -3.15903 1 0 1 1 0 0 +EDGE2 1880 1679 -1.03225 -0.111843 -0.00429228 1 0 1 1 0 0 +EDGE2 1880 1879 -1.05477 0.0423433 -0.00504578 1 0 1 1 0 0 +EDGE2 1880 1479 -1.00902 -0.0618212 0.0327488 1 0 1 1 0 0 +EDGE2 1880 1681 0.0153582 0.980427 1.55824 1 0 1 1 0 0 +EDGE2 1880 1500 0.0181105 -0.057043 -3.12566 1 0 1 1 0 0 +EDGE2 1880 1680 -0.117435 0.0164904 -0.011976 1 0 1 1 0 0 +EDGE2 1880 1480 -0.0608975 0.0114584 -0.0254099 1 0 1 1 0 0 +EDGE2 1880 1481 0.0188844 -0.940271 -1.57804 1 0 1 1 0 0 +EDGE2 1880 1340 0.0359639 -0.0979209 -3.14185 1 0 1 1 0 0 +EDGE2 1880 1501 -0.0627002 -1.03378 -1.58043 1 0 1 1 0 0 +EDGE2 1880 1341 -0.00110855 -1.02948 -1.57222 1 0 1 1 0 0 +EDGE2 1880 1361 -0.0275901 -0.994456 -1.54012 1 0 1 1 0 0 +EDGE2 1880 1359 1.11294 -0.0712245 -3.12971 1 0 1 1 0 0 +EDGE2 1880 1499 1.05062 -0.0956269 -3.15288 1 0 1 1 0 0 +EDGE2 1880 1339 1.01723 -0.021193 -3.16158 1 0 1 1 0 0 +EDGE2 1881 1360 -1.00732 -0.0282216 1.578 1 0 1 1 0 0 +EDGE2 1881 1681 0.0166386 0.0979139 -0.00993231 1 0 1 1 0 0 +EDGE2 1881 1682 0.948685 0.0833979 -0.0152665 1 0 1 1 0 0 +EDGE2 1881 1880 -0.9177 -0.00373364 -1.54682 1 0 1 1 0 0 +EDGE2 1881 1500 -1.05822 0.0576166 1.53312 1 0 1 1 0 0 +EDGE2 1881 1680 -0.989456 -0.00578804 -1.60825 1 0 1 1 0 0 +EDGE2 1881 1480 -0.95734 -0.0196621 -1.57474 1 0 1 1 0 0 +EDGE2 1881 1340 -0.989292 0.0141358 1.56483 1 0 1 1 0 0 +EDGE2 1882 1681 -1.00796 -0.0193165 -0.0435438 1 0 1 1 0 0 +EDGE2 1882 1682 0.055367 0.0359405 -0.00141953 1 0 1 1 0 0 +EDGE2 1882 1683 0.989582 0.0296149 0.0208108 1 0 1 1 0 0 +EDGE2 1882 1881 -0.968428 0.0302511 0.00371931 1 0 1 1 0 0 +EDGE2 1883 1684 0.927021 -0.0832617 -0.00884942 1 0 1 1 0 0 +EDGE2 1883 1682 -0.937216 0.0151095 0.00763666 1 0 1 1 0 0 +EDGE2 1883 1882 -1.01848 -0.0636796 0.00560133 1 0 1 1 0 0 +EDGE2 1883 1683 -0.0587378 -0.0227073 0.0232806 1 0 1 1 0 0 +EDGE2 1884 1883 -0.962154 -0.0246764 0.0165284 1 0 1 1 0 0 +EDGE2 1884 1685 1.01773 -0.0105938 -0.0272677 1 0 1 1 0 0 +EDGE2 1884 1684 0.0681752 -0.0881443 0.00452822 1 0 1 1 0 0 +EDGE2 1884 1683 -1.00934 0.035925 0.0044444 1 0 1 1 0 0 +EDGE2 1885 1686 0.14707 1.05494 1.5724 1 0 1 1 0 0 +EDGE2 1885 1884 -1.01421 0.0267397 -0.0580377 1 0 1 1 0 0 +EDGE2 1885 1685 -0.121632 0.0140824 0.0168212 1 0 1 1 0 0 +EDGE2 1885 1684 -1.04493 -0.0307151 0.0386042 1 0 1 1 0 0 +EDGE2 1886 1687 0.959425 0.0530225 0.00500863 1 0 1 1 0 0 +EDGE2 1886 1686 0.0416782 -0.0705308 0.000144036 1 0 1 1 0 0 +EDGE2 1886 1685 -1.07045 5.50722e-05 -1.5657 1 0 1 1 0 0 +EDGE2 1886 1885 -1.06884 0.0118612 -1.58505 1 0 1 1 0 0 +EDGE2 1887 1688 1.06926 -0.073562 0.0161615 1 0 1 1 0 0 +EDGE2 1887 1687 0.0399724 0.0346274 -0.0142831 1 0 1 1 0 0 +EDGE2 1887 1686 -0.983688 -0.0272461 -0.00875671 1 0 1 1 0 0 +EDGE2 1887 1886 -1.04097 0.0250703 0.00820986 1 0 1 1 0 0 +EDGE2 1888 1689 0.975624 -0.0181868 -0.0136266 1 0 1 1 0 0 +EDGE2 1888 1688 -0.0077997 0.0477161 0.0540398 1 0 1 1 0 0 +EDGE2 1888 1687 -0.991542 -0.00650793 0.0142517 1 0 1 1 0 0 +EDGE2 1888 1887 -1.04204 0.0632118 -0.00303115 1 0 1 1 0 0 +EDGE2 1889 1690 0.997046 -0.037586 -0.0282705 1 0 1 1 0 0 +EDGE2 1889 1689 -0.000986756 0.0514422 0.000680807 1 0 1 1 0 0 +EDGE2 1889 1688 -1.03482 -0.0158123 0.00141571 1 0 1 1 0 0 +EDGE2 1889 1888 -1.0182 -0.0249554 0.0119227 1 0 1 1 0 0 +EDGE2 1890 1690 -0.0741305 0.00165429 0.0111416 1 0 1 1 0 0 +EDGE2 1890 1691 -0.0340834 0.980899 1.58929 1 0 1 1 0 0 +EDGE2 1890 1689 -1.02217 0.043226 -0.00525138 1 0 1 1 0 0 +EDGE2 1890 1889 -0.925519 -0.0125762 -0.0271348 1 0 1 1 0 0 +EDGE2 1891 1690 -1.04811 -0.00401163 -1.56774 1 0 1 1 0 0 +EDGE2 1891 1890 -0.986505 -0.0802796 -1.55616 1 0 1 1 0 0 +EDGE2 1891 1691 -0.0140025 -0.0182732 0.0123785 1 0 1 1 0 0 +EDGE2 1891 1692 1.04347 0.0436296 0.01015 1 0 1 1 0 0 +EDGE2 1892 1891 -1.00371 -0.0360549 0.0274439 1 0 1 1 0 0 +EDGE2 1892 1691 -1.03211 -0.0338071 0.0107949 1 0 1 1 0 0 +EDGE2 1892 1693 1.00493 0.0187777 -0.00110607 1 0 1 1 0 0 +EDGE2 1892 1692 0.075415 -0.0423887 -0.0155371 1 0 1 1 0 0 +EDGE2 1893 1694 0.95791 0.0826797 -0.00539482 1 0 1 1 0 0 +EDGE2 1893 1892 -1.01645 0.0479573 -0.0237346 1 0 1 1 0 0 +EDGE2 1893 1693 -0.0436825 0.078083 0.0193031 1 0 1 1 0 0 +EDGE2 1893 1692 -1.00642 -0.0653748 0.0156154 1 0 1 1 0 0 +EDGE2 1894 1715 0.989811 0.118064 -3.14279 1 0 1 1 0 0 +EDGE2 1894 1694 0.049629 -0.0359979 -0.00195851 1 0 1 1 0 0 +EDGE2 1894 1693 -0.988163 -0.0258442 -0.0278471 1 0 1 1 0 0 +EDGE2 1894 1893 -0.929848 -0.13658 0.00146095 1 0 1 1 0 0 +EDGE2 1894 1875 0.926246 0.0489152 -3.13869 1 0 1 1 0 0 +EDGE2 1894 1475 0.944145 0.0160933 -3.15698 1 0 1 1 0 0 +EDGE2 1894 1675 1.02525 -0.0495538 -3.15008 1 0 1 1 0 0 +EDGE2 1894 1695 0.979937 0.0104064 -0.028675 1 0 1 1 0 0 +EDGE2 1895 1715 0.0251303 0.00967679 -3.15022 1 0 1 1 0 0 +EDGE2 1895 1694 -0.936929 0.0246543 0.0509861 1 0 1 1 0 0 +EDGE2 1895 1894 -0.97373 -0.0128923 0.00335984 1 0 1 1 0 0 +EDGE2 1895 1716 0.0184164 -1.03276 -1.54685 1 0 1 1 0 0 +EDGE2 1895 1696 -0.00555911 -1.00749 -1.55582 1 0 1 1 0 0 +EDGE2 1895 1875 0.0336354 0.0713931 -3.13093 1 0 1 1 0 0 +EDGE2 1895 1874 0.910821 -0.0282599 -3.14765 1 0 1 1 0 0 +EDGE2 1895 1475 0.0133759 0.0788267 -3.13036 1 0 1 1 0 0 +EDGE2 1895 1675 0.011247 -0.0445166 -3.15141 1 0 1 1 0 0 +EDGE2 1895 1695 -0.00784897 -0.0517794 -0.0112943 1 0 1 1 0 0 +EDGE2 1895 1474 1.02722 0.0499115 -3.13948 1 0 1 1 0 0 +EDGE2 1895 1674 1.03101 0.0302889 -3.1509 1 0 1 1 0 0 +EDGE2 1895 1714 0.904772 0.0388476 -3.11754 1 0 1 1 0 0 +EDGE2 1895 1676 -0.0268394 1.02962 1.59904 1 0 1 1 0 0 +EDGE2 1895 1876 -0.0146616 1.08293 1.56577 1 0 1 1 0 0 +EDGE2 1895 1476 0.00826501 1.02383 1.56349 1 0 1 1 0 0 +EDGE2 1896 1715 -0.950775 -0.00433382 1.60027 1 0 1 1 0 0 +EDGE2 1896 1895 -1.03085 0.0345103 -1.56886 1 0 1 1 0 0 +EDGE2 1896 1875 -0.985925 0.0218156 1.59004 1 0 1 1 0 0 +EDGE2 1896 1475 -0.991169 0.0384924 1.58441 1 0 1 1 0 0 +EDGE2 1896 1675 -0.936655 0.0415276 1.53468 1 0 1 1 0 0 +EDGE2 1896 1695 -1.05712 -0.061534 -1.53247 1 0 1 1 0 0 +EDGE2 1896 1676 0.0733897 0.0117915 -0.017789 1 0 1 1 0 0 +EDGE2 1896 1876 0.0652043 -0.0239889 -0.0140644 1 0 1 1 0 0 +EDGE2 1896 1476 0.0539797 0.0485251 -0.000666986 1 0 1 1 0 0 +EDGE2 1896 1677 0.959772 -0.07191 -0.000481865 1 0 1 1 0 0 +EDGE2 1896 1877 0.989488 -0.0454059 0.0194648 1 0 1 1 0 0 +EDGE2 1896 1477 1.05149 -0.0321547 0.00272736 1 0 1 1 0 0 +EDGE2 1897 1676 -1.00851 -0.0541347 -0.026484 1 0 1 1 0 0 +EDGE2 1897 1876 -1.02396 -0.0329572 0.0260452 1 0 1 1 0 0 +EDGE2 1897 1896 -0.962634 -0.00603303 0.000405932 1 0 1 1 0 0 +EDGE2 1897 1476 -1.00802 -0.0546639 -0.02716 1 0 1 1 0 0 +EDGE2 1897 1677 0.0208319 0.0770924 0.00687542 1 0 1 1 0 0 +EDGE2 1897 1877 0.0195329 0.0587986 -0.0268994 1 0 1 1 0 0 +EDGE2 1897 1477 0.101331 -0.029171 -0.000147888 1 0 1 1 0 0 +EDGE2 1897 1678 0.992287 -0.0218699 -0.0122087 1 0 1 1 0 0 +EDGE2 1897 1878 1.00981 -0.057737 -0.00145811 1 0 1 1 0 0 +EDGE2 1897 1478 0.897134 -0.0552361 0.0143031 1 0 1 1 0 0 +EDGE2 1898 1677 -0.959838 0.0194479 -0.0149605 1 0 1 1 0 0 +EDGE2 1898 1877 -0.948119 0.0480274 -0.00643821 1 0 1 1 0 0 +EDGE2 1898 1897 -0.960179 0.0903966 0.0230294 1 0 1 1 0 0 +EDGE2 1898 1477 -0.928817 0.0135641 -0.00456533 1 0 1 1 0 0 +EDGE2 1898 1678 -0.067321 0.0912718 0.030956 1 0 1 1 0 0 +EDGE2 1898 1878 -2.71094e-05 0.0486798 0.0141511 1 0 1 1 0 0 +EDGE2 1898 1478 0.0272221 -0.0890261 0.00458896 1 0 1 1 0 0 +EDGE2 1898 1679 0.928115 -0.0699871 -0.0458507 1 0 1 1 0 0 +EDGE2 1898 1879 1.01343 0.00733051 -0.0428463 1 0 1 1 0 0 +EDGE2 1898 1479 0.985353 0.0145294 -0.00834303 1 0 1 1 0 0 +EDGE2 1899 1678 -0.951151 0.0189413 0.00187891 1 0 1 1 0 0 +EDGE2 1899 1878 -1.00819 -0.0108395 -0.00048171 1 0 1 1 0 0 +EDGE2 1899 1898 -0.9867 -0.0561423 -0.0119351 1 0 1 1 0 0 +EDGE2 1899 1478 -1.04438 0.0797328 -0.0288927 1 0 1 1 0 0 +EDGE2 1899 1360 0.913515 0.0016177 -3.13114 1 0 1 1 0 0 +EDGE2 1899 1679 -0.0288531 -0.0241599 0.0162991 1 0 1 1 0 0 +EDGE2 1899 1879 -0.119664 0.0527786 0.0264284 1 0 1 1 0 0 +EDGE2 1899 1479 -0.0691726 -0.0792941 -0.00121704 1 0 1 1 0 0 +EDGE2 1899 1880 1.0501 -0.0120866 -0.000994483 1 0 1 1 0 0 +EDGE2 1899 1500 0.990793 -0.0179662 -3.10301 1 0 1 1 0 0 +EDGE2 1899 1680 0.961937 0.0976311 -0.0234612 1 0 1 1 0 0 +EDGE2 1899 1480 1.0441 0.0499696 0.00859077 1 0 1 1 0 0 +EDGE2 1899 1340 1.00036 -0.0136038 -3.1228 1 0 1 1 0 0 +EDGE2 1900 1360 0.0450834 -0.0210247 -3.11074 1 0 1 1 0 0 +EDGE2 1900 1679 -1.03806 -0.0278741 -0.0247182 1 0 1 1 0 0 +EDGE2 1900 1879 -1.00316 0.0230734 0.0328218 1 0 1 1 0 0 +EDGE2 1900 1899 -0.999046 0.049923 -0.0159153 1 0 1 1 0 0 +EDGE2 1900 1479 -1.09179 -0.0680921 0.0250442 1 0 1 1 0 0 +EDGE2 1900 1681 -0.00109868 0.91809 1.56426 1 0 1 1 0 0 +EDGE2 1900 1881 0.0392943 0.998165 1.56536 1 0 1 1 0 0 +EDGE2 1900 1880 0.0448499 0.0175378 -0.0186165 1 0 1 1 0 0 +EDGE2 1900 1500 -0.00323031 -0.144646 -3.14951 1 0 1 1 0 0 +EDGE2 1900 1680 -0.0136024 0.0377204 0.0194533 1 0 1 1 0 0 +EDGE2 1900 1480 -0.010213 -0.0681116 0.00422122 1 0 1 1 0 0 +EDGE2 1900 1481 -0.0590108 -0.983565 -1.56026 1 0 1 1 0 0 +EDGE2 1900 1340 -0.0631401 -0.00239222 -3.15941 1 0 1 1 0 0 +EDGE2 1900 1501 -0.0175421 -1.00432 -1.5756 1 0 1 1 0 0 +EDGE2 1900 1341 -0.0513126 -0.947812 -1.56244 1 0 1 1 0 0 +EDGE2 1900 1361 -0.0623401 -0.971206 -1.55722 1 0 1 1 0 0 +EDGE2 1900 1359 0.926392 0.0320424 -3.15011 1 0 1 1 0 0 +EDGE2 1900 1499 1.1512 -0.0682526 -3.15104 1 0 1 1 0 0 +EDGE2 1900 1339 0.93489 -0.000215138 -3.13707 1 0 1 1 0 0 +EDGE2 1901 1360 -0.967146 0.0598749 -1.55971 1 0 1 1 0 0 +EDGE2 1901 1880 -1.06546 0.0709813 1.57048 1 0 1 1 0 0 +EDGE2 1901 1900 -1.03896 -0.0293679 1.55397 1 0 1 1 0 0 +EDGE2 1901 1500 -1.00161 0.0299262 -1.53385 1 0 1 1 0 0 +EDGE2 1901 1680 -1.00267 0.0122414 1.54652 1 0 1 1 0 0 +EDGE2 1901 1480 -0.957425 0.0512065 1.56464 1 0 1 1 0 0 +EDGE2 1901 1502 1.02112 0.0510559 0.00097945 1 0 1 1 0 0 +EDGE2 1901 1481 -0.00887439 0.0373893 -0.00560167 1 0 1 1 0 0 +EDGE2 1901 1340 -1.04897 0.0628111 -1.51518 1 0 1 1 0 0 +EDGE2 1901 1501 -0.038652 -0.0854515 0.011932 1 0 1 1 0 0 +EDGE2 1901 1341 -0.0664002 0.0162535 -0.0039314 1 0 1 1 0 0 +EDGE2 1901 1361 0.00973935 0.0662465 -0.0250122 1 0 1 1 0 0 +EDGE2 1901 1342 0.999744 0.110194 0.0135088 1 0 1 1 0 0 +EDGE2 1901 1362 0.977679 0.0417809 0.0248169 1 0 1 1 0 0 +EDGE2 1901 1482 0.961518 -0.0118749 0.00579325 1 0 1 1 0 0 +EDGE2 1902 1502 -0.0066355 -0.000246315 0.015696 1 0 1 1 0 0 +EDGE2 1902 1481 -1.00795 0.0127635 -0.0098817 1 0 1 1 0 0 +EDGE2 1902 1901 -1.00911 0.0583746 -0.0108131 1 0 1 1 0 0 +EDGE2 1902 1501 -0.929995 0.0230291 -0.0202166 1 0 1 1 0 0 +EDGE2 1902 1341 -1.0277 -0.00122539 -0.0289202 1 0 1 1 0 0 +EDGE2 1902 1361 -1.04881 0.00690023 -0.00628218 1 0 1 1 0 0 +EDGE2 1902 1342 0.0557239 -0.00662694 -0.00859158 1 0 1 1 0 0 +EDGE2 1902 1362 0.00344901 -0.0308585 -0.0117801 1 0 1 1 0 0 +EDGE2 1902 1482 -0.101887 0.0307895 0.0317266 1 0 1 1 0 0 +EDGE2 1902 1363 1.05399 -0.0834402 -0.0114662 1 0 1 1 0 0 +EDGE2 1902 1483 1.05349 -0.0556215 0.0249988 1 0 1 1 0 0 +EDGE2 1902 1503 0.960028 -0.00812087 -0.0146683 1 0 1 1 0 0 +EDGE2 1902 1343 1.04651 0.0510764 0.00880554 1 0 1 1 0 0 +EDGE2 1903 1502 -1.07382 -0.118708 0.00658131 1 0 1 1 0 0 +EDGE2 1903 1902 -0.989284 0.00416819 0.00889366 1 0 1 1 0 0 +EDGE2 1903 1342 -1.10234 0.0614746 -0.0283962 1 0 1 1 0 0 +EDGE2 1903 1362 -1.02367 0.010151 -0.0154745 1 0 1 1 0 0 +EDGE2 1903 1482 -0.989223 0.0263308 0.0468187 1 0 1 1 0 0 +EDGE2 1903 1363 -0.0642568 0.0236993 -0.0286546 1 0 1 1 0 0 +EDGE2 1903 1483 -0.0423828 -0.0437762 -0.00287937 1 0 1 1 0 0 +EDGE2 1903 1503 -0.000946849 0.0510719 -0.00884651 1 0 1 1 0 0 +EDGE2 1903 1343 0.0183524 0.0465669 0.0209383 1 0 1 1 0 0 +EDGE2 1903 1344 1.04736 0.0261118 -0.0263076 1 0 1 1 0 0 +EDGE2 1903 1484 0.995822 0.0753266 -0.00175736 1 0 1 1 0 0 +EDGE2 1903 1504 0.974177 -0.0571182 -0.0382808 1 0 1 1 0 0 +EDGE2 1903 1364 1.02266 0.0153154 -0.00132957 1 0 1 1 0 0 +EDGE2 1904 1345 1.01816 0.0190473 -0.0302167 1 0 1 1 0 0 +EDGE2 1904 1903 -1.03247 0.0214679 -0.00518993 1 0 1 1 0 0 +EDGE2 1904 1363 -1.00417 -0.0998988 0.0159507 1 0 1 1 0 0 +EDGE2 1904 1483 -1.03755 0.00322782 0.0154376 1 0 1 1 0 0 +EDGE2 1904 1503 -1.0482 -0.00624673 -0.000305412 1 0 1 1 0 0 +EDGE2 1904 1343 -1.01392 -0.05151 0.0417982 1 0 1 1 0 0 +EDGE2 1904 1344 -0.0669076 -0.021675 0.00111373 1 0 1 1 0 0 +EDGE2 1904 1484 0.0158149 0.0124011 0.00815616 1 0 1 1 0 0 +EDGE2 1904 1504 0.0496327 0.0210003 0.015192 1 0 1 1 0 0 +EDGE2 1904 1364 -0.0620187 -0.04493 0.0455277 1 0 1 1 0 0 +EDGE2 1904 1525 0.983455 -0.0368919 -3.11242 1 0 1 1 0 0 +EDGE2 1904 1645 1.0702 0.0486564 -3.14239 1 0 1 1 0 0 +EDGE2 1904 1485 1.00538 -0.128851 0.0134726 1 0 1 1 0 0 +EDGE2 1904 1505 0.91638 0.03024 -0.00890098 1 0 1 1 0 0 +EDGE2 1904 1365 1.01143 -0.0651241 -0.0140051 1 0 1 1 0 0 +EDGE2 1904 1325 1.04858 -0.053296 -3.16386 1 0 1 1 0 0 +EDGE2 1905 1345 -0.0435084 0.0160142 -0.0215533 1 0 1 1 0 0 +EDGE2 1905 1526 -0.00157542 -0.994755 -1.5661 1 0 1 1 0 0 +EDGE2 1905 1646 0.0401044 -0.982157 -1.57741 1 0 1 1 0 0 +EDGE2 1905 1366 0.0552336 -1.06807 -1.55884 1 0 1 1 0 0 +EDGE2 1905 1506 0.0212679 -0.957962 -1.59934 1 0 1 1 0 0 +EDGE2 1905 1344 -1.05452 0.0489708 -0.00242335 1 0 1 1 0 0 +EDGE2 1905 1484 -0.995521 0.00190796 -0.0106514 1 0 1 1 0 0 +EDGE2 1905 1504 -0.99922 0.0447849 -0.0238246 1 0 1 1 0 0 +EDGE2 1905 1904 -1.00582 -0.0542721 0.000163418 1 0 1 1 0 0 +EDGE2 1905 1364 -0.969034 -0.0718099 -0.0143159 1 0 1 1 0 0 +EDGE2 1905 1525 -0.0394263 0.035819 -3.13546 1 0 1 1 0 0 +EDGE2 1905 1645 -0.0529968 0.0117916 -3.13658 1 0 1 1 0 0 +EDGE2 1905 1485 0.0595015 -0.0058011 0.0299875 1 0 1 1 0 0 +EDGE2 1905 1505 -0.00479177 0.00478304 -0.00388123 1 0 1 1 0 0 +EDGE2 1905 1365 -0.105944 -0.0468497 0.0270065 1 0 1 1 0 0 +EDGE2 1905 1325 -0.0367647 0.0198009 -3.17141 1 0 1 1 0 0 +EDGE2 1905 1524 1.00468 0.0471853 -3.15604 1 0 1 1 0 0 +EDGE2 1905 1644 1.07906 0.0197685 -3.11669 1 0 1 1 0 0 +EDGE2 1905 1324 1.01083 0.0546488 -3.1368 1 0 1 1 0 0 +EDGE2 1905 1486 -0.0216567 1.02142 1.53491 1 0 1 1 0 0 +EDGE2 1905 1326 0.0346338 1.01126 1.56606 1 0 1 1 0 0 +EDGE2 1905 1346 0.0433574 1.10062 1.59456 1 0 1 1 0 0 +EDGE2 1906 1345 -0.907764 -0.00928414 -1.58002 1 0 1 1 0 0 +EDGE2 1906 1525 -0.981652 4.01711e-05 1.55312 1 0 1 1 0 0 +EDGE2 1906 1905 -1.01433 0.0317521 -1.58081 1 0 1 1 0 0 +EDGE2 1906 1645 -0.890409 -0.0569844 1.57312 1 0 1 1 0 0 +EDGE2 1906 1485 -0.948231 0.0293 -1.56081 1 0 1 1 0 0 +EDGE2 1906 1505 -1.07022 -0.0178963 -1.5412 1 0 1 1 0 0 +EDGE2 1906 1365 -0.993842 0.126621 -1.57457 1 0 1 1 0 0 +EDGE2 1906 1325 -0.9917 0.0168113 1.56836 1 0 1 1 0 0 +EDGE2 1906 1327 0.977446 -0.00184213 -0.0130059 1 0 1 1 0 0 +EDGE2 1906 1486 -0.000687588 0.0216665 0.0105288 1 0 1 1 0 0 +EDGE2 1906 1326 -0.00226587 0.0330126 0.0281029 1 0 1 1 0 0 +EDGE2 1906 1346 0.0258922 -0.0234399 0.005047 1 0 1 1 0 0 +EDGE2 1906 1487 1.06574 -0.00480421 -0.0083914 1 0 1 1 0 0 +EDGE2 1906 1347 0.961514 -0.011219 -0.00870564 1 0 1 1 0 0 +EDGE2 1907 1327 0.0371637 -0.0585024 -0.00151287 1 0 1 1 0 0 +EDGE2 1907 1486 -0.982735 0.0157164 -0.0061832 1 0 1 1 0 0 +EDGE2 1907 1906 -0.95283 -0.0213273 -0.00911058 1 0 1 1 0 0 +EDGE2 1907 1326 -1.03115 0.0554891 0.0160261 1 0 1 1 0 0 +EDGE2 1907 1346 -0.999942 -0.051279 -0.0236375 1 0 1 1 0 0 +EDGE2 1907 1487 0.0161606 -0.0782003 -0.0406353 1 0 1 1 0 0 +EDGE2 1907 1347 0.0205633 -0.00807319 -0.0339019 1 0 1 1 0 0 +EDGE2 1907 1348 0.991724 0.0490854 -0.00110807 1 0 1 1 0 0 +EDGE2 1907 1488 0.999021 -0.107186 -0.037307 1 0 1 1 0 0 +EDGE2 1907 1328 1.04008 0.0186324 -0.029547 1 0 1 1 0 0 +EDGE2 1908 1327 -1.01519 -0.0270352 0.00031972 1 0 1 1 0 0 +EDGE2 1908 1487 -1.09108 -0.00925165 -0.00791325 1 0 1 1 0 0 +EDGE2 1908 1907 -1.03859 -0.0931354 0.0337715 1 0 1 1 0 0 +EDGE2 1908 1347 -0.993331 0.0251804 -0.0120795 1 0 1 1 0 0 +EDGE2 1908 1348 -0.0214777 0.0999227 0.00430978 1 0 1 1 0 0 +EDGE2 1908 1488 -0.0740363 -0.0344282 0.0131218 1 0 1 1 0 0 +EDGE2 1908 1328 -0.013644 0.00381439 -0.00387109 1 0 1 1 0 0 +EDGE2 1908 1349 1.07476 -0.0895183 -0.00606147 1 0 1 1 0 0 +EDGE2 1908 1489 0.983781 -0.0657923 -0.0229843 1 0 1 1 0 0 +EDGE2 1908 1329 0.982098 -0.0613466 -0.0106129 1 0 1 1 0 0 +EDGE2 1909 1348 -1.00143 -0.0149413 -0.00510488 1 0 1 1 0 0 +EDGE2 1909 1908 -0.97994 0.0490155 0.0287251 1 0 1 1 0 0 +EDGE2 1909 1488 -1.01079 0.000774653 0.00699173 1 0 1 1 0 0 +EDGE2 1909 1328 -0.943937 0.0165072 -0.0206067 1 0 1 1 0 0 +EDGE2 1909 1349 -0.0640357 0.0289163 0.0131585 1 0 1 1 0 0 +EDGE2 1909 1489 -0.0723411 -0.00781387 -0.0202516 1 0 1 1 0 0 +EDGE2 1909 1329 -0.01846 0.0452349 0.0171447 1 0 1 1 0 0 +EDGE2 1909 1330 0.959768 0.0460434 0.0356619 1 0 1 1 0 0 +EDGE2 1909 1350 1.03144 0.0721021 -0.0136056 1 0 1 1 0 0 +EDGE2 1909 1490 1.04833 0.084968 0.00376496 1 0 1 1 0 0 +EDGE2 1910 1349 -0.945823 -0.0201547 -0.0173787 1 0 1 1 0 0 +EDGE2 1910 1489 -0.918313 0.0319601 0.0267407 1 0 1 1 0 0 +EDGE2 1910 1909 -0.93315 0.0246033 -0.0230003 1 0 1 1 0 0 +EDGE2 1910 1329 -1.07971 0.014625 0.00789946 1 0 1 1 0 0 +EDGE2 1910 1331 0.0566765 1.04697 1.56181 1 0 1 1 0 0 +EDGE2 1910 1351 -0.0516781 0.976657 1.56076 1 0 1 1 0 0 +EDGE2 1910 1491 -0.00871628 0.983276 1.56268 1 0 1 1 0 0 +EDGE2 1910 1330 -0.0726417 -0.0478235 0.0208833 1 0 1 1 0 0 +EDGE2 1910 1350 -0.00736148 0.013896 -0.0171273 1 0 1 1 0 0 +EDGE2 1910 1490 0.0774294 -0.0294022 0.0199397 1 0 1 1 0 0 +EDGE2 1911 1910 -1.06714 0.127387 -1.56633 1 0 1 1 0 0 +EDGE2 1911 1352 0.977803 0.118028 -0.0335632 1 0 1 1 0 0 +EDGE2 1911 1492 0.977149 -0.0557515 0.00739755 1 0 1 1 0 0 +EDGE2 1911 1332 1.0288 -0.0725984 0.0216403 1 0 1 1 0 0 +EDGE2 1911 1331 0.0907532 -0.0297051 0.012502 1 0 1 1 0 0 +EDGE2 1911 1351 0.0955422 0.00816488 -0.0159552 1 0 1 1 0 0 +EDGE2 1911 1491 -0.00657895 0.0129876 -0.0158686 1 0 1 1 0 0 +EDGE2 1911 1330 -0.998533 -0.0508329 -1.56372 1 0 1 1 0 0 +EDGE2 1911 1350 -1.12363 0.0317721 -1.54871 1 0 1 1 0 0 +EDGE2 1911 1490 -0.956459 -0.0951994 -1.59212 1 0 1 1 0 0 +EDGE2 1912 1333 0.931832 -0.0733181 0.0173498 1 0 1 1 0 0 +EDGE2 1912 1493 0.985765 -0.0969316 -0.0229455 1 0 1 1 0 0 +EDGE2 1912 1353 0.994051 -0.0598935 -0.0293146 1 0 1 1 0 0 +EDGE2 1912 1911 -0.991928 0.0341474 0.0227417 1 0 1 1 0 0 +EDGE2 1912 1352 -0.00565234 0.00494957 0.00650486 1 0 1 1 0 0 +EDGE2 1912 1492 0.0442078 -0.0174505 0.0198357 1 0 1 1 0 0 +EDGE2 1912 1332 -0.0245676 0.0203844 -0.0358877 1 0 1 1 0 0 +EDGE2 1912 1331 -1.02917 0.0124311 0.011921 1 0 1 1 0 0 +EDGE2 1912 1351 -0.964883 0.0176451 0.0153456 1 0 1 1 0 0 +EDGE2 1912 1491 -1.05899 -0.0226629 0.0281741 1 0 1 1 0 0 +EDGE2 1913 1333 0.0606389 -0.0543289 0.0295142 1 0 1 1 0 0 +EDGE2 1913 1493 -0.00335043 0.0208121 -0.0189162 1 0 1 1 0 0 +EDGE2 1913 1334 0.950806 -0.0390399 -0.0111364 1 0 1 1 0 0 +EDGE2 1913 1354 0.964897 -0.142315 0.0347054 1 0 1 1 0 0 +EDGE2 1913 1494 0.952245 0.00893093 -0.0192538 1 0 1 1 0 0 +EDGE2 1913 1353 0.042571 0.0429979 -0.0224693 1 0 1 1 0 0 +EDGE2 1913 1352 -0.983761 -0.00722892 -0.0121016 1 0 1 1 0 0 +EDGE2 1913 1492 -0.955963 -0.00936076 0.0118616 1 0 1 1 0 0 +EDGE2 1913 1912 -0.998558 0.0829994 0.000596553 1 0 1 1 0 0 +EDGE2 1913 1332 -0.994568 0.034176 -0.0209693 1 0 1 1 0 0 +EDGE2 1914 1333 -0.976021 -0.0599487 -0.000601515 1 0 1 1 0 0 +EDGE2 1914 1493 -0.997079 0.0342887 0.0044761 1 0 1 1 0 0 +EDGE2 1914 1355 1.0215 0.0772865 0.00958523 1 0 1 1 0 0 +EDGE2 1914 1495 0.971736 -0.0329029 0.0125134 1 0 1 1 0 0 +EDGE2 1914 1335 0.948625 0.0404333 -0.00988333 1 0 1 1 0 0 +EDGE2 1914 1334 -0.0712501 -0.0889091 -0.00883667 1 0 1 1 0 0 +EDGE2 1914 1354 -0.0414203 -0.0763997 -0.0483378 1 0 1 1 0 0 +EDGE2 1914 1494 -0.0486474 0.0491279 -0.0224326 1 0 1 1 0 0 +EDGE2 1914 1913 -1.00975 -0.0708526 -3.01417e-05 1 0 1 1 0 0 +EDGE2 1914 1353 -0.976782 0.0138048 -0.022334 1 0 1 1 0 0 +EDGE2 1915 1336 0.0577545 1.01108 1.57716 1 0 1 1 0 0 +EDGE2 1915 1496 0.045109 1.00492 1.54997 1 0 1 1 0 0 +EDGE2 1915 1356 0.061588 1.0194 1.57461 1 0 1 1 0 0 +EDGE2 1915 1914 -1.02785 -0.0860362 0.0120333 1 0 1 1 0 0 +EDGE2 1915 1355 -0.0424053 0.0132799 -0.00657399 1 0 1 1 0 0 +EDGE2 1915 1495 -0.0309377 -0.049331 0.00168956 1 0 1 1 0 0 +EDGE2 1915 1335 0.030773 0.0578116 -0.00651656 1 0 1 1 0 0 +EDGE2 1915 1334 -0.984301 0.0940648 -0.0168163 1 0 1 1 0 0 +EDGE2 1915 1354 -1.08349 0.0458102 0.0253183 1 0 1 1 0 0 +EDGE2 1915 1494 -1.0254 -0.0591656 -0.04361 1 0 1 1 0 0 +EDGE2 1916 1336 -0.0437854 -0.043152 0.000783226 1 0 1 1 0 0 +EDGE2 1916 1357 0.968522 0.0138541 -0.0117507 1 0 1 1 0 0 +EDGE2 1916 1497 0.979404 0.0571398 -0.000254501 1 0 1 1 0 0 +EDGE2 1916 1337 1.01751 -0.108011 0.00600383 1 0 1 1 0 0 +EDGE2 1916 1496 0.00446813 0.0233023 -0.0354526 1 0 1 1 0 0 +EDGE2 1916 1356 0.0439002 -0.04981 0.0298852 1 0 1 1 0 0 +EDGE2 1916 1355 -0.944836 0.0242928 -1.58502 1 0 1 1 0 0 +EDGE2 1916 1495 -1.01613 -0.0161941 -1.5787 1 0 1 1 0 0 +EDGE2 1916 1915 -0.973228 -0.011092 -1.5546 1 0 1 1 0 0 +EDGE2 1916 1335 -1.05451 0.000634918 -1.59697 1 0 1 1 0 0 +EDGE2 1917 1336 -1.01519 -0.0139128 -0.0122404 1 0 1 1 0 0 +EDGE2 1917 1358 0.979764 0.0545134 -0.00451147 1 0 1 1 0 0 +EDGE2 1917 1498 1.01797 0.043976 0.0248938 1 0 1 1 0 0 +EDGE2 1917 1338 1.01669 -0.0900804 0.0152916 1 0 1 1 0 0 +EDGE2 1917 1357 -0.00676643 0.0352258 -0.0268113 1 0 1 1 0 0 +EDGE2 1917 1497 0.0387675 0.0288929 -0.0290946 1 0 1 1 0 0 +EDGE2 1917 1337 0.0188911 -0.083841 0.00288229 1 0 1 1 0 0 +EDGE2 1917 1496 -1.08789 -0.0390438 0.0185384 1 0 1 1 0 0 +EDGE2 1917 1916 -1.07193 0.0365374 0.00437836 1 0 1 1 0 0 +EDGE2 1917 1356 -1.07274 0.00840235 0.00743897 1 0 1 1 0 0 +EDGE2 1918 1359 1.00335 -0.00784696 0.00572433 1 0 1 1 0 0 +EDGE2 1918 1499 1.04974 -0.0691516 -0.0257793 1 0 1 1 0 0 +EDGE2 1918 1339 0.983887 -0.0329811 0.000691236 1 0 1 1 0 0 +EDGE2 1918 1358 -0.00127223 0.105106 -0.0121302 1 0 1 1 0 0 +EDGE2 1918 1498 0.028976 0.0348489 0.00283682 1 0 1 1 0 0 +EDGE2 1918 1338 0.0167556 0.0914713 0.04954 1 0 1 1 0 0 +EDGE2 1918 1357 -1.00884 0.0122578 -0.0288409 1 0 1 1 0 0 +EDGE2 1918 1497 -1.06191 -0.0164885 -0.00439015 1 0 1 1 0 0 +EDGE2 1918 1917 -0.922776 0.0429535 0.0367332 1 0 1 1 0 0 +EDGE2 1918 1337 -0.947149 -0.0596232 0.00113275 1 0 1 1 0 0 +EDGE2 1919 1360 1.0251 0.000298531 -0.00695356 1 0 1 1 0 0 +EDGE2 1919 1880 1.03919 0.0639893 -3.13778 1 0 1 1 0 0 +EDGE2 1919 1900 1.06863 0.0507684 -3.15105 1 0 1 1 0 0 +EDGE2 1919 1500 0.998729 -0.0115194 -0.00364977 1 0 1 1 0 0 +EDGE2 1919 1680 0.968992 0.0251194 -3.14835 1 0 1 1 0 0 +EDGE2 1919 1480 0.957597 -0.0786979 -3.15853 1 0 1 1 0 0 +EDGE2 1919 1340 1.02076 -0.0263488 0.00543907 1 0 1 1 0 0 +EDGE2 1919 1359 -0.00283972 -0.0566118 2.05473e-05 1 0 1 1 0 0 +EDGE2 1919 1499 -0.0284414 -0.0362667 -0.00701144 1 0 1 1 0 0 +EDGE2 1919 1339 -0.0186725 -0.0675883 0.02824 1 0 1 1 0 0 +EDGE2 1919 1358 -1.10436 -0.0240285 0.0143308 1 0 1 1 0 0 +EDGE2 1919 1498 -0.989168 0.0308876 -0.0223436 1 0 1 1 0 0 +EDGE2 1919 1918 -0.961076 0.00920183 -0.00655415 1 0 1 1 0 0 +EDGE2 1919 1338 -0.978904 0.10946 -0.0185478 1 0 1 1 0 0 +EDGE2 1920 1360 -0.0613266 0.000643278 -0.00327164 1 0 1 1 0 0 +EDGE2 1920 1679 0.989564 0.0010716 -3.14924 1 0 1 1 0 0 +EDGE2 1920 1879 1.02614 0.0489042 -3.14796 1 0 1 1 0 0 +EDGE2 1920 1899 1.00436 -0.0153875 -3.16858 1 0 1 1 0 0 +EDGE2 1920 1479 0.999878 -0.0178885 -3.13176 1 0 1 1 0 0 +EDGE2 1920 1681 -0.0621641 -0.980859 -1.55799 1 0 1 1 0 0 +EDGE2 1920 1881 0.0180241 -1.04068 -1.58496 1 0 1 1 0 0 +EDGE2 1920 1880 0.0126195 0.0325452 -3.14674 1 0 1 1 0 0 +EDGE2 1920 1900 0.0369557 0.0345905 -3.10934 1 0 1 1 0 0 +EDGE2 1920 1500 -0.00859568 -0.0817584 -0.00079599 1 0 1 1 0 0 +EDGE2 1920 1680 0.0481086 0.0171 -3.16837 1 0 1 1 0 0 +EDGE2 1920 1480 0.103174 -0.0905274 -3.13281 1 0 1 1 0 0 +EDGE2 1920 1481 0.0232888 0.962639 1.57988 1 0 1 1 0 0 +EDGE2 1920 1901 -0.0206851 0.953671 1.56254 1 0 1 1 0 0 +EDGE2 1920 1340 -0.0590092 -0.0427801 0.00065928 1 0 1 1 0 0 +EDGE2 1920 1501 0.0122652 1.08353 1.5879 1 0 1 1 0 0 +EDGE2 1920 1341 0.137693 1.0934 1.54812 1 0 1 1 0 0 +EDGE2 1920 1361 0.00861972 0.93736 1.56913 1 0 1 1 0 0 +EDGE2 1920 1359 -1.06393 0.0324429 -0.0109339 1 0 1 1 0 0 +EDGE2 1920 1499 -0.995283 0.0184281 -0.00881957 1 0 1 1 0 0 +EDGE2 1920 1919 -0.953832 0.0550287 -0.00390318 1 0 1 1 0 0 +EDGE2 1920 1339 -0.983896 -0.0212069 -0.0114655 1 0 1 1 0 0 +EDGE2 1921 1360 -0.944673 0.00326866 -1.57341 1 0 1 1 0 0 +EDGE2 1921 1880 -1.06789 -0.0530023 1.57779 1 0 1 1 0 0 +EDGE2 1921 1920 -1.0448 -0.0248486 -1.57104 1 0 1 1 0 0 +EDGE2 1921 1900 -0.97041 0.0094995 1.57816 1 0 1 1 0 0 +EDGE2 1921 1500 -1.02298 0.00116022 -1.59026 1 0 1 1 0 0 +EDGE2 1921 1680 -1.06942 -0.0328709 1.57143 1 0 1 1 0 0 +EDGE2 1921 1480 -0.945856 -0.0021635 1.59449 1 0 1 1 0 0 +EDGE2 1921 1502 1.00871 -0.00588035 0.0347317 1 0 1 1 0 0 +EDGE2 1921 1481 -0.0323927 0.0551046 0.0253285 1 0 1 1 0 0 +EDGE2 1921 1901 -0.101486 0.0495563 0.00495831 1 0 1 1 0 0 +EDGE2 1921 1340 -1.07468 -0.0462988 -1.57833 1 0 1 1 0 0 +EDGE2 1921 1501 -0.00929866 0.0158611 0.0125594 1 0 1 1 0 0 +EDGE2 1921 1341 0.0374267 0.0452721 -0.00685207 1 0 1 1 0 0 +EDGE2 1921 1361 -0.0977258 -0.00820433 0.033922 1 0 1 1 0 0 +EDGE2 1921 1902 1.02242 -0.0202983 0.00218177 1 0 1 1 0 0 +EDGE2 1921 1342 0.9394 -0.0109797 -0.0313308 1 0 1 1 0 0 +EDGE2 1921 1362 1.02489 0.0480309 0.00472705 1 0 1 1 0 0 +EDGE2 1921 1482 1.04872 -0.0454935 0.0123623 1 0 1 1 0 0 +EDGE2 1922 1502 -0.0126479 -0.0415579 0.00351958 1 0 1 1 0 0 +EDGE2 1922 1481 -1.02582 0.0295552 -0.0134238 1 0 1 1 0 0 +EDGE2 1922 1901 -0.994026 0.0549693 0.00907988 1 0 1 1 0 0 +EDGE2 1922 1921 -1.03108 -0.0069971 0.00521013 1 0 1 1 0 0 +EDGE2 1922 1501 -1.01479 0.012016 0.0360223 1 0 1 1 0 0 +EDGE2 1922 1341 -1.02524 0.0751513 -0.0232293 1 0 1 1 0 0 +EDGE2 1922 1361 -1.002 0.0256568 0.0317156 1 0 1 1 0 0 +EDGE2 1922 1902 -0.0563773 0.0111879 0.0212718 1 0 1 1 0 0 +EDGE2 1922 1903 0.959043 -0.0580862 -0.00563584 1 0 1 1 0 0 +EDGE2 1922 1342 0.0566429 -0.0199478 0.0140852 1 0 1 1 0 0 +EDGE2 1922 1362 0.0694748 -0.0346404 -0.0213263 1 0 1 1 0 0 +EDGE2 1922 1482 -0.0663108 0.014695 0.0295498 1 0 1 1 0 0 +EDGE2 1922 1363 0.986255 -0.00268518 -0.0198081 1 0 1 1 0 0 +EDGE2 1922 1483 0.947245 0.0804325 0.013132 1 0 1 1 0 0 +EDGE2 1922 1503 1.05569 -0.0439387 0.0239189 1 0 1 1 0 0 +EDGE2 1922 1343 1.04178 -0.0369059 0.000753125 1 0 1 1 0 0 +EDGE2 1923 1502 -0.942774 0.0265573 0.014858 1 0 1 1 0 0 +EDGE2 1923 1922 -0.97784 0.0535285 0.0369206 1 0 1 1 0 0 +EDGE2 1923 1902 -1.05157 -0.0446256 -0.0247212 1 0 1 1 0 0 +EDGE2 1923 1903 -0.0515634 -0.0352521 0.0127026 1 0 1 1 0 0 +EDGE2 1923 1342 -0.986882 -0.0198084 0.00356175 1 0 1 1 0 0 +EDGE2 1923 1362 -1.01602 -0.0463349 0.00460559 1 0 1 1 0 0 +EDGE2 1923 1482 -1.02401 0.0509595 -0.00689174 1 0 1 1 0 0 +EDGE2 1923 1363 -0.000428817 0.0134689 -0.00216034 1 0 1 1 0 0 +EDGE2 1923 1483 -0.0326522 0.102898 -0.0150769 1 0 1 1 0 0 +EDGE2 1923 1503 -0.00148042 -0.00335235 -0.00704298 1 0 1 1 0 0 +EDGE2 1923 1343 0.0168073 -0.0170633 -0.0364767 1 0 1 1 0 0 +EDGE2 1923 1344 0.941326 -0.0876719 -0.0263885 1 0 1 1 0 0 +EDGE2 1923 1484 0.966547 0.0675115 0.0208625 1 0 1 1 0 0 +EDGE2 1923 1504 0.977803 0.0496312 0.0144426 1 0 1 1 0 0 +EDGE2 1923 1904 1.04741 -0.0304399 0.00212736 1 0 1 1 0 0 +EDGE2 1923 1364 1.03749 -0.0674306 0.0025357 1 0 1 1 0 0 +EDGE2 1924 1345 1.02499 0.0913708 0.024124 1 0 1 1 0 0 +EDGE2 1924 1903 -0.961285 -0.00713156 -0.0462119 1 0 1 1 0 0 +EDGE2 1924 1923 -1.00823 -0.0663444 -0.0146487 1 0 1 1 0 0 +EDGE2 1924 1363 -0.979154 -0.0111048 -0.0216112 1 0 1 1 0 0 +EDGE2 1924 1483 -1.0023 0.0316609 0.00744754 1 0 1 1 0 0 +EDGE2 1924 1503 -1.06498 0.0795478 0.0173792 1 0 1 1 0 0 +EDGE2 1924 1343 -0.934273 0.0127517 -0.0202089 1 0 1 1 0 0 +EDGE2 1924 1344 0.0479136 0.0159307 0.00831286 1 0 1 1 0 0 +EDGE2 1924 1484 -0.0708825 -0.0125296 0.0142826 1 0 1 1 0 0 +EDGE2 1924 1504 0.041128 -0.0120209 -0.0242446 1 0 1 1 0 0 +EDGE2 1924 1904 0.0927567 -0.00594958 0.00858608 1 0 1 1 0 0 +EDGE2 1924 1364 0.00731296 0.112036 0.0204088 1 0 1 1 0 0 +EDGE2 1924 1525 1.04269 0.0397186 -3.11705 1 0 1 1 0 0 +EDGE2 1924 1905 0.88703 -0.0899499 0.0163723 1 0 1 1 0 0 +EDGE2 1924 1645 0.994546 0.00696027 -3.14971 1 0 1 1 0 0 +EDGE2 1924 1485 0.981254 -0.0463748 0.0072504 1 0 1 1 0 0 +EDGE2 1924 1505 0.925258 0.0498853 -0.00336086 1 0 1 1 0 0 +EDGE2 1924 1365 0.928863 0.0233349 0.00193224 1 0 1 1 0 0 +EDGE2 1924 1325 0.995603 0.00914253 -3.1341 1 0 1 1 0 0 +EDGE2 1925 1345 0.0326526 0.0441939 0.0197377 1 0 1 1 0 0 +EDGE2 1925 1526 0.050018 -1.09132 -1.5801 1 0 1 1 0 0 +EDGE2 1925 1646 0.00188437 -0.925716 -1.58052 1 0 1 1 0 0 +EDGE2 1925 1366 -0.00655033 -0.973036 -1.58969 1 0 1 1 0 0 +EDGE2 1925 1506 -0.0171501 -1.01624 -1.56669 1 0 1 1 0 0 +EDGE2 1925 1924 -1.04873 -0.0406532 0.0231565 1 0 1 1 0 0 +EDGE2 1925 1344 -0.939519 -0.000819951 -0.0124833 1 0 1 1 0 0 +EDGE2 1925 1484 -1.01596 -0.0704059 0.000206336 1 0 1 1 0 0 +EDGE2 1925 1504 -0.921028 0.0286292 0.0220964 1 0 1 1 0 0 +EDGE2 1925 1904 -1.05044 0.035268 0.0146573 1 0 1 1 0 0 +EDGE2 1925 1364 -1.09112 0.0362413 -0.0213048 1 0 1 1 0 0 +EDGE2 1925 1525 -0.0746072 -0.0769178 -3.12804 1 0 1 1 0 0 +EDGE2 1925 1905 0.00808193 -0.0327699 0.00218092 1 0 1 1 0 0 +EDGE2 1925 1645 0.00784978 -0.0240662 -3.12916 1 0 1 1 0 0 +EDGE2 1925 1485 0.0883881 -0.0331715 0.0187473 1 0 1 1 0 0 +EDGE2 1925 1505 -0.101371 0.0543886 -0.00931636 1 0 1 1 0 0 +EDGE2 1925 1365 0.0231411 -0.0291304 0.0191285 1 0 1 1 0 0 +EDGE2 1925 1325 0.0632302 -0.0647082 -3.14489 1 0 1 1 0 0 +EDGE2 1925 1524 1.03742 -0.0036676 -3.15437 1 0 1 1 0 0 +EDGE2 1925 1644 1.02195 -0.111937 -3.13973 1 0 1 1 0 0 +EDGE2 1925 1324 0.930818 0.015278 -3.15928 1 0 1 1 0 0 +EDGE2 1925 1486 0.0479892 1.03951 1.55823 1 0 1 1 0 0 +EDGE2 1925 1906 0.0962932 0.999711 1.598 1 0 1 1 0 0 +EDGE2 1925 1326 0.0216972 1.0644 1.56615 1 0 1 1 0 0 +EDGE2 1925 1346 0.00186423 0.908698 1.59737 1 0 1 1 0 0 +EDGE2 1926 1345 -0.946023 -0.00889775 1.55853 1 0 1 1 0 0 +EDGE2 1926 1526 0.0408744 0.0533576 -0.00516767 1 0 1 1 0 0 +EDGE2 1926 1507 1.03979 -0.00757356 0.0361578 1 0 1 1 0 0 +EDGE2 1926 1527 0.969525 -0.0253599 0.0063938 1 0 1 1 0 0 +EDGE2 1926 1647 1.05649 0.0912232 0.001141 1 0 1 1 0 0 +EDGE2 1926 1367 0.993554 -0.00732757 0.020302 1 0 1 1 0 0 +EDGE2 1926 1646 -0.0221794 -0.00820338 0.0127201 1 0 1 1 0 0 +EDGE2 1926 1366 0.0563478 0.0806374 -0.00116458 1 0 1 1 0 0 +EDGE2 1926 1506 -0.0201741 -0.071916 -0.0266853 1 0 1 1 0 0 +EDGE2 1926 1525 -1.00512 0.000783238 -1.56324 1 0 1 1 0 0 +EDGE2 1926 1905 -1.0474 -0.0469627 1.55661 1 0 1 1 0 0 +EDGE2 1926 1925 -1.03516 0.0162233 1.57937 1 0 1 1 0 0 +EDGE2 1926 1645 -0.982266 0.0316559 -1.54752 1 0 1 1 0 0 +EDGE2 1926 1485 -1.0502 -0.00804113 1.57054 1 0 1 1 0 0 +EDGE2 1926 1505 -1.10973 0.0393432 1.59489 1 0 1 1 0 0 +EDGE2 1926 1365 -1.04683 -0.0131508 1.60852 1 0 1 1 0 0 +EDGE2 1926 1325 -0.960531 -0.0214905 -1.60925 1 0 1 1 0 0 +EDGE2 1927 1648 0.933731 -0.115913 -0.00350672 1 0 1 1 0 0 +EDGE2 1927 1368 0.981671 0.0701361 0.00680852 1 0 1 1 0 0 +EDGE2 1927 1508 1.03955 -0.0107658 -0.00107903 1 0 1 1 0 0 +EDGE2 1927 1528 1.03518 0.00876097 -0.00235397 1 0 1 1 0 0 +EDGE2 1927 1526 -1.04918 -0.0274085 -0.0166483 1 0 1 1 0 0 +EDGE2 1927 1507 0.0149452 0.0915524 -0.0447211 1 0 1 1 0 0 +EDGE2 1927 1527 0.0398536 -0.000940338 -0.00592045 1 0 1 1 0 0 +EDGE2 1927 1647 0.0693633 0.0275918 -0.0392715 1 0 1 1 0 0 +EDGE2 1927 1367 0.0471152 0.0105449 0.00829287 1 0 1 1 0 0 +EDGE2 1927 1926 -0.936487 -0.0180098 -0.00895083 1 0 1 1 0 0 +EDGE2 1927 1646 -1.10923 0.0700709 0.0419977 1 0 1 1 0 0 +EDGE2 1927 1366 -1.02572 -0.00134996 -0.0125451 1 0 1 1 0 0 +EDGE2 1927 1506 -1.02771 -0.0147067 -0.015888 1 0 1 1 0 0 +EDGE2 1928 1509 0.984241 -0.0313617 0.00251376 1 0 1 1 0 0 +EDGE2 1928 1649 0.909234 0.12653 0.00215458 1 0 1 1 0 0 +EDGE2 1928 1529 1.04818 -0.0652808 -0.00384624 1 0 1 1 0 0 +EDGE2 1928 1369 0.935847 0.0175466 0.0317745 1 0 1 1 0 0 +EDGE2 1928 1648 0.0142586 0.0301668 0.0424222 1 0 1 1 0 0 +EDGE2 1928 1368 -0.031812 -0.0466325 0.0496814 1 0 1 1 0 0 +EDGE2 1928 1508 -0.0454259 -0.0132046 0.0133768 1 0 1 1 0 0 +EDGE2 1928 1528 -0.000614644 0.010382 0.0237269 1 0 1 1 0 0 +EDGE2 1928 1507 -1.0129 -0.0483348 -0.0171306 1 0 1 1 0 0 +EDGE2 1928 1527 -1.0421 0.0509869 0.00266875 1 0 1 1 0 0 +EDGE2 1928 1647 -1.06577 -0.000331678 -0.0190397 1 0 1 1 0 0 +EDGE2 1928 1927 -0.99986 0.141486 0.00346934 1 0 1 1 0 0 +EDGE2 1928 1367 -1.02192 -0.0248335 -0.0238515 1 0 1 1 0 0 +EDGE2 1929 1650 1.035 0.00552517 -0.00367858 1 0 1 1 0 0 +EDGE2 1929 1710 0.986524 -0.0563593 -3.15767 1 0 1 1 0 0 +EDGE2 1929 1870 0.982325 -0.0157898 -3.14987 1 0 1 1 0 0 +EDGE2 1929 1670 1.12961 0.0122504 -3.12631 1 0 1 1 0 0 +EDGE2 1929 1470 0.981267 0.0453936 -3.10595 1 0 1 1 0 0 +EDGE2 1929 1510 1.03099 -3.67613e-06 0.00226581 1 0 1 1 0 0 +EDGE2 1929 1530 1.09429 -0.0481022 -0.0339342 1 0 1 1 0 0 +EDGE2 1929 1370 0.915433 -0.0421856 0.00382214 1 0 1 1 0 0 +EDGE2 1929 1509 -0.00798813 -0.0159478 0.00697559 1 0 1 1 0 0 +EDGE2 1929 1649 0.0233463 0.00396669 0.0177237 1 0 1 1 0 0 +EDGE2 1929 1529 -0.0702881 0.00273256 0.0509124 1 0 1 1 0 0 +EDGE2 1929 1369 -0.0232394 -0.0472523 0.0325185 1 0 1 1 0 0 +EDGE2 1929 1648 -1.04786 0.0523444 0.0345407 1 0 1 1 0 0 +EDGE2 1929 1928 -0.980475 0.0718548 -0.0345145 1 0 1 1 0 0 +EDGE2 1929 1368 -1.04349 0.000440483 0.0103178 1 0 1 1 0 0 +EDGE2 1929 1508 -0.92013 0.0566838 0.0042127 1 0 1 1 0 0 +EDGE2 1929 1528 -1.02711 0.0617186 -0.00139552 1 0 1 1 0 0 +EDGE2 1930 1669 0.992208 0.101793 -3.1262 1 0 1 1 0 0 +EDGE2 1930 1709 1.01752 0.0242608 -3.13054 1 0 1 1 0 0 +EDGE2 1930 1869 1.00505 0.0228497 -3.14726 1 0 1 1 0 0 +EDGE2 1930 1469 1.00587 -0.0942514 -3.13441 1 0 1 1 0 0 +EDGE2 1930 1671 0.0371668 -1.08918 -1.57361 1 0 1 1 0 0 +EDGE2 1930 1711 0.039076 -0.973308 -1.56802 1 0 1 1 0 0 +EDGE2 1930 1871 -0.0121484 -0.852154 -1.58939 1 0 1 1 0 0 +EDGE2 1930 1471 0.0109775 -1.02089 -1.56046 1 0 1 1 0 0 +EDGE2 1930 1650 -0.0694669 -0.0118536 0.0236796 1 0 1 1 0 0 +EDGE2 1930 1710 0.00334032 -0.0875787 -3.1329 1 0 1 1 0 0 +EDGE2 1930 1870 0.0489006 0.0129886 -3.15228 1 0 1 1 0 0 +EDGE2 1930 1670 0.00640147 0.113393 -3.13018 1 0 1 1 0 0 +EDGE2 1930 1470 0.0731746 -0.00974561 -3.14225 1 0 1 1 0 0 +EDGE2 1930 1510 -0.0254346 -0.00512014 -0.00610561 1 0 1 1 0 0 +EDGE2 1930 1530 -0.0661993 0.0134298 -0.0201893 1 0 1 1 0 0 +EDGE2 1930 1370 0.0073481 -0.0249184 0.0240037 1 0 1 1 0 0 +EDGE2 1930 1371 -0.0986071 1.01418 1.58027 1 0 1 1 0 0 +EDGE2 1930 1531 0.0258226 0.981698 1.59234 1 0 1 1 0 0 +EDGE2 1930 1651 0.0305577 0.950806 1.6015 1 0 1 1 0 0 +EDGE2 1930 1511 0.0263469 0.990409 1.55188 1 0 1 1 0 0 +EDGE2 1930 1509 -1.04051 -0.0555789 -0.0213137 1 0 1 1 0 0 +EDGE2 1930 1649 -1.05262 0.0289954 -0.00125596 1 0 1 1 0 0 +EDGE2 1930 1929 -1.04199 -0.0538462 -0.0182036 1 0 1 1 0 0 +EDGE2 1930 1529 -1.03861 0.0419143 0.0111443 1 0 1 1 0 0 +EDGE2 1930 1369 -0.91365 -0.0551283 0.011519 1 0 1 1 0 0 +EDGE2 1931 1872 1.04746 -0.00653092 0.0437383 1 0 1 1 0 0 +EDGE2 1931 1672 0.934309 -0.0178322 0.0255706 1 0 1 1 0 0 +EDGE2 1931 1712 0.953154 -0.0518308 0.00128186 1 0 1 1 0 0 +EDGE2 1931 1472 1.01587 -0.127458 -0.0162898 1 0 1 1 0 0 +EDGE2 1931 1671 -0.0260868 -0.0429042 0.0188764 1 0 1 1 0 0 +EDGE2 1931 1711 -0.110892 0.0412966 -0.00552373 1 0 1 1 0 0 +EDGE2 1931 1871 0.0156599 -0.0372949 -0.000689601 1 0 1 1 0 0 +EDGE2 1931 1471 -0.0586721 0.0410617 -0.012478 1 0 1 1 0 0 +EDGE2 1931 1650 -0.958774 0.055045 1.56441 1 0 1 1 0 0 +EDGE2 1931 1710 -0.931106 0.0626128 -1.55378 1 0 1 1 0 0 +EDGE2 1931 1870 -0.912305 -0.0418819 -1.58984 1 0 1 1 0 0 +EDGE2 1931 1930 -0.970215 -0.0464159 1.56517 1 0 1 1 0 0 +EDGE2 1931 1670 -1.03502 -0.0031821 -1.56117 1 0 1 1 0 0 +EDGE2 1931 1470 -1.02313 -0.0362519 -1.55718 1 0 1 1 0 0 +EDGE2 1931 1510 -0.999106 0.0256453 1.57218 1 0 1 1 0 0 +EDGE2 1931 1530 -1.0135 0.0343861 1.5778 1 0 1 1 0 0 +EDGE2 1931 1370 -0.962713 -0.0356623 1.57378 1 0 1 1 0 0 +EDGE2 1932 1931 -0.912905 -0.0741969 0.0184383 1 0 1 1 0 0 +EDGE2 1932 1873 0.953148 0.0400551 -0.0105957 1 0 1 1 0 0 +EDGE2 1932 1872 -0.0500024 0.0359666 -0.0315131 1 0 1 1 0 0 +EDGE2 1932 1473 0.983568 -0.0204425 0.0162382 1 0 1 1 0 0 +EDGE2 1932 1673 0.917149 -0.0413293 -0.00850215 1 0 1 1 0 0 +EDGE2 1932 1713 1.03839 0.0533624 0.009614 1 0 1 1 0 0 +EDGE2 1932 1672 0.032106 0.00110091 0.00324305 1 0 1 1 0 0 +EDGE2 1932 1712 -0.00872175 0.0503224 -0.0223919 1 0 1 1 0 0 +EDGE2 1932 1472 0.0860583 0.00206293 0.0250278 1 0 1 1 0 0 +EDGE2 1932 1671 -0.944415 0.00176693 -0.0324026 1 0 1 1 0 0 +EDGE2 1932 1711 -0.982815 -0.0304583 0.0221234 1 0 1 1 0 0 +EDGE2 1932 1871 -1.00768 0.0734698 -0.0312126 1 0 1 1 0 0 +EDGE2 1932 1471 -1.09083 -0.0294396 -0.037372 1 0 1 1 0 0 +EDGE2 1933 1873 -0.0705527 -0.0220601 -0.0277464 1 0 1 1 0 0 +EDGE2 1933 1874 1.01673 0.0664542 -0.024889 1 0 1 1 0 0 +EDGE2 1933 1474 1.1018 0.102789 0.0201816 1 0 1 1 0 0 +EDGE2 1933 1674 1.02279 0.0283712 0.0029263 1 0 1 1 0 0 +EDGE2 1933 1714 1.07429 -0.0155718 -0.0248046 1 0 1 1 0 0 +EDGE2 1933 1872 -1.01143 -0.00961289 0.0122478 1 0 1 1 0 0 +EDGE2 1933 1473 -0.00951103 -0.0047307 -0.0136639 1 0 1 1 0 0 +EDGE2 1933 1673 -0.0561011 -0.00320525 -0.00789272 1 0 1 1 0 0 +EDGE2 1933 1713 -0.0192388 0.0448963 0.00820746 1 0 1 1 0 0 +EDGE2 1933 1932 -0.990881 0.00171628 0.00146682 1 0 1 1 0 0 +EDGE2 1933 1672 -0.999862 -0.0532867 0.0354498 1 0 1 1 0 0 +EDGE2 1933 1712 -0.938587 0.0178127 0.0338959 1 0 1 1 0 0 +EDGE2 1933 1472 -1.06872 0.117652 0.0275472 1 0 1 1 0 0 +EDGE2 1934 1715 1.08122 -0.0304904 -0.0394568 1 0 1 1 0 0 +EDGE2 1934 1895 0.990511 0.0633266 -3.14203 1 0 1 1 0 0 +EDGE2 1934 1875 0.984554 0.0110221 -0.00293273 1 0 1 1 0 0 +EDGE2 1934 1873 -0.953388 0.0477524 -0.00383329 1 0 1 1 0 0 +EDGE2 1934 1874 0.0559124 0.0117542 -0.0344552 1 0 1 1 0 0 +EDGE2 1934 1475 1.0238 0.155461 -0.029924 1 0 1 1 0 0 +EDGE2 1934 1675 0.947324 -0.00852081 -0.0150878 1 0 1 1 0 0 +EDGE2 1934 1695 1.10042 -0.0814414 -3.12801 1 0 1 1 0 0 +EDGE2 1934 1474 0.0148178 -0.110744 0.0282529 1 0 1 1 0 0 +EDGE2 1934 1674 -0.0429776 -0.0119989 0.0208425 1 0 1 1 0 0 +EDGE2 1934 1714 0.107079 -0.0557314 0.0111421 1 0 1 1 0 0 +EDGE2 1934 1933 -0.940417 -0.00404717 0.00727145 1 0 1 1 0 0 +EDGE2 1934 1473 -1.09454 0.0256614 0.00492747 1 0 1 1 0 0 +EDGE2 1934 1673 -1.00033 -0.0365396 -0.0280731 1 0 1 1 0 0 +EDGE2 1934 1713 -1.0199 -0.0360094 0.0128371 1 0 1 1 0 0 +EDGE2 1935 1715 0.0206601 -0.0146246 -0.0444208 1 0 1 1 0 0 +EDGE2 1935 1694 1.02723 0.0350161 -3.12466 1 0 1 1 0 0 +EDGE2 1935 1894 1.03663 0.00948197 -3.15303 1 0 1 1 0 0 +EDGE2 1935 1716 -0.00747953 1.00336 1.56145 1 0 1 1 0 0 +EDGE2 1935 1895 -0.0311425 -0.0430011 -3.10469 1 0 1 1 0 0 +EDGE2 1935 1696 0.0435838 0.978316 1.53406 1 0 1 1 0 0 +EDGE2 1935 1875 -0.0716446 -0.0193538 0.012288 1 0 1 1 0 0 +EDGE2 1935 1874 -0.982332 -0.0771142 -0.0138233 1 0 1 1 0 0 +EDGE2 1935 1475 0.100887 0.0423166 0.0261313 1 0 1 1 0 0 +EDGE2 1935 1675 -0.0420122 -0.0365289 -0.00853737 1 0 1 1 0 0 +EDGE2 1935 1695 0.106353 0.0555404 -3.12033 1 0 1 1 0 0 +EDGE2 1935 1934 -0.982869 -0.0773053 0.00987587 1 0 1 1 0 0 +EDGE2 1935 1474 -0.981825 0.0416583 0.0215274 1 0 1 1 0 0 +EDGE2 1935 1674 -1.03332 0.0999827 0.0167462 1 0 1 1 0 0 +EDGE2 1935 1714 -1.01686 -0.0227035 0.00112562 1 0 1 1 0 0 +EDGE2 1935 1676 -0.0539864 -1.06051 -1.59802 1 0 1 1 0 0 +EDGE2 1935 1876 -0.0409053 -0.90539 -1.55609 1 0 1 1 0 0 +EDGE2 1935 1896 0.066823 -1.08034 -1.56265 1 0 1 1 0 0 +EDGE2 1935 1476 -0.0312984 -1.04219 -1.60459 1 0 1 1 0 0 +EDGE2 1936 1697 1.05978 0.0265078 -0.0145038 1 0 1 1 0 0 +EDGE2 1936 1717 1.04741 -0.0679905 0.00251439 1 0 1 1 0 0 +EDGE2 1936 1715 -0.963093 0.0755849 -1.56914 1 0 1 1 0 0 +EDGE2 1936 1716 -0.0396706 0.0487279 0.00715935 1 0 1 1 0 0 +EDGE2 1936 1895 -1.02401 -0.0204004 1.57103 1 0 1 1 0 0 +EDGE2 1936 1935 -1.02082 -0.0471691 -1.5686 1 0 1 1 0 0 +EDGE2 1936 1696 -0.00215785 0.0112091 0.0250213 1 0 1 1 0 0 +EDGE2 1936 1875 -1.02918 0.00868284 -1.5533 1 0 1 1 0 0 +EDGE2 1936 1475 -1.02202 -0.0522315 -1.58473 1 0 1 1 0 0 +EDGE2 1936 1675 -1.02729 0.0550184 -1.58422 1 0 1 1 0 0 +EDGE2 1936 1695 -0.943835 -0.0356032 1.57346 1 0 1 1 0 0 +EDGE2 1937 1697 0.0379193 -0.0062103 -0.0117896 1 0 1 1 0 0 +EDGE2 1937 1698 0.964343 0.02413 -0.0196475 1 0 1 1 0 0 +EDGE2 1937 1718 0.962617 0.034807 0.0219559 1 0 1 1 0 0 +EDGE2 1937 1717 -0.00510248 -0.0191322 -0.000328571 1 0 1 1 0 0 +EDGE2 1937 1716 -1.00826 0.00762777 -0.0034826 1 0 1 1 0 0 +EDGE2 1937 1936 -1.04937 0.00248544 -0.0288146 1 0 1 1 0 0 +EDGE2 1937 1696 -0.95813 -0.0301638 0.0084713 1 0 1 1 0 0 +EDGE2 1938 1697 -1.00039 0.00846896 -0.00413268 1 0 1 1 0 0 +EDGE2 1938 1719 0.966791 0.0618737 -0.00385868 1 0 1 1 0 0 +EDGE2 1938 1699 1.05336 0.0215789 0.00563811 1 0 1 1 0 0 +EDGE2 1938 1937 -1.05201 -0.0190692 -0.00175843 1 0 1 1 0 0 +EDGE2 1938 1698 -0.0447003 0.0606133 0.0130288 1 0 1 1 0 0 +EDGE2 1938 1718 0.0500238 -0.0112341 -0.0214177 1 0 1 1 0 0 +EDGE2 1938 1717 -1.00256 0.0537978 0.0153208 1 0 1 1 0 0 +EDGE2 1939 1700 0.979582 0.0259882 -0.0508762 1 0 1 1 0 0 +EDGE2 1939 1720 0.93096 -0.0400002 0.00786158 1 0 1 1 0 0 +EDGE2 1939 1740 0.972545 0.104263 -3.13756 1 0 1 1 0 0 +EDGE2 1939 1460 0.968649 -0.050253 -3.16199 1 0 1 1 0 0 +EDGE2 1939 1938 -1.03022 -0.0153314 0.0221298 1 0 1 1 0 0 +EDGE2 1939 1719 0.0589367 0.044269 0.035121 1 0 1 1 0 0 +EDGE2 1939 1699 0.0971381 0.0245175 0.0463572 1 0 1 1 0 0 +EDGE2 1939 1698 -1.01578 -0.0190258 -0.0581155 1 0 1 1 0 0 +EDGE2 1939 1718 -0.988268 -0.0454941 -0.000120059 1 0 1 1 0 0 +EDGE2 1940 1739 1.03187 0.0208339 -3.12805 1 0 1 1 0 0 +EDGE2 1940 1459 0.914214 -0.0131432 -3.14093 1 0 1 1 0 0 +EDGE2 1940 1701 0.0403988 1.08904 1.57204 1 0 1 1 0 0 +EDGE2 1940 1741 -0.0490469 -0.984587 -1.55392 1 0 1 1 0 0 +EDGE2 1940 1721 0.124352 -1.04108 -1.57582 1 0 1 1 0 0 +EDGE2 1940 1700 0.0116281 0.0993578 -0.0102082 1 0 1 1 0 0 +EDGE2 1940 1720 -0.0245387 -0.0221942 -0.0235424 1 0 1 1 0 0 +EDGE2 1940 1740 0.0492673 0.0722759 -3.17219 1 0 1 1 0 0 +EDGE2 1940 1460 -0.0426789 -0.0507494 -3.13017 1 0 1 1 0 0 +EDGE2 1940 1461 -0.13582 0.955406 1.52179 1 0 1 1 0 0 +EDGE2 1940 1719 -0.940341 -0.00614897 -0.00977855 1 0 1 1 0 0 +EDGE2 1940 1939 -1.06332 -0.00700492 -0.0142188 1 0 1 1 0 0 +EDGE2 1940 1699 -0.977971 0.0570568 0.0463126 1 0 1 1 0 0 +EDGE2 1941 1742 0.9166 0.0455438 -0.00281198 1 0 1 1 0 0 +EDGE2 1941 1940 -0.932483 0.0706479 1.58152 1 0 1 1 0 0 +EDGE2 1941 1741 -0.0177832 -0.0163406 0.00271883 1 0 1 1 0 0 +EDGE2 1941 1722 1.04815 0.0326636 -0.00693261 1 0 1 1 0 0 +EDGE2 1941 1721 0.0178443 -0.00989616 0.030542 1 0 1 1 0 0 +EDGE2 1941 1700 -1.10257 -0.0311705 1.59143 1 0 1 1 0 0 +EDGE2 1941 1720 -1.01559 0.0581611 1.57857 1 0 1 1 0 0 +EDGE2 1941 1740 -0.978107 -0.0632292 -1.54931 1 0 1 1 0 0 +EDGE2 1941 1460 -0.963574 0.0164426 -1.57193 1 0 1 1 0 0 +EDGE2 1942 1742 0.0362251 -0.0162346 -0.0160384 1 0 1 1 0 0 +EDGE2 1942 1723 1.0266 -0.00523751 -0.0308562 1 0 1 1 0 0 +EDGE2 1942 1743 1.00178 -0.0442399 0.0323575 1 0 1 1 0 0 +EDGE2 1942 1741 -1.13368 0.0599982 0.0179641 1 0 1 1 0 0 +EDGE2 1942 1941 -0.950484 0.05123 -0.0187543 1 0 1 1 0 0 +EDGE2 1942 1722 0.109837 0.0962231 -0.00681835 1 0 1 1 0 0 +EDGE2 1942 1721 -0.991135 -0.0428786 0.00333721 1 0 1 1 0 0 +EDGE2 1943 1742 -1.0091 -0.0144612 0.0155337 1 0 1 1 0 0 +EDGE2 1943 1744 1.07834 -0.0525364 0.0201693 1 0 1 1 0 0 +EDGE2 1943 1724 1.05104 0.0101483 0.00011197 1 0 1 1 0 0 +EDGE2 1943 1723 -0.0099691 -0.087424 0.0381181 1 0 1 1 0 0 +EDGE2 1943 1743 0.106004 0.0723469 -0.00581399 1 0 1 1 0 0 +EDGE2 1943 1942 -0.936872 0.047842 0.0124432 1 0 1 1 0 0 +EDGE2 1943 1722 -1.03097 0.111263 0.00187455 1 0 1 1 0 0 +EDGE2 1944 1745 1.05954 0.0532014 0.0475307 1 0 1 1 0 0 +EDGE2 1944 1943 -1.0113 0.0549972 0.0182784 1 0 1 1 0 0 +EDGE2 1944 1744 -0.0259137 0.0196609 0.00589767 1 0 1 1 0 0 +EDGE2 1944 1725 1.00211 -0.0969017 0.0143581 1 0 1 1 0 0 +EDGE2 1944 1724 0.0107431 0.0144517 -0.0603633 1 0 1 1 0 0 +EDGE2 1944 1723 -0.99582 -0.079623 -0.00186937 1 0 1 1 0 0 +EDGE2 1944 1743 -1.0559 -0.0489055 -0.0570636 1 0 1 1 0 0 +EDGE2 1945 1746 0.0328817 0.917474 1.57951 1 0 1 1 0 0 +EDGE2 1945 1726 0.00502576 1.03875 1.58201 1 0 1 1 0 0 +EDGE2 1945 1745 -0.0238766 -0.0466072 0.0155758 1 0 1 1 0 0 +EDGE2 1945 1744 -1.03177 -0.0950939 0.0146745 1 0 1 1 0 0 +EDGE2 1945 1944 -1.08911 -0.0393698 -0.000274343 1 0 1 1 0 0 +EDGE2 1945 1725 0.0329463 0.0205138 0.0255857 1 0 1 1 0 0 +EDGE2 1945 1724 -0.989239 -0.0724414 0.00578542 1 0 1 1 0 0 +EDGE2 1946 1727 1.0669 -0.01524 0.0176557 1 0 1 1 0 0 +EDGE2 1946 1747 0.90362 0.133978 -0.0164479 1 0 1 1 0 0 +EDGE2 1946 1746 -0.00506293 -0.0339215 0.0134331 1 0 1 1 0 0 +EDGE2 1946 1726 0.0128006 0.0253146 0.0231588 1 0 1 1 0 0 +EDGE2 1946 1745 -0.931773 -0.0910893 -1.64313 1 0 1 1 0 0 +EDGE2 1946 1945 -0.960055 -0.100114 -1.55956 1 0 1 1 0 0 +EDGE2 1946 1725 -1.02632 0.0902186 -1.55526 1 0 1 1 0 0 +EDGE2 1947 1727 0.042112 -0.045823 0.00606999 1 0 1 1 0 0 +EDGE2 1947 1728 1.00372 -0.0767748 0.00828399 1 0 1 1 0 0 +EDGE2 1947 1748 0.989853 -0.0507537 0.0111542 1 0 1 1 0 0 +EDGE2 1947 1747 0.0254995 0.0205662 -0.0132315 1 0 1 1 0 0 +EDGE2 1947 1746 -0.921138 0.00548209 0.0245406 1 0 1 1 0 0 +EDGE2 1947 1946 -1.03869 0.0204681 -0.0228178 1 0 1 1 0 0 +EDGE2 1947 1726 -0.946322 0.00390248 -0.0117262 1 0 1 1 0 0 +EDGE2 1948 1749 1.02771 0.0236449 -0.0156386 1 0 1 1 0 0 +EDGE2 1948 1729 1.01239 -0.0155394 -0.00113215 1 0 1 1 0 0 +EDGE2 1948 1727 -0.970799 0.0225408 -0.00876162 1 0 1 1 0 0 +EDGE2 1948 1947 -1.0536 0.0564209 -0.011933 1 0 1 1 0 0 +EDGE2 1948 1728 0.0341724 -0.0465192 -0.00217459 1 0 1 1 0 0 +EDGE2 1948 1748 0.0449377 -0.0240675 -0.00680101 1 0 1 1 0 0 +EDGE2 1948 1747 -1.01795 0.047013 0.0549715 1 0 1 1 0 0 +EDGE2 1949 1948 -1.04201 0.0193283 0.00806039 1 0 1 1 0 0 +EDGE2 1949 1750 0.996837 0.0317135 0.00892525 1 0 1 1 0 0 +EDGE2 1949 1730 1.00664 0.00569943 0.00483779 1 0 1 1 0 0 +EDGE2 1949 1749 -0.0433132 -0.00669647 -0.0312158 1 0 1 1 0 0 +EDGE2 1949 1729 0.062398 0.0163671 -0.00208004 1 0 1 1 0 0 +EDGE2 1949 1728 -1.00679 0.0210522 0.0148563 1 0 1 1 0 0 +EDGE2 1949 1748 -1.03802 -0.0473024 -0.0150728 1 0 1 1 0 0 +EDGE2 1950 1750 -0.00459823 0.0406054 -0.0255372 1 0 1 1 0 0 +EDGE2 1950 1949 -1.00524 0.00857809 -0.0138023 1 0 1 1 0 0 +EDGE2 1950 1730 -0.101284 0.137102 0.0288636 1 0 1 1 0 0 +EDGE2 1950 1731 -0.0686287 1.0647 1.5711 1 0 1 1 0 0 +EDGE2 1950 1751 -0.00266126 0.986564 1.55767 1 0 1 1 0 0 +EDGE2 1950 1749 -1.01301 0.0292874 0.0032008 1 0 1 1 0 0 +EDGE2 1950 1729 -1.01234 0.0443516 0.0352338 1 0 1 1 0 0 +EDGE2 1951 1750 -0.959169 0.0275384 1.55596 1 0 1 1 0 0 +EDGE2 1951 1950 -1.03189 0.0470438 1.57812 1 0 1 1 0 0 +EDGE2 1951 1730 -1.08012 -0.0438711 1.55656 1 0 1 1 0 0 +EDGE2 1952 1951 -1.0225 -0.00128052 -0.0215143 1 0 1 1 0 0 +EDGE2 1953 1952 -0.943011 0.0709763 0.00281239 1 0 1 1 0 0 +EDGE2 1954 1953 -1.05417 0.00142752 0.0283419 1 0 1 1 0 0 +EDGE2 1955 1954 -1.06581 0.0927918 0.0287701 1 0 1 1 0 0 +EDGE2 1956 1955 -1.01682 0.0252341 1.5651 1 0 1 1 0 0 +EDGE2 1957 1956 -1.03777 0.0180557 0.0156521 1 0 1 1 0 0 +EDGE2 1958 1957 -0.906424 -0.0434791 -0.00809637 1 0 1 1 0 0 +EDGE2 1959 1958 -0.924016 -0.0355233 0.0261924 1 0 1 1 0 0 +EDGE2 1960 1959 -1.0605 -0.00812216 0.0268935 1 0 1 1 0 0 +EDGE2 1961 1960 -0.964846 -0.0931329 -1.55245 1 0 1 1 0 0 +EDGE2 1962 1961 -1.05809 -0.0414948 0.0105518 1 0 1 1 0 0 +EDGE2 1963 1962 -0.993888 -0.0589607 -0.0370754 1 0 1 1 0 0 +EDGE2 1964 1963 -0.966421 -0.0306585 -0.0240633 1 0 1 1 0 0 +EDGE2 1965 1964 -0.994873 -0.00466666 0.0224142 1 0 1 1 0 0 +EDGE2 1966 1965 -1.0033 0.00377487 -1.58998 1 0 1 1 0 0 +EDGE2 1967 1966 -0.971765 0.0319893 -0.00646729 1 0 1 1 0 0 +EDGE2 1968 1967 -0.946994 0.00991469 -0.00483266 1 0 1 1 0 0 +EDGE2 1969 1968 -0.93351 0.0334612 0.00776193 1 0 1 1 0 0 +EDGE2 1970 1969 -0.915027 -0.00921922 0.0389372 1 0 1 1 0 0 +EDGE2 1971 1970 -1.04248 -0.0188794 -1.5627 1 0 1 1 0 0 +EDGE2 1972 1971 -0.988714 0.0426255 -0.00833797 1 0 1 1 0 0 +EDGE2 1973 1972 -0.923307 -0.00502572 0.0160189 1 0 1 1 0 0 +EDGE2 1974 1973 -0.96362 0.0269859 0.0183691 1 0 1 1 0 0 +EDGE2 1974 1955 0.98267 -0.0587952 -3.16323 1 0 1 1 0 0 +EDGE2 1975 1954 1.06649 0.0363914 -3.16319 1 0 1 1 0 0 +EDGE2 1975 1974 -0.96762 -0.001388 0.00169247 1 0 1 1 0 0 +EDGE2 1975 1955 0.0431246 -0.024315 -3.13667 1 0 1 1 0 0 +EDGE2 1975 1956 -0.0451835 0.994651 1.61509 1 0 1 1 0 0 +EDGE2 1976 1975 -0.986738 -0.0104457 -1.55557 1 0 1 1 0 0 +EDGE2 1976 1955 -0.978853 0.0634217 1.61061 1 0 1 1 0 0 +EDGE2 1976 1956 -0.00423246 -0.050154 -0.0162084 1 0 1 1 0 0 +EDGE2 1976 1957 0.992492 0.044839 0.000239347 1 0 1 1 0 0 +EDGE2 1977 1956 -0.996629 -0.108151 -0.0454251 1 0 1 1 0 0 +EDGE2 1977 1976 -1.04692 -0.0243873 -0.00703196 1 0 1 1 0 0 +EDGE2 1977 1957 -0.0144798 -0.00277489 0.0273135 1 0 1 1 0 0 +EDGE2 1977 1958 0.967213 -0.0691074 -0.00575115 1 0 1 1 0 0 +EDGE2 1978 1977 -1.08013 0.0333463 0.0102876 1 0 1 1 0 0 +EDGE2 1978 1957 -0.987933 -0.0058788 -0.0171579 1 0 1 1 0 0 +EDGE2 1978 1958 0.0444829 0.0833283 -0.0577801 1 0 1 1 0 0 +EDGE2 1978 1959 0.966877 0.0235905 0.00500637 1 0 1 1 0 0 +EDGE2 1979 1978 -0.952346 -0.0401466 0.0123793 1 0 1 1 0 0 +EDGE2 1979 1958 -1.01589 0.0054175 -0.0215536 1 0 1 1 0 0 +EDGE2 1979 1959 -0.0389842 -0.0862518 -0.0169288 1 0 1 1 0 0 +EDGE2 1979 1960 0.975895 -0.0495453 0.0197864 1 0 1 1 0 0 +EDGE2 1980 1979 -1.00598 0.0532653 0.0216999 1 0 1 1 0 0 +EDGE2 1980 1959 -1.02501 0.0344823 -0.0127801 1 0 1 1 0 0 +EDGE2 1980 1960 -0.0471652 0.0863481 0.0062378 1 0 1 1 0 0 +EDGE2 1980 1961 0.00901442 1.03347 1.57827 1 0 1 1 0 0 +EDGE2 1981 1962 0.940742 0.00341825 0.0168041 1 0 1 1 0 0 +EDGE2 1981 1960 -1.00015 0.0438103 -1.53363 1 0 1 1 0 0 +EDGE2 1981 1980 -0.958201 0.02756 -1.58033 1 0 1 1 0 0 +EDGE2 1981 1961 0.0170745 0.0725172 -0.00124512 1 0 1 1 0 0 +EDGE2 1982 1981 -1.01578 -0.0214548 0.0311474 1 0 1 1 0 0 +EDGE2 1982 1963 1.05768 -0.0226734 0.017436 1 0 1 1 0 0 +EDGE2 1982 1962 -0.0532055 0.045735 -0.028132 1 0 1 1 0 0 +EDGE2 1982 1961 -1.03548 -0.0648484 -0.0257451 1 0 1 1 0 0 +EDGE2 1983 1964 1.00276 -0.00835625 -0.0055426 1 0 1 1 0 0 +EDGE2 1983 1982 -0.969956 -0.0322649 -0.00018619 1 0 1 1 0 0 +EDGE2 1983 1963 0.0564916 0.0369334 0.00443873 1 0 1 1 0 0 +EDGE2 1983 1962 -0.985286 0.0122176 -0.0124195 1 0 1 1 0 0 +EDGE2 1984 1964 0.0717805 0.000804701 0.000489767 1 0 1 1 0 0 +EDGE2 1984 1965 0.895167 0.0815251 -0.009058 1 0 1 1 0 0 +EDGE2 1984 1963 -0.982849 -0.0757825 -0.0479688 1 0 1 1 0 0 +EDGE2 1984 1983 -1.05478 -0.0364054 -0.0194313 1 0 1 1 0 0 +EDGE2 1985 1964 -0.999001 0.0168539 0.00163576 1 0 1 1 0 0 +EDGE2 1985 1965 -0.0197151 -0.048047 -0.0300131 1 0 1 1 0 0 +EDGE2 1985 1966 0.031442 0.977049 1.60526 1 0 1 1 0 0 +EDGE2 1985 1984 -0.949048 -0.0212716 -0.0366859 1 0 1 1 0 0 +EDGE2 1986 1967 0.937513 0.0493326 0.0199668 1 0 1 1 0 0 +EDGE2 1986 1965 -0.913676 0.02738 -1.57373 1 0 1 1 0 0 +EDGE2 1986 1985 -1.00978 0.0450655 -1.53487 1 0 1 1 0 0 +EDGE2 1986 1966 0.0626167 0.0246417 0.0179191 1 0 1 1 0 0 +EDGE2 1987 1968 0.971278 -0.0317633 0.02737 1 0 1 1 0 0 +EDGE2 1987 1986 -1.07877 -0.0756139 -0.0266188 1 0 1 1 0 0 +EDGE2 1987 1967 0.0208396 -0.0404893 -0.0377407 1 0 1 1 0 0 +EDGE2 1987 1966 -0.969448 -0.0362498 0.00101759 1 0 1 1 0 0 +EDGE2 1988 1969 1.01257 -0.0335056 0.0145992 1 0 1 1 0 0 +EDGE2 1988 1968 -0.0622395 -0.0165413 -0.00719098 1 0 1 1 0 0 +EDGE2 1988 1967 -0.993366 -0.0737222 -0.0367186 1 0 1 1 0 0 +EDGE2 1988 1987 -0.963401 0.0261517 -0.00716377 1 0 1 1 0 0 +EDGE2 1989 1970 0.948275 -0.0146619 0.0318573 1 0 1 1 0 0 +EDGE2 1989 1969 -0.0171098 -0.0273623 0.00880636 1 0 1 1 0 0 +EDGE2 1989 1968 -0.979076 -0.0709008 0.00710372 1 0 1 1 0 0 +EDGE2 1989 1988 -1.04271 -0.0833517 0.0264933 1 0 1 1 0 0 +EDGE2 1990 1970 -0.00689206 0.0189439 -0.00670274 1 0 1 1 0 0 +EDGE2 1990 1971 -0.0331747 1.01305 1.61178 1 0 1 1 0 0 +EDGE2 1990 1969 -1.03999 -0.0194879 -0.0191377 1 0 1 1 0 0 +EDGE2 1990 1989 -0.970665 -0.0273407 0.00485176 1 0 1 1 0 0 +EDGE2 1991 1970 -0.986906 0.0371399 1.55516 1 0 1 1 0 0 +EDGE2 1991 1990 -1.0075 0.030087 1.60491 1 0 1 1 0 0 +EDGE2 1992 1991 -0.889089 0.00876667 -0.0115424 1 0 1 1 0 0 +EDGE2 1993 1992 -0.979778 -0.0577887 -0.0228168 1 0 1 1 0 0 +EDGE2 1994 1993 -1.003 -0.0523314 -0.0176558 1 0 1 1 0 0 +EDGE2 1995 1994 -1.0749 -0.00669704 0.00311574 1 0 1 1 0 0 +EDGE2 1996 1995 -1.07875 0.0332414 -1.55955 1 0 1 1 0 0 +EDGE2 1997 1996 -0.973014 -0.0101613 -0.00368584 1 0 1 1 0 0 +EDGE2 1998 1997 -0.994255 -0.0436559 -0.00811794 1 0 1 1 0 0 +EDGE2 1999 1998 -0.999811 0.0197544 0.0182535 1 0 1 1 0 0 +EDGE2 2000 1999 -0.947696 -0.0869239 0.0102297 1 0 1 1 0 0 +EDGE2 2001 2000 -0.973752 0.0691682 -1.60947 1 0 1 1 0 0 +EDGE2 2002 2001 -1.05464 0.123964 0.0183274 1 0 1 1 0 0 +EDGE2 2003 2002 -1.0143 0.0423181 -0.00525544 1 0 1 1 0 0 +EDGE2 2004 2003 -1.09083 -0.0351689 0.00792952 1 0 1 1 0 0 +EDGE2 2005 2004 -0.908782 -0.0254165 -0.0143975 1 0 1 1 0 0 +EDGE2 2006 2005 -1.01976 -0.0331941 1.56854 1 0 1 1 0 0 +EDGE2 2007 2006 -1.0568 0.0397136 0.0251142 1 0 1 1 0 0 +EDGE2 2008 2007 -0.958366 0.00878078 -0.0209455 1 0 1 1 0 0 +EDGE2 2009 2008 -0.965193 0.01105 -0.00803488 1 0 1 1 0 0 +EDGE2 2010 2009 -0.976531 0.0809394 0.00656133 1 0 1 1 0 0 +EDGE2 2011 2010 -1.07244 0.0756217 -1.58931 1 0 1 1 0 0 +EDGE2 2012 2011 -0.953108 0.0135975 0.0299713 1 0 1 1 0 0 +EDGE2 2013 2012 -1.08004 0.0101901 -0.0191886 1 0 1 1 0 0 +EDGE2 2014 2013 -0.896443 0.0700767 -0.0157352 1 0 1 1 0 0 +EDGE2 2015 2014 -1.01383 0.00596184 -0.00901969 1 0 1 1 0 0 +EDGE2 2016 2015 -1.05566 -0.0720228 1.57461 1 0 1 1 0 0 +EDGE2 2017 2016 -0.996657 -0.0580298 0.0212475 1 0 1 1 0 0 +EDGE2 2018 2017 -1.02126 -0.0525167 -0.00246928 1 0 1 1 0 0 +EDGE2 2019 2018 -1.07095 0.00424662 -0.000571737 1 0 1 1 0 0 +EDGE2 2020 2019 -0.974978 0.0683737 0.0115495 1 0 1 1 0 0 +EDGE2 2021 2020 -1.0224 0.00545924 -1.55022 1 0 1 1 0 0 +EDGE2 2022 2021 -0.93369 -0.0720647 -0.0111007 1 0 1 1 0 0 +EDGE2 2023 2022 -0.891795 0.0678456 -0.0134894 1 0 1 1 0 0 +EDGE2 2024 2023 -0.92219 0.0205852 0.0148953 1 0 1 1 0 0 +EDGE2 2025 2024 -0.989427 -0.0474381 -0.0113209 1 0 1 1 0 0 +EDGE2 2026 2025 -1.06307 0.00217862 -1.58854 1 0 1 1 0 0 +EDGE2 2027 2026 -1.03087 0.0852776 0.0164415 1 0 1 1 0 0 +EDGE2 2028 2027 -1.04948 -0.0192385 0.0214181 1 0 1 1 0 0 +EDGE2 2029 2028 -1.07877 -0.0576971 -0.00977899 1 0 1 1 0 0 +EDGE2 2029 1770 0.967999 0.068146 -3.1459 1 0 1 1 0 0 +EDGE2 2030 2029 -1.0711 0.0793798 0.00827537 1 0 1 1 0 0 +EDGE2 2030 1770 -0.123098 0.0633544 -3.16166 1 0 1 1 0 0 +EDGE2 2030 1771 0.0515934 -1.04544 -1.55233 1 0 1 1 0 0 +EDGE2 2030 1769 1.04109 -0.0316559 -3.13415 1 0 1 1 0 0 +EDGE2 2031 1770 -1.07055 -0.0662899 -1.5828 1 0 1 1 0 0 +EDGE2 2031 2030 -0.995306 0.0415322 1.56804 1 0 1 1 0 0 +EDGE2 2031 1771 -0.00946214 -0.0364417 0.0106513 1 0 1 1 0 0 +EDGE2 2031 1772 1.06457 0.0331958 0.00722261 1 0 1 1 0 0 +EDGE2 2032 2031 -1.1349 -0.0164872 0.00476837 1 0 1 1 0 0 +EDGE2 2032 1771 -1.06965 -0.0186978 -0.00491418 1 0 1 1 0 0 +EDGE2 2032 1772 -0.0388556 0.0117188 0.0207303 1 0 1 1 0 0 +EDGE2 2032 1773 1.05593 -0.0637715 0.00746517 1 0 1 1 0 0 +EDGE2 2033 2032 -0.874984 0.0170643 0.0221874 1 0 1 1 0 0 +EDGE2 2033 1772 -1.02996 -0.0163435 -0.0235294 1 0 1 1 0 0 +EDGE2 2033 1773 -0.0274608 -0.00322703 0.0251846 1 0 1 1 0 0 +EDGE2 2033 1774 0.980111 -0.0052702 0.00889805 1 0 1 1 0 0 +EDGE2 2034 2033 -0.963029 -0.0441092 0.0523526 1 0 1 1 0 0 +EDGE2 2034 1773 -1.01845 -0.0505867 0.0507416 1 0 1 1 0 0 +EDGE2 2034 1774 0.0279049 -0.0178085 -0.02987 1 0 1 1 0 0 +EDGE2 2034 1775 1.0264 -0.0355689 -0.000497515 1 0 1 1 0 0 +EDGE2 2035 1776 -0.0640509 -0.902337 -1.57023 1 0 1 1 0 0 +EDGE2 2035 2034 -1.02106 -0.070849 0.0246275 1 0 1 1 0 0 +EDGE2 2035 1774 -1.01843 -0.0134186 -8.64777e-05 1 0 1 1 0 0 +EDGE2 2035 1775 -0.0290819 0.0280257 0.0198529 1 0 1 1 0 0 +EDGE2 2036 1777 0.953461 0.0236675 0.00596518 1 0 1 1 0 0 +EDGE2 2036 1776 0.00339603 0.0654598 -0.0181787 1 0 1 1 0 0 +EDGE2 2036 1775 -1.14822 -0.0929821 1.59057 1 0 1 1 0 0 +EDGE2 2036 2035 -0.995973 0.00665597 1.55615 1 0 1 1 0 0 +EDGE2 2037 1777 -0.0535354 0.113399 0.0242554 1 0 1 1 0 0 +EDGE2 2037 1778 0.942548 0.036213 0.0104191 1 0 1 1 0 0 +EDGE2 2037 2036 -0.96758 -0.0425252 -0.06032 1 0 1 1 0 0 +EDGE2 2037 1776 -1.03944 -0.00510044 -0.0159673 1 0 1 1 0 0 +EDGE2 2038 1779 0.957235 0.0325813 -0.00633615 1 0 1 1 0 0 +EDGE2 2038 1777 -0.987534 -0.0566181 -0.0150573 1 0 1 1 0 0 +EDGE2 2038 1778 -0.0754735 -0.000374015 -0.00628783 1 0 1 1 0 0 +EDGE2 2038 2037 -0.963496 0.0665324 -0.0143932 1 0 1 1 0 0 +EDGE2 2039 1780 1.01735 0.023788 -0.011127 1 0 1 1 0 0 +EDGE2 2039 1779 0.0365986 0.0654214 -0.0100751 1 0 1 1 0 0 +EDGE2 2039 1778 -1.02529 0.031823 -0.0307551 1 0 1 1 0 0 +EDGE2 2039 2038 -0.908965 -0.0479803 0.0120974 1 0 1 1 0 0 +EDGE2 2040 1780 -0.0310481 0.0546532 0.0196571 1 0 1 1 0 0 +EDGE2 2040 1781 0.0211393 0.842227 1.54761 1 0 1 1 0 0 +EDGE2 2040 2039 -0.967474 0.0271121 -0.0244794 1 0 1 1 0 0 +EDGE2 2040 1779 -1.05953 -0.0104829 0.0132364 1 0 1 1 0 0 +EDGE2 2041 2040 -1.00599 0.0236894 -1.59488 1 0 1 1 0 0 +EDGE2 2041 1780 -0.982786 0.0306551 -1.58377 1 0 1 1 0 0 +EDGE2 2041 1782 1.03618 0.0308659 0.0238998 1 0 1 1 0 0 +EDGE2 2041 1781 0.000614444 -0.100052 -0.00943012 1 0 1 1 0 0 +EDGE2 2042 2041 -1.0258 0.00400385 -0.00537019 1 0 1 1 0 0 +EDGE2 2042 1783 1.00123 -0.0177265 -0.000172465 1 0 1 1 0 0 +EDGE2 2042 1782 0.00375248 0.0720451 0.0629422 1 0 1 1 0 0 +EDGE2 2042 1781 -1.04939 0.067213 -0.035484 1 0 1 1 0 0 +EDGE2 2043 1783 0.0561227 0.0280287 -0.0276663 1 0 1 1 0 0 +EDGE2 2043 1782 -1.04549 0.00232141 -0.0155548 1 0 1 1 0 0 +EDGE2 2043 2042 -1.03689 0.0724666 0.0275124 1 0 1 1 0 0 +EDGE2 2043 1784 1.01978 0.075081 -0.0103745 1 0 1 1 0 0 +EDGE2 2044 1785 0.980821 0.012924 -0.0241203 1 0 1 1 0 0 +EDGE2 2044 1783 -0.993741 -0.0969244 0.018102 1 0 1 1 0 0 +EDGE2 2044 2043 -0.985662 -0.0827185 0.00706955 1 0 1 1 0 0 +EDGE2 2044 1784 0.0831068 0.0541412 0.0233084 1 0 1 1 0 0 +EDGE2 2045 1785 -0.0335675 0.0403073 0.00334599 1 0 1 1 0 0 +EDGE2 2045 1784 -0.948263 0.058277 0.0180606 1 0 1 1 0 0 +EDGE2 2045 2044 -0.994602 -0.0850844 0.0123895 1 0 1 1 0 0 +EDGE2 2045 1786 -0.0294208 0.987414 1.57833 1 0 1 1 0 0 +EDGE2 2046 1785 -1.0343 0.00223982 -1.5811 1 0 1 1 0 0 +EDGE2 2046 2045 -0.997694 0.0583974 -1.56846 1 0 1 1 0 0 +EDGE2 2046 1786 0.173562 0.000890702 -0.043669 1 0 1 1 0 0 +EDGE2 2046 1787 1.00324 -0.0592487 -0.000878246 1 0 1 1 0 0 +EDGE2 2047 2046 -1.03217 -0.0497853 0.0140985 1 0 1 1 0 0 +EDGE2 2047 1786 -0.998089 0.00841728 -0.0122077 1 0 1 1 0 0 +EDGE2 2047 1787 -0.0603566 0.0187924 -0.0444903 1 0 1 1 0 0 +EDGE2 2047 1788 0.997145 -0.0253479 -0.00454542 1 0 1 1 0 0 +EDGE2 2048 2047 -0.975925 0.00988346 -0.00535406 1 0 1 1 0 0 +EDGE2 2048 1787 -0.940616 0.0442035 0.0207154 1 0 1 1 0 0 +EDGE2 2048 1788 -0.0342827 0.0211036 0.0244036 1 0 1 1 0 0 +EDGE2 2048 1789 0.975748 0.0754369 -0.0120463 1 0 1 1 0 0 +EDGE2 2049 1788 -0.835679 0.0597856 0.0192458 1 0 1 1 0 0 +EDGE2 2049 2048 -1.09447 0.0201956 0.0384902 1 0 1 1 0 0 +EDGE2 2049 1789 0.0543556 0.0448541 0.020531 1 0 1 1 0 0 +EDGE2 2049 1790 1.02458 -0.0285454 0.0282421 1 0 1 1 0 0 +EDGE2 2050 2049 -1.02097 0.0695105 -0.013078 1 0 1 1 0 0 +EDGE2 2050 1789 -1.0275 -0.13845 -0.0451069 1 0 1 1 0 0 +EDGE2 2050 1790 -0.097085 -0.0397978 -0.0247852 1 0 1 1 0 0 +EDGE2 2050 1791 0.0612813 -0.987131 -1.56313 1 0 1 1 0 0 +EDGE2 2051 1790 -0.915634 -0.0355756 -1.5353 1 0 1 1 0 0 +EDGE2 2051 2050 -1.00488 0.146157 -1.55822 1 0 1 1 0 0 +EDGE2 2052 2051 -0.991211 -0.00747156 -0.0112594 1 0 1 1 0 0 +EDGE2 2053 2052 -0.922185 -0.0289034 -0.00241388 1 0 1 1 0 0 +EDGE2 2054 1775 0.958119 -0.0154867 -3.16906 1 0 1 1 0 0 +EDGE2 2054 2035 1.02775 -0.0786035 -3.118 1 0 1 1 0 0 +EDGE2 2054 2053 -1.08205 0.0196614 0.00947661 1 0 1 1 0 0 +EDGE2 2055 2036 -0.0148165 0.917164 1.58725 1 0 1 1 0 0 +EDGE2 2055 1776 0.0238426 1.00587 1.57361 1 0 1 1 0 0 +EDGE2 2055 2034 1.03926 -0.0309316 -3.12616 1 0 1 1 0 0 +EDGE2 2055 1774 1.04248 0.0593676 -3.14517 1 0 1 1 0 0 +EDGE2 2055 1775 -0.0165248 -0.00121127 -3.14973 1 0 1 1 0 0 +EDGE2 2055 2035 0.028645 0.0467519 -3.11392 1 0 1 1 0 0 +EDGE2 2055 2054 -1.01589 -0.019704 0.0218409 1 0 1 1 0 0 +EDGE2 2056 2055 -1.01486 0.0358103 1.56314 1 0 1 1 0 0 +EDGE2 2056 1775 -0.991707 0.0514897 -1.59705 1 0 1 1 0 0 +EDGE2 2056 2035 -1.0401 -0.00222917 -1.56289 1 0 1 1 0 0 +EDGE2 2057 2056 -0.939123 -0.0226298 0.00308783 1 0 1 1 0 0 +EDGE2 2058 2057 -0.969267 -0.0067039 0.0288785 1 0 1 1 0 0 +EDGE2 2059 2058 -0.889201 -0.0291386 -0.022108 1 0 1 1 0 0 +EDGE2 2059 1420 1.06908 -0.0164726 -3.16386 1 0 1 1 0 0 +EDGE2 2059 1440 1.14583 0.119619 -3.14532 1 0 1 1 0 0 +EDGE2 2059 1760 1.05482 0.00124285 -3.14953 1 0 1 1 0 0 +EDGE2 2059 1400 1.03361 -0.0139075 -3.13343 1 0 1 1 0 0 +EDGE2 2060 2059 -0.985138 -0.0620855 -0.00221214 1 0 1 1 0 0 +EDGE2 2060 1761 0.0629754 1.01857 1.56725 1 0 1 1 0 0 +EDGE2 2060 1420 0.0140972 -0.0740095 -3.12269 1 0 1 1 0 0 +EDGE2 2060 1440 -0.0478367 0.0884543 -3.17249 1 0 1 1 0 0 +EDGE2 2060 1760 -0.0454953 -0.0243298 -3.12816 1 0 1 1 0 0 +EDGE2 2060 1400 -0.070771 -0.0379852 -3.12716 1 0 1 1 0 0 +EDGE2 2060 1421 0.0768222 -0.988457 -1.56769 1 0 1 1 0 0 +EDGE2 2060 1441 -0.0324256 -0.963688 -1.57423 1 0 1 1 0 0 +EDGE2 2060 1401 0.0207538 -0.997749 -1.59414 1 0 1 1 0 0 +EDGE2 2060 1419 1.00729 -0.0517186 -3.14537 1 0 1 1 0 0 +EDGE2 2060 1759 1.10585 -0.0242619 -3.13363 1 0 1 1 0 0 +EDGE2 2060 1439 0.920979 0.0155862 -3.1729 1 0 1 1 0 0 +EDGE2 2060 1399 1.00389 0.0943357 -3.16566 1 0 1 1 0 0 +EDGE2 2061 2060 -1.03449 -0.0398276 -1.5722 1 0 1 1 0 0 +EDGE2 2061 1761 -0.0115611 0.0270517 0.0291157 1 0 1 1 0 0 +EDGE2 2061 1762 0.997926 0.0813552 -0.0128885 1 0 1 1 0 0 +EDGE2 2061 1420 -1.0343 0.00257509 1.58862 1 0 1 1 0 0 +EDGE2 2061 1440 -1.00197 0.135559 1.58379 1 0 1 1 0 0 +EDGE2 2061 1760 -0.990688 -0.0451239 1.54473 1 0 1 1 0 0 +EDGE2 2061 1400 -0.940917 -0.0326099 1.59143 1 0 1 1 0 0 +EDGE2 2062 1763 0.967165 0.00451729 -0.0170611 1 0 1 1 0 0 +EDGE2 2062 1761 -1.06771 -0.0470619 0.00766485 1 0 1 1 0 0 +EDGE2 2062 1762 0.0137865 0.0426439 -0.00735555 1 0 1 1 0 0 +EDGE2 2062 2061 -1.05584 0.0180965 0.00971573 1 0 1 1 0 0 +EDGE2 2063 2062 -1.05063 -0.00297552 -0.00807575 1 0 1 1 0 0 +EDGE2 2063 1764 1.07555 -0.0183806 -0.0101581 1 0 1 1 0 0 +EDGE2 2063 1763 -0.060543 -0.0764637 0.0258011 1 0 1 1 0 0 +EDGE2 2063 1762 -0.907638 0.0115591 0.0191108 1 0 1 1 0 0 +EDGE2 2064 1765 1.03686 0.0500381 0.0010458 1 0 1 1 0 0 +EDGE2 2064 2063 -1.08182 -0.0656002 0.0326008 1 0 1 1 0 0 +EDGE2 2064 1764 0.026534 -0.0194485 0.0205132 1 0 1 1 0 0 +EDGE2 2064 1763 -1.02745 -0.0435062 0.00220158 1 0 1 1 0 0 +EDGE2 2065 1766 -0.0477212 1.06117 1.52948 1 0 1 1 0 0 +EDGE2 2065 1765 -0.106607 0.0630137 -0.0146243 1 0 1 1 0 0 +EDGE2 2065 1764 -0.965799 0.0502871 -0.0298033 1 0 1 1 0 0 +EDGE2 2065 2064 -0.958347 -0.00109041 0.0311193 1 0 1 1 0 0 +EDGE2 2066 1767 0.993505 0.039821 0.000415005 1 0 1 1 0 0 +EDGE2 2066 1766 -0.0662006 0.0555204 -0.018927 1 0 1 1 0 0 +EDGE2 2066 1765 -0.983816 -0.0566976 -1.55691 1 0 1 1 0 0 +EDGE2 2066 2065 -1.01138 0.0872851 -1.56971 1 0 1 1 0 0 +EDGE2 2067 1768 0.99253 0.0337096 0.0135959 1 0 1 1 0 0 +EDGE2 2067 2066 -1.02827 -0.0442953 -0.0153743 1 0 1 1 0 0 +EDGE2 2067 1767 -0.0233624 0.0363088 0.0351678 1 0 1 1 0 0 +EDGE2 2067 1766 -1.02767 0.0829028 0.0221758 1 0 1 1 0 0 +EDGE2 2068 1768 -0.0332521 0.0327259 -0.0116608 1 0 1 1 0 0 +EDGE2 2068 1769 0.915822 0.027828 -0.00593092 1 0 1 1 0 0 +EDGE2 2068 1767 -1.00888 -0.0579279 -0.0119738 1 0 1 1 0 0 +EDGE2 2068 2067 -0.9876 -0.0337532 0.00619463 1 0 1 1 0 0 +EDGE2 2069 1770 1.02642 -0.0018706 0.0256941 1 0 1 1 0 0 +EDGE2 2069 2030 1.03917 -0.0340685 -3.09948 1 0 1 1 0 0 +EDGE2 2069 1768 -0.9268 -0.114679 0.00281193 1 0 1 1 0 0 +EDGE2 2069 1769 0.0297113 0.101166 -0.0111856 1 0 1 1 0 0 +EDGE2 2069 2068 -1.03303 -0.0696943 0.0156443 1 0 1 1 0 0 +EDGE2 2070 2031 -0.0603162 0.903253 1.56407 1 0 1 1 0 0 +EDGE2 2070 2029 1.04505 0.0185718 -3.17918 1 0 1 1 0 0 +EDGE2 2070 1770 0.0797658 -0.0609547 -0.00789907 1 0 1 1 0 0 +EDGE2 2070 2030 -0.0227819 0.0249908 -3.17037 1 0 1 1 0 0 +EDGE2 2070 1771 -0.0495957 0.986278 1.55011 1 0 1 1 0 0 +EDGE2 2070 1769 -0.978248 0.0501513 -0.0124575 1 0 1 1 0 0 +EDGE2 2070 2069 -0.945721 -0.0356467 -0.0359115 1 0 1 1 0 0 +EDGE2 2071 1770 -1.02439 -0.0379379 1.60636 1 0 1 1 0 0 +EDGE2 2071 2070 -1.02528 -0.0261553 1.57218 1 0 1 1 0 0 +EDGE2 2071 2030 -1.03825 -0.0309083 -1.57313 1 0 1 1 0 0 +EDGE2 2072 2071 -1.06459 -0.0247827 0.0572766 1 0 1 1 0 0 +EDGE2 2073 2072 -1.02415 -0.0219612 -0.0137681 1 0 1 1 0 0 +EDGE2 2074 2015 0.946428 0.0858099 -3.14087 1 0 1 1 0 0 +EDGE2 2074 2073 -0.995779 0.0602983 -0.0126323 1 0 1 1 0 0 +EDGE2 2075 2016 0.0452614 1.00445 1.57075 1 0 1 1 0 0 +EDGE2 2075 2015 -0.02969 0.0232956 -3.1257 1 0 1 1 0 0 +EDGE2 2075 2014 0.949928 -0.0776795 -3.16554 1 0 1 1 0 0 +EDGE2 2075 2074 -1.00756 -0.00994239 -0.0130642 1 0 1 1 0 0 +EDGE2 2076 2016 0.0106835 0.0152889 -0.00761726 1 0 1 1 0 0 +EDGE2 2076 2017 0.938967 0.0835077 -0.0154862 1 0 1 1 0 0 +EDGE2 2076 2015 -1.03568 -0.0040363 1.55059 1 0 1 1 0 0 +EDGE2 2076 2075 -1.00416 0.0240805 -1.57658 1 0 1 1 0 0 +EDGE2 2077 2018 1.01641 0.0942926 -0.0104861 1 0 1 1 0 0 +EDGE2 2077 2016 -1.07138 0.0139981 -0.0053017 1 0 1 1 0 0 +EDGE2 2077 2076 -1.0347 0.0640575 0.0247952 1 0 1 1 0 0 +EDGE2 2077 2017 0.00443803 0.0303773 -0.0126026 1 0 1 1 0 0 +EDGE2 2078 2019 1.05588 0.0480312 0.0109495 1 0 1 1 0 0 +EDGE2 2078 2077 -1.04494 -0.0312114 0.0188329 1 0 1 1 0 0 +EDGE2 2078 2018 -0.0475315 0.00977904 0.0140201 1 0 1 1 0 0 +EDGE2 2078 2017 -1.0194 0.0108486 0.00119066 1 0 1 1 0 0 +EDGE2 2079 2020 0.969797 0.0118314 -0.0319542 1 0 1 1 0 0 +EDGE2 2079 2019 0.0544526 0.00637056 -0.0113196 1 0 1 1 0 0 +EDGE2 2079 2018 -0.938811 0.0959782 -0.00454566 1 0 1 1 0 0 +EDGE2 2079 2078 -0.983424 -0.00109953 0.00967375 1 0 1 1 0 0 +EDGE2 2080 2020 0.0382977 -0.0487556 -0.00282434 1 0 1 1 0 0 +EDGE2 2080 2021 -0.0508546 1.09183 1.58755 1 0 1 1 0 0 +EDGE2 2080 2019 -0.995685 -0.0663734 -0.0358309 1 0 1 1 0 0 +EDGE2 2080 2079 -0.982326 0.0640078 0.0103493 1 0 1 1 0 0 +EDGE2 2081 2080 -1.04442 0.0452242 1.57636 1 0 1 1 0 0 +EDGE2 2081 2020 -0.993922 -0.0187882 1.62775 1 0 1 1 0 0 +EDGE2 2082 2081 -1.0596 0.010659 0.011535 1 0 1 1 0 0 +EDGE2 2083 2082 -0.906978 -0.000653896 -0.013822 1 0 1 1 0 0 +EDGE2 2084 2083 -1.00137 -0.0431951 -0.000280403 1 0 1 1 0 0 +EDGE2 2085 2084 -0.997526 0.0715798 -0.0102786 1 0 1 1 0 0 +EDGE2 2086 2085 -0.949443 -0.0803269 -1.54672 1 0 1 1 0 0 +EDGE2 2087 2086 -0.983397 0.0289306 0.000320479 1 0 1 1 0 0 +EDGE2 2088 2087 -1.01432 -0.0149881 -0.00430255 1 0 1 1 0 0 +EDGE2 2089 2088 -1.04001 -0.104707 0.038126 1 0 1 1 0 0 +EDGE2 2090 2089 -1.01943 -0.0182081 0.0111493 1 0 1 1 0 0 +EDGE2 2091 2090 -1.03675 -0.0136034 -1.58693 1 0 1 1 0 0 +EDGE2 2092 2091 -0.997326 0.0530856 0.019151 1 0 1 1 0 0 +EDGE2 2093 2092 -0.978746 0.0130074 0.00309445 1 0 1 1 0 0 +EDGE2 2094 2093 -0.97374 0.0602275 0.00545233 1 0 1 1 0 0 +EDGE2 2095 2094 -0.977473 0.0365923 0.0130362 1 0 1 1 0 0 +EDGE2 2096 2095 -1.02878 -0.0058538 -1.58979 1 0 1 1 0 0 +EDGE2 2097 2096 -1.05116 0.0535416 0.0150216 1 0 1 1 0 0 +EDGE2 2098 2097 -1.05758 -0.0377664 -0.00478365 1 0 1 1 0 0 +EDGE2 2099 2098 -0.921447 0.0907143 -0.0431315 1 0 1 1 0 0 +EDGE2 2099 2080 1.04098 0.0958132 -3.15192 1 0 1 1 0 0 +EDGE2 2099 2020 1.03273 0.0284017 -3.12157 1 0 1 1 0 0 +EDGE2 2100 2099 -1.0209 -0.0533693 0.00107134 1 0 1 1 0 0 +EDGE2 2100 2081 -0.00318037 1.00612 1.57035 1 0 1 1 0 0 +EDGE2 2100 2080 0.0315764 0.0228992 -3.14217 1 0 1 1 0 0 +EDGE2 2100 2020 -0.0158957 0.00581737 -3.15852 1 0 1 1 0 0 +EDGE2 2100 2021 0.0668871 -0.999669 -1.57278 1 0 1 1 0 0 +EDGE2 2100 2019 0.893119 -0.0868503 -3.18094 1 0 1 1 0 0 +EDGE2 2100 2079 0.990828 0.0960552 -3.15223 1 0 1 1 0 0 +EDGE2 2101 2100 -1.0187 0.0558712 1.57662 1 0 1 1 0 0 +EDGE2 2101 2080 -1.00299 0.00951651 -1.5843 1 0 1 1 0 0 +EDGE2 2101 2020 -1.07329 -0.00712989 -1.57938 1 0 1 1 0 0 +EDGE2 2101 2021 0.0789636 -0.0324057 -0.0145084 1 0 1 1 0 0 +EDGE2 2101 2022 1.0175 0.0443666 0.0333774 1 0 1 1 0 0 +EDGE2 2102 2101 -1.0428 0.0550618 -0.0160629 1 0 1 1 0 0 +EDGE2 2102 2021 -0.899866 0.0469046 0.00370307 1 0 1 1 0 0 +EDGE2 2102 2023 1.06493 0.00435909 0.0119902 1 0 1 1 0 0 +EDGE2 2102 2022 -0.0712344 0.0416546 -0.0254352 1 0 1 1 0 0 +EDGE2 2103 2102 -1.00432 0.0165683 0.021372 1 0 1 1 0 0 +EDGE2 2103 2024 1.00618 0.0563597 0.00507582 1 0 1 1 0 0 +EDGE2 2103 2023 -0.0189139 0.0696508 0.012861 1 0 1 1 0 0 +EDGE2 2103 2022 -1.0132 -0.0960378 -0.00568916 1 0 1 1 0 0 +EDGE2 2104 2024 0.000929314 -0.0960501 0.00342037 1 0 1 1 0 0 +EDGE2 2104 2023 -1.03131 0.0262795 -0.0384026 1 0 1 1 0 0 +EDGE2 2104 2103 -0.999082 -0.0785599 0.00135257 1 0 1 1 0 0 +EDGE2 2104 2025 0.985822 -0.0321817 -0.012578 1 0 1 1 0 0 +EDGE2 2105 2024 -1.07171 0.0105375 0.00323863 1 0 1 1 0 0 +EDGE2 2105 2104 -1.05713 0.129464 -0.00697857 1 0 1 1 0 0 +EDGE2 2105 2025 -0.0459595 -0.00309112 -0.00659904 1 0 1 1 0 0 +EDGE2 2105 2026 -0.0613073 0.972987 1.58181 1 0 1 1 0 0 +EDGE2 2106 2025 -1.05568 0.0461021 -1.57687 1 0 1 1 0 0 +EDGE2 2106 2105 -0.906828 -0.0416259 -1.5522 1 0 1 1 0 0 +EDGE2 2106 2026 0.0261111 -0.0549369 0.00629152 1 0 1 1 0 0 +EDGE2 2106 2027 0.992279 0.0263013 0.00583394 1 0 1 1 0 0 +EDGE2 2107 2026 -1.07114 0.078895 -0.0365612 1 0 1 1 0 0 +EDGE2 2107 2106 -1.05631 0.0398823 0.0150475 1 0 1 1 0 0 +EDGE2 2107 2027 0.0850887 -0.0135173 0.0181402 1 0 1 1 0 0 +EDGE2 2107 2028 1.03558 0.0497051 -0.00868987 1 0 1 1 0 0 +EDGE2 2108 2107 -1.04433 -0.0324162 -0.0152061 1 0 1 1 0 0 +EDGE2 2108 2027 -1.05473 -0.0915844 0.0232383 1 0 1 1 0 0 +EDGE2 2108 2028 -0.0185194 -0.000138477 0.00516703 1 0 1 1 0 0 +EDGE2 2108 2029 1.06182 0.0770012 0.0444138 1 0 1 1 0 0 +EDGE2 2109 2108 -0.962206 0.0186153 -0.0558167 1 0 1 1 0 0 +EDGE2 2109 2028 -0.994119 0.00618134 -0.000843716 1 0 1 1 0 0 +EDGE2 2109 2029 0.0464099 0.0144496 -0.0267033 1 0 1 1 0 0 +EDGE2 2109 1770 0.988552 -0.0133305 -3.13171 1 0 1 1 0 0 +EDGE2 2109 2070 1.03989 0.00807797 -3.11479 1 0 1 1 0 0 +EDGE2 2109 2030 1.02089 -0.0153217 0.0326151 1 0 1 1 0 0 +EDGE2 2110 2031 0.0258275 -1.03771 -1.55293 1 0 1 1 0 0 +EDGE2 2110 2029 -1.06614 0.00313968 0.0260195 1 0 1 1 0 0 +EDGE2 2110 2109 -1.02282 -0.0505576 0.00717995 1 0 1 1 0 0 +EDGE2 2110 2071 0.0611085 1.04181 1.60337 1 0 1 1 0 0 +EDGE2 2110 1770 0.0105189 -0.0288034 -3.12218 1 0 1 1 0 0 +EDGE2 2110 2070 -0.00847093 0.0297351 -3.16236 1 0 1 1 0 0 +EDGE2 2110 2030 -0.0508154 -0.0178504 -0.00910175 1 0 1 1 0 0 +EDGE2 2110 1771 -0.072305 -0.920753 -1.59436 1 0 1 1 0 0 +EDGE2 2110 1769 1.00332 0.0777116 -3.15547 1 0 1 1 0 0 +EDGE2 2110 2069 0.92056 0.00548391 -3.18558 1 0 1 1 0 0 +EDGE2 2111 2031 -0.0430175 -0.0292216 -0.036832 1 0 1 1 0 0 +EDGE2 2111 1770 -0.996328 -0.0247599 -1.55214 1 0 1 1 0 0 +EDGE2 2111 2070 -1.0053 0.0323561 -1.53532 1 0 1 1 0 0 +EDGE2 2111 2110 -1.01301 -0.0697333 1.55577 1 0 1 1 0 0 +EDGE2 2111 2030 -0.959948 0.0140808 1.56886 1 0 1 1 0 0 +EDGE2 2111 2032 1.04136 -0.0580931 -0.011089 1 0 1 1 0 0 +EDGE2 2111 1771 -0.0431852 0.000138957 -0.0368417 1 0 1 1 0 0 +EDGE2 2111 1772 1.0177 -0.0353598 0.00886801 1 0 1 1 0 0 +EDGE2 2112 2031 -1.02295 -0.000123469 -0.00125891 1 0 1 1 0 0 +EDGE2 2112 2111 -0.97377 0.0656096 0.0260466 1 0 1 1 0 0 +EDGE2 2112 2033 1.00376 0.0893618 0.0234729 1 0 1 1 0 0 +EDGE2 2112 2032 0.0948292 0.0332026 -0.0711405 1 0 1 1 0 0 +EDGE2 2112 1771 -0.95973 -0.0411265 0.0288917 1 0 1 1 0 0 +EDGE2 2112 1772 0.0221755 0.016046 0.00997619 1 0 1 1 0 0 +EDGE2 2112 1773 1.01112 -0.0152292 -0.039941 1 0 1 1 0 0 +EDGE2 2113 2033 0.0214689 -0.0218814 -0.0264728 1 0 1 1 0 0 +EDGE2 2113 2032 -1.08412 -0.00182486 0.00476743 1 0 1 1 0 0 +EDGE2 2113 2112 -1.00054 0.0446813 -0.0117084 1 0 1 1 0 0 +EDGE2 2113 1772 -0.965657 0.00663901 0.0202458 1 0 1 1 0 0 +EDGE2 2113 2034 0.957448 0.0699906 -0.00202312 1 0 1 1 0 0 +EDGE2 2113 1773 0.0415163 -0.0424298 0.00485451 1 0 1 1 0 0 +EDGE2 2113 1774 1.07321 -0.0192271 -0.0143044 1 0 1 1 0 0 +EDGE2 2114 2055 1.04904 -0.0207354 -3.12047 1 0 1 1 0 0 +EDGE2 2114 2033 -0.946869 0.0062116 -0.00686742 1 0 1 1 0 0 +EDGE2 2114 2113 -1.00167 -0.0568069 -0.0161574 1 0 1 1 0 0 +EDGE2 2114 2034 0.0424024 0.0492294 -0.00336042 1 0 1 1 0 0 +EDGE2 2114 1773 -0.950496 -0.0380122 -0.0219629 1 0 1 1 0 0 +EDGE2 2114 1774 -0.0735037 0.0364226 0.0183374 1 0 1 1 0 0 +EDGE2 2114 1775 0.978579 0.0248006 0.0315569 1 0 1 1 0 0 +EDGE2 2114 2035 0.996272 -0.0556722 0.0036541 1 0 1 1 0 0 +EDGE2 2115 2036 -0.0392524 -1.03163 -1.57703 1 0 1 1 0 0 +EDGE2 2115 1776 0.0848339 -0.952973 -1.57008 1 0 1 1 0 0 +EDGE2 2115 2055 -0.0728618 -0.00111868 -3.16889 1 0 1 1 0 0 +EDGE2 2115 2034 -1.05858 0.0617278 -0.0313116 1 0 1 1 0 0 +EDGE2 2115 2114 -1.06255 0.0117029 0.00134959 1 0 1 1 0 0 +EDGE2 2115 1774 -1.01801 -0.0505351 0.00356831 1 0 1 1 0 0 +EDGE2 2115 1775 0.0379211 0.00148825 0.0261973 1 0 1 1 0 0 +EDGE2 2115 2035 -0.00327963 0.0484166 -0.00645236 1 0 1 1 0 0 +EDGE2 2115 2056 0.0168224 0.98751 1.59045 1 0 1 1 0 0 +EDGE2 2115 2054 0.942327 -0.0209194 -3.12021 1 0 1 1 0 0 +EDGE2 2116 2055 -0.979648 0.000118157 1.59241 1 0 1 1 0 0 +EDGE2 2116 2115 -1.0621 0.0303404 -1.59426 1 0 1 1 0 0 +EDGE2 2116 1775 -0.957428 -0.011067 -1.54968 1 0 1 1 0 0 +EDGE2 2116 2035 -1.019 0.00419893 -1.56731 1 0 1 1 0 0 +EDGE2 2116 2056 -0.0323181 0.0827865 0.00496588 1 0 1 1 0 0 +EDGE2 2116 2057 0.968697 0.00522441 0.000371984 1 0 1 1 0 0 +EDGE2 2117 2116 -1.02897 0.0507525 -3.15061e-05 1 0 1 1 0 0 +EDGE2 2117 2056 -1.06016 0.0472808 -0.0131717 1 0 1 1 0 0 +EDGE2 2117 2057 0.0877517 -0.0109193 0.0122564 1 0 1 1 0 0 +EDGE2 2117 2058 1.06836 0.00910208 -0.0110186 1 0 1 1 0 0 +EDGE2 2118 2117 -0.963754 0.095809 0.0132844 1 0 1 1 0 0 +EDGE2 2118 2057 -0.957014 -0.00407833 -0.00268461 1 0 1 1 0 0 +EDGE2 2118 2058 -0.0335061 0.00153255 0.0137327 1 0 1 1 0 0 +EDGE2 2118 2059 0.998088 0.0796098 0.00790634 1 0 1 1 0 0 +EDGE2 2119 2118 -1.0618 -0.00793034 0.0322613 1 0 1 1 0 0 +EDGE2 2119 2058 -1.03658 -0.0245791 -0.0106727 1 0 1 1 0 0 +EDGE2 2119 2059 0.00747888 0.0768782 -0.0342538 1 0 1 1 0 0 +EDGE2 2119 2060 0.952697 -0.0333444 -0.0163433 1 0 1 1 0 0 +EDGE2 2119 1420 1.02695 0.0623987 -3.16454 1 0 1 1 0 0 +EDGE2 2119 1440 1.11282 0.085876 -3.13355 1 0 1 1 0 0 +EDGE2 2119 1760 1.03036 -0.0279408 -3.13564 1 0 1 1 0 0 +EDGE2 2119 1400 1.01036 -0.0248991 -3.16753 1 0 1 1 0 0 +EDGE2 2120 2119 -0.995385 0.0212753 -0.00523411 1 0 1 1 0 0 +EDGE2 2120 2059 -1.02647 0.0276763 0.0233169 1 0 1 1 0 0 +EDGE2 2120 2060 0.0233956 -0.010295 -0.0386243 1 0 1 1 0 0 +EDGE2 2120 1761 0.0143282 1.02949 1.56184 1 0 1 1 0 0 +EDGE2 2120 2061 0.129479 1.00342 1.60582 1 0 1 1 0 0 +EDGE2 2120 1420 -0.0445815 -0.0314426 -3.13767 1 0 1 1 0 0 +EDGE2 2120 1440 0.0751796 -0.0173639 -3.11964 1 0 1 1 0 0 +EDGE2 2120 1760 -0.0672784 0.0624051 -3.17418 1 0 1 1 0 0 +EDGE2 2120 1400 0.0623975 -0.0766294 -3.15116 1 0 1 1 0 0 +EDGE2 2120 1421 0.0678818 -1.11881 -1.57456 1 0 1 1 0 0 +EDGE2 2120 1441 -0.00699511 -0.984132 -1.56019 1 0 1 1 0 0 +EDGE2 2120 1401 0.0148432 -1.01822 -1.57649 1 0 1 1 0 0 +EDGE2 2120 1419 0.956802 -0.0478142 -3.1864 1 0 1 1 0 0 +EDGE2 2120 1759 1.01996 -0.0871324 -3.12208 1 0 1 1 0 0 +EDGE2 2120 1439 0.970511 -0.0368245 -3.17482 1 0 1 1 0 0 +EDGE2 2120 1399 0.922125 0.00692366 -3.10654 1 0 1 1 0 0 +EDGE2 2121 2062 0.95723 -0.0609666 -0.0107413 1 0 1 1 0 0 +EDGE2 2121 2060 -0.966137 0.0890762 -1.56605 1 0 1 1 0 0 +EDGE2 2121 1761 -0.0448875 -0.0962443 0.0239125 1 0 1 1 0 0 +EDGE2 2121 1762 0.994271 -0.0274739 0.00553838 1 0 1 1 0 0 +EDGE2 2121 2061 -0.0509815 -0.00675293 0.0140137 1 0 1 1 0 0 +EDGE2 2121 2120 -0.95302 0.0525633 -1.57497 1 0 1 1 0 0 +EDGE2 2121 1420 -1.0363 0.022528 1.5727 1 0 1 1 0 0 +EDGE2 2121 1440 -0.959391 0.00647622 1.54375 1 0 1 1 0 0 +EDGE2 2121 1760 -0.985105 -0.0846348 1.55716 1 0 1 1 0 0 +EDGE2 2121 1400 -0.990121 -0.0427813 1.57858 1 0 1 1 0 0 +EDGE2 2122 2062 -0.00543367 0.014351 -0.00562405 1 0 1 1 0 0 +EDGE2 2122 2063 1.08436 -0.00116884 0.00804677 1 0 1 1 0 0 +EDGE2 2122 1763 0.93943 0.00791176 -0.00751305 1 0 1 1 0 0 +EDGE2 2122 1761 -1.11114 -0.00443181 0.0306857 1 0 1 1 0 0 +EDGE2 2122 2121 -0.989952 -0.0288564 -0.0121534 1 0 1 1 0 0 +EDGE2 2122 1762 -0.0255395 0.0356069 0.015911 1 0 1 1 0 0 +EDGE2 2122 2061 -0.956105 0.00166083 -0.0417194 1 0 1 1 0 0 +EDGE2 2123 2062 -0.967028 0.0955054 0.0115402 1 0 1 1 0 0 +EDGE2 2123 2063 0.027001 -0.0495244 -0.0348709 1 0 1 1 0 0 +EDGE2 2123 1764 1.01779 0.109508 0.00541058 1 0 1 1 0 0 +EDGE2 2123 2064 0.957778 0.0313455 0.00103415 1 0 1 1 0 0 +EDGE2 2123 1763 0.0902569 0.0148158 0.0177371 1 0 1 1 0 0 +EDGE2 2123 2122 -0.96683 0.0122463 -0.00843763 1 0 1 1 0 0 +EDGE2 2123 1762 -0.935369 -0.0520348 0.00316514 1 0 1 1 0 0 +EDGE2 2124 1765 1.01253 0.0223597 0.0368958 1 0 1 1 0 0 +EDGE2 2124 2065 0.925291 -0.0188363 -0.0219726 1 0 1 1 0 0 +EDGE2 2124 2063 -1.03918 -0.002176 0.0368266 1 0 1 1 0 0 +EDGE2 2124 1764 0.0165955 -0.0692185 0.0154578 1 0 1 1 0 0 +EDGE2 2124 2064 -0.0329459 -0.0342488 -0.00163604 1 0 1 1 0 0 +EDGE2 2124 2123 -0.955951 -0.000906907 0.0198795 1 0 1 1 0 0 +EDGE2 2124 1763 -1.02947 0.0167777 -0.0313413 1 0 1 1 0 0 +EDGE2 2125 2066 -0.0840417 1.07117 1.54974 1 0 1 1 0 0 +EDGE2 2125 1766 -0.114318 0.96385 1.59608 1 0 1 1 0 0 +EDGE2 2125 2124 -1.07324 -0.0631846 -0.0142491 1 0 1 1 0 0 +EDGE2 2125 1765 0.0438516 -0.00331334 0.0344422 1 0 1 1 0 0 +EDGE2 2125 2065 -0.0390183 0.0292667 -0.0105669 1 0 1 1 0 0 +EDGE2 2125 1764 -0.994799 -0.0420432 -0.00251607 1 0 1 1 0 0 +EDGE2 2125 2064 -1.00337 0.0421382 -0.0204242 1 0 1 1 0 0 +EDGE2 2126 2066 0.0662128 0.0036597 0.030812 1 0 1 1 0 0 +EDGE2 2126 1767 1.00205 0.0393167 -0.0143622 1 0 1 1 0 0 +EDGE2 2126 2067 1.0682 -0.00248275 -0.0210313 1 0 1 1 0 0 +EDGE2 2126 1766 0.0261344 0.0288732 -0.0066177 1 0 1 1 0 0 +EDGE2 2126 1765 -0.96919 -0.00459971 -1.57841 1 0 1 1 0 0 +EDGE2 2126 2065 -0.993917 0.0992482 -1.55037 1 0 1 1 0 0 +EDGE2 2126 2125 -1.02876 -0.00537504 -1.60091 1 0 1 1 0 0 +EDGE2 2127 1768 0.971738 -0.0555182 0.0059376 1 0 1 1 0 0 +EDGE2 2127 2068 0.958961 -0.0566217 0.0279767 1 0 1 1 0 0 +EDGE2 2127 2066 -0.949012 -0.0658096 0.00589561 1 0 1 1 0 0 +EDGE2 2127 1767 -0.0447977 0.0604895 -0.0377962 1 0 1 1 0 0 +EDGE2 2127 2067 0.0228432 0.127512 0.0267901 1 0 1 1 0 0 +EDGE2 2127 2126 -1.05871 0.0347504 0.00131928 1 0 1 1 0 0 +EDGE2 2127 1766 -0.956018 -0.0317041 -0.0392394 1 0 1 1 0 0 +EDGE2 2128 1768 0.039142 -0.0773551 0.00850324 1 0 1 1 0 0 +EDGE2 2128 1769 1.02833 0.0824695 0.0502969 1 0 1 1 0 0 +EDGE2 2128 2069 1.02413 0.0473882 0.0233597 1 0 1 1 0 0 +EDGE2 2128 2068 0.0421494 0.0125335 0.0344858 1 0 1 1 0 0 +EDGE2 2128 1767 -1.03278 0.0175283 0.0242706 1 0 1 1 0 0 +EDGE2 2128 2127 -1.02746 -0.0697398 -0.0245693 1 0 1 1 0 0 +EDGE2 2128 2067 -0.989312 -0.0524644 -0.0186746 1 0 1 1 0 0 +EDGE2 2129 1770 0.946032 -0.0192594 0.0198042 1 0 1 1 0 0 +EDGE2 2129 2070 0.944347 -0.0523335 0.00211984 1 0 1 1 0 0 +EDGE2 2129 2110 0.90482 0.0201957 -3.14969 1 0 1 1 0 0 +EDGE2 2129 2030 1.02265 0.0396286 -3.1282 1 0 1 1 0 0 +EDGE2 2129 1768 -0.913199 0.0261001 -0.0347171 1 0 1 1 0 0 +EDGE2 2129 1769 0.146684 0.0415503 -0.0291998 1 0 1 1 0 0 +EDGE2 2129 2069 -0.0446853 -0.0650026 -0.0278136 1 0 1 1 0 0 +EDGE2 2129 2128 -0.994113 -0.0564965 0.0191885 1 0 1 1 0 0 +EDGE2 2129 2068 -1.02525 -0.0452652 -0.0285952 1 0 1 1 0 0 +EDGE2 2130 2031 0.00644329 1.08883 1.5448 1 0 1 1 0 0 +EDGE2 2130 2029 0.967655 0.0431124 -3.1433 1 0 1 1 0 0 +EDGE2 2130 2109 1.02156 -0.0581716 -3.13797 1 0 1 1 0 0 +EDGE2 2130 2071 0.0504805 -0.923154 -1.56987 1 0 1 1 0 0 +EDGE2 2130 1770 -0.0137817 0.0688501 -0.00492827 1 0 1 1 0 0 +EDGE2 2130 2070 0.0407453 0.0600664 -0.00426472 1 0 1 1 0 0 +EDGE2 2130 2110 -0.00226706 -0.0067987 -3.13729 1 0 1 1 0 0 +EDGE2 2130 2030 0.00972412 -0.00980523 -3.1627 1 0 1 1 0 0 +EDGE2 2130 2111 0.0509911 0.968896 1.58433 1 0 1 1 0 0 +EDGE2 2130 1771 -0.0116382 1.00651 1.56959 1 0 1 1 0 0 +EDGE2 2130 1769 -0.979921 -0.0519056 0.01661 1 0 1 1 0 0 +EDGE2 2130 2129 -1.03442 0.0191067 -0.0108855 1 0 1 1 0 0 +EDGE2 2130 2069 -1.03083 -0.00635786 -0.00601349 1 0 1 1 0 0 +EDGE2 2131 2031 0.05051 0.0218263 -0.00941524 1 0 1 1 0 0 +EDGE2 2131 1770 -0.934832 0.0399018 -1.58242 1 0 1 1 0 0 +EDGE2 2131 2070 -1.06498 -0.0496941 -1.59843 1 0 1 1 0 0 +EDGE2 2131 2110 -1.00315 0.00619677 1.56114 1 0 1 1 0 0 +EDGE2 2131 2130 -0.981242 -0.0584842 -1.5942 1 0 1 1 0 0 +EDGE2 2131 2030 -0.988207 -0.0568867 1.60395 1 0 1 1 0 0 +EDGE2 2131 2111 0.0241523 -0.0160355 0.00620322 1 0 1 1 0 0 +EDGE2 2131 2032 1.02296 0.0189532 0.010691 1 0 1 1 0 0 +EDGE2 2131 1771 0.0176606 0.0770694 -0.0171339 1 0 1 1 0 0 +EDGE2 2131 2112 0.973104 0.0404452 0.020003 1 0 1 1 0 0 +EDGE2 2131 1772 1.05882 0.127897 -0.00330267 1 0 1 1 0 0 +EDGE2 2132 2031 -1.13615 -0.0246521 -0.00559443 1 0 1 1 0 0 +EDGE2 2132 2131 -0.981372 -0.0423817 0.0195945 1 0 1 1 0 0 +EDGE2 2132 2111 -1.02737 0.0673695 -0.0297265 1 0 1 1 0 0 +EDGE2 2132 2033 1.02888 -0.00219127 0.0342471 1 0 1 1 0 0 +EDGE2 2132 2032 0.00648185 0.0224511 0.00855231 1 0 1 1 0 0 +EDGE2 2132 1771 -0.984248 0.0393846 -0.011714 1 0 1 1 0 0 +EDGE2 2132 2112 -0.0565508 0.0177493 -0.00200871 1 0 1 1 0 0 +EDGE2 2132 1772 0.0098627 0.00794153 0.0224302 1 0 1 1 0 0 +EDGE2 2132 2113 0.94897 0.00199076 0.0114176 1 0 1 1 0 0 +EDGE2 2132 1773 1.02058 -0.00572451 -0.0376892 1 0 1 1 0 0 +EDGE2 2133 2033 -0.0180411 0.0180678 0.00274969 1 0 1 1 0 0 +EDGE2 2133 2032 -1.0638 -0.0116489 0.0122665 1 0 1 1 0 0 +EDGE2 2133 2132 -0.953872 0.0401365 0.00237034 1 0 1 1 0 0 +EDGE2 2133 2112 -0.984206 0.022041 0.0116049 1 0 1 1 0 0 +EDGE2 2133 1772 -1.0004 0.0599585 0.00137104 1 0 1 1 0 0 +EDGE2 2133 2113 0.0155654 0.0172569 -0.0228548 1 0 1 1 0 0 +EDGE2 2133 2034 1.05618 0.0493705 0.0203457 1 0 1 1 0 0 +EDGE2 2133 1773 -0.0688041 -0.0512704 0.00616447 1 0 1 1 0 0 +EDGE2 2133 2114 1.05011 -0.0132926 -0.0180479 1 0 1 1 0 0 +EDGE2 2133 1774 0.9573 0.0597761 0.00951757 1 0 1 1 0 0 +EDGE2 2134 2055 0.935601 -0.0531536 -3.16639 1 0 1 1 0 0 +EDGE2 2134 2033 -0.97281 -0.0429713 -0.0154164 1 0 1 1 0 0 +EDGE2 2134 2133 -0.988288 -0.0327684 0.0265888 1 0 1 1 0 0 +EDGE2 2134 2113 -0.93359 0.0297447 0.00456672 1 0 1 1 0 0 +EDGE2 2134 2034 0.0302459 0.0217298 -0.00176522 1 0 1 1 0 0 +EDGE2 2134 1773 -0.990388 0.063863 -0.0084871 1 0 1 1 0 0 +EDGE2 2134 2114 -0.011403 0.0205443 0.0124145 1 0 1 1 0 0 +EDGE2 2134 1774 0.041707 0.0570125 -0.0122849 1 0 1 1 0 0 +EDGE2 2134 2115 1.02664 -0.0136897 -0.0155646 1 0 1 1 0 0 +EDGE2 2134 1775 1.03299 0.0113838 -0.0154616 1 0 1 1 0 0 +EDGE2 2134 2035 0.955011 0.144081 -0.0143669 1 0 1 1 0 0 +EDGE2 2135 2036 -0.0317956 -0.974603 -1.53248 1 0 1 1 0 0 +EDGE2 2135 1776 0.0491819 -0.985891 -1.57114 1 0 1 1 0 0 +EDGE2 2135 2055 0.00858784 -0.0115934 -3.14643 1 0 1 1 0 0 +EDGE2 2135 2034 -1.04092 0.084666 -0.0255083 1 0 1 1 0 0 +EDGE2 2135 2134 -0.926256 0.0327771 0.0332607 1 0 1 1 0 0 +EDGE2 2135 2114 -1.08279 -0.0543691 -0.00685658 1 0 1 1 0 0 +EDGE2 2135 1774 -1.04035 -0.0235174 0.0229116 1 0 1 1 0 0 +EDGE2 2135 2115 0.0310311 0.0108819 -0.0181542 1 0 1 1 0 0 +EDGE2 2135 2116 -0.0437798 1.00845 1.58777 1 0 1 1 0 0 +EDGE2 2135 1775 -0.0632006 -0.0088647 -0.00242807 1 0 1 1 0 0 +EDGE2 2135 2035 0.00947675 -0.0501069 0.0363812 1 0 1 1 0 0 +EDGE2 2135 2056 -0.0526073 0.989391 1.58935 1 0 1 1 0 0 +EDGE2 2135 2054 1.02071 -0.0102113 -3.15348 1 0 1 1 0 0 +EDGE2 2136 2117 0.985712 -0.0429884 0.0215282 1 0 1 1 0 0 +EDGE2 2136 2055 -1.0727 -0.0156858 1.538 1 0 1 1 0 0 +EDGE2 2136 2135 -1.0753 0.0314819 -1.58821 1 0 1 1 0 0 +EDGE2 2136 2115 -0.988884 -0.01292 -1.53819 1 0 1 1 0 0 +EDGE2 2136 2116 0.0233877 0.025507 -0.00665764 1 0 1 1 0 0 +EDGE2 2136 1775 -0.968255 -0.0344263 -1.57516 1 0 1 1 0 0 +EDGE2 2136 2035 -1.05087 0.0290139 -1.55421 1 0 1 1 0 0 +EDGE2 2136 2056 -0.0187041 0.0398392 -0.00965872 1 0 1 1 0 0 +EDGE2 2136 2057 0.931922 0.0448532 -0.0125544 1 0 1 1 0 0 +EDGE2 2137 2117 -0.0794599 -0.0513178 -0.00443321 1 0 1 1 0 0 +EDGE2 2137 2116 -1.11167 0.0480245 -0.0327877 1 0 1 1 0 0 +EDGE2 2137 2136 -1.02245 -0.00598409 -0.0226187 1 0 1 1 0 0 +EDGE2 2137 2056 -1.03937 0.0598943 -0.0270745 1 0 1 1 0 0 +EDGE2 2137 2057 -0.0240558 0.0124696 0.0191601 1 0 1 1 0 0 +EDGE2 2137 2118 1.02511 0.0437808 0.0029782 1 0 1 1 0 0 +EDGE2 2137 2058 1.01896 -0.0267783 -0.0089259 1 0 1 1 0 0 +EDGE2 2138 2117 -0.981585 0.0434842 0.00094317 1 0 1 1 0 0 +EDGE2 2138 2137 -0.945581 0.0939661 0.0213716 1 0 1 1 0 0 +EDGE2 2138 2057 -1.0264 0.042036 -0.0100941 1 0 1 1 0 0 +EDGE2 2138 2118 -0.0208841 0.0360138 0.00613906 1 0 1 1 0 0 +EDGE2 2138 2058 -0.0761977 -0.0497238 0.0101612 1 0 1 1 0 0 +EDGE2 2138 2119 0.914283 0.0123164 0.0203723 1 0 1 1 0 0 +EDGE2 2138 2059 1.06456 0.0484995 0.00410986 1 0 1 1 0 0 +EDGE2 2139 2118 -0.989125 0.0629565 -0.0147081 1 0 1 1 0 0 +EDGE2 2139 2138 -1.01333 -0.0368171 -0.00417494 1 0 1 1 0 0 +EDGE2 2139 2058 -1.01661 0.0114938 0.00554392 1 0 1 1 0 0 +EDGE2 2139 2119 0.0532085 0.0452969 0.0386636 1 0 1 1 0 0 +EDGE2 2139 2059 0.040179 0.0222588 -0.0173383 1 0 1 1 0 0 +EDGE2 2139 2060 0.935669 0.0262909 -0.00738662 1 0 1 1 0 0 +EDGE2 2139 2120 1.0041 0.0507642 -0.0292668 1 0 1 1 0 0 +EDGE2 2139 1420 1.00434 0.0570851 -3.12593 1 0 1 1 0 0 +EDGE2 2139 1440 1.03349 -0.0382724 -3.16017 1 0 1 1 0 0 +EDGE2 2139 1760 0.956614 0.0414972 -3.1647 1 0 1 1 0 0 +EDGE2 2139 1400 1.03375 -0.0190431 -3.12039 1 0 1 1 0 0 +EDGE2 2140 2119 -1.05177 -0.0348297 -0.00151519 1 0 1 1 0 0 +EDGE2 2140 2139 -1.02082 -0.0577717 -0.0082233 1 0 1 1 0 0 +EDGE2 2140 2059 -0.977615 -0.0537744 -0.0250101 1 0 1 1 0 0 +EDGE2 2140 2060 0.057373 0.0967994 -0.0292126 1 0 1 1 0 0 +EDGE2 2140 1761 0.00630683 1.00233 1.54678 1 0 1 1 0 0 +EDGE2 2140 2121 0.0120936 1.02809 1.58273 1 0 1 1 0 0 +EDGE2 2140 2061 -0.0314984 1.00206 1.58063 1 0 1 1 0 0 +EDGE2 2140 2120 -0.00889272 -0.0381287 0.027195 1 0 1 1 0 0 +EDGE2 2140 1420 0.0606329 -0.0227663 -3.1392 1 0 1 1 0 0 +EDGE2 2140 1440 -0.030841 0.0489055 -3.14178 1 0 1 1 0 0 +EDGE2 2140 1760 0.00617007 -0.020092 -3.14895 1 0 1 1 0 0 +EDGE2 2140 1400 -0.0382925 0.0355926 -3.116 1 0 1 1 0 0 +EDGE2 2140 1421 -0.0436642 -1.033 -1.5631 1 0 1 1 0 0 +EDGE2 2140 1441 -0.048517 -1.00822 -1.55992 1 0 1 1 0 0 +EDGE2 2140 1401 -0.0319911 -1.03078 -1.59618 1 0 1 1 0 0 +EDGE2 2140 1419 1.05643 -0.0339835 -3.12093 1 0 1 1 0 0 +EDGE2 2140 1759 0.998243 -0.0212021 -3.16627 1 0 1 1 0 0 +EDGE2 2140 1439 1.01572 0.0335978 -3.10909 1 0 1 1 0 0 +EDGE2 2140 1399 0.918345 0.00782832 -3.15577 1 0 1 1 0 0 +EDGE2 2141 2062 0.919043 -0.0990335 -0.00332162 1 0 1 1 0 0 +EDGE2 2141 2122 0.968348 0.0185552 0.018825 1 0 1 1 0 0 +EDGE2 2141 2060 -0.940843 -0.0451073 -1.56021 1 0 1 1 0 0 +EDGE2 2141 1761 -0.0652839 0.0695102 -0.02094 1 0 1 1 0 0 +EDGE2 2141 2121 0.0423214 0.0112048 0.0234356 1 0 1 1 0 0 +EDGE2 2141 1762 1.0925 0.00605762 0.0269634 1 0 1 1 0 0 +EDGE2 2141 2061 0.0739603 -0.0735255 0.000177775 1 0 1 1 0 0 +EDGE2 2141 2140 -1.01477 -0.0160286 -1.57313 1 0 1 1 0 0 +EDGE2 2141 2120 -0.987545 -0.0151765 -1.56482 1 0 1 1 0 0 +EDGE2 2141 1420 -1.00946 0.0333799 1.55832 1 0 1 1 0 0 +EDGE2 2141 1440 -0.99205 0.145742 1.55324 1 0 1 1 0 0 +EDGE2 2141 1760 -1.08217 0.0731162 1.59015 1 0 1 1 0 0 +EDGE2 2141 1400 -0.986446 -0.0721182 1.60813 1 0 1 1 0 0 +EDGE2 2142 2062 0.0274019 0.0953217 0.0104806 1 0 1 1 0 0 +EDGE2 2142 2063 0.972991 -0.0623394 -0.0216414 1 0 1 1 0 0 +EDGE2 2142 2123 0.979189 -0.0208516 0.00728185 1 0 1 1 0 0 +EDGE2 2142 1763 1.07914 0.0279393 -0.031546 1 0 1 1 0 0 +EDGE2 2142 2122 -0.0051291 0.0123718 -0.0120194 1 0 1 1 0 0 +EDGE2 2142 1761 -0.93769 0.0720888 -0.00784004 1 0 1 1 0 0 +EDGE2 2142 2121 -1.01191 -0.00859257 -0.00999056 1 0 1 1 0 0 +EDGE2 2142 2141 -0.942976 0.00992733 0.0386113 1 0 1 1 0 0 +EDGE2 2142 1762 -0.0670512 -0.00388939 -0.0263189 1 0 1 1 0 0 +EDGE2 2142 2061 -0.957107 0.0479833 -0.0151287 1 0 1 1 0 0 +EDGE2 2143 2062 -1.04618 -0.0193152 -0.00905739 1 0 1 1 0 0 +EDGE2 2143 2124 0.958291 0.000963069 0.00580546 1 0 1 1 0 0 +EDGE2 2143 2063 0.0494016 -0.053348 -0.0385155 1 0 1 1 0 0 +EDGE2 2143 1764 0.975717 -0.0664229 0.0104597 1 0 1 1 0 0 +EDGE2 2143 2064 0.997768 -0.0447196 -0.00448337 1 0 1 1 0 0 +EDGE2 2143 2123 -0.0039596 -0.0258277 0.0121204 1 0 1 1 0 0 +EDGE2 2143 2142 -1.06191 -0.00729354 -0.00389805 1 0 1 1 0 0 +EDGE2 2143 1763 -0.0145879 0.00305901 0.0329244 1 0 1 1 0 0 +EDGE2 2143 2122 -0.979698 -0.00137356 -0.0438078 1 0 1 1 0 0 +EDGE2 2143 1762 -0.970178 0.0187638 0.0107331 1 0 1 1 0 0 +EDGE2 2144 2124 0.0026569 0.00511299 -0.0163317 1 0 1 1 0 0 +EDGE2 2144 1765 0.982977 -0.0235982 -0.0120299 1 0 1 1 0 0 +EDGE2 2144 2065 0.969918 -0.000255854 -0.00367856 1 0 1 1 0 0 +EDGE2 2144 2125 1.0164 0.072227 -0.0460538 1 0 1 1 0 0 +EDGE2 2144 2063 -1.0384 0.0414788 -0.0073614 1 0 1 1 0 0 +EDGE2 2144 2143 -1.01022 0.134819 0.0430942 1 0 1 1 0 0 +EDGE2 2144 1764 -0.0169396 0.0522081 0.0104241 1 0 1 1 0 0 +EDGE2 2144 2064 -0.00843171 0.0272033 -0.025827 1 0 1 1 0 0 +EDGE2 2144 2123 -0.938382 -0.0609824 -0.0107155 1 0 1 1 0 0 +EDGE2 2144 1763 -1.02678 0.0464617 0.00413197 1 0 1 1 0 0 +EDGE2 2145 2066 -0.0281287 1.03151 1.58547 1 0 1 1 0 0 +EDGE2 2145 2126 0.0288166 1.04823 1.55683 1 0 1 1 0 0 +EDGE2 2145 1766 -0.00194843 0.931142 1.63222 1 0 1 1 0 0 +EDGE2 2145 2124 -1.12298 -0.0148346 0.024851 1 0 1 1 0 0 +EDGE2 2145 1765 0.0205137 0.0569806 0.00325317 1 0 1 1 0 0 +EDGE2 2145 2065 -0.0324178 -0.0744966 -0.0251125 1 0 1 1 0 0 +EDGE2 2145 2125 -0.00741265 -0.0469085 0.0176661 1 0 1 1 0 0 +EDGE2 2145 2144 -0.980218 -0.00920543 0.0173801 1 0 1 1 0 0 +EDGE2 2145 1764 -1.01789 -0.0915957 0.0482522 1 0 1 1 0 0 +EDGE2 2145 2064 -1.01378 -0.0342162 -0.0242909 1 0 1 1 0 0 +EDGE2 2146 2066 -0.0416859 -0.00445669 -0.0219009 1 0 1 1 0 0 +EDGE2 2146 1767 0.99087 0.049725 0.0195482 1 0 1 1 0 0 +EDGE2 2146 2127 0.995027 -0.0259581 0.00679813 1 0 1 1 0 0 +EDGE2 2146 2067 0.957839 -0.0730827 0.00651767 1 0 1 1 0 0 +EDGE2 2146 2126 -0.0291707 0.0101312 -0.02727 1 0 1 1 0 0 +EDGE2 2146 1766 -0.0171773 -0.0614932 0.00510234 1 0 1 1 0 0 +EDGE2 2146 2145 -0.924126 -0.00338023 -1.58238 1 0 1 1 0 0 +EDGE2 2146 1765 -0.982637 -0.0151409 -1.60107 1 0 1 1 0 0 +EDGE2 2146 2065 -1.01824 0.0830237 -1.61355 1 0 1 1 0 0 +EDGE2 2146 2125 -1.01436 -0.0199971 -1.55902 1 0 1 1 0 0 +EDGE2 2147 1768 0.999137 0.114562 0.0246687 1 0 1 1 0 0 +EDGE2 2147 2128 0.985815 -0.00472245 -0.0108413 1 0 1 1 0 0 +EDGE2 2147 2068 0.995126 0.00232037 0.00110351 1 0 1 1 0 0 +EDGE2 2147 2066 -0.965356 0.0270971 -0.0354506 1 0 1 1 0 0 +EDGE2 2147 1767 -0.0133459 0.0295678 0.0171941 1 0 1 1 0 0 +EDGE2 2147 2127 -0.0913134 -0.0303879 -0.0161037 1 0 1 1 0 0 +EDGE2 2147 2067 -0.0374851 0.0448755 -0.0158587 1 0 1 1 0 0 +EDGE2 2147 2126 -1.05096 -0.0127667 0.0429862 1 0 1 1 0 0 +EDGE2 2147 2146 -0.983925 0.041369 0.00775468 1 0 1 1 0 0 +EDGE2 2147 1766 -1.01457 -0.0209982 0.0402171 1 0 1 1 0 0 +EDGE2 2148 1768 -0.0765663 -0.0430005 -0.0368574 1 0 1 1 0 0 +EDGE2 2148 1769 0.954126 0.130841 -0.00834334 1 0 1 1 0 0 +EDGE2 2148 2129 0.972108 0.0870903 -0.0102388 1 0 1 1 0 0 +EDGE2 2148 2069 0.996129 -0.00689945 -0.0431852 1 0 1 1 0 0 +EDGE2 2148 2128 0.0441863 0.016278 0.0185926 1 0 1 1 0 0 +EDGE2 2148 2068 0.000964008 -0.00456855 0.0310087 1 0 1 1 0 0 +EDGE2 2148 1767 -0.904377 0.0449246 -0.0123226 1 0 1 1 0 0 +EDGE2 2148 2127 -0.951134 0.0606908 0.0470292 1 0 1 1 0 0 +EDGE2 2148 2147 -1.0713 -0.00997429 0.00568354 1 0 1 1 0 0 +EDGE2 2148 2067 -1.01741 0.0656124 0.0268899 1 0 1 1 0 0 +EDGE2 2149 1770 1.01249 -0.142513 -0.0108624 1 0 1 1 0 0 +EDGE2 2149 2070 1.0431 -0.025551 -0.0147354 1 0 1 1 0 0 +EDGE2 2149 2110 0.900655 0.00986393 -3.10194 1 0 1 1 0 0 +EDGE2 2149 2130 1.00749 -0.0354626 -0.017853 1 0 1 1 0 0 +EDGE2 2149 2030 0.964912 -0.0171075 -3.15339 1 0 1 1 0 0 +EDGE2 2149 1768 -0.998561 -0.000491829 0.0120647 1 0 1 1 0 0 +EDGE2 2149 1769 0.024981 -0.0153941 0.0183681 1 0 1 1 0 0 +EDGE2 2149 2129 0.11085 0.0504977 0.0128851 1 0 1 1 0 0 +EDGE2 2149 2069 0.0607463 -0.0976818 -0.00866014 1 0 1 1 0 0 +EDGE2 2149 2128 -0.955171 -0.0463886 0.00753196 1 0 1 1 0 0 +EDGE2 2149 2148 -0.983603 0.115327 0.0390148 1 0 1 1 0 0 +EDGE2 2149 2068 -0.985828 -0.0225632 0.0383619 1 0 1 1 0 0 +EDGE2 2150 2031 0.0779402 1.01442 1.56007 1 0 1 1 0 0 +EDGE2 2150 2029 0.982819 0.129393 -3.11634 1 0 1 1 0 0 +EDGE2 2150 2109 0.971696 -0.00842702 -3.15046 1 0 1 1 0 0 +EDGE2 2150 2071 -0.0505193 -0.922037 -1.55886 1 0 1 1 0 0 +EDGE2 2150 1770 -0.00156449 0.0711679 0.00148242 1 0 1 1 0 0 +EDGE2 2150 2070 0.0388335 -0.0717624 0.0175031 1 0 1 1 0 0 +EDGE2 2150 2110 0.055015 0.0014011 -3.11114 1 0 1 1 0 0 +EDGE2 2150 2130 0.0550182 0.0293224 0.0245622 1 0 1 1 0 0 +EDGE2 2150 2030 -0.0187848 -0.00936618 -3.1378 1 0 1 1 0 0 +EDGE2 2150 2131 -0.0363553 0.955636 1.55898 1 0 1 1 0 0 +EDGE2 2150 2111 0.0124872 1.01398 1.54783 1 0 1 1 0 0 +EDGE2 2150 1771 -0.057691 1.02705 1.56704 1 0 1 1 0 0 +EDGE2 2150 1769 -1.01294 0.0349429 0.0149898 1 0 1 1 0 0 +EDGE2 2150 2129 -1.09127 -0.00483189 -0.0337149 1 0 1 1 0 0 +EDGE2 2150 2149 -0.916494 -0.0111012 -0.0243648 1 0 1 1 0 0 +EDGE2 2150 2069 -0.995101 0.0308637 -0.0145533 1 0 1 1 0 0 +EDGE2 2151 2031 0.0383566 0.00558518 0.0109489 1 0 1 1 0 0 +EDGE2 2151 2150 -0.962209 0.0347526 -1.59014 1 0 1 1 0 0 +EDGE2 2151 1770 -1.06269 -0.0463538 -1.58458 1 0 1 1 0 0 +EDGE2 2151 2070 -0.962176 0.0015052 -1.5909 1 0 1 1 0 0 +EDGE2 2151 2110 -1.01297 -0.150565 1.56985 1 0 1 1 0 0 +EDGE2 2151 2130 -1.03496 -0.00284747 -1.56765 1 0 1 1 0 0 +EDGE2 2151 2030 -0.988159 -0.0302927 1.60518 1 0 1 1 0 0 +EDGE2 2151 2131 -0.0277533 0.0499653 0.0346786 1 0 1 1 0 0 +EDGE2 2151 2111 -0.00889112 0.0478691 -0.00874927 1 0 1 1 0 0 +EDGE2 2151 2032 0.943815 -0.000267299 -0.0220528 1 0 1 1 0 0 +EDGE2 2151 2132 0.945164 0.0169028 0.0237803 1 0 1 1 0 0 +EDGE2 2151 1771 0.00770296 -0.0212146 0.00204412 1 0 1 1 0 0 +EDGE2 2151 2112 0.983723 -0.0558071 -0.0423173 1 0 1 1 0 0 +EDGE2 2151 1772 1.05941 -0.0560329 0.00515916 1 0 1 1 0 0 +EDGE2 2152 2031 -0.97255 0.0812907 0.0161338 1 0 1 1 0 0 +EDGE2 2152 2131 -1.07235 -0.0175878 -0.00609396 1 0 1 1 0 0 +EDGE2 2152 2151 -0.964006 0.00915322 -0.011781 1 0 1 1 0 0 +EDGE2 2152 2111 -0.949178 0.047174 -0.00410907 1 0 1 1 0 0 +EDGE2 2152 2033 1.00374 -0.057827 0.000693533 1 0 1 1 0 0 +EDGE2 2152 2032 -0.107185 0.0132926 -0.0386537 1 0 1 1 0 0 +EDGE2 2152 2132 0.041485 0.11101 0.0429635 1 0 1 1 0 0 +EDGE2 2152 1771 -1.03739 0.0457296 -0.0273784 1 0 1 1 0 0 +EDGE2 2152 2112 0.0123759 -0.0533267 0.0352847 1 0 1 1 0 0 +EDGE2 2152 2133 0.981366 -0.0833606 -0.0121508 1 0 1 1 0 0 +EDGE2 2152 1772 -0.0907211 0.0165932 -0.0253797 1 0 1 1 0 0 +EDGE2 2152 2113 0.918696 -0.0503031 0.00493612 1 0 1 1 0 0 +EDGE2 2152 1773 1.07347 0.0588579 -0.0458253 1 0 1 1 0 0 +EDGE2 2153 2033 -0.0327026 -0.0135233 0.0184951 1 0 1 1 0 0 +EDGE2 2153 2032 -1.01087 -0.0351265 0.039465 1 0 1 1 0 0 +EDGE2 2153 2132 -1.04432 -0.0180234 -0.0024872 1 0 1 1 0 0 +EDGE2 2153 2152 -0.996689 -0.0794339 -0.0120804 1 0 1 1 0 0 +EDGE2 2153 2112 -1.01849 -0.00168807 0.0222188 1 0 1 1 0 0 +EDGE2 2153 2133 -0.00571872 -0.0271016 0.0127416 1 0 1 1 0 0 +EDGE2 2153 1772 -0.950697 -0.0331099 -0.0273368 1 0 1 1 0 0 +EDGE2 2153 2113 0.0451084 -0.000485517 -0.0215513 1 0 1 1 0 0 +EDGE2 2153 2034 1.0031 0.0119146 0.0138802 1 0 1 1 0 0 +EDGE2 2153 2134 1.07738 0.0253669 -0.00794568 1 0 1 1 0 0 +EDGE2 2153 1773 -0.035697 -0.0584871 -0.0106129 1 0 1 1 0 0 +EDGE2 2153 2114 0.981247 -0.013623 -0.0226365 1 0 1 1 0 0 +EDGE2 2153 1774 1.00017 -0.085448 -0.0570329 1 0 1 1 0 0 +EDGE2 2154 2055 1.10186 0.0122557 -3.14063 1 0 1 1 0 0 +EDGE2 2154 2033 -0.967002 -0.0623595 -0.00131179 1 0 1 1 0 0 +EDGE2 2154 2133 -0.913073 -0.043056 6.04156e-05 1 0 1 1 0 0 +EDGE2 2154 2153 -1.0058 -0.104584 -0.024797 1 0 1 1 0 0 +EDGE2 2154 2113 -0.994807 0.104614 0.0195563 1 0 1 1 0 0 +EDGE2 2154 2034 0.0412066 0.131224 -0.00556407 1 0 1 1 0 0 +EDGE2 2154 2134 -0.0637556 0.093065 -0.00858285 1 0 1 1 0 0 +EDGE2 2154 1773 -0.956062 -0.0802569 0.00480149 1 0 1 1 0 0 +EDGE2 2154 2114 -0.0600149 -0.0433362 0.0452994 1 0 1 1 0 0 +EDGE2 2154 2135 1.06493 0.00548445 0.00981909 1 0 1 1 0 0 +EDGE2 2154 1774 -0.0836456 0.0548278 0.000812056 1 0 1 1 0 0 +EDGE2 2154 2115 1.04703 -0.0120987 0.0123449 1 0 1 1 0 0 +EDGE2 2154 1775 0.990395 -0.0159136 0.0192883 1 0 1 1 0 0 +EDGE2 2154 2035 0.971709 -0.00595075 -0.0280341 1 0 1 1 0 0 +EDGE2 2155 2036 -0.0131398 -0.999248 -1.61036 1 0 1 1 0 0 +EDGE2 2155 1776 0.0307315 -1.03328 -1.57951 1 0 1 1 0 0 +EDGE2 2155 2055 -0.0121844 -0.0267689 -3.1449 1 0 1 1 0 0 +EDGE2 2155 2034 -1.09017 -0.0782261 -0.0383449 1 0 1 1 0 0 +EDGE2 2155 2134 -0.944689 -0.0382336 -0.0232296 1 0 1 1 0 0 +EDGE2 2155 2154 -1.01717 -0.021274 -0.0445014 1 0 1 1 0 0 +EDGE2 2155 2114 -1.09619 -0.0673838 0.0101295 1 0 1 1 0 0 +EDGE2 2155 2135 -0.0252368 0.00109343 0.0413344 1 0 1 1 0 0 +EDGE2 2155 1774 -1.02066 -0.0280212 0.00696114 1 0 1 1 0 0 +EDGE2 2155 2115 -0.0399096 0.0139647 -0.0260379 1 0 1 1 0 0 +EDGE2 2155 2116 0.0391872 0.981119 1.53893 1 0 1 1 0 0 +EDGE2 2155 1775 -0.0795056 -0.056011 -0.0189584 1 0 1 1 0 0 +EDGE2 2155 2035 0.00617699 -0.0534773 0.01508 1 0 1 1 0 0 +EDGE2 2155 2136 -0.0109961 0.891476 1.56983 1 0 1 1 0 0 +EDGE2 2155 2056 0.0734421 0.935821 1.57445 1 0 1 1 0 0 +EDGE2 2155 2054 0.970232 -0.0945339 -3.18381 1 0 1 1 0 0 +EDGE2 2156 2117 1.02219 -0.00308621 0.00806564 1 0 1 1 0 0 +EDGE2 2156 2055 -1.08137 -0.122963 1.59782 1 0 1 1 0 0 +EDGE2 2156 2135 -0.925095 -0.0372533 -1.55697 1 0 1 1 0 0 +EDGE2 2156 2155 -1.05244 -0.0354571 -1.58522 1 0 1 1 0 0 +EDGE2 2156 2115 -1.02161 -0.0231534 -1.58255 1 0 1 1 0 0 +EDGE2 2156 2116 -0.0207834 -0.0471509 -0.025427 1 0 1 1 0 0 +EDGE2 2156 1775 -0.900254 0.0259227 -1.58229 1 0 1 1 0 0 +EDGE2 2156 2035 -0.926598 0.0649076 -1.57367 1 0 1 1 0 0 +EDGE2 2156 2136 -0.0110056 -0.0676493 0.0114276 1 0 1 1 0 0 +EDGE2 2156 2056 0.0377565 0.0873145 0.0186249 1 0 1 1 0 0 +EDGE2 2156 2137 0.93683 0.00526891 -0.0128303 1 0 1 1 0 0 +EDGE2 2156 2057 0.916954 0.0260657 0.00674878 1 0 1 1 0 0 +EDGE2 2157 2117 -0.0116672 -0.0734999 -0.0018203 1 0 1 1 0 0 +EDGE2 2157 2116 -0.938876 -0.0425026 -0.0220027 1 0 1 1 0 0 +EDGE2 2157 2156 -1.0458 -0.038232 0.0119803 1 0 1 1 0 0 +EDGE2 2157 2136 -1.05811 0.00401652 0.00361491 1 0 1 1 0 0 +EDGE2 2157 2056 -1.01383 0.107717 0.0170109 1 0 1 1 0 0 +EDGE2 2157 2137 -0.0157515 -0.00643121 -0.00887667 1 0 1 1 0 0 +EDGE2 2157 2057 -0.0377315 0.00348972 0.0202597 1 0 1 1 0 0 +EDGE2 2157 2118 0.938411 0.0657364 0.0768158 1 0 1 1 0 0 +EDGE2 2157 2138 1.02366 0.00707999 -0.0158587 1 0 1 1 0 0 +EDGE2 2157 2058 1.13596 0.026482 0.00855017 1 0 1 1 0 0 +EDGE2 2158 2117 -0.987921 0.0698489 -0.0121112 1 0 1 1 0 0 +EDGE2 2158 2157 -0.945042 0.0280148 0.00900763 1 0 1 1 0 0 +EDGE2 2158 2137 -0.910104 -0.0766604 0.0168465 1 0 1 1 0 0 +EDGE2 2158 2057 -0.985554 -0.0084293 -0.0179406 1 0 1 1 0 0 +EDGE2 2158 2118 -0.0505681 -0.0526429 0.0259383 1 0 1 1 0 0 +EDGE2 2158 2138 0.013704 -0.0173082 0.00277606 1 0 1 1 0 0 +EDGE2 2158 2058 -0.00117117 -0.0260766 0.00254365 1 0 1 1 0 0 +EDGE2 2158 2119 1.04599 -0.026415 -0.0213984 1 0 1 1 0 0 +EDGE2 2158 2139 1.05706 -0.00246163 0.00786481 1 0 1 1 0 0 +EDGE2 2158 2059 0.973486 -0.0830937 0.0226076 1 0 1 1 0 0 +EDGE2 2159 2118 -0.962761 -0.10109 -0.0103992 1 0 1 1 0 0 +EDGE2 2159 2138 -0.991052 0.00164175 -0.00533341 1 0 1 1 0 0 +EDGE2 2159 2158 -0.957929 -0.0241907 -0.00854185 1 0 1 1 0 0 +EDGE2 2159 2058 -1.02649 0.0424568 0.0199016 1 0 1 1 0 0 +EDGE2 2159 2119 0.034583 0.019147 -0.0349373 1 0 1 1 0 0 +EDGE2 2159 2139 0.00336203 0.0535123 -0.0283343 1 0 1 1 0 0 +EDGE2 2159 2059 0.0771458 -0.0810224 0.00762926 1 0 1 1 0 0 +EDGE2 2159 2060 0.971299 0.0181986 -0.00906204 1 0 1 1 0 0 +EDGE2 2159 2140 1.02054 0.00806835 0.0107156 1 0 1 1 0 0 +EDGE2 2159 2120 1.03932 -0.00430184 0.00339393 1 0 1 1 0 0 +EDGE2 2159 1420 1.10362 -0.00947109 -3.12417 1 0 1 1 0 0 +EDGE2 2159 1440 1.03449 0.0909414 -3.13243 1 0 1 1 0 0 +EDGE2 2159 1760 0.981366 0.0748872 -3.1659 1 0 1 1 0 0 +EDGE2 2159 1400 0.961723 0.0168108 -3.14428 1 0 1 1 0 0 +EDGE2 2160 2119 -0.923066 0.0302641 0.00616334 1 0 1 1 0 0 +EDGE2 2160 2139 -1.00457 0.0489027 -0.0308056 1 0 1 1 0 0 +EDGE2 2160 2159 -0.948492 0.0286304 0.00420153 1 0 1 1 0 0 +EDGE2 2160 2059 -1.07113 0.0388267 0.0040935 1 0 1 1 0 0 +EDGE2 2160 2060 0.0240412 -0.0608532 -0.01071 1 0 1 1 0 0 +EDGE2 2160 1761 0.0316742 0.956432 1.60667 1 0 1 1 0 0 +EDGE2 2160 2121 -0.0243597 0.995726 1.56615 1 0 1 1 0 0 +EDGE2 2160 2141 -0.0767397 1.08493 1.57418 1 0 1 1 0 0 +EDGE2 2160 2061 0.12063 0.928251 1.58681 1 0 1 1 0 0 +EDGE2 2160 2140 0.0382808 -0.0895761 0.0134341 1 0 1 1 0 0 +EDGE2 2160 2120 0.117579 -0.0399614 -0.0181253 1 0 1 1 0 0 +EDGE2 2160 1420 -0.0621775 0.010681 -3.14914 1 0 1 1 0 0 +EDGE2 2160 1440 -0.0347934 -0.0409953 -3.14206 1 0 1 1 0 0 +EDGE2 2160 1760 0.0256843 0.00491113 -3.1327 1 0 1 1 0 0 +EDGE2 2160 1400 0.00560932 -0.0016794 -3.1256 1 0 1 1 0 0 +EDGE2 2160 1421 -0.0363902 -0.961125 -1.56688 1 0 1 1 0 0 +EDGE2 2160 1441 -0.0941894 -0.93257 -1.5811 1 0 1 1 0 0 +EDGE2 2160 1401 -0.0443448 -1.09755 -1.57577 1 0 1 1 0 0 +EDGE2 2160 1419 1.06765 0.0735164 -3.14617 1 0 1 1 0 0 +EDGE2 2160 1759 0.940133 -0.0442674 -3.14698 1 0 1 1 0 0 +EDGE2 2160 1439 0.942638 0.0558055 -3.1332 1 0 1 1 0 0 +EDGE2 2160 1399 1.09494 -0.00694803 -3.10761 1 0 1 1 0 0 +EDGE2 2161 1422 1.05322 -0.0202488 -0.00805645 1 0 1 1 0 0 +EDGE2 2161 2060 -1.05484 -0.047882 1.57594 1 0 1 1 0 0 +EDGE2 2161 2140 -1.06624 0.0111216 1.57065 1 0 1 1 0 0 +EDGE2 2161 2160 -0.953976 -0.00562038 1.55331 1 0 1 1 0 0 +EDGE2 2161 2120 -0.966058 0.0974957 1.5916 1 0 1 1 0 0 +EDGE2 2161 1420 -1.03026 0.00334177 -1.55871 1 0 1 1 0 0 +EDGE2 2161 1440 -1.02657 -0.0728393 -1.58679 1 0 1 1 0 0 +EDGE2 2161 1760 -1.05927 0.0171542 -1.55942 1 0 1 1 0 0 +EDGE2 2161 1400 -0.977024 -0.00448279 -1.51963 1 0 1 1 0 0 +EDGE2 2161 1421 -0.0483206 -0.0526077 0.0158146 1 0 1 1 0 0 +EDGE2 2161 1441 -0.0662035 -0.053088 0.00449469 1 0 1 1 0 0 +EDGE2 2161 1401 -0.0430731 -0.0484491 0.00268215 1 0 1 1 0 0 +EDGE2 2161 1442 0.961352 0.0598923 0.0199952 1 0 1 1 0 0 +EDGE2 2161 1402 1.07897 0.00830086 0.000203994 1 0 1 1 0 0 +EDGE2 2162 1422 0.035141 0.0404635 -0.0161564 1 0 1 1 0 0 +EDGE2 2162 1421 -0.95937 -0.0282445 -0.00289045 1 0 1 1 0 0 +EDGE2 2162 1441 -1.01811 0.0273954 -0.0252841 1 0 1 1 0 0 +EDGE2 2162 2161 -0.974164 -0.0128088 0.00275781 1 0 1 1 0 0 +EDGE2 2162 1401 -0.977128 -0.00936804 -0.0182806 1 0 1 1 0 0 +EDGE2 2162 1442 0.0735056 0.0369394 -0.0331195 1 0 1 1 0 0 +EDGE2 2162 1423 0.995687 0.0157335 0.00632665 1 0 1 1 0 0 +EDGE2 2162 1402 0.00633081 -0.00800988 0.00769924 1 0 1 1 0 0 +EDGE2 2162 1443 1.0093 0.0175616 -0.0193062 1 0 1 1 0 0 +EDGE2 2162 1403 0.979577 -0.014709 0.0112541 1 0 1 1 0 0 +EDGE2 2163 1422 -1.01238 -0.00618147 0.0199013 1 0 1 1 0 0 +EDGE2 2163 1442 -0.984638 0.00877279 -0.00649107 1 0 1 1 0 0 +EDGE2 2163 2162 -0.968746 0.0730391 0.00606215 1 0 1 1 0 0 +EDGE2 2163 1423 0.0281758 0.0423529 0.0104906 1 0 1 1 0 0 +EDGE2 2163 1402 -0.963266 0.00964569 -0.0249387 1 0 1 1 0 0 +EDGE2 2163 1443 0.0370779 -0.015244 0.0089714 1 0 1 1 0 0 +EDGE2 2163 1424 1.11559 0.0523575 0.0656686 1 0 1 1 0 0 +EDGE2 2163 1403 -0.0573297 0.0102892 -0.0290027 1 0 1 1 0 0 +EDGE2 2163 1444 1.04195 0.0469309 -0.00934369 1 0 1 1 0 0 +EDGE2 2163 1404 1.04719 -0.00808132 0.0349614 1 0 1 1 0 0 +EDGE2 2164 1423 -1.05208 0.0909107 0.0259358 1 0 1 1 0 0 +EDGE2 2164 2163 -0.968113 -0.0113096 0.0340009 1 0 1 1 0 0 +EDGE2 2164 1443 -1.05182 -0.0974489 -0.0148713 1 0 1 1 0 0 +EDGE2 2164 1425 0.937111 0.0312961 -0.0178452 1 0 1 1 0 0 +EDGE2 2164 1424 -0.031647 -0.042553 0.0060932 1 0 1 1 0 0 +EDGE2 2164 1403 -0.921542 0.00126014 0.00552526 1 0 1 1 0 0 +EDGE2 2164 1444 -0.135943 -0.0760855 0.00213706 1 0 1 1 0 0 +EDGE2 2164 1404 -0.0656478 -0.0397019 0.0386858 1 0 1 1 0 0 +EDGE2 2164 1445 0.961993 -0.0257562 -0.0320363 1 0 1 1 0 0 +EDGE2 2164 1405 0.972242 0.0955003 0.000961515 1 0 1 1 0 0 +EDGE2 2165 1425 0.0289239 0.0542867 -0.00394483 1 0 1 1 0 0 +EDGE2 2165 1424 -1.02387 0.0145243 0.0154385 1 0 1 1 0 0 +EDGE2 2165 2164 -1.04521 -0.0880307 0.0287398 1 0 1 1 0 0 +EDGE2 2165 1444 -0.979355 -0.0669125 0.00616113 1 0 1 1 0 0 +EDGE2 2165 1404 -0.888178 -0.0297084 -0.00978513 1 0 1 1 0 0 +EDGE2 2165 1445 0.00850152 -0.0610517 -0.0105915 1 0 1 1 0 0 +EDGE2 2165 1405 0.0471483 0.0526353 -0.0152785 1 0 1 1 0 0 +EDGE2 2165 1426 0.0664428 0.924722 1.55364 1 0 1 1 0 0 +EDGE2 2165 1446 -0.00838977 0.948636 1.59147 1 0 1 1 0 0 +EDGE2 2165 1406 -0.029718 0.999764 1.62789 1 0 1 1 0 0 +EDGE2 2166 1425 -1.02601 0.00404923 -1.59466 1 0 1 1 0 0 +EDGE2 2166 2165 -1.04663 0.0775792 -1.57337 1 0 1 1 0 0 +EDGE2 2166 1445 -0.999771 -0.0788388 -1.60569 1 0 1 1 0 0 +EDGE2 2166 1405 -0.982212 0.086481 -1.56669 1 0 1 1 0 0 +EDGE2 2166 1426 0.0142755 0.00948727 -0.025432 1 0 1 1 0 0 +EDGE2 2166 1446 -0.0959932 0.0329353 0.0061126 1 0 1 1 0 0 +EDGE2 2166 1406 -0.00839402 0.0529874 0.00146941 1 0 1 1 0 0 +EDGE2 2166 1427 1.02439 -0.0519323 -0.0222825 1 0 1 1 0 0 +EDGE2 2166 1447 0.907376 0.0865611 -0.0115074 1 0 1 1 0 0 +EDGE2 2166 1407 0.953863 0.0721782 -0.0145765 1 0 1 1 0 0 +EDGE2 2167 1426 -0.902573 0.000639396 -0.0117158 1 0 1 1 0 0 +EDGE2 2167 1446 -1.07324 0.00784171 -0.0331629 1 0 1 1 0 0 +EDGE2 2167 2166 -1.03158 0.134319 -0.0164046 1 0 1 1 0 0 +EDGE2 2167 1406 -0.93714 0.00395199 -0.0195102 1 0 1 1 0 0 +EDGE2 2167 1427 -0.0905608 0.0172765 -0.00704601 1 0 1 1 0 0 +EDGE2 2167 1447 0.0325023 -0.0130422 -0.0266763 1 0 1 1 0 0 +EDGE2 2167 1407 -0.0151982 -0.0188946 0.0148205 1 0 1 1 0 0 +EDGE2 2167 1428 0.987887 0.0860047 0.0254344 1 0 1 1 0 0 +EDGE2 2167 1448 1.02447 0.0236799 0.0180739 1 0 1 1 0 0 +EDGE2 2167 1408 0.94656 0.0201841 -0.0123951 1 0 1 1 0 0 +EDGE2 2168 1427 -1.02305 -0.020687 0.0085091 1 0 1 1 0 0 +EDGE2 2168 1447 -0.928862 0.0405912 -0.0251089 1 0 1 1 0 0 +EDGE2 2168 2167 -0.973974 0.0211974 -0.00324583 1 0 1 1 0 0 +EDGE2 2168 1407 -1.05249 -0.00231193 0.0138735 1 0 1 1 0 0 +EDGE2 2168 1428 -0.0470197 0.00840883 -0.0206992 1 0 1 1 0 0 +EDGE2 2168 1448 0.0948541 -0.0723114 0.0264621 1 0 1 1 0 0 +EDGE2 2168 1408 0.0337609 0.124462 0.0398613 1 0 1 1 0 0 +EDGE2 2168 1429 0.99246 -0.0562804 -0.00575124 1 0 1 1 0 0 +EDGE2 2168 1449 1.00612 0.039361 0.0245283 1 0 1 1 0 0 +EDGE2 2168 1409 0.916712 -0.0204006 -0.00509082 1 0 1 1 0 0 +EDGE2 2169 1428 -0.971735 -0.0198201 0.0235252 1 0 1 1 0 0 +EDGE2 2169 1448 -1.01786 0.112455 -0.0147199 1 0 1 1 0 0 +EDGE2 2169 2168 -1.02411 0.0179391 -0.00934958 1 0 1 1 0 0 +EDGE2 2169 1408 -1.05639 0.0526352 0.0293486 1 0 1 1 0 0 +EDGE2 2169 1429 -0.0596775 0.0456905 0.00321963 1 0 1 1 0 0 +EDGE2 2169 1449 0.0327979 0.0131643 0.0368713 1 0 1 1 0 0 +EDGE2 2169 1409 -0.0233443 -0.0116006 -0.00151069 1 0 1 1 0 0 +EDGE2 2169 1450 0.94985 -0.0851454 -0.00624386 1 0 1 1 0 0 +EDGE2 2169 1390 1.00807 -0.0729407 -3.12328 1 0 1 1 0 0 +EDGE2 2169 1410 0.957417 0.0944105 0.0525542 1 0 1 1 0 0 +EDGE2 2169 1430 0.965164 0.0438492 -0.0463758 1 0 1 1 0 0 +EDGE2 2170 1451 0.00275783 0.98345 1.57502 1 0 1 1 0 0 +EDGE2 2170 1429 -1.05873 0.0609948 0.00444902 1 0 1 1 0 0 +EDGE2 2170 1449 -0.972035 0.00545974 0.0011272 1 0 1 1 0 0 +EDGE2 2170 2169 -0.954611 0.0261287 -0.00233453 1 0 1 1 0 0 +EDGE2 2170 1409 -0.910225 0.0317837 -0.0326608 1 0 1 1 0 0 +EDGE2 2170 1450 -0.0204794 0.113675 0.0080621 1 0 1 1 0 0 +EDGE2 2170 1391 -0.0146248 0.974574 1.57375 1 0 1 1 0 0 +EDGE2 2170 1411 -0.0364264 1.04669 1.56945 1 0 1 1 0 0 +EDGE2 2170 1431 0.0146668 1.02177 1.56619 1 0 1 1 0 0 +EDGE2 2170 1390 0.0845061 0.079856 -3.13686 1 0 1 1 0 0 +EDGE2 2170 1410 0.0146693 -0.0722215 -0.0122847 1 0 1 1 0 0 +EDGE2 2170 1430 -0.0019128 0.0173506 0.016401 1 0 1 1 0 0 +EDGE2 2170 1389 1.02108 0.0461242 -3.15037 1 0 1 1 0 0 +EDGE2 2171 1451 -0.0139317 -0.109101 0.0175989 1 0 1 1 0 0 +EDGE2 2171 1432 0.92098 0.010979 -0.0232751 1 0 1 1 0 0 +EDGE2 2171 1452 0.976232 -0.024777 -0.0145933 1 0 1 1 0 0 +EDGE2 2171 1392 0.986655 -0.0326097 0.0189926 1 0 1 1 0 0 +EDGE2 2171 1412 1.01705 -0.115416 -0.0207827 1 0 1 1 0 0 +EDGE2 2171 1450 -1.03227 -0.017942 -1.56911 1 0 1 1 0 0 +EDGE2 2171 1391 -0.0802767 -0.00266092 0.0179575 1 0 1 1 0 0 +EDGE2 2171 1411 -0.029655 -0.0431536 0.0475622 1 0 1 1 0 0 +EDGE2 2171 1431 0.0338169 -0.055676 0.0361138 1 0 1 1 0 0 +EDGE2 2171 2170 -0.926041 -0.0961336 -1.54127 1 0 1 1 0 0 +EDGE2 2171 1390 -1.09591 -0.0668351 1.55906 1 0 1 1 0 0 +EDGE2 2171 1410 -0.932307 0.0501725 -1.58762 1 0 1 1 0 0 +EDGE2 2171 1430 -1.08176 -0.03448 -1.54456 1 0 1 1 0 0 +EDGE2 2172 1451 -0.939022 0.028084 -0.0166975 1 0 1 1 0 0 +EDGE2 2172 1433 0.915193 0.0356339 -0.00159994 1 0 1 1 0 0 +EDGE2 2172 1453 0.910186 -0.0676577 -0.00649151 1 0 1 1 0 0 +EDGE2 2172 1432 -0.0233764 0.042577 0.0320593 1 0 1 1 0 0 +EDGE2 2172 1393 0.962657 0.0622476 -0.00684217 1 0 1 1 0 0 +EDGE2 2172 1413 0.939624 -0.0221383 -0.00826404 1 0 1 1 0 0 +EDGE2 2172 1452 -0.0259795 0.0636276 -0.012006 1 0 1 1 0 0 +EDGE2 2172 1392 0.0506376 -0.0497304 -0.0304454 1 0 1 1 0 0 +EDGE2 2172 1412 -0.01872 0.068387 -0.0157592 1 0 1 1 0 0 +EDGE2 2172 2171 -1.08722 0.0476598 -0.0204218 1 0 1 1 0 0 +EDGE2 2172 1391 -1.10307 -0.0057483 0.0168448 1 0 1 1 0 0 +EDGE2 2172 1411 -1.05311 0.028209 0.00215334 1 0 1 1 0 0 +EDGE2 2172 1431 -0.937945 -0.0656981 0.0286257 1 0 1 1 0 0 +EDGE2 2173 1433 0.0470904 0.0207899 0.00280038 1 0 1 1 0 0 +EDGE2 2173 1434 1.05641 -0.0418486 0.0269649 1 0 1 1 0 0 +EDGE2 2173 1454 0.938874 0.0582747 -0.0386677 1 0 1 1 0 0 +EDGE2 2173 1394 0.929915 0.11887 0.00747146 1 0 1 1 0 0 +EDGE2 2173 1414 1.01394 0.0092012 0.0217883 1 0 1 1 0 0 +EDGE2 2173 1453 0.095334 0.00710744 -0.00845368 1 0 1 1 0 0 +EDGE2 2173 1432 -1.00797 0.029218 -0.013047 1 0 1 1 0 0 +EDGE2 2173 2172 -0.943391 -0.065826 0.00707673 1 0 1 1 0 0 +EDGE2 2173 1393 0.0208308 0.0344136 -0.0318077 1 0 1 1 0 0 +EDGE2 2173 1413 0.0347848 0.0269486 -0.0138188 1 0 1 1 0 0 +EDGE2 2173 1452 -1.02869 -0.0232956 0.000208084 1 0 1 1 0 0 +EDGE2 2173 1392 -1.06217 -0.0425506 -0.000326003 1 0 1 1 0 0 +EDGE2 2173 1412 -1.00014 -0.0476692 0.0185272 1 0 1 1 0 0 +EDGE2 2174 1435 1.00351 0.0127174 0.00954696 1 0 1 1 0 0 +EDGE2 2174 1455 0.986299 -0.0378007 -0.0139524 1 0 1 1 0 0 +EDGE2 2174 1755 0.931442 0.0554107 -3.15064 1 0 1 1 0 0 +EDGE2 2174 1735 1.00896 -0.0318516 -3.15636 1 0 1 1 0 0 +EDGE2 2174 1433 -1.04268 0.00982017 -0.0153145 1 0 1 1 0 0 +EDGE2 2174 1434 0.00283637 -0.0196887 -0.0283833 1 0 1 1 0 0 +EDGE2 2174 1395 1.04924 -0.00770247 0.0202528 1 0 1 1 0 0 +EDGE2 2174 1415 1.01224 -0.0274906 -0.000732876 1 0 1 1 0 0 +EDGE2 2174 1454 0.0639598 0.0573265 -0.0326466 1 0 1 1 0 0 +EDGE2 2174 2173 -1.10089 0.0225205 -0.0214009 1 0 1 1 0 0 +EDGE2 2174 1394 0.0968998 -0.0331922 -0.0199345 1 0 1 1 0 0 +EDGE2 2174 1414 -0.0662713 0.0148373 -0.00617601 1 0 1 1 0 0 +EDGE2 2174 1453 -1.0574 -0.0350358 -0.00932643 1 0 1 1 0 0 +EDGE2 2174 1393 -1.04563 0.0891931 -0.031951 1 0 1 1 0 0 +EDGE2 2174 1413 -1.0776 -0.00858707 0.020352 1 0 1 1 0 0 +EDGE2 2175 1734 0.935188 -0.030937 -3.14704 1 0 1 1 0 0 +EDGE2 2175 1754 0.975311 0.110923 -3.14948 1 0 1 1 0 0 +EDGE2 2175 1435 0.0218965 -0.0404234 0.0314053 1 0 1 1 0 0 +EDGE2 2175 1455 -0.0262788 -0.0414213 -0.019305 1 0 1 1 0 0 +EDGE2 2175 1416 -0.0565657 1.02302 1.57933 1 0 1 1 0 0 +EDGE2 2175 1756 0.00102216 0.990549 1.53951 1 0 1 1 0 0 +EDGE2 2175 1436 0.0680999 1.06416 1.59277 1 0 1 1 0 0 +EDGE2 2175 1755 -0.146519 0.0256236 -3.09465 1 0 1 1 0 0 +EDGE2 2175 1396 -0.0250842 1.06664 1.57877 1 0 1 1 0 0 +EDGE2 2175 1735 -0.0138891 -0.104851 -3.15426 1 0 1 1 0 0 +EDGE2 2175 1434 -1.0431 0.0483901 0.00836917 1 0 1 1 0 0 +EDGE2 2175 2174 -1.04346 0.0404417 -0.0233866 1 0 1 1 0 0 +EDGE2 2175 1395 0.0138117 -0.0187471 0.0206363 1 0 1 1 0 0 +EDGE2 2175 1415 -0.0377849 -0.066931 0.00380256 1 0 1 1 0 0 +EDGE2 2175 1454 -0.948671 0.0236793 -0.0168033 1 0 1 1 0 0 +EDGE2 2175 1394 -1.00718 0.0132586 0.011156 1 0 1 1 0 0 +EDGE2 2175 1414 -1.02761 0.154384 -0.00495521 1 0 1 1 0 0 +EDGE2 2175 1456 -0.0608586 -1.00859 -1.55847 1 0 1 1 0 0 +EDGE2 2175 1736 -0.0418557 -0.934679 -1.57278 1 0 1 1 0 0 +EDGE2 2176 1417 1.01374 -0.0144572 -0.00365631 1 0 1 1 0 0 +EDGE2 2176 1757 1.02493 0.0500275 0.0277699 1 0 1 1 0 0 +EDGE2 2176 1437 0.967014 -0.0507085 -0.00552081 1 0 1 1 0 0 +EDGE2 2176 1435 -1.05727 -0.0569473 -1.55289 1 0 1 1 0 0 +EDGE2 2176 1455 -1.02378 0.0355363 -1.57541 1 0 1 1 0 0 +EDGE2 2176 1416 0.000366036 -0.12459 0.0414368 1 0 1 1 0 0 +EDGE2 2176 1756 0.0169987 -0.0453958 -0.0113034 1 0 1 1 0 0 +EDGE2 2176 1397 1.03133 -0.00297457 -0.0140056 1 0 1 1 0 0 +EDGE2 2176 1436 0.087574 0.0436427 0.0172756 1 0 1 1 0 0 +EDGE2 2176 1755 -0.95333 0.0676606 1.5521 1 0 1 1 0 0 +EDGE2 2176 2175 -1.02263 -0.0433011 -1.53233 1 0 1 1 0 0 +EDGE2 2176 1396 -0.0100082 0.0310993 -0.0150863 1 0 1 1 0 0 +EDGE2 2176 1735 -0.97081 -0.0326683 1.60064 1 0 1 1 0 0 +EDGE2 2176 1395 -1.0263 0.0371929 -1.57759 1 0 1 1 0 0 +EDGE2 2176 1415 -0.957627 -0.0299261 -1.57631 1 0 1 1 0 0 +EDGE2 2177 1417 -0.0416173 -0.0887367 0.0271824 1 0 1 1 0 0 +EDGE2 2177 1758 0.986847 -0.0123899 -0.0134056 1 0 1 1 0 0 +EDGE2 2177 1398 0.993085 0.078246 -0.0252534 1 0 1 1 0 0 +EDGE2 2177 1438 1.04587 -0.0591013 -0.00905132 1 0 1 1 0 0 +EDGE2 2177 1418 0.999997 0.0389547 0.0288537 1 0 1 1 0 0 +EDGE2 2177 1757 0.00995343 -0.056312 -0.0499771 1 0 1 1 0 0 +EDGE2 2177 1437 0.0225704 0.0356753 -0.0316616 1 0 1 1 0 0 +EDGE2 2177 1416 -1.05899 -0.0882499 0.0100207 1 0 1 1 0 0 +EDGE2 2177 1756 -0.904457 -0.0471421 -0.0472831 1 0 1 1 0 0 +EDGE2 2177 2176 -0.992375 0.030789 -0.00619644 1 0 1 1 0 0 +EDGE2 2177 1397 -0.00194014 0.0220497 0.00364324 1 0 1 1 0 0 +EDGE2 2177 1436 -1.02347 0.011747 -0.00113962 1 0 1 1 0 0 +EDGE2 2177 1396 -0.913628 -0.0303645 -0.0143641 1 0 1 1 0 0 +EDGE2 2178 1417 -1.10322 -0.028607 0.00108362 1 0 1 1 0 0 +EDGE2 2178 1758 0.0520138 -0.0357845 -0.020726 1 0 1 1 0 0 +EDGE2 2178 1419 1.00333 0.0469166 0.0258957 1 0 1 1 0 0 +EDGE2 2178 1759 0.966825 0.0128351 -0.00269254 1 0 1 1 0 0 +EDGE2 2178 1439 1.0275 0.0582378 0.00490917 1 0 1 1 0 0 +EDGE2 2178 1399 1.0354 -0.085349 0.00174072 1 0 1 1 0 0 +EDGE2 2178 1398 -0.0334166 0.0410899 0.0249786 1 0 1 1 0 0 +EDGE2 2178 1438 0.0209738 0.0727165 -0.00930652 1 0 1 1 0 0 +EDGE2 2178 1418 -0.0185307 -0.0100416 0.00619548 1 0 1 1 0 0 +EDGE2 2178 1757 -1.10454 0.00373757 0.0162183 1 0 1 1 0 0 +EDGE2 2178 2177 -1.04413 0.0138097 0.014911 1 0 1 1 0 0 +EDGE2 2178 1437 -0.963261 -0.0893631 0.0294062 1 0 1 1 0 0 +EDGE2 2178 1397 -0.955729 -0.0622119 -0.00293302 1 0 1 1 0 0 +EDGE2 2179 2060 0.897285 0.0112347 -3.13733 1 0 1 1 0 0 +EDGE2 2179 2140 1.0037 0.0385328 -3.13125 1 0 1 1 0 0 +EDGE2 2179 2160 0.967067 0.0128808 -3.10506 1 0 1 1 0 0 +EDGE2 2179 2120 0.929576 0.0234331 -3.14166 1 0 1 1 0 0 +EDGE2 2179 1420 0.951821 -0.0153585 -0.0165936 1 0 1 1 0 0 +EDGE2 2179 1440 1.01537 -0.0549417 0.00144972 1 0 1 1 0 0 +EDGE2 2179 1760 1.0216 0.0647576 0.00571276 1 0 1 1 0 0 +EDGE2 2179 1400 0.974346 -0.105354 0.0133036 1 0 1 1 0 0 +EDGE2 2179 1758 -0.990972 -0.0858514 -0.020801 1 0 1 1 0 0 +EDGE2 2179 1419 0.104123 0.050242 -0.0263571 1 0 1 1 0 0 +EDGE2 2179 1759 0.0191357 0.0459923 0.014073 1 0 1 1 0 0 +EDGE2 2179 1439 -0.0258528 -0.00223342 0.0113439 1 0 1 1 0 0 +EDGE2 2179 2178 -0.999787 0.021889 -0.0133011 1 0 1 1 0 0 +EDGE2 2179 1399 0.0489365 -0.0257986 0.0138414 1 0 1 1 0 0 +EDGE2 2179 1398 -0.982995 0.0692225 -0.00609271 1 0 1 1 0 0 +EDGE2 2179 1438 -1.06279 -0.0545077 -0.0205672 1 0 1 1 0 0 +EDGE2 2179 1418 -0.988098 -0.0529106 -0.00675838 1 0 1 1 0 0 +EDGE2 2180 2119 0.954654 0.0710265 -3.11706 1 0 1 1 0 0 +EDGE2 2180 2139 1.04379 -0.0378412 -3.12786 1 0 1 1 0 0 +EDGE2 2180 2159 1.01163 -0.0406897 -3.13998 1 0 1 1 0 0 +EDGE2 2180 2059 0.914056 0.00412228 -3.15295 1 0 1 1 0 0 +EDGE2 2180 2060 -0.0948626 -0.0196899 -3.11782 1 0 1 1 0 0 +EDGE2 2180 1761 0.043392 -1.02823 -1.58112 1 0 1 1 0 0 +EDGE2 2180 2121 0.0734414 -1.05424 -1.57453 1 0 1 1 0 0 +EDGE2 2180 2141 0.00235159 -1.0646 -1.55059 1 0 1 1 0 0 +EDGE2 2180 2061 -0.0224966 -1.00138 -1.55381 1 0 1 1 0 0 +EDGE2 2180 2140 -0.00833545 -0.0993956 -3.12956 1 0 1 1 0 0 +EDGE2 2180 2160 -0.0351611 0.00675803 -3.15312 1 0 1 1 0 0 +EDGE2 2180 2120 -0.00164531 -0.0372959 -3.11872 1 0 1 1 0 0 +EDGE2 2180 1420 0.0338075 -0.0213172 0.00813993 1 0 1 1 0 0 +EDGE2 2180 1440 0.0525534 0.0128701 -0.0113227 1 0 1 1 0 0 +EDGE2 2180 1760 -0.0713215 -0.000531802 -0.000911128 1 0 1 1 0 0 +EDGE2 2180 1400 -0.0033474 0.0159566 -0.0103069 1 0 1 1 0 0 +EDGE2 2180 1421 0.0748204 0.959735 1.5921 1 0 1 1 0 0 +EDGE2 2180 1441 -0.0131848 0.978508 1.5733 1 0 1 1 0 0 +EDGE2 2180 2161 0.0418288 0.933013 1.56717 1 0 1 1 0 0 +EDGE2 2180 1401 -0.0644859 1.08422 1.61699 1 0 1 1 0 0 +EDGE2 2180 1419 -1.07923 -0.0766671 0.00230673 1 0 1 1 0 0 +EDGE2 2180 1759 -0.985099 0.0718979 -0.00906212 1 0 1 1 0 0 +EDGE2 2180 2179 -0.956433 -0.0132132 -0.00861031 1 0 1 1 0 0 +EDGE2 2180 1439 -1.04162 -0.0358767 0.0351547 1 0 1 1 0 0 +EDGE2 2180 1399 -1.02728 0.00611809 -0.0396808 1 0 1 1 0 0 +EDGE2 2181 1422 1.03889 0.0320414 -0.0217837 1 0 1 1 0 0 +EDGE2 2181 2060 -0.880509 -0.0726758 1.56544 1 0 1 1 0 0 +EDGE2 2181 2140 -0.883551 -0.00817901 1.5899 1 0 1 1 0 0 +EDGE2 2181 2160 -0.924055 -0.0238153 1.5645 1 0 1 1 0 0 +EDGE2 2181 2180 -0.989412 0.0216186 -1.54248 1 0 1 1 0 0 +EDGE2 2181 2120 -1.044 -0.0820733 1.57231 1 0 1 1 0 0 +EDGE2 2181 1420 -0.969531 -0.0151049 -1.57395 1 0 1 1 0 0 +EDGE2 2181 1440 -1.01787 0.024962 -1.58095 1 0 1 1 0 0 +EDGE2 2181 1760 -1.03571 -0.0376793 -1.55921 1 0 1 1 0 0 +EDGE2 2181 1400 -0.959929 -0.00941574 -1.56052 1 0 1 1 0 0 +EDGE2 2181 1421 0.0870644 0.000864871 0.00510808 1 0 1 1 0 0 +EDGE2 2181 1441 -0.0595351 -0.0569711 0.0110196 1 0 1 1 0 0 +EDGE2 2181 2161 0.0731673 0.00920308 0.0114171 1 0 1 1 0 0 +EDGE2 2181 1401 -0.0277142 0.0381049 -0.0153805 1 0 1 1 0 0 +EDGE2 2181 1442 0.951041 -0.0453643 0.014388 1 0 1 1 0 0 +EDGE2 2181 2162 1.03373 -0.0557148 0.0173836 1 0 1 1 0 0 +EDGE2 2181 1402 1.01276 -0.0289262 -0.0268784 1 0 1 1 0 0 +EDGE2 2182 1422 -0.0543826 0.00782201 0.0592131 1 0 1 1 0 0 +EDGE2 2182 2181 -1.00626 -0.067705 0.0183327 1 0 1 1 0 0 +EDGE2 2182 1421 -0.992036 -0.0954678 0.00973197 1 0 1 1 0 0 +EDGE2 2182 1441 -1.08432 -0.0128314 -0.00554434 1 0 1 1 0 0 +EDGE2 2182 2161 -1.04976 -0.00996168 0.00249958 1 0 1 1 0 0 +EDGE2 2182 1401 -1.04892 0.00719151 -0.0221932 1 0 1 1 0 0 +EDGE2 2182 1442 -0.0156651 -0.0880728 -0.0383723 1 0 1 1 0 0 +EDGE2 2182 2162 0.0370736 -0.0194386 -0.00294003 1 0 1 1 0 0 +EDGE2 2182 1423 0.923874 0.00953701 -0.0506806 1 0 1 1 0 0 +EDGE2 2182 2163 0.98186 0.0240462 0.00269037 1 0 1 1 0 0 +EDGE2 2182 1402 0.00623126 -0.0257622 0.0106131 1 0 1 1 0 0 +EDGE2 2182 1443 0.980441 0.0361469 -0.0100435 1 0 1 1 0 0 +EDGE2 2182 1403 1.03125 -0.0111131 0.00779674 1 0 1 1 0 0 +EDGE2 2183 1422 -0.972551 -0.0244959 0.0189524 1 0 1 1 0 0 +EDGE2 2183 2182 -1.04107 -0.00131453 -0.00483585 1 0 1 1 0 0 +EDGE2 2183 1442 -0.993362 0.0172301 0.0172795 1 0 1 1 0 0 +EDGE2 2183 2162 -0.943666 0.0564983 -0.00317975 1 0 1 1 0 0 +EDGE2 2183 1423 -0.0845097 -0.0294212 0.00139713 1 0 1 1 0 0 +EDGE2 2183 2163 0.0242921 0.087572 -0.0215206 1 0 1 1 0 0 +EDGE2 2183 1402 -1.03978 -0.106216 0.00140953 1 0 1 1 0 0 +EDGE2 2183 1443 0.00858685 -0.00523451 0.0175468 1 0 1 1 0 0 +EDGE2 2183 1424 0.944634 -0.0759116 0.0260261 1 0 1 1 0 0 +EDGE2 2183 2164 1.01686 -0.0834614 -0.00254076 1 0 1 1 0 0 +EDGE2 2183 1403 -0.014354 0.0506272 0.0205474 1 0 1 1 0 0 +EDGE2 2183 1444 0.903401 0.0290439 -0.0134621 1 0 1 1 0 0 +EDGE2 2183 1404 1.0091 0.00681291 -0.00360477 1 0 1 1 0 0 +EDGE2 2184 1423 -1.04878 -0.0215708 -3.33116e-05 1 0 1 1 0 0 +EDGE2 2184 2163 -1.06437 0.0937028 0.0479207 1 0 1 1 0 0 +EDGE2 2184 2183 -0.997657 -0.0355402 -0.00576653 1 0 1 1 0 0 +EDGE2 2184 1443 -0.978708 0.0314818 0.0341623 1 0 1 1 0 0 +EDGE2 2184 1425 0.966145 0.00929622 -0.0279077 1 0 1 1 0 0 +EDGE2 2184 1424 -0.072626 0.0318602 -0.0294825 1 0 1 1 0 0 +EDGE2 2184 2164 0.0658596 -0.0922437 -0.00723288 1 0 1 1 0 0 +EDGE2 2184 1403 -1.00786 0.0274992 0.0115305 1 0 1 1 0 0 +EDGE2 2184 1444 0.0120609 -0.0401694 -0.00513384 1 0 1 1 0 0 +EDGE2 2184 2165 1.06819 -0.0232264 -0.0298429 1 0 1 1 0 0 +EDGE2 2184 1404 -0.0216494 -0.0415635 -0.00585614 1 0 1 1 0 0 +EDGE2 2184 1445 0.934506 -0.0854857 0.0257269 1 0 1 1 0 0 +EDGE2 2184 1405 0.999862 -0.0959842 -0.0193207 1 0 1 1 0 0 +EDGE2 2185 1425 0.0923291 0.125453 -0.0237248 1 0 1 1 0 0 +EDGE2 2185 1424 -1.03006 0.0004755 0.00753839 1 0 1 1 0 0 +EDGE2 2185 2164 -1.028 -0.0341 -0.00191103 1 0 1 1 0 0 +EDGE2 2185 2184 -1.01814 -0.0676239 0.0129221 1 0 1 1 0 0 +EDGE2 2185 1444 -1.06233 0.0538436 -0.0313218 1 0 1 1 0 0 +EDGE2 2185 2165 -0.0556345 -0.0455121 0.0106658 1 0 1 1 0 0 +EDGE2 2185 1404 -0.950283 -0.0120488 0.0174735 1 0 1 1 0 0 +EDGE2 2185 1445 -0.0221831 -0.00201257 -0.00234343 1 0 1 1 0 0 +EDGE2 2185 1405 0.0887945 0.0533982 -0.0100952 1 0 1 1 0 0 +EDGE2 2185 1426 -0.0642847 0.984826 1.58416 1 0 1 1 0 0 +EDGE2 2185 1446 -0.0175258 0.949181 1.5731 1 0 1 1 0 0 +EDGE2 2185 2166 -0.0118313 0.975391 1.57496 1 0 1 1 0 0 +EDGE2 2185 1406 -0.033847 1.00471 1.56513 1 0 1 1 0 0 +EDGE2 2186 1425 -0.896147 0.0481932 1.55446 1 0 1 1 0 0 +EDGE2 2186 2165 -1.10377 -0.0665918 1.5909 1 0 1 1 0 0 +EDGE2 2186 2185 -1.01599 -0.0173334 1.58737 1 0 1 1 0 0 +EDGE2 2186 1445 -1.02395 -0.0318941 1.59324 1 0 1 1 0 0 +EDGE2 2186 1405 -1.06642 0.0288155 1.56573 1 0 1 1 0 0 +EDGE2 2187 2186 -0.992988 0.083076 0.0100594 1 0 1 1 0 0 +EDGE2 2188 2187 -1.04896 0.0578093 -0.0251365 1 0 1 1 0 0 +EDGE2 2189 1790 0.969248 -0.0497689 -3.15415 1 0 1 1 0 0 +EDGE2 2189 2050 1.01046 -0.075706 -3.18863 1 0 1 1 0 0 +EDGE2 2189 2188 -1.00837 -0.00385855 -0.0310049 1 0 1 1 0 0 +EDGE2 2190 2049 1.04884 -0.0317418 -3.12243 1 0 1 1 0 0 +EDGE2 2190 1789 0.962467 -0.0645758 -3.14224 1 0 1 1 0 0 +EDGE2 2190 2051 -0.0488412 -1.01008 -1.57221 1 0 1 1 0 0 +EDGE2 2190 1790 0.0493555 -0.00609352 -3.15869 1 0 1 1 0 0 +EDGE2 2190 2050 0.0780072 0.0177905 -3.1728 1 0 1 1 0 0 +EDGE2 2190 1791 0.0772045 0.853087 1.58233 1 0 1 1 0 0 +EDGE2 2190 2189 -1.15743 -0.00234355 -0.0133109 1 0 1 1 0 0 +EDGE2 2191 2190 -1.02529 -0.0282563 -1.55479 1 0 1 1 0 0 +EDGE2 2191 1790 -1.0631 0.0122197 1.59419 1 0 1 1 0 0 +EDGE2 2191 2050 -0.937157 0.0307331 1.55503 1 0 1 1 0 0 +EDGE2 2191 1791 0.0367043 0.0270711 -0.00367781 1 0 1 1 0 0 +EDGE2 2191 1792 0.977954 0.0420549 -0.0167213 1 0 1 1 0 0 +EDGE2 2192 2191 -0.967204 0.0263267 -0.0342351 1 0 1 1 0 0 +EDGE2 2192 1791 -0.986703 0.0233637 0.0299736 1 0 1 1 0 0 +EDGE2 2192 1792 0.0181997 0.00285782 -0.0449398 1 0 1 1 0 0 +EDGE2 2192 1793 0.949876 -0.0245773 -0.000384924 1 0 1 1 0 0 +EDGE2 2193 2192 -0.961564 0.0302504 -1.65408e-05 1 0 1 1 0 0 +EDGE2 2193 1792 -1.04611 -0.0653375 -0.0103747 1 0 1 1 0 0 +EDGE2 2193 1793 -0.00561917 -0.027699 -0.0210584 1 0 1 1 0 0 +EDGE2 2193 1794 1.04293 0.0309926 -0.0146176 1 0 1 1 0 0 +EDGE2 2194 2193 -1.0431 -0.0656662 0.0106075 1 0 1 1 0 0 +EDGE2 2194 1793 -0.966104 -0.0225551 0.0589684 1 0 1 1 0 0 +EDGE2 2194 1794 0.00173657 -0.00997574 -0.00190855 1 0 1 1 0 0 +EDGE2 2194 1795 1.06088 0.0308372 -0.0150368 1 0 1 1 0 0 +EDGE2 2195 2194 -0.962456 -0.00664463 -0.010253 1 0 1 1 0 0 +EDGE2 2195 1794 -0.938939 -0.0254766 0.0270911 1 0 1 1 0 0 +EDGE2 2195 1795 0.0240659 -0.0849868 -0.0338022 1 0 1 1 0 0 +EDGE2 2195 1796 0.00539704 1.03566 1.58173 1 0 1 1 0 0 +EDGE2 2196 2195 -0.995448 0.0980084 1.59678 1 0 1 1 0 0 +EDGE2 2196 1795 -0.982372 -0.0166543 1.5753 1 0 1 1 0 0 +EDGE2 2197 2196 -0.99984 0.0736154 0.00177205 1 0 1 1 0 0 +EDGE2 2198 2197 -1.02575 0.0202262 0.000461052 1 0 1 1 0 0 +EDGE2 2199 2198 -1.02163 -0.0395936 -0.0141716 1 0 1 1 0 0 +EDGE2 2200 2199 -1.00407 -0.0590026 -0.0144651 1 0 1 1 0 0 +EDGE2 2201 2200 -0.979192 -0.0543442 1.53603 1 0 1 1 0 0 +EDGE2 2202 2201 -1.07273 0.017045 -0.00468813 1 0 1 1 0 0 +EDGE2 2203 2202 -0.940669 0.0704567 0.000849279 1 0 1 1 0 0 +EDGE2 2204 1785 1.01271 -0.037945 -3.12584 1 0 1 1 0 0 +EDGE2 2204 2045 0.999426 -0.0184158 -3.14595 1 0 1 1 0 0 +EDGE2 2204 2203 -1.00415 -0.0251315 -0.00360985 1 0 1 1 0 0 +EDGE2 2205 2046 0.0147106 -0.917316 -1.55608 1 0 1 1 0 0 +EDGE2 2205 1785 0.0153126 0.0616142 -3.15344 1 0 1 1 0 0 +EDGE2 2205 1784 1.01545 -0.0139545 -3.15039 1 0 1 1 0 0 +EDGE2 2205 2044 0.979683 0.0356822 -3.17474 1 0 1 1 0 0 +EDGE2 2205 2045 0.0200051 0.0287686 -3.16402 1 0 1 1 0 0 +EDGE2 2205 2204 -0.978458 -0.028867 -0.0050807 1 0 1 1 0 0 +EDGE2 2205 1786 -0.00754414 -0.950161 -1.59542 1 0 1 1 0 0 +EDGE2 2206 1785 -0.980034 0.010794 1.53513 1 0 1 1 0 0 +EDGE2 2206 2205 -1.03588 0.0421834 -1.54638 1 0 1 1 0 0 +EDGE2 2206 2045 -1.09311 -0.0301418 1.57767 1 0 1 1 0 0 +EDGE2 2207 2206 -1.06871 0.000501531 -0.000749082 1 0 1 1 0 0 +EDGE2 2208 2207 -1.02861 -0.0190341 0.00513373 1 0 1 1 0 0 +EDGE2 2209 2208 -0.956376 -0.0834457 -0.000875387 1 0 1 1 0 0 +EDGE2 2210 2209 -1.01017 0.023664 0.017762 1 0 1 1 0 0 +EDGE2 2211 2210 -0.902452 0.0234987 -1.5722 1 0 1 1 0 0 +EDGE2 2212 2211 -0.998166 -0.0355796 -0.0119089 1 0 1 1 0 0 +EDGE2 2213 2212 -0.987716 0.0293255 0.0248976 1 0 1 1 0 0 +EDGE2 2214 2213 -0.912834 -0.106959 0.000960611 1 0 1 1 0 0 +EDGE2 2215 2214 -0.998556 0.0833323 0.0226073 1 0 1 1 0 0 +EDGE2 2216 2215 -0.980913 0.0101927 -1.55954 1 0 1 1 0 0 +EDGE2 2217 2216 -0.990428 0.00109724 -0.0120515 1 0 1 1 0 0 +EDGE2 2218 2217 -1.05896 0.0159169 -0.0278579 1 0 1 1 0 0 +EDGE2 2219 2218 -0.950234 0.0621747 -0.0482245 1 0 1 1 0 0 +EDGE2 2219 2200 0.866943 -0.0165007 -3.15058 1 0 1 1 0 0 +EDGE2 2220 2219 -1.05135 -0.0222841 -0.000121729 1 0 1 1 0 0 +EDGE2 2220 2201 0.00968592 0.974881 1.59624 1 0 1 1 0 0 +EDGE2 2220 2200 -0.076765 -0.00763856 -3.11147 1 0 1 1 0 0 +EDGE2 2220 2199 0.933738 -0.0409065 -3.12548 1 0 1 1 0 0 +EDGE2 2221 2200 -1.01386 -0.0166158 -1.56709 1 0 1 1 0 0 +EDGE2 2221 2220 -1.01962 0.0629319 1.60639 1 0 1 1 0 0 +EDGE2 2222 2221 -1.02742 -0.047289 -0.0263962 1 0 1 1 0 0 +EDGE2 2223 2222 -0.985796 -0.0250537 -0.0241682 1 0 1 1 0 0 +EDGE2 2224 2223 -0.940008 -0.0491287 -0.00339472 1 0 1 1 0 0 +EDGE2 2225 2224 -0.993908 -0.0684599 0.0173383 1 0 1 1 0 0 +EDGE2 2226 2225 -0.987591 0.0180776 -1.57381 1 0 1 1 0 0 +EDGE2 2227 2226 -0.977113 -0.0442372 0.04251 1 0 1 1 0 0 +EDGE2 2228 2227 -1.11938 0.0786999 -0.0134007 1 0 1 1 0 0 +EDGE2 2229 2228 -0.935866 -0.0408408 0.00287699 1 0 1 1 0 0 +EDGE2 2229 1810 0.981498 0.0316527 -3.14264 1 0 1 1 0 0 +EDGE2 2230 2229 -0.935261 -0.0170677 -0.0213083 1 0 1 1 0 0 +EDGE2 2230 1810 -0.0973341 0.0255385 -3.12896 1 0 1 1 0 0 +EDGE2 2230 1811 -0.00186838 -1.02557 -1.58791 1 0 1 1 0 0 +EDGE2 2230 1809 1.0269 0.0495208 -3.14422 1 0 1 1 0 0 +EDGE2 2231 1810 -0.919156 0.0217323 -1.60131 1 0 1 1 0 0 +EDGE2 2231 2230 -0.961825 9.51495e-05 1.58921 1 0 1 1 0 0 +EDGE2 2231 1811 0.0589507 0.040168 -0.000502909 1 0 1 1 0 0 +EDGE2 2231 1812 1.00439 0.0227712 0.00290161 1 0 1 1 0 0 +EDGE2 2232 2231 -1.00216 -0.0908075 0.0272264 1 0 1 1 0 0 +EDGE2 2232 1811 -1.05 -0.0220479 -0.0340585 1 0 1 1 0 0 +EDGE2 2232 1812 -0.0521485 -0.0202906 -0.00190847 1 0 1 1 0 0 +EDGE2 2232 1813 1.04299 0.00600606 0.0488324 1 0 1 1 0 0 +EDGE2 2233 1812 -0.994068 -0.0338151 0.0214558 1 0 1 1 0 0 +EDGE2 2233 2232 -0.962631 -0.0124822 -0.00714006 1 0 1 1 0 0 +EDGE2 2233 1813 -0.0655957 0.0166774 0.00720525 1 0 1 1 0 0 +EDGE2 2233 1814 0.948846 0.0522389 -0.00126824 1 0 1 1 0 0 +EDGE2 2234 1813 -0.984018 -0.00845452 -0.0105727 1 0 1 1 0 0 +EDGE2 2234 2233 -0.974382 -0.0210266 0.0173431 1 0 1 1 0 0 +EDGE2 2234 1814 0.0615544 -0.0292107 0.0249075 1 0 1 1 0 0 +EDGE2 2234 1815 0.962326 -0.0344142 0.0178285 1 0 1 1 0 0 +EDGE2 2235 2234 -0.911326 0.0320809 0.0100203 1 0 1 1 0 0 +EDGE2 2235 1814 -0.982545 0.0791267 0.0137085 1 0 1 1 0 0 +EDGE2 2235 1815 -0.0284333 -0.0587497 0.040644 1 0 1 1 0 0 +EDGE2 2235 1816 -0.0364036 0.954751 1.57415 1 0 1 1 0 0 +EDGE2 2236 2235 -1.05967 0.0207741 -1.56145 1 0 1 1 0 0 +EDGE2 2236 1815 -0.952067 0.0568114 -1.55016 1 0 1 1 0 0 +EDGE2 2236 1816 0.0470602 0.0082977 -0.0362904 1 0 1 1 0 0 +EDGE2 2236 1817 0.982596 0.0306546 0.00583324 1 0 1 1 0 0 +EDGE2 2237 1816 -0.998984 0.0315525 0.00164735 1 0 1 1 0 0 +EDGE2 2237 2236 -0.964224 0.0571551 -0.00354015 1 0 1 1 0 0 +EDGE2 2237 1817 0.00618513 0.0534451 0.0197818 1 0 1 1 0 0 +EDGE2 2237 1818 0.999486 0.00726764 0.0357258 1 0 1 1 0 0 +EDGE2 2238 2237 -1.0361 0.0316472 0.00524252 1 0 1 1 0 0 +EDGE2 2238 1817 -0.993579 -0.00141216 0.0201416 1 0 1 1 0 0 +EDGE2 2238 1818 -0.0704455 0.00784236 -0.0209088 1 0 1 1 0 0 +EDGE2 2238 1819 1.02704 -0.0368111 0.0187475 1 0 1 1 0 0 +EDGE2 2239 2238 -1.00584 0.00581569 0.0160898 1 0 1 1 0 0 +EDGE2 2239 1818 -1.05335 0.0643557 0.0271207 1 0 1 1 0 0 +EDGE2 2239 1819 0.0118783 0.0411003 0.0214704 1 0 1 1 0 0 +EDGE2 2239 1820 0.921448 0.0489993 -0.0152416 1 0 1 1 0 0 +EDGE2 2239 1240 0.94281 0.0923984 -3.17065 1 0 1 1 0 0 +EDGE2 2240 2239 -1.02113 0.00416257 -0.00977465 1 0 1 1 0 0 +EDGE2 2240 1819 -0.946715 0.0598838 0.0127978 1 0 1 1 0 0 +EDGE2 2240 1821 -0.0737684 1.08539 1.57587 1 0 1 1 0 0 +EDGE2 2240 1820 -0.0495917 0.0674565 0.0137116 1 0 1 1 0 0 +EDGE2 2240 1240 0.122908 -0.0629923 -3.12208 1 0 1 1 0 0 +EDGE2 2240 1241 -0.0518896 -1.06607 -1.59971 1 0 1 1 0 0 +EDGE2 2240 1239 1.07575 0.00537076 -3.14172 1 0 1 1 0 0 +EDGE2 2241 1821 -0.00827236 0.0178409 0.0302914 1 0 1 1 0 0 +EDGE2 2241 1822 0.979094 0.0702065 -0.00479287 1 0 1 1 0 0 +EDGE2 2241 1820 -1.06369 0.052777 -1.55733 1 0 1 1 0 0 +EDGE2 2241 2240 -1.02334 0.0115801 -1.59757 1 0 1 1 0 0 +EDGE2 2241 1240 -1.12251 -0.0396515 1.55758 1 0 1 1 0 0 +EDGE2 2242 1823 1.0024 0.00634102 0.024658 1 0 1 1 0 0 +EDGE2 2242 1821 -1.01886 -0.0199512 0.00813317 1 0 1 1 0 0 +EDGE2 2242 2241 -1.00463 0.0137905 -0.0127072 1 0 1 1 0 0 +EDGE2 2242 1822 -0.0464618 -0.0500091 -0.00173833 1 0 1 1 0 0 +EDGE2 2243 2242 -1.01059 -0.0382833 0.000173557 1 0 1 1 0 0 +EDGE2 2243 1824 0.971327 -0.118992 -0.00253553 1 0 1 1 0 0 +EDGE2 2243 1823 0.0288452 -0.0151128 -0.0270904 1 0 1 1 0 0 +EDGE2 2243 1822 -1.01681 -0.00914453 -0.0120744 1 0 1 1 0 0 +EDGE2 2244 1805 1.01236 -0.0691229 -3.15729 1 0 1 1 0 0 +EDGE2 2244 1825 0.93987 0.122967 -0.0145253 1 0 1 1 0 0 +EDGE2 2244 2243 -0.964134 -0.0166506 0.0197035 1 0 1 1 0 0 +EDGE2 2244 1824 -0.0125981 0.115562 0.0100693 1 0 1 1 0 0 +EDGE2 2244 1823 -1.02898 0.0419815 -0.036612 1 0 1 1 0 0 +EDGE2 2245 1805 0.00202461 0.0829931 -3.13649 1 0 1 1 0 0 +EDGE2 2245 1806 0.00712901 0.94657 1.60428 1 0 1 1 0 0 +EDGE2 2245 1804 1.04725 0.0851976 -3.1762 1 0 1 1 0 0 +EDGE2 2245 1825 -0.0363504 0.0542909 8.12935e-05 1 0 1 1 0 0 +EDGE2 2245 1824 -1.05851 -0.0426968 0.027242 1 0 1 1 0 0 +EDGE2 2245 2244 -1.00991 0.0118014 0.0019055 1 0 1 1 0 0 +EDGE2 2245 1826 0.092312 -0.964149 -1.61005 1 0 1 1 0 0 +EDGE2 2246 1805 -1.00519 -0.0169705 1.56474 1 0 1 1 0 0 +EDGE2 2246 1807 0.900014 -0.0429377 -0.0241006 1 0 1 1 0 0 +EDGE2 2246 1806 -0.0198883 -0.0233319 0.00350834 1 0 1 1 0 0 +EDGE2 2246 2245 -1.10038 -0.00736328 -1.57097 1 0 1 1 0 0 +EDGE2 2246 1825 -1.01514 0.0260051 -1.56092 1 0 1 1 0 0 +EDGE2 2247 1808 0.973321 0.0280216 -0.00911399 1 0 1 1 0 0 +EDGE2 2247 1807 -0.0293415 -0.0904575 0.023395 1 0 1 1 0 0 +EDGE2 2247 2246 -1.01068 -0.028558 -0.0211754 1 0 1 1 0 0 +EDGE2 2247 1806 -1.04537 0.0978448 0.0213238 1 0 1 1 0 0 +EDGE2 2248 1809 1.05598 0.0240239 0.00678473 1 0 1 1 0 0 +EDGE2 2248 1808 -0.0571487 0.032591 0.00177662 1 0 1 1 0 0 +EDGE2 2248 1807 -0.977004 -0.00429029 -0.0015959 1 0 1 1 0 0 +EDGE2 2248 2247 -1.0847 0.0562862 -0.0222751 1 0 1 1 0 0 +EDGE2 2249 1810 1.06001 -0.0325586 0.00451264 1 0 1 1 0 0 +EDGE2 2249 2230 1.01231 -0.0619056 -3.1213 1 0 1 1 0 0 +EDGE2 2249 1809 0.0108681 0.00630155 -0.0197925 1 0 1 1 0 0 +EDGE2 2249 2248 -0.892826 0.0366822 0.0192289 1 0 1 1 0 0 +EDGE2 2249 1808 -1.14696 0.0110914 0.000609394 1 0 1 1 0 0 +EDGE2 2250 2229 0.945452 0.014711 -3.14447 1 0 1 1 0 0 +EDGE2 2250 1810 -0.0449264 -0.0459565 0.0144516 1 0 1 1 0 0 +EDGE2 2250 2230 -0.0315215 0.047602 -3.16539 1 0 1 1 0 0 +EDGE2 2250 2231 0.0617815 1.03709 1.53764 1 0 1 1 0 0 +EDGE2 2250 1811 0.00374681 1.0704 1.57839 1 0 1 1 0 0 +EDGE2 2250 2249 -1.01742 -0.0131065 0.0255309 1 0 1 1 0 0 +EDGE2 2250 1809 -1.06886 -0.0624344 -0.00395313 1 0 1 1 0 0 +EDGE2 2251 1810 -0.947204 0.0428707 -1.55232 1 0 1 1 0 0 +EDGE2 2251 2250 -1.06411 -0.0499018 -1.56723 1 0 1 1 0 0 +EDGE2 2251 2230 -0.937661 -0.00918312 1.54996 1 0 1 1 0 0 +EDGE2 2251 2231 0.114605 0.0123217 -0.0277718 1 0 1 1 0 0 +EDGE2 2251 1811 0.0291856 0.0324308 -0.0285044 1 0 1 1 0 0 +EDGE2 2251 1812 0.937239 0.0631008 0.0341404 1 0 1 1 0 0 +EDGE2 2251 2232 1.00434 0.0209418 0.0315095 1 0 1 1 0 0 +EDGE2 2252 2231 -1.03336 -0.0090041 0.00717995 1 0 1 1 0 0 +EDGE2 2252 2251 -1.00437 0.0275256 -0.00143166 1 0 1 1 0 0 +EDGE2 2252 1811 -0.95417 -0.0137557 0.00753428 1 0 1 1 0 0 +EDGE2 2252 1812 0.0491979 -0.0792169 -0.000560784 1 0 1 1 0 0 +EDGE2 2252 2232 0.0246512 -0.031773 0.00287362 1 0 1 1 0 0 +EDGE2 2252 1813 1.0165 -0.0399217 -0.0023022 1 0 1 1 0 0 +EDGE2 2252 2233 1.12365 0.0708566 -0.00846054 1 0 1 1 0 0 +EDGE2 2253 2234 0.929335 0.0632164 -0.0375949 1 0 1 1 0 0 +EDGE2 2253 1812 -1.00351 0.0460695 0.00662813 1 0 1 1 0 0 +EDGE2 2253 2232 -0.997109 -0.0974173 0.000733697 1 0 1 1 0 0 +EDGE2 2253 2252 -0.995527 -0.0567923 0.00194569 1 0 1 1 0 0 +EDGE2 2253 1813 0.00554064 -0.00477075 -0.0161343 1 0 1 1 0 0 +EDGE2 2253 2233 0.0326677 0.0942047 -0.0442064 1 0 1 1 0 0 +EDGE2 2253 1814 0.993789 0.0498965 0.0260198 1 0 1 1 0 0 +EDGE2 2254 2234 0.00965922 -0.104301 0.0156682 1 0 1 1 0 0 +EDGE2 2254 2253 -1.03334 -0.0641178 -0.0231453 1 0 1 1 0 0 +EDGE2 2254 1813 -1.0385 -0.0111062 -0.00021707 1 0 1 1 0 0 +EDGE2 2254 2233 -1.06735 0.0175275 0.00862042 1 0 1 1 0 0 +EDGE2 2254 1814 -0.0303251 -0.00906965 -0.0331739 1 0 1 1 0 0 +EDGE2 2254 2235 0.970963 -0.0137603 0.00935207 1 0 1 1 0 0 +EDGE2 2254 1815 1.05565 0.0140442 0.0164555 1 0 1 1 0 0 +EDGE2 2255 2234 -1.08696 -0.00665773 0.00961381 1 0 1 1 0 0 +EDGE2 2255 2254 -1.06486 -0.0465214 0.024059 1 0 1 1 0 0 +EDGE2 2255 1814 -0.997831 -0.0626928 0.00313905 1 0 1 1 0 0 +EDGE2 2255 2235 -0.0270471 0.0395227 -0.00239377 1 0 1 1 0 0 +EDGE2 2255 1815 0.0794167 -0.0687751 0.0167401 1 0 1 1 0 0 +EDGE2 2255 1816 0.0595161 0.979383 1.58522 1 0 1 1 0 0 +EDGE2 2255 2236 0.0258562 1.03949 1.57843 1 0 1 1 0 0 +EDGE2 2256 2235 -1.00278 -0.0210231 1.55103 1 0 1 1 0 0 +EDGE2 2256 2255 -0.977899 0.00670128 1.58707 1 0 1 1 0 0 +EDGE2 2256 1815 -1.00312 -0.058147 1.58385 1 0 1 1 0 0 +EDGE2 2257 2256 -1.0476 -0.0304371 0.00239068 1 0 1 1 0 0 +EDGE2 2258 2257 -0.986032 -0.0245986 -0.0011378 1 0 1 1 0 0 +EDGE2 2259 2258 -0.963523 -0.0567753 -0.033095 1 0 1 1 0 0 +EDGE2 2260 2259 -0.968169 0.0102012 0.0229242 1 0 1 1 0 0 +EDGE2 2261 2260 -0.968096 0.0601889 1.55966 1 0 1 1 0 0 +EDGE2 2262 2261 -1.0846 0.0186602 0.0145632 1 0 1 1 0 0 +EDGE2 2263 2262 -1.10091 -0.0401625 -0.0260163 1 0 1 1 0 0 +EDGE2 2264 2225 0.960863 -0.00213127 -3.14225 1 0 1 1 0 0 +EDGE2 2264 2263 -0.983672 0.066609 -0.0201821 1 0 1 1 0 0 +EDGE2 2265 2264 -0.895279 -0.00336886 0.0327365 1 0 1 1 0 0 +EDGE2 2265 2224 0.90607 -0.00970558 -3.12999 1 0 1 1 0 0 +EDGE2 2265 2225 -0.059645 0.0227574 -3.11858 1 0 1 1 0 0 +EDGE2 2265 2226 -0.0800687 -0.989239 -1.60255 1 0 1 1 0 0 +EDGE2 2266 2265 -0.940563 -0.0329862 1.55499 1 0 1 1 0 0 +EDGE2 2266 2225 -0.914928 0.0839846 -1.55909 1 0 1 1 0 0 +EDGE2 2266 2227 1.07918 0.0190052 0.0331152 1 0 1 1 0 0 +EDGE2 2266 2226 -0.0196707 -0.047381 -0.0199326 1 0 1 1 0 0 +EDGE2 2267 2227 -0.0185762 -0.00177945 -0.0130186 1 0 1 1 0 0 +EDGE2 2267 2226 -0.958507 0.00110046 0.0443282 1 0 1 1 0 0 +EDGE2 2267 2266 -1.02037 -0.00753881 -0.015324 1 0 1 1 0 0 +EDGE2 2267 2228 1.0511 -0.00840435 -0.0398634 1 0 1 1 0 0 +EDGE2 2268 2227 -1.0522 0.0604045 -0.0178527 1 0 1 1 0 0 +EDGE2 2268 2267 -1.08649 0.0137838 0.0101768 1 0 1 1 0 0 +EDGE2 2268 2228 -0.00686648 0.0482542 -0.0276338 1 0 1 1 0 0 +EDGE2 2268 2229 1.02332 -0.0225749 -0.0211639 1 0 1 1 0 0 +EDGE2 2269 2228 -0.974532 0.0105026 0.0026515 1 0 1 1 0 0 +EDGE2 2269 2268 -0.984665 0.050507 -0.024153 1 0 1 1 0 0 +EDGE2 2269 2229 0.0248123 -0.0346554 0.0214357 1 0 1 1 0 0 +EDGE2 2269 1810 1.07067 0.124732 -3.13117 1 0 1 1 0 0 +EDGE2 2269 2250 1.04439 0.0569933 -3.14773 1 0 1 1 0 0 +EDGE2 2269 2230 1.03494 -0.0109421 -0.0310119 1 0 1 1 0 0 +EDGE2 2270 2229 -1.03231 -0.00995102 0.0103883 1 0 1 1 0 0 +EDGE2 2270 2269 -1.02714 0.0226655 -0.0176492 1 0 1 1 0 0 +EDGE2 2270 1810 0.0121422 -0.0447394 -3.16672 1 0 1 1 0 0 +EDGE2 2270 2250 0.0228857 0.0296903 -3.1752 1 0 1 1 0 0 +EDGE2 2270 2230 0.0472937 0.0528689 -0.00108403 1 0 1 1 0 0 +EDGE2 2270 2231 0.046254 -0.851615 -1.55783 1 0 1 1 0 0 +EDGE2 2270 2251 -0.0242514 -1.0428 -1.58145 1 0 1 1 0 0 +EDGE2 2270 1811 -0.0184344 -1.01341 -1.5907 1 0 1 1 0 0 +EDGE2 2270 2249 0.972717 0.00104047 -3.1653 1 0 1 1 0 0 +EDGE2 2270 1809 0.929447 0.00363994 -3.12643 1 0 1 1 0 0 +EDGE2 2271 1810 -0.963009 -0.0272647 -1.55616 1 0 1 1 0 0 +EDGE2 2271 2250 -0.962462 -0.00362632 -1.55671 1 0 1 1 0 0 +EDGE2 2271 2270 -1.01761 -0.0330804 1.58628 1 0 1 1 0 0 +EDGE2 2271 2230 -0.893662 -0.0742078 1.5561 1 0 1 1 0 0 +EDGE2 2271 2231 0.100971 0.138306 -0.0319037 1 0 1 1 0 0 +EDGE2 2271 2251 -0.0599893 -0.0828281 -0.00787724 1 0 1 1 0 0 +EDGE2 2271 1811 0.0486521 0.0371603 0.0180612 1 0 1 1 0 0 +EDGE2 2271 1812 1.02256 -0.00684749 0.0302622 1 0 1 1 0 0 +EDGE2 2271 2232 0.934767 -0.0356368 -0.0121952 1 0 1 1 0 0 +EDGE2 2271 2252 0.989478 0.063831 -0.027007 1 0 1 1 0 0 +EDGE2 2272 2231 -0.951766 0.00223019 0.00280961 1 0 1 1 0 0 +EDGE2 2272 2251 -1.02117 0.0109921 0.00836634 1 0 1 1 0 0 +EDGE2 2272 2271 -0.998294 0.0166325 -0.0362877 1 0 1 1 0 0 +EDGE2 2272 1811 -0.989729 -0.120176 -0.0124737 1 0 1 1 0 0 +EDGE2 2272 2253 1.01171 0.0211435 0.00323757 1 0 1 1 0 0 +EDGE2 2272 1812 0.0417556 0.0354387 -0.0467723 1 0 1 1 0 0 +EDGE2 2272 2232 -0.0352983 -0.126181 0.00760715 1 0 1 1 0 0 +EDGE2 2272 2252 0.0240976 -0.0120517 -0.0299283 1 0 1 1 0 0 +EDGE2 2272 1813 0.949963 -0.00728336 0.0370116 1 0 1 1 0 0 +EDGE2 2272 2233 1.03756 -0.0542714 -0.0153967 1 0 1 1 0 0 +EDGE2 2273 2234 1.0396 -0.0282857 -0.0130267 1 0 1 1 0 0 +EDGE2 2273 2272 -1.04725 0.010381 0.00292502 1 0 1 1 0 0 +EDGE2 2273 2253 0.0558459 -0.0168724 -0.00129994 1 0 1 1 0 0 +EDGE2 2273 1812 -1.09222 0.0186869 0.000795469 1 0 1 1 0 0 +EDGE2 2273 2232 -1.11485 -0.0303011 -0.00249442 1 0 1 1 0 0 +EDGE2 2273 2252 -1.04091 0.0852524 0.0149513 1 0 1 1 0 0 +EDGE2 2273 1813 0.0969013 0.0737523 0.00786206 1 0 1 1 0 0 +EDGE2 2273 2233 0.0911658 0.0237914 -0.0205169 1 0 1 1 0 0 +EDGE2 2273 2254 1.01289 0.0017883 0.00266575 1 0 1 1 0 0 +EDGE2 2273 1814 0.95942 0.0671514 -0.00919886 1 0 1 1 0 0 +EDGE2 2274 2234 -0.0369592 0.0559076 -0.0190215 1 0 1 1 0 0 +EDGE2 2274 2253 -0.956241 0.0819798 -0.00348315 1 0 1 1 0 0 +EDGE2 2274 2273 -1.03422 -0.0826559 -0.000473425 1 0 1 1 0 0 +EDGE2 2274 1813 -0.981878 -0.0787058 0.0159252 1 0 1 1 0 0 +EDGE2 2274 2233 -1.02767 -0.0740127 0.0237645 1 0 1 1 0 0 +EDGE2 2274 2254 0.0740861 -0.0145099 -0.0123906 1 0 1 1 0 0 +EDGE2 2274 1814 0.0131371 0.0302494 -0.0111284 1 0 1 1 0 0 +EDGE2 2274 2235 1.01626 0.0338599 -0.0206287 1 0 1 1 0 0 +EDGE2 2274 2255 0.947244 0.0974983 -0.0143302 1 0 1 1 0 0 +EDGE2 2274 1815 0.949121 0.0743842 0.0139098 1 0 1 1 0 0 +EDGE2 2275 2256 -0.0807985 -1.01716 -1.57605 1 0 1 1 0 0 +EDGE2 2275 2234 -1.05647 0.051909 0.00198063 1 0 1 1 0 0 +EDGE2 2275 2274 -0.983683 -0.0224888 0.00729944 1 0 1 1 0 0 +EDGE2 2275 2254 -0.982162 0.0848683 -0.0177289 1 0 1 1 0 0 +EDGE2 2275 1814 -0.982186 0.0888906 -0.00349178 1 0 1 1 0 0 +EDGE2 2275 2235 -0.0838311 0.0583761 0.00333937 1 0 1 1 0 0 +EDGE2 2275 2255 0.0322842 -0.0772128 0.00769518 1 0 1 1 0 0 +EDGE2 2275 1815 -0.0596747 -0.0156397 0.0249712 1 0 1 1 0 0 +EDGE2 2275 1816 -0.110026 1.01502 1.574 1 0 1 1 0 0 +EDGE2 2275 2236 0.0408007 0.946335 1.60179 1 0 1 1 0 0 +EDGE2 2276 2237 0.933095 0.0420039 -0.0111283 1 0 1 1 0 0 +EDGE2 2276 2235 -0.993946 0.0553599 -1.56416 1 0 1 1 0 0 +EDGE2 2276 2255 -1.03535 -0.00963307 -1.55271 1 0 1 1 0 0 +EDGE2 2276 2275 -0.978926 -0.0500461 -1.54469 1 0 1 1 0 0 +EDGE2 2276 1815 -1.00242 -0.0337453 -1.53865 1 0 1 1 0 0 +EDGE2 2276 1816 -0.0122941 0.0152987 -0.0161468 1 0 1 1 0 0 +EDGE2 2276 2236 -0.052465 0.00170467 0.0328627 1 0 1 1 0 0 +EDGE2 2276 1817 1.02695 -0.12472 -0.042141 1 0 1 1 0 0 +EDGE2 2277 2237 0.0596316 -0.0262159 0.0150429 1 0 1 1 0 0 +EDGE2 2277 2276 -1.10937 0.0381148 -0.0173387 1 0 1 1 0 0 +EDGE2 2277 1816 -0.964018 -0.0768243 -0.00934771 1 0 1 1 0 0 +EDGE2 2277 2236 -0.987172 0.0287585 -0.00325411 1 0 1 1 0 0 +EDGE2 2277 2238 1.05858 -0.0554789 0.0309569 1 0 1 1 0 0 +EDGE2 2277 1817 0.0401997 -0.00998459 -0.0526985 1 0 1 1 0 0 +EDGE2 2277 1818 0.955415 -0.0597753 -0.0349623 1 0 1 1 0 0 +EDGE2 2278 2237 -1.08602 -0.103778 -0.0100091 1 0 1 1 0 0 +EDGE2 2278 2277 -0.998321 0.0428621 -0.00907977 1 0 1 1 0 0 +EDGE2 2278 2238 0.00704264 0.0104476 0.0257719 1 0 1 1 0 0 +EDGE2 2278 1817 -0.969142 -0.00419166 -0.0206018 1 0 1 1 0 0 +EDGE2 2278 1818 0.00127857 0.101764 0.0333333 1 0 1 1 0 0 +EDGE2 2278 2239 1.06236 0.00817676 -0.00570875 1 0 1 1 0 0 +EDGE2 2278 1819 0.966867 -0.022063 -0.0111273 1 0 1 1 0 0 +EDGE2 2279 2238 -0.96296 -0.0835958 0.00865964 1 0 1 1 0 0 +EDGE2 2279 2278 -1.0005 0.0449264 0.0289258 1 0 1 1 0 0 +EDGE2 2279 1818 -1.00892 -0.00745888 0.00740139 1 0 1 1 0 0 +EDGE2 2279 2239 0.00697077 0.0813547 0.0275011 1 0 1 1 0 0 +EDGE2 2279 1819 -0.0318121 -0.00774699 -0.0107294 1 0 1 1 0 0 +EDGE2 2279 1820 0.980275 0.00376905 0.00752574 1 0 1 1 0 0 +EDGE2 2279 2240 1.01793 -0.00555429 -0.0244158 1 0 1 1 0 0 +EDGE2 2279 1240 1.03414 0.021729 -3.16744 1 0 1 1 0 0 +EDGE2 2280 2239 -1.07657 -0.0814787 0.010715 1 0 1 1 0 0 +EDGE2 2280 2279 -0.98289 -0.0737404 -0.034179 1 0 1 1 0 0 +EDGE2 2280 1819 -1.01616 0.0143114 0.00620327 1 0 1 1 0 0 +EDGE2 2280 1821 0.0200342 1.02519 1.54334 1 0 1 1 0 0 +EDGE2 2280 2241 0.0629961 1.05904 1.53002 1 0 1 1 0 0 +EDGE2 2280 1820 -0.0155947 0.0258245 -0.00770861 1 0 1 1 0 0 +EDGE2 2280 2240 0.0472931 -0.0280696 0.00344105 1 0 1 1 0 0 +EDGE2 2280 1240 0.0458152 -0.0460163 -3.13385 1 0 1 1 0 0 +EDGE2 2280 1241 0.0211229 -1.03334 -1.5777 1 0 1 1 0 0 +EDGE2 2280 1239 0.957433 0.0154356 -3.13387 1 0 1 1 0 0 +EDGE2 2281 1820 -0.89213 0.0306666 1.56333 1 0 1 1 0 0 +EDGE2 2281 2240 -0.970757 -0.0561205 1.55454 1 0 1 1 0 0 +EDGE2 2281 2280 -0.996229 0.0309959 1.56215 1 0 1 1 0 0 +EDGE2 2281 1240 -1.04925 -0.0549671 -1.57359 1 0 1 1 0 0 +EDGE2 2281 1241 0.0212086 0.0293083 -0.00183858 1 0 1 1 0 0 +EDGE2 2281 1242 1.00059 0.0668551 -0.0158178 1 0 1 1 0 0 +EDGE2 2282 1241 -1.08105 0.0792927 -0.0109765 1 0 1 1 0 0 +EDGE2 2282 2281 -0.942796 -0.0947966 0.00878802 1 0 1 1 0 0 +EDGE2 2282 1242 0.0537988 0.0296124 0.00605862 1 0 1 1 0 0 +EDGE2 2282 1243 1.06893 0.0525892 -0.000983481 1 0 1 1 0 0 +EDGE2 2283 1242 -0.98475 0.054795 -0.0161837 1 0 1 1 0 0 +EDGE2 2283 2282 -1.0793 -0.0922273 0.00324085 1 0 1 1 0 0 +EDGE2 2283 1243 -0.0874858 0.161514 -0.0210681 1 0 1 1 0 0 +EDGE2 2283 1244 0.965371 -0.0273335 0.00547419 1 0 1 1 0 0 +EDGE2 2284 2283 -0.950329 0.00843254 0.0116506 1 0 1 1 0 0 +EDGE2 2284 1243 -1.01225 -0.0530397 0.0456016 1 0 1 1 0 0 +EDGE2 2284 785 1.02253 -0.0138766 -3.15117 1 0 1 1 0 0 +EDGE2 2284 1244 -0.0735341 -0.0459956 -0.00844892 1 0 1 1 0 0 +EDGE2 2284 1245 1.01832 -0.0399263 -0.00156963 1 0 1 1 0 0 +EDGE2 2284 805 1.04497 0.000938478 -3.1618 1 0 1 1 0 0 +EDGE2 2284 745 1.0371 -0.0173101 -3.11918 1 0 1 1 0 0 +EDGE2 2284 765 1.00424 -0.0243382 -3.13475 1 0 1 1 0 0 +EDGE2 2285 806 -0.0466841 -0.953856 -1.55884 1 0 1 1 0 0 +EDGE2 2285 766 0.0344037 -1.02421 -1.55847 1 0 1 1 0 0 +EDGE2 2285 786 0.0231583 -0.946073 -1.57542 1 0 1 1 0 0 +EDGE2 2285 746 -0.10401 -0.969899 -1.59823 1 0 1 1 0 0 +EDGE2 2285 785 -0.0268831 -0.0214488 -3.17219 1 0 1 1 0 0 +EDGE2 2285 1244 -0.980164 0.0376489 0.0143762 1 0 1 1 0 0 +EDGE2 2285 2284 -0.989564 9.29562e-05 0.0160882 1 0 1 1 0 0 +EDGE2 2285 1245 0.00296324 0.0731533 0.0250152 1 0 1 1 0 0 +EDGE2 2285 805 0.0316345 -0.013167 -3.12251 1 0 1 1 0 0 +EDGE2 2285 784 1.00124 0.0640096 -3.17416 1 0 1 1 0 0 +EDGE2 2285 745 -0.0455377 0.0181995 -3.14588 1 0 1 1 0 0 +EDGE2 2285 765 -0.0195367 0.0703545 -3.14446 1 0 1 1 0 0 +EDGE2 2285 804 0.973724 0.0710036 -3.12398 1 0 1 1 0 0 +EDGE2 2285 744 0.983835 -0.00768286 -3.11018 1 0 1 1 0 0 +EDGE2 2285 764 0.988874 -0.0223829 -3.13261 1 0 1 1 0 0 +EDGE2 2285 1246 0.0103725 0.966634 1.56816 1 0 1 1 0 0 +EDGE2 2286 785 -0.994234 -0.0160254 1.58647 1 0 1 1 0 0 +EDGE2 2286 1245 -1.00559 -0.00738669 -1.53221 1 0 1 1 0 0 +EDGE2 2286 2285 -0.96473 -0.0368428 -1.58194 1 0 1 1 0 0 +EDGE2 2286 805 -1.03361 -0.0010633 1.56271 1 0 1 1 0 0 +EDGE2 2286 745 -1.00426 -0.032343 1.55253 1 0 1 1 0 0 +EDGE2 2286 765 -0.909038 -0.0622023 1.56715 1 0 1 1 0 0 +EDGE2 2286 1246 0.0873612 0.00428744 -0.0159144 1 0 1 1 0 0 +EDGE2 2286 1247 0.975543 0.0343692 0.0264226 1 0 1 1 0 0 +EDGE2 2287 2286 -0.996834 0.0270702 -0.00179421 1 0 1 1 0 0 +EDGE2 2287 1246 -1.04176 -0.0940255 -0.00718277 1 0 1 1 0 0 +EDGE2 2287 1247 -0.029441 0.0423608 -0.0239459 1 0 1 1 0 0 +EDGE2 2287 1248 0.996669 -0.130681 -0.0110616 1 0 1 1 0 0 +EDGE2 2288 2287 -0.943297 0.0153034 0.0172121 1 0 1 1 0 0 +EDGE2 2288 1247 -0.985845 0.00481571 -0.0067036 1 0 1 1 0 0 +EDGE2 2288 1248 -0.0702964 0.0342906 -0.00589051 1 0 1 1 0 0 +EDGE2 2288 1249 1.00992 0.0618102 0.0500466 1 0 1 1 0 0 +EDGE2 2289 1248 -1.024 0.0765231 -0.00952158 1 0 1 1 0 0 +EDGE2 2289 2288 -0.997352 0.0133563 0.035315 1 0 1 1 0 0 +EDGE2 2289 1249 0.0713266 0.0322968 0.00180736 1 0 1 1 0 0 +EDGE2 2289 1250 1.01194 -0.0757634 -0.00329619 1 0 1 1 0 0 +EDGE2 2289 1230 1.08123 -0.0490101 -3.10295 1 0 1 1 0 0 +EDGE2 2290 2289 -1.06603 0.0335219 -0.00854999 1 0 1 1 0 0 +EDGE2 2290 1249 -0.957038 0.0266563 -0.00576693 1 0 1 1 0 0 +EDGE2 2290 1250 -0.0485286 -0.000598961 -0.00113809 1 0 1 1 0 0 +EDGE2 2290 1231 0.0904417 1.01302 1.56809 1 0 1 1 0 0 +EDGE2 2290 1251 0.0488141 1.02946 1.56329 1 0 1 1 0 0 +EDGE2 2290 1230 -0.071802 -0.0288665 -3.15953 1 0 1 1 0 0 +EDGE2 2290 1229 0.953934 0.0614912 -3.11927 1 0 1 1 0 0 +EDGE2 2291 1252 0.986391 0.058489 0.0358377 1 0 1 1 0 0 +EDGE2 2291 1232 0.811776 -0.0445922 0.00869736 1 0 1 1 0 0 +EDGE2 2291 1250 -0.951343 0.0276403 -1.55571 1 0 1 1 0 0 +EDGE2 2291 1231 0.115714 -0.0926148 0.00304753 1 0 1 1 0 0 +EDGE2 2291 1251 -0.0163286 0.108095 0.0346141 1 0 1 1 0 0 +EDGE2 2291 2290 -1.08251 -0.0335936 -1.57475 1 0 1 1 0 0 +EDGE2 2291 1230 -0.972194 0.040447 1.57824 1 0 1 1 0 0 +EDGE2 2292 1233 1.06448 -0.0237124 -0.0250224 1 0 1 1 0 0 +EDGE2 2292 1253 0.977298 0.0241714 -0.0505921 1 0 1 1 0 0 +EDGE2 2292 2291 -1.00941 0.0311682 0.0126912 1 0 1 1 0 0 +EDGE2 2292 1252 -0.0324447 -0.0393413 -0.00653611 1 0 1 1 0 0 +EDGE2 2292 1232 -0.0263144 0.0664707 -0.00215553 1 0 1 1 0 0 +EDGE2 2292 1231 -1.02083 -0.016991 -0.000342024 1 0 1 1 0 0 +EDGE2 2292 1251 -0.973777 0.0642029 -0.00828764 1 0 1 1 0 0 +EDGE2 2293 2292 -0.953938 -0.0240107 -0.00509774 1 0 1 1 0 0 +EDGE2 2293 1254 0.952885 0.00110267 -0.0197184 1 0 1 1 0 0 +EDGE2 2293 1234 1.08885 -0.0683997 8.20106e-05 1 0 1 1 0 0 +EDGE2 2293 1233 0.0867173 -0.0282964 0.0352712 1 0 1 1 0 0 +EDGE2 2293 1253 0.0820596 0.0452022 -0.0261033 1 0 1 1 0 0 +EDGE2 2293 1252 -0.988487 -0.0511214 -0.0402486 1 0 1 1 0 0 +EDGE2 2293 1232 -1.06503 0.109573 -0.00228797 1 0 1 1 0 0 +EDGE2 2294 2293 -1.02987 0.0307655 -0.0349329 1 0 1 1 0 0 +EDGE2 2294 1235 1.01629 0.0150959 -0.0031048 1 0 1 1 0 0 +EDGE2 2294 1255 0.954571 -0.00682478 -0.00501158 1 0 1 1 0 0 +EDGE2 2294 1254 -0.0224362 0.0543859 0.00659038 1 0 1 1 0 0 +EDGE2 2294 1234 -0.0450462 0.0239867 0.0287165 1 0 1 1 0 0 +EDGE2 2294 1233 -0.950929 0.00560298 -7.34372e-06 1 0 1 1 0 0 +EDGE2 2294 1253 -0.99947 0.00396566 0.0144976 1 0 1 1 0 0 +EDGE2 2295 1236 -0.016591 1.04154 1.53619 1 0 1 1 0 0 +EDGE2 2295 1235 -0.011577 0.000287964 0.000261736 1 0 1 1 0 0 +EDGE2 2295 1255 0.00669328 0.0482423 -0.0173641 1 0 1 1 0 0 +EDGE2 2295 1254 -1.09815 -0.0526241 -0.0179137 1 0 1 1 0 0 +EDGE2 2295 2294 -0.931626 -0.0590529 -0.011338 1 0 1 1 0 0 +EDGE2 2295 1234 -1.05915 -0.0428021 -0.00615836 1 0 1 1 0 0 +EDGE2 2295 1256 0.00355746 -1.0134 -1.54961 1 0 1 1 0 0 +EDGE2 2296 1235 -1.00153 0.0394404 1.58534 1 0 1 1 0 0 +EDGE2 2296 2295 -1.02101 0.0758413 1.60152 1 0 1 1 0 0 +EDGE2 2296 1255 -1.02283 -0.00173317 1.58738 1 0 1 1 0 0 +EDGE2 2296 1256 -0.0135442 -0.0432622 -0.00664639 1 0 1 1 0 0 +EDGE2 2296 1257 0.950158 -0.0211152 -0.0118443 1 0 1 1 0 0 +EDGE2 2297 1256 -0.978759 -0.0546255 -0.0114661 1 0 1 1 0 0 +EDGE2 2297 2296 -0.932992 -0.0958459 -0.000915376 1 0 1 1 0 0 +EDGE2 2297 1257 0.031124 -0.0144095 -0.0125253 1 0 1 1 0 0 +EDGE2 2297 1258 0.951526 0.0346518 -0.00581342 1 0 1 1 0 0 +EDGE2 2298 2297 -0.918679 0.0457111 -0.00221142 1 0 1 1 0 0 +EDGE2 2298 1257 -0.918943 0.0299872 -0.0424073 1 0 1 1 0 0 +EDGE2 2298 1258 -0.043694 0.0300648 0.0369877 1 0 1 1 0 0 +EDGE2 2298 1259 0.993748 -0.0481177 -0.00272488 1 0 1 1 0 0 +EDGE2 2299 2298 -1.02252 -0.0488316 -0.0394554 1 0 1 1 0 0 +EDGE2 2299 1258 -1.08922 -0.0381856 0.00590415 1 0 1 1 0 0 +EDGE2 2299 1259 0.0264868 -0.0290887 -0.0157489 1 0 1 1 0 0 +EDGE2 2299 1260 0.971086 0.066224 0.0070838 1 0 1 1 0 0 +EDGE2 2300 1261 0.000679175 0.980745 1.57038 1 0 1 1 0 0 +EDGE2 2300 2299 -0.952792 -0.0464553 0.00805982 1 0 1 1 0 0 +EDGE2 2300 1259 -1.03025 -0.0208093 -0.0380997 1 0 1 1 0 0 +EDGE2 2300 1260 -0.0212231 0.0535073 -0.025192 1 0 1 1 0 0 +EDGE2 2301 1262 0.973119 0.0337715 0.00431338 1 0 1 1 0 0 +EDGE2 2301 1261 -0.0389315 0.0594071 -0.0305668 1 0 1 1 0 0 +EDGE2 2301 2300 -1.01633 -0.00122001 -1.55815 1 0 1 1 0 0 +EDGE2 2301 1260 -1.00508 -0.0907368 -1.59828 1 0 1 1 0 0 +EDGE2 2302 1263 0.935773 0.0408394 -0.0159596 1 0 1 1 0 0 +EDGE2 2302 1262 -0.108275 0.0089081 0.0258675 1 0 1 1 0 0 +EDGE2 2302 2301 -0.900742 -0.0177196 0.0572032 1 0 1 1 0 0 +EDGE2 2302 1261 -1.02505 -0.0183387 -0.0210575 1 0 1 1 0 0 +EDGE2 2303 1264 1.00837 -0.0367522 0.00856362 1 0 1 1 0 0 +EDGE2 2303 2302 -1.02742 0.0254297 -0.00412399 1 0 1 1 0 0 +EDGE2 2303 1263 -0.00367063 0.0474429 0.0216899 1 0 1 1 0 0 +EDGE2 2303 1262 -1.04124 0.0591984 -0.0609174 1 0 1 1 0 0 +EDGE2 2304 1265 1.038 -0.0605345 0.000297023 1 0 1 1 0 0 +EDGE2 2304 1565 0.845558 -0.013559 -3.13911 1 0 1 1 0 0 +EDGE2 2304 1585 1.0286 -0.0725465 -3.16535 1 0 1 1 0 0 +EDGE2 2304 1845 0.996837 -0.0215148 -3.15206 1 0 1 1 0 0 +EDGE2 2304 1545 0.970015 -0.00692949 -3.16529 1 0 1 1 0 0 +EDGE2 2304 1264 -0.0763537 -0.107153 -0.0347525 1 0 1 1 0 0 +EDGE2 2304 2303 -0.95635 0.0288484 0.0254835 1 0 1 1 0 0 +EDGE2 2304 1263 -0.979656 -0.0534436 0.0107118 1 0 1 1 0 0 +EDGE2 2305 1564 0.980014 -0.00556851 -3.19705 1 0 1 1 0 0 +EDGE2 2305 1844 0.944699 -0.00142102 -3.12531 1 0 1 1 0 0 +EDGE2 2305 1584 1.02854 0.0351661 -3.16252 1 0 1 1 0 0 +EDGE2 2305 1544 1.03619 0.0179263 -3.15982 1 0 1 1 0 0 +EDGE2 2305 1546 0.00803287 0.977603 1.59569 1 0 1 1 0 0 +EDGE2 2305 1265 -0.0328491 0.0665597 0.0256264 1 0 1 1 0 0 +EDGE2 2305 1565 -0.119813 -0.0151399 -3.14405 1 0 1 1 0 0 +EDGE2 2305 1585 -0.0460685 -0.0407985 -3.12012 1 0 1 1 0 0 +EDGE2 2305 1845 0.0492564 -0.0350624 -3.1679 1 0 1 1 0 0 +EDGE2 2305 1545 -0.0467493 -0.0047818 -3.15945 1 0 1 1 0 0 +EDGE2 2305 1264 -0.944001 -0.0374771 -0.0225072 1 0 1 1 0 0 +EDGE2 2305 2304 -0.977843 -0.0167068 -0.00144829 1 0 1 1 0 0 +EDGE2 2305 1566 0.014011 -1.00116 -1.58179 1 0 1 1 0 0 +EDGE2 2305 1846 0.00679061 -0.978924 -1.57406 1 0 1 1 0 0 +EDGE2 2305 1586 0.0263921 -0.997853 -1.53575 1 0 1 1 0 0 +EDGE2 2305 1266 0.0429512 -0.992628 -1.57579 1 0 1 1 0 0 +EDGE2 2306 1265 -0.972145 0.0429318 1.59735 1 0 1 1 0 0 +EDGE2 2306 2305 -1.01102 -0.00253553 1.53446 1 0 1 1 0 0 +EDGE2 2306 1565 -1.02304 -0.00590917 -1.57176 1 0 1 1 0 0 +EDGE2 2306 1585 -0.938706 -0.00120406 -1.60119 1 0 1 1 0 0 +EDGE2 2306 1845 -0.998634 -0.0350056 -1.54821 1 0 1 1 0 0 +EDGE2 2306 1545 -1.04114 -0.0288949 -1.5907 1 0 1 1 0 0 +EDGE2 2306 1567 1.0344 -0.0430537 0.0356184 1 0 1 1 0 0 +EDGE2 2306 1587 0.990568 0.0583289 -0.0368308 1 0 1 1 0 0 +EDGE2 2306 1566 0.0189961 0.015013 0.0208599 1 0 1 1 0 0 +EDGE2 2306 1846 -0.00747922 -0.0678984 0.00723936 1 0 1 1 0 0 +EDGE2 2306 1586 0.048874 0.0429494 -0.0020508 1 0 1 1 0 0 +EDGE2 2306 1266 0.0434973 -0.017446 0.0114342 1 0 1 1 0 0 +EDGE2 2306 1847 0.99927 -0.0245754 -0.0306979 1 0 1 1 0 0 +EDGE2 2306 1267 0.997252 -0.032706 -0.00178968 1 0 1 1 0 0 +EDGE2 2307 1567 0.0150097 0.0538267 0.0242705 1 0 1 1 0 0 +EDGE2 2307 1587 0.0529162 0.0259437 0.0207199 1 0 1 1 0 0 +EDGE2 2307 1566 -0.910494 -0.0133521 -0.0187671 1 0 1 1 0 0 +EDGE2 2307 1846 -0.956738 -0.0393337 0.00798678 1 0 1 1 0 0 +EDGE2 2307 2306 -0.917006 -0.0104554 -0.016613 1 0 1 1 0 0 +EDGE2 2307 1586 -1.04386 0.040976 0.0489173 1 0 1 1 0 0 +EDGE2 2307 1266 -1.04411 0.0514959 -0.000965115 1 0 1 1 0 0 +EDGE2 2307 1847 0.0752599 0.035265 -0.0174102 1 0 1 1 0 0 +EDGE2 2307 1588 1.03184 -0.0047991 -0.0558124 1 0 1 1 0 0 +EDGE2 2307 1267 0.0377517 -0.0513204 0.0107571 1 0 1 1 0 0 +EDGE2 2307 1848 1.00917 0.107668 0.0137563 1 0 1 1 0 0 +EDGE2 2307 1268 1.17867 -0.0050377 0.0291315 1 0 1 1 0 0 +EDGE2 2307 1568 1.0191 0.0268793 -0.0132053 1 0 1 1 0 0 +EDGE2 2308 1567 -1.01819 -0.0706616 -0.00344801 1 0 1 1 0 0 +EDGE2 2308 1587 -1.02545 0.0130972 -0.00122149 1 0 1 1 0 0 +EDGE2 2308 2307 -0.926734 -0.0123968 0.00379213 1 0 1 1 0 0 +EDGE2 2308 1847 -1.1464 0.0123659 0.0235258 1 0 1 1 0 0 +EDGE2 2308 1849 0.940154 -0.000438426 -0.0109708 1 0 1 1 0 0 +EDGE2 2308 1588 0.0354584 -0.0169309 0.0293351 1 0 1 1 0 0 +EDGE2 2308 1267 -0.979473 0.00176881 -0.0108332 1 0 1 1 0 0 +EDGE2 2308 1848 0.0527921 0.0318219 -0.0056478 1 0 1 1 0 0 +EDGE2 2308 1268 0.0198723 -0.0514746 0.00459369 1 0 1 1 0 0 +EDGE2 2308 1568 -0.00473731 0.0122894 -0.0188757 1 0 1 1 0 0 +EDGE2 2308 1569 1.0545 0.0706566 -0.00181258 1 0 1 1 0 0 +EDGE2 2308 1589 1.0533 -0.00799771 0.00289958 1 0 1 1 0 0 +EDGE2 2308 1269 1.04532 0.0721634 0.0193798 1 0 1 1 0 0 +EDGE2 2309 1849 0.123529 0.00645597 0.00819517 1 0 1 1 0 0 +EDGE2 2309 1588 -1.00397 -0.0186109 0.0186316 1 0 1 1 0 0 +EDGE2 2309 2308 -0.948619 -0.00280652 -0.00809197 1 0 1 1 0 0 +EDGE2 2309 1848 -0.995089 0.026757 0.00726521 1 0 1 1 0 0 +EDGE2 2309 1268 -0.982973 0.00779727 0.0273274 1 0 1 1 0 0 +EDGE2 2309 1568 -1.02307 -0.084185 -0.0369971 1 0 1 1 0 0 +EDGE2 2309 1569 0.0195786 -0.0197713 -0.00472322 1 0 1 1 0 0 +EDGE2 2309 1589 -0.0211842 -0.0244076 -0.0089295 1 0 1 1 0 0 +EDGE2 2309 1269 -0.0735596 -0.0158389 -0.00162032 1 0 1 1 0 0 +EDGE2 2309 1590 1.03587 0.0844523 0.0109911 1 0 1 1 0 0 +EDGE2 2309 1850 0.933139 -0.0111081 -0.0150953 1 0 1 1 0 0 +EDGE2 2309 1270 0.968688 -0.0257364 -0.0205233 1 0 1 1 0 0 +EDGE2 2309 1290 0.99227 -0.0605299 -3.10863 1 0 1 1 0 0 +EDGE2 2309 1570 1.07066 -0.0842309 0.00456073 1 0 1 1 0 0 +EDGE2 2310 1851 0.00245614 0.975319 1.5918 1 0 1 1 0 0 +EDGE2 2310 1571 0.0580556 0.967362 1.5945 1 0 1 1 0 0 +EDGE2 2310 1591 0.0714705 0.965981 1.57002 1 0 1 1 0 0 +EDGE2 2310 1849 -1.04543 0.030159 -0.0107918 1 0 1 1 0 0 +EDGE2 2310 2309 -0.976015 -0.0811867 0.0105248 1 0 1 1 0 0 +EDGE2 2310 1569 -0.984657 0.057357 -0.0236883 1 0 1 1 0 0 +EDGE2 2310 1589 -0.991426 0.0419789 -0.0383638 1 0 1 1 0 0 +EDGE2 2310 1269 -0.970008 -0.012483 -0.00351345 1 0 1 1 0 0 +EDGE2 2310 1291 -0.0117229 -0.956719 -1.57176 1 0 1 1 0 0 +EDGE2 2310 1590 0.0126368 0.0704599 0.00819683 1 0 1 1 0 0 +EDGE2 2310 1850 -0.0520006 -0.0085177 -8.08305e-05 1 0 1 1 0 0 +EDGE2 2310 1270 -0.0276749 0.0150729 -0.0229271 1 0 1 1 0 0 +EDGE2 2310 1290 0.00695759 -0.0426871 -3.11986 1 0 1 1 0 0 +EDGE2 2310 1570 0.117504 0.079667 -0.013795 1 0 1 1 0 0 +EDGE2 2310 1271 0.0725427 -0.991949 -1.52324 1 0 1 1 0 0 +EDGE2 2310 1289 0.998774 -0.0364363 -3.13351 1 0 1 1 0 0 +EDGE2 2311 1851 0.0210626 0.000702955 -0.00294098 1 0 1 1 0 0 +EDGE2 2311 1852 1.04947 0.122094 0.012644 1 0 1 1 0 0 +EDGE2 2311 1572 1.00723 0.0665485 -0.0192633 1 0 1 1 0 0 +EDGE2 2311 1592 1.03669 0.036314 0.0163737 1 0 1 1 0 0 +EDGE2 2311 1571 0.0293622 0.0672679 0.00137832 1 0 1 1 0 0 +EDGE2 2311 1591 -0.0437962 -0.0413055 0.00359373 1 0 1 1 0 0 +EDGE2 2311 1590 -1.10609 -0.117709 -1.55326 1 0 1 1 0 0 +EDGE2 2311 2310 -1.05429 0.0347009 -1.58543 1 0 1 1 0 0 +EDGE2 2311 1850 -1.01611 -0.0397139 -1.56995 1 0 1 1 0 0 +EDGE2 2311 1270 -0.967076 0.0415639 -1.58441 1 0 1 1 0 0 +EDGE2 2311 1290 -1.01098 0.0616318 1.56762 1 0 1 1 0 0 +EDGE2 2311 1570 -0.928844 -0.0921217 -1.55565 1 0 1 1 0 0 +EDGE2 2312 1851 -1.04281 -0.00822592 -0.0443714 1 0 1 1 0 0 +EDGE2 2312 1853 1.00825 -0.0733084 0.00688546 1 0 1 1 0 0 +EDGE2 2312 1852 0.0445934 -0.0341847 -0.0167182 1 0 1 1 0 0 +EDGE2 2312 1573 0.977833 -0.0380096 -0.00181154 1 0 1 1 0 0 +EDGE2 2312 1593 1.01076 -0.00689968 0.0172399 1 0 1 1 0 0 +EDGE2 2312 1572 0.00110451 0.0242433 0.00913925 1 0 1 1 0 0 +EDGE2 2312 1592 0.0257191 -0.0262674 0.00410719 1 0 1 1 0 0 +EDGE2 2312 2311 -1.01313 -0.00574756 -0.0290886 1 0 1 1 0 0 +EDGE2 2312 1571 -1.05659 -0.0153523 -0.0141039 1 0 1 1 0 0 +EDGE2 2312 1591 -1.00638 0.151622 -0.0181014 1 0 1 1 0 0 +EDGE2 2313 1853 0.0270935 -0.0680472 -0.000717323 1 0 1 1 0 0 +EDGE2 2313 1854 1.00536 0.0927596 -0.0271453 1 0 1 1 0 0 +EDGE2 2313 1574 0.905325 0.0596693 -0.000481459 1 0 1 1 0 0 +EDGE2 2313 1594 0.877715 -0.049566 -0.00376044 1 0 1 1 0 0 +EDGE2 2313 1852 -1.01835 0.027968 -0.0161285 1 0 1 1 0 0 +EDGE2 2313 1573 -0.00299058 -0.0720915 0.0105658 1 0 1 1 0 0 +EDGE2 2313 1593 -0.0297982 -0.0528574 -0.0287274 1 0 1 1 0 0 +EDGE2 2313 2312 -0.94983 -0.0715598 0.0119405 1 0 1 1 0 0 +EDGE2 2313 1572 -1.0059 0.00698471 0.00878028 1 0 1 1 0 0 +EDGE2 2313 1592 -0.961172 -0.0117521 0.0109365 1 0 1 1 0 0 +EDGE2 2314 1535 0.962772 -0.0312145 -3.13105 1 0 1 1 0 0 +EDGE2 2314 1855 0.995269 0.0217447 0.0346518 1 0 1 1 0 0 +EDGE2 2314 1595 1.05543 -0.0323051 -0.0026387 1 0 1 1 0 0 +EDGE2 2314 1655 0.921007 0.0317547 -3.14998 1 0 1 1 0 0 +EDGE2 2314 1575 0.934214 -0.0484596 0.00608045 1 0 1 1 0 0 +EDGE2 2314 1853 -0.980961 -0.00307375 0.0382101 1 0 1 1 0 0 +EDGE2 2314 1854 0.0362911 -0.0303286 -0.0142494 1 0 1 1 0 0 +EDGE2 2314 1375 1.07038 -0.0044111 -3.16244 1 0 1 1 0 0 +EDGE2 2314 1515 1.00395 -0.0564526 -3.11138 1 0 1 1 0 0 +EDGE2 2314 1574 -0.0257981 0.0152941 0.0309614 1 0 1 1 0 0 +EDGE2 2314 1594 -0.00313021 -0.0599932 0.0205385 1 0 1 1 0 0 +EDGE2 2314 2313 -0.925752 -0.0717818 0.00754021 1 0 1 1 0 0 +EDGE2 2314 1573 -0.995494 -0.00706012 -0.0357747 1 0 1 1 0 0 +EDGE2 2314 1593 -1.03118 0.019589 0.00327269 1 0 1 1 0 0 +EDGE2 2315 1656 0.0321642 1.01029 1.56473 1 0 1 1 0 0 +EDGE2 2315 1856 0.0415677 1.00678 1.59177 1 0 1 1 0 0 +EDGE2 2315 1536 0.00228734 0.983228 1.5536 1 0 1 1 0 0 +EDGE2 2315 1576 0.0461966 0.866706 1.57396 1 0 1 1 0 0 +EDGE2 2315 1376 -0.0661908 1.09067 1.57561 1 0 1 1 0 0 +EDGE2 2315 1535 0.0230992 -0.0127592 -3.1331 1 0 1 1 0 0 +EDGE2 2315 1514 0.924866 0.00245059 -3.13299 1 0 1 1 0 0 +EDGE2 2315 1654 0.907211 -0.0613618 -3.1092 1 0 1 1 0 0 +EDGE2 2315 1534 0.926573 -0.0313705 -3.1151 1 0 1 1 0 0 +EDGE2 2315 1374 1.0361 -0.0171119 -3.13638 1 0 1 1 0 0 +EDGE2 2315 1855 -0.0295673 -0.0933436 -0.0198556 1 0 1 1 0 0 +EDGE2 2315 1595 0.0285219 0.0604185 -0.00171031 1 0 1 1 0 0 +EDGE2 2315 1655 0.047046 0.00804752 -3.15618 1 0 1 1 0 0 +EDGE2 2315 1575 -0.035135 -0.0381993 0.0166181 1 0 1 1 0 0 +EDGE2 2315 1854 -1.03632 0.0484529 -0.0159674 1 0 1 1 0 0 +EDGE2 2315 1375 -0.108554 0.0491528 -3.13446 1 0 1 1 0 0 +EDGE2 2315 1515 0.0324709 0.0341347 -3.1464 1 0 1 1 0 0 +EDGE2 2315 2314 -0.978895 0.0126063 0.00722248 1 0 1 1 0 0 +EDGE2 2315 1574 -0.912284 -0.0293629 0.0274428 1 0 1 1 0 0 +EDGE2 2315 1594 -0.960653 0.0169973 -0.0226203 1 0 1 1 0 0 +EDGE2 2315 1516 0.0650626 -0.98438 -1.55687 1 0 1 1 0 0 +EDGE2 2315 1596 0.0855636 -0.970138 -1.53698 1 0 1 1 0 0 +EDGE2 2316 1535 -0.947125 0.0509977 -1.60673 1 0 1 1 0 0 +EDGE2 2316 1855 -0.989283 0.0182791 1.544 1 0 1 1 0 0 +EDGE2 2316 2315 -1.01835 -0.0558138 1.56585 1 0 1 1 0 0 +EDGE2 2316 1595 -1.0446 0.12506 1.56327 1 0 1 1 0 0 +EDGE2 2316 1655 -0.913998 0.0393121 -1.56025 1 0 1 1 0 0 +EDGE2 2316 1575 -0.97734 6.72566e-05 1.57973 1 0 1 1 0 0 +EDGE2 2316 1375 -0.814314 0.0175117 -1.56402 1 0 1 1 0 0 +EDGE2 2316 1515 -0.95788 0.0195189 -1.57354 1 0 1 1 0 0 +EDGE2 2316 1516 -0.0194679 -0.00103516 -0.00168446 1 0 1 1 0 0 +EDGE2 2316 1596 -0.0106961 -0.00113066 0.00641737 1 0 1 1 0 0 +EDGE2 2316 1597 0.933541 0.0520136 -0.0368912 1 0 1 1 0 0 +EDGE2 2316 1517 1.01805 0.0169824 -0.00958318 1 0 1 1 0 0 +EDGE2 2317 1516 -0.973166 0.0222883 0.0267451 1 0 1 1 0 0 +EDGE2 2317 1596 -1.02515 -0.04573 -0.0345262 1 0 1 1 0 0 +EDGE2 2317 2316 -1.04656 -0.0194527 0.00608194 1 0 1 1 0 0 +EDGE2 2317 1597 -0.0592268 -0.0757192 -0.0417627 1 0 1 1 0 0 +EDGE2 2317 1517 0.0070036 0.0106187 -0.0430078 1 0 1 1 0 0 +EDGE2 2317 1598 1.03518 0.036892 0.0192392 1 0 1 1 0 0 +EDGE2 2317 1518 1.03699 0.0253103 0.000750984 1 0 1 1 0 0 +EDGE2 2318 1597 -1.01099 0.0553005 -0.00472447 1 0 1 1 0 0 +EDGE2 2318 2317 -1.07962 0.126934 0.0533126 1 0 1 1 0 0 +EDGE2 2318 1517 -0.948814 -0.00502686 -0.00829731 1 0 1 1 0 0 +EDGE2 2318 1598 0.0223156 -0.00183106 -0.0168558 1 0 1 1 0 0 +EDGE2 2318 1518 -0.014814 -0.0419225 -0.019339 1 0 1 1 0 0 +EDGE2 2318 1599 0.906223 0.0261311 0.00956973 1 0 1 1 0 0 +EDGE2 2318 1519 1.04294 0.0222238 0.0224358 1 0 1 1 0 0 +EDGE2 2319 1598 -1.0656 -0.0706686 0.0483851 1 0 1 1 0 0 +EDGE2 2319 2318 -0.967122 0.00596335 -0.0250944 1 0 1 1 0 0 +EDGE2 2319 1518 -0.999417 0.0525536 -0.0301278 1 0 1 1 0 0 +EDGE2 2319 1599 0.132307 -0.096248 0.0299923 1 0 1 1 0 0 +EDGE2 2319 1519 0.0270413 0.0332422 0.00845524 1 0 1 1 0 0 +EDGE2 2319 1520 1.06729 0.0203329 0.0326521 1 0 1 1 0 0 +EDGE2 2319 1620 1.00711 -0.0160482 -3.13817 1 0 1 1 0 0 +EDGE2 2319 1640 1.08284 0.0130007 -3.13916 1 0 1 1 0 0 +EDGE2 2319 1600 0.982427 -0.0127114 0.0174518 1 0 1 1 0 0 +EDGE2 2319 1320 1.00672 0.0180795 -3.14363 1 0 1 1 0 0 +EDGE2 2320 1599 -0.990867 -0.00550522 -0.0284896 1 0 1 1 0 0 +EDGE2 2320 2319 -1.04674 -0.0337076 0.0122502 1 0 1 1 0 0 +EDGE2 2320 1519 -1.07016 -0.086242 0.0153222 1 0 1 1 0 0 +EDGE2 2320 1521 0.114532 0.990934 1.57875 1 0 1 1 0 0 +EDGE2 2320 1641 0.0327883 0.982359 1.55517 1 0 1 1 0 0 +EDGE2 2320 1321 0.0464333 1.06427 1.61291 1 0 1 1 0 0 +EDGE2 2320 1520 0.0216386 -0.0179292 0.00301867 1 0 1 1 0 0 +EDGE2 2320 1620 -0.0295271 -0.0318911 -3.16845 1 0 1 1 0 0 +EDGE2 2320 1640 0.0113679 -0.0143026 -3.14486 1 0 1 1 0 0 +EDGE2 2320 1600 0.0251609 -0.0385843 0.0114057 1 0 1 1 0 0 +EDGE2 2320 1621 -0.00920159 -1.01173 -1.56029 1 0 1 1 0 0 +EDGE2 2320 1320 -0.0602577 -0.0806227 -3.1817 1 0 1 1 0 0 +EDGE2 2320 1601 0.00495171 -0.933156 -1.55285 1 0 1 1 0 0 +EDGE2 2320 1619 1.0249 -0.0188566 -3.11838 1 0 1 1 0 0 +EDGE2 2320 1639 0.984203 -0.0214042 -3.12296 1 0 1 1 0 0 +EDGE2 2320 1319 0.932497 -0.0037438 -3.15252 1 0 1 1 0 0 +EDGE2 2321 1322 0.909927 -0.000698878 0.0364409 1 0 1 1 0 0 +EDGE2 2321 1642 1.00356 0.0102963 0.0396656 1 0 1 1 0 0 +EDGE2 2321 1522 0.931168 -0.0947409 0.0205696 1 0 1 1 0 0 +EDGE2 2321 1521 0.0351178 0.0644435 0.0583464 1 0 1 1 0 0 +EDGE2 2321 1641 0.00626456 -0.000966798 -0.00791992 1 0 1 1 0 0 +EDGE2 2321 1321 0.00649261 -0.0486355 0.00615781 1 0 1 1 0 0 +EDGE2 2321 1520 -1.01292 -0.00200915 -1.59093 1 0 1 1 0 0 +EDGE2 2321 1620 -0.958297 -0.0159085 1.57558 1 0 1 1 0 0 +EDGE2 2321 1640 -1.01058 -0.00704422 1.60103 1 0 1 1 0 0 +EDGE2 2321 2320 -1.09156 -0.0468556 -1.59569 1 0 1 1 0 0 +EDGE2 2321 1600 -0.928865 -0.0261049 -1.57251 1 0 1 1 0 0 +EDGE2 2321 1320 -1.02616 -0.131582 1.58456 1 0 1 1 0 0 +EDGE2 2322 1323 1.01927 -0.0695526 0.0233045 1 0 1 1 0 0 +EDGE2 2322 1643 1.06618 -0.00940044 -0.0212448 1 0 1 1 0 0 +EDGE2 2322 1523 0.976743 0.0405378 -0.016492 1 0 1 1 0 0 +EDGE2 2322 1322 0.00634972 0.0489311 0.0122897 1 0 1 1 0 0 +EDGE2 2322 1642 0.0860584 -0.0130948 -0.00486107 1 0 1 1 0 0 +EDGE2 2322 1522 -0.0604162 -0.0306504 -0.00244046 1 0 1 1 0 0 +EDGE2 2322 1521 -0.989867 0.00882731 0.0402896 1 0 1 1 0 0 +EDGE2 2322 1641 -0.980983 0.130555 0.0102763 1 0 1 1 0 0 +EDGE2 2322 2321 -0.985482 -0.0419972 -0.00513515 1 0 1 1 0 0 +EDGE2 2322 1321 -0.995323 -0.0121308 0.0519101 1 0 1 1 0 0 +EDGE2 2323 1524 1.01383 0.0110372 0.0193177 1 0 1 1 0 0 +EDGE2 2323 1644 0.975682 -0.00547791 -0.000229869 1 0 1 1 0 0 +EDGE2 2323 1324 1.0234 0.0988168 -0.00133026 1 0 1 1 0 0 +EDGE2 2323 1323 -0.0256091 -0.0447572 -0.0514566 1 0 1 1 0 0 +EDGE2 2323 1643 0.104276 0.00882661 -0.00691356 1 0 1 1 0 0 +EDGE2 2323 1523 0.00525047 0.00738195 0.0518323 1 0 1 1 0 0 +EDGE2 2323 1322 -0.921056 0.0720166 0.0266728 1 0 1 1 0 0 +EDGE2 2323 1642 -0.98426 0.0734663 -0.0192563 1 0 1 1 0 0 +EDGE2 2323 2322 -0.986549 0.151582 -0.0124045 1 0 1 1 0 0 +EDGE2 2323 1522 -0.996338 0.017901 -0.00114477 1 0 1 1 0 0 +EDGE2 2324 1345 0.992384 0.0118178 -3.13929 1 0 1 1 0 0 +EDGE2 2324 1525 0.944521 -0.0253519 0.0153202 1 0 1 1 0 0 +EDGE2 2324 1905 0.926701 0.000981021 -3.14655 1 0 1 1 0 0 +EDGE2 2324 1925 1.03155 0.0401244 -3.12799 1 0 1 1 0 0 +EDGE2 2324 1645 0.949588 -0.0475185 -0.0169193 1 0 1 1 0 0 +EDGE2 2324 1485 1.04711 0.0311911 -3.14074 1 0 1 1 0 0 +EDGE2 2324 1505 1.08123 0.0183751 -3.13959 1 0 1 1 0 0 +EDGE2 2324 1365 1.03317 -0.0100865 -3.14495 1 0 1 1 0 0 +EDGE2 2324 1325 1.05985 -0.0594189 -0.0178761 1 0 1 1 0 0 +EDGE2 2324 1524 -0.0497548 0.0626769 -0.0114302 1 0 1 1 0 0 +EDGE2 2324 1644 -0.0374948 0.0657164 -0.0107755 1 0 1 1 0 0 +EDGE2 2324 1324 -0.000966176 0.00544833 0.0292376 1 0 1 1 0 0 +EDGE2 2324 1323 -1.02912 0.0344644 0.0523848 1 0 1 1 0 0 +EDGE2 2324 1643 -1.06826 0.00073217 0.0155318 1 0 1 1 0 0 +EDGE2 2324 2323 -0.960489 -0.0253323 0.00917573 1 0 1 1 0 0 +EDGE2 2324 1523 -0.943093 -0.0384004 0.00485456 1 0 1 1 0 0 +EDGE2 2325 1345 -0.0148334 -0.0242278 -3.14988 1 0 1 1 0 0 +EDGE2 2325 1526 0.00237261 0.97707 1.55281 1 0 1 1 0 0 +EDGE2 2325 1926 -0.0512425 0.916844 1.57856 1 0 1 1 0 0 +EDGE2 2325 1646 -0.0455893 1.04977 1.56254 1 0 1 1 0 0 +EDGE2 2325 1366 0.0351134 0.936249 1.57257 1 0 1 1 0 0 +EDGE2 2325 1506 -0.0108162 1.02081 1.56834 1 0 1 1 0 0 +EDGE2 2325 1924 0.982472 0.120081 -3.13893 1 0 1 1 0 0 +EDGE2 2325 1344 1.01353 0.00464408 -3.16247 1 0 1 1 0 0 +EDGE2 2325 1484 0.985054 -0.0467229 -3.13411 1 0 1 1 0 0 +EDGE2 2325 1504 0.956388 -0.00433153 -3.13968 1 0 1 1 0 0 +EDGE2 2325 1904 1.05614 -0.0196309 -3.14405 1 0 1 1 0 0 +EDGE2 2325 1364 0.976104 0.0285974 -3.12867 1 0 1 1 0 0 +EDGE2 2325 1525 0.115235 0.10489 -0.0300198 1 0 1 1 0 0 +EDGE2 2325 1905 -0.013415 -0.0547567 -3.16382 1 0 1 1 0 0 +EDGE2 2325 1925 -0.0154124 0.00428224 -3.14986 1 0 1 1 0 0 +EDGE2 2325 1645 0.117803 -0.0761512 -0.00207321 1 0 1 1 0 0 +EDGE2 2325 1485 0.0282252 0.0166928 -3.13834 1 0 1 1 0 0 +EDGE2 2325 1505 0.0101323 0.0481602 -3.15505 1 0 1 1 0 0 +EDGE2 2325 1365 -0.0865378 0.0684433 -3.13854 1 0 1 1 0 0 +EDGE2 2325 1325 0.0690279 0.0299121 -0.0299165 1 0 1 1 0 0 +EDGE2 2325 1524 -0.992665 0.0909917 -0.011293 1 0 1 1 0 0 +EDGE2 2325 2324 -1.06714 -0.0308649 -0.0206759 1 0 1 1 0 0 +EDGE2 2325 1644 -1.00159 0.00712973 0.0161157 1 0 1 1 0 0 +EDGE2 2325 1324 -0.921286 0.0278215 -0.0215956 1 0 1 1 0 0 +EDGE2 2325 1486 -0.0587229 -0.961548 -1.59645 1 0 1 1 0 0 +EDGE2 2325 1906 -0.0274539 -0.956293 -1.59263 1 0 1 1 0 0 +EDGE2 2325 1326 -0.00190233 -0.970086 -1.55302 1 0 1 1 0 0 +EDGE2 2325 1346 -0.147281 -0.996815 -1.58374 1 0 1 1 0 0 +EDGE2 2326 1345 -0.957905 -0.0296943 1.57624 1 0 1 1 0 0 +EDGE2 2326 1526 0.0620964 0.0160033 -0.018867 1 0 1 1 0 0 +EDGE2 2326 1507 1.02718 -0.0658021 0.0294665 1 0 1 1 0 0 +EDGE2 2326 1527 0.971264 -0.0198367 -0.0128572 1 0 1 1 0 0 +EDGE2 2326 1647 1.06154 0.0306286 -0.00474325 1 0 1 1 0 0 +EDGE2 2326 1927 0.966207 0.0186354 0.024419 1 0 1 1 0 0 +EDGE2 2326 1367 1.02244 0.0888521 -0.0384416 1 0 1 1 0 0 +EDGE2 2326 1926 -0.0345376 0.0400858 -0.000895235 1 0 1 1 0 0 +EDGE2 2326 1646 0.0470975 0.0583924 0.00706154 1 0 1 1 0 0 +EDGE2 2326 1366 0.0150312 0.0597576 0.0298308 1 0 1 1 0 0 +EDGE2 2326 1506 -0.0345721 0.062834 -0.00872531 1 0 1 1 0 0 +EDGE2 2326 1525 -1.01107 0.0142641 -1.59189 1 0 1 1 0 0 +EDGE2 2326 1905 -1.0266 -0.00131588 1.57852 1 0 1 1 0 0 +EDGE2 2326 1925 -0.993564 0.00822934 1.56146 1 0 1 1 0 0 +EDGE2 2326 2325 -0.974448 -0.0362021 -1.55668 1 0 1 1 0 0 +EDGE2 2326 1645 -0.962131 0.0228113 -1.59786 1 0 1 1 0 0 +EDGE2 2326 1485 -0.987706 -0.0280885 1.55286 1 0 1 1 0 0 +EDGE2 2326 1505 -0.955654 0.028861 1.54623 1 0 1 1 0 0 +EDGE2 2326 1365 -1.06026 0.0550088 1.59015 1 0 1 1 0 0 +EDGE2 2326 1325 -1.02288 0.0528273 -1.58278 1 0 1 1 0 0 +EDGE2 2327 1648 0.87298 -0.0329104 0.0213118 1 0 1 1 0 0 +EDGE2 2327 1928 1.01056 -0.0337899 0.00111395 1 0 1 1 0 0 +EDGE2 2327 1368 0.989973 -0.0615544 0.00646193 1 0 1 1 0 0 +EDGE2 2327 1508 0.962944 -0.0344659 0.00367171 1 0 1 1 0 0 +EDGE2 2327 1528 0.986525 -0.0128619 0.0165171 1 0 1 1 0 0 +EDGE2 2327 1526 -1.02123 -0.0853497 -0.0317421 1 0 1 1 0 0 +EDGE2 2327 1507 0.0722434 -0.0752185 0.0322902 1 0 1 1 0 0 +EDGE2 2327 1527 -0.0501136 0.132574 0.0156778 1 0 1 1 0 0 +EDGE2 2327 1647 -0.0267462 -0.0332533 -0.00974089 1 0 1 1 0 0 +EDGE2 2327 1927 0.0313113 -0.0561484 0.000785635 1 0 1 1 0 0 +EDGE2 2327 1367 0.0671313 -0.0524953 0.0125365 1 0 1 1 0 0 +EDGE2 2327 1926 -0.983791 0.0160672 -0.000487557 1 0 1 1 0 0 +EDGE2 2327 2326 -1.01933 -0.0119352 -0.00975648 1 0 1 1 0 0 +EDGE2 2327 1646 -1.00741 -0.029262 -0.011463 1 0 1 1 0 0 +EDGE2 2327 1366 -1.06637 0.0519558 0.020992 1 0 1 1 0 0 +EDGE2 2327 1506 -1.00315 0.0393873 -0.00314441 1 0 1 1 0 0 +EDGE2 2328 2327 -1.04545 -0.0338351 -0.000939274 1 0 1 1 0 0 +EDGE2 2328 1509 0.962968 -0.0563407 0.0198877 1 0 1 1 0 0 +EDGE2 2328 1649 0.983067 0.035855 -0.0368844 1 0 1 1 0 0 +EDGE2 2328 1929 0.935388 0.0862144 0.0384782 1 0 1 1 0 0 +EDGE2 2328 1529 1.00474 -0.0605942 -0.00522142 1 0 1 1 0 0 +EDGE2 2328 1369 1.03201 0.0874929 0.0284333 1 0 1 1 0 0 +EDGE2 2328 1648 -0.0168518 0.0297725 -0.0118319 1 0 1 1 0 0 +EDGE2 2328 1928 -0.0138468 -0.039769 -0.000685798 1 0 1 1 0 0 +EDGE2 2328 1368 -0.00664057 -0.0519016 0.00615917 1 0 1 1 0 0 +EDGE2 2328 1508 0.124877 0.00144318 -0.0120067 1 0 1 1 0 0 +EDGE2 2328 1528 -0.0347599 0.0222008 -0.0027322 1 0 1 1 0 0 +EDGE2 2328 1507 -0.963751 0.0509355 -0.0200255 1 0 1 1 0 0 +EDGE2 2328 1527 -1.01905 0.106277 -0.0293248 1 0 1 1 0 0 +EDGE2 2328 1647 -0.97979 0.00491558 0.00140415 1 0 1 1 0 0 +EDGE2 2328 1927 -0.887087 -0.0601685 0.0115318 1 0 1 1 0 0 +EDGE2 2328 1367 -0.925114 0.0585819 -0.0302302 1 0 1 1 0 0 +EDGE2 2329 1650 1.06194 -0.0147421 -0.0186593 1 0 1 1 0 0 +EDGE2 2329 1710 1.03773 -0.0549877 -3.13792 1 0 1 1 0 0 +EDGE2 2329 1870 0.995437 0.0482224 -3.13166 1 0 1 1 0 0 +EDGE2 2329 1930 1.03348 -0.00772396 0.0197281 1 0 1 1 0 0 +EDGE2 2329 1670 0.908386 0.00513215 -3.13999 1 0 1 1 0 0 +EDGE2 2329 1470 1.02461 0.121318 -3.1709 1 0 1 1 0 0 +EDGE2 2329 1510 1.03264 -0.01671 0.0212825 1 0 1 1 0 0 +EDGE2 2329 1530 1.05841 0.0455094 -0.00496324 1 0 1 1 0 0 +EDGE2 2329 1370 1.06155 0.027806 0.000659932 1 0 1 1 0 0 +EDGE2 2329 1509 0.0175148 0.0385937 -0.0519713 1 0 1 1 0 0 +EDGE2 2329 1649 0.0337994 -0.0708433 0.0269863 1 0 1 1 0 0 +EDGE2 2329 1929 -0.100347 -0.0497911 0.00132854 1 0 1 1 0 0 +EDGE2 2329 1529 -0.0267476 0.0192384 0.0217433 1 0 1 1 0 0 +EDGE2 2329 1369 -0.093361 -0.0349826 0.00753749 1 0 1 1 0 0 +EDGE2 2329 1648 -1.07211 -0.0167457 0.0232614 1 0 1 1 0 0 +EDGE2 2329 1928 -0.94146 -0.00283871 0.000139407 1 0 1 1 0 0 +EDGE2 2329 2328 -1.03183 -0.0902934 -0.043417 1 0 1 1 0 0 +EDGE2 2329 1368 -1.03211 -0.0329813 0.00417471 1 0 1 1 0 0 +EDGE2 2329 1508 -1.03859 -0.0168646 -0.00139132 1 0 1 1 0 0 +EDGE2 2329 1528 -0.984656 -0.0215083 -0.00310365 1 0 1 1 0 0 +EDGE2 2330 1931 -0.0500384 -0.935075 -1.58349 1 0 1 1 0 0 +EDGE2 2330 1669 1.00733 -0.0263626 -3.14318 1 0 1 1 0 0 +EDGE2 2330 1709 0.994357 -0.0293264 -3.12052 1 0 1 1 0 0 +EDGE2 2330 1869 1.03422 0.0146589 -3.14528 1 0 1 1 0 0 +EDGE2 2330 1469 0.945106 -0.00971415 -3.16402 1 0 1 1 0 0 +EDGE2 2330 1671 -0.0780067 -1.03619 -1.54418 1 0 1 1 0 0 +EDGE2 2330 1711 0.0684923 -0.993521 -1.56168 1 0 1 1 0 0 +EDGE2 2330 1871 -0.00207575 -1.08536 -1.56839 1 0 1 1 0 0 +EDGE2 2330 1471 0.0349002 -1.03984 -1.55041 1 0 1 1 0 0 +EDGE2 2330 1650 -0.00908462 -0.0841157 0.0271951 1 0 1 1 0 0 +EDGE2 2330 1710 0.0158627 0.0233514 -3.13886 1 0 1 1 0 0 +EDGE2 2330 1870 0.0190736 0.02709 -3.15865 1 0 1 1 0 0 +EDGE2 2330 1930 0.0739615 -0.00155005 0.019948 1 0 1 1 0 0 +EDGE2 2330 1670 -0.0555822 -0.0918662 -3.1276 1 0 1 1 0 0 +EDGE2 2330 1470 0.0278917 -0.0688881 -3.12992 1 0 1 1 0 0 +EDGE2 2330 1510 -0.0627668 -0.0739149 0.00776917 1 0 1 1 0 0 +EDGE2 2330 1530 0.0214006 -0.0084206 -0.0407541 1 0 1 1 0 0 +EDGE2 2330 1370 0.0126815 -0.110088 0.0137075 1 0 1 1 0 0 +EDGE2 2330 1371 -0.000450182 0.925652 1.55605 1 0 1 1 0 0 +EDGE2 2330 1531 -0.0669701 0.928977 1.5915 1 0 1 1 0 0 +EDGE2 2330 1651 -0.0367707 1.06219 1.59039 1 0 1 1 0 0 +EDGE2 2330 1511 -0.0347359 0.946578 1.53542 1 0 1 1 0 0 +EDGE2 2330 1509 -0.922773 0.00190479 0.00345791 1 0 1 1 0 0 +EDGE2 2330 1649 -0.947414 -0.043911 0.00128802 1 0 1 1 0 0 +EDGE2 2330 1929 -0.929845 -0.00301705 0.0364543 1 0 1 1 0 0 +EDGE2 2330 2329 -0.975461 -0.00245337 -0.00130115 1 0 1 1 0 0 +EDGE2 2330 1529 -0.943586 0.0559801 0.00104389 1 0 1 1 0 0 +EDGE2 2330 1369 -1.05919 -0.0424447 0.0350253 1 0 1 1 0 0 +EDGE2 2331 2330 -1.0146 0.0185095 -1.52255 1 0 1 1 0 0 +EDGE2 2331 1650 -0.957293 0.109135 -1.5423 1 0 1 1 0 0 +EDGE2 2331 1710 -1.01145 -0.0485501 1.56944 1 0 1 1 0 0 +EDGE2 2331 1870 -0.887807 -0.0777505 1.57168 1 0 1 1 0 0 +EDGE2 2331 1930 -1.01055 -0.0471916 -1.57913 1 0 1 1 0 0 +EDGE2 2331 1670 -0.96999 -0.0372129 1.58339 1 0 1 1 0 0 +EDGE2 2331 1470 -0.969558 0.00782227 1.56796 1 0 1 1 0 0 +EDGE2 2331 1510 -1.03306 0.0288557 -1.54866 1 0 1 1 0 0 +EDGE2 2331 1530 -0.910417 -0.0751939 -1.58285 1 0 1 1 0 0 +EDGE2 2331 1370 -1.03105 -0.0432376 -1.54884 1 0 1 1 0 0 +EDGE2 2331 1371 -0.0181444 0.05962 0.0280386 1 0 1 1 0 0 +EDGE2 2331 1531 -0.0394306 0.0308802 -0.0173764 1 0 1 1 0 0 +EDGE2 2331 1651 -0.0345631 -0.00430035 0.0256157 1 0 1 1 0 0 +EDGE2 2331 1511 -0.0477561 0.0496499 -0.019622 1 0 1 1 0 0 +EDGE2 2331 1512 0.973054 -0.0210726 -0.00641973 1 0 1 1 0 0 +EDGE2 2331 1652 1.05811 0.106341 -0.019894 1 0 1 1 0 0 +EDGE2 2331 1532 1.07245 0.0723858 0.0109016 1 0 1 1 0 0 +EDGE2 2331 1372 1.00749 -0.0259199 0.00308539 1 0 1 1 0 0 +EDGE2 2332 1371 -1.0538 0.0171499 -0.00997131 1 0 1 1 0 0 +EDGE2 2332 1531 -1.00205 0.0217857 -0.0336501 1 0 1 1 0 0 +EDGE2 2332 1651 -0.989633 0.0196064 0.00723151 1 0 1 1 0 0 +EDGE2 2332 2331 -1.002 -0.0722019 0.00617944 1 0 1 1 0 0 +EDGE2 2332 1511 -0.931657 0.0337535 -0.00600096 1 0 1 1 0 0 +EDGE2 2332 1512 -0.0387538 0.029736 0.0291228 1 0 1 1 0 0 +EDGE2 2332 1652 -0.0827008 0.0279352 0.0308783 1 0 1 1 0 0 +EDGE2 2332 1532 -0.0302364 0.0040669 0.0164853 1 0 1 1 0 0 +EDGE2 2332 1372 0.0671233 -0.0989766 0.00614918 1 0 1 1 0 0 +EDGE2 2332 1513 0.957535 0.104368 -0.00328876 1 0 1 1 0 0 +EDGE2 2332 1653 0.953065 0.075886 0.0107447 1 0 1 1 0 0 +EDGE2 2332 1533 0.931597 -0.00295554 0.0106094 1 0 1 1 0 0 +EDGE2 2332 1373 1.02344 -0.0473049 0.0206228 1 0 1 1 0 0 +EDGE2 2333 1512 -1.02945 -0.0242352 -0.00881047 1 0 1 1 0 0 +EDGE2 2333 1652 -0.99066 0.0883205 0.00729854 1 0 1 1 0 0 +EDGE2 2333 2332 -0.983539 0.067879 0.0108958 1 0 1 1 0 0 +EDGE2 2333 1532 -1.06283 -0.0586052 -0.0055103 1 0 1 1 0 0 +EDGE2 2333 1372 -1.04301 0.00957538 0.0164005 1 0 1 1 0 0 +EDGE2 2333 1513 -0.000932422 0.0517335 -0.00419027 1 0 1 1 0 0 +EDGE2 2333 1653 0.0227249 -0.0404817 0.0341561 1 0 1 1 0 0 +EDGE2 2333 1533 0.0747827 -0.00296059 -0.0094202 1 0 1 1 0 0 +EDGE2 2333 1373 -0.0565169 0.0153714 -0.00381397 1 0 1 1 0 0 +EDGE2 2333 1514 1.01992 -0.0191835 0.00420711 1 0 1 1 0 0 +EDGE2 2333 1654 1.05973 -0.0167797 -0.0120177 1 0 1 1 0 0 +EDGE2 2333 1534 1.01184 -0.0213393 0.0424298 1 0 1 1 0 0 +EDGE2 2333 1374 0.960544 -0.0121894 0.0173899 1 0 1 1 0 0 +EDGE2 2334 1535 1.06686 0.0226669 -0.0399967 1 0 1 1 0 0 +EDGE2 2334 1513 -1.04107 -0.0535392 0.00681102 1 0 1 1 0 0 +EDGE2 2334 1653 -0.989225 0.0580143 0.0155319 1 0 1 1 0 0 +EDGE2 2334 2333 -0.992608 -0.0468962 -0.0163665 1 0 1 1 0 0 +EDGE2 2334 1533 -0.985697 0.016881 -0.0161322 1 0 1 1 0 0 +EDGE2 2334 1373 -1.01528 0.000789677 -0.00498323 1 0 1 1 0 0 +EDGE2 2334 1514 0.0456507 0.0132038 0.00936528 1 0 1 1 0 0 +EDGE2 2334 1654 0.099044 0.0102407 0.0238653 1 0 1 1 0 0 +EDGE2 2334 1534 -0.0365652 -0.0533053 0.0216475 1 0 1 1 0 0 +EDGE2 2334 1374 -0.10255 -0.0409734 0.00182119 1 0 1 1 0 0 +EDGE2 2334 1855 1.05927 0.0918034 -3.12569 1 0 1 1 0 0 +EDGE2 2334 2315 0.960361 0.0517343 -3.12203 1 0 1 1 0 0 +EDGE2 2334 1595 1.01237 -0.0349958 -3.1558 1 0 1 1 0 0 +EDGE2 2334 1655 1.04298 0.00705874 0.00320333 1 0 1 1 0 0 +EDGE2 2334 1575 1.00308 -0.0120654 -3.10326 1 0 1 1 0 0 +EDGE2 2334 1375 1.01512 -0.0644738 0.0353436 1 0 1 1 0 0 +EDGE2 2334 1515 0.93648 -0.0670433 -0.000987272 1 0 1 1 0 0 +EDGE2 2335 1656 -0.01525 -1.03137 -1.53956 1 0 1 1 0 0 +EDGE2 2335 1856 0.0775563 -0.954847 -1.58065 1 0 1 1 0 0 +EDGE2 2335 1536 -0.0472256 -0.946022 -1.58555 1 0 1 1 0 0 +EDGE2 2335 1576 -0.0352706 -0.952944 -1.59036 1 0 1 1 0 0 +EDGE2 2335 1376 0.0127604 -0.972867 -1.52157 1 0 1 1 0 0 +EDGE2 2335 1535 0.0464013 0.0284156 0.0224606 1 0 1 1 0 0 +EDGE2 2335 1514 -1.10137 -0.0362997 0.00202513 1 0 1 1 0 0 +EDGE2 2335 1654 -1.04482 0.0109861 -0.0173683 1 0 1 1 0 0 +EDGE2 2335 2334 -0.989931 -0.0710587 0.0147591 1 0 1 1 0 0 +EDGE2 2335 1534 -0.97148 0.123345 0.0265476 1 0 1 1 0 0 +EDGE2 2335 1374 -1.0051 -0.0388642 -0.0153378 1 0 1 1 0 0 +EDGE2 2335 1855 0.0798048 0.026515 -3.1425 1 0 1 1 0 0 +EDGE2 2335 2315 0.0094599 0.00684951 -3.17868 1 0 1 1 0 0 +EDGE2 2335 1595 0.0117231 -0.0392116 -3.13939 1 0 1 1 0 0 +EDGE2 2335 1655 0.0407818 0.0865699 0.0153086 1 0 1 1 0 0 +EDGE2 2335 1575 0.000124704 0.0611299 -3.17076 1 0 1 1 0 0 +EDGE2 2335 1854 0.942902 -0.0133248 -3.14144 1 0 1 1 0 0 +EDGE2 2335 1375 -0.0347017 -0.0630808 -0.0202447 1 0 1 1 0 0 +EDGE2 2335 1515 -0.030419 0.024446 0.0158909 1 0 1 1 0 0 +EDGE2 2335 2314 0.945887 -0.0417279 -3.14892 1 0 1 1 0 0 +EDGE2 2335 1574 1.0328 0.00132825 -3.14204 1 0 1 1 0 0 +EDGE2 2335 1594 0.997952 0.0498493 -3.13333 1 0 1 1 0 0 +EDGE2 2335 1516 0.0580468 1.00151 1.56616 1 0 1 1 0 0 +EDGE2 2335 1596 -0.00376782 0.884593 1.58985 1 0 1 1 0 0 +EDGE2 2335 2316 0.0185097 0.980627 1.5626 1 0 1 1 0 0 +EDGE2 2336 1535 -0.995788 -0.067201 -1.55309 1 0 1 1 0 0 +EDGE2 2336 1855 -0.963627 -0.0117732 1.56571 1 0 1 1 0 0 +EDGE2 2336 2335 -1.0565 0.0219569 -1.55671 1 0 1 1 0 0 +EDGE2 2336 2315 -1.11499 -0.0569874 1.57852 1 0 1 1 0 0 +EDGE2 2336 1595 -0.944355 -0.013772 1.59226 1 0 1 1 0 0 +EDGE2 2336 1655 -1.02422 0.0338476 -1.62396 1 0 1 1 0 0 +EDGE2 2336 1575 -0.95924 0.0133979 1.58278 1 0 1 1 0 0 +EDGE2 2336 1375 -0.994192 0.0183168 -1.53285 1 0 1 1 0 0 +EDGE2 2336 1515 -0.981829 -0.0053444 -1.55125 1 0 1 1 0 0 +EDGE2 2336 1516 -0.0868868 -0.1066 -0.00138905 1 0 1 1 0 0 +EDGE2 2336 1596 -0.0386718 -0.00376588 0.00701749 1 0 1 1 0 0 +EDGE2 2336 2316 -0.0494744 0.0219411 -0.00256145 1 0 1 1 0 0 +EDGE2 2336 1597 0.934236 -0.0565222 -0.00366725 1 0 1 1 0 0 +EDGE2 2336 2317 1.01647 -0.00510625 -0.00454612 1 0 1 1 0 0 +EDGE2 2336 1517 1.00644 -0.000502314 -0.000294366 1 0 1 1 0 0 +EDGE2 2337 2336 -1.03707 -0.0385512 -0.0141066 1 0 1 1 0 0 +EDGE2 2337 1516 -1.00232 -0.0232682 -0.0214572 1 0 1 1 0 0 +EDGE2 2337 1596 -0.977876 -0.00908124 0.0154294 1 0 1 1 0 0 +EDGE2 2337 2316 -0.90824 0.0509789 -0.0346524 1 0 1 1 0 0 +EDGE2 2337 1597 -0.029477 0.0498502 0.0161619 1 0 1 1 0 0 +EDGE2 2337 2317 0.023694 -0.0649108 0.00614899 1 0 1 1 0 0 +EDGE2 2337 1517 -0.00762993 -0.0317524 0.0106118 1 0 1 1 0 0 +EDGE2 2337 1598 0.984621 -0.0330929 -0.0115316 1 0 1 1 0 0 +EDGE2 2337 2318 1.06706 -0.0333609 0.0160494 1 0 1 1 0 0 +EDGE2 2337 1518 1.03671 0.0387888 -0.0276409 1 0 1 1 0 0 +EDGE2 2338 2337 -0.99544 0.0718438 0.0188573 1 0 1 1 0 0 +EDGE2 2338 1597 -1.01501 0.0432265 -0.00861763 1 0 1 1 0 0 +EDGE2 2338 2317 -1.02953 0.0735836 0.00209366 1 0 1 1 0 0 +EDGE2 2338 1517 -1.01856 0.0455565 -0.0392343 1 0 1 1 0 0 +EDGE2 2338 1598 -0.0209802 0.0697235 -0.015089 1 0 1 1 0 0 +EDGE2 2338 2318 -0.00406316 -0.0259255 -0.0074135 1 0 1 1 0 0 +EDGE2 2338 1518 -0.042973 0.0161553 0.0235308 1 0 1 1 0 0 +EDGE2 2338 1599 0.992 0.00286107 0.0141807 1 0 1 1 0 0 +EDGE2 2338 2319 1.00957 0.0683905 -0.0174383 1 0 1 1 0 0 +EDGE2 2338 1519 1.02116 0.0246091 -0.00580206 1 0 1 1 0 0 +EDGE2 2339 1598 -1.01453 0.116329 -0.0321902 1 0 1 1 0 0 +EDGE2 2339 2338 -0.984895 0.0197365 0.00139872 1 0 1 1 0 0 +EDGE2 2339 2318 -1.03646 0.0009091 0.0323512 1 0 1 1 0 0 +EDGE2 2339 1518 -1.12375 0.00128026 0.0183014 1 0 1 1 0 0 +EDGE2 2339 1599 0.0202965 -0.0177755 0.00465473 1 0 1 1 0 0 +EDGE2 2339 2319 0.0485671 0.0181112 0.00901104 1 0 1 1 0 0 +EDGE2 2339 1519 0.00184232 0.0562923 0.0096121 1 0 1 1 0 0 +EDGE2 2339 1520 0.943841 0.0960495 -0.00457071 1 0 1 1 0 0 +EDGE2 2339 1620 1.00242 0.0167723 -3.15183 1 0 1 1 0 0 +EDGE2 2339 1640 1.14084 0.0426115 -3.15163 1 0 1 1 0 0 +EDGE2 2339 2320 0.95315 -0.0291167 0.000276147 1 0 1 1 0 0 +EDGE2 2339 1600 1.00779 0.0252645 -0.0174049 1 0 1 1 0 0 +EDGE2 2339 1320 0.972327 0.0361221 -3.14705 1 0 1 1 0 0 +EDGE2 2340 1599 -0.98119 -0.0241017 -0.0292346 1 0 1 1 0 0 +EDGE2 2340 2319 -0.95186 -0.0187962 -0.00759367 1 0 1 1 0 0 +EDGE2 2340 2339 -0.983068 -0.0227056 0.00145176 1 0 1 1 0 0 +EDGE2 2340 1519 -1.00192 0.015418 0.00726146 1 0 1 1 0 0 +EDGE2 2340 1521 0.0112692 0.995114 1.56917 1 0 1 1 0 0 +EDGE2 2340 1641 0.0449136 0.9864 1.53954 1 0 1 1 0 0 +EDGE2 2340 2321 -0.0361435 0.977437 1.58094 1 0 1 1 0 0 +EDGE2 2340 1321 -0.0452161 1.02777 1.60209 1 0 1 1 0 0 +EDGE2 2340 1520 -0.0168966 -0.025092 0.0207685 1 0 1 1 0 0 +EDGE2 2340 1620 -0.0113004 -0.053711 -3.12028 1 0 1 1 0 0 +EDGE2 2340 1640 -0.00373339 0.0461966 -3.15621 1 0 1 1 0 0 +EDGE2 2340 2320 -0.0148618 -0.00943767 0.0177802 1 0 1 1 0 0 +EDGE2 2340 1600 -0.0169315 0.0731619 0.0602113 1 0 1 1 0 0 +EDGE2 2340 1621 -0.0938167 -0.997644 -1.60531 1 0 1 1 0 0 +EDGE2 2340 1320 0.0134271 0.0605544 -3.16928 1 0 1 1 0 0 +EDGE2 2340 1601 -0.0444775 -0.989585 -1.55469 1 0 1 1 0 0 +EDGE2 2340 1619 0.969328 -0.0336226 -3.17901 1 0 1 1 0 0 +EDGE2 2340 1639 0.947136 -0.0312285 -3.12938 1 0 1 1 0 0 +EDGE2 2340 1319 0.993276 0.0328665 -3.15984 1 0 1 1 0 0 +EDGE2 2341 2340 -0.928263 0.0278636 -1.57638 1 0 1 1 0 0 +EDGE2 2341 1322 0.949404 -0.0428409 0.00618358 1 0 1 1 0 0 +EDGE2 2341 1642 0.963277 0.0150012 0.0114521 1 0 1 1 0 0 +EDGE2 2341 2322 1.07313 -0.0296855 -0.00850599 1 0 1 1 0 0 +EDGE2 2341 1522 1.0894 0.0360862 -0.063483 1 0 1 1 0 0 +EDGE2 2341 1521 -0.00385596 -0.00021301 0.0176213 1 0 1 1 0 0 +EDGE2 2341 1641 -0.0373337 0.0102376 0.0216391 1 0 1 1 0 0 +EDGE2 2341 2321 0.0400082 0.04282 -0.0106887 1 0 1 1 0 0 +EDGE2 2341 1321 -0.0686452 -0.0287096 -0.0301452 1 0 1 1 0 0 +EDGE2 2341 1520 -0.997227 -0.0300526 -1.60116 1 0 1 1 0 0 +EDGE2 2341 1620 -1.01643 0.0331114 1.5814 1 0 1 1 0 0 +EDGE2 2341 1640 -0.921009 -0.0173699 1.6008 1 0 1 1 0 0 +EDGE2 2341 2320 -1.00692 -0.12951 -1.57671 1 0 1 1 0 0 +EDGE2 2341 1600 -1.05854 0.0511181 -1.56768 1 0 1 1 0 0 +EDGE2 2341 1320 -0.936271 0.0191929 1.60573 1 0 1 1 0 0 +EDGE2 2342 1323 0.911385 0.0422864 0.00874231 1 0 1 1 0 0 +EDGE2 2342 1643 1.07069 -0.0335351 -0.0078329 1 0 1 1 0 0 +EDGE2 2342 2323 0.968752 0.0561053 0.0174792 1 0 1 1 0 0 +EDGE2 2342 1523 0.989194 -0.0404554 0.0301272 1 0 1 1 0 0 +EDGE2 2342 2341 -0.987269 -0.00272272 -0.0334978 1 0 1 1 0 0 +EDGE2 2342 1322 -0.0299704 0.0314564 -0.0580563 1 0 1 1 0 0 +EDGE2 2342 1642 0.0770023 0.00443084 0.00468106 1 0 1 1 0 0 +EDGE2 2342 2322 0.0328485 -0.0292435 0.00248366 1 0 1 1 0 0 +EDGE2 2342 1522 0.0201999 0.0523579 -0.0297751 1 0 1 1 0 0 +EDGE2 2342 1521 -0.989224 -0.0642041 0.00667835 1 0 1 1 0 0 +EDGE2 2342 1641 -0.978995 0.0280652 -0.0170862 1 0 1 1 0 0 +EDGE2 2342 2321 -1.01895 -0.0846934 -0.0173151 1 0 1 1 0 0 +EDGE2 2342 1321 -0.922265 0.034689 0.00416088 1 0 1 1 0 0 +EDGE2 2343 1524 1.00821 0.0602351 0.0149572 1 0 1 1 0 0 +EDGE2 2343 2324 1.00907 -0.0114267 0.00894808 1 0 1 1 0 0 +EDGE2 2343 1644 0.957188 -0.0147342 0.0077098 1 0 1 1 0 0 +EDGE2 2343 1324 1.01937 -0.0194084 0.00707865 1 0 1 1 0 0 +EDGE2 2343 1323 -0.0302133 -0.0147202 -0.00929763 1 0 1 1 0 0 +EDGE2 2343 1643 0.0236762 0.0825196 0.0111222 1 0 1 1 0 0 +EDGE2 2343 2323 0.0734556 0.000523805 -0.00131575 1 0 1 1 0 0 +EDGE2 2343 1523 -0.0683987 -0.0126481 0.00134469 1 0 1 1 0 0 +EDGE2 2343 1322 -1.02784 0.0410061 0.0269284 1 0 1 1 0 0 +EDGE2 2343 1642 -1.01612 0.0340012 -0.00440194 1 0 1 1 0 0 +EDGE2 2343 2322 -1.03401 0.0471737 -0.0446596 1 0 1 1 0 0 +EDGE2 2343 2342 -1.12977 -0.0429308 -0.0187501 1 0 1 1 0 0 +EDGE2 2343 1522 -1.0041 0.0484499 -0.0126666 1 0 1 1 0 0 +EDGE2 2344 1345 1.08126 -0.0222521 -3.13184 1 0 1 1 0 0 +EDGE2 2344 1525 1.0004 -0.0811339 0.02221 1 0 1 1 0 0 +EDGE2 2344 1905 0.94487 0.082767 -3.12694 1 0 1 1 0 0 +EDGE2 2344 1925 0.906615 -0.0038905 -3.13098 1 0 1 1 0 0 +EDGE2 2344 2325 0.945595 -0.0153711 0.0231301 1 0 1 1 0 0 +EDGE2 2344 1645 0.989514 0.0456243 -0.0152884 1 0 1 1 0 0 +EDGE2 2344 1485 1.07909 0.0597533 -3.17839 1 0 1 1 0 0 +EDGE2 2344 1505 1.02772 -0.0455658 -3.13292 1 0 1 1 0 0 +EDGE2 2344 1365 0.928953 -0.0217237 -3.14195 1 0 1 1 0 0 +EDGE2 2344 1325 1.00666 -0.156317 0.0103404 1 0 1 1 0 0 +EDGE2 2344 1524 0.0745197 -0.0265458 0.000143812 1 0 1 1 0 0 +EDGE2 2344 2324 0.0364684 -0.0415495 0.0303595 1 0 1 1 0 0 +EDGE2 2344 1644 0.00848446 -0.00780669 -0.00319134 1 0 1 1 0 0 +EDGE2 2344 1324 -0.0569417 0.0311511 0.0133405 1 0 1 1 0 0 +EDGE2 2344 1323 -1.06448 0.0155985 -0.00387202 1 0 1 1 0 0 +EDGE2 2344 1643 -0.992294 -0.0772276 0.00887025 1 0 1 1 0 0 +EDGE2 2344 2323 -0.97915 -0.0146632 0.0310526 1 0 1 1 0 0 +EDGE2 2344 2343 -0.99398 0.0220012 0.0402435 1 0 1 1 0 0 +EDGE2 2344 1523 -1.01821 -0.138132 0.0254999 1 0 1 1 0 0 +EDGE2 2345 1345 0.0488821 0.015242 -3.12395 1 0 1 1 0 0 +EDGE2 2345 1526 -0.0533797 1.06095 1.55129 1 0 1 1 0 0 +EDGE2 2345 1926 -0.0036372 1.02387 1.58879 1 0 1 1 0 0 +EDGE2 2345 2326 -0.0225178 0.988686 1.54112 1 0 1 1 0 0 +EDGE2 2345 1646 -0.0336749 1.01151 1.55477 1 0 1 1 0 0 +EDGE2 2345 1366 -0.0321557 0.98653 1.59496 1 0 1 1 0 0 +EDGE2 2345 1506 -0.0196963 0.987276 1.55021 1 0 1 1 0 0 +EDGE2 2345 1924 0.988143 -0.100616 -3.12649 1 0 1 1 0 0 +EDGE2 2345 1344 1.06255 0.0700035 -3.14989 1 0 1 1 0 0 +EDGE2 2345 1484 0.897136 0.0398293 -3.14267 1 0 1 1 0 0 +EDGE2 2345 1504 0.947326 0.0696707 -3.10759 1 0 1 1 0 0 +EDGE2 2345 1904 1.02333 0.0397371 -3.16124 1 0 1 1 0 0 +EDGE2 2345 1364 0.940617 0.0312824 -3.11266 1 0 1 1 0 0 +EDGE2 2345 1525 -0.0117551 0.031417 -0.00413602 1 0 1 1 0 0 +EDGE2 2345 1905 -0.0827404 -0.00629459 -3.14809 1 0 1 1 0 0 +EDGE2 2345 1925 0.00355936 0.0446128 -3.15187 1 0 1 1 0 0 +EDGE2 2345 2325 -0.0262311 0.0550394 -0.00721521 1 0 1 1 0 0 +EDGE2 2345 1645 -0.10114 0.0743022 -0.00962984 1 0 1 1 0 0 +EDGE2 2345 1485 -0.0308638 0.0556211 -3.14796 1 0 1 1 0 0 +EDGE2 2345 1505 0.0835371 0.00161833 -3.13945 1 0 1 1 0 0 +EDGE2 2345 1365 0.0519941 -0.0329302 -3.11537 1 0 1 1 0 0 +EDGE2 2345 1325 -0.00533905 0.0371301 0.00433699 1 0 1 1 0 0 +EDGE2 2345 1524 -0.948752 -0.02129 0.00667192 1 0 1 1 0 0 +EDGE2 2345 2324 -0.940797 -0.0251334 -0.0271005 1 0 1 1 0 0 +EDGE2 2345 2344 -0.957151 -0.0464023 -0.0125287 1 0 1 1 0 0 +EDGE2 2345 1644 -1.12147 -0.0174215 0.0192604 1 0 1 1 0 0 +EDGE2 2345 1324 -1.01548 -0.00583156 0.00592259 1 0 1 1 0 0 +EDGE2 2345 1486 -0.0176867 -0.96199 -1.60427 1 0 1 1 0 0 +EDGE2 2345 1906 0.103516 -1.00375 -1.59088 1 0 1 1 0 0 +EDGE2 2345 1326 0.0173215 -1.07192 -1.58452 1 0 1 1 0 0 +EDGE2 2345 1346 0.124634 -1.08203 -1.61991 1 0 1 1 0 0 +EDGE2 2346 2327 1.07896 -0.0699963 0.0164385 1 0 1 1 0 0 +EDGE2 2346 1345 -0.937682 0.0130073 1.55974 1 0 1 1 0 0 +EDGE2 2346 1526 0.035746 0.014778 0.02639 1 0 1 1 0 0 +EDGE2 2346 1507 0.939358 0.0188668 0.0342072 1 0 1 1 0 0 +EDGE2 2346 1527 0.979162 -0.0490507 -0.0171235 1 0 1 1 0 0 +EDGE2 2346 1647 1.12785 0.0539079 -0.0203266 1 0 1 1 0 0 +EDGE2 2346 1927 0.954268 0.0581234 -0.0117851 1 0 1 1 0 0 +EDGE2 2346 1367 0.996196 0.0773242 0.0229511 1 0 1 1 0 0 +EDGE2 2346 1926 0.0670667 -0.131661 0.0291608 1 0 1 1 0 0 +EDGE2 2346 2326 -0.002799 -0.0540353 0.00304038 1 0 1 1 0 0 +EDGE2 2346 1646 -0.044944 -0.00951436 0.0411339 1 0 1 1 0 0 +EDGE2 2346 1366 0.00653995 -0.0559229 -0.0210578 1 0 1 1 0 0 +EDGE2 2346 1506 0.0113133 -0.0187427 0.00427759 1 0 1 1 0 0 +EDGE2 2346 2345 -0.946421 -0.0167714 -1.55044 1 0 1 1 0 0 +EDGE2 2346 1525 -1.03108 -0.0440046 -1.59148 1 0 1 1 0 0 +EDGE2 2346 1905 -0.976564 0.0205308 1.5631 1 0 1 1 0 0 +EDGE2 2346 1925 -0.984314 0.0482715 1.54504 1 0 1 1 0 0 +EDGE2 2346 2325 -0.98258 0.0107161 -1.56602 1 0 1 1 0 0 +EDGE2 2346 1645 -1.03607 -0.0469752 -1.58072 1 0 1 1 0 0 +EDGE2 2346 1485 -0.971671 -0.0112021 1.60822 1 0 1 1 0 0 +EDGE2 2346 1505 -0.953671 -0.0154661 1.55714 1 0 1 1 0 0 +EDGE2 2346 1365 -1.13475 0.0152728 1.55159 1 0 1 1 0 0 +EDGE2 2346 1325 -0.986062 0.00922927 -1.55052 1 0 1 1 0 0 +EDGE2 2347 2327 -0.0374528 -0.067111 0.0386892 1 0 1 1 0 0 +EDGE2 2347 1648 1.01848 0.0786479 0.000878503 1 0 1 1 0 0 +EDGE2 2347 1928 1.0655 -0.0468269 -0.00995607 1 0 1 1 0 0 +EDGE2 2347 2328 0.976475 -0.00111002 0.0249197 1 0 1 1 0 0 +EDGE2 2347 1368 0.971889 0.0218669 0.0166972 1 0 1 1 0 0 +EDGE2 2347 1508 1.06316 -0.0538422 -0.00574332 1 0 1 1 0 0 +EDGE2 2347 1528 0.984947 -0.0588763 -0.0105115 1 0 1 1 0 0 +EDGE2 2347 1526 -0.984338 -0.0844731 -0.0120877 1 0 1 1 0 0 +EDGE2 2347 1507 -0.0363208 -0.0186616 0.0219234 1 0 1 1 0 0 +EDGE2 2347 1527 0.099935 0.130568 -0.0163946 1 0 1 1 0 0 +EDGE2 2347 1647 0.0135394 0.0214818 -0.0140308 1 0 1 1 0 0 +EDGE2 2347 1927 -0.0247211 -0.0219474 0.00260868 1 0 1 1 0 0 +EDGE2 2347 1367 -0.0168069 0.10102 0.037023 1 0 1 1 0 0 +EDGE2 2347 1926 -1.01224 -0.0281967 0.0179372 1 0 1 1 0 0 +EDGE2 2347 2326 -1.05015 0.0721451 -0.0278465 1 0 1 1 0 0 +EDGE2 2347 2346 -0.963487 -0.0287413 0.0196628 1 0 1 1 0 0 +EDGE2 2347 1646 -0.993739 -0.0580721 -0.0189001 1 0 1 1 0 0 +EDGE2 2347 1366 -1.0777 0.0877139 0.000221284 1 0 1 1 0 0 +EDGE2 2347 1506 -1.00969 0.103893 -0.00291378 1 0 1 1 0 0 +EDGE2 2348 2327 -1.03438 -0.0176169 -0.0194496 1 0 1 1 0 0 +EDGE2 2348 1509 1.00672 -0.0272816 0.0212601 1 0 1 1 0 0 +EDGE2 2348 1649 0.946787 -0.0645932 0.0216465 1 0 1 1 0 0 +EDGE2 2348 1929 0.996626 -0.120157 0.0189485 1 0 1 1 0 0 +EDGE2 2348 2329 0.976862 -0.00640177 -0.00293783 1 0 1 1 0 0 +EDGE2 2348 1529 0.988672 -0.00895805 -0.00671282 1 0 1 1 0 0 +EDGE2 2348 1369 0.99617 -0.00571891 -0.012987 1 0 1 1 0 0 +EDGE2 2348 1648 -0.00582723 -0.0140054 0.0221316 1 0 1 1 0 0 +EDGE2 2348 1928 -0.0442691 0.0910677 0.00862866 1 0 1 1 0 0 +EDGE2 2348 2328 0.0544147 0.0339442 0.0483915 1 0 1 1 0 0 +EDGE2 2348 1368 -0.0142081 -0.0529267 0.0139866 1 0 1 1 0 0 +EDGE2 2348 1508 0.00919715 0.0396146 0.025132 1 0 1 1 0 0 +EDGE2 2348 1528 0.0362508 0.0211055 0.0233975 1 0 1 1 0 0 +EDGE2 2348 2347 -0.971393 -0.0543569 -0.00192845 1 0 1 1 0 0 +EDGE2 2348 1507 -1.00395 -0.0476232 -0.0229768 1 0 1 1 0 0 +EDGE2 2348 1527 -1.02111 0.00695088 0.000780386 1 0 1 1 0 0 +EDGE2 2348 1647 -1.0878 -0.0132221 0.00607505 1 0 1 1 0 0 +EDGE2 2348 1927 -1.00013 -0.0281714 -0.000302052 1 0 1 1 0 0 +EDGE2 2348 1367 -0.991204 0.0189669 -0.0218252 1 0 1 1 0 0 +EDGE2 2349 2330 1.01105 0.00484139 -0.00846343 1 0 1 1 0 0 +EDGE2 2349 1650 1.10855 0.0232125 0.0478661 1 0 1 1 0 0 +EDGE2 2349 1710 1.02309 -0.0381128 -3.15036 1 0 1 1 0 0 +EDGE2 2349 1870 1.03267 -0.0112539 -3.13347 1 0 1 1 0 0 +EDGE2 2349 1930 0.990881 -0.0168162 -0.00795647 1 0 1 1 0 0 +EDGE2 2349 1670 1.02336 0.00971973 -3.1513 1 0 1 1 0 0 +EDGE2 2349 1470 1.08373 -0.0405774 -3.15432 1 0 1 1 0 0 +EDGE2 2349 1510 0.930065 -0.01304 -0.0194303 1 0 1 1 0 0 +EDGE2 2349 1530 1.00057 0.00269798 0.018397 1 0 1 1 0 0 +EDGE2 2349 1370 0.919045 0.030261 -0.00961013 1 0 1 1 0 0 +EDGE2 2349 1509 -0.0736905 0.0205061 -0.00979026 1 0 1 1 0 0 +EDGE2 2349 1649 0.000492325 -0.0238101 0.0332386 1 0 1 1 0 0 +EDGE2 2349 1929 0.0405134 0.0388989 0.00673913 1 0 1 1 0 0 +EDGE2 2349 2329 -0.0184864 0.0472664 -0.0324841 1 0 1 1 0 0 +EDGE2 2349 1529 0.0423154 -0.0394617 0.0098782 1 0 1 1 0 0 +EDGE2 2349 1369 0.0331981 -0.0719245 0.00721221 1 0 1 1 0 0 +EDGE2 2349 1648 -1.05219 0.0973667 0.0171913 1 0 1 1 0 0 +EDGE2 2349 1928 -1.00884 -0.0320332 -0.00824423 1 0 1 1 0 0 +EDGE2 2349 2328 -1.03187 0.057815 0.00334962 1 0 1 1 0 0 +EDGE2 2349 2348 -1.02274 -0.0953678 0.024962 1 0 1 1 0 0 +EDGE2 2349 1368 -1.01625 -0.000527289 0.0386032 1 0 1 1 0 0 +EDGE2 2349 1508 -0.983739 0.0625694 0.0133014 1 0 1 1 0 0 +EDGE2 2349 1528 -1.04687 -0.00734346 0.0108224 1 0 1 1 0 0 +EDGE2 2350 1931 -0.0289812 -1.01751 -1.5492 1 0 1 1 0 0 +EDGE2 2350 1669 1.0228 -0.000305323 -3.09979 1 0 1 1 0 0 +EDGE2 2350 1709 0.98182 -0.0147426 -3.15526 1 0 1 1 0 0 +EDGE2 2350 1869 0.973839 -0.0215832 -3.13472 1 0 1 1 0 0 +EDGE2 2350 1469 1.05821 0.0296756 -3.12363 1 0 1 1 0 0 +EDGE2 2350 2330 -0.00136377 0.0706605 -0.0164102 1 0 1 1 0 0 +EDGE2 2350 1671 -0.0421415 -0.875181 -1.58971 1 0 1 1 0 0 +EDGE2 2350 1711 -0.0404354 -0.948124 -1.6095 1 0 1 1 0 0 +EDGE2 2350 1871 0.0214423 -1.00671 -1.56775 1 0 1 1 0 0 +EDGE2 2350 1471 -0.0351864 -0.952867 -1.5569 1 0 1 1 0 0 +EDGE2 2350 1650 -0.0194166 -0.0283721 0.0111327 1 0 1 1 0 0 +EDGE2 2350 1710 -0.0878749 0.0155878 -3.13245 1 0 1 1 0 0 +EDGE2 2350 1870 0.0729521 -0.0861669 -3.14543 1 0 1 1 0 0 +EDGE2 2350 1930 0.0374068 0.0481704 -0.0232676 1 0 1 1 0 0 +EDGE2 2350 1670 -0.0309292 0.0305915 -3.14614 1 0 1 1 0 0 +EDGE2 2350 1470 -0.0580429 -0.0757841 -3.16816 1 0 1 1 0 0 +EDGE2 2350 1510 -0.0832057 -0.0262212 -0.000859797 1 0 1 1 0 0 +EDGE2 2350 1530 -0.0493103 -0.0366388 -0.0228256 1 0 1 1 0 0 +EDGE2 2350 1370 0.00964993 0.0543988 -0.0270614 1 0 1 1 0 0 +EDGE2 2350 1371 -0.0107619 1.0109 1.55419 1 0 1 1 0 0 +EDGE2 2350 1531 -0.0820824 1.0737 1.5822 1 0 1 1 0 0 +EDGE2 2350 1651 -0.0952278 0.991728 1.58041 1 0 1 1 0 0 +EDGE2 2350 2331 0.0540689 0.983961 1.55417 1 0 1 1 0 0 +EDGE2 2350 1511 -0.0198012 0.937783 1.54421 1 0 1 1 0 0 +EDGE2 2350 2349 -1.02247 -0.0314479 -0.0234645 1 0 1 1 0 0 +EDGE2 2350 1509 -1.03168 -0.0646736 0.0123273 1 0 1 1 0 0 +EDGE2 2350 1649 -0.959755 0.0413415 0.00321613 1 0 1 1 0 0 +EDGE2 2350 1929 -0.996666 -0.0327338 -0.0218777 1 0 1 1 0 0 +EDGE2 2350 2329 -0.906671 -0.0287449 0.0285961 1 0 1 1 0 0 +EDGE2 2350 1529 -1.0246 0.0101917 -0.0121057 1 0 1 1 0 0 +EDGE2 2350 1369 -1.01247 -0.0478466 0.000514107 1 0 1 1 0 0 +EDGE2 2351 2330 -0.954357 0.00440403 -1.55591 1 0 1 1 0 0 +EDGE2 2351 2350 -1.00702 0.0218081 -1.53892 1 0 1 1 0 0 +EDGE2 2351 1650 -1.04645 0.0197988 -1.54192 1 0 1 1 0 0 +EDGE2 2351 1710 -0.998202 0.0558514 1.52921 1 0 1 1 0 0 +EDGE2 2351 1870 -0.963145 0.0014924 1.56762 1 0 1 1 0 0 +EDGE2 2351 1930 -0.938979 -0.0176323 -1.53878 1 0 1 1 0 0 +EDGE2 2351 1670 -0.964389 0.0258706 1.57758 1 0 1 1 0 0 +EDGE2 2351 1470 -0.9812 -0.00365037 1.60564 1 0 1 1 0 0 +EDGE2 2351 1510 -1.01608 0.0162946 -1.53818 1 0 1 1 0 0 +EDGE2 2351 1530 -1.02467 0.0871985 -1.57297 1 0 1 1 0 0 +EDGE2 2351 1370 -1.04094 0.0741533 -1.57513 1 0 1 1 0 0 +EDGE2 2351 1371 0.0762903 -0.107249 -0.00698474 1 0 1 1 0 0 +EDGE2 2351 1531 0.071327 -0.106709 0.0121494 1 0 1 1 0 0 +EDGE2 2351 1651 -0.0292031 0.0537998 0.0238088 1 0 1 1 0 0 +EDGE2 2351 2331 -0.0978264 0.0580301 -0.0171751 1 0 1 1 0 0 +EDGE2 2351 1511 -0.0572018 -0.0527483 0.000131485 1 0 1 1 0 0 +EDGE2 2351 1512 1.08574 0.0547264 -0.00911074 1 0 1 1 0 0 +EDGE2 2351 1652 0.961683 -0.0505626 0.0242673 1 0 1 1 0 0 +EDGE2 2351 2332 1.03601 0.0226423 0.00206825 1 0 1 1 0 0 +EDGE2 2351 1532 1.02904 -0.0271971 -0.0136221 1 0 1 1 0 0 +EDGE2 2351 1372 1.04326 -0.049315 -0.0138398 1 0 1 1 0 0 +EDGE2 2352 2351 -0.994297 -0.038022 -0.0337396 1 0 1 1 0 0 +EDGE2 2352 1371 -1.04472 -0.00300438 -0.0185998 1 0 1 1 0 0 +EDGE2 2352 1531 -1.02083 0.0401924 0.00376845 1 0 1 1 0 0 +EDGE2 2352 1651 -1.01281 -0.0203028 0.0249092 1 0 1 1 0 0 +EDGE2 2352 2331 -0.90959 0.107879 0.0497347 1 0 1 1 0 0 +EDGE2 2352 1511 -0.908959 0.0380787 -0.0126202 1 0 1 1 0 0 +EDGE2 2352 1512 -0.0920599 0.0350782 -0.00584269 1 0 1 1 0 0 +EDGE2 2352 1652 -0.00812756 0.0479399 -0.0209349 1 0 1 1 0 0 +EDGE2 2352 2332 -0.081667 0.0161778 0.0141186 1 0 1 1 0 0 +EDGE2 2352 1532 0.0890215 0.0163709 0.00927402 1 0 1 1 0 0 +EDGE2 2352 1372 -0.0190124 -0.0243517 -0.0369276 1 0 1 1 0 0 +EDGE2 2352 1513 0.96837 0.0268121 -0.0313454 1 0 1 1 0 0 +EDGE2 2352 1653 1.0341 0.0352891 -0.0486202 1 0 1 1 0 0 +EDGE2 2352 2333 1.01388 0.0627096 -0.0080449 1 0 1 1 0 0 +EDGE2 2352 1533 1.08652 0.0760844 -0.0208374 1 0 1 1 0 0 +EDGE2 2352 1373 1.04796 0.106202 0.0267679 1 0 1 1 0 0 +EDGE2 2353 1512 -0.943023 -0.0809686 -0.0220818 1 0 1 1 0 0 +EDGE2 2353 1652 -1.02768 -0.00445306 0.0337898 1 0 1 1 0 0 +EDGE2 2353 2332 -1.01334 0.0316242 0.0408957 1 0 1 1 0 0 +EDGE2 2353 2352 -1.0051 -0.0128848 0.0219362 1 0 1 1 0 0 +EDGE2 2353 1532 -0.973012 -0.0246021 0.0354441 1 0 1 1 0 0 +EDGE2 2353 1372 -1.03092 0.079698 0.0149177 1 0 1 1 0 0 +EDGE2 2353 1513 -0.0301608 -0.0419909 -0.0179065 1 0 1 1 0 0 +EDGE2 2353 1653 -0.00147731 -0.0125857 -0.00160892 1 0 1 1 0 0 +EDGE2 2353 2333 0.00158818 -0.0774691 0.0218431 1 0 1 1 0 0 +EDGE2 2353 1533 -0.114897 -0.0239543 -0.00840123 1 0 1 1 0 0 +EDGE2 2353 1373 -0.0628211 0.016253 -0.0194247 1 0 1 1 0 0 +EDGE2 2353 1514 0.935157 0.0184012 0.0216955 1 0 1 1 0 0 +EDGE2 2353 1654 0.968692 -0.0498512 -0.0197651 1 0 1 1 0 0 +EDGE2 2353 2334 0.96182 -0.0488 0.00702018 1 0 1 1 0 0 +EDGE2 2353 1534 0.956744 -0.0661707 -0.002728 1 0 1 1 0 0 +EDGE2 2353 1374 1.06901 0.0859252 -0.0368023 1 0 1 1 0 0 +EDGE2 2354 1535 0.980684 -0.0329766 -0.016708 1 0 1 1 0 0 +EDGE2 2354 1513 -1.00373 0.0446702 0.002549 1 0 1 1 0 0 +EDGE2 2354 1653 -0.978148 0.0110126 0.0208103 1 0 1 1 0 0 +EDGE2 2354 2333 -1.06184 0.0135224 0.0196608 1 0 1 1 0 0 +EDGE2 2354 2353 -0.914844 -0.00933781 0.00535877 1 0 1 1 0 0 +EDGE2 2354 1533 -0.953445 0.0289557 0.0244385 1 0 1 1 0 0 +EDGE2 2354 1373 -1.01757 0.0163792 0.00358143 1 0 1 1 0 0 +EDGE2 2354 1514 -0.0196189 0.013184 -0.00289315 1 0 1 1 0 0 +EDGE2 2354 1654 -0.0431429 0.035453 -0.0208168 1 0 1 1 0 0 +EDGE2 2354 2334 0.0237643 0.0209447 -0.00582559 1 0 1 1 0 0 +EDGE2 2354 1534 0.0672453 -0.00923232 -0.0180123 1 0 1 1 0 0 +EDGE2 2354 1374 -0.0423302 0.0250151 0.0121227 1 0 1 1 0 0 +EDGE2 2354 1855 1.02172 0.0234181 -3.13787 1 0 1 1 0 0 +EDGE2 2354 2335 1.0102 -0.00816557 0.00536735 1 0 1 1 0 0 +EDGE2 2354 2315 0.986184 0.0358756 -3.15367 1 0 1 1 0 0 +EDGE2 2354 1595 1.07221 -0.0539862 -3.10548 1 0 1 1 0 0 +EDGE2 2354 1655 1.05213 -0.0355577 0.0321353 1 0 1 1 0 0 +EDGE2 2354 1575 1.05904 0.0833456 -3.12597 1 0 1 1 0 0 +EDGE2 2354 1375 0.908025 -0.0381473 -0.00538319 1 0 1 1 0 0 +EDGE2 2354 1515 0.970318 -0.00830192 -0.00422047 1 0 1 1 0 0 +EDGE2 2355 1656 0.00121251 -1.05228 -1.56651 1 0 1 1 0 0 +EDGE2 2355 1856 -0.0504288 -1.01058 -1.50021 1 0 1 1 0 0 +EDGE2 2355 1536 0.0596521 -0.939897 -1.56884 1 0 1 1 0 0 +EDGE2 2355 1576 -0.0376334 -0.934221 -1.56328 1 0 1 1 0 0 +EDGE2 2355 1376 -0.0232162 -0.982014 -1.56597 1 0 1 1 0 0 +EDGE2 2355 1535 0.0941178 0.0312359 -0.00697012 1 0 1 1 0 0 +EDGE2 2355 1514 -1.09973 -0.035984 0.0191539 1 0 1 1 0 0 +EDGE2 2355 1654 -1.03766 -0.0269744 -0.0447637 1 0 1 1 0 0 +EDGE2 2355 2334 -0.898712 0.0350229 -0.00116185 1 0 1 1 0 0 +EDGE2 2355 2354 -1.06727 0.0750219 -0.00143126 1 0 1 1 0 0 +EDGE2 2355 1534 -1.03931 0.0714202 -0.00180403 1 0 1 1 0 0 +EDGE2 2355 1374 -0.996596 -0.0221779 -0.0200936 1 0 1 1 0 0 +EDGE2 2355 1855 -0.0821804 -0.070284 -3.18499 1 0 1 1 0 0 +EDGE2 2355 2335 0.00647827 -0.0249283 0.000837027 1 0 1 1 0 0 +EDGE2 2355 2315 -0.130747 -0.0972613 -3.10751 1 0 1 1 0 0 +EDGE2 2355 1595 0.0242696 0.0799602 -3.13581 1 0 1 1 0 0 +EDGE2 2355 1655 0.0723331 0.0526111 0.0218399 1 0 1 1 0 0 +EDGE2 2355 1575 -0.0407641 0.0619287 -3.10956 1 0 1 1 0 0 +EDGE2 2355 1854 0.935445 -0.0363754 -3.14816 1 0 1 1 0 0 +EDGE2 2355 1375 0.0663342 0.0202009 0.0216192 1 0 1 1 0 0 +EDGE2 2355 1515 -0.0111357 -0.0292808 0.00290894 1 0 1 1 0 0 +EDGE2 2355 2314 0.92479 -0.0292384 -3.14352 1 0 1 1 0 0 +EDGE2 2355 1574 0.966832 0.0206127 -3.17344 1 0 1 1 0 0 +EDGE2 2355 1594 1.05445 -0.0840552 -3.12313 1 0 1 1 0 0 +EDGE2 2355 2336 0.075271 1.03997 1.55074 1 0 1 1 0 0 +EDGE2 2355 1516 -0.0365071 0.979231 1.59585 1 0 1 1 0 0 +EDGE2 2355 1596 0.0236272 1.01426 1.59194 1 0 1 1 0 0 +EDGE2 2355 2316 0.0571022 1.01794 1.53919 1 0 1 1 0 0 +EDGE2 2356 1535 -1.02297 0.000958336 -1.56369 1 0 1 1 0 0 +EDGE2 2356 1855 -1.06481 -0.0973796 1.57039 1 0 1 1 0 0 +EDGE2 2356 2335 -0.985557 -0.00414002 -1.58336 1 0 1 1 0 0 +EDGE2 2356 2355 -1.03689 -0.0571786 -1.5449 1 0 1 1 0 0 +EDGE2 2356 2315 -1.05224 -0.052582 1.56574 1 0 1 1 0 0 +EDGE2 2356 1595 -0.99433 0.0477855 1.54154 1 0 1 1 0 0 +EDGE2 2356 1655 -0.986498 -0.047731 -1.55394 1 0 1 1 0 0 +EDGE2 2356 1575 -0.963038 0.0665605 1.57805 1 0 1 1 0 0 +EDGE2 2356 1375 -0.983266 -0.0225834 -1.5788 1 0 1 1 0 0 +EDGE2 2356 1515 -0.947828 0.055114 -1.58172 1 0 1 1 0 0 +EDGE2 2356 2336 -0.00288884 -0.0149047 -0.000686926 1 0 1 1 0 0 +EDGE2 2356 1516 -0.0313138 0.0624717 -0.0151754 1 0 1 1 0 0 +EDGE2 2356 1596 0.00696149 -0.0722521 -0.0232396 1 0 1 1 0 0 +EDGE2 2356 2316 -0.0869023 0.00492803 -0.00820589 1 0 1 1 0 0 +EDGE2 2356 2337 1.06429 -0.11848 0.0272349 1 0 1 1 0 0 +EDGE2 2356 1597 0.947781 -0.00354765 -0.0117334 1 0 1 1 0 0 +EDGE2 2356 2317 0.909198 0.0796866 0.00488614 1 0 1 1 0 0 +EDGE2 2356 1517 0.978068 -0.0121529 0.00147984 1 0 1 1 0 0 +EDGE2 2357 2336 -0.995789 -0.0022544 0.0332644 1 0 1 1 0 0 +EDGE2 2357 2356 -0.97315 -0.0518012 0.00815711 1 0 1 1 0 0 +EDGE2 2357 1516 -1.00806 -0.0614451 -0.00793818 1 0 1 1 0 0 +EDGE2 2357 1596 -0.970607 -0.0780168 -0.02568 1 0 1 1 0 0 +EDGE2 2357 2316 -0.908879 -0.0546122 -0.0142166 1 0 1 1 0 0 +EDGE2 2357 2337 0.0097474 -0.0699079 0.014465 1 0 1 1 0 0 +EDGE2 2357 1597 0.0170953 0.0124459 0.00747407 1 0 1 1 0 0 +EDGE2 2357 2317 -0.0190261 0.0144317 -0.0178179 1 0 1 1 0 0 +EDGE2 2357 1517 0.0138938 0.0287162 -0.00779669 1 0 1 1 0 0 +EDGE2 2357 1598 0.98928 -0.00901947 0.00798654 1 0 1 1 0 0 +EDGE2 2357 2338 1.0692 0.092407 0.0175026 1 0 1 1 0 0 +EDGE2 2357 2318 1.04248 0.0282683 0.0262914 1 0 1 1 0 0 +EDGE2 2357 1518 1.05017 0.0231493 0.00737786 1 0 1 1 0 0 +EDGE2 2358 2337 -1.0062 0.0811474 0.0165643 1 0 1 1 0 0 +EDGE2 2358 2357 -1.00638 0.0237627 -0.00466261 1 0 1 1 0 0 +EDGE2 2358 1597 -1.01161 -0.0271081 0.0028726 1 0 1 1 0 0 +EDGE2 2358 2317 -0.932027 0.00752387 -0.0226597 1 0 1 1 0 0 +EDGE2 2358 1517 -0.962084 -0.00896991 -0.0164057 1 0 1 1 0 0 +EDGE2 2358 1598 0.0992266 -0.0526034 0.0219472 1 0 1 1 0 0 +EDGE2 2358 2338 -0.0247971 -0.0159381 -0.00586818 1 0 1 1 0 0 +EDGE2 2358 2318 0.00161264 0.0282281 0.023009 1 0 1 1 0 0 +EDGE2 2358 1518 -0.106561 -0.0858775 0.00585127 1 0 1 1 0 0 +EDGE2 2358 1599 1.00261 -0.0347833 0.0120975 1 0 1 1 0 0 +EDGE2 2358 2319 1.05101 -0.0277259 0.0102474 1 0 1 1 0 0 +EDGE2 2358 2339 1.02606 -0.0301889 -0.0159133 1 0 1 1 0 0 +EDGE2 2358 1519 0.929673 -0.0154968 -0.0142397 1 0 1 1 0 0 +EDGE2 2359 1598 -1.03457 -0.00818857 0.0296809 1 0 1 1 0 0 +EDGE2 2359 2338 -0.976664 -0.00120259 0.047143 1 0 1 1 0 0 +EDGE2 2359 2358 -1.05411 0.068919 -0.00376641 1 0 1 1 0 0 +EDGE2 2359 2318 -0.889288 -0.0317583 -0.00262364 1 0 1 1 0 0 +EDGE2 2359 1518 -1.01866 0.0279128 -0.023906 1 0 1 1 0 0 +EDGE2 2359 1599 -0.0239175 0.0479452 -0.00329053 1 0 1 1 0 0 +EDGE2 2359 2319 0.0205953 -0.04458 -0.00410284 1 0 1 1 0 0 +EDGE2 2359 2339 0.037797 -0.00170414 0.0227867 1 0 1 1 0 0 +EDGE2 2359 1519 0.0568374 0.0396361 -0.00684011 1 0 1 1 0 0 +EDGE2 2359 2340 0.93446 0.00531861 -0.0306833 1 0 1 1 0 0 +EDGE2 2359 1520 1.02088 0.0715912 -0.0279984 1 0 1 1 0 0 +EDGE2 2359 1620 0.957112 0.0347553 -3.13551 1 0 1 1 0 0 +EDGE2 2359 1640 1.03144 0.00670615 -3.13466 1 0 1 1 0 0 +EDGE2 2359 2320 0.838629 0.0195448 -0.0077181 1 0 1 1 0 0 +EDGE2 2359 1600 0.930161 0.0286983 0.0179035 1 0 1 1 0 0 +EDGE2 2359 1320 1.01494 -0.00553162 -3.16403 1 0 1 1 0 0 +EDGE2 2360 2359 -0.975033 0.0421254 0.0121198 1 0 1 1 0 0 +EDGE2 2360 1599 -0.955133 0.0505189 0.0117976 1 0 1 1 0 0 +EDGE2 2360 2319 -0.986234 -0.0493817 0.00409482 1 0 1 1 0 0 +EDGE2 2360 2339 -0.996152 -0.0268007 0.0178249 1 0 1 1 0 0 +EDGE2 2360 1519 -1.08995 0.0593834 0.00486757 1 0 1 1 0 0 +EDGE2 2360 2340 0.000705517 0.0487214 -0.0012314 1 0 1 1 0 0 +EDGE2 2360 2341 0.0749391 1.0307 1.57261 1 0 1 1 0 0 +EDGE2 2360 1521 0.037626 1.02072 1.57793 1 0 1 1 0 0 +EDGE2 2360 1641 0.0296464 0.975972 1.54368 1 0 1 1 0 0 +EDGE2 2360 2321 -0.00366829 0.992231 1.56062 1 0 1 1 0 0 +EDGE2 2360 1321 -0.0350231 1.00898 1.59951 1 0 1 1 0 0 +EDGE2 2360 1520 -0.0303004 0.00364921 0.00586986 1 0 1 1 0 0 +EDGE2 2360 1620 0.104481 0.00919635 -3.17843 1 0 1 1 0 0 +EDGE2 2360 1640 0.00373789 0.094318 -3.14692 1 0 1 1 0 0 +EDGE2 2360 2320 0.02668 0.0290858 0.0209885 1 0 1 1 0 0 +EDGE2 2360 1600 0.01418 0.0474975 0.0122978 1 0 1 1 0 0 +EDGE2 2360 1621 -0.0667934 -0.999262 -1.59319 1 0 1 1 0 0 +EDGE2 2360 1320 0.0138543 -0.0661195 -3.11824 1 0 1 1 0 0 +EDGE2 2360 1601 -0.0459138 -1.05547 -1.56526 1 0 1 1 0 0 +EDGE2 2360 1619 0.9877 0.116926 -3.15303 1 0 1 1 0 0 +EDGE2 2360 1639 0.991627 0.0364139 -3.15079 1 0 1 1 0 0 +EDGE2 2360 1319 0.993012 -0.0470136 -3.12906 1 0 1 1 0 0 +EDGE2 2361 2340 -1.06701 -0.0161207 -1.58213 1 0 1 1 0 0 +EDGE2 2361 2341 -0.0291331 -0.0062104 0.034501 1 0 1 1 0 0 +EDGE2 2361 1322 0.927245 0.00217121 -0.0251799 1 0 1 1 0 0 +EDGE2 2361 1642 1.01027 -0.0964976 -0.00954934 1 0 1 1 0 0 +EDGE2 2361 2322 0.982058 -0.0514302 -0.00165495 1 0 1 1 0 0 +EDGE2 2361 2342 1.07228 0.122704 -0.00754256 1 0 1 1 0 0 +EDGE2 2361 1522 0.984006 -0.0311713 -0.00621639 1 0 1 1 0 0 +EDGE2 2361 1521 -0.0349308 0.0609055 0.0228142 1 0 1 1 0 0 +EDGE2 2361 1641 0.0230547 -0.0314275 0.000701293 1 0 1 1 0 0 +EDGE2 2361 2321 -0.0159228 0.0333421 -0.00730226 1 0 1 1 0 0 +EDGE2 2361 1321 0.0393063 -0.0239221 0.024378 1 0 1 1 0 0 +EDGE2 2361 2360 -0.966589 0.0177875 -1.57289 1 0 1 1 0 0 +EDGE2 2361 1520 -1.08071 -0.0272928 -1.53685 1 0 1 1 0 0 +EDGE2 2361 1620 -1.03487 -0.0242144 1.56632 1 0 1 1 0 0 +EDGE2 2361 1640 -1.12036 -0.0332013 1.56812 1 0 1 1 0 0 +EDGE2 2361 2320 -0.953921 0.00931171 -1.60665 1 0 1 1 0 0 +EDGE2 2361 1600 -0.991498 0.0164543 -1.60152 1 0 1 1 0 0 +EDGE2 2361 1320 -0.968877 -0.0645445 1.55823 1 0 1 1 0 0 +EDGE2 2362 1323 0.983513 -0.00729631 0.0216849 1 0 1 1 0 0 +EDGE2 2362 1643 1.02214 0.0187303 0.0139073 1 0 1 1 0 0 +EDGE2 2362 2323 1.03786 0.0455361 0.00925684 1 0 1 1 0 0 +EDGE2 2362 2343 1.01428 -0.00659485 0.0190545 1 0 1 1 0 0 +EDGE2 2362 1523 0.983937 0.0187377 0.00686595 1 0 1 1 0 0 +EDGE2 2362 2341 -1.07057 0.0189407 -0.0140982 1 0 1 1 0 0 +EDGE2 2362 1322 0.0300752 -0.0141122 0.0236799 1 0 1 1 0 0 +EDGE2 2362 1642 0.0294113 -0.0475481 0.0198334 1 0 1 1 0 0 +EDGE2 2362 2322 -0.109315 -0.0575546 0.00211494 1 0 1 1 0 0 +EDGE2 2362 2342 -0.0755024 -0.0061069 0.00311514 1 0 1 1 0 0 +EDGE2 2362 1522 0.022944 0.0107856 0.00522323 1 0 1 1 0 0 +EDGE2 2362 2361 -1.04529 0.0722098 -0.0318068 1 0 1 1 0 0 +EDGE2 2362 1521 -1.01279 0.0241865 0.0170191 1 0 1 1 0 0 +EDGE2 2362 1641 -0.941395 -0.0627208 0.0501962 1 0 1 1 0 0 +EDGE2 2362 2321 -0.997171 -0.080985 0.0411295 1 0 1 1 0 0 +EDGE2 2362 1321 -1.09035 0.085428 0.0157571 1 0 1 1 0 0 +EDGE2 2363 2362 -1.03773 0.0051291 -0.00492387 1 0 1 1 0 0 +EDGE2 2363 1524 1.03282 -0.0667968 0.0026397 1 0 1 1 0 0 +EDGE2 2363 2324 0.930518 -0.113744 -0.00510176 1 0 1 1 0 0 +EDGE2 2363 2344 1.06336 -0.0197662 0.00667574 1 0 1 1 0 0 +EDGE2 2363 1644 1.04418 0.0657673 0.0193235 1 0 1 1 0 0 +EDGE2 2363 1324 0.973412 0.0294277 -0.0129445 1 0 1 1 0 0 +EDGE2 2363 1323 0.058593 -0.0163061 0.0243003 1 0 1 1 0 0 +EDGE2 2363 1643 -0.0215389 -0.0262668 0.000769844 1 0 1 1 0 0 +EDGE2 2363 2323 0.0331641 -0.01424 0.00408845 1 0 1 1 0 0 +EDGE2 2363 2343 0.0211387 -0.055759 0.0249903 1 0 1 1 0 0 +EDGE2 2363 1523 -0.04014 -0.0821157 0.0223761 1 0 1 1 0 0 +EDGE2 2363 1322 -1.03351 0.0767593 0.00263055 1 0 1 1 0 0 +EDGE2 2363 1642 -1.08257 0.0356939 -0.0215119 1 0 1 1 0 0 +EDGE2 2363 2322 -0.962963 0.100419 0.00213639 1 0 1 1 0 0 +EDGE2 2363 2342 -0.987711 -0.0240691 -0.00845852 1 0 1 1 0 0 +EDGE2 2363 1522 -0.968051 0.0029591 0.00746454 1 0 1 1 0 0 +EDGE2 2364 1345 1.04252 0.0674004 -3.16673 1 0 1 1 0 0 +EDGE2 2364 2345 0.966562 0.0287715 0.0173616 1 0 1 1 0 0 +EDGE2 2364 1525 0.925932 0.0365541 -0.00982304 1 0 1 1 0 0 +EDGE2 2364 1905 0.996358 0.00332069 -3.11116 1 0 1 1 0 0 +EDGE2 2364 1925 1.02454 -0.0749792 -3.11307 1 0 1 1 0 0 +EDGE2 2364 2325 1.02474 0.0536128 -0.035214 1 0 1 1 0 0 +EDGE2 2364 1645 0.981985 0.00798523 0.0119766 1 0 1 1 0 0 +EDGE2 2364 1485 0.99383 0.0471049 -3.15817 1 0 1 1 0 0 +EDGE2 2364 1505 1.02014 -0.0580081 -3.17383 1 0 1 1 0 0 +EDGE2 2364 1365 1.07705 0.00170568 -3.14553 1 0 1 1 0 0 +EDGE2 2364 1325 0.957249 0.0366433 -0.0247724 1 0 1 1 0 0 +EDGE2 2364 2363 -0.976762 -0.0340733 0.000826526 1 0 1 1 0 0 +EDGE2 2364 1524 0.00184582 -0.0199428 0.00228319 1 0 1 1 0 0 +EDGE2 2364 2324 -0.0773584 -0.0173777 -0.0336605 1 0 1 1 0 0 +EDGE2 2364 2344 -0.000824809 -0.0139473 -0.00508765 1 0 1 1 0 0 +EDGE2 2364 1644 0.0530387 -0.0400245 -0.00536217 1 0 1 1 0 0 +EDGE2 2364 1324 0.000557784 -0.00623088 -0.01792 1 0 1 1 0 0 +EDGE2 2364 1323 -1.04185 -0.0204997 0.000202699 1 0 1 1 0 0 +EDGE2 2364 1643 -0.99836 -0.093288 0.0203935 1 0 1 1 0 0 +EDGE2 2364 2323 -1.0357 -0.0395749 0.0203349 1 0 1 1 0 0 +EDGE2 2364 2343 -1.07315 -0.0239737 -0.0253996 1 0 1 1 0 0 +EDGE2 2364 1523 -1.03421 0.0251952 -0.0182473 1 0 1 1 0 0 +EDGE2 2365 1345 0.114942 0.129832 -3.09822 1 0 1 1 0 0 +EDGE2 2365 1526 0.042614 1.11441 1.55761 1 0 1 1 0 0 +EDGE2 2365 1926 -0.0638654 0.952974 1.58723 1 0 1 1 0 0 +EDGE2 2365 2326 -0.0059713 1.00979 1.56644 1 0 1 1 0 0 +EDGE2 2365 2346 0.0498625 0.972388 1.57342 1 0 1 1 0 0 +EDGE2 2365 1646 0.0254052 1.00278 1.57618 1 0 1 1 0 0 +EDGE2 2365 1366 0.0248356 0.986036 1.56812 1 0 1 1 0 0 +EDGE2 2365 1506 -0.0307989 1.06171 1.55339 1 0 1 1 0 0 +EDGE2 2365 1924 1.1297 0.0111048 -3.15514 1 0 1 1 0 0 +EDGE2 2365 2345 0.0334391 -0.00904063 0.0246872 1 0 1 1 0 0 +EDGE2 2365 1344 1.04123 0.00299953 -3.16828 1 0 1 1 0 0 +EDGE2 2365 1484 1.06744 -0.0243192 -3.14087 1 0 1 1 0 0 +EDGE2 2365 1504 1.03495 -0.0212726 -3.13904 1 0 1 1 0 0 +EDGE2 2365 1904 1.02671 -0.0283437 -3.14613 1 0 1 1 0 0 +EDGE2 2365 1364 1.0166 -0.043249 -3.15265 1 0 1 1 0 0 +EDGE2 2365 1525 -0.083936 -0.0320183 0.0234542 1 0 1 1 0 0 +EDGE2 2365 1905 -0.0210981 0.0862897 -3.14768 1 0 1 1 0 0 +EDGE2 2365 1925 0.0674745 0.018071 -3.16666 1 0 1 1 0 0 +EDGE2 2365 2325 -0.125498 -0.0488184 0.00343893 1 0 1 1 0 0 +EDGE2 2365 1645 0.00893464 0.0171793 0.00900349 1 0 1 1 0 0 +EDGE2 2365 1485 0.000751843 0.00970778 -3.14948 1 0 1 1 0 0 +EDGE2 2365 1505 0.0355513 0.110788 -3.17032 1 0 1 1 0 0 +EDGE2 2365 1365 -0.049308 0.069884 -3.14998 1 0 1 1 0 0 +EDGE2 2365 1325 -0.061593 0.014882 -0.0110414 1 0 1 1 0 0 +EDGE2 2365 1524 -1.06653 0.0062178 -0.00422881 1 0 1 1 0 0 +EDGE2 2365 2324 -1.0085 -0.0270343 -0.0174786 1 0 1 1 0 0 +EDGE2 2365 2344 -1.01454 -0.00646446 -0.0376203 1 0 1 1 0 0 +EDGE2 2365 2364 -0.982618 -0.00757604 -0.0145685 1 0 1 1 0 0 +EDGE2 2365 1644 -0.972793 0.0482775 -0.0260529 1 0 1 1 0 0 +EDGE2 2365 1324 -0.989828 -0.0191355 0.0149836 1 0 1 1 0 0 +EDGE2 2365 1486 -0.00964685 -1.06772 -1.57367 1 0 1 1 0 0 +EDGE2 2365 1906 -0.0459064 -1.05447 -1.5834 1 0 1 1 0 0 +EDGE2 2365 1326 -0.032974 -0.992135 -1.54964 1 0 1 1 0 0 +EDGE2 2365 1346 0.0609728 -0.945296 -1.59018 1 0 1 1 0 0 +EDGE2 2366 2327 1.02782 -0.0376064 0.00679726 1 0 1 1 0 0 +EDGE2 2366 2347 1.02693 0.0932982 0.0092537 1 0 1 1 0 0 +EDGE2 2366 1345 -1.02824 0.115036 1.56239 1 0 1 1 0 0 +EDGE2 2366 1526 0.0061565 0.016377 -0.0117797 1 0 1 1 0 0 +EDGE2 2366 1507 1.00546 -0.0378656 0.00606565 1 0 1 1 0 0 +EDGE2 2366 1527 1.0365 -0.0249533 0.0174248 1 0 1 1 0 0 +EDGE2 2366 1647 1.05529 -0.0602007 -0.00472264 1 0 1 1 0 0 +EDGE2 2366 1927 0.984495 0.0671996 0.0177186 1 0 1 1 0 0 +EDGE2 2366 1367 0.979224 0.0182125 0.0110974 1 0 1 1 0 0 +EDGE2 2366 1926 0.0276203 0.025605 0.00131745 1 0 1 1 0 0 +EDGE2 2366 2326 0.0098411 0.0253462 -0.036887 1 0 1 1 0 0 +EDGE2 2366 2346 0.00457375 -0.0265882 -0.00665926 1 0 1 1 0 0 +EDGE2 2366 1646 0.00318477 -0.0322762 -0.0180245 1 0 1 1 0 0 +EDGE2 2366 1366 0.00933086 0.0252172 -0.00417571 1 0 1 1 0 0 +EDGE2 2366 1506 -0.011287 -0.0131216 -0.0128846 1 0 1 1 0 0 +EDGE2 2366 2345 -1.04455 0.0101332 -1.59953 1 0 1 1 0 0 +EDGE2 2366 2365 -0.983033 -0.0811804 -1.59494 1 0 1 1 0 0 +EDGE2 2366 1525 -1.10442 0.0189178 -1.61681 1 0 1 1 0 0 +EDGE2 2366 1905 -0.990965 -0.0919576 1.57424 1 0 1 1 0 0 +EDGE2 2366 1925 -1.09431 -0.0785735 1.60471 1 0 1 1 0 0 +EDGE2 2366 2325 -0.897002 -0.0266413 -1.5679 1 0 1 1 0 0 +EDGE2 2366 1645 -1.07372 0.00208186 -1.54603 1 0 1 1 0 0 +EDGE2 2366 1485 -0.929617 0.0382432 1.59966 1 0 1 1 0 0 +EDGE2 2366 1505 -0.890714 0.0758377 1.59376 1 0 1 1 0 0 +EDGE2 2366 1365 -1.06007 -0.0131166 1.5798 1 0 1 1 0 0 +EDGE2 2366 1325 -1.07583 0.0225257 -1.53981 1 0 1 1 0 0 +EDGE2 2367 2327 0.0297256 -0.0597085 -0.0277869 1 0 1 1 0 0 +EDGE2 2367 1648 0.980436 -0.0175052 -0.0442635 1 0 1 1 0 0 +EDGE2 2367 1928 1.07995 0.00545068 0.00148162 1 0 1 1 0 0 +EDGE2 2367 2328 0.978142 -0.0056107 0.0110015 1 0 1 1 0 0 +EDGE2 2367 2348 1.01578 0.00859585 0.00971666 1 0 1 1 0 0 +EDGE2 2367 1368 1.00768 0.00546226 0.00740903 1 0 1 1 0 0 +EDGE2 2367 1508 1.03722 0.074327 -0.00684381 1 0 1 1 0 0 +EDGE2 2367 1528 1.02797 -0.0599163 -0.0352493 1 0 1 1 0 0 +EDGE2 2367 2347 -0.0359403 -0.0189914 -0.0256537 1 0 1 1 0 0 +EDGE2 2367 1526 -1.05933 -0.0527264 -0.0378333 1 0 1 1 0 0 +EDGE2 2367 1507 0.0163573 0.029164 0.0303487 1 0 1 1 0 0 +EDGE2 2367 1527 0.0767499 -0.0279343 -0.0427188 1 0 1 1 0 0 +EDGE2 2367 1647 -0.0118597 -0.0669387 0.0184903 1 0 1 1 0 0 +EDGE2 2367 1927 0.0173748 0.022393 0.0147436 1 0 1 1 0 0 +EDGE2 2367 2366 -0.9344 -0.0272444 -0.0342659 1 0 1 1 0 0 +EDGE2 2367 1367 -0.017476 -0.103548 0.00898542 1 0 1 1 0 0 +EDGE2 2367 1926 -0.953726 0.0151045 0.0222981 1 0 1 1 0 0 +EDGE2 2367 2326 -1.11957 -0.0575145 0.0066669 1 0 1 1 0 0 +EDGE2 2367 2346 -1.00421 -0.014811 -0.0299584 1 0 1 1 0 0 +EDGE2 2367 1646 -0.971635 -0.0410338 0.0197678 1 0 1 1 0 0 +EDGE2 2367 1366 -0.963437 -0.066115 -0.004566 1 0 1 1 0 0 +EDGE2 2367 1506 -1.04214 0.0205405 0.0301999 1 0 1 1 0 0 +EDGE2 2368 2327 -0.960747 -0.00319232 -0.0125201 1 0 1 1 0 0 +EDGE2 2368 2349 0.92029 0.0427402 0.00357142 1 0 1 1 0 0 +EDGE2 2368 1509 0.977926 0.0249099 0.0200725 1 0 1 1 0 0 +EDGE2 2368 1649 1.00382 -0.0761222 0.00442991 1 0 1 1 0 0 +EDGE2 2368 1929 1.05961 -0.074313 0.00947247 1 0 1 1 0 0 +EDGE2 2368 2329 0.947308 -0.145152 0.0249499 1 0 1 1 0 0 +EDGE2 2368 1529 1.0377 -0.0598074 -0.0224977 1 0 1 1 0 0 +EDGE2 2368 1369 0.970579 -0.100353 -0.0127021 1 0 1 1 0 0 +EDGE2 2368 1648 0.0857169 0.0406641 -0.0127918 1 0 1 1 0 0 +EDGE2 2368 1928 -0.0237481 0.00545918 0.0235001 1 0 1 1 0 0 +EDGE2 2368 2328 -0.0289532 0.0311895 -0.0232209 1 0 1 1 0 0 +EDGE2 2368 2348 -0.0564515 -0.00340367 -0.0280031 1 0 1 1 0 0 +EDGE2 2368 1368 -0.0111263 0.012284 0.026959 1 0 1 1 0 0 +EDGE2 2368 1508 0.0294481 0.0802211 0.0113867 1 0 1 1 0 0 +EDGE2 2368 1528 0.0582826 -0.172723 0.00612343 1 0 1 1 0 0 +EDGE2 2368 2367 -0.989865 0.11027 0.00252764 1 0 1 1 0 0 +EDGE2 2368 2347 -0.947354 -0.034158 0.0151236 1 0 1 1 0 0 +EDGE2 2368 1507 -0.928575 0.0560431 0.0192337 1 0 1 1 0 0 +EDGE2 2368 1527 -0.980857 0.0102852 -0.0032298 1 0 1 1 0 0 +EDGE2 2368 1647 -1.01273 -0.0460968 -0.0442736 1 0 1 1 0 0 +EDGE2 2368 1927 -0.929412 -0.0129313 0.0156534 1 0 1 1 0 0 +EDGE2 2368 1367 -1.03096 -0.0334772 -0.0200317 1 0 1 1 0 0 +EDGE2 2369 2330 1.05731 0.0549712 0.00336664 1 0 1 1 0 0 +EDGE2 2369 2350 0.96696 0.0303445 -0.00561736 1 0 1 1 0 0 +EDGE2 2369 1650 0.992409 -0.0167298 -0.00545877 1 0 1 1 0 0 +EDGE2 2369 1710 1.01806 -0.0169517 -3.11291 1 0 1 1 0 0 +EDGE2 2369 1870 1.07383 0.0272088 -3.14721 1 0 1 1 0 0 +EDGE2 2369 1930 0.981136 -0.0704442 -0.00463429 1 0 1 1 0 0 +EDGE2 2369 1670 1.05904 -0.00268904 -3.11801 1 0 1 1 0 0 +EDGE2 2369 1470 1.04482 0.0858386 -3.17083 1 0 1 1 0 0 +EDGE2 2369 1510 1.0254 -0.00498243 0.00115968 1 0 1 1 0 0 +EDGE2 2369 1530 0.888474 0.0409477 0.0290751 1 0 1 1 0 0 +EDGE2 2369 1370 1.04085 -0.0250699 -0.0164745 1 0 1 1 0 0 +EDGE2 2369 2368 -1.00042 -0.0767672 0.0239455 1 0 1 1 0 0 +EDGE2 2369 2349 0.0834798 -0.0292128 0.0287083 1 0 1 1 0 0 +EDGE2 2369 1509 0.0184299 0.018325 0.00913636 1 0 1 1 0 0 +EDGE2 2369 1649 0.0336043 0.0783117 0.0122426 1 0 1 1 0 0 +EDGE2 2369 1929 -0.0130981 -0.00971509 0.0205297 1 0 1 1 0 0 +EDGE2 2369 2329 -0.0701436 -0.0398587 -0.0166578 1 0 1 1 0 0 +EDGE2 2369 1529 -0.0406855 -0.0383969 0.0191699 1 0 1 1 0 0 +EDGE2 2369 1369 -0.00125 0.0557154 -0.00792382 1 0 1 1 0 0 +EDGE2 2369 1648 -0.880847 -0.0428381 -0.0395011 1 0 1 1 0 0 +EDGE2 2369 1928 -1.1203 0.0406844 -0.0124161 1 0 1 1 0 0 +EDGE2 2369 2328 -0.888241 0.00878633 -0.0073282 1 0 1 1 0 0 +EDGE2 2369 2348 -1.00692 0.07598 -0.0278681 1 0 1 1 0 0 +EDGE2 2369 1368 -1.00876 -0.0394399 0.00321385 1 0 1 1 0 0 +EDGE2 2369 1508 -1.03108 0.120153 0.0335168 1 0 1 1 0 0 +EDGE2 2369 1528 -0.875329 0.0373993 -0.0261994 1 0 1 1 0 0 +EDGE2 2370 1931 -0.00450511 -0.987491 -1.58298 1 0 1 1 0 0 +EDGE2 2370 1669 0.942209 0.0736852 -3.16372 1 0 1 1 0 0 +EDGE2 2370 1709 0.851899 0.0156411 -3.14628 1 0 1 1 0 0 +EDGE2 2370 1869 0.969937 0.0449557 -3.10785 1 0 1 1 0 0 +EDGE2 2370 1469 0.977225 -0.0297321 -3.14195 1 0 1 1 0 0 +EDGE2 2370 2330 -0.047651 -0.0177726 -0.00437119 1 0 1 1 0 0 +EDGE2 2370 1671 0.0165642 -1.0108 -1.56659 1 0 1 1 0 0 +EDGE2 2370 1711 -0.0239837 -0.957137 -1.58502 1 0 1 1 0 0 +EDGE2 2370 1871 0.0508808 -1.02345 -1.572 1 0 1 1 0 0 +EDGE2 2370 1471 -0.0456031 -0.979106 -1.56409 1 0 1 1 0 0 +EDGE2 2370 2350 -0.0154184 -0.00881735 0.0104921 1 0 1 1 0 0 +EDGE2 2370 1650 -0.0488379 -0.0193531 -0.0182845 1 0 1 1 0 0 +EDGE2 2370 1710 0.0153937 -0.0206477 -3.13829 1 0 1 1 0 0 +EDGE2 2370 1870 -0.0246639 0.0138674 -3.13271 1 0 1 1 0 0 +EDGE2 2370 1930 0.00661179 -0.0445279 0.0148274 1 0 1 1 0 0 +EDGE2 2370 1670 -0.0838774 -0.0553978 -3.15509 1 0 1 1 0 0 +EDGE2 2370 1470 0.0809731 0.0298821 -3.12819 1 0 1 1 0 0 +EDGE2 2370 1510 -0.0308581 -0.0351147 0.00737871 1 0 1 1 0 0 +EDGE2 2370 1530 0.116507 0.0118051 0.014333 1 0 1 1 0 0 +EDGE2 2370 1370 0.0462222 0.0219774 0.0164417 1 0 1 1 0 0 +EDGE2 2370 2351 0.0439636 0.986569 1.57956 1 0 1 1 0 0 +EDGE2 2370 1371 -0.0733425 0.927232 1.59748 1 0 1 1 0 0 +EDGE2 2370 1531 0.0916152 1.00101 1.5707 1 0 1 1 0 0 +EDGE2 2370 1651 0.0489835 0.999039 1.57875 1 0 1 1 0 0 +EDGE2 2370 2331 0.0187923 1.03358 1.60093 1 0 1 1 0 0 +EDGE2 2370 1511 -0.0522771 0.989589 1.55419 1 0 1 1 0 0 +EDGE2 2370 2349 -0.928608 -0.0190539 0.0204268 1 0 1 1 0 0 +EDGE2 2370 2369 -1.01576 0.0617763 -0.0228985 1 0 1 1 0 0 +EDGE2 2370 1509 -1.02095 -0.044762 -0.00587869 1 0 1 1 0 0 +EDGE2 2370 1649 -0.935713 0.0397592 0.0244563 1 0 1 1 0 0 +EDGE2 2370 1929 -0.945728 -0.0253168 0.0587976 1 0 1 1 0 0 +EDGE2 2370 2329 -1.05682 -0.0131869 -0.000533478 1 0 1 1 0 0 +EDGE2 2370 1529 -0.909858 0.0224391 -0.0206072 1 0 1 1 0 0 +EDGE2 2370 1369 -0.947759 0.0402984 0.00311078 1 0 1 1 0 0 +EDGE2 2371 2330 -1.02961 0.0367522 -1.56413 1 0 1 1 0 0 +EDGE2 2371 2370 -0.989095 -0.118626 -1.58429 1 0 1 1 0 0 +EDGE2 2371 2350 -1.09698 -0.00506869 -1.57151 1 0 1 1 0 0 +EDGE2 2371 1650 -0.98792 0.0175551 -1.56628 1 0 1 1 0 0 +EDGE2 2371 1710 -1.026 -0.0715343 1.59552 1 0 1 1 0 0 +EDGE2 2371 1870 -1.12729 0.0457374 1.59301 1 0 1 1 0 0 +EDGE2 2371 1930 -0.915127 0.0607396 -1.55968 1 0 1 1 0 0 +EDGE2 2371 1670 -0.947279 -0.00212294 1.56055 1 0 1 1 0 0 +EDGE2 2371 1470 -1.04668 -0.0156034 1.58649 1 0 1 1 0 0 +EDGE2 2371 1510 -1.04949 -0.00468756 -1.59329 1 0 1 1 0 0 +EDGE2 2371 1530 -0.976622 -0.0186945 -1.58486 1 0 1 1 0 0 +EDGE2 2371 1370 -0.98116 -0.0145141 -1.55765 1 0 1 1 0 0 +EDGE2 2371 2351 -0.069648 0.0829461 0.00835277 1 0 1 1 0 0 +EDGE2 2371 1371 0.000643404 -0.052732 0.015665 1 0 1 1 0 0 +EDGE2 2371 1531 -0.0130277 0.0520402 -0.00352872 1 0 1 1 0 0 +EDGE2 2371 1651 0.0164396 -0.00736319 0.0516024 1 0 1 1 0 0 +EDGE2 2371 2331 0.0779126 0.0271947 -0.000465005 1 0 1 1 0 0 +EDGE2 2371 1511 0.0417577 -0.0574156 -0.00419058 1 0 1 1 0 0 +EDGE2 2371 1512 0.984089 0.0536457 -0.00585102 1 0 1 1 0 0 +EDGE2 2371 1652 1.11592 0.0509049 -0.0126642 1 0 1 1 0 0 +EDGE2 2371 2332 0.973691 0.0386696 -0.00063196 1 0 1 1 0 0 +EDGE2 2371 2352 0.940394 0.0317378 -0.00501484 1 0 1 1 0 0 +EDGE2 2371 1532 1.07982 -0.00192017 -0.00106921 1 0 1 1 0 0 +EDGE2 2371 1372 0.986032 0.106191 0.0199622 1 0 1 1 0 0 +EDGE2 2372 2351 -1.04669 0.0284106 -0.00882605 1 0 1 1 0 0 +EDGE2 2372 2371 -1.07669 -0.0365208 0.00283105 1 0 1 1 0 0 +EDGE2 2372 1371 -0.923133 0.0188055 -0.0283065 1 0 1 1 0 0 +EDGE2 2372 1531 -0.941631 -0.0297138 -0.0252098 1 0 1 1 0 0 +EDGE2 2372 1651 -1.04446 0.020784 0.0150664 1 0 1 1 0 0 +EDGE2 2372 2331 -0.989842 0.0475617 -0.014389 1 0 1 1 0 0 +EDGE2 2372 1511 -1.00547 -0.0869307 0.0196679 1 0 1 1 0 0 +EDGE2 2372 1512 0.0113523 -0.0127015 0.00389609 1 0 1 1 0 0 +EDGE2 2372 1652 -0.00946342 -0.036482 -0.00419451 1 0 1 1 0 0 +EDGE2 2372 2332 0.0219142 -0.0381476 -0.0113241 1 0 1 1 0 0 +EDGE2 2372 2352 -0.0360868 -0.00837544 0.00310144 1 0 1 1 0 0 +EDGE2 2372 1532 0.0189627 0.0616967 -0.04349 1 0 1 1 0 0 +EDGE2 2372 1372 0.00562751 0.111733 -0.00160547 1 0 1 1 0 0 +EDGE2 2372 1513 0.992286 0.00892053 -0.00865527 1 0 1 1 0 0 +EDGE2 2372 1653 0.976246 -0.0500945 0.0280845 1 0 1 1 0 0 +EDGE2 2372 2333 0.986134 0.0107461 0.0292186 1 0 1 1 0 0 +EDGE2 2372 2353 1.05636 0.0840043 0.0241481 1 0 1 1 0 0 +EDGE2 2372 1533 0.953769 0.0608139 0.00263066 1 0 1 1 0 0 +EDGE2 2372 1373 0.985463 -0.0918392 -0.0205899 1 0 1 1 0 0 +EDGE2 2373 2372 -0.979145 -0.0209819 0.000531799 1 0 1 1 0 0 +EDGE2 2373 1512 -1.06676 -0.0193625 -0.0160591 1 0 1 1 0 0 +EDGE2 2373 1652 -0.997544 0.00504918 -0.0260103 1 0 1 1 0 0 +EDGE2 2373 2332 -0.941775 -0.00798676 0.00518478 1 0 1 1 0 0 +EDGE2 2373 2352 -1.09336 0.0417426 0.0196771 1 0 1 1 0 0 +EDGE2 2373 1532 -1.00702 0.0090766 -0.00205743 1 0 1 1 0 0 +EDGE2 2373 1372 -1.0208 0.061133 0.0192046 1 0 1 1 0 0 +EDGE2 2373 1513 -0.0136909 0.0281742 0.0288162 1 0 1 1 0 0 +EDGE2 2373 1653 0.0136119 -0.0296658 -0.0103374 1 0 1 1 0 0 +EDGE2 2373 2333 -0.00205052 0.00115064 0.00896431 1 0 1 1 0 0 +EDGE2 2373 2353 -0.0278721 -0.0515494 -0.00738004 1 0 1 1 0 0 +EDGE2 2373 1533 0.035249 0.0247409 -0.0143494 1 0 1 1 0 0 +EDGE2 2373 1373 0.0336044 0.0805898 0.0228673 1 0 1 1 0 0 +EDGE2 2373 1514 0.94724 -0.0182076 0.0198373 1 0 1 1 0 0 +EDGE2 2373 1654 0.999532 -0.0238794 0.0381061 1 0 1 1 0 0 +EDGE2 2373 2334 1.00047 0.0437425 0.003726 1 0 1 1 0 0 +EDGE2 2373 2354 0.993297 0.0145614 -0.0018059 1 0 1 1 0 0 +EDGE2 2373 1534 0.939613 -0.0313374 0.0167074 1 0 1 1 0 0 +EDGE2 2373 1374 1.02836 -0.025327 0.00147074 1 0 1 1 0 0 +EDGE2 2374 1535 0.94976 -0.0194067 0.0304826 1 0 1 1 0 0 +EDGE2 2374 2373 -0.974969 0.0343653 0.030335 1 0 1 1 0 0 +EDGE2 2374 1513 -0.963028 -0.0654295 0.006982 1 0 1 1 0 0 +EDGE2 2374 1653 -0.981856 0.058487 0.00759129 1 0 1 1 0 0 +EDGE2 2374 2333 -0.977956 -0.0704319 0.000209918 1 0 1 1 0 0 +EDGE2 2374 2353 -1.02727 -0.0231595 0.00589235 1 0 1 1 0 0 +EDGE2 2374 1533 -0.920393 0.0524272 0.0270403 1 0 1 1 0 0 +EDGE2 2374 1373 -1.025 0.083314 -0.00863096 1 0 1 1 0 0 +EDGE2 2374 1514 0.0131688 0.013225 -0.00949885 1 0 1 1 0 0 +EDGE2 2374 1654 -0.0701167 0.025165 -0.00553503 1 0 1 1 0 0 +EDGE2 2374 2334 -0.0158021 0.0748873 0.0273846 1 0 1 1 0 0 +EDGE2 2374 2354 0.0492621 -0.0244272 0.0110614 1 0 1 1 0 0 +EDGE2 2374 1534 -0.0416667 0.0222152 0.00441179 1 0 1 1 0 0 +EDGE2 2374 1374 -0.0487068 0.00254653 0.0105551 1 0 1 1 0 0 +EDGE2 2374 1855 1.0216 0.0590445 -3.15895 1 0 1 1 0 0 +EDGE2 2374 2335 1.04488 -0.090181 0.0130989 1 0 1 1 0 0 +EDGE2 2374 2355 0.960111 -0.0725648 -0.0144669 1 0 1 1 0 0 +EDGE2 2374 2315 1.02929 -0.047906 -3.13114 1 0 1 1 0 0 +EDGE2 2374 1595 1.01759 0.0511768 -3.13216 1 0 1 1 0 0 +EDGE2 2374 1655 0.91916 -0.0122974 -0.0252157 1 0 1 1 0 0 +EDGE2 2374 1575 0.993183 0.035684 -3.15729 1 0 1 1 0 0 +EDGE2 2374 1375 0.982606 -0.0207742 -0.0122376 1 0 1 1 0 0 +EDGE2 2374 1515 0.996105 -0.0715753 0.0317736 1 0 1 1 0 0 +EDGE2 2375 1656 0.0370193 -0.955726 -1.57496 1 0 1 1 0 0 +EDGE2 2375 1856 0.0362859 -0.951656 -1.56894 1 0 1 1 0 0 +EDGE2 2375 1536 0.0546335 -0.952612 -1.63388 1 0 1 1 0 0 +EDGE2 2375 1576 -0.0302808 -1.01585 -1.59234 1 0 1 1 0 0 +EDGE2 2375 1376 0.039411 -0.961876 -1.57193 1 0 1 1 0 0 +EDGE2 2375 1535 0.0151161 -0.0937992 0.0276862 1 0 1 1 0 0 +EDGE2 2375 2374 -0.957417 0.0446119 0.00585935 1 0 1 1 0 0 +EDGE2 2375 1514 -0.938051 -0.0124205 0.0177189 1 0 1 1 0 0 +EDGE2 2375 1654 -1.04235 -0.0598646 -0.0195206 1 0 1 1 0 0 +EDGE2 2375 2334 -1.0391 -0.0197455 -0.00349675 1 0 1 1 0 0 +EDGE2 2375 2354 -0.993538 0.0284739 -0.0196445 1 0 1 1 0 0 +EDGE2 2375 1534 -0.997419 -0.0103878 0.016839 1 0 1 1 0 0 +EDGE2 2375 1374 -0.941502 -0.00598922 0.022248 1 0 1 1 0 0 +EDGE2 2375 1855 -0.0885252 0.0413286 -3.15259 1 0 1 1 0 0 +EDGE2 2375 2335 -0.0252085 0.0385925 0.000162912 1 0 1 1 0 0 +EDGE2 2375 2355 -0.0361976 0.0745198 0.00105327 1 0 1 1 0 0 +EDGE2 2375 2315 -0.016611 0.0314001 -3.09422 1 0 1 1 0 0 +EDGE2 2375 1595 -0.0379587 -0.0711787 -3.16099 1 0 1 1 0 0 +EDGE2 2375 1655 -0.0418966 0.0560108 0.000753956 1 0 1 1 0 0 +EDGE2 2375 1575 0.00329583 -0.0604783 -3.14857 1 0 1 1 0 0 +EDGE2 2375 1854 0.948672 -0.0798787 -3.14448 1 0 1 1 0 0 +EDGE2 2375 1375 0.00821777 0.0268617 -0.0165754 1 0 1 1 0 0 +EDGE2 2375 1515 0.0627411 -0.0019077 -0.0198943 1 0 1 1 0 0 +EDGE2 2375 2314 1.05409 0.0091675 -3.12593 1 0 1 1 0 0 +EDGE2 2375 1574 1.06314 0.000122885 -3.13167 1 0 1 1 0 0 +EDGE2 2375 1594 1.00703 -0.0301863 -3.13559 1 0 1 1 0 0 +EDGE2 2375 2336 -0.00693022 0.989792 1.5755 1 0 1 1 0 0 +EDGE2 2375 2356 0.0319639 0.991238 1.58994 1 0 1 1 0 0 +EDGE2 2375 1516 0.053838 0.967547 1.59928 1 0 1 1 0 0 +EDGE2 2375 1596 0.0344651 0.982857 1.56636 1 0 1 1 0 0 +EDGE2 2375 2316 -0.0193845 1.02665 1.56745 1 0 1 1 0 0 +EDGE2 2376 1537 0.958584 -0.0237903 -0.00737528 1 0 1 1 0 0 +EDGE2 2376 1577 0.929436 -0.00828665 -0.00596266 1 0 1 1 0 0 +EDGE2 2376 1857 0.985132 0.0502635 0.0165527 1 0 1 1 0 0 +EDGE2 2376 1657 0.936151 0.0341944 -0.0155449 1 0 1 1 0 0 +EDGE2 2376 1656 0.0275226 0.00867642 0.0253784 1 0 1 1 0 0 +EDGE2 2376 1377 0.982112 -0.0808649 -0.0126096 1 0 1 1 0 0 +EDGE2 2376 1856 0.0889388 -0.0206891 0.00717926 1 0 1 1 0 0 +EDGE2 2376 1536 0.00687024 0.0673298 0.000803417 1 0 1 1 0 0 +EDGE2 2376 1576 0.0607088 0.102593 0.00564546 1 0 1 1 0 0 +EDGE2 2376 1376 -0.0332201 -0.0637939 -0.0113117 1 0 1 1 0 0 +EDGE2 2376 1535 -1.01804 0.025812 1.5968 1 0 1 1 0 0 +EDGE2 2376 1855 -0.992997 -0.0289929 -1.56641 1 0 1 1 0 0 +EDGE2 2376 2335 -1.04713 -0.0213303 1.58919 1 0 1 1 0 0 +EDGE2 2376 2355 -0.975632 -0.0755704 1.56236 1 0 1 1 0 0 +EDGE2 2376 2375 -0.92045 -0.0299274 1.55932 1 0 1 1 0 0 +EDGE2 2376 2315 -0.980957 0.0159567 -1.58088 1 0 1 1 0 0 +EDGE2 2376 1595 -1.03337 0.0357172 -1.57343 1 0 1 1 0 0 +EDGE2 2376 1655 -1.00166 -0.0680566 1.57472 1 0 1 1 0 0 +EDGE2 2376 1575 -1.02472 0.0109947 -1.531 1 0 1 1 0 0 +EDGE2 2376 1375 -1.01913 -0.00733721 1.59663 1 0 1 1 0 0 +EDGE2 2376 1515 -1.08638 -0.014205 1.54965 1 0 1 1 0 0 +EDGE2 2377 1378 1.07822 0.0154802 0.0153292 1 0 1 1 0 0 +EDGE2 2377 1858 1.08263 0.0133047 -0.00118644 1 0 1 1 0 0 +EDGE2 2377 1578 0.977684 0.0123598 -0.0102902 1 0 1 1 0 0 +EDGE2 2377 1658 0.977235 0.0217652 0.0140323 1 0 1 1 0 0 +EDGE2 2377 1538 0.994216 -0.0728698 -0.0278466 1 0 1 1 0 0 +EDGE2 2377 1537 0.101785 -0.017781 0.0340697 1 0 1 1 0 0 +EDGE2 2377 1577 0.0383872 0.0203677 -0.00900936 1 0 1 1 0 0 +EDGE2 2377 1857 -0.0365318 0.0511443 0.00532012 1 0 1 1 0 0 +EDGE2 2377 1657 0.0126955 -0.0702239 0.0121462 1 0 1 1 0 0 +EDGE2 2377 1656 -0.978072 -0.00367145 0.0200682 1 0 1 1 0 0 +EDGE2 2377 2376 -0.987489 0.0587731 -0.0157541 1 0 1 1 0 0 +EDGE2 2377 1377 0.0492766 -0.101422 -0.0339822 1 0 1 1 0 0 +EDGE2 2377 1856 -1.02931 -0.0848416 -0.0217073 1 0 1 1 0 0 +EDGE2 2377 1536 -1.06828 0.00135596 0.0102207 1 0 1 1 0 0 +EDGE2 2377 1576 -1.0548 0.0815518 -0.00870457 1 0 1 1 0 0 +EDGE2 2377 1376 -0.992176 0.0823959 -0.028022 1 0 1 1 0 0 +EDGE2 2378 1378 -0.0702374 0.0403042 0.0137974 1 0 1 1 0 0 +EDGE2 2378 1858 -0.0284737 -0.0318304 -0.0192144 1 0 1 1 0 0 +EDGE2 2378 1579 1.03481 0.113911 0.021654 1 0 1 1 0 0 +EDGE2 2378 1859 0.943517 0.0546224 -0.00361161 1 0 1 1 0 0 +EDGE2 2378 1659 0.942809 -0.0252024 -0.0145064 1 0 1 1 0 0 +EDGE2 2378 1379 0.963669 -0.0127508 0.00398484 1 0 1 1 0 0 +EDGE2 2378 1539 1.09831 -0.00271769 0.0400735 1 0 1 1 0 0 +EDGE2 2378 1578 0.0483365 -0.118599 -0.00906933 1 0 1 1 0 0 +EDGE2 2378 1658 0.00465301 0.0763969 -0.00129301 1 0 1 1 0 0 +EDGE2 2378 1538 -0.0337743 -0.0685182 0.00367476 1 0 1 1 0 0 +EDGE2 2378 1537 -1.02183 -0.00386423 0.00541953 1 0 1 1 0 0 +EDGE2 2378 1577 -0.923192 -0.0228758 0.0105599 1 0 1 1 0 0 +EDGE2 2378 1857 -1.03111 0.0283831 0.0155114 1 0 1 1 0 0 +EDGE2 2378 2377 -1.01112 -0.0372106 -0.0102423 1 0 1 1 0 0 +EDGE2 2378 1657 -1.00627 0.00506705 0.00324555 1 0 1 1 0 0 +EDGE2 2378 1377 -1.05085 0.0515837 0.0254548 1 0 1 1 0 0 +EDGE2 2379 1540 0.997027 -0.0280121 0.0178795 1 0 1 1 0 0 +EDGE2 2379 1860 0.969085 0.0115576 0.0156168 1 0 1 1 0 0 +EDGE2 2379 1580 0.937373 0.0458839 -0.00210666 1 0 1 1 0 0 +EDGE2 2379 1660 0.967456 0.0638934 -0.00143759 1 0 1 1 0 0 +EDGE2 2379 1840 0.999516 0.0134455 -3.15324 1 0 1 1 0 0 +EDGE2 2379 1560 0.967827 -0.0178021 -3.09738 1 0 1 1 0 0 +EDGE2 2379 1380 0.985753 0.0861285 -0.00113707 1 0 1 1 0 0 +EDGE2 2379 1378 -0.972064 -0.0244244 -0.0100871 1 0 1 1 0 0 +EDGE2 2379 1858 -1.03072 -0.0553834 -0.0102931 1 0 1 1 0 0 +EDGE2 2379 1579 0.0408504 -0.0258858 0.0228988 1 0 1 1 0 0 +EDGE2 2379 1859 -0.0242943 0.06525 -0.00859588 1 0 1 1 0 0 +EDGE2 2379 1659 0.0014628 0.0122308 -0.027063 1 0 1 1 0 0 +EDGE2 2379 1379 0.0307658 0.0199815 0.00703471 1 0 1 1 0 0 +EDGE2 2379 1539 0.000374957 -0.11317 -0.0180407 1 0 1 1 0 0 +EDGE2 2379 2378 -1.05049 0.0377305 -0.00490407 1 0 1 1 0 0 +EDGE2 2379 1578 -0.994652 0.0333492 0.0123814 1 0 1 1 0 0 +EDGE2 2379 1658 -1.01028 0.0438672 0.00120468 1 0 1 1 0 0 +EDGE2 2379 1538 -1.03747 -0.0213513 -0.00620801 1 0 1 1 0 0 +EDGE2 2380 1839 0.973254 -0.00399004 -3.13225 1 0 1 1 0 0 +EDGE2 2380 1559 0.971733 0.0141032 -3.14126 1 0 1 1 0 0 +EDGE2 2380 1540 -0.0379979 0.0220023 0.0161559 1 0 1 1 0 0 +EDGE2 2380 1861 0.0475599 -0.995613 -1.58021 1 0 1 1 0 0 +EDGE2 2380 1860 0.0920734 0.0364186 -0.00690137 1 0 1 1 0 0 +EDGE2 2380 1381 -0.0475661 -0.99537 -1.57199 1 0 1 1 0 0 +EDGE2 2380 1661 0.0710219 -1.00783 -1.58932 1 0 1 1 0 0 +EDGE2 2380 1580 -0.112312 0.126293 -0.0130383 1 0 1 1 0 0 +EDGE2 2380 1660 -0.0223193 -0.0940541 -0.0158134 1 0 1 1 0 0 +EDGE2 2380 1840 -0.0431337 0.0238067 -3.1507 1 0 1 1 0 0 +EDGE2 2380 1560 0.011821 0.0482029 -3.13316 1 0 1 1 0 0 +EDGE2 2380 1581 -0.0206278 0.954409 1.56503 1 0 1 1 0 0 +EDGE2 2380 1380 0.0117481 -0.109964 -0.0139801 1 0 1 1 0 0 +EDGE2 2380 1841 0.0282924 0.998443 1.56474 1 0 1 1 0 0 +EDGE2 2380 1541 0.0450651 1.0019 1.57304 1 0 1 1 0 0 +EDGE2 2380 1561 0.0741636 1.00488 1.57155 1 0 1 1 0 0 +EDGE2 2380 1579 -0.974067 -0.0174755 -0.0046164 1 0 1 1 0 0 +EDGE2 2380 1859 -1.07806 0.0988177 -0.0078994 1 0 1 1 0 0 +EDGE2 2380 2379 -1.06223 0.0832331 -0.0118806 1 0 1 1 0 0 +EDGE2 2380 1659 -1.01879 -0.0676268 -0.0198624 1 0 1 1 0 0 +EDGE2 2380 1379 -0.975281 -0.141855 0.0102306 1 0 1 1 0 0 +EDGE2 2380 1539 -0.973357 -0.0425771 -0.0247797 1 0 1 1 0 0 +EDGE2 2381 1540 -1.05637 0.0585167 -1.56169 1 0 1 1 0 0 +EDGE2 2381 1860 -0.929436 -0.00327382 -1.54055 1 0 1 1 0 0 +EDGE2 2381 2380 -1.01145 -0.0467151 -1.57714 1 0 1 1 0 0 +EDGE2 2381 1580 -1.07451 0.0462158 -1.59558 1 0 1 1 0 0 +EDGE2 2381 1660 -0.997876 0.0143438 -1.58147 1 0 1 1 0 0 +EDGE2 2381 1840 -1.0222 0.094048 1.59828 1 0 1 1 0 0 +EDGE2 2381 1560 -1.0699 -0.0564656 1.57495 1 0 1 1 0 0 +EDGE2 2381 1842 1.05671 -0.00211993 -0.00173279 1 0 1 1 0 0 +EDGE2 2381 1581 -0.0140211 0.0593724 -0.00932294 1 0 1 1 0 0 +EDGE2 2381 1380 -0.951117 0.0514948 -1.55988 1 0 1 1 0 0 +EDGE2 2381 1841 -0.0203619 -0.00816411 -0.00155823 1 0 1 1 0 0 +EDGE2 2381 1541 -0.0102792 -0.00499536 -0.0239562 1 0 1 1 0 0 +EDGE2 2381 1561 0.0352827 0.0168626 0.00952737 1 0 1 1 0 0 +EDGE2 2381 1542 1.0199 -0.0570937 -4.79744e-05 1 0 1 1 0 0 +EDGE2 2381 1562 1.02394 -0.0660079 -0.0278135 1 0 1 1 0 0 +EDGE2 2381 1582 0.993386 0.0332881 -0.0180132 1 0 1 1 0 0 +EDGE2 2382 1543 1.04751 -0.00840101 0.00252693 1 0 1 1 0 0 +EDGE2 2382 1842 -0.0723912 0.052139 -0.0120086 1 0 1 1 0 0 +EDGE2 2382 1581 -1.04975 0.0913226 -0.00403821 1 0 1 1 0 0 +EDGE2 2382 2381 -0.969115 9.91778e-05 0.00891288 1 0 1 1 0 0 +EDGE2 2382 1841 -1.0432 0.00863989 -0.0108755 1 0 1 1 0 0 +EDGE2 2382 1541 -0.940206 -0.0902821 -0.0105616 1 0 1 1 0 0 +EDGE2 2382 1561 -0.972467 -0.0792014 0.0218057 1 0 1 1 0 0 +EDGE2 2382 1542 -0.0618839 0.0336737 -0.0494318 1 0 1 1 0 0 +EDGE2 2382 1562 0.0476832 0.0710953 0.00526841 1 0 1 1 0 0 +EDGE2 2382 1582 0.0945759 -0.00318978 0.0353851 1 0 1 1 0 0 +EDGE2 2382 1583 0.916926 -0.0294449 -0.0141194 1 0 1 1 0 0 +EDGE2 2382 1843 1.08825 0.0426892 0.0140508 1 0 1 1 0 0 +EDGE2 2382 1563 1.02428 0.01277 -0.0124701 1 0 1 1 0 0 +EDGE2 2383 1543 -0.00143274 -0.0609602 0.00966635 1 0 1 1 0 0 +EDGE2 2383 1842 -1.00912 -0.076886 -0.0204841 1 0 1 1 0 0 +EDGE2 2383 2382 -0.964164 -0.000801941 0.0332422 1 0 1 1 0 0 +EDGE2 2383 1542 -1.05409 -0.0143155 -0.00686602 1 0 1 1 0 0 +EDGE2 2383 1562 -0.929766 0.0217503 0.0164381 1 0 1 1 0 0 +EDGE2 2383 1582 -0.96761 -0.0518449 -0.0212148 1 0 1 1 0 0 +EDGE2 2383 1583 0.0132857 -0.0319354 0.00967816 1 0 1 1 0 0 +EDGE2 2383 1843 0.0534239 0.0177551 0.0185937 1 0 1 1 0 0 +EDGE2 2383 1563 -0.0262201 -0.106366 -0.00280729 1 0 1 1 0 0 +EDGE2 2383 1564 0.981409 0.0308028 -0.0052502 1 0 1 1 0 0 +EDGE2 2383 1844 1.02964 0.0840331 -0.0325978 1 0 1 1 0 0 +EDGE2 2383 1584 0.973601 0.061537 0.0155023 1 0 1 1 0 0 +EDGE2 2383 1544 0.876565 0.0231573 0.0257279 1 0 1 1 0 0 +EDGE2 2384 1543 -1.02121 -0.0119624 -0.0201811 1 0 1 1 0 0 +EDGE2 2384 2383 -1.10713 -0.00370564 0.0193024 1 0 1 1 0 0 +EDGE2 2384 1583 -1.00524 -0.0268634 0.00203235 1 0 1 1 0 0 +EDGE2 2384 1843 -0.971831 0.0323656 -0.0292413 1 0 1 1 0 0 +EDGE2 2384 1563 -1.05972 -0.041709 0.00474851 1 0 1 1 0 0 +EDGE2 2384 1564 0.00216702 -0.00424939 -0.0130074 1 0 1 1 0 0 +EDGE2 2384 1844 0.00532503 0.00825624 0.0257287 1 0 1 1 0 0 +EDGE2 2384 1584 -0.0646308 0.0811334 0.0106559 1 0 1 1 0 0 +EDGE2 2384 1544 0.0202978 0.0415301 0.0269562 1 0 1 1 0 0 +EDGE2 2384 1265 1.04005 -0.0158453 -3.15851 1 0 1 1 0 0 +EDGE2 2384 2305 1.02752 -0.0632356 -3.12777 1 0 1 1 0 0 +EDGE2 2384 1565 0.932368 0.0289863 -0.016 1 0 1 1 0 0 +EDGE2 2384 1585 1.03822 0.0102471 0.000996162 1 0 1 1 0 0 +EDGE2 2384 1845 1.0036 -0.0570092 -0.038763 1 0 1 1 0 0 +EDGE2 2384 1545 0.949728 -0.0427416 0.0219593 1 0 1 1 0 0 +EDGE2 2385 1564 -1.0731 -0.00959608 0.00704406 1 0 1 1 0 0 +EDGE2 2385 1844 -0.969694 0.0323594 -0.0023644 1 0 1 1 0 0 +EDGE2 2385 2384 -0.948781 -0.0680201 -0.00544962 1 0 1 1 0 0 +EDGE2 2385 1584 -1.00375 -0.0354681 0.00722791 1 0 1 1 0 0 +EDGE2 2385 1544 -0.955245 -0.0869276 -0.00942865 1 0 1 1 0 0 +EDGE2 2385 1546 0.0764131 -0.949275 -1.56445 1 0 1 1 0 0 +EDGE2 2385 1265 -0.0295796 0.0400732 -3.16208 1 0 1 1 0 0 +EDGE2 2385 2305 -0.00211017 -0.00923364 -3.17901 1 0 1 1 0 0 +EDGE2 2385 1565 -0.0502585 -0.00434719 0.0185195 1 0 1 1 0 0 +EDGE2 2385 1585 -0.0408593 0.0903246 0.000364885 1 0 1 1 0 0 +EDGE2 2385 1845 0.0829997 0.0162355 -0.0457216 1 0 1 1 0 0 +EDGE2 2385 1545 -0.0468549 0.0707942 0.0108461 1 0 1 1 0 0 +EDGE2 2385 1264 1.10857 -0.0338281 -3.13113 1 0 1 1 0 0 +EDGE2 2385 2304 1.02063 0.033175 -3.11825 1 0 1 1 0 0 +EDGE2 2385 1566 0.0179797 0.883314 1.58884 1 0 1 1 0 0 +EDGE2 2385 1846 -0.00801094 1.02941 1.52792 1 0 1 1 0 0 +EDGE2 2385 2306 0.0213484 1.11418 1.58797 1 0 1 1 0 0 +EDGE2 2385 1586 -0.0528012 0.990094 1.56265 1 0 1 1 0 0 +EDGE2 2385 1266 -0.00145097 1.06247 1.58875 1 0 1 1 0 0 +EDGE2 2386 1265 -0.939987 0.0113021 1.57264 1 0 1 1 0 0 +EDGE2 2386 2305 -1.04921 -0.0158491 1.55998 1 0 1 1 0 0 +EDGE2 2386 2385 -1.04054 0.0095242 -1.59156 1 0 1 1 0 0 +EDGE2 2386 1565 -0.983922 0.00709654 -1.58032 1 0 1 1 0 0 +EDGE2 2386 1585 -0.998635 -0.0974602 -1.57492 1 0 1 1 0 0 +EDGE2 2386 1845 -1.00789 0.0112642 -1.57582 1 0 1 1 0 0 +EDGE2 2386 1545 -0.946344 0.0133603 -1.54351 1 0 1 1 0 0 +EDGE2 2386 1567 0.988978 0.0718342 0.0286606 1 0 1 1 0 0 +EDGE2 2386 1587 0.954622 0.0153857 0.0193482 1 0 1 1 0 0 +EDGE2 2386 1566 0.0265775 -0.00247813 -0.0287274 1 0 1 1 0 0 +EDGE2 2386 1846 0.0214904 -0.0173431 0.0113494 1 0 1 1 0 0 +EDGE2 2386 2306 0.0196192 -0.00401697 -0.00101757 1 0 1 1 0 0 +EDGE2 2386 1586 0.097173 0.0312755 -0.0147113 1 0 1 1 0 0 +EDGE2 2386 2307 0.973699 -0.0514613 -0.0133889 1 0 1 1 0 0 +EDGE2 2386 1266 0.0092314 -0.114041 0.059955 1 0 1 1 0 0 +EDGE2 2386 1847 1.04724 -0.0542602 0.00671811 1 0 1 1 0 0 +EDGE2 2386 1267 0.985423 0.0141719 -0.00960471 1 0 1 1 0 0 +EDGE2 2387 1567 0.0503286 -0.0598975 0.0103995 1 0 1 1 0 0 +EDGE2 2387 1587 0.0223091 -0.0238499 0.0242878 1 0 1 1 0 0 +EDGE2 2387 1566 -0.935134 0.0296541 0.00856228 1 0 1 1 0 0 +EDGE2 2387 1846 -1.03352 0.00479235 0.013995 1 0 1 1 0 0 +EDGE2 2387 2306 -0.931083 0.011373 0.0325595 1 0 1 1 0 0 +EDGE2 2387 2386 -0.896089 0.0440399 -0.0131317 1 0 1 1 0 0 +EDGE2 2387 1586 -0.98344 0.020027 -0.00126945 1 0 1 1 0 0 +EDGE2 2387 2307 -0.0147662 0.0382069 0.010345 1 0 1 1 0 0 +EDGE2 2387 1266 -1.07061 -0.0643283 -0.0174235 1 0 1 1 0 0 +EDGE2 2387 1847 0.0711124 0.0122235 0.00146655 1 0 1 1 0 0 +EDGE2 2387 1588 0.964595 0.00202301 0.0161844 1 0 1 1 0 0 +EDGE2 2387 2308 0.966437 0.0222684 -0.0297273 1 0 1 1 0 0 +EDGE2 2387 1267 0.0346284 -0.0452354 0.0228449 1 0 1 1 0 0 +EDGE2 2387 1848 0.988981 0.131925 -0.0196189 1 0 1 1 0 0 +EDGE2 2387 1268 0.989488 0.0266251 -0.000216445 1 0 1 1 0 0 +EDGE2 2387 1568 0.946978 0.061692 -0.00505501 1 0 1 1 0 0 +EDGE2 2388 1567 -1.00849 -0.0670826 0.0241346 1 0 1 1 0 0 +EDGE2 2388 1587 -0.991589 -0.0787976 0.0122964 1 0 1 1 0 0 +EDGE2 2388 2307 -0.976868 -0.0161672 -0.0308049 1 0 1 1 0 0 +EDGE2 2388 2387 -0.945913 0.0120621 0.0109252 1 0 1 1 0 0 +EDGE2 2388 1847 -0.93611 -0.0149608 -0.0572838 1 0 1 1 0 0 +EDGE2 2388 1849 0.972261 0.0502562 0.0159563 1 0 1 1 0 0 +EDGE2 2388 1588 0.0024876 0.0564915 0.0443418 1 0 1 1 0 0 +EDGE2 2388 2308 0.0529878 0.0343369 -0.0205135 1 0 1 1 0 0 +EDGE2 2388 1267 -0.965445 0.00202201 0.0194159 1 0 1 1 0 0 +EDGE2 2388 1848 -0.0389562 -0.128274 -0.00500993 1 0 1 1 0 0 +EDGE2 2388 1268 0.0164649 -0.0107445 -0.012818 1 0 1 1 0 0 +EDGE2 2388 1568 0.0270652 -0.042805 0.0371069 1 0 1 1 0 0 +EDGE2 2388 2309 0.920375 0.0505386 -0.00870181 1 0 1 1 0 0 +EDGE2 2388 1569 0.98149 0.055689 -0.0452822 1 0 1 1 0 0 +EDGE2 2388 1589 0.927168 0.030609 -0.0118625 1 0 1 1 0 0 +EDGE2 2388 1269 0.94925 0.0320432 0.0112748 1 0 1 1 0 0 +EDGE2 2389 1849 -0.0506489 -0.050004 -0.0127372 1 0 1 1 0 0 +EDGE2 2389 1588 -0.914359 0.0598146 0.00798362 1 0 1 1 0 0 +EDGE2 2389 2308 -0.942879 -0.0346935 0.0213906 1 0 1 1 0 0 +EDGE2 2389 2388 -0.989412 0.0121372 0.0105798 1 0 1 1 0 0 +EDGE2 2389 1848 -0.976819 -0.0125698 -0.0236687 1 0 1 1 0 0 +EDGE2 2389 1268 -1.03315 0.0139573 0.0149237 1 0 1 1 0 0 +EDGE2 2389 1568 -0.960857 -0.0550564 0.00519577 1 0 1 1 0 0 +EDGE2 2389 2309 0.0469744 0.0205694 0.0174141 1 0 1 1 0 0 +EDGE2 2389 1569 0.00900939 -0.129923 -0.0162427 1 0 1 1 0 0 +EDGE2 2389 1589 -0.053486 0.124397 0.0248568 1 0 1 1 0 0 +EDGE2 2389 1269 -0.0107948 -0.0246164 0.0252185 1 0 1 1 0 0 +EDGE2 2389 1590 0.896693 0.0563754 -0.00358007 1 0 1 1 0 0 +EDGE2 2389 2310 0.963091 -0.0484651 -0.0147016 1 0 1 1 0 0 +EDGE2 2389 1850 0.99915 0.0582759 -0.00303117 1 0 1 1 0 0 +EDGE2 2389 1270 0.992268 -0.0616883 -0.00929214 1 0 1 1 0 0 +EDGE2 2389 1290 0.977093 0.106017 -3.12098 1 0 1 1 0 0 +EDGE2 2389 1570 1.0298 0.106856 -0.0124377 1 0 1 1 0 0 +EDGE2 2390 1851 0.0330902 1.06401 1.59755 1 0 1 1 0 0 +EDGE2 2390 2311 -0.0338699 1.03282 1.5847 1 0 1 1 0 0 +EDGE2 2390 1571 0.10819 1.06463 1.52832 1 0 1 1 0 0 +EDGE2 2390 1591 -0.0683434 1.0041 1.58545 1 0 1 1 0 0 +EDGE2 2390 1849 -0.968058 -0.0404104 -0.0230583 1 0 1 1 0 0 +EDGE2 2390 2389 -0.981225 0.0861706 0.00246122 1 0 1 1 0 0 +EDGE2 2390 2309 -0.992513 0.0758461 0.0235366 1 0 1 1 0 0 +EDGE2 2390 1569 -0.960247 -0.000917412 -0.0200846 1 0 1 1 0 0 +EDGE2 2390 1589 -0.964675 0.163215 0.0186527 1 0 1 1 0 0 +EDGE2 2390 1269 -1.04419 0.0260801 0.0224601 1 0 1 1 0 0 +EDGE2 2390 1291 -0.104972 -1.00429 -1.56222 1 0 1 1 0 0 +EDGE2 2390 1590 -0.00567791 0.000652253 0.0222611 1 0 1 1 0 0 +EDGE2 2390 2310 -0.0739637 -0.0406385 0.0161991 1 0 1 1 0 0 +EDGE2 2390 1850 0.0356376 -0.0519353 0.0286556 1 0 1 1 0 0 +EDGE2 2390 1270 -0.00505755 0.0529568 -0.00259651 1 0 1 1 0 0 +EDGE2 2390 1290 -0.0280966 -0.0308044 -3.13298 1 0 1 1 0 0 +EDGE2 2390 1570 -0.0260954 -0.0855044 -0.017352 1 0 1 1 0 0 +EDGE2 2390 1271 -0.00112601 -1.02441 -1.57706 1 0 1 1 0 0 +EDGE2 2390 1289 1.07766 0.0709595 -3.14639 1 0 1 1 0 0 +EDGE2 2391 1851 0.101947 -0.00881176 0.0255062 1 0 1 1 0 0 +EDGE2 2391 1852 0.959143 -0.0759465 -0.0114051 1 0 1 1 0 0 +EDGE2 2391 2312 1.00122 0.000283611 -0.0294758 1 0 1 1 0 0 +EDGE2 2391 1572 0.988049 0.0233194 -0.0118062 1 0 1 1 0 0 +EDGE2 2391 1592 0.960333 0.00721548 0.00490303 1 0 1 1 0 0 +EDGE2 2391 2311 0.0738081 -0.0314794 0.00695077 1 0 1 1 0 0 +EDGE2 2391 1571 -0.0716957 -0.0353004 0.0319077 1 0 1 1 0 0 +EDGE2 2391 1591 -0.00652866 0.0354511 -0.00159735 1 0 1 1 0 0 +EDGE2 2391 1590 -1.03296 -0.0248882 -1.57615 1 0 1 1 0 0 +EDGE2 2391 2310 -0.974285 -0.0175457 -1.61339 1 0 1 1 0 0 +EDGE2 2391 2390 -1.0231 -0.0198375 -1.6058 1 0 1 1 0 0 +EDGE2 2391 1850 -0.987557 -0.0149654 -1.53027 1 0 1 1 0 0 +EDGE2 2391 1270 -0.986074 -0.0247749 -1.55169 1 0 1 1 0 0 +EDGE2 2391 1290 -0.946385 -0.0194589 1.53577 1 0 1 1 0 0 +EDGE2 2391 1570 -1.03195 -0.0708472 -1.54875 1 0 1 1 0 0 +EDGE2 2392 1851 -0.917796 0.00281805 -0.0260238 1 0 1 1 0 0 +EDGE2 2392 1853 1.0004 0.0501078 -0.00111445 1 0 1 1 0 0 +EDGE2 2392 2313 0.975448 -0.102212 -0.0272703 1 0 1 1 0 0 +EDGE2 2392 1852 0.0997747 -0.0269675 -0.0195161 1 0 1 1 0 0 +EDGE2 2392 1573 0.964179 -0.00595387 -0.00397685 1 0 1 1 0 0 +EDGE2 2392 1593 0.982892 0.0193419 0.0440259 1 0 1 1 0 0 +EDGE2 2392 2312 -0.037703 -0.0277178 0.0395395 1 0 1 1 0 0 +EDGE2 2392 2391 -1.05517 -0.0770409 -0.0206754 1 0 1 1 0 0 +EDGE2 2392 1572 -0.00735567 -0.040408 -0.0121176 1 0 1 1 0 0 +EDGE2 2392 1592 0.0011617 0.0438351 0.039649 1 0 1 1 0 0 +EDGE2 2392 2311 -1.03491 -0.0742613 0.0241093 1 0 1 1 0 0 +EDGE2 2392 1571 -0.990652 -0.031952 0.00726092 1 0 1 1 0 0 +EDGE2 2392 1591 -0.963234 0.0542514 0.00819224 1 0 1 1 0 0 +EDGE2 2393 1853 0.0387524 0.0478426 0.0121498 1 0 1 1 0 0 +EDGE2 2393 1854 0.991962 -0.0309579 0.0376455 1 0 1 1 0 0 +EDGE2 2393 2314 1.04406 -0.0390563 -0.0120822 1 0 1 1 0 0 +EDGE2 2393 1574 1.01446 -0.0680324 0.00213535 1 0 1 1 0 0 +EDGE2 2393 1594 1.02172 0.0707466 -0.0314013 1 0 1 1 0 0 +EDGE2 2393 2313 -0.0208049 0.00645414 0.00690839 1 0 1 1 0 0 +EDGE2 2393 1852 -1.03543 0.0151927 -0.0124897 1 0 1 1 0 0 +EDGE2 2393 2392 -1.01173 0.0572912 -0.013371 1 0 1 1 0 0 +EDGE2 2393 1573 0.0876483 -0.00631769 -0.0129774 1 0 1 1 0 0 +EDGE2 2393 1593 0.0330577 0.0224985 0.00251144 1 0 1 1 0 0 +EDGE2 2393 2312 -0.977824 -0.016767 0.0185135 1 0 1 1 0 0 +EDGE2 2393 1572 -0.947151 -0.00462807 0.00225287 1 0 1 1 0 0 +EDGE2 2393 1592 -1.01586 -0.0318648 -0.0102607 1 0 1 1 0 0 +EDGE2 2394 1535 1.05928 0.0675457 -3.1234 1 0 1 1 0 0 +EDGE2 2394 1855 0.954358 0.0242292 0.00657731 1 0 1 1 0 0 +EDGE2 2394 2335 1.07885 -0.0279493 -3.11664 1 0 1 1 0 0 +EDGE2 2394 2355 0.90477 0.028656 -3.14848 1 0 1 1 0 0 +EDGE2 2394 2375 1.00734 0.0138355 -3.14225 1 0 1 1 0 0 +EDGE2 2394 2315 0.947423 0.0149227 -0.0128318 1 0 1 1 0 0 +EDGE2 2394 1595 0.908538 0.0844196 -0.0255104 1 0 1 1 0 0 +EDGE2 2394 1655 0.971138 -0.0297192 -3.16556 1 0 1 1 0 0 +EDGE2 2394 1575 0.950304 -0.0113146 -0.0187138 1 0 1 1 0 0 +EDGE2 2394 1853 -1.00828 -0.00493741 -0.00135654 1 0 1 1 0 0 +EDGE2 2394 1854 0.00626232 0.0197688 -0.0136064 1 0 1 1 0 0 +EDGE2 2394 1375 0.988898 0.0141663 -3.13306 1 0 1 1 0 0 +EDGE2 2394 1515 0.991973 -0.0635145 -3.13554 1 0 1 1 0 0 +EDGE2 2394 2314 0.0753907 -0.0377877 0.00340207 1 0 1 1 0 0 +EDGE2 2394 2393 -1.02188 0.0399472 -0.00799346 1 0 1 1 0 0 +EDGE2 2394 1574 0.0174209 -0.00211556 0.006066 1 0 1 1 0 0 +EDGE2 2394 1594 0.0475293 -0.0397498 -0.00959103 1 0 1 1 0 0 +EDGE2 2394 2313 -0.997054 -0.0302071 0.00796807 1 0 1 1 0 0 +EDGE2 2394 1573 -0.974171 0.00937922 -0.0145582 1 0 1 1 0 0 +EDGE2 2394 1593 -1.04282 -0.008131 -0.0185751 1 0 1 1 0 0 +EDGE2 2395 1656 0.0302946 1.07901 1.60372 1 0 1 1 0 0 +EDGE2 2395 2376 -0.107767 0.97096 1.58531 1 0 1 1 0 0 +EDGE2 2395 1856 -0.026681 1.04192 1.54147 1 0 1 1 0 0 +EDGE2 2395 1536 -0.0630215 0.974499 1.57672 1 0 1 1 0 0 +EDGE2 2395 1576 0.00356043 0.920218 1.56753 1 0 1 1 0 0 +EDGE2 2395 1376 0.0374092 1.09634 1.59375 1 0 1 1 0 0 +EDGE2 2395 1535 -0.0435825 0.0102213 -3.13591 1 0 1 1 0 0 +EDGE2 2395 2374 0.995935 0.035162 -3.18408 1 0 1 1 0 0 +EDGE2 2395 1514 1.08326 0.00938021 -3.13925 1 0 1 1 0 0 +EDGE2 2395 1654 0.879593 0.0235164 -3.12762 1 0 1 1 0 0 +EDGE2 2395 2334 0.985591 -0.025086 -3.09678 1 0 1 1 0 0 +EDGE2 2395 2354 0.996452 -0.0260832 -3.1822 1 0 1 1 0 0 +EDGE2 2395 1534 0.99399 0.0493158 -3.16196 1 0 1 1 0 0 +EDGE2 2395 1374 1.027 0.0284388 -3.11439 1 0 1 1 0 0 +EDGE2 2395 1855 0.0293679 -0.0487539 0.0164309 1 0 1 1 0 0 +EDGE2 2395 2335 -0.0172061 0.0911249 -3.11969 1 0 1 1 0 0 +EDGE2 2395 2355 0.0343489 -0.014331 -3.1284 1 0 1 1 0 0 +EDGE2 2395 2375 0.0231639 0.0761543 -3.10548 1 0 1 1 0 0 +EDGE2 2395 2315 -0.00424742 -0.0195304 0.00679231 1 0 1 1 0 0 +EDGE2 2395 1595 -0.0303925 0.0172193 0.00976834 1 0 1 1 0 0 +EDGE2 2395 1655 -0.0299204 -0.0793242 -3.18143 1 0 1 1 0 0 +EDGE2 2395 1575 0.0750926 -0.0015455 0.0170776 1 0 1 1 0 0 +EDGE2 2395 1854 -1.05488 -0.0314191 0.0136046 1 0 1 1 0 0 +EDGE2 2395 2394 -1.07525 -0.0678872 -0.0173945 1 0 1 1 0 0 +EDGE2 2395 1375 0.00322459 0.00499422 -3.1287 1 0 1 1 0 0 +EDGE2 2395 1515 -0.119119 -0.00832315 -3.14143 1 0 1 1 0 0 +EDGE2 2395 2314 -0.918214 -0.0776362 0.00134394 1 0 1 1 0 0 +EDGE2 2395 1574 -1.01629 -0.096146 -0.00222365 1 0 1 1 0 0 +EDGE2 2395 1594 -1.04468 -0.0173774 0.00919533 1 0 1 1 0 0 +EDGE2 2395 2336 0.159471 -0.965701 -1.60971 1 0 1 1 0 0 +EDGE2 2395 2356 0.0423915 -0.985103 -1.58234 1 0 1 1 0 0 +EDGE2 2395 1516 -0.00391209 -0.992216 -1.596 1 0 1 1 0 0 +EDGE2 2395 1596 -0.0281045 -0.976649 -1.55861 1 0 1 1 0 0 +EDGE2 2395 2316 -0.0538384 -1.00357 -1.56528 1 0 1 1 0 0 +EDGE2 2396 1537 1.02907 -0.0246481 0.0170104 1 0 1 1 0 0 +EDGE2 2396 1577 1.06624 -0.00737617 -0.000765843 1 0 1 1 0 0 +EDGE2 2396 1857 1.00857 0.0181599 0.0429103 1 0 1 1 0 0 +EDGE2 2396 2377 1.04399 0.0263306 -0.0087439 1 0 1 1 0 0 +EDGE2 2396 1657 0.933 0.0607545 0.0302739 1 0 1 1 0 0 +EDGE2 2396 1656 0.0330492 -0.0664552 -0.016285 1 0 1 1 0 0 +EDGE2 2396 2376 0.0203238 -0.0363412 -0.0110114 1 0 1 1 0 0 +EDGE2 2396 1377 1.10858 -0.0220117 -0.0088089 1 0 1 1 0 0 +EDGE2 2396 1856 0.044976 -0.058915 -0.0343044 1 0 1 1 0 0 +EDGE2 2396 1536 0.0491307 -0.0488838 -0.016919 1 0 1 1 0 0 +EDGE2 2396 1576 0.107733 0.059193 -0.00197859 1 0 1 1 0 0 +EDGE2 2396 1376 -0.0465586 -0.0373708 -0.0128417 1 0 1 1 0 0 +EDGE2 2396 1535 -0.988303 0.0287562 1.57065 1 0 1 1 0 0 +EDGE2 2396 2395 -0.959109 -0.0159201 -1.57866 1 0 1 1 0 0 +EDGE2 2396 1855 -0.968144 -0.0554403 -1.60426 1 0 1 1 0 0 +EDGE2 2396 2335 -0.965975 -0.0145937 1.58157 1 0 1 1 0 0 +EDGE2 2396 2355 -0.931874 -0.0865054 1.56589 1 0 1 1 0 0 +EDGE2 2396 2375 -1.00674 -0.0198078 1.55506 1 0 1 1 0 0 +EDGE2 2396 2315 -1.08499 -0.0676418 -1.58388 1 0 1 1 0 0 +EDGE2 2396 1595 -1.11708 -0.0107192 -1.56883 1 0 1 1 0 0 +EDGE2 2396 1655 -1.06997 -0.00175638 1.57209 1 0 1 1 0 0 +EDGE2 2396 1575 -1.0728 -0.00901616 -1.57776 1 0 1 1 0 0 +EDGE2 2396 1375 -0.87618 -0.0155131 1.5568 1 0 1 1 0 0 +EDGE2 2396 1515 -1.0966 -0.0356505 1.57369 1 0 1 1 0 0 +EDGE2 2397 1378 1.08535 -0.0798522 -0.00935212 1 0 1 1 0 0 +EDGE2 2397 1858 0.990433 -0.0299629 0.00426848 1 0 1 1 0 0 +EDGE2 2397 2378 1.06059 0.00274902 0.00422912 1 0 1 1 0 0 +EDGE2 2397 1578 1.01751 0.0511089 0.00268571 1 0 1 1 0 0 +EDGE2 2397 1658 0.931421 -0.0311834 0.000958581 1 0 1 1 0 0 +EDGE2 2397 1538 1.0343 0.0626698 -0.00963566 1 0 1 1 0 0 +EDGE2 2397 1537 0.0248646 0.00176925 0.00840089 1 0 1 1 0 0 +EDGE2 2397 1577 -0.0589373 -0.0341619 -0.0231407 1 0 1 1 0 0 +EDGE2 2397 1857 0.0998572 0.0268699 0.0155345 1 0 1 1 0 0 +EDGE2 2397 2377 0.0554122 0.0569485 0.00860491 1 0 1 1 0 0 +EDGE2 2397 1657 -0.00982145 -0.0575368 -0.0271135 1 0 1 1 0 0 +EDGE2 2397 1656 -1.03129 -0.0305101 0.00695739 1 0 1 1 0 0 +EDGE2 2397 2376 -0.96232 -0.0248927 -0.0287409 1 0 1 1 0 0 +EDGE2 2397 2396 -1.02711 0.0568764 -0.00406097 1 0 1 1 0 0 +EDGE2 2397 1377 0.0554539 -0.00625204 -0.0406036 1 0 1 1 0 0 +EDGE2 2397 1856 -1.0176 -0.0278254 -0.0132688 1 0 1 1 0 0 +EDGE2 2397 1536 -0.961484 0.0197782 -0.0200803 1 0 1 1 0 0 +EDGE2 2397 1576 -1.08144 -0.0107364 -0.000107199 1 0 1 1 0 0 +EDGE2 2397 1376 -1.07137 -0.0164479 0.0278943 1 0 1 1 0 0 +EDGE2 2398 1378 -0.059428 -0.096083 -0.0490602 1 0 1 1 0 0 +EDGE2 2398 1858 -0.0419216 0.0310763 -0.0124924 1 0 1 1 0 0 +EDGE2 2398 1579 1.06304 -0.0194133 0.0116068 1 0 1 1 0 0 +EDGE2 2398 1859 1.02936 -0.0143329 0.0118656 1 0 1 1 0 0 +EDGE2 2398 2379 1.00574 0.000411998 0.00727229 1 0 1 1 0 0 +EDGE2 2398 1659 1.00373 -0.00376695 0.0106385 1 0 1 1 0 0 +EDGE2 2398 1379 0.914024 -0.00441478 0.0196719 1 0 1 1 0 0 +EDGE2 2398 1539 1.04111 -0.0312874 -0.00364943 1 0 1 1 0 0 +EDGE2 2398 2378 0.037837 0.0300574 0.0151709 1 0 1 1 0 0 +EDGE2 2398 1578 0.0361748 0.0789649 -0.0337195 1 0 1 1 0 0 +EDGE2 2398 1658 -0.0246221 0.00350093 0.00228956 1 0 1 1 0 0 +EDGE2 2398 1538 0.0491247 0.0427576 0.0263309 1 0 1 1 0 0 +EDGE2 2398 1537 -0.973626 -0.0131474 0.00457374 1 0 1 1 0 0 +EDGE2 2398 1577 -0.951963 -0.0339853 -0.0307505 1 0 1 1 0 0 +EDGE2 2398 1857 -0.913806 -0.0795033 0.00972204 1 0 1 1 0 0 +EDGE2 2398 2377 -0.950945 -0.0284507 -0.00670477 1 0 1 1 0 0 +EDGE2 2398 2397 -0.931987 -0.119718 0.0204991 1 0 1 1 0 0 +EDGE2 2398 1657 -0.973567 0.0179061 -0.0141911 1 0 1 1 0 0 +EDGE2 2398 1377 -1.04512 0.00350641 0.0110294 1 0 1 1 0 0 +EDGE2 2399 1540 1.00209 0.0748733 -0.0226208 1 0 1 1 0 0 +EDGE2 2399 1860 1.00923 -0.066758 0.0265693 1 0 1 1 0 0 +EDGE2 2399 2380 0.939983 0.00217375 -0.00663733 1 0 1 1 0 0 +EDGE2 2399 1580 1.02982 0.0423269 0.00250432 1 0 1 1 0 0 +EDGE2 2399 1660 0.989324 0.00902591 -0.00828789 1 0 1 1 0 0 +EDGE2 2399 1840 0.972618 -0.0604655 -3.15405 1 0 1 1 0 0 +EDGE2 2399 1560 1.08999 0.0127697 -3.15235 1 0 1 1 0 0 +EDGE2 2399 1380 0.982092 -0.0484391 -0.00576979 1 0 1 1 0 0 +EDGE2 2399 1378 -0.9487 -0.0237281 -0.00403917 1 0 1 1 0 0 +EDGE2 2399 1858 -1.04532 -0.0685744 -0.0272305 1 0 1 1 0 0 +EDGE2 2399 1579 -0.0387036 -0.0179382 -0.0285807 1 0 1 1 0 0 +EDGE2 2399 1859 0.072352 -0.0336579 -0.0095589 1 0 1 1 0 0 +EDGE2 2399 2379 0.0715832 0.0162653 -0.0280648 1 0 1 1 0 0 +EDGE2 2399 1659 -0.00763328 0.0746282 0.0284705 1 0 1 1 0 0 +EDGE2 2399 2398 -1.03974 -0.0455657 -0.0152171 1 0 1 1 0 0 +EDGE2 2399 1379 -0.0300987 -0.0160483 0.0186254 1 0 1 1 0 0 +EDGE2 2399 1539 -0.0705405 0.000301599 0.00055094 1 0 1 1 0 0 +EDGE2 2399 2378 -0.99451 -0.0554148 0.0101593 1 0 1 1 0 0 +EDGE2 2399 1578 -0.950833 0.0512465 0.0255479 1 0 1 1 0 0 +EDGE2 2399 1658 -0.997216 -0.00533487 -0.00583225 1 0 1 1 0 0 +EDGE2 2399 1538 -0.931449 -0.0089348 0.0202201 1 0 1 1 0 0 +EDGE2 2400 1839 0.978084 -0.0164126 -3.15478 1 0 1 1 0 0 +EDGE2 2400 1559 0.995109 -0.0697785 -3.1649 1 0 1 1 0 0 +EDGE2 2400 1540 0.0358508 0.0127269 -0.000729533 1 0 1 1 0 0 +EDGE2 2400 1861 0.00988716 -1.09181 -1.53297 1 0 1 1 0 0 +EDGE2 2400 1860 0.0376826 -0.0641522 -0.0219424 1 0 1 1 0 0 +EDGE2 2400 1381 -0.0240404 -1.06701 -1.59614 1 0 1 1 0 0 +EDGE2 2400 1661 -0.0049967 -0.924546 -1.57098 1 0 1 1 0 0 +EDGE2 2400 2380 0.0204855 -0.0070662 -0.0157544 1 0 1 1 0 0 +EDGE2 2400 1580 0.014013 -0.0126222 -0.0126041 1 0 1 1 0 0 +EDGE2 2400 1660 0.0708887 0.00256261 0.0357357 1 0 1 1 0 0 +EDGE2 2400 1840 -0.0655158 0.025612 -3.19083 1 0 1 1 0 0 +EDGE2 2400 1560 0.0325171 -0.00928004 -3.16718 1 0 1 1 0 0 +EDGE2 2400 1581 0.0682929 0.923457 1.59208 1 0 1 1 0 0 +EDGE2 2400 2381 0.0360985 0.976235 1.5598 1 0 1 1 0 0 +EDGE2 2400 1380 0.0187348 0.00368589 0.00767399 1 0 1 1 0 0 +EDGE2 2400 1841 0.018303 1.01011 1.5837 1 0 1 1 0 0 +EDGE2 2400 1541 0.0761353 1.00644 1.578 1 0 1 1 0 0 +EDGE2 2400 1561 0.0879009 0.923811 1.56144 1 0 1 1 0 0 +EDGE2 2400 1579 -1.00122 -0.00863699 -0.00706349 1 0 1 1 0 0 +EDGE2 2400 1859 -1.07933 -0.0447881 0.0340223 1 0 1 1 0 0 +EDGE2 2400 2379 -1.09105 -0.0288467 0.0129455 1 0 1 1 0 0 +EDGE2 2400 2399 -0.994374 0.0108394 -0.00373848 1 0 1 1 0 0 +EDGE2 2400 1659 -0.996269 -0.0153779 -0.0416441 1 0 1 1 0 0 +EDGE2 2400 1379 -0.895278 0.0366617 0.00962019 1 0 1 1 0 0 +EDGE2 2400 1539 -1.04775 0.000953042 0.0314333 1 0 1 1 0 0 +EDGE2 2401 1540 -1.02708 0.00595839 -1.58297 1 0 1 1 0 0 +EDGE2 2401 1860 -0.974884 -0.0238777 -1.54266 1 0 1 1 0 0 +EDGE2 2401 2400 -1.01725 -0.067642 -1.58606 1 0 1 1 0 0 +EDGE2 2401 2380 -1.08167 -0.0441985 -1.58645 1 0 1 1 0 0 +EDGE2 2401 1580 -1.02169 -0.046678 -1.56448 1 0 1 1 0 0 +EDGE2 2401 1660 -0.967775 -0.0121329 -1.58034 1 0 1 1 0 0 +EDGE2 2401 1840 -0.921154 0.00718246 1.58416 1 0 1 1 0 0 +EDGE2 2401 1560 -1.0083 -0.105794 1.56081 1 0 1 1 0 0 +EDGE2 2401 1842 0.934609 -0.0507412 0.00324922 1 0 1 1 0 0 +EDGE2 2401 1581 0.0571953 -0.0263342 -0.0336445 1 0 1 1 0 0 +EDGE2 2401 2381 -0.0344821 -0.024629 -0.0234929 1 0 1 1 0 0 +EDGE2 2401 1380 -1.06737 0.0470824 -1.58446 1 0 1 1 0 0 +EDGE2 2401 1841 0.00984764 0.153752 0.00578085 1 0 1 1 0 0 +EDGE2 2401 1541 -0.0108372 -0.023341 -0.0164609 1 0 1 1 0 0 +EDGE2 2401 1561 -0.0250805 -0.0641489 -0.0282362 1 0 1 1 0 0 +EDGE2 2401 2382 0.957928 0.000355682 -0.0222827 1 0 1 1 0 0 +EDGE2 2401 1542 1.01485 0.0443052 -0.0309321 1 0 1 1 0 0 +EDGE2 2401 1562 0.9922 -0.00160143 -0.0049046 1 0 1 1 0 0 +EDGE2 2401 1582 0.957033 0.0432814 0.0121261 1 0 1 1 0 0 +EDGE2 2402 1543 0.946099 -0.0045424 -0.0226851 1 0 1 1 0 0 +EDGE2 2402 1842 0.0257252 0.0394292 0.0218447 1 0 1 1 0 0 +EDGE2 2402 1581 -1.01033 0.00168522 -0.00186155 1 0 1 1 0 0 +EDGE2 2402 2381 -1.0618 -0.0379455 -0.00820582 1 0 1 1 0 0 +EDGE2 2402 2401 -0.987191 0.066663 -0.00980797 1 0 1 1 0 0 +EDGE2 2402 1841 -0.944521 -0.0140391 -0.0171739 1 0 1 1 0 0 +EDGE2 2402 1541 -0.936632 0.0302033 -0.0282614 1 0 1 1 0 0 +EDGE2 2402 1561 -0.973451 0.0135341 -0.0150963 1 0 1 1 0 0 +EDGE2 2402 2382 0.0415448 0.00526467 -0.015265 1 0 1 1 0 0 +EDGE2 2402 2383 1.09212 -0.0225186 0.00852503 1 0 1 1 0 0 +EDGE2 2402 1542 -0.0577683 -0.0403969 0.0128925 1 0 1 1 0 0 +EDGE2 2402 1562 0.00455347 -0.0582823 -0.00503599 1 0 1 1 0 0 +EDGE2 2402 1582 0.0852932 -0.0512606 -0.000351796 1 0 1 1 0 0 +EDGE2 2402 1583 1.04925 0.0080381 -0.0103021 1 0 1 1 0 0 +EDGE2 2402 1843 0.985744 0.0669997 0.0102843 1 0 1 1 0 0 +EDGE2 2402 1563 0.99249 -0.0483029 0.0234191 1 0 1 1 0 0 +EDGE2 2403 1543 -0.035427 0.0521133 -0.0107253 1 0 1 1 0 0 +EDGE2 2403 1842 -0.973924 0.0110258 0.0164841 1 0 1 1 0 0 +EDGE2 2403 2402 -0.957959 0.0221753 0.0163602 1 0 1 1 0 0 +EDGE2 2403 2382 -0.991216 -0.0297647 0.0344786 1 0 1 1 0 0 +EDGE2 2403 2383 0.00901847 -0.00517911 0.0109611 1 0 1 1 0 0 +EDGE2 2403 1542 -0.943917 0.0888054 -0.0150842 1 0 1 1 0 0 +EDGE2 2403 1562 -1.05219 -0.0244696 -0.00524748 1 0 1 1 0 0 +EDGE2 2403 1582 -0.955141 -0.0365527 0.00913247 1 0 1 1 0 0 +EDGE2 2403 1583 -0.032204 0.0339898 0.0150085 1 0 1 1 0 0 +EDGE2 2403 1843 0.0126506 0.0337612 0.0282647 1 0 1 1 0 0 +EDGE2 2403 1563 0.00932781 0.041139 -0.020993 1 0 1 1 0 0 +EDGE2 2403 1564 0.975031 -0.0341358 -0.0133222 1 0 1 1 0 0 +EDGE2 2403 1844 0.965344 0.0431945 -0.00959581 1 0 1 1 0 0 +EDGE2 2403 2384 1.06158 0.0871833 0.0205159 1 0 1 1 0 0 +EDGE2 2403 1584 1.01879 -0.0094325 0.066824 1 0 1 1 0 0 +EDGE2 2403 1544 1.03621 -0.0424536 -0.0131331 1 0 1 1 0 0 +EDGE2 2404 1543 -1.06258 -0.0798233 0.00699461 1 0 1 1 0 0 +EDGE2 2404 2383 -1.05661 0.00527616 -0.0167989 1 0 1 1 0 0 +EDGE2 2404 2403 -1.03385 -0.0422396 0.000507157 1 0 1 1 0 0 +EDGE2 2404 1583 -1.09641 0.0363274 0.0413926 1 0 1 1 0 0 +EDGE2 2404 1843 -0.877555 -0.0675184 0.00844957 1 0 1 1 0 0 +EDGE2 2404 1563 -0.931653 0.0426184 0.0222252 1 0 1 1 0 0 +EDGE2 2404 1564 -0.0982339 -0.0316277 -0.0422869 1 0 1 1 0 0 +EDGE2 2404 1844 -0.0273206 -0.0325594 -0.00485554 1 0 1 1 0 0 +EDGE2 2404 2384 -0.0210139 0.0114116 0.0178552 1 0 1 1 0 0 +EDGE2 2404 1584 0.0281713 0.0905142 -0.0143618 1 0 1 1 0 0 +EDGE2 2404 1544 0.0419831 -0.0118398 0.028638 1 0 1 1 0 0 +EDGE2 2404 1265 1.10448 -0.0288383 -3.1403 1 0 1 1 0 0 +EDGE2 2404 2305 1.06358 -0.0504425 -3.14803 1 0 1 1 0 0 +EDGE2 2404 2385 1.04929 0.0070215 0.0233552 1 0 1 1 0 0 +EDGE2 2404 1565 0.947926 0.0371822 -0.015267 1 0 1 1 0 0 +EDGE2 2404 1585 1.05022 0.0187651 0.0208739 1 0 1 1 0 0 +EDGE2 2404 1845 1.06464 -0.0926506 0.000547599 1 0 1 1 0 0 +EDGE2 2404 1545 0.950787 -0.112828 -0.0282827 1 0 1 1 0 0 +EDGE2 2405 1564 -1.00092 -0.0285278 -0.0185568 1 0 1 1 0 0 +EDGE2 2405 1844 -1.00267 0.0610798 -0.00957143 1 0 1 1 0 0 +EDGE2 2405 2384 -1.01781 0.0188919 -0.0109115 1 0 1 1 0 0 +EDGE2 2405 2404 -1.03284 0.027461 -0.0100225 1 0 1 1 0 0 +EDGE2 2405 1584 -1.04496 -0.0245506 0.00738629 1 0 1 1 0 0 +EDGE2 2405 1544 -0.976529 -0.0215697 0.0060617 1 0 1 1 0 0 +EDGE2 2405 1546 0.00250149 -1.10088 -1.58972 1 0 1 1 0 0 +EDGE2 2405 1265 0.017079 -0.0365995 -3.1617 1 0 1 1 0 0 +EDGE2 2405 2305 -0.0293489 -0.0433864 -3.12464 1 0 1 1 0 0 +EDGE2 2405 2385 -0.0465823 -0.0271182 0.0102915 1 0 1 1 0 0 +EDGE2 2405 1565 0.0875429 -0.0345041 0.00798047 1 0 1 1 0 0 +EDGE2 2405 1585 -0.0815344 -0.0242586 -0.0101171 1 0 1 1 0 0 +EDGE2 2405 1845 -0.0833671 0.051768 -0.0181398 1 0 1 1 0 0 +EDGE2 2405 1545 -0.0861139 -0.041454 0.00713794 1 0 1 1 0 0 +EDGE2 2405 1264 1.0506 -0.0412008 -3.1356 1 0 1 1 0 0 +EDGE2 2405 2304 0.927236 0.0451562 -3.14817 1 0 1 1 0 0 +EDGE2 2405 1566 0.0412204 1.01498 1.56551 1 0 1 1 0 0 +EDGE2 2405 1846 -0.0110169 0.972912 1.57278 1 0 1 1 0 0 +EDGE2 2405 2306 0.0322945 0.936012 1.5496 1 0 1 1 0 0 +EDGE2 2405 2386 0.0266415 0.911928 1.56838 1 0 1 1 0 0 +EDGE2 2405 1586 -0.00662257 1.04647 1.59025 1 0 1 1 0 0 +EDGE2 2405 1266 0.0276592 1.08132 1.56958 1 0 1 1 0 0 +EDGE2 2406 1547 1.01475 0.022729 -0.0327664 1 0 1 1 0 0 +EDGE2 2406 1546 -0.0476568 0.0228552 0.0144306 1 0 1 1 0 0 +EDGE2 2406 1265 -1.04491 -0.0584429 -1.53975 1 0 1 1 0 0 +EDGE2 2406 2305 -1.01787 0.00377335 -1.57236 1 0 1 1 0 0 +EDGE2 2406 2405 -0.992399 -0.0638354 1.61354 1 0 1 1 0 0 +EDGE2 2406 2385 -1.07981 -0.165309 1.55594 1 0 1 1 0 0 +EDGE2 2406 1565 -0.948926 -0.0476893 1.56088 1 0 1 1 0 0 +EDGE2 2406 1585 -0.99991 -0.0466557 1.58167 1 0 1 1 0 0 +EDGE2 2406 1845 -1.12642 0.00854357 1.53393 1 0 1 1 0 0 +EDGE2 2406 1545 -0.993026 0.0403561 1.55997 1 0 1 1 0 0 +EDGE2 2407 1548 0.896438 -0.0385336 -0.0243288 1 0 1 1 0 0 +EDGE2 2407 1547 0.0110438 0.0411422 0.000808119 1 0 1 1 0 0 +EDGE2 2407 2406 -0.933228 -0.0795813 0.0628233 1 0 1 1 0 0 +EDGE2 2407 1546 -1.00995 0.00405866 -0.00898252 1 0 1 1 0 0 +EDGE2 2408 1549 1.01606 0.0421242 0.0131199 1 0 1 1 0 0 +EDGE2 2408 1548 0.0580843 -0.0290646 -0.00163342 1 0 1 1 0 0 +EDGE2 2408 1547 -1.01581 0.0068028 -0.0065745 1 0 1 1 0 0 +EDGE2 2408 2407 -0.982059 -0.010456 -0.0284735 1 0 1 1 0 0 +EDGE2 2409 1550 0.999596 -0.000343102 0.0125361 1 0 1 1 0 0 +EDGE2 2409 1830 0.939953 -0.0406548 -3.12134 1 0 1 1 0 0 +EDGE2 2409 1549 -0.0388712 0.0012861 -0.0011524 1 0 1 1 0 0 +EDGE2 2409 1548 -0.909126 0.0133965 -0.0308238 1 0 1 1 0 0 +EDGE2 2409 2408 -1.02619 -0.0357629 0.0211143 1 0 1 1 0 0 +EDGE2 2410 1829 1.02269 0.00325084 -3.09508 1 0 1 1 0 0 +EDGE2 2410 1831 0.0353951 -0.959921 -1.56447 1 0 1 1 0 0 +EDGE2 2410 1551 0.0221476 -0.980918 -1.59797 1 0 1 1 0 0 +EDGE2 2410 1550 0.00158908 0.0664778 0.00267586 1 0 1 1 0 0 +EDGE2 2410 1830 -0.0100475 0.0536997 -3.14475 1 0 1 1 0 0 +EDGE2 2410 1549 -1.03502 -0.0553792 -0.00668095 1 0 1 1 0 0 +EDGE2 2410 2409 -0.950672 -0.0348841 -0.0406503 1 0 1 1 0 0 +EDGE2 2411 1550 -0.924354 0.0672994 -1.59666 1 0 1 1 0 0 +EDGE2 2411 1830 -0.923152 -0.0306007 1.55056 1 0 1 1 0 0 +EDGE2 2411 2410 -1.03912 0.0643034 -1.6057 1 0 1 1 0 0 +EDGE2 2412 2411 -1.07287 -0.00224615 0.00963858 1 0 1 1 0 0 +EDGE2 2413 2412 -0.951812 -0.0121879 -0.0116914 1 0 1 1 0 0 +EDGE2 2414 2413 -1.02159 -0.0389736 -0.0148101 1 0 1 1 0 0 +EDGE2 2414 1235 0.984634 0.0611816 -3.16125 1 0 1 1 0 0 +EDGE2 2414 2295 1.08767 0.0312509 -3.11 1 0 1 1 0 0 +EDGE2 2414 1255 1.038 -0.00246415 -3.1649 1 0 1 1 0 0 +EDGE2 2415 1236 0.0228305 -1.01013 -1.59697 1 0 1 1 0 0 +EDGE2 2415 2414 -1.08304 -0.0185295 0.000454202 1 0 1 1 0 0 +EDGE2 2415 1235 -0.0620878 -0.0810883 -3.17053 1 0 1 1 0 0 +EDGE2 2415 2295 -0.0341192 0.0683666 -3.13114 1 0 1 1 0 0 +EDGE2 2415 1255 0.00185228 0.00197267 -3.12296 1 0 1 1 0 0 +EDGE2 2415 1254 0.945733 -0.076843 -3.16433 1 0 1 1 0 0 +EDGE2 2415 2294 0.945716 -0.0301248 -3.11438 1 0 1 1 0 0 +EDGE2 2415 1234 0.966482 -0.0173509 -3.14487 1 0 1 1 0 0 +EDGE2 2415 1256 -0.0521495 0.952365 1.54911 1 0 1 1 0 0 +EDGE2 2415 2296 -0.0696439 0.872548 1.54758 1 0 1 1 0 0 +EDGE2 2416 1235 -1.0292 -0.0062313 1.60136 1 0 1 1 0 0 +EDGE2 2416 2295 -1.05962 -0.0431031 1.5727 1 0 1 1 0 0 +EDGE2 2416 2415 -1.05711 -0.0139515 -1.57631 1 0 1 1 0 0 +EDGE2 2416 1255 -1.02234 0.0240556 1.58487 1 0 1 1 0 0 +EDGE2 2416 1256 -0.083322 -0.0885841 0.00569625 1 0 1 1 0 0 +EDGE2 2416 2296 0.00656796 -0.0151071 0.0220605 1 0 1 1 0 0 +EDGE2 2416 2297 1.02819 0.111781 0.0509567 1 0 1 1 0 0 +EDGE2 2416 1257 0.985126 -0.0347159 -0.00635324 1 0 1 1 0 0 +EDGE2 2417 2416 -0.921605 -0.089339 0.0322234 1 0 1 1 0 0 +EDGE2 2417 1256 -1.03909 0.0841839 0.00894962 1 0 1 1 0 0 +EDGE2 2417 2296 -0.966985 0.0163125 0.00211888 1 0 1 1 0 0 +EDGE2 2417 2297 0.0131426 -0.0352465 -0.0221697 1 0 1 1 0 0 +EDGE2 2417 1257 0.0274626 -0.015396 0.0217498 1 0 1 1 0 0 +EDGE2 2417 2298 1.01419 -0.0236659 0.0149152 1 0 1 1 0 0 +EDGE2 2417 1258 1.0295 0.0676832 -0.00224571 1 0 1 1 0 0 +EDGE2 2418 2297 -1.00514 0.0816707 -0.0112738 1 0 1 1 0 0 +EDGE2 2418 2417 -0.97405 0.0300584 -0.00282912 1 0 1 1 0 0 +EDGE2 2418 1257 -0.993242 -0.0434524 -0.0138367 1 0 1 1 0 0 +EDGE2 2418 2298 -0.00840909 -0.00903428 0.0286844 1 0 1 1 0 0 +EDGE2 2418 1258 0.0685339 0.078326 -0.0130377 1 0 1 1 0 0 +EDGE2 2418 2299 0.970277 0.105176 0.0215863 1 0 1 1 0 0 +EDGE2 2418 1259 0.986899 -0.0048209 -0.0215474 1 0 1 1 0 0 +EDGE2 2419 2298 -0.979491 -0.0077452 0.0237194 1 0 1 1 0 0 +EDGE2 2419 2418 -0.971511 -0.0415662 0.00510188 1 0 1 1 0 0 +EDGE2 2419 1258 -1.03268 0.00146858 -0.0108773 1 0 1 1 0 0 +EDGE2 2419 2299 0.01359 -0.0167288 0.00425997 1 0 1 1 0 0 +EDGE2 2419 1259 -0.0523759 -0.0284766 0.0173583 1 0 1 1 0 0 +EDGE2 2419 2300 0.986309 -0.072376 0.0102223 1 0 1 1 0 0 +EDGE2 2419 1260 1.04102 -0.0264988 0.0168872 1 0 1 1 0 0 +EDGE2 2420 2301 0.0347579 0.94612 1.5644 1 0 1 1 0 0 +EDGE2 2420 1261 -0.0131414 1.03204 1.58301 1 0 1 1 0 0 +EDGE2 2420 2299 -0.893393 -0.00779703 -0.0120082 1 0 1 1 0 0 +EDGE2 2420 2419 -1.00861 -0.0333561 0.0198375 1 0 1 1 0 0 +EDGE2 2420 1259 -0.926672 -0.0798282 0.00533915 1 0 1 1 0 0 +EDGE2 2420 2300 0.0318712 0.00662662 -0.0422296 1 0 1 1 0 0 +EDGE2 2420 1260 -0.0571867 -0.041485 0.00358942 1 0 1 1 0 0 +EDGE2 2421 2302 1.06255 -0.123748 0.0192139 1 0 1 1 0 0 +EDGE2 2421 1262 0.931844 -0.0726036 -0.0201297 1 0 1 1 0 0 +EDGE2 2421 2301 0.0629422 0.105522 0.0155863 1 0 1 1 0 0 +EDGE2 2421 1261 -0.0196893 -0.0373171 0.00799886 1 0 1 1 0 0 +EDGE2 2421 2420 -1.01559 0.0727216 -1.53893 1 0 1 1 0 0 +EDGE2 2421 2300 -1.02953 0.0757471 -1.59503 1 0 1 1 0 0 +EDGE2 2421 1260 -1.02235 0.0443955 -1.58542 1 0 1 1 0 0 +EDGE2 2422 2302 0.0516071 -0.004231 0.00473957 1 0 1 1 0 0 +EDGE2 2422 2303 0.941217 0.0720014 0.0112141 1 0 1 1 0 0 +EDGE2 2422 1263 0.948219 -0.0334493 0.0203627 1 0 1 1 0 0 +EDGE2 2422 1262 -0.0204909 0.0361166 0.0228058 1 0 1 1 0 0 +EDGE2 2422 2301 -1.04377 -0.0873252 0.0280713 1 0 1 1 0 0 +EDGE2 2422 2421 -0.947715 -0.0621831 -0.0013717 1 0 1 1 0 0 +EDGE2 2422 1261 -0.94308 0.00322951 -0.015217 1 0 1 1 0 0 +EDGE2 2423 1264 1.05409 -0.0414326 0.0257867 1 0 1 1 0 0 +EDGE2 2423 2304 1.05422 0.0874765 0.0243137 1 0 1 1 0 0 +EDGE2 2423 2302 -0.94851 0.0490327 -0.0227111 1 0 1 1 0 0 +EDGE2 2423 2303 -0.0319492 0.0876242 0.0309922 1 0 1 1 0 0 +EDGE2 2423 1263 0.00413525 0.0846837 0.027576 1 0 1 1 0 0 +EDGE2 2423 2422 -1.00559 0.0361286 -0.00624554 1 0 1 1 0 0 +EDGE2 2423 1262 -0.902125 -0.016233 -0.0097183 1 0 1 1 0 0 +EDGE2 2424 1265 0.98232 0.0135017 0.00524286 1 0 1 1 0 0 +EDGE2 2424 2305 0.974889 -0.0564468 0.0110715 1 0 1 1 0 0 +EDGE2 2424 2405 1.01082 0.00993466 -3.15127 1 0 1 1 0 0 +EDGE2 2424 2385 1.00078 0.0017444 -3.16869 1 0 1 1 0 0 +EDGE2 2424 1565 1.03489 -0.0431009 -3.14762 1 0 1 1 0 0 +EDGE2 2424 1585 1.02077 -0.0269206 -3.19313 1 0 1 1 0 0 +EDGE2 2424 1845 0.939521 -0.0157437 -3.17288 1 0 1 1 0 0 +EDGE2 2424 1545 1.05441 0.0258812 -3.12577 1 0 1 1 0 0 +EDGE2 2424 1264 0.0438163 0.0242262 0.0265897 1 0 1 1 0 0 +EDGE2 2424 2304 -0.0831885 0.0679398 -0.0100325 1 0 1 1 0 0 +EDGE2 2424 2303 -0.96849 0.0699523 0.00464069 1 0 1 1 0 0 +EDGE2 2424 2423 -0.968835 -0.0361217 -0.0197593 1 0 1 1 0 0 +EDGE2 2424 1263 -0.992626 -0.0318103 3.98428e-05 1 0 1 1 0 0 +EDGE2 2425 1564 0.969636 -0.047673 -3.14901 1 0 1 1 0 0 +EDGE2 2425 1844 1.00054 -0.0138333 -3.11835 1 0 1 1 0 0 +EDGE2 2425 2384 0.963301 -0.0423874 -3.15321 1 0 1 1 0 0 +EDGE2 2425 2404 0.952577 0.0139362 -3.14457 1 0 1 1 0 0 +EDGE2 2425 1584 1.00941 0.043262 -3.10915 1 0 1 1 0 0 +EDGE2 2425 1544 0.970671 0.00717468 -3.16331 1 0 1 1 0 0 +EDGE2 2425 2406 0.00358402 0.950617 1.56587 1 0 1 1 0 0 +EDGE2 2425 1546 -0.0324695 1.00607 1.55374 1 0 1 1 0 0 +EDGE2 2425 1265 0.0612147 -0.0371988 0.0236533 1 0 1 1 0 0 +EDGE2 2425 2305 0.0229812 -0.0481087 0.0150887 1 0 1 1 0 0 +EDGE2 2425 2405 0.0705961 0.0137384 -3.13969 1 0 1 1 0 0 +EDGE2 2425 2385 0.099512 0.02259 -3.14625 1 0 1 1 0 0 +EDGE2 2425 1565 0.0330802 -0.10013 -3.14296 1 0 1 1 0 0 +EDGE2 2425 1585 -0.119357 0.0758326 -3.14557 1 0 1 1 0 0 +EDGE2 2425 1845 -0.0730254 -0.115658 -3.16042 1 0 1 1 0 0 +EDGE2 2425 1545 -0.00443723 0.0465753 -3.15199 1 0 1 1 0 0 +EDGE2 2425 2424 -0.938652 0.0503575 0.0205197 1 0 1 1 0 0 +EDGE2 2425 1264 -0.982937 -0.0520357 0.0126648 1 0 1 1 0 0 +EDGE2 2425 2304 -0.97064 -0.019618 -0.0169389 1 0 1 1 0 0 +EDGE2 2425 1566 -0.0020356 -0.991422 -1.58267 1 0 1 1 0 0 +EDGE2 2425 1846 -0.0989733 -0.95306 -1.56687 1 0 1 1 0 0 +EDGE2 2425 2306 -0.0384086 -1.03172 -1.55702 1 0 1 1 0 0 +EDGE2 2425 2386 -0.00620158 -0.948283 -1.5467 1 0 1 1 0 0 +EDGE2 2425 1586 -0.00996961 -0.996151 -1.58067 1 0 1 1 0 0 +EDGE2 2425 1266 0.0110736 -1.0071 -1.58615 1 0 1 1 0 0 +EDGE2 2426 1547 0.96472 -0.0558874 -0.00224381 1 0 1 1 0 0 +EDGE2 2426 2407 1.05155 0.0560527 -0.00296483 1 0 1 1 0 0 +EDGE2 2426 2406 0.0517998 -0.0558268 0.0225435 1 0 1 1 0 0 +EDGE2 2426 1546 0.0466361 0.0173233 -0.00382591 1 0 1 1 0 0 +EDGE2 2426 1265 -1.00189 -0.00767171 -1.61224 1 0 1 1 0 0 +EDGE2 2426 2305 -0.94646 0.0257469 -1.57635 1 0 1 1 0 0 +EDGE2 2426 2405 -0.982402 -0.0746178 1.5721 1 0 1 1 0 0 +EDGE2 2426 2425 -0.952967 -0.00885029 -1.57667 1 0 1 1 0 0 +EDGE2 2426 2385 -0.973426 0.0683586 1.59427 1 0 1 1 0 0 +EDGE2 2426 1565 -0.975931 -0.0816998 1.57771 1 0 1 1 0 0 +EDGE2 2426 1585 -0.930248 0.0620819 1.53353 1 0 1 1 0 0 +EDGE2 2426 1845 -0.990775 -0.0122394 1.56767 1 0 1 1 0 0 +EDGE2 2426 1545 -0.961825 0.0100488 1.56149 1 0 1 1 0 0 +EDGE2 2427 1548 1.02498 -0.00441963 0.0232481 1 0 1 1 0 0 +EDGE2 2427 2408 0.979936 -0.0536512 -0.048269 1 0 1 1 0 0 +EDGE2 2427 2426 -1.00852 -0.0715195 -0.0173488 1 0 1 1 0 0 +EDGE2 2427 1547 -0.103202 0.0300479 0.0336044 1 0 1 1 0 0 +EDGE2 2427 2407 0.030314 -0.0591352 0.0257165 1 0 1 1 0 0 +EDGE2 2427 2406 -0.968998 0.0134923 0.00378236 1 0 1 1 0 0 +EDGE2 2427 1546 -0.949122 -0.0474716 -0.0297231 1 0 1 1 0 0 +EDGE2 2428 1549 1.06173 -0.0900732 -0.0118194 1 0 1 1 0 0 +EDGE2 2428 2409 0.958081 -0.00842744 0.0119024 1 0 1 1 0 0 +EDGE2 2428 1548 -0.0372016 -0.0607302 -0.0313105 1 0 1 1 0 0 +EDGE2 2428 2408 0.129802 0.0518569 -0.004379 1 0 1 1 0 0 +EDGE2 2428 1547 -1.10037 -0.0834377 0.0270603 1 0 1 1 0 0 +EDGE2 2428 2427 -0.963059 0.11474 -0.0187124 1 0 1 1 0 0 +EDGE2 2428 2407 -1.06246 -0.0182409 -0.0130859 1 0 1 1 0 0 +EDGE2 2429 1550 1.02568 0.00637306 0.0210465 1 0 1 1 0 0 +EDGE2 2429 1830 1.11883 0.0035261 -3.14025 1 0 1 1 0 0 +EDGE2 2429 2410 0.982275 0.0055467 -0.0129884 1 0 1 1 0 0 +EDGE2 2429 1549 -0.0318536 0.0797195 -0.020737 1 0 1 1 0 0 +EDGE2 2429 2409 -0.0119535 -0.0495044 0.0196497 1 0 1 1 0 0 +EDGE2 2429 1548 -0.980639 0.019426 -0.0102683 1 0 1 1 0 0 +EDGE2 2429 2408 -1.03195 0.0558491 -0.0210113 1 0 1 1 0 0 +EDGE2 2429 2428 -0.969437 -0.0026918 0.0179042 1 0 1 1 0 0 +EDGE2 2430 1829 1.00747 -0.00170531 -3.16572 1 0 1 1 0 0 +EDGE2 2430 1831 -0.0575325 -0.962933 -1.54975 1 0 1 1 0 0 +EDGE2 2430 1551 -0.0236767 -0.962254 -1.60894 1 0 1 1 0 0 +EDGE2 2430 2411 0.0650208 1.11761 1.56278 1 0 1 1 0 0 +EDGE2 2430 1550 -0.0533948 0.0685661 0.0378655 1 0 1 1 0 0 +EDGE2 2430 1830 -0.0224119 -0.0713966 -3.13787 1 0 1 1 0 0 +EDGE2 2430 2410 -0.0902297 0.0866167 0.0099185 1 0 1 1 0 0 +EDGE2 2430 2429 -0.998897 0.00727804 0.0210425 1 0 1 1 0 0 +EDGE2 2430 1549 -1.04753 0.00680693 0.00434605 1 0 1 1 0 0 +EDGE2 2430 2409 -0.979751 0.00766507 0.0198997 1 0 1 1 0 0 +EDGE2 2431 2411 0.021414 0.00575095 0.00357579 1 0 1 1 0 0 +EDGE2 2431 2430 -0.969093 0.00810813 -1.56117 1 0 1 1 0 0 +EDGE2 2431 1550 -1.03477 -0.116776 -1.54477 1 0 1 1 0 0 +EDGE2 2431 1830 -1.00503 -0.0587068 1.55379 1 0 1 1 0 0 +EDGE2 2431 2410 -0.897765 -0.0119405 -1.56597 1 0 1 1 0 0 +EDGE2 2431 2412 1.01259 0.032181 0.0352551 1 0 1 1 0 0 +EDGE2 2432 2411 -1.01869 0.0264328 -0.0111084 1 0 1 1 0 0 +EDGE2 2432 2431 -1.02649 -0.055893 0.0183944 1 0 1 1 0 0 +EDGE2 2432 2412 -0.00694946 -0.0341427 -0.0156559 1 0 1 1 0 0 +EDGE2 2432 2413 1.05028 -0.0260819 0.00217541 1 0 1 1 0 0 +EDGE2 2433 2432 -1.00027 0.0418403 0.0193167 1 0 1 1 0 0 +EDGE2 2433 2412 -0.887121 -0.0318981 0.0125325 1 0 1 1 0 0 +EDGE2 2433 2413 0.0074995 -0.0549049 -0.00424631 1 0 1 1 0 0 +EDGE2 2433 2414 1.06961 -0.042631 -0.00128757 1 0 1 1 0 0 +EDGE2 2434 2413 -0.999515 0.182567 -0.0117054 1 0 1 1 0 0 +EDGE2 2434 2433 -0.999911 0.0197396 -0.0148355 1 0 1 1 0 0 +EDGE2 2434 2414 -0.0329494 -0.00761274 0.0216325 1 0 1 1 0 0 +EDGE2 2434 1235 1.07814 -0.00678314 -3.16263 1 0 1 1 0 0 +EDGE2 2434 2295 0.987877 -0.0321378 -3.1584 1 0 1 1 0 0 +EDGE2 2434 2415 0.965317 -0.0626393 -0.0155244 1 0 1 1 0 0 +EDGE2 2434 1255 1.06474 -0.0254579 -3.15624 1 0 1 1 0 0 +EDGE2 2435 2416 -0.0142287 1.01829 1.54578 1 0 1 1 0 0 +EDGE2 2435 1236 -0.0426594 -0.95463 -1.57419 1 0 1 1 0 0 +EDGE2 2435 2414 -0.985209 -0.0769775 -0.0028775 1 0 1 1 0 0 +EDGE2 2435 2434 -1.06454 0.076625 -0.0118517 1 0 1 1 0 0 +EDGE2 2435 1235 -0.018122 0.0530577 -3.12804 1 0 1 1 0 0 +EDGE2 2435 2295 0.00746301 0.0265387 -3.10328 1 0 1 1 0 0 +EDGE2 2435 2415 0.00289384 -0.100706 -0.00297588 1 0 1 1 0 0 +EDGE2 2435 1255 0.0244112 -0.0706415 -3.12694 1 0 1 1 0 0 +EDGE2 2435 1254 1.04211 0.0654109 -3.12055 1 0 1 1 0 0 +EDGE2 2435 2294 1.10507 0.0451652 -3.1839 1 0 1 1 0 0 +EDGE2 2435 1234 0.960578 -0.0662833 -3.15981 1 0 1 1 0 0 +EDGE2 2435 1256 0.0491723 0.969242 1.58413 1 0 1 1 0 0 +EDGE2 2435 2296 0.109328 1.04251 1.54823 1 0 1 1 0 0 +EDGE2 2436 2416 0.0250594 0.0231296 0.00643084 1 0 1 1 0 0 +EDGE2 2436 1235 -1.05098 -0.0754596 1.55357 1 0 1 1 0 0 +EDGE2 2436 2295 -1.05761 0.0708639 1.58099 1 0 1 1 0 0 +EDGE2 2436 2415 -1.04004 0.0167765 -1.56468 1 0 1 1 0 0 +EDGE2 2436 2435 -0.949825 0.053666 -1.58909 1 0 1 1 0 0 +EDGE2 2436 1255 -0.997226 0.0544077 1.56597 1 0 1 1 0 0 +EDGE2 2436 1256 0.0109532 -0.0218179 -0.0235131 1 0 1 1 0 0 +EDGE2 2436 2296 -0.02211 -0.00710728 -0.0380941 1 0 1 1 0 0 +EDGE2 2436 2297 1.04486 0.0123418 -0.0111215 1 0 1 1 0 0 +EDGE2 2436 2417 0.959831 -0.0477888 0.0332462 1 0 1 1 0 0 +EDGE2 2436 1257 1.02209 -0.0349228 0.01142 1 0 1 1 0 0 +EDGE2 2437 2416 -0.967829 -0.0819249 -0.0297588 1 0 1 1 0 0 +EDGE2 2437 2436 -1.00731 0.114734 0.0155873 1 0 1 1 0 0 +EDGE2 2437 1256 -0.905641 -0.0150344 0.0141738 1 0 1 1 0 0 +EDGE2 2437 2296 -0.973572 0.0228904 -0.00564323 1 0 1 1 0 0 +EDGE2 2437 2297 0.0149085 -0.10812 0.0189654 1 0 1 1 0 0 +EDGE2 2437 2417 0.00414667 0.00495354 0.0464912 1 0 1 1 0 0 +EDGE2 2437 1257 0.0300312 -0.0697385 0.0597397 1 0 1 1 0 0 +EDGE2 2437 2298 0.992462 -0.0938103 0.0387302 1 0 1 1 0 0 +EDGE2 2437 2418 1.0385 -0.0159299 -0.0318052 1 0 1 1 0 0 +EDGE2 2437 1258 1.05253 -0.0129007 -0.0165492 1 0 1 1 0 0 +EDGE2 2438 2297 -0.947768 0.00742366 -0.0252476 1 0 1 1 0 0 +EDGE2 2438 2417 -1.0186 0.0160848 -0.0213364 1 0 1 1 0 0 +EDGE2 2438 2437 -0.988773 -0.0133418 0.0153587 1 0 1 1 0 0 +EDGE2 2438 1257 -0.985123 -0.0122204 0.00210268 1 0 1 1 0 0 +EDGE2 2438 2298 -0.0189314 -0.0793257 -0.00420747 1 0 1 1 0 0 +EDGE2 2438 2418 -0.0574611 -0.0263804 0.0177603 1 0 1 1 0 0 +EDGE2 2438 1258 0.0325694 -0.00764251 -0.00602278 1 0 1 1 0 0 +EDGE2 2438 2299 1.03251 0.06251 -0.0202103 1 0 1 1 0 0 +EDGE2 2438 2419 0.907427 0.0180781 -0.00903443 1 0 1 1 0 0 +EDGE2 2438 1259 0.955872 0.11035 0.00720773 1 0 1 1 0 0 +EDGE2 2439 2298 -1.08614 -0.0723293 0.0301781 1 0 1 1 0 0 +EDGE2 2439 2418 -0.926997 -0.0220689 -0.00684835 1 0 1 1 0 0 +EDGE2 2439 2438 -0.935239 -0.0127126 -0.00881816 1 0 1 1 0 0 +EDGE2 2439 1258 -0.937171 -0.00312629 0.0127468 1 0 1 1 0 0 +EDGE2 2439 2299 0.00553323 -0.0156923 0.00547479 1 0 1 1 0 0 +EDGE2 2439 2419 0.0188118 0.0106116 -0.00709643 1 0 1 1 0 0 +EDGE2 2439 1259 0.0133969 0.0245363 -0.0043593 1 0 1 1 0 0 +EDGE2 2439 2420 1.03774 0.00485986 0.00536431 1 0 1 1 0 0 +EDGE2 2439 2300 0.986925 0.0125946 0.00128316 1 0 1 1 0 0 +EDGE2 2439 1260 0.976853 -0.023055 0.0331913 1 0 1 1 0 0 +EDGE2 2440 2301 -0.0215396 1.04543 1.551 1 0 1 1 0 0 +EDGE2 2440 2421 -0.00989405 1.09194 1.56218 1 0 1 1 0 0 +EDGE2 2440 1261 -0.00418143 0.98959 1.59018 1 0 1 1 0 0 +EDGE2 2440 2299 -1.11078 0.0439989 -0.0452211 1 0 1 1 0 0 +EDGE2 2440 2419 -0.988981 -0.0327458 0.00584911 1 0 1 1 0 0 +EDGE2 2440 2439 -1.01645 -0.0425137 -0.00905095 1 0 1 1 0 0 +EDGE2 2440 1259 -1.02736 0.00881384 -0.00943056 1 0 1 1 0 0 +EDGE2 2440 2420 -0.00514173 -0.0180559 0.0219504 1 0 1 1 0 0 +EDGE2 2440 2300 -0.0597372 -0.0136443 0.00119541 1 0 1 1 0 0 +EDGE2 2440 1260 -0.0477989 0.0465001 0.0101334 1 0 1 1 0 0 +EDGE2 2441 2420 -0.953198 -0.0385767 1.5661 1 0 1 1 0 0 +EDGE2 2441 2440 -0.97421 -0.0156183 1.53018 1 0 1 1 0 0 +EDGE2 2441 2300 -1.08753 0.0616755 1.53703 1 0 1 1 0 0 +EDGE2 2441 1260 -0.86174 0.0128982 1.55203 1 0 1 1 0 0 +EDGE2 2442 2441 -0.946538 -0.00687919 0.00489251 1 0 1 1 0 0 +EDGE2 2443 2442 -0.987134 -0.0129858 -0.00456288 1 0 1 1 0 0 +EDGE2 2444 2443 -1.00363 -0.0482368 -0.00509877 1 0 1 1 0 0 +EDGE2 2444 1225 1.05045 0.022598 -3.11834 1 0 1 1 0 0 +EDGE2 2445 1226 -0.0297718 -0.931691 -1.55291 1 0 1 1 0 0 +EDGE2 2445 2444 -0.971473 -0.0195698 -0.023893 1 0 1 1 0 0 +EDGE2 2445 1225 -0.08675 0.0482106 -3.15527 1 0 1 1 0 0 +EDGE2 2445 1224 1.08518 -0.0105757 -3.17258 1 0 1 1 0 0 +EDGE2 2446 1227 0.927995 -0.027947 0.0118505 1 0 1 1 0 0 +EDGE2 2446 1226 -0.0863865 0.0443745 0.0260092 1 0 1 1 0 0 +EDGE2 2446 1225 -0.953698 -0.0511443 -1.57397 1 0 1 1 0 0 +EDGE2 2446 2445 -0.969561 0.0239703 1.60825 1 0 1 1 0 0 +EDGE2 2447 1228 1.00735 0.00385063 0.0234345 1 0 1 1 0 0 +EDGE2 2447 1227 -0.00604213 0.0602925 -0.0328502 1 0 1 1 0 0 +EDGE2 2447 2446 -0.939568 -0.0838343 0.0407637 1 0 1 1 0 0 +EDGE2 2447 1226 -1.11631 -0.0222113 0.0161213 1 0 1 1 0 0 +EDGE2 2448 1229 1.02327 -0.0517493 -0.00578126 1 0 1 1 0 0 +EDGE2 2448 1228 -0.0194744 -0.0210896 0.0226693 1 0 1 1 0 0 +EDGE2 2448 1227 -1.1501 0.0465958 0.0133793 1 0 1 1 0 0 +EDGE2 2448 2447 -0.972798 -0.0240371 -0.0100629 1 0 1 1 0 0 +EDGE2 2449 1250 1.11541 0.029033 -3.11216 1 0 1 1 0 0 +EDGE2 2449 2290 0.979721 -0.119721 -3.13546 1 0 1 1 0 0 +EDGE2 2449 1230 1.01065 0.0857195 -0.00577561 1 0 1 1 0 0 +EDGE2 2449 1229 0.0105023 0.164058 -0.0123113 1 0 1 1 0 0 +EDGE2 2449 1228 -1.06915 0.0227244 -0.00258918 1 0 1 1 0 0 +EDGE2 2449 2448 -0.976461 -0.0234813 -0.0133003 1 0 1 1 0 0 +EDGE2 2450 2291 -0.0163675 -1.00177 -1.53329 1 0 1 1 0 0 +EDGE2 2450 2289 1.04636 -0.00224981 -3.16018 1 0 1 1 0 0 +EDGE2 2450 1249 0.972032 -0.0398704 -3.17813 1 0 1 1 0 0 +EDGE2 2450 1250 0.0198304 0.000220323 -3.14511 1 0 1 1 0 0 +EDGE2 2450 1231 0.0303744 -0.991391 -1.543 1 0 1 1 0 0 +EDGE2 2450 1251 0.0399568 -1.0177 -1.54586 1 0 1 1 0 0 +EDGE2 2450 2290 -0.0658763 -0.00673333 -3.12035 1 0 1 1 0 0 +EDGE2 2450 1230 -0.0432411 -0.027253 -0.00454197 1 0 1 1 0 0 +EDGE2 2450 2449 -0.978649 -0.091482 0.0124306 1 0 1 1 0 0 +EDGE2 2450 1229 -1.05709 -0.0315113 -0.00874821 1 0 1 1 0 0 +EDGE2 2451 2292 0.9621 -0.046923 -0.0269575 1 0 1 1 0 0 +EDGE2 2451 2291 0.0220614 0.101873 0.0123148 1 0 1 1 0 0 +EDGE2 2451 1252 0.923521 -0.0657811 0.00762392 1 0 1 1 0 0 +EDGE2 2451 1232 1.01039 -0.0341862 0.00287588 1 0 1 1 0 0 +EDGE2 2451 1250 -0.864218 0.000624912 -1.54681 1 0 1 1 0 0 +EDGE2 2451 1231 -0.0669092 0.0218298 0.0137918 1 0 1 1 0 0 +EDGE2 2451 1251 -0.0417396 -0.0389278 -0.0010005 1 0 1 1 0 0 +EDGE2 2451 2450 -1.08527 0.086311 1.52662 1 0 1 1 0 0 +EDGE2 2451 2290 -0.96272 -0.124923 -1.58078 1 0 1 1 0 0 +EDGE2 2451 1230 -0.970191 0.0123677 1.55767 1 0 1 1 0 0 +EDGE2 2452 2292 -0.0708644 -0.0714873 0.055965 1 0 1 1 0 0 +EDGE2 2452 2293 0.991195 0.070854 -0.0256816 1 0 1 1 0 0 +EDGE2 2452 1233 0.99673 -0.0158554 -0.0142491 1 0 1 1 0 0 +EDGE2 2452 1253 1.05033 -0.106394 -0.0218525 1 0 1 1 0 0 +EDGE2 2452 2291 -0.991617 -0.026103 -0.00607626 1 0 1 1 0 0 +EDGE2 2452 1252 0.0629131 -0.0138165 0.00308646 1 0 1 1 0 0 +EDGE2 2452 1232 0.060803 -0.0654615 -0.0158608 1 0 1 1 0 0 +EDGE2 2452 2451 -1.00033 -0.048564 -0.0218221 1 0 1 1 0 0 +EDGE2 2452 1231 -1.13097 -0.0278928 0.0200744 1 0 1 1 0 0 +EDGE2 2452 1251 -0.943758 0.016767 -0.021133 1 0 1 1 0 0 +EDGE2 2453 2292 -1.02135 0.0205601 0.0159478 1 0 1 1 0 0 +EDGE2 2453 2293 -0.0512949 -0.0790973 0.0121761 1 0 1 1 0 0 +EDGE2 2453 1254 0.975454 -0.112558 -0.0165287 1 0 1 1 0 0 +EDGE2 2453 2294 0.881166 0.0336268 0.023301 1 0 1 1 0 0 +EDGE2 2453 1234 0.950897 -0.0226296 -0.00593538 1 0 1 1 0 0 +EDGE2 2453 2452 -1.00943 0.00884429 -0.0193628 1 0 1 1 0 0 +EDGE2 2453 1233 -0.0431308 0.113673 -0.00108508 1 0 1 1 0 0 +EDGE2 2453 1253 -0.0513898 -0.0313533 0.00627752 1 0 1 1 0 0 +EDGE2 2453 1252 -0.988961 -0.0575863 0.0143022 1 0 1 1 0 0 +EDGE2 2453 1232 -0.900602 -0.0656257 -0.0251437 1 0 1 1 0 0 +EDGE2 2454 2293 -0.970524 0.00581817 0.0213941 1 0 1 1 0 0 +EDGE2 2454 1235 0.985262 -0.0113638 0.000956148 1 0 1 1 0 0 +EDGE2 2454 2295 1.0169 0.0149715 0.0313399 1 0 1 1 0 0 +EDGE2 2454 2415 1.00378 0.0699089 -3.15955 1 0 1 1 0 0 +EDGE2 2454 2435 0.929636 -0.00674611 -3.16454 1 0 1 1 0 0 +EDGE2 2454 1255 1.03952 0.0033477 -0.0270315 1 0 1 1 0 0 +EDGE2 2454 1254 -0.0264361 0.010576 -0.0196203 1 0 1 1 0 0 +EDGE2 2454 2294 -0.0161742 -0.0420059 0.00120281 1 0 1 1 0 0 +EDGE2 2454 1234 -0.0720715 0.0359249 0.00773392 1 0 1 1 0 0 +EDGE2 2454 2453 -1.00828 0.116585 0.0190753 1 0 1 1 0 0 +EDGE2 2454 1233 -0.936619 0.0683554 -0.0194969 1 0 1 1 0 0 +EDGE2 2454 1253 -1.04323 0.0387948 -0.029842 1 0 1 1 0 0 +EDGE2 2455 2416 -0.00337327 -1.00665 -1.55827 1 0 1 1 0 0 +EDGE2 2455 1236 -0.0630913 1.03955 1.56767 1 0 1 1 0 0 +EDGE2 2455 2414 1.00564 -0.0403293 -3.15546 1 0 1 1 0 0 +EDGE2 2455 2434 0.942086 -0.00329729 -3.15232 1 0 1 1 0 0 +EDGE2 2455 1235 -0.0280913 -0.112454 0.0290572 1 0 1 1 0 0 +EDGE2 2455 2295 0.0552241 -0.0478916 0.0271106 1 0 1 1 0 0 +EDGE2 2455 2415 -0.0754413 -0.0827538 -3.14522 1 0 1 1 0 0 +EDGE2 2455 2435 0.0813208 0.0122358 -3.1236 1 0 1 1 0 0 +EDGE2 2455 1255 -0.051607 0.0961583 0.0138092 1 0 1 1 0 0 +EDGE2 2455 1254 -1.01259 0.0454653 -0.0160498 1 0 1 1 0 0 +EDGE2 2455 2454 -0.977681 0.0335817 -0.0167419 1 0 1 1 0 0 +EDGE2 2455 2294 -1.02065 -0.0267872 -0.00516332 1 0 1 1 0 0 +EDGE2 2455 1234 -0.972234 -0.00828072 0.0303889 1 0 1 1 0 0 +EDGE2 2455 2436 0.0454851 -0.994078 -1.56842 1 0 1 1 0 0 +EDGE2 2455 1256 0.0538796 -1.02024 -1.58808 1 0 1 1 0 0 +EDGE2 2455 2296 0.00535409 -1.03126 -1.60297 1 0 1 1 0 0 +EDGE2 2456 1237 1.02082 -0.00310247 0.0238323 1 0 1 1 0 0 +EDGE2 2456 1236 -0.00137414 -0.0326381 0.00643813 1 0 1 1 0 0 +EDGE2 2456 1235 -1.10013 0.00585649 -1.58132 1 0 1 1 0 0 +EDGE2 2456 2455 -0.9366 -0.0305422 -1.54069 1 0 1 1 0 0 +EDGE2 2456 2295 -1.00382 -0.0752345 -1.57467 1 0 1 1 0 0 +EDGE2 2456 2415 -1.02258 -0.0690469 1.55601 1 0 1 1 0 0 +EDGE2 2456 2435 -0.962081 -0.0685277 1.57037 1 0 1 1 0 0 +EDGE2 2456 1255 -1.00577 0.00190503 -1.58481 1 0 1 1 0 0 +EDGE2 2457 1238 0.92607 0.0435191 -0.00106337 1 0 1 1 0 0 +EDGE2 2457 2456 -0.92911 0.0443393 0.0290557 1 0 1 1 0 0 +EDGE2 2457 1237 -0.0440031 0.0165659 0.0191756 1 0 1 1 0 0 +EDGE2 2457 1236 -0.933746 -0.0488338 -0.0254841 1 0 1 1 0 0 +EDGE2 2458 1239 0.973925 0.00492143 0.024822 1 0 1 1 0 0 +EDGE2 2458 1238 0.0102007 -0.0108625 0.00538162 1 0 1 1 0 0 +EDGE2 2458 1237 -1.06065 0.0102441 0.0114051 1 0 1 1 0 0 +EDGE2 2458 2457 -0.966763 -0.0230656 -0.0240864 1 0 1 1 0 0 +EDGE2 2459 1820 0.982828 -0.0299352 -3.09574 1 0 1 1 0 0 +EDGE2 2459 2240 1.04356 -0.0277815 -3.16479 1 0 1 1 0 0 +EDGE2 2459 2280 1.04503 0.023016 -3.16662 1 0 1 1 0 0 +EDGE2 2459 1240 1.01002 0.0578016 -0.00433578 1 0 1 1 0 0 +EDGE2 2459 1239 0.0655979 -0.0834775 0.0111 1 0 1 1 0 0 +EDGE2 2459 2458 -1.04455 0.0035729 0.020523 1 0 1 1 0 0 +EDGE2 2459 1238 -0.990879 0.0948045 -0.0016681 1 0 1 1 0 0 +EDGE2 2460 2239 1.08543 0.0532223 -3.14703 1 0 1 1 0 0 +EDGE2 2460 2279 1.02777 0.112449 -3.1364 1 0 1 1 0 0 +EDGE2 2460 1819 0.973672 -0.0850953 -3.11927 1 0 1 1 0 0 +EDGE2 2460 1821 0.0238537 -1.07266 -1.60035 1 0 1 1 0 0 +EDGE2 2460 2241 -0.00961681 -1.05381 -1.55448 1 0 1 1 0 0 +EDGE2 2460 1820 -0.0605152 0.0118335 -3.16106 1 0 1 1 0 0 +EDGE2 2460 2240 -0.090283 0.0984557 -3.13729 1 0 1 1 0 0 +EDGE2 2460 2280 -0.00564034 0.0196628 -3.13539 1 0 1 1 0 0 +EDGE2 2460 1240 0.00148712 0.109412 -0.0212915 1 0 1 1 0 0 +EDGE2 2460 1241 -0.0368167 1.00842 1.54268 1 0 1 1 0 0 +EDGE2 2460 2281 0.0644236 0.995673 1.56268 1 0 1 1 0 0 +EDGE2 2460 1239 -0.97509 -0.0785858 0.03623 1 0 1 1 0 0 +EDGE2 2460 2459 -0.963824 0.0335849 0.0195406 1 0 1 1 0 0 +EDGE2 2461 2460 -1.03146 -0.0792961 -1.53212 1 0 1 1 0 0 +EDGE2 2461 1820 -1.09208 -0.0273659 1.60875 1 0 1 1 0 0 +EDGE2 2461 2240 -1.05373 0.0768932 1.56603 1 0 1 1 0 0 +EDGE2 2461 2280 -0.942121 -0.080102 1.58167 1 0 1 1 0 0 +EDGE2 2461 1240 -1.04736 0.0112514 -1.57773 1 0 1 1 0 0 +EDGE2 2461 1241 0.0139903 -0.14099 0.0261832 1 0 1 1 0 0 +EDGE2 2461 2281 0.0323029 0.0364132 -0.014498 1 0 1 1 0 0 +EDGE2 2461 1242 0.970647 0.0263542 -0.0426446 1 0 1 1 0 0 +EDGE2 2461 2282 1.03305 -0.10352 -0.00609886 1 0 1 1 0 0 +EDGE2 2462 1241 -1.05179 0.0360648 -0.0275395 1 0 1 1 0 0 +EDGE2 2462 2281 -1.16913 -0.00650935 -0.000272433 1 0 1 1 0 0 +EDGE2 2462 2461 -0.903338 0.0645053 0.0105396 1 0 1 1 0 0 +EDGE2 2462 1242 0.0316375 -0.00358116 0.0125705 1 0 1 1 0 0 +EDGE2 2462 2282 0.0600483 -0.0399734 0.0203021 1 0 1 1 0 0 +EDGE2 2462 2283 0.987066 0.106708 0.0146146 1 0 1 1 0 0 +EDGE2 2462 1243 1.05592 -0.0769309 0.000520707 1 0 1 1 0 0 +EDGE2 2463 2462 -1.01272 -0.0690261 0.00191126 1 0 1 1 0 0 +EDGE2 2463 1242 -0.994879 0.0152569 -0.00646807 1 0 1 1 0 0 +EDGE2 2463 2282 -0.972182 -0.029187 0.0296932 1 0 1 1 0 0 +EDGE2 2463 2283 0.00267374 0.0140353 -0.0167084 1 0 1 1 0 0 +EDGE2 2463 1243 0.0436323 -0.020751 -0.0325168 1 0 1 1 0 0 +EDGE2 2463 1244 1.08806 0.0440145 0.0292887 1 0 1 1 0 0 +EDGE2 2463 2284 0.935191 0.0516339 -0.00359334 1 0 1 1 0 0 +EDGE2 2464 2283 -1.08538 0.0240731 -0.00108235 1 0 1 1 0 0 +EDGE2 2464 2463 -0.94437 0.0106857 0.0150489 1 0 1 1 0 0 +EDGE2 2464 1243 -1.0157 0.082881 0.0110402 1 0 1 1 0 0 +EDGE2 2464 785 0.953611 0.0202886 -3.1735 1 0 1 1 0 0 +EDGE2 2464 1244 -0.0253123 0.0219676 -0.0214075 1 0 1 1 0 0 +EDGE2 2464 2284 0.148454 -0.0121008 0.00895055 1 0 1 1 0 0 +EDGE2 2464 1245 1.02329 -0.00873504 -0.0143049 1 0 1 1 0 0 +EDGE2 2464 2285 1.05219 -0.00951993 -0.0228982 1 0 1 1 0 0 +EDGE2 2464 805 1.01722 0.0226048 -3.14315 1 0 1 1 0 0 +EDGE2 2464 745 1.05015 0.0201925 -3.12966 1 0 1 1 0 0 +EDGE2 2464 765 0.959616 0.0821176 -3.12094 1 0 1 1 0 0 +EDGE2 2465 806 -0.0772877 -0.938853 -1.57076 1 0 1 1 0 0 +EDGE2 2465 766 0.067852 -1.04008 -1.58109 1 0 1 1 0 0 +EDGE2 2465 786 0.0760877 -1.05397 -1.58692 1 0 1 1 0 0 +EDGE2 2465 746 -0.0441249 -0.995777 -1.54749 1 0 1 1 0 0 +EDGE2 2465 785 0.0292162 -0.0334825 -3.14485 1 0 1 1 0 0 +EDGE2 2465 1244 -0.970094 -0.0205976 0.000611334 1 0 1 1 0 0 +EDGE2 2465 2284 -0.96097 0.00821543 0.0157495 1 0 1 1 0 0 +EDGE2 2465 2464 -1.03571 -0.0947016 -0.0390594 1 0 1 1 0 0 +EDGE2 2465 1245 -0.00389524 0.00341185 0.00609843 1 0 1 1 0 0 +EDGE2 2465 2285 -0.0425584 -0.0660734 0.00519771 1 0 1 1 0 0 +EDGE2 2465 805 0.0680871 -0.00675577 -3.13314 1 0 1 1 0 0 +EDGE2 2465 784 0.996222 -0.0356947 -3.11718 1 0 1 1 0 0 +EDGE2 2465 745 -0.101115 -0.0478546 -3.11455 1 0 1 1 0 0 +EDGE2 2465 765 0.0621426 -0.0516576 -3.13581 1 0 1 1 0 0 +EDGE2 2465 804 0.985697 -0.0627955 -3.16673 1 0 1 1 0 0 +EDGE2 2465 744 1.01883 0.0594486 -3.13747 1 0 1 1 0 0 +EDGE2 2465 764 0.961043 -0.000935227 -3.12212 1 0 1 1 0 0 +EDGE2 2465 2286 0.0316778 0.968108 1.57238 1 0 1 1 0 0 +EDGE2 2465 1246 0.0250605 0.941188 1.54131 1 0 1 1 0 0 +EDGE2 2466 785 -0.951784 -0.00181444 1.58146 1 0 1 1 0 0 +EDGE2 2466 1245 -0.886142 0.0124306 -1.57802 1 0 1 1 0 0 +EDGE2 2466 2285 -0.975833 0.0504703 -1.59762 1 0 1 1 0 0 +EDGE2 2466 2465 -0.917871 -0.0565933 -1.55223 1 0 1 1 0 0 +EDGE2 2466 805 -0.942684 0.0183317 1.61295 1 0 1 1 0 0 +EDGE2 2466 745 -1.04178 -0.0196278 1.57919 1 0 1 1 0 0 +EDGE2 2466 765 -1.06324 0.136055 1.53 1 0 1 1 0 0 +EDGE2 2466 2286 -0.0250289 -0.00169364 0.00138414 1 0 1 1 0 0 +EDGE2 2466 2287 0.945761 -0.0148045 0.00389921 1 0 1 1 0 0 +EDGE2 2466 1246 0.0260503 -0.0309736 0.00451807 1 0 1 1 0 0 +EDGE2 2466 1247 1.02952 -0.0713999 -0.013257 1 0 1 1 0 0 +EDGE2 2467 2286 -0.965601 -0.0425896 -0.0179687 1 0 1 1 0 0 +EDGE2 2467 2466 -0.953694 -0.0671787 -7.02487e-06 1 0 1 1 0 0 +EDGE2 2467 2287 -0.00881683 0.0262953 0.0186054 1 0 1 1 0 0 +EDGE2 2467 1246 -1.03793 0.0437289 -0.0117854 1 0 1 1 0 0 +EDGE2 2467 1247 -0.0121208 0.0489833 0.00412268 1 0 1 1 0 0 +EDGE2 2467 1248 0.975137 0.0792655 0.00664304 1 0 1 1 0 0 +EDGE2 2467 2288 1.01796 -0.144657 -0.0239313 1 0 1 1 0 0 +EDGE2 2468 2287 -0.89362 -0.0980299 0.00983841 1 0 1 1 0 0 +EDGE2 2468 2467 -0.966431 0.0557176 0.011971 1 0 1 1 0 0 +EDGE2 2468 1247 -0.96824 0.0267242 0.0379662 1 0 1 1 0 0 +EDGE2 2468 2289 0.988754 0.0582538 -0.029575 1 0 1 1 0 0 +EDGE2 2468 1248 -0.042071 0.0304533 -0.0186119 1 0 1 1 0 0 +EDGE2 2468 2288 -0.00436854 -0.0276745 -0.00960482 1 0 1 1 0 0 +EDGE2 2468 1249 0.954185 -0.0174687 -0.0169564 1 0 1 1 0 0 +EDGE2 2469 2289 -0.026599 0.0288982 -0.0337626 1 0 1 1 0 0 +EDGE2 2469 1248 -0.979728 0.0292642 0.00217004 1 0 1 1 0 0 +EDGE2 2469 2288 -0.926431 -0.0536226 0.0191795 1 0 1 1 0 0 +EDGE2 2469 2468 -1.03523 0.0132271 0.0067361 1 0 1 1 0 0 +EDGE2 2469 1249 0.0179782 0.0600289 0.00518158 1 0 1 1 0 0 +EDGE2 2469 1250 0.916176 0.0835205 0.00538417 1 0 1 1 0 0 +EDGE2 2469 2450 0.966058 -0.05392 -3.13967 1 0 1 1 0 0 +EDGE2 2469 2290 1.08117 -0.00474052 -0.00122768 1 0 1 1 0 0 +EDGE2 2469 1230 1.03183 -0.124285 -3.15231 1 0 1 1 0 0 +EDGE2 2470 2291 -0.0265179 1.0654 1.57161 1 0 1 1 0 0 +EDGE2 2470 2289 -1.02905 0.0188213 0.024538 1 0 1 1 0 0 +EDGE2 2470 2469 -0.963831 0.0546955 0.00860828 1 0 1 1 0 0 +EDGE2 2470 2451 -0.0142006 0.981674 1.53786 1 0 1 1 0 0 +EDGE2 2470 1249 -1.00985 -0.00177242 0.017504 1 0 1 1 0 0 +EDGE2 2470 1250 -0.0999251 -0.0037764 -0.023477 1 0 1 1 0 0 +EDGE2 2470 1231 0.00355189 0.942124 1.56441 1 0 1 1 0 0 +EDGE2 2470 1251 -0.00894397 0.995255 1.59157 1 0 1 1 0 0 +EDGE2 2470 2450 0.0603909 0.0461776 -3.14104 1 0 1 1 0 0 +EDGE2 2470 2290 0.0698515 -0.0328309 0.00448352 1 0 1 1 0 0 +EDGE2 2470 1230 -0.0305628 -0.0288768 -3.12096 1 0 1 1 0 0 +EDGE2 2470 2449 1.05865 0.0273572 -3.13475 1 0 1 1 0 0 +EDGE2 2470 1229 1.0043 -0.037136 -3.13769 1 0 1 1 0 0 +EDGE2 2471 1250 -1.06464 -0.11206 1.57699 1 0 1 1 0 0 +EDGE2 2471 2450 -1.07961 -0.0388191 -1.56219 1 0 1 1 0 0 +EDGE2 2471 2470 -1.0199 0.00836507 1.54275 1 0 1 1 0 0 +EDGE2 2471 2290 -1.06196 -0.0288779 1.55501 1 0 1 1 0 0 +EDGE2 2471 1230 -1.03987 0.00207815 -1.60397 1 0 1 1 0 0 +EDGE2 2472 2471 -0.889439 0.0190064 -0.00422027 1 0 1 1 0 0 +EDGE2 2473 2472 -1.03017 -0.0333184 -0.0180904 1 0 1 1 0 0 +EDGE2 2474 2473 -0.980756 0.0866499 0.00735478 1 0 1 1 0 0 +EDGE2 2474 715 0.929689 -0.00910312 -3.15403 1 0 1 1 0 0 +EDGE2 2474 735 1.05191 -0.0818933 -3.12378 1 0 1 1 0 0 +EDGE2 2474 1215 1.03751 0.0331671 -3.10465 1 0 1 1 0 0 +EDGE2 2475 736 0.00147344 -1.0592 -1.56135 1 0 1 1 0 0 +EDGE2 2475 2474 -1.02625 -0.0749122 -0.0118502 1 0 1 1 0 0 +EDGE2 2475 715 0.000717196 0.0190149 -3.11049 1 0 1 1 0 0 +EDGE2 2475 735 -0.0626963 -0.0340428 -3.12644 1 0 1 1 0 0 +EDGE2 2475 1215 0.0704655 0.023675 -3.16168 1 0 1 1 0 0 +EDGE2 2475 734 1.01395 0.0178649 -3.13481 1 0 1 1 0 0 +EDGE2 2475 1214 1.01992 -0.0517666 -3.15565 1 0 1 1 0 0 +EDGE2 2475 714 1.05047 0.0738977 -3.1756 1 0 1 1 0 0 +EDGE2 2475 1216 0.0300292 0.992146 1.54462 1 0 1 1 0 0 +EDGE2 2475 716 0.0373169 0.975881 1.54202 1 0 1 1 0 0 +EDGE2 2476 2475 -1.03984 0.0548714 -1.5555 1 0 1 1 0 0 +EDGE2 2476 715 -1.02175 -0.0279355 1.60507 1 0 1 1 0 0 +EDGE2 2476 735 -0.972164 -0.0569087 1.59389 1 0 1 1 0 0 +EDGE2 2476 1215 -1.04293 0.0389562 1.55665 1 0 1 1 0 0 +EDGE2 2476 1216 0.0563307 0.0962234 -0.0212374 1 0 1 1 0 0 +EDGE2 2476 716 -0.0315471 0.0663383 -0.025256 1 0 1 1 0 0 +EDGE2 2476 1217 0.979977 -0.0313462 0.0233579 1 0 1 1 0 0 +EDGE2 2476 717 0.935175 -0.0178792 0.00443213 1 0 1 1 0 0 +EDGE2 2477 1218 0.958121 0.0420965 0.010652 1 0 1 1 0 0 +EDGE2 2477 1216 -0.862997 -0.00420376 0.0108962 1 0 1 1 0 0 +EDGE2 2477 2476 -1.05457 -0.0244596 0.0401448 1 0 1 1 0 0 +EDGE2 2477 716 -1.00542 -0.0189783 0.0387129 1 0 1 1 0 0 +EDGE2 2477 1217 -0.000252644 0.0576165 -0.00837067 1 0 1 1 0 0 +EDGE2 2477 717 0.0637894 0.0224021 0.0363686 1 0 1 1 0 0 +EDGE2 2477 718 1.00467 0.0555282 -0.0116255 1 0 1 1 0 0 +EDGE2 2478 1218 -0.0525964 -0.0365286 -0.00717312 1 0 1 1 0 0 +EDGE2 2478 1217 -0.943169 0.00580067 0.00466373 1 0 1 1 0 0 +EDGE2 2478 2477 -0.928911 -0.0315336 0.0269751 1 0 1 1 0 0 +EDGE2 2478 717 -0.979656 -0.0302436 0.00732679 1 0 1 1 0 0 +EDGE2 2478 718 -0.0141935 -0.0271571 -0.0453434 1 0 1 1 0 0 +EDGE2 2478 719 0.975396 0.0339999 0.0283199 1 0 1 1 0 0 +EDGE2 2478 1219 0.963476 0.0528441 0.0161497 1 0 1 1 0 0 +EDGE2 2479 1218 -1.00987 0.0850289 -0.0048297 1 0 1 1 0 0 +EDGE2 2479 2478 -0.988317 0.0117893 -0.00709539 1 0 1 1 0 0 +EDGE2 2479 718 -1.03513 0.060098 0.0340218 1 0 1 1 0 0 +EDGE2 2479 719 0.0517513 0.087432 -0.0127089 1 0 1 1 0 0 +EDGE2 2479 1219 -0.0846242 0.0806826 0.0255527 1 0 1 1 0 0 +EDGE2 2479 1220 0.99285 -0.0617586 0.00342124 1 0 1 1 0 0 +EDGE2 2479 720 1.03627 0.0693674 -0.00192939 1 0 1 1 0 0 +EDGE2 2480 2479 -1.08794 -0.00414136 -0.00433004 1 0 1 1 0 0 +EDGE2 2480 719 -0.936229 -0.0837793 0.00253693 1 0 1 1 0 0 +EDGE2 2480 1219 -0.982323 0.0615183 0.00988639 1 0 1 1 0 0 +EDGE2 2480 1221 0.00431717 1.01737 1.58493 1 0 1 1 0 0 +EDGE2 2480 1220 -0.0392929 0.00668882 -0.019205 1 0 1 1 0 0 +EDGE2 2480 720 -0.00695567 0.0267009 0.00452185 1 0 1 1 0 0 +EDGE2 2480 721 0.0125422 -1.08439 -1.57349 1 0 1 1 0 0 +EDGE2 2481 1221 -0.0573901 0.104847 0.0174605 1 0 1 1 0 0 +EDGE2 2481 1222 0.975678 0.030233 -0.0275717 1 0 1 1 0 0 +EDGE2 2481 1220 -1.01637 0.00650268 -1.55069 1 0 1 1 0 0 +EDGE2 2481 2480 -0.977448 0.0938964 -1.57041 1 0 1 1 0 0 +EDGE2 2481 720 -0.986614 -0.0658037 -1.61002 1 0 1 1 0 0 +EDGE2 2482 1221 -0.990596 -0.0544754 0.0152769 1 0 1 1 0 0 +EDGE2 2482 1223 0.995831 -0.0219377 0.0068099 1 0 1 1 0 0 +EDGE2 2482 1222 0.0253884 -0.0212053 0.0324737 1 0 1 1 0 0 +EDGE2 2482 2481 -0.986272 0.077136 -0.0346166 1 0 1 1 0 0 +EDGE2 2483 1223 -0.0794304 0.0823714 -0.0238381 1 0 1 1 0 0 +EDGE2 2483 1224 0.90496 0.00218656 -0.0385325 1 0 1 1 0 0 +EDGE2 2483 1222 -1.05074 0.0249777 -0.00272648 1 0 1 1 0 0 +EDGE2 2483 2482 -0.993703 0.0262627 0.0205647 1 0 1 1 0 0 +EDGE2 2484 1225 0.961802 -0.00756886 -0.00119496 1 0 1 1 0 0 +EDGE2 2484 2445 0.926297 0.0214852 -3.11139 1 0 1 1 0 0 +EDGE2 2484 1223 -1.02675 -0.0367805 -0.0344693 1 0 1 1 0 0 +EDGE2 2484 1224 -0.0778123 0.00881313 -0.00536896 1 0 1 1 0 0 +EDGE2 2484 2483 -0.97334 0.0595747 -0.00517111 1 0 1 1 0 0 +EDGE2 2485 2446 0.119315 1.00077 1.576 1 0 1 1 0 0 +EDGE2 2485 1226 0.0122347 0.890656 1.60708 1 0 1 1 0 0 +EDGE2 2485 2444 0.886234 -0.0532201 -3.13318 1 0 1 1 0 0 +EDGE2 2485 1225 0.00568215 0.0211364 0.0225206 1 0 1 1 0 0 +EDGE2 2485 2445 0.0382532 -0.0202548 -3.13886 1 0 1 1 0 0 +EDGE2 2485 1224 -0.938676 -0.00675635 -0.00254881 1 0 1 1 0 0 +EDGE2 2485 2484 -0.96142 -0.0287222 -0.00536899 1 0 1 1 0 0 +EDGE2 2486 1227 0.992515 -0.063337 0.00697337 1 0 1 1 0 0 +EDGE2 2486 2447 0.924073 -0.0175347 -0.0211896 1 0 1 1 0 0 +EDGE2 2486 2446 -0.0176248 -0.0227926 -0.0252118 1 0 1 1 0 0 +EDGE2 2486 1226 -0.0622366 0.0312073 0.00296691 1 0 1 1 0 0 +EDGE2 2486 1225 -1.02729 0.0225429 -1.5767 1 0 1 1 0 0 +EDGE2 2486 2485 -0.896838 0.0138736 -1.5671 1 0 1 1 0 0 +EDGE2 2486 2445 -0.901107 0.085123 1.55771 1 0 1 1 0 0 +EDGE2 2487 1228 0.998993 -0.00289293 -0.0103992 1 0 1 1 0 0 +EDGE2 2487 2448 1.02072 0.00307038 -0.0217677 1 0 1 1 0 0 +EDGE2 2487 1227 -0.0272764 0.067136 -0.0150167 1 0 1 1 0 0 +EDGE2 2487 2447 0.0688955 -0.0657161 0.00727321 1 0 1 1 0 0 +EDGE2 2487 2446 -0.975636 0.101193 0.00123297 1 0 1 1 0 0 +EDGE2 2487 2486 -0.990391 -0.0371682 -0.0366585 1 0 1 1 0 0 +EDGE2 2487 1226 -1.03953 0.0205062 0.0143818 1 0 1 1 0 0 +EDGE2 2488 2449 1.01123 -0.112808 0.0285566 1 0 1 1 0 0 +EDGE2 2488 1229 0.920304 0.0474349 0.0123575 1 0 1 1 0 0 +EDGE2 2488 1228 -0.00293741 -0.00769308 -0.00764752 1 0 1 1 0 0 +EDGE2 2488 2448 -0.023299 0.0344955 -0.000507899 1 0 1 1 0 0 +EDGE2 2488 1227 -0.937607 -0.00208332 0.0478564 1 0 1 1 0 0 +EDGE2 2488 2487 -0.994423 0.0183431 -0.000910802 1 0 1 1 0 0 +EDGE2 2488 2447 -0.996974 0.134815 -0.0328511 1 0 1 1 0 0 +EDGE2 2489 1250 0.925746 -0.0434877 -3.11485 1 0 1 1 0 0 +EDGE2 2489 2450 1.04637 -0.0314147 0.0196489 1 0 1 1 0 0 +EDGE2 2489 2470 0.984538 0.106738 -3.13465 1 0 1 1 0 0 +EDGE2 2489 2290 0.98082 -0.132981 -3.14267 1 0 1 1 0 0 +EDGE2 2489 1230 1.13251 -0.113563 0.0247474 1 0 1 1 0 0 +EDGE2 2489 2488 -1.01422 0.0659677 -0.0365073 1 0 1 1 0 0 +EDGE2 2489 2449 -0.117414 -0.0104233 -0.0009726 1 0 1 1 0 0 +EDGE2 2489 1229 0.0160146 -0.0222837 0.010008 1 0 1 1 0 0 +EDGE2 2489 1228 -0.963968 -0.0579213 0.00408479 1 0 1 1 0 0 +EDGE2 2489 2448 -0.959826 -0.0257294 0.00582599 1 0 1 1 0 0 +EDGE2 2490 2291 -0.0815478 -0.988595 -1.56397 1 0 1 1 0 0 +EDGE2 2490 2289 1.0005 -0.0390356 -3.10838 1 0 1 1 0 0 +EDGE2 2490 2469 1.00344 0.00706864 -3.13991 1 0 1 1 0 0 +EDGE2 2490 2451 0.0126962 -1.06251 -1.56701 1 0 1 1 0 0 +EDGE2 2490 1249 0.996001 0.00740308 -3.13843 1 0 1 1 0 0 +EDGE2 2490 1250 -0.0122251 0.00323796 -3.19306 1 0 1 1 0 0 +EDGE2 2490 1231 0.0106867 -1.01743 -1.56519 1 0 1 1 0 0 +EDGE2 2490 1251 0.0293263 -1.03635 -1.54525 1 0 1 1 0 0 +EDGE2 2490 2450 0.0255277 0.0145671 -0.00501698 1 0 1 1 0 0 +EDGE2 2490 2470 -0.0465992 -0.0435109 -3.12093 1 0 1 1 0 0 +EDGE2 2490 2290 -0.00487172 0.0620664 -3.12922 1 0 1 1 0 0 +EDGE2 2490 1230 -0.0639728 0.0278153 -0.033484 1 0 1 1 0 0 +EDGE2 2490 2471 -0.0875887 1.01292 1.5595 1 0 1 1 0 0 +EDGE2 2490 2449 -1.02453 -0.0404896 -0.0215441 1 0 1 1 0 0 +EDGE2 2490 2489 -0.981932 -0.0196352 0.00144499 1 0 1 1 0 0 +EDGE2 2490 1229 -1.06726 0.000659238 -0.0371268 1 0 1 1 0 0 +EDGE2 2491 2292 0.999081 -0.0440589 0.006986 1 0 1 1 0 0 +EDGE2 2491 2452 0.983193 -0.0121173 -0.0021128 1 0 1 1 0 0 +EDGE2 2491 2291 0.107276 0.0519415 0.00706722 1 0 1 1 0 0 +EDGE2 2491 1252 0.941269 0.0317396 -0.0383914 1 0 1 1 0 0 +EDGE2 2491 1232 1.04854 0.00899812 -0.00432553 1 0 1 1 0 0 +EDGE2 2491 2451 -0.0760036 0.0965045 -0.000925061 1 0 1 1 0 0 +EDGE2 2491 1250 -1.0047 0.0212972 -1.56463 1 0 1 1 0 0 +EDGE2 2491 1231 -0.0846938 0.00268349 0.0153535 1 0 1 1 0 0 +EDGE2 2491 1251 0.0615432 0.0271134 0.0160153 1 0 1 1 0 0 +EDGE2 2491 2450 -1.01749 0.0323552 1.56573 1 0 1 1 0 0 +EDGE2 2491 2470 -1.04592 -0.0538401 -1.5666 1 0 1 1 0 0 +EDGE2 2491 2490 -0.955829 0.0188591 1.56584 1 0 1 1 0 0 +EDGE2 2491 2290 -1.00047 0.0151558 -1.61503 1 0 1 1 0 0 +EDGE2 2491 1230 -1.00915 -0.0659114 1.56215 1 0 1 1 0 0 +EDGE2 2492 2292 -0.0818981 0.0461235 -0.028017 1 0 1 1 0 0 +EDGE2 2492 2293 0.961173 0.025349 -0.0441442 1 0 1 1 0 0 +EDGE2 2492 2453 1.07222 -0.0419144 -0.0329068 1 0 1 1 0 0 +EDGE2 2492 2452 -0.0105411 -0.0485417 0.0386746 1 0 1 1 0 0 +EDGE2 2492 1233 1.01286 -0.0198476 -0.0445874 1 0 1 1 0 0 +EDGE2 2492 1253 0.940619 0.0155488 -0.0337422 1 0 1 1 0 0 +EDGE2 2492 2291 -0.97452 0.0873724 0.00703009 1 0 1 1 0 0 +EDGE2 2492 1252 0.051738 0.102862 0.0423721 1 0 1 1 0 0 +EDGE2 2492 2491 -0.975882 0.0212925 0.0143899 1 0 1 1 0 0 +EDGE2 2492 1232 -0.0608478 0.00964225 0.0309385 1 0 1 1 0 0 +EDGE2 2492 2451 -0.981117 -0.132549 0.0214689 1 0 1 1 0 0 +EDGE2 2492 1231 -0.87324 -0.055265 -0.00173 1 0 1 1 0 0 +EDGE2 2492 1251 -0.99265 -0.019842 0.0253757 1 0 1 1 0 0 +EDGE2 2493 2292 -0.988664 0.0602414 0.0152766 1 0 1 1 0 0 +EDGE2 2493 2293 -0.0399292 0.0662848 -0.0307655 1 0 1 1 0 0 +EDGE2 2493 1254 0.837918 -0.032209 0.0284855 1 0 1 1 0 0 +EDGE2 2493 2454 0.903236 0.00134121 0.000287183 1 0 1 1 0 0 +EDGE2 2493 2294 1.03821 -0.0128005 0.00881732 1 0 1 1 0 0 +EDGE2 2493 1234 0.961214 0.0595532 0.00845709 1 0 1 1 0 0 +EDGE2 2493 2453 0.0316429 -0.0294459 -0.0348476 1 0 1 1 0 0 +EDGE2 2493 2452 -1.06128 0.00553693 0.0058088 1 0 1 1 0 0 +EDGE2 2493 1233 0.0790159 0.0384073 0.0266143 1 0 1 1 0 0 +EDGE2 2493 1253 -0.00148797 -0.00471323 -0.000684766 1 0 1 1 0 0 +EDGE2 2493 2492 -0.973879 0.0234084 0.0645466 1 0 1 1 0 0 +EDGE2 2493 1252 -1.05818 0.00934411 0.00523452 1 0 1 1 0 0 +EDGE2 2493 1232 -1.08531 0.0462407 0.0286438 1 0 1 1 0 0 +EDGE2 2494 2293 -0.991589 -0.0416281 0.00310954 1 0 1 1 0 0 +EDGE2 2494 1235 0.979968 -0.0442858 0.0475402 1 0 1 1 0 0 +EDGE2 2494 2455 1.01539 0.0474379 -0.010912 1 0 1 1 0 0 +EDGE2 2494 2295 0.92655 0.0115923 -0.00228973 1 0 1 1 0 0 +EDGE2 2494 2415 0.979015 -0.096093 -3.16707 1 0 1 1 0 0 +EDGE2 2494 2435 1.04852 0.0282475 -3.12007 1 0 1 1 0 0 +EDGE2 2494 1255 0.983514 -0.0796659 -0.0349713 1 0 1 1 0 0 +EDGE2 2494 1254 -0.0325755 -0.114095 0.0255199 1 0 1 1 0 0 +EDGE2 2494 2454 0.0499014 -0.00100106 -0.00556805 1 0 1 1 0 0 +EDGE2 2494 2294 -0.0635404 0.050901 -0.0078307 1 0 1 1 0 0 +EDGE2 2494 2493 -0.95561 -0.0126884 -0.00925269 1 0 1 1 0 0 +EDGE2 2494 1234 -0.0041525 0.0596515 0.0187137 1 0 1 1 0 0 +EDGE2 2494 2453 -1.02201 -0.0204926 0.0362133 1 0 1 1 0 0 +EDGE2 2494 1233 -0.897005 0.041334 0.00135658 1 0 1 1 0 0 +EDGE2 2494 1253 -0.922822 -0.0467016 0.00783151 1 0 1 1 0 0 +EDGE2 2495 2416 -0.0333389 -0.97667 -1.56996 1 0 1 1 0 0 +EDGE2 2495 2456 -0.0944812 1.01079 1.5729 1 0 1 1 0 0 +EDGE2 2495 1236 0.0499369 1.11684 1.60418 1 0 1 1 0 0 +EDGE2 2495 2414 1.02241 0.0327369 -3.1473 1 0 1 1 0 0 +EDGE2 2495 2434 0.99978 0.0095414 -3.12001 1 0 1 1 0 0 +EDGE2 2495 1235 0.0112018 -0.0601681 0.0135669 1 0 1 1 0 0 +EDGE2 2495 2455 0.0455502 0.0580823 -0.0121326 1 0 1 1 0 0 +EDGE2 2495 2295 -0.00191591 0.00370641 -0.0165951 1 0 1 1 0 0 +EDGE2 2495 2415 0.0946108 0.0652089 -3.13637 1 0 1 1 0 0 +EDGE2 2495 2435 0.0200504 -0.0315489 -3.14972 1 0 1 1 0 0 +EDGE2 2495 1255 0.106075 -0.0763725 0.0085197 1 0 1 1 0 0 +EDGE2 2495 1254 -0.963008 -0.0947342 -0.00557743 1 0 1 1 0 0 +EDGE2 2495 2454 -0.926628 0.0103464 0.0158661 1 0 1 1 0 0 +EDGE2 2495 2494 -1.04963 0.0154624 0.0461673 1 0 1 1 0 0 +EDGE2 2495 2294 -0.970234 0.00141385 -0.00790221 1 0 1 1 0 0 +EDGE2 2495 1234 -1.07515 0.0185639 -0.0121964 1 0 1 1 0 0 +EDGE2 2495 2436 0.0531943 -1.04021 -1.55688 1 0 1 1 0 0 +EDGE2 2495 1256 -0.0261737 -1.08359 -1.54873 1 0 1 1 0 0 +EDGE2 2495 2296 -0.0278137 -0.993164 -1.58672 1 0 1 1 0 0 +EDGE2 2496 2416 -0.0438322 -0.00125263 -0.0321816 1 0 1 1 0 0 +EDGE2 2496 1235 -1.08908 -0.103236 1.56325 1 0 1 1 0 0 +EDGE2 2496 2455 -1.02439 -0.0610698 1.55864 1 0 1 1 0 0 +EDGE2 2496 2495 -1.00168 -0.0254712 1.56978 1 0 1 1 0 0 +EDGE2 2496 2295 -0.96866 -0.0286932 1.57735 1 0 1 1 0 0 +EDGE2 2496 2415 -1.00724 0.0158309 -1.59217 1 0 1 1 0 0 +EDGE2 2496 2435 -0.917728 0.0102536 -1.54309 1 0 1 1 0 0 +EDGE2 2496 1255 -0.962474 0.00533476 1.58137 1 0 1 1 0 0 +EDGE2 2496 2436 -0.0775357 0.0620691 0.0173981 1 0 1 1 0 0 +EDGE2 2496 1256 -0.0345089 -0.00838532 0.0113818 1 0 1 1 0 0 +EDGE2 2496 2296 -0.0108089 0.030445 -0.00154132 1 0 1 1 0 0 +EDGE2 2496 2297 0.963673 -0.047619 0.00258712 1 0 1 1 0 0 +EDGE2 2496 2417 1.01719 0.0425751 0.00140913 1 0 1 1 0 0 +EDGE2 2496 2437 1.02815 -0.0330312 0.00278958 1 0 1 1 0 0 +EDGE2 2496 1257 0.998982 0.0369014 -0.00845543 1 0 1 1 0 0 +EDGE2 2497 2416 -0.961855 0.020249 0.0133226 1 0 1 1 0 0 +EDGE2 2497 2496 -1.05742 0.0579792 -0.0201813 1 0 1 1 0 0 +EDGE2 2497 2436 -1.01636 0.0291184 -0.0293915 1 0 1 1 0 0 +EDGE2 2497 1256 -0.983578 0.0583248 0.00799599 1 0 1 1 0 0 +EDGE2 2497 2296 -0.968691 0.0747911 -0.0132624 1 0 1 1 0 0 +EDGE2 2497 2297 0.0426795 -0.0277162 -0.0300862 1 0 1 1 0 0 +EDGE2 2497 2417 0.0727245 -0.00668208 -0.021636 1 0 1 1 0 0 +EDGE2 2497 2437 -0.0583058 0.0215306 -0.0126943 1 0 1 1 0 0 +EDGE2 2497 1257 0.0214934 -0.0458827 -0.0224576 1 0 1 1 0 0 +EDGE2 2497 2298 0.996853 -0.0660222 -0.0128428 1 0 1 1 0 0 +EDGE2 2497 2418 1.001 0.0223373 -0.0171756 1 0 1 1 0 0 +EDGE2 2497 2438 1.01607 0.0201441 0.0228104 1 0 1 1 0 0 +EDGE2 2497 1258 0.996873 0.0872509 -0.00920578 1 0 1 1 0 0 +EDGE2 2498 2497 -0.984644 -0.126086 -0.00262801 1 0 1 1 0 0 +EDGE2 2498 2297 -0.923131 -0.0623348 0.0105756 1 0 1 1 0 0 +EDGE2 2498 2417 -1.04817 0.0185815 -0.00348238 1 0 1 1 0 0 +EDGE2 2498 2437 -1.08375 0.0102112 0.0227587 1 0 1 1 0 0 +EDGE2 2498 1257 -1.03089 0.014439 0.00838597 1 0 1 1 0 0 +EDGE2 2498 2298 0.00817686 0.0307305 -0.0164789 1 0 1 1 0 0 +EDGE2 2498 2418 -0.0300935 0.0246417 0.000745748 1 0 1 1 0 0 +EDGE2 2498 2438 0.0309457 -0.00636765 -0.0345891 1 0 1 1 0 0 +EDGE2 2498 1258 -0.0423187 0.0482152 0.0328184 1 0 1 1 0 0 +EDGE2 2498 2299 1.03955 0.0146232 -0.0158202 1 0 1 1 0 0 +EDGE2 2498 2419 0.981553 -0.00317462 0.00728133 1 0 1 1 0 0 +EDGE2 2498 2439 0.946619 -0.0227201 0.00608471 1 0 1 1 0 0 +EDGE2 2498 1259 1.00252 -0.076281 0.0195976 1 0 1 1 0 0 +EDGE2 2499 2498 -1.04556 -0.00396939 0.0126523 1 0 1 1 0 0 +EDGE2 2499 2298 -0.95427 0.0523002 -0.0367787 1 0 1 1 0 0 +EDGE2 2499 2418 -1.00302 0.00801322 -0.011055 1 0 1 1 0 0 +EDGE2 2499 2438 -1.04815 0.0640604 0.0201783 1 0 1 1 0 0 +EDGE2 2499 1258 -0.970397 -0.0473459 0.00766455 1 0 1 1 0 0 +EDGE2 2499 2299 -0.00588154 0.00815253 -0.00921315 1 0 1 1 0 0 +EDGE2 2499 2419 -0.0494285 -0.0130961 0.000109346 1 0 1 1 0 0 +EDGE2 2499 2439 0.0418413 -0.0736902 0.0183071 1 0 1 1 0 0 +EDGE2 2499 1259 -0.0928285 0.0330261 0.0125738 1 0 1 1 0 0 +EDGE2 2499 2420 0.922857 0.0146453 0.0276947 1 0 1 1 0 0 +EDGE2 2499 2440 1.04895 -0.0592561 0.00738374 1 0 1 1 0 0 +EDGE2 2499 2300 1.03906 0.0215838 -0.00245603 1 0 1 1 0 0 +EDGE2 2499 1260 1.01951 0.0224558 0.00388594 1 0 1 1 0 0 +EDGE2 2500 2441 -0.0204381 -0.941463 -1.58059 1 0 1 1 0 0 +EDGE2 2500 2301 -0.0566379 0.979697 1.54812 1 0 1 1 0 0 +EDGE2 2500 2421 -0.0463217 1.05902 1.53683 1 0 1 1 0 0 +EDGE2 2500 1261 0.0787511 0.948901 1.54998 1 0 1 1 0 0 +EDGE2 2500 2499 -1.05517 -0.0405942 0.0106244 1 0 1 1 0 0 +EDGE2 2500 2299 -1.03401 0.0211384 0.000277897 1 0 1 1 0 0 +EDGE2 2500 2419 -1.0595 -0.0294704 -0.00121702 1 0 1 1 0 0 +EDGE2 2500 2439 -1.01454 -0.0014686 0.00525789 1 0 1 1 0 0 +EDGE2 2500 1259 -0.960102 0.101747 -0.0254703 1 0 1 1 0 0 +EDGE2 2500 2420 0.00417434 -0.000539614 -0.0184175 1 0 1 1 0 0 +EDGE2 2500 2440 -0.0587183 -0.0476058 0.023175 1 0 1 1 0 0 +EDGE2 2500 2300 0.0295344 -0.0230555 -0.00497462 1 0 1 1 0 0 +EDGE2 2500 1260 0.02078 0.00214727 -0.00872958 1 0 1 1 0 0 +EDGE2 2501 2441 0.0767531 0.00907741 0.0178406 1 0 1 1 0 0 +EDGE2 2501 2420 -0.958467 -0.0392126 1.6067 1 0 1 1 0 0 +EDGE2 2501 2500 -0.905136 -0.0299385 1.57477 1 0 1 1 0 0 +EDGE2 2501 2440 -0.990077 0.0577003 1.56923 1 0 1 1 0 0 +EDGE2 2501 2300 -1.03857 -0.120893 1.56491 1 0 1 1 0 0 +EDGE2 2501 1260 -1.0297 -0.0304566 1.57153 1 0 1 1 0 0 +EDGE2 2501 2442 0.973274 0.00331883 -0.0428233 1 0 1 1 0 0 +EDGE2 2502 2441 -0.910892 -0.0244066 0.0148042 1 0 1 1 0 0 +EDGE2 2502 2501 -0.982969 0.00176451 -0.033908 1 0 1 1 0 0 +EDGE2 2502 2443 0.949689 0.00313332 -0.0150407 1 0 1 1 0 0 +EDGE2 2502 2442 -0.0140305 0.0265597 0.0119586 1 0 1 1 0 0 +EDGE2 2503 2443 0.0387641 0.0693209 0.0200612 1 0 1 1 0 0 +EDGE2 2503 2442 -0.946838 0.0174961 0.0133181 1 0 1 1 0 0 +EDGE2 2503 2502 -0.956086 -0.00670747 0.0598263 1 0 1 1 0 0 +EDGE2 2503 2444 1.09585 0.108842 -0.000302232 1 0 1 1 0 0 +EDGE2 2504 2443 -1.05342 -0.0463295 -0.0208915 1 0 1 1 0 0 +EDGE2 2504 2503 -0.960115 0.0312214 -0.0192505 1 0 1 1 0 0 +EDGE2 2504 2444 -0.0452337 -0.047608 0.0173467 1 0 1 1 0 0 +EDGE2 2504 1225 1.02839 -0.0407784 -3.13166 1 0 1 1 0 0 +EDGE2 2504 2485 0.974257 -0.082864 -3.12407 1 0 1 1 0 0 +EDGE2 2504 2445 0.97845 -0.022487 0.0466163 1 0 1 1 0 0 +EDGE2 2505 2446 -0.0557702 -1.01314 -1.5661 1 0 1 1 0 0 +EDGE2 2505 2486 0.053055 -0.978868 -1.5813 1 0 1 1 0 0 +EDGE2 2505 1226 -0.0220142 -1.00726 -1.55046 1 0 1 1 0 0 +EDGE2 2505 2444 -1.02226 -0.00575924 -0.00459313 1 0 1 1 0 0 +EDGE2 2505 2504 -1.04719 -0.081742 0.00614273 1 0 1 1 0 0 +EDGE2 2505 1225 -0.0384154 0.00429214 -3.17959 1 0 1 1 0 0 +EDGE2 2505 2485 -0.000401938 -0.0259913 -3.14569 1 0 1 1 0 0 +EDGE2 2505 2445 0.013804 0.010537 -0.0415617 1 0 1 1 0 0 +EDGE2 2505 1224 0.973081 -0.0292651 -3.13565 1 0 1 1 0 0 +EDGE2 2505 2484 1.00801 0.0388086 -3.13315 1 0 1 1 0 0 +EDGE2 2506 1225 -0.962832 -0.00777461 1.61098 1 0 1 1 0 0 +EDGE2 2506 2485 -0.975805 -0.0108983 1.58567 1 0 1 1 0 0 +EDGE2 2506 2505 -1.10891 -0.0303371 -1.58696 1 0 1 1 0 0 +EDGE2 2506 2445 -1.02 -0.0117353 -1.55316 1 0 1 1 0 0 +EDGE2 2507 2506 -0.935171 -0.0281697 -0.0110743 1 0 1 1 0 0 +EDGE2 2508 2507 -1.03633 0.000419304 0.031771 1 0 1 1 0 0 +EDGE2 2509 2508 -0.959097 -0.0379371 0.00534489 1 0 1 1 0 0 +EDGE2 2510 2509 -1.00315 -0.0392183 -0.0062275 1 0 1 1 0 0 +EDGE2 2511 2510 -1.07157 0.0595082 -1.58634 1 0 1 1 0 0 +EDGE2 2512 2511 -0.9191 0.0492141 0.022253 1 0 1 1 0 0 +EDGE2 2513 2512 -0.998167 0.0558812 -0.00241926 1 0 1 1 0 0 +EDGE2 2514 1295 0.94274 -0.0753611 -3.15892 1 0 1 1 0 0 +EDGE2 2514 1275 1.05341 -0.0158355 -3.15252 1 0 1 1 0 0 +EDGE2 2514 2513 -0.980155 -0.0588873 0.00602629 1 0 1 1 0 0 +EDGE2 2515 1274 0.959218 -0.00498217 -3.16323 1 0 1 1 0 0 +EDGE2 2515 1294 0.958651 0.0232793 -3.12705 1 0 1 1 0 0 +EDGE2 2515 1295 -0.0160574 -0.0730153 -3.14522 1 0 1 1 0 0 +EDGE2 2515 1275 -0.0646171 0.0888208 -3.11461 1 0 1 1 0 0 +EDGE2 2515 2514 -1.07125 0.00654499 0.0200356 1 0 1 1 0 0 +EDGE2 2515 1296 0.0276212 -0.953394 -1.54414 1 0 1 1 0 0 +EDGE2 2515 1276 0.0331039 -1.05162 -1.53908 1 0 1 1 0 0 +EDGE2 2516 1295 -1.02443 -0.0728775 1.59655 1 0 1 1 0 0 +EDGE2 2516 2515 -0.997237 0.00104503 -1.5882 1 0 1 1 0 0 +EDGE2 2516 1275 -0.967647 0.0197916 1.59604 1 0 1 1 0 0 +EDGE2 2517 2516 -0.975442 -0.0342579 0.0271175 1 0 1 1 0 0 +EDGE2 2518 2517 -0.915198 -0.0580817 0.00876991 1 0 1 1 0 0 +EDGE2 2519 2420 1.00232 0.0312008 -3.12876 1 0 1 1 0 0 +EDGE2 2519 2500 1.03786 0.0326398 -3.15348 1 0 1 1 0 0 +EDGE2 2519 2440 0.920838 0.0546179 -3.13435 1 0 1 1 0 0 +EDGE2 2519 2300 0.987055 0.0263861 -3.17362 1 0 1 1 0 0 +EDGE2 2519 1260 0.96422 -0.0960264 -3.13388 1 0 1 1 0 0 +EDGE2 2519 2518 -0.953204 0.0342608 0.0503007 1 0 1 1 0 0 +EDGE2 2520 2441 0.000885963 1.0848 1.56367 1 0 1 1 0 0 +EDGE2 2520 2301 -0.0295547 -0.98153 -1.57873 1 0 1 1 0 0 +EDGE2 2520 2421 -0.0288586 -0.959257 -1.60231 1 0 1 1 0 0 +EDGE2 2520 1261 0.0168255 -0.870965 -1.53687 1 0 1 1 0 0 +EDGE2 2520 2499 0.922375 0.0167465 -3.14178 1 0 1 1 0 0 +EDGE2 2520 2299 0.943922 0.0179561 -3.11377 1 0 1 1 0 0 +EDGE2 2520 2419 1.0324 -0.0379954 -3.1328 1 0 1 1 0 0 +EDGE2 2520 2439 1.06963 0.0505573 -3.10985 1 0 1 1 0 0 +EDGE2 2520 1259 0.949507 0.084914 -3.1461 1 0 1 1 0 0 +EDGE2 2520 2420 0.00893668 0.064712 -3.13887 1 0 1 1 0 0 +EDGE2 2520 2500 -0.0754503 -0.0710023 -3.17293 1 0 1 1 0 0 +EDGE2 2520 2440 -0.0620527 -0.0148075 -3.15322 1 0 1 1 0 0 +EDGE2 2520 2300 -0.0368951 0.0133933 -3.15318 1 0 1 1 0 0 +EDGE2 2520 1260 -0.0229471 0.0680788 -3.12392 1 0 1 1 0 0 +EDGE2 2520 2501 -0.0531934 1.00199 1.55112 1 0 1 1 0 0 +EDGE2 2520 2519 -0.9985 0.0114741 -0.0255686 1 0 1 1 0 0 +EDGE2 2521 2302 0.969007 -0.168129 0.00432846 1 0 1 1 0 0 +EDGE2 2521 2422 1.0642 0.0724632 -0.0307748 1 0 1 1 0 0 +EDGE2 2521 1262 0.963907 0.0545465 0.0197306 1 0 1 1 0 0 +EDGE2 2521 2301 0.0142676 0.0465934 -0.0348275 1 0 1 1 0 0 +EDGE2 2521 2421 0.0558902 0.0345354 0.00674918 1 0 1 1 0 0 +EDGE2 2521 1261 -0.061545 0.0472601 -0.0171532 1 0 1 1 0 0 +EDGE2 2521 2420 -1.01258 -0.0238011 -1.56557 1 0 1 1 0 0 +EDGE2 2521 2500 -1.02382 0.035958 -1.57962 1 0 1 1 0 0 +EDGE2 2521 2520 -1.03069 -0.00358348 1.5585 1 0 1 1 0 0 +EDGE2 2521 2440 -0.946521 0.0571982 -1.56613 1 0 1 1 0 0 +EDGE2 2521 2300 -0.99667 -0.0353976 -1.55874 1 0 1 1 0 0 +EDGE2 2521 1260 -0.986892 -0.0386437 -1.56481 1 0 1 1 0 0 +EDGE2 2522 2302 -0.0399922 0.0334934 -0.0323487 1 0 1 1 0 0 +EDGE2 2522 2303 0.991362 0.107688 -0.00313956 1 0 1 1 0 0 +EDGE2 2522 2423 1.0196 -0.08717 0.00830188 1 0 1 1 0 0 +EDGE2 2522 1263 0.935859 0.0469635 0.00569803 1 0 1 1 0 0 +EDGE2 2522 2422 0.0377263 0.0716299 0.0158464 1 0 1 1 0 0 +EDGE2 2522 2521 -1.00528 -0.0543831 0.0410933 1 0 1 1 0 0 +EDGE2 2522 1262 -0.0159265 -0.0573769 9.69697e-05 1 0 1 1 0 0 +EDGE2 2522 2301 -0.969014 0.0613393 -0.0129794 1 0 1 1 0 0 +EDGE2 2522 2421 -1.01986 -0.00950435 -0.00872108 1 0 1 1 0 0 +EDGE2 2522 1261 -0.995316 0.0332309 0.0339808 1 0 1 1 0 0 +EDGE2 2523 2424 1.04371 -0.00664775 0.0342744 1 0 1 1 0 0 +EDGE2 2523 1264 1.00904 -0.0591245 0.00929289 1 0 1 1 0 0 +EDGE2 2523 2304 0.998223 0.00984897 0.0203282 1 0 1 1 0 0 +EDGE2 2523 2302 -1.04307 0.0365811 -0.00166842 1 0 1 1 0 0 +EDGE2 2523 2303 0.0960928 -0.0379724 -0.0223532 1 0 1 1 0 0 +EDGE2 2523 2423 0.0333925 0.027225 0.0223292 1 0 1 1 0 0 +EDGE2 2523 1263 0.0379532 -0.057563 0.00109589 1 0 1 1 0 0 +EDGE2 2523 2522 -0.895364 0.0471555 -0.0384403 1 0 1 1 0 0 +EDGE2 2523 2422 -1.00854 0.0299381 0.00650282 1 0 1 1 0 0 +EDGE2 2523 1262 -0.941862 -0.0593972 0.0290586 1 0 1 1 0 0 +EDGE2 2524 1265 1.0564 0.0213522 -0.00104654 1 0 1 1 0 0 +EDGE2 2524 2305 0.979921 -0.0744142 0.0174935 1 0 1 1 0 0 +EDGE2 2524 2405 1.04929 -0.0160213 -3.17292 1 0 1 1 0 0 +EDGE2 2524 2425 0.944662 0.0202194 -6.30652e-05 1 0 1 1 0 0 +EDGE2 2524 2385 1.03047 0.042326 -3.12018 1 0 1 1 0 0 +EDGE2 2524 1565 0.962697 -0.0728722 -3.15177 1 0 1 1 0 0 +EDGE2 2524 1585 0.998169 0.0253096 -3.10491 1 0 1 1 0 0 +EDGE2 2524 1845 1.02656 -0.0088568 -3.14805 1 0 1 1 0 0 +EDGE2 2524 1545 1.00667 0.0154092 -3.17508 1 0 1 1 0 0 +EDGE2 2524 2424 0.0398784 -0.0549014 0.0251599 1 0 1 1 0 0 +EDGE2 2524 1264 0.0586502 -0.00130365 0.015366 1 0 1 1 0 0 +EDGE2 2524 2304 0.0700342 0.0294717 0.0199496 1 0 1 1 0 0 +EDGE2 2524 2303 -0.981673 0.029065 0.00328903 1 0 1 1 0 0 +EDGE2 2524 2423 -1.0257 0.0664421 0.0235911 1 0 1 1 0 0 +EDGE2 2524 2523 -1.02936 0.049426 -0.0291203 1 0 1 1 0 0 +EDGE2 2524 1263 -0.963215 0.050038 -0.0064925 1 0 1 1 0 0 +EDGE2 2525 1564 1.06559 0.0465515 -3.11279 1 0 1 1 0 0 +EDGE2 2525 1844 0.986376 -0.0485117 -3.12913 1 0 1 1 0 0 +EDGE2 2525 2384 1.01408 -0.0183881 -3.16427 1 0 1 1 0 0 +EDGE2 2525 2404 1.00302 0.0324275 -3.18349 1 0 1 1 0 0 +EDGE2 2525 1584 0.975625 0.0670827 -3.10773 1 0 1 1 0 0 +EDGE2 2525 1544 1.02735 0.00238341 -3.11108 1 0 1 1 0 0 +EDGE2 2525 2426 -0.023842 1.08184 1.58685 1 0 1 1 0 0 +EDGE2 2525 2406 0.0231333 0.997744 1.57446 1 0 1 1 0 0 +EDGE2 2525 1546 0.0244219 0.95249 1.56022 1 0 1 1 0 0 +EDGE2 2525 1265 -0.0358195 0.0359892 0.00751866 1 0 1 1 0 0 +EDGE2 2525 2305 -0.0969857 0.0829672 -0.0036106 1 0 1 1 0 0 +EDGE2 2525 2405 0.0422103 -0.026605 -3.15369 1 0 1 1 0 0 +EDGE2 2525 2425 -0.0446868 -0.0418935 -0.0198441 1 0 1 1 0 0 +EDGE2 2525 2385 0.0246905 0.0433878 -3.12412 1 0 1 1 0 0 +EDGE2 2525 1565 0.052921 -0.00504012 -3.2072 1 0 1 1 0 0 +EDGE2 2525 1585 -0.0215646 0.0182975 -3.14932 1 0 1 1 0 0 +EDGE2 2525 1845 -0.0479125 0.0763477 -3.18055 1 0 1 1 0 0 +EDGE2 2525 1545 -0.0628887 0.0446983 -3.13842 1 0 1 1 0 0 +EDGE2 2525 2424 -1.02742 0.0303971 -0.0357175 1 0 1 1 0 0 +EDGE2 2525 2524 -0.923388 -0.039765 -0.0166953 1 0 1 1 0 0 +EDGE2 2525 1264 -1.02784 0.0111519 -0.00389098 1 0 1 1 0 0 +EDGE2 2525 2304 -1.00542 0.0870596 -0.0103345 1 0 1 1 0 0 +EDGE2 2525 1566 0.0613972 -0.935593 -1.55076 1 0 1 1 0 0 +EDGE2 2525 1846 -0.0315683 -0.994234 -1.58921 1 0 1 1 0 0 +EDGE2 2525 2306 0.0714461 -1.02885 -1.57363 1 0 1 1 0 0 +EDGE2 2525 2386 -0.035311 -0.971967 -1.57689 1 0 1 1 0 0 +EDGE2 2525 1586 -0.118207 -1.01825 -1.53365 1 0 1 1 0 0 +EDGE2 2525 1266 -0.0298252 -0.979997 -1.56856 1 0 1 1 0 0 +EDGE2 2526 2426 0.00536219 -0.0936933 -0.00815851 1 0 1 1 0 0 +EDGE2 2526 1547 1.05557 0.0331423 0.0208593 1 0 1 1 0 0 +EDGE2 2526 2427 0.962867 -0.0143474 0.00790015 1 0 1 1 0 0 +EDGE2 2526 2407 1.00948 0.0945251 0.0291731 1 0 1 1 0 0 +EDGE2 2526 2406 -0.140303 -0.025931 -0.0393037 1 0 1 1 0 0 +EDGE2 2526 1546 0.0125734 0.113547 -0.0222479 1 0 1 1 0 0 +EDGE2 2526 1265 -1.10093 -0.0305387 -1.56903 1 0 1 1 0 0 +EDGE2 2526 2305 -0.978914 -0.05584 -1.55237 1 0 1 1 0 0 +EDGE2 2526 2405 -1.07259 0.00611699 1.55093 1 0 1 1 0 0 +EDGE2 2526 2425 -1.04757 -0.0729928 -1.57655 1 0 1 1 0 0 +EDGE2 2526 2525 -1.02215 0.0427627 -1.56639 1 0 1 1 0 0 +EDGE2 2526 2385 -0.965914 -0.00541304 1.54918 1 0 1 1 0 0 +EDGE2 2526 1565 -1.0053 0.0273969 1.55978 1 0 1 1 0 0 +EDGE2 2526 1585 -0.958835 0.0418304 1.55921 1 0 1 1 0 0 +EDGE2 2526 1845 -0.996947 -0.13886 1.56141 1 0 1 1 0 0 +EDGE2 2526 1545 -0.862615 0.0814423 1.56711 1 0 1 1 0 0 +EDGE2 2527 1548 0.935046 0.0160518 -0.0508905 1 0 1 1 0 0 +EDGE2 2527 2408 1.01193 0.00961778 -0.00168979 1 0 1 1 0 0 +EDGE2 2527 2428 0.961502 0.175653 0.0179969 1 0 1 1 0 0 +EDGE2 2527 2426 -1.08249 -0.00211407 -0.0074917 1 0 1 1 0 0 +EDGE2 2527 1547 0.0701254 0.0280005 0.0107875 1 0 1 1 0 0 +EDGE2 2527 2427 -0.0365004 0.072244 -0.00806596 1 0 1 1 0 0 +EDGE2 2527 2407 -0.1015 -0.0333849 -0.0134653 1 0 1 1 0 0 +EDGE2 2527 2526 -0.944064 -0.0693983 -0.0150362 1 0 1 1 0 0 +EDGE2 2527 2406 -1.00979 0.0357484 -0.0220913 1 0 1 1 0 0 +EDGE2 2527 1546 -1.01777 -0.142287 -0.0371222 1 0 1 1 0 0 +EDGE2 2528 2429 1.03261 -0.011533 -0.039673 1 0 1 1 0 0 +EDGE2 2528 1549 1.0378 -0.0544313 0.0102832 1 0 1 1 0 0 +EDGE2 2528 2409 0.942064 -0.0730588 -0.0252771 1 0 1 1 0 0 +EDGE2 2528 1548 0.00356724 0.00537635 0.00665763 1 0 1 1 0 0 +EDGE2 2528 2408 0.0324397 -0.0220223 -0.0142768 1 0 1 1 0 0 +EDGE2 2528 2428 0.0178507 0.00402848 0.00876093 1 0 1 1 0 0 +EDGE2 2528 1547 -1.0378 -0.0140383 0.0216043 1 0 1 1 0 0 +EDGE2 2528 2427 -0.940561 -0.0788959 0.0164 1 0 1 1 0 0 +EDGE2 2528 2527 -0.990156 0.00473824 0.0234642 1 0 1 1 0 0 +EDGE2 2528 2407 -0.924862 -0.00468669 0.023436 1 0 1 1 0 0 +EDGE2 2529 2430 0.939773 -0.0649991 0.0327481 1 0 1 1 0 0 +EDGE2 2529 1550 0.939344 -0.0539372 -0.00431655 1 0 1 1 0 0 +EDGE2 2529 1830 1.00973 -0.0671934 -3.14046 1 0 1 1 0 0 +EDGE2 2529 2410 0.94045 -0.0038669 0.0276709 1 0 1 1 0 0 +EDGE2 2529 2429 0.0444077 0.0190917 -0.038191 1 0 1 1 0 0 +EDGE2 2529 1549 -0.00622704 0.0183899 -0.0259082 1 0 1 1 0 0 +EDGE2 2529 2409 0.0294469 0.0342799 0.00275305 1 0 1 1 0 0 +EDGE2 2529 2528 -1.05081 -0.0164341 0.00673551 1 0 1 1 0 0 +EDGE2 2529 1548 -1.04945 -0.0562202 -0.021776 1 0 1 1 0 0 +EDGE2 2529 2408 -1.02256 -0.0766646 0.00118813 1 0 1 1 0 0 +EDGE2 2529 2428 -0.971646 -0.00336716 0.0307367 1 0 1 1 0 0 +EDGE2 2530 1829 0.985591 0.0138528 -3.16688 1 0 1 1 0 0 +EDGE2 2530 1831 0.038606 -1.03797 -1.57414 1 0 1 1 0 0 +EDGE2 2530 1551 0.0213209 -1.00991 -1.57886 1 0 1 1 0 0 +EDGE2 2530 2411 0.0265975 1.06069 1.55848 1 0 1 1 0 0 +EDGE2 2530 2430 -0.014938 0.0287302 -0.013417 1 0 1 1 0 0 +EDGE2 2530 1550 -0.0854952 -0.0489979 0.0120129 1 0 1 1 0 0 +EDGE2 2530 1830 -0.0187366 0.11272 -3.1405 1 0 1 1 0 0 +EDGE2 2530 2410 -0.0403252 -0.00563314 -0.00767995 1 0 1 1 0 0 +EDGE2 2530 2431 0.0322249 0.982769 1.59818 1 0 1 1 0 0 +EDGE2 2530 2429 -0.976376 -0.0681596 -0.00357574 1 0 1 1 0 0 +EDGE2 2530 2529 -0.935767 -0.0233605 0.0228083 1 0 1 1 0 0 +EDGE2 2530 1549 -0.988511 0.0269612 0.017382 1 0 1 1 0 0 +EDGE2 2530 2409 -1.00664 0.0804799 0.00989624 1 0 1 1 0 0 +EDGE2 2531 2411 0.0801105 0.026742 -0.00345957 1 0 1 1 0 0 +EDGE2 2531 2430 -1.0688 -0.0414971 -1.59202 1 0 1 1 0 0 +EDGE2 2531 2530 -1.07305 0.036246 -1.59968 1 0 1 1 0 0 +EDGE2 2531 1550 -1.07636 -0.00525978 -1.59391 1 0 1 1 0 0 +EDGE2 2531 1830 -1.0114 0.0310442 1.6021 1 0 1 1 0 0 +EDGE2 2531 2410 -0.986356 -0.0385374 -1.55221 1 0 1 1 0 0 +EDGE2 2531 2431 -0.0548192 -0.0503457 -0.00671817 1 0 1 1 0 0 +EDGE2 2531 2432 1.03192 0.0470551 -0.00285137 1 0 1 1 0 0 +EDGE2 2531 2412 0.999972 -0.0112164 0.0212846 1 0 1 1 0 0 +EDGE2 2532 2411 -0.929686 0.0019451 -0.0105601 1 0 1 1 0 0 +EDGE2 2532 2531 -1.07393 0.0622535 0.00876766 1 0 1 1 0 0 +EDGE2 2532 2431 -0.995439 -0.0168227 -0.0148668 1 0 1 1 0 0 +EDGE2 2532 2432 0.00843602 0.060993 0.000853454 1 0 1 1 0 0 +EDGE2 2532 2412 -0.0333574 -0.0502596 -0.0159046 1 0 1 1 0 0 +EDGE2 2532 2413 1.02546 -0.0316741 0.0104829 1 0 1 1 0 0 +EDGE2 2532 2433 0.902287 0.0325522 -0.0269173 1 0 1 1 0 0 +EDGE2 2533 2432 -0.998546 0.0115883 0.0104405 1 0 1 1 0 0 +EDGE2 2533 2532 -0.978018 -0.0470591 0.00657349 1 0 1 1 0 0 +EDGE2 2533 2412 -0.953539 -0.00957438 -0.0398165 1 0 1 1 0 0 +EDGE2 2533 2413 0.0447039 0.0484397 -0.0201544 1 0 1 1 0 0 +EDGE2 2533 2433 -0.0026756 0.0250937 0.00625509 1 0 1 1 0 0 +EDGE2 2533 2414 0.957415 -0.107043 0.00479517 1 0 1 1 0 0 +EDGE2 2533 2434 1.02317 -0.0303433 -0.00520236 1 0 1 1 0 0 +EDGE2 2534 2533 -1.06461 -0.046612 -0.0118266 1 0 1 1 0 0 +EDGE2 2534 2413 -1.00012 -0.00260565 -0.0106851 1 0 1 1 0 0 +EDGE2 2534 2433 -0.937123 0.0404106 0.00615672 1 0 1 1 0 0 +EDGE2 2534 2414 -0.0630831 0.00237944 -0.00339549 1 0 1 1 0 0 +EDGE2 2534 2434 -0.0621179 -0.0214685 0.0230035 1 0 1 1 0 0 +EDGE2 2534 1235 0.939751 -0.0176326 -3.11009 1 0 1 1 0 0 +EDGE2 2534 2455 0.981933 -0.0270363 -3.1188 1 0 1 1 0 0 +EDGE2 2534 2495 1.01377 -0.0149728 -3.1441 1 0 1 1 0 0 +EDGE2 2534 2295 0.944884 -0.0750905 -3.14233 1 0 1 1 0 0 +EDGE2 2534 2415 0.941738 -0.0599888 -0.00319181 1 0 1 1 0 0 +EDGE2 2534 2435 1.06628 0.0205825 -0.00766086 1 0 1 1 0 0 +EDGE2 2534 1255 0.997903 0.0331594 -3.14067 1 0 1 1 0 0 +EDGE2 2535 2416 0.0266321 0.98282 1.56788 1 0 1 1 0 0 +EDGE2 2535 2456 0.0229412 -0.965731 -1.57664 1 0 1 1 0 0 +EDGE2 2535 1236 0.0670029 -1.00201 -1.58203 1 0 1 1 0 0 +EDGE2 2535 2414 -0.945176 -0.00625145 0.0229292 1 0 1 1 0 0 +EDGE2 2535 2434 -1.04357 0.0360372 -0.0138747 1 0 1 1 0 0 +EDGE2 2535 2534 -0.851132 0.0232927 -0.0207949 1 0 1 1 0 0 +EDGE2 2535 1235 -0.0467061 0.0322438 -3.14571 1 0 1 1 0 0 +EDGE2 2535 2455 0.00242985 -0.0099577 -3.1233 1 0 1 1 0 0 +EDGE2 2535 2495 -0.0371745 0.0419845 -3.16238 1 0 1 1 0 0 +EDGE2 2535 2295 -0.132391 -0.0143338 -3.14779 1 0 1 1 0 0 +EDGE2 2535 2415 -0.107713 -0.0302638 0.0239207 1 0 1 1 0 0 +EDGE2 2535 2435 0.0606848 -0.00709912 -0.00569674 1 0 1 1 0 0 +EDGE2 2535 1255 -0.054962 0.00596775 -3.14977 1 0 1 1 0 0 +EDGE2 2535 1254 1.06164 -0.0164682 -3.11885 1 0 1 1 0 0 +EDGE2 2535 2454 1.05494 -0.0741045 -3.12037 1 0 1 1 0 0 +EDGE2 2535 2494 1.04405 -0.0146847 -3.17029 1 0 1 1 0 0 +EDGE2 2535 2294 0.988132 -0.0481355 -3.14234 1 0 1 1 0 0 +EDGE2 2535 1234 1.02792 0.0747126 -3.12884 1 0 1 1 0 0 +EDGE2 2535 2496 0.0704125 0.981709 1.60459 1 0 1 1 0 0 +EDGE2 2535 2436 -0.0173571 1.04566 1.60294 1 0 1 1 0 0 +EDGE2 2535 1256 0.0127926 1.07993 1.6084 1 0 1 1 0 0 +EDGE2 2535 2296 0.063066 1.05406 1.53207 1 0 1 1 0 0 +EDGE2 2536 2416 0.054107 -0.0224582 -0.00967473 1 0 1 1 0 0 +EDGE2 2536 1235 -0.987579 -0.066211 1.58054 1 0 1 1 0 0 +EDGE2 2536 2455 -1.00235 -0.0308829 1.62413 1 0 1 1 0 0 +EDGE2 2536 2535 -0.930932 -0.0729289 -1.59143 1 0 1 1 0 0 +EDGE2 2536 2495 -1.04363 -0.0524982 1.58674 1 0 1 1 0 0 +EDGE2 2536 2295 -1.0246 0.0487454 1.59098 1 0 1 1 0 0 +EDGE2 2536 2415 -0.983597 -0.16434 -1.57674 1 0 1 1 0 0 +EDGE2 2536 2435 -0.990023 -0.0136204 -1.62283 1 0 1 1 0 0 +EDGE2 2536 1255 -0.96872 0.00282633 1.54994 1 0 1 1 0 0 +EDGE2 2536 2496 -0.107849 0.0448942 0.0344309 1 0 1 1 0 0 +EDGE2 2536 2436 0.0124781 0.00111031 -0.0165331 1 0 1 1 0 0 +EDGE2 2536 1256 -0.0155363 0.0263349 0.0218742 1 0 1 1 0 0 +EDGE2 2536 2296 0.0401218 0.0467663 -0.013495 1 0 1 1 0 0 +EDGE2 2536 2497 0.999702 0.0194941 -0.0183855 1 0 1 1 0 0 +EDGE2 2536 2297 1.01991 -0.0275969 0.0150548 1 0 1 1 0 0 +EDGE2 2536 2417 0.969912 -0.108541 -0.00861214 1 0 1 1 0 0 +EDGE2 2536 2437 0.940569 0.00499973 -0.0198723 1 0 1 1 0 0 +EDGE2 2536 1257 0.960322 -0.0738467 0.00972063 1 0 1 1 0 0 +EDGE2 2537 2416 -0.939979 -0.0762865 -0.000556058 1 0 1 1 0 0 +EDGE2 2537 2496 -1.00068 -0.124889 0.00989611 1 0 1 1 0 0 +EDGE2 2537 2536 -1.03961 0.106755 0.00377672 1 0 1 1 0 0 +EDGE2 2537 2436 -0.965841 -0.11132 0.0180109 1 0 1 1 0 0 +EDGE2 2537 2498 0.906929 -0.063115 -0.00746378 1 0 1 1 0 0 +EDGE2 2537 1256 -0.918708 0.00341965 -0.00185427 1 0 1 1 0 0 +EDGE2 2537 2296 -1.08598 0.00751973 -0.0144586 1 0 1 1 0 0 +EDGE2 2537 2497 -0.0123605 -0.0400288 -0.041274 1 0 1 1 0 0 +EDGE2 2537 2297 -0.0119471 0.0600088 0.0206612 1 0 1 1 0 0 +EDGE2 2537 2417 -0.0453966 0.0143185 -0.0208752 1 0 1 1 0 0 +EDGE2 2537 2437 0.0681922 0.00649681 -0.00240151 1 0 1 1 0 0 +EDGE2 2537 1257 -0.0432651 0.0464351 -0.0319967 1 0 1 1 0 0 +EDGE2 2537 2298 1.03178 0.0114236 -0.0111692 1 0 1 1 0 0 +EDGE2 2537 2418 0.952626 0.0249058 0.00262315 1 0 1 1 0 0 +EDGE2 2537 2438 1.03447 0.0362659 -0.0166567 1 0 1 1 0 0 +EDGE2 2537 1258 0.989513 0.0381986 0.00692882 1 0 1 1 0 0 +EDGE2 2538 2498 0.0219707 -0.0455602 -0.00114487 1 0 1 1 0 0 +EDGE2 2538 2497 -0.969917 -0.0532357 -0.00496537 1 0 1 1 0 0 +EDGE2 2538 2537 -0.907599 -0.0213788 -0.00198699 1 0 1 1 0 0 +EDGE2 2538 2297 -0.978525 -0.01038 0.0138954 1 0 1 1 0 0 +EDGE2 2538 2417 -0.978382 -0.00362497 0.0232083 1 0 1 1 0 0 +EDGE2 2538 2437 -0.925654 -0.00515748 0.0316497 1 0 1 1 0 0 +EDGE2 2538 1257 -0.996958 -0.0371336 0.019203 1 0 1 1 0 0 +EDGE2 2538 2298 0.0186478 -0.0172701 -0.0138121 1 0 1 1 0 0 +EDGE2 2538 2418 -0.065448 -0.00960927 0.00791643 1 0 1 1 0 0 +EDGE2 2538 2438 -0.0469373 0.0260058 0.0185672 1 0 1 1 0 0 +EDGE2 2538 1258 0.0249692 0.0157414 0.00434212 1 0 1 1 0 0 +EDGE2 2538 2499 1.02442 -0.056582 0.0121005 1 0 1 1 0 0 +EDGE2 2538 2299 1.10641 -0.0254252 0.0089975 1 0 1 1 0 0 +EDGE2 2538 2419 0.989468 0.0265867 -0.00419933 1 0 1 1 0 0 +EDGE2 2538 2439 0.961622 -0.0464053 -0.0293185 1 0 1 1 0 0 +EDGE2 2538 1259 0.971708 -0.0138227 -0.0156665 1 0 1 1 0 0 +EDGE2 2539 2498 -1.03707 0.045853 -0.00839321 1 0 1 1 0 0 +EDGE2 2539 2538 -0.971519 0.000477951 0.0267101 1 0 1 1 0 0 +EDGE2 2539 2298 -1.05223 -0.109053 -0.045022 1 0 1 1 0 0 +EDGE2 2539 2418 -0.979914 0.00621185 -0.0187934 1 0 1 1 0 0 +EDGE2 2539 2438 -1.06108 0.0757264 -0.0430187 1 0 1 1 0 0 +EDGE2 2539 1258 -1.02724 -0.0805587 0.00651441 1 0 1 1 0 0 +EDGE2 2539 2499 -0.0594863 0.051413 -0.00304802 1 0 1 1 0 0 +EDGE2 2539 2299 -0.00123184 0.090068 0.0222752 1 0 1 1 0 0 +EDGE2 2539 2419 -0.0367413 -0.0338813 0.0278927 1 0 1 1 0 0 +EDGE2 2539 2439 -0.021177 0.0461495 0.0151698 1 0 1 1 0 0 +EDGE2 2539 1259 0.0300208 -0.0315435 0.00631842 1 0 1 1 0 0 +EDGE2 2539 2420 1.01801 0.0133921 0.00709366 1 0 1 1 0 0 +EDGE2 2539 2500 1.04752 -0.04296 0.0444333 1 0 1 1 0 0 +EDGE2 2539 2520 1.0202 -0.00128362 -3.15475 1 0 1 1 0 0 +EDGE2 2539 2440 1.05163 0.0436619 0.00843231 1 0 1 1 0 0 +EDGE2 2539 2300 0.945463 0.0741464 0.0269335 1 0 1 1 0 0 +EDGE2 2539 1260 0.975377 0.0100672 0.0144299 1 0 1 1 0 0 +EDGE2 2540 2441 0.0215497 -1.08429 -1.57515 1 0 1 1 0 0 +EDGE2 2540 2521 -0.053685 1.05638 1.5581 1 0 1 1 0 0 +EDGE2 2540 2301 -0.0489043 1.0132 1.54237 1 0 1 1 0 0 +EDGE2 2540 2421 -0.00623292 0.94522 1.62129 1 0 1 1 0 0 +EDGE2 2540 1261 -0.08748 1.0833 1.54924 1 0 1 1 0 0 +EDGE2 2540 2499 -1.02053 -0.0222205 -0.0104341 1 0 1 1 0 0 +EDGE2 2540 2539 -1.08696 -0.00224922 0.0265422 1 0 1 1 0 0 +EDGE2 2540 2299 -0.991109 -0.0283383 0.0203294 1 0 1 1 0 0 +EDGE2 2540 2419 -1.01084 0.0612285 0.0111224 1 0 1 1 0 0 +EDGE2 2540 2439 -1.01685 0.100734 -0.0125095 1 0 1 1 0 0 +EDGE2 2540 1259 -1.09583 0.0508058 0.00471344 1 0 1 1 0 0 +EDGE2 2540 2420 0.0558197 0.00850123 -0.0226879 1 0 1 1 0 0 +EDGE2 2540 2500 0.0346282 -0.047107 -0.00267267 1 0 1 1 0 0 +EDGE2 2540 2520 -0.0281909 0.0212514 -3.17342 1 0 1 1 0 0 +EDGE2 2540 2440 0.0440022 -0.030495 0.000754111 1 0 1 1 0 0 +EDGE2 2540 2300 -0.0614165 0.0521251 0.013072 1 0 1 1 0 0 +EDGE2 2540 1260 -0.0355948 -0.0159111 -0.00973072 1 0 1 1 0 0 +EDGE2 2540 2501 -0.0109099 -1.05144 -1.5422 1 0 1 1 0 0 +EDGE2 2540 2519 1.01128 0.0273367 -3.17247 1 0 1 1 0 0 +EDGE2 2541 2302 0.891998 -0.0572252 -0.0051755 1 0 1 1 0 0 +EDGE2 2541 2522 0.982431 0.0571979 -0.0270599 1 0 1 1 0 0 +EDGE2 2541 2422 1.04268 -0.0343251 0.0249966 1 0 1 1 0 0 +EDGE2 2541 2521 0.0577659 0.0421691 4.06926e-05 1 0 1 1 0 0 +EDGE2 2541 1262 0.954541 0.0659767 0.00541469 1 0 1 1 0 0 +EDGE2 2541 2301 -0.0596475 0.0319371 -0.0151721 1 0 1 1 0 0 +EDGE2 2541 2421 -0.00528379 0.00922792 -0.00110432 1 0 1 1 0 0 +EDGE2 2541 1261 -0.019622 0.0226943 0.00316364 1 0 1 1 0 0 +EDGE2 2541 2420 -1.03511 -0.00876243 -1.57779 1 0 1 1 0 0 +EDGE2 2541 2500 -1.00942 -0.0240186 -1.57066 1 0 1 1 0 0 +EDGE2 2541 2520 -0.9761 -0.052723 1.56848 1 0 1 1 0 0 +EDGE2 2541 2540 -1.01315 -0.0482762 -1.57461 1 0 1 1 0 0 +EDGE2 2541 2440 -0.996772 0.0708342 -1.55253 1 0 1 1 0 0 +EDGE2 2541 2300 -0.98354 0.0107787 -1.59605 1 0 1 1 0 0 +EDGE2 2541 1260 -0.988574 0.0446167 -1.53882 1 0 1 1 0 0 +EDGE2 2542 2302 -0.117792 0.0264508 -0.0322241 1 0 1 1 0 0 +EDGE2 2542 2303 0.991434 0.0118609 0.0124872 1 0 1 1 0 0 +EDGE2 2542 2423 1.02292 -0.0299741 0.00979463 1 0 1 1 0 0 +EDGE2 2542 2523 1.04778 -0.0452398 0.00202893 1 0 1 1 0 0 +EDGE2 2542 1263 1.02303 0.05781 0.000168264 1 0 1 1 0 0 +EDGE2 2542 2522 0.00719525 -0.0841537 -0.0136979 1 0 1 1 0 0 +EDGE2 2542 2422 0.0394767 0.101681 0.0235788 1 0 1 1 0 0 +EDGE2 2542 2521 -0.966066 -0.0546282 -0.0143886 1 0 1 1 0 0 +EDGE2 2542 1262 0.088513 0.0203589 -0.0272041 1 0 1 1 0 0 +EDGE2 2542 2541 -0.920294 -0.0539592 -0.00576223 1 0 1 1 0 0 +EDGE2 2542 2301 -0.944483 0.0416421 -0.0268491 1 0 1 1 0 0 +EDGE2 2542 2421 -1.00815 0.0140571 -0.0216298 1 0 1 1 0 0 +EDGE2 2542 1261 -0.889449 0.0469076 0.0177392 1 0 1 1 0 0 +EDGE2 2543 2424 1.05802 -0.0263335 -0.00588355 1 0 1 1 0 0 +EDGE2 2543 2524 1.0224 -0.0799845 0.0108712 1 0 1 1 0 0 +EDGE2 2543 1264 1.06213 0.0810266 0.021091 1 0 1 1 0 0 +EDGE2 2543 2304 0.94261 -0.0397383 -0.0199973 1 0 1 1 0 0 +EDGE2 2543 2302 -1.01342 -0.000370133 0.00770573 1 0 1 1 0 0 +EDGE2 2543 2303 0.0140174 0.0085418 -0.00137078 1 0 1 1 0 0 +EDGE2 2543 2423 0.0462754 0.0123689 -0.00128136 1 0 1 1 0 0 +EDGE2 2543 2523 0.0855607 0.0561316 0.0155772 1 0 1 1 0 0 +EDGE2 2543 1263 -0.0401444 0.0203716 0.0442767 1 0 1 1 0 0 +EDGE2 2543 2522 -1.08544 0.00845843 -0.0015088 1 0 1 1 0 0 +EDGE2 2543 2542 -0.963385 -0.0375363 -0.0225477 1 0 1 1 0 0 +EDGE2 2543 2422 -1.0099 -0.02312 0.0103153 1 0 1 1 0 0 +EDGE2 2543 1262 -0.927675 0.0984661 0.00251799 1 0 1 1 0 0 +EDGE2 2544 2543 -0.953203 -0.0759382 0.016884 1 0 1 1 0 0 +EDGE2 2544 1265 1.05871 0.0364411 0.0315329 1 0 1 1 0 0 +EDGE2 2544 2305 0.994473 0.0611102 -0.0254507 1 0 1 1 0 0 +EDGE2 2544 2405 0.932396 -0.0911944 -3.13794 1 0 1 1 0 0 +EDGE2 2544 2425 0.974035 -0.0159021 0.00509318 1 0 1 1 0 0 +EDGE2 2544 2525 0.955702 -0.107591 0.0125377 1 0 1 1 0 0 +EDGE2 2544 2385 0.960881 -0.00438963 -3.13139 1 0 1 1 0 0 +EDGE2 2544 1565 1.09107 -0.0105218 -3.16929 1 0 1 1 0 0 +EDGE2 2544 1585 1.05258 -0.0341032 -3.12408 1 0 1 1 0 0 +EDGE2 2544 1845 0.980448 0.0248374 -3.14447 1 0 1 1 0 0 +EDGE2 2544 1545 0.991251 -0.0277155 -3.13168 1 0 1 1 0 0 +EDGE2 2544 2424 -0.0164739 0.0540936 0.014694 1 0 1 1 0 0 +EDGE2 2544 2524 -0.0413088 0.0498606 0.000407164 1 0 1 1 0 0 +EDGE2 2544 1264 0.0376489 -0.0123568 0.02671 1 0 1 1 0 0 +EDGE2 2544 2304 0.0496115 -9.76821e-05 0.0344623 1 0 1 1 0 0 +EDGE2 2544 2303 -0.992356 0.0152689 -0.00182293 1 0 1 1 0 0 +EDGE2 2544 2423 -0.988348 0.0436839 0.0110911 1 0 1 1 0 0 +EDGE2 2544 2523 -1.04866 -0.0513853 -0.0304044 1 0 1 1 0 0 +EDGE2 2544 1263 -1.04307 0.0126586 -0.0330676 1 0 1 1 0 0 +EDGE2 2545 1564 1.00901 0.0864002 -3.1477 1 0 1 1 0 0 +EDGE2 2545 1844 0.979981 0.0508946 -3.14828 1 0 1 1 0 0 +EDGE2 2545 2384 1.00324 0.00472717 -3.14051 1 0 1 1 0 0 +EDGE2 2545 2404 0.950253 0.0753873 -3.16876 1 0 1 1 0 0 +EDGE2 2545 1584 1.03654 -0.0452513 -3.14751 1 0 1 1 0 0 +EDGE2 2545 1544 1.03891 0.0582973 -3.15411 1 0 1 1 0 0 +EDGE2 2545 2426 0.00668488 0.946023 1.61 1 0 1 1 0 0 +EDGE2 2545 2526 -0.0222731 1.00308 1.55597 1 0 1 1 0 0 +EDGE2 2545 2406 -0.0623078 0.968566 1.55674 1 0 1 1 0 0 +EDGE2 2545 1546 -0.0276321 0.949765 1.54075 1 0 1 1 0 0 +EDGE2 2545 1265 0.0154241 0.0261651 -0.0174676 1 0 1 1 0 0 +EDGE2 2545 2305 0.0101393 -0.0465558 -0.000199468 1 0 1 1 0 0 +EDGE2 2545 2405 -0.00596581 -0.125897 -3.12814 1 0 1 1 0 0 +EDGE2 2545 2425 0.0425566 -0.0119404 0.011301 1 0 1 1 0 0 +EDGE2 2545 2525 -0.0352011 -0.00889524 0.0120973 1 0 1 1 0 0 +EDGE2 2545 2385 -0.105697 -0.0735503 -3.13411 1 0 1 1 0 0 +EDGE2 2545 1565 0.0249478 0.0217869 -3.15497 1 0 1 1 0 0 +EDGE2 2545 1585 -0.0816246 -0.0138402 -3.13977 1 0 1 1 0 0 +EDGE2 2545 1845 0.0730118 -0.071896 -3.14614 1 0 1 1 0 0 +EDGE2 2545 1545 -0.00464939 0.00500998 -3.15015 1 0 1 1 0 0 +EDGE2 2545 2424 -0.987624 0.0521841 -0.0187675 1 0 1 1 0 0 +EDGE2 2545 2544 -1.05016 0.0299389 -0.00691071 1 0 1 1 0 0 +EDGE2 2545 2524 -1.03211 0.0394065 -0.015778 1 0 1 1 0 0 +EDGE2 2545 1264 -1.00007 -0.0560072 -0.0521724 1 0 1 1 0 0 +EDGE2 2545 2304 -0.993522 0.0459549 -0.0405776 1 0 1 1 0 0 +EDGE2 2545 1566 -0.0234081 -1.0306 -1.5765 1 0 1 1 0 0 +EDGE2 2545 1846 -0.00344824 -0.928374 -1.5664 1 0 1 1 0 0 +EDGE2 2545 2306 -0.0485252 -1.05388 -1.55311 1 0 1 1 0 0 +EDGE2 2545 2386 -0.00899486 -1.00462 -1.58172 1 0 1 1 0 0 +EDGE2 2545 1586 0.00155821 -1.02256 -1.5672 1 0 1 1 0 0 +EDGE2 2545 1266 -3.50206e-05 -1.07637 -1.56943 1 0 1 1 0 0 +EDGE2 2546 2545 -1.06519 -0.0749338 -1.56878 1 0 1 1 0 0 +EDGE2 2546 2426 0.0423849 -0.0574211 -0.00118118 1 0 1 1 0 0 +EDGE2 2546 1547 1.00366 -0.0354535 -0.0131463 1 0 1 1 0 0 +EDGE2 2546 2427 1.04686 -0.0940904 -0.0246486 1 0 1 1 0 0 +EDGE2 2546 2527 0.945408 -0.00257882 -0.0361843 1 0 1 1 0 0 +EDGE2 2546 2407 0.980172 -0.133171 -0.0124777 1 0 1 1 0 0 +EDGE2 2546 2526 -0.0159263 0.0194593 0.0253472 1 0 1 1 0 0 +EDGE2 2546 2406 0.0020506 0.0672303 -0.0345149 1 0 1 1 0 0 +EDGE2 2546 1546 -0.0269455 -0.00644217 0.00110453 1 0 1 1 0 0 +EDGE2 2546 1265 -1.0534 0.0447113 -1.59795 1 0 1 1 0 0 +EDGE2 2546 2305 -0.966035 0.051704 -1.54056 1 0 1 1 0 0 +EDGE2 2546 2405 -1.12744 -0.0425858 1.56765 1 0 1 1 0 0 +EDGE2 2546 2425 -1.06146 -0.0492002 -1.57776 1 0 1 1 0 0 +EDGE2 2546 2525 -1.04738 0.0497664 -1.54742 1 0 1 1 0 0 +EDGE2 2546 2385 -0.950756 -0.0288258 1.56304 1 0 1 1 0 0 +EDGE2 2546 1565 -1.05923 0.0606904 1.57152 1 0 1 1 0 0 +EDGE2 2546 1585 -0.97476 -0.0260747 1.564 1 0 1 1 0 0 +EDGE2 2546 1845 -0.997883 0.0148904 1.57256 1 0 1 1 0 0 +EDGE2 2546 1545 -0.928989 -0.096134 1.57138 1 0 1 1 0 0 +EDGE2 2547 2528 0.936202 -0.0351365 0.0329981 1 0 1 1 0 0 +EDGE2 2547 1548 0.954788 -0.0381199 -0.0440514 1 0 1 1 0 0 +EDGE2 2547 2408 1.00945 0.017088 -0.00108726 1 0 1 1 0 0 +EDGE2 2547 2428 1.06216 0.00683445 -0.0236453 1 0 1 1 0 0 +EDGE2 2547 2426 -0.905186 -0.00343334 -0.000726435 1 0 1 1 0 0 +EDGE2 2547 1547 -0.118478 0.0134776 -0.0263008 1 0 1 1 0 0 +EDGE2 2547 2427 0.0197472 -0.0329174 -0.00283622 1 0 1 1 0 0 +EDGE2 2547 2527 -0.0719174 -0.00507568 0.0106121 1 0 1 1 0 0 +EDGE2 2547 2407 -0.0394017 0.0464209 -0.0227669 1 0 1 1 0 0 +EDGE2 2547 2546 -1.03218 -0.0080962 0.00454397 1 0 1 1 0 0 +EDGE2 2547 2526 -1.01659 -0.0229358 0.0199239 1 0 1 1 0 0 +EDGE2 2547 2406 -1.06114 0.05705 0.00474136 1 0 1 1 0 0 +EDGE2 2547 1546 -1.05148 0.0227891 0.0156218 1 0 1 1 0 0 +EDGE2 2548 2429 0.946939 0.0286815 -0.0230529 1 0 1 1 0 0 +EDGE2 2548 2529 0.986341 0.00155029 0.0329087 1 0 1 1 0 0 +EDGE2 2548 1549 0.9512 -0.0384716 -0.0143453 1 0 1 1 0 0 +EDGE2 2548 2409 1.05065 0.00682456 -0.00682856 1 0 1 1 0 0 +EDGE2 2548 2528 -0.0157986 0.00951852 -0.00210805 1 0 1 1 0 0 +EDGE2 2548 1548 -0.0822393 0.0540224 0.0148315 1 0 1 1 0 0 +EDGE2 2548 2408 -0.0401712 0.00976199 -0.0365492 1 0 1 1 0 0 +EDGE2 2548 2428 0.00504025 0.0337067 0.00271404 1 0 1 1 0 0 +EDGE2 2548 1547 -1.08159 0.030933 -0.00694835 1 0 1 1 0 0 +EDGE2 2548 2427 -0.984124 -0.0364076 -0.00475097 1 0 1 1 0 0 +EDGE2 2548 2527 -1.00365 -0.0373503 0.00411756 1 0 1 1 0 0 +EDGE2 2548 2547 -1.05708 -0.0447357 0.00650056 1 0 1 1 0 0 +EDGE2 2548 2407 -0.993831 -0.0714687 -0.0453448 1 0 1 1 0 0 +EDGE2 2549 2430 0.964356 0.0520312 -0.00823009 1 0 1 1 0 0 +EDGE2 2549 2530 1.07087 0.0873972 -0.0242092 1 0 1 1 0 0 +EDGE2 2549 1550 1.00307 0.0579961 -0.0211728 1 0 1 1 0 0 +EDGE2 2549 1830 0.995074 -0.00708291 -3.13504 1 0 1 1 0 0 +EDGE2 2549 2410 0.928633 0.0125243 0.0164854 1 0 1 1 0 0 +EDGE2 2549 2429 -0.0247893 -0.00310018 -0.0298005 1 0 1 1 0 0 +EDGE2 2549 2529 0.0114142 0.0746476 -0.0109421 1 0 1 1 0 0 +EDGE2 2549 1549 -0.00165791 -0.0126478 -0.0132888 1 0 1 1 0 0 +EDGE2 2549 2409 -0.0652263 0.0605397 -0.0326221 1 0 1 1 0 0 +EDGE2 2549 2528 -0.963269 -0.00329506 -0.0134604 1 0 1 1 0 0 +EDGE2 2549 2548 -1.01649 -0.0566943 -0.0209089 1 0 1 1 0 0 +EDGE2 2549 1548 -0.957991 0.0736048 0.0517629 1 0 1 1 0 0 +EDGE2 2549 2408 -1.03058 -0.00627945 0.0140465 1 0 1 1 0 0 +EDGE2 2549 2428 -1.03861 0.0139041 -0.0166583 1 0 1 1 0 0 +EDGE2 2550 1829 1.0269 -0.134614 -3.17096 1 0 1 1 0 0 +EDGE2 2550 1831 0.144369 -0.946292 -1.58471 1 0 1 1 0 0 +EDGE2 2550 1551 0.0471152 -1.0731 -1.55991 1 0 1 1 0 0 +EDGE2 2550 2411 0.00492035 0.985084 1.5966 1 0 1 1 0 0 +EDGE2 2550 2430 -0.0782613 0.0315518 -0.00617201 1 0 1 1 0 0 +EDGE2 2550 2530 -0.0542941 -0.025237 -0.0239909 1 0 1 1 0 0 +EDGE2 2550 1550 0.0552424 -0.0120565 0.0160871 1 0 1 1 0 0 +EDGE2 2550 1830 0.00209454 0.0323572 -3.14864 1 0 1 1 0 0 +EDGE2 2550 2410 -0.127341 0.0458105 0.0176135 1 0 1 1 0 0 +EDGE2 2550 2531 0.0479133 0.918086 1.56804 1 0 1 1 0 0 +EDGE2 2550 2431 0.0531173 1.03578 1.57245 1 0 1 1 0 0 +EDGE2 2550 2429 -1.06817 -0.0460493 -0.0295066 1 0 1 1 0 0 +EDGE2 2550 2549 -1.0064 -0.0776244 0.00293612 1 0 1 1 0 0 +EDGE2 2550 2529 -0.887088 0.00867952 -0.00616555 1 0 1 1 0 0 +EDGE2 2550 1549 -0.973511 -0.0164582 -0.00216976 1 0 1 1 0 0 +EDGE2 2550 2409 -1.04097 -0.102983 -0.00723673 1 0 1 1 0 0 +EDGE2 2551 2411 0.00259162 0.0227842 -0.00247004 1 0 1 1 0 0 +EDGE2 2551 2430 -0.869617 0.0324865 -1.59465 1 0 1 1 0 0 +EDGE2 2551 2550 -0.995973 0.0384505 -1.56378 1 0 1 1 0 0 +EDGE2 2551 2530 -0.972673 0.022346 -1.58121 1 0 1 1 0 0 +EDGE2 2551 1550 -0.967193 -0.0827464 -1.57692 1 0 1 1 0 0 +EDGE2 2551 1830 -0.972144 0.0553984 1.59562 1 0 1 1 0 0 +EDGE2 2551 2410 -1.01774 0.0386333 -1.55758 1 0 1 1 0 0 +EDGE2 2551 2531 0.0966814 -0.0173303 0.0151208 1 0 1 1 0 0 +EDGE2 2551 2431 -0.00491521 0.0274015 -0.0123184 1 0 1 1 0 0 +EDGE2 2551 2432 1.04807 -0.0163064 -0.0091745 1 0 1 1 0 0 +EDGE2 2551 2532 1.05135 0.0979476 0.019349 1 0 1 1 0 0 +EDGE2 2551 2412 0.980611 -0.0320789 -0.00774764 1 0 1 1 0 0 +EDGE2 2552 2411 -0.881478 -0.0325014 0.0401638 1 0 1 1 0 0 +EDGE2 2552 2531 -0.9583 0.0116157 -0.00210734 1 0 1 1 0 0 +EDGE2 2552 2551 -0.987065 -0.102948 -0.0248205 1 0 1 1 0 0 +EDGE2 2552 2431 -1.04656 -0.0261404 0.0378919 1 0 1 1 0 0 +EDGE2 2552 2533 1.04667 -0.011359 -0.00793694 1 0 1 1 0 0 +EDGE2 2552 2432 0.0892738 0.0726807 -0.0215527 1 0 1 1 0 0 +EDGE2 2552 2532 0.000481581 -0.0726082 0.00705562 1 0 1 1 0 0 +EDGE2 2552 2412 -0.070767 0.0319288 -0.00146363 1 0 1 1 0 0 +EDGE2 2552 2413 0.994458 0.0088129 0.0237455 1 0 1 1 0 0 +EDGE2 2552 2433 1.06628 -0.124252 -0.00171723 1 0 1 1 0 0 +EDGE2 2553 2533 -0.00804348 -0.0121101 0.00760156 1 0 1 1 0 0 +EDGE2 2553 2432 -1.00031 -0.00708705 -0.0181583 1 0 1 1 0 0 +EDGE2 2553 2552 -0.976643 -0.0529838 0.0163751 1 0 1 1 0 0 +EDGE2 2553 2532 -1.04312 -0.0362125 0.00738084 1 0 1 1 0 0 +EDGE2 2553 2412 -1.04156 0.035608 -0.00926434 1 0 1 1 0 0 +EDGE2 2553 2413 -0.0242872 -0.0164795 -0.0117179 1 0 1 1 0 0 +EDGE2 2553 2433 0.0169973 0.0642172 0.00663482 1 0 1 1 0 0 +EDGE2 2553 2414 0.972246 0.0195927 0.0053799 1 0 1 1 0 0 +EDGE2 2553 2434 1.03481 0.00622586 -0.0392316 1 0 1 1 0 0 +EDGE2 2553 2534 0.998 0.000729493 0.0195029 1 0 1 1 0 0 +EDGE2 2554 2533 -0.987153 0.0167217 0.00328224 1 0 1 1 0 0 +EDGE2 2554 2553 -1.01971 0.0632213 -0.00105091 1 0 1 1 0 0 +EDGE2 2554 2413 -0.993241 -0.0235685 -0.032634 1 0 1 1 0 0 +EDGE2 2554 2433 -0.966537 0.0306771 -0.0190035 1 0 1 1 0 0 +EDGE2 2554 2414 0.0231982 -0.0227713 -0.000632763 1 0 1 1 0 0 +EDGE2 2554 2434 -0.0867903 0.0150824 0.0188651 1 0 1 1 0 0 +EDGE2 2554 2534 -0.0299627 0.0337895 -0.00697852 1 0 1 1 0 0 +EDGE2 2554 1235 1.04782 0.0383506 -3.14622 1 0 1 1 0 0 +EDGE2 2554 2455 1.01732 -0.0471631 -3.12309 1 0 1 1 0 0 +EDGE2 2554 2535 1.04859 -0.0519571 0.00196892 1 0 1 1 0 0 +EDGE2 2554 2495 0.974866 0.00764957 -3.16813 1 0 1 1 0 0 +EDGE2 2554 2295 0.925244 0.0651518 -3.10317 1 0 1 1 0 0 +EDGE2 2554 2415 0.963931 0.145632 0.000827798 1 0 1 1 0 0 +EDGE2 2554 2435 0.992703 -0.00134289 0.0161161 1 0 1 1 0 0 +EDGE2 2554 1255 0.998629 -0.0254502 -3.12674 1 0 1 1 0 0 +EDGE2 2555 2416 -0.00473328 0.964394 1.56189 1 0 1 1 0 0 +EDGE2 2555 2456 0.0721937 -1.06818 -1.59101 1 0 1 1 0 0 +EDGE2 2555 1236 -0.0363141 -0.941511 -1.58358 1 0 1 1 0 0 +EDGE2 2555 2554 -0.945895 0.0394347 -0.0231331 1 0 1 1 0 0 +EDGE2 2555 2414 -1.02352 -0.0127826 0.00222604 1 0 1 1 0 0 +EDGE2 2555 2434 -0.985006 -0.0333892 -0.0233517 1 0 1 1 0 0 +EDGE2 2555 2534 -1.0053 0.124795 -0.0212906 1 0 1 1 0 0 +EDGE2 2555 1235 0.00120718 0.0490519 -3.14886 1 0 1 1 0 0 +EDGE2 2555 2455 0.0273531 -0.0624413 -3.11255 1 0 1 1 0 0 +EDGE2 2555 2535 0.0568118 -0.0335214 -0.00484788 1 0 1 1 0 0 +EDGE2 2555 2495 0.0184103 0.00267258 -3.13537 1 0 1 1 0 0 +EDGE2 2555 2295 -0.0693984 -0.0223257 -3.1455 1 0 1 1 0 0 +EDGE2 2555 2415 -0.00628365 -0.0410133 -0.0182005 1 0 1 1 0 0 +EDGE2 2555 2435 -0.00574731 -0.0948795 0.0132605 1 0 1 1 0 0 +EDGE2 2555 1255 0.100682 -0.0135209 -3.14005 1 0 1 1 0 0 +EDGE2 2555 1254 0.967452 3.3751e-05 -3.12419 1 0 1 1 0 0 +EDGE2 2555 2454 0.982511 0.0397105 -3.1465 1 0 1 1 0 0 +EDGE2 2555 2494 0.902206 0.00655198 -3.1663 1 0 1 1 0 0 +EDGE2 2555 2294 0.94889 -0.115335 -3.12567 1 0 1 1 0 0 +EDGE2 2555 1234 0.972052 0.0246615 -3.1291 1 0 1 1 0 0 +EDGE2 2555 2496 0.0114985 0.987785 1.57409 1 0 1 1 0 0 +EDGE2 2555 2536 -0.0188123 1.08826 1.58861 1 0 1 1 0 0 +EDGE2 2555 2436 0.0394085 0.999529 1.55037 1 0 1 1 0 0 +EDGE2 2555 1256 -0.0926408 0.922884 1.56697 1 0 1 1 0 0 +EDGE2 2555 2296 0.0330024 1.02186 1.56331 1 0 1 1 0 0 +EDGE2 2556 2416 0.0528375 -0.0172115 0.0353663 1 0 1 1 0 0 +EDGE2 2556 1235 -0.98181 0.0734487 1.5963 1 0 1 1 0 0 +EDGE2 2556 2455 -1.06125 -0.0127722 1.55928 1 0 1 1 0 0 +EDGE2 2556 2535 -1.01951 0.044111 -1.57147 1 0 1 1 0 0 +EDGE2 2556 2555 -0.991137 0.0436072 -1.57279 1 0 1 1 0 0 +EDGE2 2556 2495 -1.04189 -0.061051 1.5683 1 0 1 1 0 0 +EDGE2 2556 2295 -1.06179 -0.0142879 1.58083 1 0 1 1 0 0 +EDGE2 2556 2415 -1.05475 0.0712224 -1.56636 1 0 1 1 0 0 +EDGE2 2556 2435 -1.04666 0.0650503 -1.55845 1 0 1 1 0 0 +EDGE2 2556 1255 -1.00355 -0.0162355 1.57904 1 0 1 1 0 0 +EDGE2 2556 2496 -0.0805683 0.00385612 0.0097899 1 0 1 1 0 0 +EDGE2 2556 2536 0.0238925 0.0325761 -0.0164253 1 0 1 1 0 0 +EDGE2 2556 2436 0.0259278 0.0405103 0.011066 1 0 1 1 0 0 +EDGE2 2556 1256 0.00677122 0.0721684 -0.0121769 1 0 1 1 0 0 +EDGE2 2556 2296 0.0591294 -0.0359728 0.0167039 1 0 1 1 0 0 +EDGE2 2556 2497 1.01349 -0.0632471 0.00177981 1 0 1 1 0 0 +EDGE2 2556 2537 1.00951 0.0965335 0.0131027 1 0 1 1 0 0 +EDGE2 2556 2297 0.84603 0.0308532 -0.00098498 1 0 1 1 0 0 +EDGE2 2556 2417 1.00878 0.0589427 -0.00380744 1 0 1 1 0 0 +EDGE2 2556 2437 0.977623 -0.057064 -0.0054924 1 0 1 1 0 0 +EDGE2 2556 1257 1.02017 -0.0184366 0.0119509 1 0 1 1 0 0 +EDGE2 2557 2416 -1.01522 -0.0613794 0.0150532 1 0 1 1 0 0 +EDGE2 2557 2556 -1.02523 -0.0439606 -0.016043 1 0 1 1 0 0 +EDGE2 2557 2496 -0.949598 0.0188225 -0.0251908 1 0 1 1 0 0 +EDGE2 2557 2536 -0.981482 0.0180321 -0.016087 1 0 1 1 0 0 +EDGE2 2557 2436 -1.01095 -0.0272698 -0.0416738 1 0 1 1 0 0 +EDGE2 2557 2498 1.03507 0.106918 -0.0118198 1 0 1 1 0 0 +EDGE2 2557 1256 -1.09194 -0.0205 -0.0137524 1 0 1 1 0 0 +EDGE2 2557 2296 -1.03697 0.0245118 -0.0238218 1 0 1 1 0 0 +EDGE2 2557 2497 0.083572 -0.0242862 0.0470472 1 0 1 1 0 0 +EDGE2 2557 2537 0.0169595 -0.0187841 -0.00873064 1 0 1 1 0 0 +EDGE2 2557 2297 -0.0185816 -0.115389 -0.0123341 1 0 1 1 0 0 +EDGE2 2557 2417 -0.0145479 0.0175346 -0.0112985 1 0 1 1 0 0 +EDGE2 2557 2437 0.0168327 -0.0605902 -0.0329731 1 0 1 1 0 0 +EDGE2 2557 1257 -0.0308203 0.0188361 0.036444 1 0 1 1 0 0 +EDGE2 2557 2538 1.02786 0.0434114 -0.0287811 1 0 1 1 0 0 +EDGE2 2557 2298 0.936416 -0.0507954 -0.0125344 1 0 1 1 0 0 +EDGE2 2557 2418 0.908093 0.046501 -0.0120278 1 0 1 1 0 0 +EDGE2 2557 2438 0.922425 0.00370166 -0.0319373 1 0 1 1 0 0 +EDGE2 2557 1258 0.991086 -0.0200805 0.0011257 1 0 1 1 0 0 +EDGE2 2558 2498 0.00770537 0.0180313 -0.0151724 1 0 1 1 0 0 +EDGE2 2558 2497 -0.935302 0.119144 -0.00746679 1 0 1 1 0 0 +EDGE2 2558 2557 -1.09143 0.0478856 0.00646059 1 0 1 1 0 0 +EDGE2 2558 2537 -0.935233 0.0287329 0.00309892 1 0 1 1 0 0 +EDGE2 2558 2297 -0.904335 -0.00609692 -0.0246679 1 0 1 1 0 0 +EDGE2 2558 2417 -1.02672 0.00647289 -0.0186975 1 0 1 1 0 0 +EDGE2 2558 2437 -0.905075 0.0320751 -0.0169951 1 0 1 1 0 0 +EDGE2 2558 1257 -1.05958 -0.0327069 -0.0349226 1 0 1 1 0 0 +EDGE2 2558 2538 0.0656529 0.0406066 -0.037562 1 0 1 1 0 0 +EDGE2 2558 2298 -0.0180398 -0.0147553 -0.00940893 1 0 1 1 0 0 +EDGE2 2558 2418 -0.0468791 -0.0279145 0.0300154 1 0 1 1 0 0 +EDGE2 2558 2438 -0.0465262 -0.0631837 0.00153906 1 0 1 1 0 0 +EDGE2 2558 1258 -0.0131349 -0.00271907 -0.0330706 1 0 1 1 0 0 +EDGE2 2558 2499 1.1607 0.0378439 0.0270929 1 0 1 1 0 0 +EDGE2 2558 2539 0.973085 -0.0386814 0.00267662 1 0 1 1 0 0 +EDGE2 2558 2299 1.08347 0.0528558 0.00841165 1 0 1 1 0 0 +EDGE2 2558 2419 0.897655 -0.000923693 0.0304288 1 0 1 1 0 0 +EDGE2 2558 2439 1.02161 0.0119419 -0.0181129 1 0 1 1 0 0 +EDGE2 2558 1259 0.983972 0.0210918 -0.017514 1 0 1 1 0 0 +EDGE2 2559 2498 -0.991091 -0.0794283 0.0148291 1 0 1 1 0 0 +EDGE2 2559 2558 -0.986554 -0.0356921 -0.00160189 1 0 1 1 0 0 +EDGE2 2559 2538 -0.990349 -0.140054 -0.0228025 1 0 1 1 0 0 +EDGE2 2559 2298 -1.0182 0.0054974 -0.0125889 1 0 1 1 0 0 +EDGE2 2559 2418 -1.01339 -0.0392102 0.0199832 1 0 1 1 0 0 +EDGE2 2559 2438 -0.981261 0.0251703 0.0276438 1 0 1 1 0 0 +EDGE2 2559 1258 -1.02449 -0.0177474 -0.00544702 1 0 1 1 0 0 +EDGE2 2559 2499 0.00831716 0.012264 0.00369113 1 0 1 1 0 0 +EDGE2 2559 2539 -0.0268989 -0.0923215 -0.000580734 1 0 1 1 0 0 +EDGE2 2559 2299 0.0234801 0.0170004 0.0165155 1 0 1 1 0 0 +EDGE2 2559 2419 -0.0307841 0.0534468 -0.0122629 1 0 1 1 0 0 +EDGE2 2559 2439 0.00857657 0.0896909 0.0264191 1 0 1 1 0 0 +EDGE2 2559 1259 0.017233 0.03031 -0.0147284 1 0 1 1 0 0 +EDGE2 2559 2420 1.0111 -0.021335 0.0344112 1 0 1 1 0 0 +EDGE2 2559 2500 1.05377 -0.0469632 -0.00499667 1 0 1 1 0 0 +EDGE2 2559 2520 0.886385 0.112535 -3.13648 1 0 1 1 0 0 +EDGE2 2559 2540 0.907621 0.0370872 -0.0185839 1 0 1 1 0 0 +EDGE2 2559 2440 1.01156 0.023357 -0.0156578 1 0 1 1 0 0 +EDGE2 2559 2300 0.919976 0.100897 -0.00356039 1 0 1 1 0 0 +EDGE2 2559 1260 0.950181 -0.0452441 0.0349384 1 0 1 1 0 0 +EDGE2 2560 2441 -0.0252458 -0.990232 -1.56545 1 0 1 1 0 0 +EDGE2 2560 2521 -0.0432115 0.921082 1.5715 1 0 1 1 0 0 +EDGE2 2560 2541 0.0662711 1.01945 1.59359 1 0 1 1 0 0 +EDGE2 2560 2301 0.022669 0.926798 1.60842 1 0 1 1 0 0 +EDGE2 2560 2421 -0.0477585 0.983374 1.56213 1 0 1 1 0 0 +EDGE2 2560 1261 -0.0341983 1.02743 1.58805 1 0 1 1 0 0 +EDGE2 2560 2499 -0.965231 -0.0183876 6.63165e-05 1 0 1 1 0 0 +EDGE2 2560 2559 -1.01052 -0.0505203 -0.0246634 1 0 1 1 0 0 +EDGE2 2560 2539 -0.931951 -0.0619249 -0.00202945 1 0 1 1 0 0 +EDGE2 2560 2299 -1.06491 0.070522 -0.010109 1 0 1 1 0 0 +EDGE2 2560 2419 -0.971344 0.0533395 0.0123187 1 0 1 1 0 0 +EDGE2 2560 2439 -0.959933 0.0146875 -0.00748741 1 0 1 1 0 0 +EDGE2 2560 1259 -0.884657 -0.0972193 -0.00727478 1 0 1 1 0 0 +EDGE2 2560 2420 0.0112091 -0.0396865 0.0261684 1 0 1 1 0 0 +EDGE2 2560 2500 -0.022207 0.0295186 -0.00885356 1 0 1 1 0 0 +EDGE2 2560 2520 -0.0518783 0.00956001 -3.15572 1 0 1 1 0 0 +EDGE2 2560 2540 0.000228631 -0.063116 -0.0188889 1 0 1 1 0 0 +EDGE2 2560 2440 0.0183049 0.00182903 0.0126695 1 0 1 1 0 0 +EDGE2 2560 2300 -0.0188267 -0.0216718 0.00487271 1 0 1 1 0 0 +EDGE2 2560 1260 -0.0399195 -0.0972935 -0.00540179 1 0 1 1 0 0 +EDGE2 2560 2501 -0.0179897 -0.951896 -1.56049 1 0 1 1 0 0 +EDGE2 2560 2519 1.05099 0.0565163 -3.16942 1 0 1 1 0 0 +EDGE2 2561 2302 1.02568 -0.0606873 -0.00807666 1 0 1 1 0 0 +EDGE2 2561 2522 1.03557 0.0846611 -0.000398577 1 0 1 1 0 0 +EDGE2 2561 2542 0.991517 0.0649309 0.0357327 1 0 1 1 0 0 +EDGE2 2561 2422 0.972175 -0.082397 -0.000388228 1 0 1 1 0 0 +EDGE2 2561 2521 -0.018652 0.11248 0.00860215 1 0 1 1 0 0 +EDGE2 2561 1262 0.982511 -0.0429325 0.00235335 1 0 1 1 0 0 +EDGE2 2561 2541 -0.0737482 -0.059694 -0.00871608 1 0 1 1 0 0 +EDGE2 2561 2301 0.0298543 -0.0657306 -0.0167853 1 0 1 1 0 0 +EDGE2 2561 2421 0.0159378 0.0253755 0.0432384 1 0 1 1 0 0 +EDGE2 2561 1261 0.0674489 -0.0277913 -0.0290287 1 0 1 1 0 0 +EDGE2 2561 2420 -0.953823 0.0336383 -1.57589 1 0 1 1 0 0 +EDGE2 2561 2560 -1.02963 -0.0221099 -1.55636 1 0 1 1 0 0 +EDGE2 2561 2500 -1.04882 -0.128277 -1.55539 1 0 1 1 0 0 +EDGE2 2561 2520 -0.96881 0.0147633 1.56887 1 0 1 1 0 0 +EDGE2 2561 2540 -0.94146 -0.0823474 -1.56815 1 0 1 1 0 0 +EDGE2 2561 2440 -1.00777 0.0511454 -1.5795 1 0 1 1 0 0 +EDGE2 2561 2300 -0.957264 0.0105704 -1.57216 1 0 1 1 0 0 +EDGE2 2561 1260 -0.975515 -0.0342786 -1.57485 1 0 1 1 0 0 +EDGE2 2562 2543 1.02677 0.0144258 0.00714854 1 0 1 1 0 0 +EDGE2 2562 2302 0.0760598 0.0101262 0.00756751 1 0 1 1 0 0 +EDGE2 2562 2303 1.01357 0.112586 0.0191157 1 0 1 1 0 0 +EDGE2 2562 2423 1.00187 0.0397462 -0.00633918 1 0 1 1 0 0 +EDGE2 2562 2523 1.04869 -0.025396 -0.0205624 1 0 1 1 0 0 +EDGE2 2562 1263 0.96201 0.0356199 -0.0303494 1 0 1 1 0 0 +EDGE2 2562 2522 -0.00712265 -0.105553 -0.0364356 1 0 1 1 0 0 +EDGE2 2562 2542 0.0482088 -0.0638791 -0.0197365 1 0 1 1 0 0 +EDGE2 2562 2422 -0.0714038 -0.03495 0.0184257 1 0 1 1 0 0 +EDGE2 2562 2521 -0.983385 -0.0208925 0.0337257 1 0 1 1 0 0 +EDGE2 2562 2561 -0.985971 -0.0382112 0.0284997 1 0 1 1 0 0 +EDGE2 2562 1262 -0.00967674 -0.0384936 0.0284946 1 0 1 1 0 0 +EDGE2 2562 2541 -1.03329 0.0516674 0.0115778 1 0 1 1 0 0 +EDGE2 2562 2301 -0.9686 -0.0024199 0.0163821 1 0 1 1 0 0 +EDGE2 2562 2421 -1.04796 0.0108699 -0.01816 1 0 1 1 0 0 +EDGE2 2562 1261 -1.13652 -0.0220594 0.00198525 1 0 1 1 0 0 +EDGE2 2563 2543 -0.017795 -0.110815 0.0281105 1 0 1 1 0 0 +EDGE2 2563 2424 0.977392 0.0283578 0.0197914 1 0 1 1 0 0 +EDGE2 2563 2544 1.02017 -0.0737328 -0.037849 1 0 1 1 0 0 +EDGE2 2563 2524 0.948809 -0.0448436 0.00207905 1 0 1 1 0 0 +EDGE2 2563 1264 1.01371 -0.0174671 -0.0114771 1 0 1 1 0 0 +EDGE2 2563 2304 1.06762 0.0183871 0.0017382 1 0 1 1 0 0 +EDGE2 2563 2302 -1.0385 -0.138208 -0.00503238 1 0 1 1 0 0 +EDGE2 2563 2303 0.0526657 0.007221 -0.0124151 1 0 1 1 0 0 +EDGE2 2563 2423 0.0436146 -0.0549787 -0.0201935 1 0 1 1 0 0 +EDGE2 2563 2523 0.0215837 0.0487083 0.032065 1 0 1 1 0 0 +EDGE2 2563 1263 0.0336489 -0.00635496 0.00718847 1 0 1 1 0 0 +EDGE2 2563 2522 -0.966863 0.0305076 -0.0033965 1 0 1 1 0 0 +EDGE2 2563 2542 -0.97672 -0.0419087 0.0154436 1 0 1 1 0 0 +EDGE2 2563 2562 -1.01316 0.0938343 -0.0194915 1 0 1 1 0 0 +EDGE2 2563 2422 -0.946274 0.0189793 -0.00939767 1 0 1 1 0 0 +EDGE2 2563 1262 -1.00808 -0.0151063 -0.0295779 1 0 1 1 0 0 +EDGE2 2564 2545 0.976232 -0.0192138 0.0305994 1 0 1 1 0 0 +EDGE2 2564 2543 -1.019 0.0253553 -0.0174246 1 0 1 1 0 0 +EDGE2 2564 1265 0.960165 0.0324757 -0.0058936 1 0 1 1 0 0 +EDGE2 2564 2305 0.988285 0.0595321 0.00873472 1 0 1 1 0 0 +EDGE2 2564 2405 1.02728 -0.00465567 -3.14211 1 0 1 1 0 0 +EDGE2 2564 2425 0.978013 -0.140599 -0.0118684 1 0 1 1 0 0 +EDGE2 2564 2525 1.03583 0.0601499 0.0260014 1 0 1 1 0 0 +EDGE2 2564 2385 0.971114 -0.0373467 -3.11544 1 0 1 1 0 0 +EDGE2 2564 1565 0.997961 -0.0332475 -3.1574 1 0 1 1 0 0 +EDGE2 2564 1585 0.96606 0.0830891 -3.14409 1 0 1 1 0 0 +EDGE2 2564 1845 1.12208 0.0680894 -3.14064 1 0 1 1 0 0 +EDGE2 2564 1545 1.05146 0.0558906 -3.15692 1 0 1 1 0 0 +EDGE2 2564 2424 0.0229917 -0.0122479 0.0119798 1 0 1 1 0 0 +EDGE2 2564 2544 0.00567969 -0.0314746 -0.00919851 1 0 1 1 0 0 +EDGE2 2564 2524 -0.0504434 0.0301687 -0.00234823 1 0 1 1 0 0 +EDGE2 2564 1264 0.00974315 0.00281105 -0.00554285 1 0 1 1 0 0 +EDGE2 2564 2304 0.00349643 -0.0038683 0.0140934 1 0 1 1 0 0 +EDGE2 2564 2563 -1.02764 -0.0395767 -0.0253765 1 0 1 1 0 0 +EDGE2 2564 2303 -1.01496 0.0480903 0.0280557 1 0 1 1 0 0 +EDGE2 2564 2423 -1.0551 -0.0518438 0.00219398 1 0 1 1 0 0 +EDGE2 2564 2523 -1.00941 0.0737155 0.00802812 1 0 1 1 0 0 +EDGE2 2564 1263 -0.954976 -0.0851995 -0.0245888 1 0 1 1 0 0 +EDGE2 2565 1564 1.04179 0.0764655 -3.09806 1 0 1 1 0 0 +EDGE2 2565 1844 0.950835 0.00894462 -3.15661 1 0 1 1 0 0 +EDGE2 2565 2384 0.982926 0.0289216 -3.14206 1 0 1 1 0 0 +EDGE2 2565 2404 1.01353 -0.0600899 -3.12414 1 0 1 1 0 0 +EDGE2 2565 1584 0.980568 0.0458953 -3.13504 1 0 1 1 0 0 +EDGE2 2565 1544 1.08609 0.00892471 -3.11593 1 0 1 1 0 0 +EDGE2 2565 2545 -0.0166939 0.0112994 -0.0059066 1 0 1 1 0 0 +EDGE2 2565 2426 0.098912 1.00813 1.58594 1 0 1 1 0 0 +EDGE2 2565 2546 0.0675973 0.977197 1.59179 1 0 1 1 0 0 +EDGE2 2565 2526 -0.0225482 0.972485 1.56428 1 0 1 1 0 0 +EDGE2 2565 2406 -0.0158094 0.925684 1.54361 1 0 1 1 0 0 +EDGE2 2565 1546 0.061389 1.02503 1.5879 1 0 1 1 0 0 +EDGE2 2565 1265 -0.0211814 -0.0856778 0.0240191 1 0 1 1 0 0 +EDGE2 2565 2305 0.0693917 -0.0422062 0.0113148 1 0 1 1 0 0 +EDGE2 2565 2405 0.00582835 0.00994996 -3.15075 1 0 1 1 0 0 +EDGE2 2565 2425 0.0238894 -0.00739583 0.00202745 1 0 1 1 0 0 +EDGE2 2565 2525 0.0495487 -0.0574394 0.0169865 1 0 1 1 0 0 +EDGE2 2565 2385 -0.0403955 0.0321086 -3.141 1 0 1 1 0 0 +EDGE2 2565 1565 0.0869156 0.0924641 -3.12905 1 0 1 1 0 0 +EDGE2 2565 1585 0.016632 -0.0312559 -3.17826 1 0 1 1 0 0 +EDGE2 2565 1845 0.0190169 -0.0485266 -3.12734 1 0 1 1 0 0 +EDGE2 2565 1545 -0.131222 0.00735236 -3.12335 1 0 1 1 0 0 +EDGE2 2565 2424 -1.01715 0.036073 0.0149079 1 0 1 1 0 0 +EDGE2 2565 2544 -1.01158 0.0198178 -0.0181394 1 0 1 1 0 0 +EDGE2 2565 2564 -1.08335 -0.0460859 -0.00100504 1 0 1 1 0 0 +EDGE2 2565 2524 -0.997584 0.0435944 -0.0369224 1 0 1 1 0 0 +EDGE2 2565 1264 -1.07691 -0.0407974 0.0153548 1 0 1 1 0 0 +EDGE2 2565 2304 -1.03578 0.0267373 0.0485433 1 0 1 1 0 0 +EDGE2 2565 1566 -0.0489457 -0.968764 -1.5889 1 0 1 1 0 0 +EDGE2 2565 1846 -0.0372003 -1.00166 -1.54026 1 0 1 1 0 0 +EDGE2 2565 2306 0.00837324 -1.01483 -1.55619 1 0 1 1 0 0 +EDGE2 2565 2386 -0.0943032 -1.01084 -1.58156 1 0 1 1 0 0 +EDGE2 2565 1586 0.0206379 -0.955487 -1.54539 1 0 1 1 0 0 +EDGE2 2565 1266 -0.000203359 -1.06286 -1.58568 1 0 1 1 0 0 +EDGE2 2566 2545 -0.957907 -0.0238439 -1.54873 1 0 1 1 0 0 +EDGE2 2566 2426 0.0558956 -0.0618234 -0.0110857 1 0 1 1 0 0 +EDGE2 2566 1547 0.947025 -0.104969 0.0121637 1 0 1 1 0 0 +EDGE2 2566 2427 1.01174 0.0384815 -0.0154465 1 0 1 1 0 0 +EDGE2 2566 2527 1.02469 -0.0918933 -0.0125457 1 0 1 1 0 0 +EDGE2 2566 2547 1.03653 0.00909035 0.0135776 1 0 1 1 0 0 +EDGE2 2566 2407 0.977595 0.0431959 0.00329607 1 0 1 1 0 0 +EDGE2 2566 2546 -0.0125928 -0.0716496 0.000189966 1 0 1 1 0 0 +EDGE2 2566 2526 -0.00449655 0.0421891 -0.0165915 1 0 1 1 0 0 +EDGE2 2566 2406 0.0976321 -0.00502825 0.0425948 1 0 1 1 0 0 +EDGE2 2566 1546 0.0720233 -0.0137566 -0.0248856 1 0 1 1 0 0 +EDGE2 2566 2565 -0.996677 0.00650686 -1.54554 1 0 1 1 0 0 +EDGE2 2566 1265 -1.05519 -0.0517018 -1.5966 1 0 1 1 0 0 +EDGE2 2566 2305 -1.03049 -0.0735956 -1.56067 1 0 1 1 0 0 +EDGE2 2566 2405 -0.986119 -0.00496431 1.54667 1 0 1 1 0 0 +EDGE2 2566 2425 -1.02596 -0.0258573 -1.60055 1 0 1 1 0 0 +EDGE2 2566 2525 -0.956919 0.0158826 -1.5797 1 0 1 1 0 0 +EDGE2 2566 2385 -1.02227 -0.031902 1.56557 1 0 1 1 0 0 +EDGE2 2566 1565 -0.921336 0.105453 1.58128 1 0 1 1 0 0 +EDGE2 2566 1585 -1.07717 -0.0432233 1.57567 1 0 1 1 0 0 +EDGE2 2566 1845 -0.973739 -0.00426771 1.57118 1 0 1 1 0 0 +EDGE2 2566 1545 -0.994725 -0.016048 1.54589 1 0 1 1 0 0 +EDGE2 2567 2528 0.957729 0.0355652 -0.0157223 1 0 1 1 0 0 +EDGE2 2567 2548 1.03272 0.0410147 0.00441744 1 0 1 1 0 0 +EDGE2 2567 1548 1.08053 -0.0128474 0.0190367 1 0 1 1 0 0 +EDGE2 2567 2408 1.05444 0.0511674 -0.0367889 1 0 1 1 0 0 +EDGE2 2567 2428 1.0289 0.0661129 0.00390335 1 0 1 1 0 0 +EDGE2 2567 2426 -0.99541 -0.0723295 0.0177973 1 0 1 1 0 0 +EDGE2 2567 1547 -0.0226081 -0.0774808 0.0219014 1 0 1 1 0 0 +EDGE2 2567 2427 -0.0036139 -0.0164558 0.00277269 1 0 1 1 0 0 +EDGE2 2567 2527 0.0495012 -0.00549422 -0.000196028 1 0 1 1 0 0 +EDGE2 2567 2547 0.095831 -0.100182 -0.00477836 1 0 1 1 0 0 +EDGE2 2567 2407 -0.023027 0.00662108 0.0219656 1 0 1 1 0 0 +EDGE2 2567 2546 -0.924014 -0.0212188 -0.0456088 1 0 1 1 0 0 +EDGE2 2567 2566 -1.10882 0.027359 0.0319491 1 0 1 1 0 0 +EDGE2 2567 2526 -0.932838 -0.0909722 -0.0230458 1 0 1 1 0 0 +EDGE2 2567 2406 -0.969548 -0.0273995 -0.0244866 1 0 1 1 0 0 +EDGE2 2567 1546 -0.914903 -0.0567456 0.000667337 1 0 1 1 0 0 +EDGE2 2568 2429 1.03893 0.118529 -0.0197389 1 0 1 1 0 0 +EDGE2 2568 2549 1.089 0.0707807 -0.0241381 1 0 1 1 0 0 +EDGE2 2568 2529 0.955177 -0.0194004 -0.0205388 1 0 1 1 0 0 +EDGE2 2568 1549 0.978477 -0.0624612 0.00588906 1 0 1 1 0 0 +EDGE2 2568 2409 0.956094 -0.0239288 -0.023479 1 0 1 1 0 0 +EDGE2 2568 2567 -1.03394 -0.0500585 -0.000365682 1 0 1 1 0 0 +EDGE2 2568 2528 -0.090992 0.0289405 -0.0031262 1 0 1 1 0 0 +EDGE2 2568 2548 0.0010444 -0.059365 0.00764534 1 0 1 1 0 0 +EDGE2 2568 1548 -0.0260419 0.0890369 -0.0139447 1 0 1 1 0 0 +EDGE2 2568 2408 -0.0735464 0.0060781 -0.0325556 1 0 1 1 0 0 +EDGE2 2568 2428 -0.0929287 0.0398317 0.00112124 1 0 1 1 0 0 +EDGE2 2568 1547 -1.01216 0.0206042 0.0174367 1 0 1 1 0 0 +EDGE2 2568 2427 -0.962752 0.00941012 0.0220114 1 0 1 1 0 0 +EDGE2 2568 2527 -1.00075 0.00726183 -0.0175529 1 0 1 1 0 0 +EDGE2 2568 2547 -1.04898 -0.0430281 -0.00215369 1 0 1 1 0 0 +EDGE2 2568 2407 -0.984394 -0.0609067 0.0145599 1 0 1 1 0 0 +EDGE2 2569 2430 1.0269 0.00424533 -0.0481785 1 0 1 1 0 0 +EDGE2 2569 2550 1.02324 -0.107482 0.0263596 1 0 1 1 0 0 +EDGE2 2569 2530 1.0795 -0.00514702 -0.00660521 1 0 1 1 0 0 +EDGE2 2569 1550 0.959905 -0.0779766 -0.00104276 1 0 1 1 0 0 +EDGE2 2569 1830 0.89713 -0.131532 -3.12799 1 0 1 1 0 0 +EDGE2 2569 2410 0.953437 0.0281417 0.011485 1 0 1 1 0 0 +EDGE2 2569 2429 -0.00317511 0.0490495 0.00651667 1 0 1 1 0 0 +EDGE2 2569 2549 -0.0322959 0.0378016 0.0114291 1 0 1 1 0 0 +EDGE2 2569 2529 -0.00845061 -0.0329349 0.0199758 1 0 1 1 0 0 +EDGE2 2569 1549 0.0668703 0.0104383 -0.00423395 1 0 1 1 0 0 +EDGE2 2569 2409 0.0295532 -0.0977325 -0.00820398 1 0 1 1 0 0 +EDGE2 2569 2528 -1.09768 0.00398479 -0.0164696 1 0 1 1 0 0 +EDGE2 2569 2568 -0.941355 -0.0229245 0.0416326 1 0 1 1 0 0 +EDGE2 2569 2548 -0.987135 0.0634503 -0.0338039 1 0 1 1 0 0 +EDGE2 2569 1548 -1.00776 0.000350406 0.00566461 1 0 1 1 0 0 +EDGE2 2569 2408 -1.08299 -0.0255334 0.0199419 1 0 1 1 0 0 +EDGE2 2569 2428 -1.04207 -0.00552745 -0.0252998 1 0 1 1 0 0 +EDGE2 2570 1829 1.04196 0.0190535 -3.17813 1 0 1 1 0 0 +EDGE2 2570 1831 -0.0599741 -1.08538 -1.54497 1 0 1 1 0 0 +EDGE2 2570 1551 0.0545259 -1.02087 -1.57877 1 0 1 1 0 0 +EDGE2 2570 2411 0.0363462 0.965251 1.57618 1 0 1 1 0 0 +EDGE2 2570 2430 0.0644547 -0.0691387 0.027196 1 0 1 1 0 0 +EDGE2 2570 2550 0.0159973 0.0730285 0.00662848 1 0 1 1 0 0 +EDGE2 2570 2530 0.0371412 -0.050232 0.00995007 1 0 1 1 0 0 +EDGE2 2570 1550 -0.015217 -0.0700971 -0.0243479 1 0 1 1 0 0 +EDGE2 2570 1830 0.0721096 0.0320244 -3.12757 1 0 1 1 0 0 +EDGE2 2570 2410 -0.093217 0.0351046 0.00388474 1 0 1 1 0 0 +EDGE2 2570 2531 -0.0371013 1.03096 1.57109 1 0 1 1 0 0 +EDGE2 2570 2551 0.102324 0.93788 1.59117 1 0 1 1 0 0 +EDGE2 2570 2431 0.00420963 1.00029 1.56498 1 0 1 1 0 0 +EDGE2 2570 2429 -0.974474 -0.0337261 -0.0157577 1 0 1 1 0 0 +EDGE2 2570 2549 -0.884774 -0.0371004 -0.00254633 1 0 1 1 0 0 +EDGE2 2570 2569 -1.08052 -0.0271607 -0.00738838 1 0 1 1 0 0 +EDGE2 2570 2529 -0.975336 0.041227 -0.00638258 1 0 1 1 0 0 +EDGE2 2570 1549 -0.994838 0.0192442 -0.0211923 1 0 1 1 0 0 +EDGE2 2570 2409 -0.962238 -0.0257617 0.0102688 1 0 1 1 0 0 +EDGE2 2571 2411 -0.0940279 0.0155172 0.0266366 1 0 1 1 0 0 +EDGE2 2571 2430 -0.938819 -0.0137089 -1.54871 1 0 1 1 0 0 +EDGE2 2571 2550 -0.903325 -0.0118539 -1.57897 1 0 1 1 0 0 +EDGE2 2571 2570 -0.991011 0.0014186 -1.55602 1 0 1 1 0 0 +EDGE2 2571 2530 -0.965145 -0.00237443 -1.55915 1 0 1 1 0 0 +EDGE2 2571 1550 -1.02678 -0.0567163 -1.56814 1 0 1 1 0 0 +EDGE2 2571 1830 -0.887366 -0.0966116 1.56451 1 0 1 1 0 0 +EDGE2 2571 2410 -1.08118 0.0165077 -1.55616 1 0 1 1 0 0 +EDGE2 2571 2531 -0.00781897 -0.0345699 0.012319 1 0 1 1 0 0 +EDGE2 2571 2551 0.0209534 -0.0535327 0.00565479 1 0 1 1 0 0 +EDGE2 2571 2431 -0.0507623 -0.0433796 0.0160477 1 0 1 1 0 0 +EDGE2 2571 2432 0.979123 0.0112123 0.0392645 1 0 1 1 0 0 +EDGE2 2571 2552 1.03234 -0.00109356 -0.0138155 1 0 1 1 0 0 +EDGE2 2571 2532 1.05028 0.0360339 0.00680189 1 0 1 1 0 0 +EDGE2 2571 2412 0.953955 0.0661025 -0.0144166 1 0 1 1 0 0 +EDGE2 2572 2411 -1.04313 -0.0346277 -0.0309153 1 0 1 1 0 0 +EDGE2 2572 2571 -0.915621 0.0617612 0.00103746 1 0 1 1 0 0 +EDGE2 2572 2531 -1.04371 -0.0233013 0.00773627 1 0 1 1 0 0 +EDGE2 2572 2551 -0.985804 -0.0644272 -0.0117843 1 0 1 1 0 0 +EDGE2 2572 2431 -0.975668 0.060472 0.0082006 1 0 1 1 0 0 +EDGE2 2572 2533 0.995599 0.0476148 0.0115753 1 0 1 1 0 0 +EDGE2 2572 2432 0.0910504 0.00933122 0.00720407 1 0 1 1 0 0 +EDGE2 2572 2552 -0.0428782 -0.0597484 -0.00255324 1 0 1 1 0 0 +EDGE2 2572 2532 0.0310272 -0.0555599 -0.0194281 1 0 1 1 0 0 +EDGE2 2572 2412 -0.00106876 0.0422285 0.00431843 1 0 1 1 0 0 +EDGE2 2572 2553 1.03622 0.0510779 0.0361244 1 0 1 1 0 0 +EDGE2 2572 2413 1.02318 0.033339 0.0107181 1 0 1 1 0 0 +EDGE2 2572 2433 1.07231 -0.0229288 0.00269638 1 0 1 1 0 0 +EDGE2 2573 2533 0.0291535 -0.042766 0.0197672 1 0 1 1 0 0 +EDGE2 2573 2432 -0.961521 0.0394451 0.00992961 1 0 1 1 0 0 +EDGE2 2573 2552 -1.019 0.0374498 -0.0103181 1 0 1 1 0 0 +EDGE2 2573 2572 -1.016 -0.0382814 -0.00332682 1 0 1 1 0 0 +EDGE2 2573 2532 -1.04972 0.0699133 -0.00441435 1 0 1 1 0 0 +EDGE2 2573 2412 -0.98715 -0.0423339 -0.036543 1 0 1 1 0 0 +EDGE2 2573 2553 0.0593969 -0.0528437 0.0207327 1 0 1 1 0 0 +EDGE2 2573 2554 0.961384 -0.0211735 0.00671393 1 0 1 1 0 0 +EDGE2 2573 2413 -0.0101595 0.00448043 0.0386186 1 0 1 1 0 0 +EDGE2 2573 2433 -0.0719408 -0.00823896 0.00377616 1 0 1 1 0 0 +EDGE2 2573 2414 0.967438 -0.00957937 0.0136021 1 0 1 1 0 0 +EDGE2 2573 2434 0.950024 -0.0138619 0.0339787 1 0 1 1 0 0 +EDGE2 2573 2534 1.10387 0.0319988 0.0131672 1 0 1 1 0 0 +EDGE2 2574 2533 -0.958966 0.0453825 -0.0134643 1 0 1 1 0 0 +EDGE2 2574 2573 -0.947049 -0.00381317 0.0134353 1 0 1 1 0 0 +EDGE2 2574 2553 -1.1413 -0.0351082 -0.0180677 1 0 1 1 0 0 +EDGE2 2574 2554 -0.0433468 0.0404916 -0.0220939 1 0 1 1 0 0 +EDGE2 2574 2413 -0.999335 0.032534 0.0311299 1 0 1 1 0 0 +EDGE2 2574 2433 -0.950864 0.0588324 -0.0121057 1 0 1 1 0 0 +EDGE2 2574 2414 0.044654 -0.118006 -0.0197944 1 0 1 1 0 0 +EDGE2 2574 2434 0.13513 0.0167391 0.0279528 1 0 1 1 0 0 +EDGE2 2574 2534 0.00150647 -0.0820404 -0.0107809 1 0 1 1 0 0 +EDGE2 2574 1235 1.04847 0.036846 -3.13272 1 0 1 1 0 0 +EDGE2 2574 2455 1.08024 0.040877 -3.13478 1 0 1 1 0 0 +EDGE2 2574 2535 1.12612 0.0202904 -0.00564559 1 0 1 1 0 0 +EDGE2 2574 2555 0.914873 -0.0444865 0.01028 1 0 1 1 0 0 +EDGE2 2574 2495 0.918324 -0.0155237 -3.15531 1 0 1 1 0 0 +EDGE2 2574 2295 1.01444 -0.00518132 -3.15853 1 0 1 1 0 0 +EDGE2 2574 2415 1.03882 0.000772671 -0.0146777 1 0 1 1 0 0 +EDGE2 2574 2435 1.04997 0.0198024 -0.0232151 1 0 1 1 0 0 +EDGE2 2574 1255 1.00101 0.000940851 -3.10608 1 0 1 1 0 0 +EDGE2 2575 2416 0.0142277 1.02881 1.57626 1 0 1 1 0 0 +EDGE2 2575 2456 -0.0544829 -1.04424 -1.5774 1 0 1 1 0 0 +EDGE2 2575 1236 0.0345602 -1.03324 -1.57008 1 0 1 1 0 0 +EDGE2 2575 2554 -0.986429 -0.00485312 -0.00607564 1 0 1 1 0 0 +EDGE2 2575 2574 -1.01046 -0.0542799 -0.00758799 1 0 1 1 0 0 +EDGE2 2575 2414 -0.966738 -0.0620336 0.00564801 1 0 1 1 0 0 +EDGE2 2575 2434 -1.01758 0.0838862 0.0134198 1 0 1 1 0 0 +EDGE2 2575 2534 -0.989235 -0.0769816 -0.0179203 1 0 1 1 0 0 +EDGE2 2575 1235 -0.0315922 -0.0604015 -3.1532 1 0 1 1 0 0 +EDGE2 2575 2455 0.0669046 -0.0487339 -3.13076 1 0 1 1 0 0 +EDGE2 2575 2535 -0.0570577 0.0101141 0.0363443 1 0 1 1 0 0 +EDGE2 2575 2555 0.0239673 0.00842408 -0.0189698 1 0 1 1 0 0 +EDGE2 2575 2495 -0.0184433 0.0244209 -3.15245 1 0 1 1 0 0 +EDGE2 2575 2295 -0.0345736 -0.0734848 -3.15081 1 0 1 1 0 0 +EDGE2 2575 2415 0.0998866 0.032147 -0.00288992 1 0 1 1 0 0 +EDGE2 2575 2435 -0.052606 0.0298978 0.00685655 1 0 1 1 0 0 +EDGE2 2575 1255 -0.00521872 0.0304778 -3.14594 1 0 1 1 0 0 +EDGE2 2575 1254 1.03163 -0.0359631 -3.12408 1 0 1 1 0 0 +EDGE2 2575 2454 1.06083 0.0647311 -3.14668 1 0 1 1 0 0 +EDGE2 2575 2494 1.00694 0.0333567 -3.12602 1 0 1 1 0 0 +EDGE2 2575 2294 1.02747 -0.0508401 -3.12707 1 0 1 1 0 0 +EDGE2 2575 1234 1.04585 0.0379038 -3.16239 1 0 1 1 0 0 +EDGE2 2575 2556 -0.0491057 1.0732 1.53157 1 0 1 1 0 0 +EDGE2 2575 2496 -0.030669 0.990511 1.55354 1 0 1 1 0 0 +EDGE2 2575 2536 0.0407463 0.991907 1.57335 1 0 1 1 0 0 +EDGE2 2575 2436 0.0324389 1.03382 1.57169 1 0 1 1 0 0 +EDGE2 2575 1256 0.0199701 0.990595 1.5613 1 0 1 1 0 0 +EDGE2 2575 2296 -0.0293088 1.03616 1.59291 1 0 1 1 0 0 +EDGE2 2576 2416 -0.0266866 0.0757334 -0.0438879 1 0 1 1 0 0 +EDGE2 2576 1235 -1.00578 -0.021959 1.59712 1 0 1 1 0 0 +EDGE2 2576 2455 -0.961828 -0.0135772 1.59073 1 0 1 1 0 0 +EDGE2 2576 2535 -1.09607 -0.0334285 -1.55244 1 0 1 1 0 0 +EDGE2 2576 2555 -0.952646 0.0693502 -1.53858 1 0 1 1 0 0 +EDGE2 2576 2575 -0.856438 -0.000168859 -1.55223 1 0 1 1 0 0 +EDGE2 2576 2495 -0.976453 -0.0954645 1.55652 1 0 1 1 0 0 +EDGE2 2576 2295 -0.954079 -0.00830169 1.56216 1 0 1 1 0 0 +EDGE2 2576 2415 -0.995666 -0.028902 -1.58859 1 0 1 1 0 0 +EDGE2 2576 2435 -0.969589 -0.0535342 -1.57133 1 0 1 1 0 0 +EDGE2 2576 1255 -0.94652 0.040716 1.5879 1 0 1 1 0 0 +EDGE2 2576 2556 0.0890157 -0.0827251 -0.0106955 1 0 1 1 0 0 +EDGE2 2576 2496 -0.0466541 0.011618 -0.00339304 1 0 1 1 0 0 +EDGE2 2576 2536 -0.026567 -0.0398505 0.00186239 1 0 1 1 0 0 +EDGE2 2576 2436 0.0328902 0.0607192 -0.0530372 1 0 1 1 0 0 +EDGE2 2576 1256 -0.049621 -0.0508107 -0.0109369 1 0 1 1 0 0 +EDGE2 2576 2296 0.00401599 -0.087439 0.0128159 1 0 1 1 0 0 +EDGE2 2576 2497 1.01328 -0.0331152 -0.00805727 1 0 1 1 0 0 +EDGE2 2576 2557 0.945709 -0.0293818 -0.02432 1 0 1 1 0 0 +EDGE2 2576 2537 0.950988 -0.0827928 0.0284242 1 0 1 1 0 0 +EDGE2 2576 2297 1.06452 0.0214623 0.0407569 1 0 1 1 0 0 +EDGE2 2576 2417 0.96677 -0.00832468 -0.017278 1 0 1 1 0 0 +EDGE2 2576 2437 0.981266 -0.0141908 0.0167529 1 0 1 1 0 0 +EDGE2 2576 1257 1.0194 -0.0493678 0.0156117 1 0 1 1 0 0 +EDGE2 2577 2416 -0.959722 0.0101471 0.0184411 1 0 1 1 0 0 +EDGE2 2577 2556 -0.968592 -0.0418163 -0.0174761 1 0 1 1 0 0 +EDGE2 2577 2576 -1.07267 -0.0397986 -0.0145192 1 0 1 1 0 0 +EDGE2 2577 2496 -0.930015 0.0437191 -0.0144136 1 0 1 1 0 0 +EDGE2 2577 2536 -1.00546 -0.0234836 0.0199145 1 0 1 1 0 0 +EDGE2 2577 2436 -0.961418 0.0120327 0.036477 1 0 1 1 0 0 +EDGE2 2577 2498 0.957709 -0.0086688 0.0132742 1 0 1 1 0 0 +EDGE2 2577 1256 -1.08531 0.00514491 -0.0223568 1 0 1 1 0 0 +EDGE2 2577 2296 -0.978081 -0.0923345 -0.00484936 1 0 1 1 0 0 +EDGE2 2577 2497 -0.0395746 -0.0022492 -0.0140778 1 0 1 1 0 0 +EDGE2 2577 2557 -0.0559742 0.0142185 0.00899163 1 0 1 1 0 0 +EDGE2 2577 2537 0.0487516 0.0149556 -0.00235477 1 0 1 1 0 0 +EDGE2 2577 2297 0.109532 0.0668368 0.00122162 1 0 1 1 0 0 +EDGE2 2577 2417 0.0419137 0.0054674 -0.0236775 1 0 1 1 0 0 +EDGE2 2577 2437 0.0356543 0.08114 0.00524322 1 0 1 1 0 0 +EDGE2 2577 1257 0.0517875 -0.0475828 -0.00577904 1 0 1 1 0 0 +EDGE2 2577 2558 0.952234 -0.0685536 -0.00259254 1 0 1 1 0 0 +EDGE2 2577 2538 0.954041 -0.0811703 -0.0104586 1 0 1 1 0 0 +EDGE2 2577 2298 1.10857 -0.0294563 -0.016368 1 0 1 1 0 0 +EDGE2 2577 2418 1.05501 0.094024 -0.0140661 1 0 1 1 0 0 +EDGE2 2577 2438 0.976416 0.0853781 0.0270265 1 0 1 1 0 0 +EDGE2 2577 1258 0.947366 -0.0437606 0.00747547 1 0 1 1 0 0 +EDGE2 2578 2498 -0.0279467 0.0683047 -0.0458342 1 0 1 1 0 0 +EDGE2 2578 2497 -0.960713 -0.0269486 0.0243662 1 0 1 1 0 0 +EDGE2 2578 2557 -0.90004 -0.0567094 0.00301432 1 0 1 1 0 0 +EDGE2 2578 2577 -0.96271 -0.100074 0.0118687 1 0 1 1 0 0 +EDGE2 2578 2537 -1.00152 -0.0552505 -0.00439704 1 0 1 1 0 0 +EDGE2 2578 2297 -0.973599 -0.0411405 -0.0166138 1 0 1 1 0 0 +EDGE2 2578 2417 -0.991415 0.0509317 -0.0322605 1 0 1 1 0 0 +EDGE2 2578 2437 -0.972022 0.0450714 0.0271705 1 0 1 1 0 0 +EDGE2 2578 1257 -1.02887 0.0592435 -0.00550882 1 0 1 1 0 0 +EDGE2 2578 2558 0.062143 0.0269779 0.0121321 1 0 1 1 0 0 +EDGE2 2578 2538 -0.0666983 0.0321883 0.00484133 1 0 1 1 0 0 +EDGE2 2578 2298 0.0193181 0.0919155 0.0209457 1 0 1 1 0 0 +EDGE2 2578 2418 -0.0683433 0.103451 -0.0261278 1 0 1 1 0 0 +EDGE2 2578 2438 -0.0332959 0.026437 -0.00304434 1 0 1 1 0 0 +EDGE2 2578 1258 -0.0564848 0.0094783 0.00975023 1 0 1 1 0 0 +EDGE2 2578 2499 1.04519 -0.0394381 -0.0100705 1 0 1 1 0 0 +EDGE2 2578 2559 0.919705 -0.0626558 -0.0344184 1 0 1 1 0 0 +EDGE2 2578 2539 0.957629 0.00507445 0.0031454 1 0 1 1 0 0 +EDGE2 2578 2299 1.00638 -0.0595971 0.0019392 1 0 1 1 0 0 +EDGE2 2578 2419 0.986898 -0.0648192 0.0186099 1 0 1 1 0 0 +EDGE2 2578 2439 0.972289 -0.00867563 0.0107662 1 0 1 1 0 0 +EDGE2 2578 1259 1.02231 0.0545287 0.0112826 1 0 1 1 0 0 +EDGE2 2579 2498 -1.01254 0.0485681 0.00896088 1 0 1 1 0 0 +EDGE2 2579 2558 -0.98681 0.0287117 0.00452548 1 0 1 1 0 0 +EDGE2 2579 2578 -0.959124 -0.111093 -0.00894856 1 0 1 1 0 0 +EDGE2 2579 2538 -1.0881 -0.0789328 0.0295035 1 0 1 1 0 0 +EDGE2 2579 2298 -0.936443 -0.0352767 -0.0359507 1 0 1 1 0 0 +EDGE2 2579 2418 -0.94054 0.031652 0.0164024 1 0 1 1 0 0 +EDGE2 2579 2438 -1.08828 0.0708867 0.0356407 1 0 1 1 0 0 +EDGE2 2579 1258 -1.03966 0.0658811 -0.013699 1 0 1 1 0 0 +EDGE2 2579 2499 0.0197015 -0.0149665 -0.00170159 1 0 1 1 0 0 +EDGE2 2579 2559 -0.00879233 -0.00204662 -0.0295035 1 0 1 1 0 0 +EDGE2 2579 2539 -0.00568224 -0.0713467 -0.000897094 1 0 1 1 0 0 +EDGE2 2579 2299 0.0247625 -0.0240044 0.0040598 1 0 1 1 0 0 +EDGE2 2579 2419 -0.0599939 -0.0707548 0.0132755 1 0 1 1 0 0 +EDGE2 2579 2439 0.110075 0.0180104 0.0111823 1 0 1 1 0 0 +EDGE2 2579 1259 0.029015 0.0221092 -0.00791365 1 0 1 1 0 0 +EDGE2 2579 2420 1.02321 -0.0220505 -0.0113512 1 0 1 1 0 0 +EDGE2 2579 2560 0.980853 0.0649176 -0.0171851 1 0 1 1 0 0 +EDGE2 2579 2500 1.05409 -0.0585901 0.00881 1 0 1 1 0 0 +EDGE2 2579 2520 0.920971 -0.0619257 -3.11949 1 0 1 1 0 0 +EDGE2 2579 2540 0.993315 -0.0717786 -0.0228071 1 0 1 1 0 0 +EDGE2 2579 2440 0.992019 -0.01766 0.0111198 1 0 1 1 0 0 +EDGE2 2579 2300 1.05552 0.0179186 0.0198647 1 0 1 1 0 0 +EDGE2 2579 1260 1.05369 -0.0607185 -0.0239632 1 0 1 1 0 0 +EDGE2 2580 2441 0.0398329 -0.974798 -1.55577 1 0 1 1 0 0 +EDGE2 2580 2521 -0.0782642 0.961928 1.57623 1 0 1 1 0 0 +EDGE2 2580 2561 -0.0402553 1.08073 1.58278 1 0 1 1 0 0 +EDGE2 2580 2541 0.0746004 0.920706 1.57077 1 0 1 1 0 0 +EDGE2 2580 2301 -0.00848423 1.0729 1.57991 1 0 1 1 0 0 +EDGE2 2580 2421 0.0423762 0.992176 1.57201 1 0 1 1 0 0 +EDGE2 2580 1261 0.0010364 1.04474 1.60415 1 0 1 1 0 0 +EDGE2 2580 2499 -1.07216 -0.0586296 -0.0096666 1 0 1 1 0 0 +EDGE2 2580 2559 -1.03105 -0.112049 0.0239944 1 0 1 1 0 0 +EDGE2 2580 2579 -1.00206 -0.0548437 -0.0293528 1 0 1 1 0 0 +EDGE2 2580 2539 -0.977474 -0.00695897 0.0106319 1 0 1 1 0 0 +EDGE2 2580 2299 -0.991643 0.0318381 -0.0195703 1 0 1 1 0 0 +EDGE2 2580 2419 -1.03326 -0.0675165 0.0123416 1 0 1 1 0 0 +EDGE2 2580 2439 -1.01694 0.0508272 -0.0296185 1 0 1 1 0 0 +EDGE2 2580 1259 -0.946896 -0.0426347 0.00198687 1 0 1 1 0 0 +EDGE2 2580 2420 0.0202553 0.0685075 -0.0118058 1 0 1 1 0 0 +EDGE2 2580 2560 0.00651341 -0.0313355 0.00677915 1 0 1 1 0 0 +EDGE2 2580 2500 -0.0516893 0.0748953 0.0032923 1 0 1 1 0 0 +EDGE2 2580 2520 -0.0295163 -0.00421343 -3.15387 1 0 1 1 0 0 +EDGE2 2580 2540 0.0508304 -0.116587 -0.020759 1 0 1 1 0 0 +EDGE2 2580 2440 -0.00427169 0.0353136 -0.00218297 1 0 1 1 0 0 +EDGE2 2580 2300 0.123144 0.0710551 0.00474007 1 0 1 1 0 0 +EDGE2 2580 1260 -0.0594178 0.0577415 -0.0182235 1 0 1 1 0 0 +EDGE2 2580 2501 -0.0326331 -1.04427 -1.65435 1 0 1 1 0 0 +EDGE2 2580 2519 1.04199 -0.11 -3.12013 1 0 1 1 0 0 +EDGE2 2581 2302 0.91719 -0.0050491 -0.0581948 1 0 1 1 0 0 +EDGE2 2581 2522 1.01972 -0.0636304 0.0157759 1 0 1 1 0 0 +EDGE2 2581 2542 1.03389 0.0175214 0.00571173 1 0 1 1 0 0 +EDGE2 2581 2562 1.11431 0.0322477 0.00101444 1 0 1 1 0 0 +EDGE2 2581 2422 1.01632 -0.0505946 -0.0401941 1 0 1 1 0 0 +EDGE2 2581 2521 0.0844785 0.0849101 0.0389684 1 0 1 1 0 0 +EDGE2 2581 2561 0.0144434 -0.117649 -0.0176301 1 0 1 1 0 0 +EDGE2 2581 1262 0.9791 0.0741205 -0.00878798 1 0 1 1 0 0 +EDGE2 2581 2541 -0.0940987 0.0811996 0.00633002 1 0 1 1 0 0 +EDGE2 2581 2301 0.00224307 -0.0597653 0.0144323 1 0 1 1 0 0 +EDGE2 2581 2421 0.0458435 -0.0164319 0.00545051 1 0 1 1 0 0 +EDGE2 2581 1261 0.0559107 0.00938595 -0.0242317 1 0 1 1 0 0 +EDGE2 2581 2420 -1.03081 0.0530954 -1.61243 1 0 1 1 0 0 +EDGE2 2581 2560 -1.02778 -0.0211815 -1.57164 1 0 1 1 0 0 +EDGE2 2581 2580 -0.974072 0.0259514 -1.53674 1 0 1 1 0 0 +EDGE2 2581 2500 -0.963329 -0.0429357 -1.58673 1 0 1 1 0 0 +EDGE2 2581 2520 -0.953491 0.0255923 1.53728 1 0 1 1 0 0 +EDGE2 2581 2540 -1.07227 0.0187681 -1.52054 1 0 1 1 0 0 +EDGE2 2581 2440 -1.05129 0.0420925 -1.5362 1 0 1 1 0 0 +EDGE2 2581 2300 -0.99285 -0.0673838 -1.53632 1 0 1 1 0 0 +EDGE2 2581 1260 -0.981752 0.0475322 -1.57603 1 0 1 1 0 0 +EDGE2 2582 2543 0.910892 0.0647208 -0.0516149 1 0 1 1 0 0 +EDGE2 2582 2563 0.979967 -0.0494902 -0.0263 1 0 1 1 0 0 +EDGE2 2582 2302 -0.00794516 0.0477764 0.00638008 1 0 1 1 0 0 +EDGE2 2582 2303 0.977101 0.0673142 0.0157787 1 0 1 1 0 0 +EDGE2 2582 2423 0.958016 0.00155888 -0.00570182 1 0 1 1 0 0 +EDGE2 2582 2523 1.15079 0.0488129 0.01038 1 0 1 1 0 0 +EDGE2 2582 1263 1.04137 -0.0293691 -0.0234187 1 0 1 1 0 0 +EDGE2 2582 2522 -0.0699699 0.0649904 -0.0289846 1 0 1 1 0 0 +EDGE2 2582 2542 0.0444579 0.0458396 -0.0101797 1 0 1 1 0 0 +EDGE2 2582 2562 -0.0253849 -0.00366945 0.00408734 1 0 1 1 0 0 +EDGE2 2582 2422 0.00644031 0.0480413 -0.0145874 1 0 1 1 0 0 +EDGE2 2582 2521 -1.06116 -0.0620333 0.00307967 1 0 1 1 0 0 +EDGE2 2582 2561 -1.06903 -0.105836 0.0050717 1 0 1 1 0 0 +EDGE2 2582 2581 -0.98609 -0.00538875 0.0226724 1 0 1 1 0 0 +EDGE2 2582 1262 0.00788761 -0.0488395 0.0234283 1 0 1 1 0 0 +EDGE2 2582 2541 -0.869277 -0.0403744 -0.023272 1 0 1 1 0 0 +EDGE2 2582 2301 -1.00155 -0.0125169 -0.0324442 1 0 1 1 0 0 +EDGE2 2582 2421 -0.984159 0.0273524 -0.0052507 1 0 1 1 0 0 +EDGE2 2582 1261 -0.998184 -0.00151493 -0.00190486 1 0 1 1 0 0 +EDGE2 2583 2543 0.000758686 0.0200517 -0.0297443 1 0 1 1 0 0 +EDGE2 2583 2424 1.05669 -0.00665904 0.00452761 1 0 1 1 0 0 +EDGE2 2583 2544 0.975964 -0.0326673 0.035062 1 0 1 1 0 0 +EDGE2 2583 2564 1.02753 -0.0521962 0.00543237 1 0 1 1 0 0 +EDGE2 2583 2524 0.994781 0.0847783 0.0354287 1 0 1 1 0 0 +EDGE2 2583 1264 1.016 -0.00161042 -0.00475009 1 0 1 1 0 0 +EDGE2 2583 2304 0.960254 0.0610918 0.0188636 1 0 1 1 0 0 +EDGE2 2583 2563 0.0203734 0.042551 -0.034792 1 0 1 1 0 0 +EDGE2 2583 2302 -0.973652 0.0469727 0.00518059 1 0 1 1 0 0 +EDGE2 2583 2582 -0.956506 0.0231201 -0.0311089 1 0 1 1 0 0 +EDGE2 2583 2303 0.00974715 -0.0308729 0.00605923 1 0 1 1 0 0 +EDGE2 2583 2423 0.0471338 0.0519693 0.0202641 1 0 1 1 0 0 +EDGE2 2583 2523 -0.011473 0.0487447 0.0111749 1 0 1 1 0 0 +EDGE2 2583 1263 0.0230104 0.0211422 -0.0279528 1 0 1 1 0 0 +EDGE2 2583 2522 -0.972294 -0.0416501 0.0200077 1 0 1 1 0 0 +EDGE2 2583 2542 -1.00922 -0.00586221 -0.00870221 1 0 1 1 0 0 +EDGE2 2583 2562 -0.997196 -0.1047 -0.0422285 1 0 1 1 0 0 +EDGE2 2583 2422 -1.00328 0.0703383 0.014586 1 0 1 1 0 0 +EDGE2 2583 1262 -1.03293 0.017865 -0.0236263 1 0 1 1 0 0 +EDGE2 2584 2545 0.91244 0.0354739 0.0299849 1 0 1 1 0 0 +EDGE2 2584 2565 0.920382 -0.0171746 -0.0319545 1 0 1 1 0 0 +EDGE2 2584 2543 -0.968886 0.00587737 -0.0202599 1 0 1 1 0 0 +EDGE2 2584 1265 1.03546 0.0369269 0.0262984 1 0 1 1 0 0 +EDGE2 2584 2305 0.979034 0.0236599 -0.0186938 1 0 1 1 0 0 +EDGE2 2584 2405 1.0698 -0.00491018 -3.16865 1 0 1 1 0 0 +EDGE2 2584 2425 1.01447 0.0225485 -0.00725056 1 0 1 1 0 0 +EDGE2 2584 2525 1.03395 0.0306414 0.00771751 1 0 1 1 0 0 +EDGE2 2584 2385 0.969912 -0.0444522 -3.14058 1 0 1 1 0 0 +EDGE2 2584 1565 0.950042 -0.0694009 -3.12597 1 0 1 1 0 0 +EDGE2 2584 1585 0.956825 -0.0373336 -3.11578 1 0 1 1 0 0 +EDGE2 2584 1845 1.03808 0.0388175 -3.14691 1 0 1 1 0 0 +EDGE2 2584 1545 0.957745 0.0444172 -3.16914 1 0 1 1 0 0 +EDGE2 2584 2424 -0.0173151 -0.0118447 0.0576116 1 0 1 1 0 0 +EDGE2 2584 2544 -0.0154998 -0.0128075 0.0104306 1 0 1 1 0 0 +EDGE2 2584 2564 -0.0256103 -0.0174904 0.00873232 1 0 1 1 0 0 +EDGE2 2584 2524 -0.0602712 0.0607259 -0.0242403 1 0 1 1 0 0 +EDGE2 2584 2583 -1.06002 0.0476255 0.0014769 1 0 1 1 0 0 +EDGE2 2584 1264 -0.057342 -0.00910286 -0.0103989 1 0 1 1 0 0 +EDGE2 2584 2304 0.0230323 -0.0510612 0.0134151 1 0 1 1 0 0 +EDGE2 2584 2563 -0.940381 0.0451434 -0.0200141 1 0 1 1 0 0 +EDGE2 2584 2303 -1.0087 -0.0288862 -0.000397114 1 0 1 1 0 0 +EDGE2 2584 2423 -0.986404 0.00680455 0.0421855 1 0 1 1 0 0 +EDGE2 2584 2523 -0.978468 -0.0420103 0.0106549 1 0 1 1 0 0 +EDGE2 2584 1263 -0.955631 -0.113918 0.0161573 1 0 1 1 0 0 +EDGE2 2585 1564 1.06425 0.00772061 -3.10777 1 0 1 1 0 0 +EDGE2 2585 1844 0.83782 -0.033863 -3.17499 1 0 1 1 0 0 +EDGE2 2585 2384 1.00858 0.061254 -3.1362 1 0 1 1 0 0 +EDGE2 2585 2404 0.958947 -0.0159946 -3.11019 1 0 1 1 0 0 +EDGE2 2585 1584 0.938886 0.0437297 -3.11927 1 0 1 1 0 0 +EDGE2 2585 1544 1.00414 0.0961585 -3.15477 1 0 1 1 0 0 +EDGE2 2585 2545 -0.0313571 -0.0509439 -0.0136301 1 0 1 1 0 0 +EDGE2 2585 2426 -0.091773 1.09736 1.56326 1 0 1 1 0 0 +EDGE2 2585 2546 0.0154293 1.01536 1.58543 1 0 1 1 0 0 +EDGE2 2585 2566 -0.0224715 1.00561 1.56732 1 0 1 1 0 0 +EDGE2 2585 2526 0.0590084 1.00755 1.54533 1 0 1 1 0 0 +EDGE2 2585 2406 -0.038489 0.934427 1.57625 1 0 1 1 0 0 +EDGE2 2585 1546 0.0391217 1.03185 1.6008 1 0 1 1 0 0 +EDGE2 2585 2565 0.0958596 0.0237844 -0.0302329 1 0 1 1 0 0 +EDGE2 2585 1265 0.0304807 0.0748747 0.00273259 1 0 1 1 0 0 +EDGE2 2585 2305 -0.0254866 0.0386094 -0.0240839 1 0 1 1 0 0 +EDGE2 2585 2405 0.0437638 -0.0167539 -3.1504 1 0 1 1 0 0 +EDGE2 2585 2425 0.0149235 -0.0473428 -0.0042666 1 0 1 1 0 0 +EDGE2 2585 2525 -0.136351 -0.0278386 0.0110859 1 0 1 1 0 0 +EDGE2 2585 2385 -0.025622 -0.0697746 -3.12186 1 0 1 1 0 0 +EDGE2 2585 1565 0.0212782 0.0224392 -3.14743 1 0 1 1 0 0 +EDGE2 2585 1585 -0.0365868 -0.069758 -3.14035 1 0 1 1 0 0 +EDGE2 2585 1845 -0.0228862 -0.0141837 -3.14642 1 0 1 1 0 0 +EDGE2 2585 1545 -0.0482059 0.0148138 -3.13289 1 0 1 1 0 0 +EDGE2 2585 2424 -0.930983 0.0205722 0.00457741 1 0 1 1 0 0 +EDGE2 2585 2544 -0.992685 0.00546861 -0.0156881 1 0 1 1 0 0 +EDGE2 2585 2564 -0.889863 -0.0294237 0.0135965 1 0 1 1 0 0 +EDGE2 2585 2584 -0.923041 0.0564924 0.00117467 1 0 1 1 0 0 +EDGE2 2585 2524 -0.900579 -0.0155015 -0.000687801 1 0 1 1 0 0 +EDGE2 2585 1264 -0.995897 -0.0133746 -0.0595575 1 0 1 1 0 0 +EDGE2 2585 2304 -0.921284 0.115894 0.0023767 1 0 1 1 0 0 +EDGE2 2585 1566 0.0331639 -0.979337 -1.57395 1 0 1 1 0 0 +EDGE2 2585 1846 0.0403651 -1.02 -1.58694 1 0 1 1 0 0 +EDGE2 2585 2306 -0.0758482 -1.00118 -1.57937 1 0 1 1 0 0 +EDGE2 2585 2386 0.0133481 -0.959319 -1.57627 1 0 1 1 0 0 +EDGE2 2585 1586 -0.0452993 -1.02113 -1.53894 1 0 1 1 0 0 +EDGE2 2585 1266 -0.0985264 -0.992609 -1.58009 1 0 1 1 0 0 +EDGE2 2586 2545 -0.941105 -0.0206797 -1.57886 1 0 1 1 0 0 +EDGE2 2586 2567 0.980389 0.0229471 0.0113735 1 0 1 1 0 0 +EDGE2 2586 2426 0.00167817 0.0211115 0.00405882 1 0 1 1 0 0 +EDGE2 2586 1547 1.02079 -0.121894 0.00892962 1 0 1 1 0 0 +EDGE2 2586 2427 0.962746 0.0406904 0.0168763 1 0 1 1 0 0 +EDGE2 2586 2527 1.01504 -0.0370795 0.00221216 1 0 1 1 0 0 +EDGE2 2586 2547 0.971034 -0.084912 -0.0415456 1 0 1 1 0 0 +EDGE2 2586 2407 1.01572 0.0405541 0.00677944 1 0 1 1 0 0 +EDGE2 2586 2546 0.0161129 0.0154417 -0.0149897 1 0 1 1 0 0 +EDGE2 2586 2566 -0.112662 -0.0490779 0.022208 1 0 1 1 0 0 +EDGE2 2586 2526 -0.0790745 0.0625222 0.0137259 1 0 1 1 0 0 +EDGE2 2586 2406 -0.00972562 -0.0924268 -0.0142981 1 0 1 1 0 0 +EDGE2 2586 2585 -0.938022 0.0545583 -1.57386 1 0 1 1 0 0 +EDGE2 2586 1546 0.029543 0.0536212 -0.00161234 1 0 1 1 0 0 +EDGE2 2586 2565 -0.996894 -0.0866763 -1.57365 1 0 1 1 0 0 +EDGE2 2586 1265 -1.01218 -0.00523191 -1.57248 1 0 1 1 0 0 +EDGE2 2586 2305 -0.938297 0.0302373 -1.55898 1 0 1 1 0 0 +EDGE2 2586 2405 -0.972073 -0.0270034 1.56661 1 0 1 1 0 0 +EDGE2 2586 2425 -1.13236 -0.0280197 -1.56284 1 0 1 1 0 0 +EDGE2 2586 2525 -0.938104 0.0102126 -1.59121 1 0 1 1 0 0 +EDGE2 2586 2385 -1.01219 0.0882872 1.58799 1 0 1 1 0 0 +EDGE2 2586 1565 -0.912642 -0.0298071 1.57487 1 0 1 1 0 0 +EDGE2 2586 1585 -1.01194 -0.0175031 1.56812 1 0 1 1 0 0 +EDGE2 2586 1845 -1.06364 0.0957725 1.57405 1 0 1 1 0 0 +EDGE2 2586 1545 -0.874874 0.0194852 1.62567 1 0 1 1 0 0 +EDGE2 2587 2567 -0.0132222 0.0767874 0.0184357 1 0 1 1 0 0 +EDGE2 2587 2528 0.972407 0.0127262 -0.00127608 1 0 1 1 0 0 +EDGE2 2587 2568 0.976173 0.00535667 0.0251076 1 0 1 1 0 0 +EDGE2 2587 2548 0.891149 -0.0585224 0.000807558 1 0 1 1 0 0 +EDGE2 2587 1548 0.965189 0.0322458 0.0238146 1 0 1 1 0 0 +EDGE2 2587 2408 1.05279 0.0339034 0.0182713 1 0 1 1 0 0 +EDGE2 2587 2428 0.988916 -0.00112056 0.00383983 1 0 1 1 0 0 +EDGE2 2587 2426 -1.00372 0.00452523 -0.00759885 1 0 1 1 0 0 +EDGE2 2587 1547 -0.0689954 0.02156 -0.0199667 1 0 1 1 0 0 +EDGE2 2587 2427 0.015325 0.0682013 0.025335 1 0 1 1 0 0 +EDGE2 2587 2527 0.0123794 -0.0285431 0.0211888 1 0 1 1 0 0 +EDGE2 2587 2547 -0.00695403 -0.0301863 -0.0349029 1 0 1 1 0 0 +EDGE2 2587 2407 0.0124198 0.0366279 -0.0156682 1 0 1 1 0 0 +EDGE2 2587 2546 -0.97243 -0.0664492 -0.00253345 1 0 1 1 0 0 +EDGE2 2587 2566 -1.07382 -0.016416 -0.0149692 1 0 1 1 0 0 +EDGE2 2587 2586 -1.0622 0.0233195 0.00929877 1 0 1 1 0 0 +EDGE2 2587 2526 -0.985449 -0.0329688 0.0249189 1 0 1 1 0 0 +EDGE2 2587 2406 -1.05606 0.124206 -0.018648 1 0 1 1 0 0 +EDGE2 2587 1546 -0.993545 -0.0668465 0.00352395 1 0 1 1 0 0 +EDGE2 2588 2429 1.08081 -0.017497 0.00257311 1 0 1 1 0 0 +EDGE2 2588 2549 0.908912 -0.00328916 -0.00606916 1 0 1 1 0 0 +EDGE2 2588 2569 0.969479 -0.04719 0.0201166 1 0 1 1 0 0 +EDGE2 2588 2529 1.09041 -0.052964 0.0197067 1 0 1 1 0 0 +EDGE2 2588 1549 0.947931 0.0468847 -0.00474365 1 0 1 1 0 0 +EDGE2 2588 2409 0.983576 0.0459179 -0.00625121 1 0 1 1 0 0 +EDGE2 2588 2567 -1.06632 -0.0330416 -0.00240303 1 0 1 1 0 0 +EDGE2 2588 2528 -0.0427188 0.0276499 0.0656344 1 0 1 1 0 0 +EDGE2 2588 2568 0.0339603 0.0812426 0.0555073 1 0 1 1 0 0 +EDGE2 2588 2548 -0.114486 -0.0262968 0.00863983 1 0 1 1 0 0 +EDGE2 2588 1548 0.00585206 0.0293711 0.0227011 1 0 1 1 0 0 +EDGE2 2588 2408 0.036856 -0.016058 0.010918 1 0 1 1 0 0 +EDGE2 2588 2428 -0.0786176 -0.0253855 -0.00347958 1 0 1 1 0 0 +EDGE2 2588 2587 -0.929782 -0.0346253 -0.00438318 1 0 1 1 0 0 +EDGE2 2588 1547 -0.934479 -0.07992 -3.31824e-06 1 0 1 1 0 0 +EDGE2 2588 2427 -1.05819 -0.0149098 0.0210762 1 0 1 1 0 0 +EDGE2 2588 2527 -0.971724 0.0850942 0.00784142 1 0 1 1 0 0 +EDGE2 2588 2547 -0.964157 0.0553656 -0.00108004 1 0 1 1 0 0 +EDGE2 2588 2407 -1.08162 -0.0641896 0.0116907 1 0 1 1 0 0 +EDGE2 2589 2430 1.01627 -0.0581354 -0.00439018 1 0 1 1 0 0 +EDGE2 2589 2550 0.987181 -0.0111286 0.0138105 1 0 1 1 0 0 +EDGE2 2589 2570 0.979549 -0.010091 0.00744374 1 0 1 1 0 0 +EDGE2 2589 2530 0.97416 -0.00551692 0.0411036 1 0 1 1 0 0 +EDGE2 2589 1550 1.0572 -0.0213385 0.0099175 1 0 1 1 0 0 +EDGE2 2589 1830 0.885294 -0.0301136 -3.1326 1 0 1 1 0 0 +EDGE2 2589 2410 1.09619 0.0471502 0.0132894 1 0 1 1 0 0 +EDGE2 2589 2429 -0.0244004 0.00105923 0.0132839 1 0 1 1 0 0 +EDGE2 2589 2549 0.0238735 -0.0372498 -0.0264763 1 0 1 1 0 0 +EDGE2 2589 2569 0.0122907 0.0401812 -0.0268128 1 0 1 1 0 0 +EDGE2 2589 2529 -0.0425476 0.057406 0.0071645 1 0 1 1 0 0 +EDGE2 2589 1549 -0.0876375 0.0935625 -0.034519 1 0 1 1 0 0 +EDGE2 2589 2409 -0.125006 -0.033074 0.0110125 1 0 1 1 0 0 +EDGE2 2589 2528 -0.975818 0.0373003 0.0179788 1 0 1 1 0 0 +EDGE2 2589 2568 -0.929258 0.0860188 -0.00812786 1 0 1 1 0 0 +EDGE2 2589 2588 -1.09425 -0.0593398 -0.0216363 1 0 1 1 0 0 +EDGE2 2589 2548 -0.987902 -0.120293 0.00394857 1 0 1 1 0 0 +EDGE2 2589 1548 -0.948922 0.0334892 0.00644923 1 0 1 1 0 0 +EDGE2 2589 2408 -0.971127 0.0103084 4.01542e-05 1 0 1 1 0 0 +EDGE2 2589 2428 -0.921304 0.0397287 0.0101508 1 0 1 1 0 0 +EDGE2 2590 1829 0.982215 0.0205628 -3.19445 1 0 1 1 0 0 +EDGE2 2590 1831 -0.0892204 -1.09959 -1.5957 1 0 1 1 0 0 +EDGE2 2590 1551 -0.00324496 -0.989727 -1.53847 1 0 1 1 0 0 +EDGE2 2590 2411 0.0420287 1.01915 1.55661 1 0 1 1 0 0 +EDGE2 2590 2571 -0.0133874 1.05214 1.58499 1 0 1 1 0 0 +EDGE2 2590 2430 -0.0703168 -0.0616335 0.0321884 1 0 1 1 0 0 +EDGE2 2590 2550 0.0848331 -0.0461621 -0.0128894 1 0 1 1 0 0 +EDGE2 2590 2570 -0.0288078 0.105071 -0.00554793 1 0 1 1 0 0 +EDGE2 2590 2530 -0.134888 -0.0483258 -0.0272114 1 0 1 1 0 0 +EDGE2 2590 1550 0.00996356 0.0509708 -0.0144798 1 0 1 1 0 0 +EDGE2 2590 1830 0.00697895 0.00311975 -3.15243 1 0 1 1 0 0 +EDGE2 2590 2410 0.0983116 -0.0510087 -0.00964141 1 0 1 1 0 0 +EDGE2 2590 2531 -0.0304039 1.03045 1.59246 1 0 1 1 0 0 +EDGE2 2590 2551 -0.00630457 1.06512 1.59531 1 0 1 1 0 0 +EDGE2 2590 2431 0.0301367 0.971991 1.56711 1 0 1 1 0 0 +EDGE2 2590 2429 -1.00778 0.0333639 0.0169946 1 0 1 1 0 0 +EDGE2 2590 2549 -0.954609 -0.00270886 0.0459862 1 0 1 1 0 0 +EDGE2 2590 2569 -0.986232 -0.00907706 -0.00329232 1 0 1 1 0 0 +EDGE2 2590 2589 -0.950695 -0.065195 0.010974 1 0 1 1 0 0 +EDGE2 2590 2529 -0.983177 -0.0387638 -0.0182886 1 0 1 1 0 0 +EDGE2 2590 1549 -1.02308 -0.00573899 -0.0288164 1 0 1 1 0 0 +EDGE2 2590 2409 -1.10943 -0.00942042 0.00570991 1 0 1 1 0 0 +EDGE2 2591 2411 0.00893156 0.0818829 -0.00374359 1 0 1 1 0 0 +EDGE2 2591 2571 -0.0699491 -0.0235187 -0.051115 1 0 1 1 0 0 +EDGE2 2591 2430 -0.972583 -0.0530672 -1.57782 1 0 1 1 0 0 +EDGE2 2591 2550 -0.994718 0.0330976 -1.56784 1 0 1 1 0 0 +EDGE2 2591 2570 -1.00797 -0.00589353 -1.55379 1 0 1 1 0 0 +EDGE2 2591 2590 -0.966311 -0.0182308 -1.55887 1 0 1 1 0 0 +EDGE2 2591 2530 -0.900921 -0.0635022 -1.54869 1 0 1 1 0 0 +EDGE2 2591 1550 -0.939487 0.0288122 -1.57475 1 0 1 1 0 0 +EDGE2 2591 1830 -0.963474 0.011872 1.5498 1 0 1 1 0 0 +EDGE2 2591 2410 -0.886222 -0.0348804 -1.58802 1 0 1 1 0 0 +EDGE2 2591 2531 0.0402163 0.0878394 0.0144205 1 0 1 1 0 0 +EDGE2 2591 2551 -0.0358339 0.00819039 -0.0238276 1 0 1 1 0 0 +EDGE2 2591 2431 0.0173852 0.0234111 -0.0235444 1 0 1 1 0 0 +EDGE2 2591 2432 1.05032 0.00490108 0.00779503 1 0 1 1 0 0 +EDGE2 2591 2552 0.908251 -0.00642067 0.00579632 1 0 1 1 0 0 +EDGE2 2591 2572 1.01598 0.0246466 -0.032961 1 0 1 1 0 0 +EDGE2 2591 2532 1.02253 0.0503309 0.0521596 1 0 1 1 0 0 +EDGE2 2591 2412 0.998537 -0.134056 -0.00863142 1 0 1 1 0 0 +EDGE2 2592 2411 -1.05871 0.0639024 -0.0303337 1 0 1 1 0 0 +EDGE2 2592 2571 -0.973247 0.0840482 -0.0446157 1 0 1 1 0 0 +EDGE2 2592 2591 -1.00339 0.00892344 -0.00454005 1 0 1 1 0 0 +EDGE2 2592 2531 -0.997582 0.00206554 0.0441362 1 0 1 1 0 0 +EDGE2 2592 2551 -1.03748 0.0314438 0.00865066 1 0 1 1 0 0 +EDGE2 2592 2431 -1.03253 0.0360194 0.01103 1 0 1 1 0 0 +EDGE2 2592 2533 0.863224 -0.00994821 0.0332311 1 0 1 1 0 0 +EDGE2 2592 2432 -0.00282132 0.0275096 0.0235865 1 0 1 1 0 0 +EDGE2 2592 2552 0.011516 -0.0523002 0.0209282 1 0 1 1 0 0 +EDGE2 2592 2572 0.0452469 -0.0787996 -0.00203382 1 0 1 1 0 0 +EDGE2 2592 2532 -0.0715573 -0.0328677 0.00881502 1 0 1 1 0 0 +EDGE2 2592 2573 1.01258 0.0442549 -0.0128676 1 0 1 1 0 0 +EDGE2 2592 2412 -0.0707489 0.0670843 0.00644422 1 0 1 1 0 0 +EDGE2 2592 2553 0.994214 0.0397251 0.0498758 1 0 1 1 0 0 +EDGE2 2592 2413 0.989741 -0.049127 -0.00703392 1 0 1 1 0 0 +EDGE2 2592 2433 0.927972 -0.00828896 0.0107176 1 0 1 1 0 0 +EDGE2 2593 2533 -0.00428848 -0.0561805 0.00497638 1 0 1 1 0 0 +EDGE2 2593 2432 -0.984005 0.00458689 -0.00223066 1 0 1 1 0 0 +EDGE2 2593 2552 -0.993503 0.0256307 -0.00829069 1 0 1 1 0 0 +EDGE2 2593 2572 -1.09619 -0.0761637 0.0137229 1 0 1 1 0 0 +EDGE2 2593 2592 -0.907446 -0.16466 0.0167099 1 0 1 1 0 0 +EDGE2 2593 2532 -0.976099 -0.000144133 -0.0219858 1 0 1 1 0 0 +EDGE2 2593 2573 0.0250722 0.0365791 0.000415354 1 0 1 1 0 0 +EDGE2 2593 2412 -0.959414 -0.0331255 -0.000884351 1 0 1 1 0 0 +EDGE2 2593 2553 0.0674293 -0.034894 0.022737 1 0 1 1 0 0 +EDGE2 2593 2554 1.08209 -0.0459451 -0.0147502 1 0 1 1 0 0 +EDGE2 2593 2413 -0.0340355 0.0230051 -0.000104555 1 0 1 1 0 0 +EDGE2 2593 2433 -0.0419021 -0.059022 -0.00971205 1 0 1 1 0 0 +EDGE2 2593 2574 0.972966 0.0241092 0.00319399 1 0 1 1 0 0 +EDGE2 2593 2414 1.06334 -0.0588683 0.0214278 1 0 1 1 0 0 +EDGE2 2593 2434 1.06619 0.0727792 0.0114947 1 0 1 1 0 0 +EDGE2 2593 2534 0.956066 0.0512023 -0.00206983 1 0 1 1 0 0 +EDGE2 2594 2533 -0.985298 0.0750643 -0.00825289 1 0 1 1 0 0 +EDGE2 2594 2573 -0.973167 -0.0121582 -0.0356224 1 0 1 1 0 0 +EDGE2 2594 2593 -0.994094 -0.0640839 0.0149561 1 0 1 1 0 0 +EDGE2 2594 2553 -0.977021 -0.0791456 -0.0307377 1 0 1 1 0 0 +EDGE2 2594 2554 0.00738678 -0.0516981 -0.00983653 1 0 1 1 0 0 +EDGE2 2594 2413 -1.01118 -0.00485484 0.0507574 1 0 1 1 0 0 +EDGE2 2594 2433 -0.904693 -0.0097961 0.0022681 1 0 1 1 0 0 +EDGE2 2594 2574 -0.00452022 -0.0420467 0.00930154 1 0 1 1 0 0 +EDGE2 2594 2414 0.0305626 0.00669963 -0.00325961 1 0 1 1 0 0 +EDGE2 2594 2434 0.0746606 0.0714135 0.00232182 1 0 1 1 0 0 +EDGE2 2594 2534 0.00659166 0.0514749 -0.009584 1 0 1 1 0 0 +EDGE2 2594 1235 1.01687 -0.0678515 -3.13396 1 0 1 1 0 0 +EDGE2 2594 2455 1.01471 -0.0453167 -3.12315 1 0 1 1 0 0 +EDGE2 2594 2535 1.0455 -0.0142519 -0.0157628 1 0 1 1 0 0 +EDGE2 2594 2555 0.969271 -0.0366111 -0.0272035 1 0 1 1 0 0 +EDGE2 2594 2575 0.955114 0.0502292 0.0179996 1 0 1 1 0 0 +EDGE2 2594 2495 1.06353 -0.00751143 -3.15876 1 0 1 1 0 0 +EDGE2 2594 2295 1.01743 0.0277733 -3.13952 1 0 1 1 0 0 +EDGE2 2594 2415 0.942801 0.0099583 -0.000447901 1 0 1 1 0 0 +EDGE2 2594 2435 1.0233 -0.060705 0.0272348 1 0 1 1 0 0 +EDGE2 2594 1255 0.981966 0.10094 -3.17201 1 0 1 1 0 0 +EDGE2 2595 2416 -0.00279237 1.01903 1.5816 1 0 1 1 0 0 +EDGE2 2595 2456 0.0237631 -0.957562 -1.56753 1 0 1 1 0 0 +EDGE2 2595 1236 -0.00156727 -0.979547 -1.55345 1 0 1 1 0 0 +EDGE2 2595 2554 -0.982862 0.0596737 -0.0252047 1 0 1 1 0 0 +EDGE2 2595 2594 -1.0124 -0.0271227 -0.0409285 1 0 1 1 0 0 +EDGE2 2595 2574 -0.932781 0.0986418 0.00333756 1 0 1 1 0 0 +EDGE2 2595 2414 -0.977582 0.037005 0.00379578 1 0 1 1 0 0 +EDGE2 2595 2434 -1.05137 0.0543579 -0.00301324 1 0 1 1 0 0 +EDGE2 2595 2534 -1.06022 -0.0840562 0.0364039 1 0 1 1 0 0 +EDGE2 2595 1235 0.0188073 0.00262249 -3.14454 1 0 1 1 0 0 +EDGE2 2595 2455 0.00703353 -0.0809366 -3.1586 1 0 1 1 0 0 +EDGE2 2595 2535 -0.0237188 -0.00919924 0.0200544 1 0 1 1 0 0 +EDGE2 2595 2555 0.00339028 0.0285782 -0.00660569 1 0 1 1 0 0 +EDGE2 2595 2575 0.0147845 0.0126341 0.00784344 1 0 1 1 0 0 +EDGE2 2595 2495 -0.0235686 -0.0161567 -3.15052 1 0 1 1 0 0 +EDGE2 2595 2295 -0.0323145 0.00257754 -3.13846 1 0 1 1 0 0 +EDGE2 2595 2415 0.100002 -0.0304659 0.00287064 1 0 1 1 0 0 +EDGE2 2595 2435 -0.00843806 0.0134332 -0.02287 1 0 1 1 0 0 +EDGE2 2595 1255 0.0799708 0.0354358 -3.15708 1 0 1 1 0 0 +EDGE2 2595 1254 0.985649 -0.0264627 -3.15789 1 0 1 1 0 0 +EDGE2 2595 2454 0.891564 -0.034378 -3.12534 1 0 1 1 0 0 +EDGE2 2595 2494 0.99866 0.0190685 -3.16917 1 0 1 1 0 0 +EDGE2 2595 2294 0.921457 -0.015829 -3.16522 1 0 1 1 0 0 +EDGE2 2595 1234 0.959476 -0.0504552 -3.13051 1 0 1 1 0 0 +EDGE2 2595 2556 -0.0750366 1.02598 1.54289 1 0 1 1 0 0 +EDGE2 2595 2576 0.0410542 0.935964 1.57872 1 0 1 1 0 0 +EDGE2 2595 2496 -0.0161547 0.952351 1.56971 1 0 1 1 0 0 +EDGE2 2595 2536 -0.0590788 0.945108 1.5763 1 0 1 1 0 0 +EDGE2 2595 2436 0.0334962 1.10902 1.56805 1 0 1 1 0 0 +EDGE2 2595 1256 -0.0166289 0.990494 1.56793 1 0 1 1 0 0 +EDGE2 2595 2296 0.0645589 0.926686 1.55667 1 0 1 1 0 0 +EDGE2 2596 2416 0.00797672 0.0800465 -0.00575188 1 0 1 1 0 0 +EDGE2 2596 2595 -1.04625 0.0542257 -1.5501 1 0 1 1 0 0 +EDGE2 2596 1235 -1.01272 -0.0536359 1.57311 1 0 1 1 0 0 +EDGE2 2596 2455 -1.01491 0.0180525 1.55245 1 0 1 1 0 0 +EDGE2 2596 2535 -1.04267 0.0337789 -1.54668 1 0 1 1 0 0 +EDGE2 2596 2555 -1.00667 0.0434324 -1.56848 1 0 1 1 0 0 +EDGE2 2596 2575 -1.11946 -0.00767662 -1.59165 1 0 1 1 0 0 +EDGE2 2596 2495 -0.920676 0.041754 1.57199 1 0 1 1 0 0 +EDGE2 2596 2295 -1.06631 -0.0476706 1.52866 1 0 1 1 0 0 +EDGE2 2596 2415 -1.04096 -0.0217405 -1.55189 1 0 1 1 0 0 +EDGE2 2596 2435 -1.01005 -0.0205206 -1.58269 1 0 1 1 0 0 +EDGE2 2596 1255 -1.00374 0.0641612 1.53388 1 0 1 1 0 0 +EDGE2 2596 2556 0.0843985 -0.0307401 0.012683 1 0 1 1 0 0 +EDGE2 2596 2576 0.0432591 -0.0394416 -0.0218955 1 0 1 1 0 0 +EDGE2 2596 2496 -0.126134 0.063203 -0.0055608 1 0 1 1 0 0 +EDGE2 2596 2536 -0.0832704 -0.137999 2.56298e-05 1 0 1 1 0 0 +EDGE2 2596 2436 0.0497937 -0.0668613 0.0148285 1 0 1 1 0 0 +EDGE2 2596 1256 0.0975503 -0.0289472 0.0151784 1 0 1 1 0 0 +EDGE2 2596 2296 0.0343254 0.0132061 -0.0108544 1 0 1 1 0 0 +EDGE2 2596 2497 1.02166 -0.0556865 -0.0346692 1 0 1 1 0 0 +EDGE2 2596 2557 1.03435 0.0681806 0.020775 1 0 1 1 0 0 +EDGE2 2596 2577 1.01666 0.0157925 0.000509035 1 0 1 1 0 0 +EDGE2 2596 2537 1.00871 0.0274997 -0.0204863 1 0 1 1 0 0 +EDGE2 2596 2297 0.989302 0.0803955 0.0146024 1 0 1 1 0 0 +EDGE2 2596 2417 0.996414 0.0393852 0.018416 1 0 1 1 0 0 +EDGE2 2596 2437 1.0561 -0.0110855 -0.00980867 1 0 1 1 0 0 +EDGE2 2596 1257 0.939884 -0.0219047 0.0344229 1 0 1 1 0 0 +EDGE2 2597 2416 -1.01681 0.0139838 0.0279598 1 0 1 1 0 0 +EDGE2 2597 2556 -0.985491 -0.0169087 0.0200582 1 0 1 1 0 0 +EDGE2 2597 2596 -1.02359 0.0221521 0.00464781 1 0 1 1 0 0 +EDGE2 2597 2576 -0.994917 0.0569067 0.000437554 1 0 1 1 0 0 +EDGE2 2597 2496 -1.05458 -0.0316992 -0.0127434 1 0 1 1 0 0 +EDGE2 2597 2536 -0.865598 -0.0500125 -0.0117157 1 0 1 1 0 0 +EDGE2 2597 2436 -1.04444 -0.000934066 0.0277194 1 0 1 1 0 0 +EDGE2 2597 2498 0.871805 -0.0450022 -0.0261328 1 0 1 1 0 0 +EDGE2 2597 1256 -0.930769 -0.0234437 -0.00784066 1 0 1 1 0 0 +EDGE2 2597 2296 -0.945417 -0.00385595 0.0134334 1 0 1 1 0 0 +EDGE2 2597 2497 0.0435357 -0.0302358 -0.0164516 1 0 1 1 0 0 +EDGE2 2597 2557 -0.0420877 0.0263117 -0.00346769 1 0 1 1 0 0 +EDGE2 2597 2577 -0.0409796 0.0207262 0.000839384 1 0 1 1 0 0 +EDGE2 2597 2537 -0.0553665 0.0275838 -0.00146641 1 0 1 1 0 0 +EDGE2 2597 2297 0.0224183 -0.0041205 -0.0108822 1 0 1 1 0 0 +EDGE2 2597 2417 -0.00192861 0.0422615 0.0371675 1 0 1 1 0 0 +EDGE2 2597 2437 -0.00958662 0.0170941 -0.0445696 1 0 1 1 0 0 +EDGE2 2597 1257 0.00178601 0.0592559 -0.00550958 1 0 1 1 0 0 +EDGE2 2597 2558 1.04698 0.0084739 0.0148857 1 0 1 1 0 0 +EDGE2 2597 2578 0.961953 -0.0108915 0.0177494 1 0 1 1 0 0 +EDGE2 2597 2538 0.98703 -0.101422 -0.0302707 1 0 1 1 0 0 +EDGE2 2597 2298 1.08191 -0.0324116 -0.00235696 1 0 1 1 0 0 +EDGE2 2597 2418 0.99335 -0.0323487 0.00872981 1 0 1 1 0 0 +EDGE2 2597 2438 0.97504 0.00922077 -0.011256 1 0 1 1 0 0 +EDGE2 2597 1258 1.06762 -0.0182755 0.0118631 1 0 1 1 0 0 +EDGE2 2598 2498 -0.0565549 0.0566249 0.00609088 1 0 1 1 0 0 +EDGE2 2598 2497 -1.00637 -0.0617156 0.00812346 1 0 1 1 0 0 +EDGE2 2598 2557 -1.08981 0.0835239 -0.00720105 1 0 1 1 0 0 +EDGE2 2598 2577 -1.00236 0.00250348 0.0238245 1 0 1 1 0 0 +EDGE2 2598 2597 -0.923692 -0.0354415 0.0193996 1 0 1 1 0 0 +EDGE2 2598 2537 -1.04474 0.00694051 0.0090599 1 0 1 1 0 0 +EDGE2 2598 2297 -1.05306 -0.0157254 -0.0194654 1 0 1 1 0 0 +EDGE2 2598 2417 -1.03823 0.0856523 0.0101123 1 0 1 1 0 0 +EDGE2 2598 2437 -1.02493 -0.0606189 0.0213852 1 0 1 1 0 0 +EDGE2 2598 1257 -0.990825 0.00546702 -0.00951895 1 0 1 1 0 0 +EDGE2 2598 2558 -0.0416052 -0.0153637 0.0306843 1 0 1 1 0 0 +EDGE2 2598 2578 -0.00409806 -0.000658939 0.0245941 1 0 1 1 0 0 +EDGE2 2598 2538 0.067618 0.0361138 -0.0361675 1 0 1 1 0 0 +EDGE2 2598 2298 -0.062665 0.0358831 -0.00408354 1 0 1 1 0 0 +EDGE2 2598 2418 0.0136541 0.0398945 0.00265545 1 0 1 1 0 0 +EDGE2 2598 2438 0.00403876 0.048811 -0.0106804 1 0 1 1 0 0 +EDGE2 2598 1258 0.0561501 -0.0859444 0.000935447 1 0 1 1 0 0 +EDGE2 2598 2499 0.92777 -0.0790916 -0.0156282 1 0 1 1 0 0 +EDGE2 2598 2559 1.01887 -0.0729952 -0.0243199 1 0 1 1 0 0 +EDGE2 2598 2579 1.00743 -0.0186585 0.0336255 1 0 1 1 0 0 +EDGE2 2598 2539 0.957295 0.0435604 -0.0128268 1 0 1 1 0 0 +EDGE2 2598 2299 0.996998 -0.0376136 -0.01391 1 0 1 1 0 0 +EDGE2 2598 2419 0.918715 0.00789078 0.0164301 1 0 1 1 0 0 +EDGE2 2598 2439 1.02528 0.029453 -0.0526657 1 0 1 1 0 0 +EDGE2 2598 1259 0.999358 -0.0271865 -0.0225054 1 0 1 1 0 0 +EDGE2 2599 2498 -1.00055 -3.60761e-06 -0.00351788 1 0 1 1 0 0 +EDGE2 2599 2558 -1.01653 -0.0579061 0.000921046 1 0 1 1 0 0 +EDGE2 2599 2578 -1.00247 0.0126231 -0.00110447 1 0 1 1 0 0 +EDGE2 2599 2598 -0.971962 -0.0146544 -0.00878493 1 0 1 1 0 0 +EDGE2 2599 2538 -1.03474 -0.0367271 0.0100738 1 0 1 1 0 0 +EDGE2 2599 2298 -0.99918 0.0531245 0.00593221 1 0 1 1 0 0 +EDGE2 2599 2418 -1.03174 0.00571604 -0.0146751 1 0 1 1 0 0 +EDGE2 2599 2438 -0.906825 -0.0388645 -0.038621 1 0 1 1 0 0 +EDGE2 2599 1258 -0.930221 0.0152085 -0.00387 1 0 1 1 0 0 +EDGE2 2599 2499 0.0877108 0.0114279 0.0123772 1 0 1 1 0 0 +EDGE2 2599 2559 0.0528102 0.0915527 0.0139396 1 0 1 1 0 0 +EDGE2 2599 2579 -0.0649432 -0.0464635 0.00368416 1 0 1 1 0 0 +EDGE2 2599 2539 0.0653159 0.0721474 -0.0150849 1 0 1 1 0 0 +EDGE2 2599 2299 -0.0299017 -0.064835 0.00305864 1 0 1 1 0 0 +EDGE2 2599 2419 0.0518465 0.0156092 0.00419024 1 0 1 1 0 0 +EDGE2 2599 2439 -0.0890284 0.0904695 0.00638109 1 0 1 1 0 0 +EDGE2 2599 1259 -0.0650459 0.0162928 0.00546289 1 0 1 1 0 0 +EDGE2 2599 2420 0.993793 0.0225432 0.021706 1 0 1 1 0 0 +EDGE2 2599 2560 1.01742 -0.0197515 -0.0310831 1 0 1 1 0 0 +EDGE2 2599 2580 1.00013 0.0119254 0.0107537 1 0 1 1 0 0 +EDGE2 2599 2500 0.93008 0.0817546 0.0198219 1 0 1 1 0 0 +EDGE2 2599 2520 1.02205 0.0235474 -3.11374 1 0 1 1 0 0 +EDGE2 2599 2540 0.962636 -0.10576 0.00801713 1 0 1 1 0 0 +EDGE2 2599 2440 0.990524 0.00591119 0.00627306 1 0 1 1 0 0 +EDGE2 2599 2300 0.909562 0.0332284 -0.0101197 1 0 1 1 0 0 +EDGE2 2599 1260 1.13595 0.00418515 0.00104584 1 0 1 1 0 0 +EDGE2 2600 2441 -0.0125989 -1.07777 -1.58783 1 0 1 1 0 0 +EDGE2 2600 2521 0.0277174 0.997555 1.57416 1 0 1 1 0 0 +EDGE2 2600 2561 0.0161086 0.995299 1.6099 1 0 1 1 0 0 +EDGE2 2600 2581 -0.0109169 1.0679 1.5958 1 0 1 1 0 0 +EDGE2 2600 2541 0.00904422 1.003 1.57792 1 0 1 1 0 0 +EDGE2 2600 2301 0.0381017 0.941729 1.6125 1 0 1 1 0 0 +EDGE2 2600 2421 -0.0139373 1.00346 1.58384 1 0 1 1 0 0 +EDGE2 2600 1261 0.0409637 1.08212 1.57544 1 0 1 1 0 0 +EDGE2 2600 2499 -1.03954 0.0832311 0.00263434 1 0 1 1 0 0 +EDGE2 2600 2559 -0.994625 -0.0558421 -0.0116507 1 0 1 1 0 0 +EDGE2 2600 2579 -0.995554 0.00321834 -0.0132756 1 0 1 1 0 0 +EDGE2 2600 2599 -0.933432 -0.0549095 -0.0429203 1 0 1 1 0 0 +EDGE2 2600 2539 -0.997499 -0.0307681 -0.0251575 1 0 1 1 0 0 +EDGE2 2600 2299 -1.00827 0.00707725 -0.0161864 1 0 1 1 0 0 +EDGE2 2600 2419 -0.975361 -0.0727455 -0.0239576 1 0 1 1 0 0 +EDGE2 2600 2439 -0.91282 -0.020467 -0.0466117 1 0 1 1 0 0 +EDGE2 2600 1259 -0.984822 0.0310479 -0.00847476 1 0 1 1 0 0 +EDGE2 2600 2420 0.0190235 0.0851673 -0.0287364 1 0 1 1 0 0 +EDGE2 2600 2560 0.0278305 0.0788086 -0.024363 1 0 1 1 0 0 +EDGE2 2600 2580 -0.0528246 0.0724391 0.0424171 1 0 1 1 0 0 +EDGE2 2600 2500 -0.0216012 0.0284871 -0.0209014 1 0 1 1 0 0 +EDGE2 2600 2520 -0.058937 -0.0234909 -3.1455 1 0 1 1 0 0 +EDGE2 2600 2540 -0.0711638 -0.0270424 0.00189296 1 0 1 1 0 0 +EDGE2 2600 2440 0.0360635 0.027926 -0.020965 1 0 1 1 0 0 +EDGE2 2600 2300 -0.00807465 -0.029893 -0.0103562 1 0 1 1 0 0 +EDGE2 2600 1260 -0.0427322 -0.0609557 0.0055766 1 0 1 1 0 0 +EDGE2 2600 2501 0.0152187 -0.998857 -1.58093 1 0 1 1 0 0 +EDGE2 2600 2519 0.957425 -0.0136789 -3.14538 1 0 1 1 0 0 +EDGE2 2601 2441 0.015395 -0.102316 0.00146164 1 0 1 1 0 0 +EDGE2 2601 2420 -1.04064 -0.0104697 1.55325 1 0 1 1 0 0 +EDGE2 2601 2560 -1.00742 0.0235109 1.55415 1 0 1 1 0 0 +EDGE2 2601 2600 -1.03625 0.0392677 1.54572 1 0 1 1 0 0 +EDGE2 2601 2580 -1.02548 0.0646476 1.57836 1 0 1 1 0 0 +EDGE2 2601 2500 -1.02872 -0.0247328 1.5588 1 0 1 1 0 0 +EDGE2 2601 2520 -0.952468 0.0954306 -1.55771 1 0 1 1 0 0 +EDGE2 2601 2540 -0.87633 0.00324021 1.59501 1 0 1 1 0 0 +EDGE2 2601 2440 -1.01906 0.0250661 1.56059 1 0 1 1 0 0 +EDGE2 2601 2300 -1.13552 0.0403083 1.55718 1 0 1 1 0 0 +EDGE2 2601 1260 -1.02132 0.0136885 1.55166 1 0 1 1 0 0 +EDGE2 2601 2501 -0.0266855 -0.0166229 -0.0256275 1 0 1 1 0 0 +EDGE2 2601 2442 1.03863 -0.033703 0.0180333 1 0 1 1 0 0 +EDGE2 2601 2502 0.987963 0.0183543 -0.00810308 1 0 1 1 0 0 +EDGE2 2602 2441 -1.00323 0.0558768 -0.0203932 1 0 1 1 0 0 +EDGE2 2602 2601 -0.930315 0.0420798 0.00264122 1 0 1 1 0 0 +EDGE2 2602 2501 -1.00976 0.0346476 -0.00662365 1 0 1 1 0 0 +EDGE2 2602 2443 1.0464 -0.0328245 0.0097628 1 0 1 1 0 0 +EDGE2 2602 2442 -0.0374381 0.0595827 -0.0151342 1 0 1 1 0 0 +EDGE2 2602 2502 0.0839227 0.0442506 -0.0132263 1 0 1 1 0 0 +EDGE2 2602 2503 0.997538 -0.0174924 -0.00549483 1 0 1 1 0 0 +EDGE2 2603 2443 -0.0686885 0.0115505 -0.00286479 1 0 1 1 0 0 +EDGE2 2603 2442 -0.989626 0.0212311 -0.00264154 1 0 1 1 0 0 +EDGE2 2603 2602 -0.95858 0.0769357 0.00350891 1 0 1 1 0 0 +EDGE2 2603 2502 -1.01134 0.0442469 0.0141505 1 0 1 1 0 0 +EDGE2 2603 2503 -0.0216942 0.011338 -0.00901802 1 0 1 1 0 0 +EDGE2 2603 2444 1.01059 -0.0202332 0.00624208 1 0 1 1 0 0 +EDGE2 2603 2504 1.07209 0.0567767 0.0312855 1 0 1 1 0 0 +EDGE2 2604 2443 -1.04918 -0.0154608 0.0187948 1 0 1 1 0 0 +EDGE2 2604 2603 -0.946277 0.0128252 -0.0294269 1 0 1 1 0 0 +EDGE2 2604 2503 -1.06851 -0.0410828 -0.00654015 1 0 1 1 0 0 +EDGE2 2604 2444 -0.0108119 -0.0203385 -0.032626 1 0 1 1 0 0 +EDGE2 2604 2504 -0.0941684 -0.0612994 0.0288835 1 0 1 1 0 0 +EDGE2 2604 1225 0.999738 -0.0357109 -3.16924 1 0 1 1 0 0 +EDGE2 2604 2485 1.07478 -0.0717778 -3.15665 1 0 1 1 0 0 +EDGE2 2604 2505 1.03237 0.0395107 0.010409 1 0 1 1 0 0 +EDGE2 2604 2445 1.05713 -0.00120234 0.00562791 1 0 1 1 0 0 +EDGE2 2605 2446 -0.0130781 -1.03412 -1.55798 1 0 1 1 0 0 +EDGE2 2605 2486 0.0181444 -1.06767 -1.58283 1 0 1 1 0 0 +EDGE2 2605 1226 0.00326464 -1.01204 -1.5706 1 0 1 1 0 0 +EDGE2 2605 2444 -0.996634 -0.121046 -0.00244635 1 0 1 1 0 0 +EDGE2 2605 2604 -0.987905 0.0360316 -0.0308895 1 0 1 1 0 0 +EDGE2 2605 2504 -1.01376 0.11189 -0.00928453 1 0 1 1 0 0 +EDGE2 2605 1225 0.0286265 -0.0228468 -3.10492 1 0 1 1 0 0 +EDGE2 2605 2485 0.0384022 -0.0370128 -3.1356 1 0 1 1 0 0 +EDGE2 2605 2505 -0.0358542 0.0381692 0.00238037 1 0 1 1 0 0 +EDGE2 2605 2445 0.0142381 -0.0358898 0.00374613 1 0 1 1 0 0 +EDGE2 2605 1224 1.07975 0.0043281 -3.14476 1 0 1 1 0 0 +EDGE2 2605 2484 1.01043 0.0360285 -3.15631 1 0 1 1 0 0 +EDGE2 2605 2506 0.0362673 1.07411 1.54373 1 0 1 1 0 0 +EDGE2 2606 1225 -1.01215 -0.0538854 1.58424 1 0 1 1 0 0 +EDGE2 2606 2485 -0.968942 0.0941166 1.57179 1 0 1 1 0 0 +EDGE2 2606 2505 -1.01421 0.0912837 -1.55649 1 0 1 1 0 0 +EDGE2 2606 2605 -1.04033 -0.0558567 -1.58823 1 0 1 1 0 0 +EDGE2 2606 2445 -1.02226 -0.0144153 -1.58395 1 0 1 1 0 0 +EDGE2 2606 2506 0.074767 -0.0472209 -0.0182421 1 0 1 1 0 0 +EDGE2 2606 2507 1.02607 -0.0255053 0.014893 1 0 1 1 0 0 +EDGE2 2607 2506 -1.02627 0.0259209 0.0276052 1 0 1 1 0 0 +EDGE2 2607 2606 -1.00492 0.0574312 -0.0262059 1 0 1 1 0 0 +EDGE2 2607 2507 0.0434013 0.0355055 -0.0474223 1 0 1 1 0 0 +EDGE2 2607 2508 1.01191 -0.0232408 -0.0164531 1 0 1 1 0 0 +EDGE2 2608 2607 -0.963625 0.0229001 0.0322533 1 0 1 1 0 0 +EDGE2 2608 2507 -1.03398 0.00010022 -0.0298986 1 0 1 1 0 0 +EDGE2 2608 2508 0.0611784 0.0474047 0.0073258 1 0 1 1 0 0 +EDGE2 2608 2509 0.95797 0.0393459 -0.0119357 1 0 1 1 0 0 +EDGE2 2609 2508 -0.925739 -0.0487793 0.00692279 1 0 1 1 0 0 +EDGE2 2609 2608 -0.934665 -0.0442076 0.017111 1 0 1 1 0 0 +EDGE2 2609 2509 -0.0546066 0.0103935 -0.0162956 1 0 1 1 0 0 +EDGE2 2609 2510 0.91877 -0.015646 -0.0304995 1 0 1 1 0 0 +EDGE2 2610 2609 -0.981492 0.0516744 -0.0152169 1 0 1 1 0 0 +EDGE2 2610 2509 -0.876044 0.0642551 0.0124894 1 0 1 1 0 0 +EDGE2 2610 2511 -0.00251734 0.981729 1.56125 1 0 1 1 0 0 +EDGE2 2610 2510 -0.0521515 -0.020013 0.00206061 1 0 1 1 0 0 +EDGE2 2611 2510 -0.961243 0.0146107 1.56622 1 0 1 1 0 0 +EDGE2 2611 2610 -1.03314 0.0139709 1.57517 1 0 1 1 0 0 +EDGE2 2612 2611 -1.01624 0.00925606 0.008761 1 0 1 1 0 0 +EDGE2 2613 2612 -1.04452 0.0239113 0.0199168 1 0 1 1 0 0 +EDGE2 2614 2613 -1.02509 0.0413119 -0.0101375 1 0 1 1 0 0 +EDGE2 2615 2614 -1.0003 -0.110041 -0.0502442 1 0 1 1 0 0 +EDGE2 2616 2615 -1.01774 0.00634131 -1.55444 1 0 1 1 0 0 +EDGE2 2617 2616 -1.01877 -0.0486028 0.0169337 1 0 1 1 0 0 +EDGE2 2618 2617 -1.0178 -0.0719207 0.0130989 1 0 1 1 0 0 +EDGE2 2619 2618 -0.968557 0.0562836 0.0104629 1 0 1 1 0 0 +EDGE2 2620 2619 -0.92132 0.0424003 -0.0182671 1 0 1 1 0 0 +EDGE2 2621 2620 -0.992215 0.0310544 -1.55431 1 0 1 1 0 0 +EDGE2 2622 2621 -1.03807 0.000394342 0.00213406 1 0 1 1 0 0 +EDGE2 2623 2622 -0.966565 -0.0105088 -0.0283699 1 0 1 1 0 0 +EDGE2 2624 2623 -0.901256 -0.00466457 -0.0130446 1 0 1 1 0 0 +EDGE2 2625 2624 -0.986039 -0.133776 -0.0334206 1 0 1 1 0 0 +EDGE2 2626 2625 -0.918482 0.0467157 -1.60094 1 0 1 1 0 0 +EDGE2 2627 2626 -0.975588 -0.0283175 0.012449 1 0 1 1 0 0 +EDGE2 2628 2627 -0.976033 -0.0487543 0.00366299 1 0 1 1 0 0 +EDGE2 2629 2510 1.05915 -0.0616106 -3.15166 1 0 1 1 0 0 +EDGE2 2629 2610 1.03316 0.0062006 -3.13939 1 0 1 1 0 0 +EDGE2 2629 2628 -0.938003 -0.00444316 -0.0218632 1 0 1 1 0 0 +EDGE2 2630 2609 0.981295 0.0647251 -3.13334 1 0 1 1 0 0 +EDGE2 2630 2509 1.00842 0.126294 -3.13665 1 0 1 1 0 0 +EDGE2 2630 2511 0.00572135 -0.974786 -1.54142 1 0 1 1 0 0 +EDGE2 2630 2510 0.0244432 -0.0226504 -3.13856 1 0 1 1 0 0 +EDGE2 2630 2610 -0.0599169 -0.0103201 -3.12395 1 0 1 1 0 0 +EDGE2 2630 2629 -1.00968 0.00911591 -0.01373 1 0 1 1 0 0 +EDGE2 2630 2611 -0.0246418 1.00442 1.55064 1 0 1 1 0 0 +EDGE2 2631 2512 1.00149 0.00905945 0.00516155 1 0 1 1 0 0 +EDGE2 2631 2511 -0.0178875 -0.00376698 -0.0198079 1 0 1 1 0 0 +EDGE2 2631 2510 -1.05067 -0.0928289 -1.59434 1 0 1 1 0 0 +EDGE2 2631 2630 -0.997073 -0.0103506 1.54498 1 0 1 1 0 0 +EDGE2 2631 2610 -0.976462 0.0817134 -1.52193 1 0 1 1 0 0 +EDGE2 2632 2631 -0.889729 -0.00556378 -0.0235908 1 0 1 1 0 0 +EDGE2 2632 2513 0.997355 -0.00292191 -0.00477625 1 0 1 1 0 0 +EDGE2 2632 2512 0.0401761 -0.020301 0.0246968 1 0 1 1 0 0 +EDGE2 2632 2511 -0.880054 0.0276417 0.0142827 1 0 1 1 0 0 +EDGE2 2633 2513 0.101562 -0.0244484 -0.0180106 1 0 1 1 0 0 +EDGE2 2633 2514 1.02365 0.0383279 -0.0320371 1 0 1 1 0 0 +EDGE2 2633 2512 -0.975558 -0.0103168 0.0138421 1 0 1 1 0 0 +EDGE2 2633 2632 -0.959143 0.123337 -0.00668109 1 0 1 1 0 0 +EDGE2 2634 1295 0.999038 -0.0338814 -3.14275 1 0 1 1 0 0 +EDGE2 2634 2515 0.961459 -0.0434193 -0.011908 1 0 1 1 0 0 +EDGE2 2634 1275 0.985922 0.0431732 -3.12739 1 0 1 1 0 0 +EDGE2 2634 2513 -1.05041 -0.05235 -0.00681694 1 0 1 1 0 0 +EDGE2 2634 2514 0.0299514 0.0125874 -0.0196749 1 0 1 1 0 0 +EDGE2 2634 2633 -0.945921 0.0200587 0.0270212 1 0 1 1 0 0 +EDGE2 2635 2516 0.0203985 0.907877 1.55581 1 0 1 1 0 0 +EDGE2 2635 1274 0.957723 0.0896926 -3.13827 1 0 1 1 0 0 +EDGE2 2635 1294 0.97424 0.0387257 -3.12767 1 0 1 1 0 0 +EDGE2 2635 1295 0.119355 0.127853 -3.1342 1 0 1 1 0 0 +EDGE2 2635 2515 0.0429114 -0.0132745 0.00327927 1 0 1 1 0 0 +EDGE2 2635 1275 0.0788386 -0.0948164 -3.13355 1 0 1 1 0 0 +EDGE2 2635 2514 -0.946997 -0.00877969 0.0148052 1 0 1 1 0 0 +EDGE2 2635 2634 -1.07767 0.0225922 -0.0269582 1 0 1 1 0 0 +EDGE2 2635 1296 0.022464 -0.922329 -1.53586 1 0 1 1 0 0 +EDGE2 2635 1276 0.0305133 -0.974941 -1.55759 1 0 1 1 0 0 +EDGE2 2636 2517 1.11929 -0.0216355 -0.0484228 1 0 1 1 0 0 +EDGE2 2636 2516 0.0160088 -0.00114859 0.0139048 1 0 1 1 0 0 +EDGE2 2636 1295 -0.968431 0.104913 1.53311 1 0 1 1 0 0 +EDGE2 2636 2515 -1.0088 -0.0288229 -1.58009 1 0 1 1 0 0 +EDGE2 2636 2635 -0.957313 -0.0336717 -1.543 1 0 1 1 0 0 +EDGE2 2636 1275 -0.983528 -0.0533716 1.57137 1 0 1 1 0 0 +EDGE2 2637 2518 1.00857 0.0342167 -0.00597339 1 0 1 1 0 0 +EDGE2 2637 2517 -0.0665581 -0.0194558 0.00967833 1 0 1 1 0 0 +EDGE2 2637 2516 -1.05417 0.133297 0.00641172 1 0 1 1 0 0 +EDGE2 2637 2636 -1.03737 0.0308891 0.0146742 1 0 1 1 0 0 +EDGE2 2638 2519 1.03774 0.0649014 -0.0112759 1 0 1 1 0 0 +EDGE2 2638 2637 -0.945659 -0.0625795 -0.0196416 1 0 1 1 0 0 +EDGE2 2638 2518 -0.00309392 -0.0530745 -0.00784875 1 0 1 1 0 0 +EDGE2 2638 2517 -1.01263 -0.0889441 -0.0167943 1 0 1 1 0 0 +EDGE2 2639 2420 1.0373 0.0602631 -3.12986 1 0 1 1 0 0 +EDGE2 2639 2560 1.01677 0.104586 -3.13965 1 0 1 1 0 0 +EDGE2 2639 2600 1.11163 -0.0324289 -3.12986 1 0 1 1 0 0 +EDGE2 2639 2580 1.09742 0.0394412 -3.15062 1 0 1 1 0 0 +EDGE2 2639 2500 0.9728 -0.0969051 -3.16299 1 0 1 1 0 0 +EDGE2 2639 2520 0.929294 -0.0882461 -0.00172781 1 0 1 1 0 0 +EDGE2 2639 2540 1.07398 0.149962 -3.1121 1 0 1 1 0 0 +EDGE2 2639 2440 1.07007 0.0323235 -3.14946 1 0 1 1 0 0 +EDGE2 2639 2300 0.984746 -0.041679 -3.13197 1 0 1 1 0 0 +EDGE2 2639 1260 1.04885 0.0171009 -3.11819 1 0 1 1 0 0 +EDGE2 2639 2519 0.132868 -0.0360873 -0.0181793 1 0 1 1 0 0 +EDGE2 2639 2518 -1.00183 -0.075306 0.0177544 1 0 1 1 0 0 +EDGE2 2639 2638 -0.9931 -0.0605764 0.0289555 1 0 1 1 0 0 +EDGE2 2640 2441 0.0288916 0.943928 1.57803 1 0 1 1 0 0 +EDGE2 2640 2521 0.0535596 -0.975233 -1.5558 1 0 1 1 0 0 +EDGE2 2640 2561 0.00214564 -1.04065 -1.54939 1 0 1 1 0 0 +EDGE2 2640 2581 -0.0449299 -1.04877 -1.57616 1 0 1 1 0 0 +EDGE2 2640 2541 0.0628795 -1.00951 -1.54439 1 0 1 1 0 0 +EDGE2 2640 2301 0.0345544 -0.88914 -1.60493 1 0 1 1 0 0 +EDGE2 2640 2421 0.0258837 -1.00109 -1.58736 1 0 1 1 0 0 +EDGE2 2640 1261 -0.028926 -1.07519 -1.59195 1 0 1 1 0 0 +EDGE2 2640 2499 0.965715 0.021762 -3.13677 1 0 1 1 0 0 +EDGE2 2640 2559 0.986142 -0.0135545 -3.15737 1 0 1 1 0 0 +EDGE2 2640 2579 0.955888 -0.0358023 -3.1177 1 0 1 1 0 0 +EDGE2 2640 2599 0.96647 0.0467398 -3.11297 1 0 1 1 0 0 +EDGE2 2640 2539 1.01197 0.0938772 -3.12629 1 0 1 1 0 0 +EDGE2 2640 2299 0.950889 -0.00335601 -3.17482 1 0 1 1 0 0 +EDGE2 2640 2419 0.990957 0.0216311 -3.13419 1 0 1 1 0 0 +EDGE2 2640 2439 0.914389 0.0225885 -3.15833 1 0 1 1 0 0 +EDGE2 2640 1259 0.996882 0.0307842 -3.1721 1 0 1 1 0 0 +EDGE2 2640 2420 -0.0219522 -0.105493 -3.15348 1 0 1 1 0 0 +EDGE2 2640 2560 -0.0312777 0.0615125 -3.13956 1 0 1 1 0 0 +EDGE2 2640 2600 -0.0499977 0.036172 -3.15068 1 0 1 1 0 0 +EDGE2 2640 2580 0.0864678 0.0576018 -3.13156 1 0 1 1 0 0 +EDGE2 2640 2500 -0.0294712 -0.0164578 -3.16757 1 0 1 1 0 0 +EDGE2 2640 2520 0.00270328 0.0168268 0.0297194 1 0 1 1 0 0 +EDGE2 2640 2540 -0.0197273 0.0695367 -3.17431 1 0 1 1 0 0 +EDGE2 2640 2440 0.00307808 -0.0560503 -3.09564 1 0 1 1 0 0 +EDGE2 2640 2300 -0.0124559 0.096095 -3.12574 1 0 1 1 0 0 +EDGE2 2640 1260 -0.0215143 -0.0179314 -3.16904 1 0 1 1 0 0 +EDGE2 2640 2601 0.0999454 0.99852 1.6064 1 0 1 1 0 0 +EDGE2 2640 2501 0.0049995 0.936461 1.54519 1 0 1 1 0 0 +EDGE2 2640 2639 -1.03516 0.000294276 0.0439599 1 0 1 1 0 0 +EDGE2 2640 2519 -0.988731 0.0328474 0.0392131 1 0 1 1 0 0 +EDGE2 2641 2441 -0.022702 -0.0180371 -0.0196553 1 0 1 1 0 0 +EDGE2 2641 2420 -0.904481 0.150731 1.59454 1 0 1 1 0 0 +EDGE2 2641 2560 -1.05089 -0.0598694 1.5621 1 0 1 1 0 0 +EDGE2 2641 2600 -0.894727 0.0538044 1.58994 1 0 1 1 0 0 +EDGE2 2641 2640 -0.997752 -0.100851 -1.55193 1 0 1 1 0 0 +EDGE2 2641 2580 -0.964219 -0.0485051 1.54707 1 0 1 1 0 0 +EDGE2 2641 2500 -0.963783 -0.0305169 1.58915 1 0 1 1 0 0 +EDGE2 2641 2520 -0.935972 -0.038568 -1.57587 1 0 1 1 0 0 +EDGE2 2641 2540 -1.01541 -0.0461146 1.55182 1 0 1 1 0 0 +EDGE2 2641 2440 -1.04742 -0.0245307 1.56195 1 0 1 1 0 0 +EDGE2 2641 2300 -0.985605 -0.0266066 1.58481 1 0 1 1 0 0 +EDGE2 2641 1260 -1.09277 0.134583 1.55288 1 0 1 1 0 0 +EDGE2 2641 2601 0.0451214 0.0559481 0.00102115 1 0 1 1 0 0 +EDGE2 2641 2501 -0.0336473 0.00606243 0.0404062 1 0 1 1 0 0 +EDGE2 2641 2442 1.02992 0.0325797 0.0228787 1 0 1 1 0 0 +EDGE2 2641 2602 1.00624 -0.0623064 -0.0285836 1 0 1 1 0 0 +EDGE2 2641 2502 1.03748 -0.0226345 -0.0358077 1 0 1 1 0 0 +EDGE2 2642 2441 -0.997102 -0.0628039 -0.00590753 1 0 1 1 0 0 +EDGE2 2642 2601 -1.07915 -0.0102633 0.0116102 1 0 1 1 0 0 +EDGE2 2642 2641 -1.03506 0.0106698 0.0163545 1 0 1 1 0 0 +EDGE2 2642 2501 -1.01313 0.0347931 -0.0224638 1 0 1 1 0 0 +EDGE2 2642 2443 1.01259 0.113226 0.0160884 1 0 1 1 0 0 +EDGE2 2642 2442 0.0394605 0.0516145 0.0327605 1 0 1 1 0 0 +EDGE2 2642 2602 0.0275185 -0.0799256 -0.0356131 1 0 1 1 0 0 +EDGE2 2642 2502 -0.121724 0.0292317 0.00812121 1 0 1 1 0 0 +EDGE2 2642 2603 0.969189 -0.0550325 -0.00657553 1 0 1 1 0 0 +EDGE2 2642 2503 0.998919 -0.0534832 -0.00867091 1 0 1 1 0 0 +EDGE2 2643 2443 0.0322676 -0.0422987 0.0217656 1 0 1 1 0 0 +EDGE2 2643 2442 -1.03608 0.0042405 -0.0302408 1 0 1 1 0 0 +EDGE2 2643 2602 -0.914375 -0.0617627 -0.0134132 1 0 1 1 0 0 +EDGE2 2643 2642 -0.980661 -0.032317 0.0093673 1 0 1 1 0 0 +EDGE2 2643 2502 -0.919755 0.020822 0.0236995 1 0 1 1 0 0 +EDGE2 2643 2603 -0.0525835 0.033282 -0.00964505 1 0 1 1 0 0 +EDGE2 2643 2503 -0.0197244 0.0405963 -0.0254438 1 0 1 1 0 0 +EDGE2 2643 2444 1.03727 0.0162358 0.0179872 1 0 1 1 0 0 +EDGE2 2643 2604 0.878494 0.0421628 -0.0151938 1 0 1 1 0 0 +EDGE2 2643 2504 0.955546 -0.0658979 -0.0153948 1 0 1 1 0 0 +EDGE2 2644 2443 -1.01435 -0.050132 -0.00430458 1 0 1 1 0 0 +EDGE2 2644 2603 -0.94692 -0.0197853 -0.0608866 1 0 1 1 0 0 +EDGE2 2644 2643 -0.936954 -0.0966963 -0.022032 1 0 1 1 0 0 +EDGE2 2644 2503 -1.02811 0.0337036 -0.0131478 1 0 1 1 0 0 +EDGE2 2644 2444 0.0403921 -0.0502738 -0.0228945 1 0 1 1 0 0 +EDGE2 2644 2604 0.0168407 -0.0341626 0.0102217 1 0 1 1 0 0 +EDGE2 2644 2504 0.0519216 -0.0173723 0.0137773 1 0 1 1 0 0 +EDGE2 2644 1225 1.04448 -0.0921797 -3.15145 1 0 1 1 0 0 +EDGE2 2644 2485 1.06046 -0.0302488 -3.11327 1 0 1 1 0 0 +EDGE2 2644 2505 1.00639 0.0784309 0.00526645 1 0 1 1 0 0 +EDGE2 2644 2605 0.920049 0.0562204 -0.0510155 1 0 1 1 0 0 +EDGE2 2644 2445 1.0512 0.0207439 0.012046 1 0 1 1 0 0 +EDGE2 2645 2446 -0.0214127 -1.00159 -1.54164 1 0 1 1 0 0 +EDGE2 2645 2486 0.00929627 -0.977044 -1.53772 1 0 1 1 0 0 +EDGE2 2645 1226 0.0698834 -1.03292 -1.58902 1 0 1 1 0 0 +EDGE2 2645 2444 -1.07213 -0.00612474 -0.0270668 1 0 1 1 0 0 +EDGE2 2645 2604 -0.947577 -0.115303 0.00170984 1 0 1 1 0 0 +EDGE2 2645 2644 -0.972406 0.0307382 -0.0179188 1 0 1 1 0 0 +EDGE2 2645 2504 -0.954586 -0.00177133 -0.00534399 1 0 1 1 0 0 +EDGE2 2645 1225 -0.0299924 -0.0283113 -3.13604 1 0 1 1 0 0 +EDGE2 2645 2485 0.0421714 -0.0388445 -3.15419 1 0 1 1 0 0 +EDGE2 2645 2505 0.130953 0.0170898 0.0251767 1 0 1 1 0 0 +EDGE2 2645 2605 -0.047206 0.0226715 -0.00747357 1 0 1 1 0 0 +EDGE2 2645 2445 -0.0713531 0.016576 0.00209218 1 0 1 1 0 0 +EDGE2 2645 1224 1.03493 -0.011621 -3.10682 1 0 1 1 0 0 +EDGE2 2645 2484 1.06468 0.0328559 -3.15468 1 0 1 1 0 0 +EDGE2 2645 2506 0.0278409 1.06632 1.57934 1 0 1 1 0 0 +EDGE2 2645 2606 -0.10062 1.00824 1.58615 1 0 1 1 0 0 +EDGE2 2646 2645 -0.985682 -0.037475 -1.57729 1 0 1 1 0 0 +EDGE2 2646 1225 -0.985803 0.0142192 1.55862 1 0 1 1 0 0 +EDGE2 2646 2485 -1.00165 0.0382314 1.57181 1 0 1 1 0 0 +EDGE2 2646 2505 -1.04276 0.0657856 -1.54699 1 0 1 1 0 0 +EDGE2 2646 2605 -0.962925 -0.014944 -1.5803 1 0 1 1 0 0 +EDGE2 2646 2445 -1.01526 0.0778804 -1.54535 1 0 1 1 0 0 +EDGE2 2646 2506 0.0298286 0.0554883 0.00710651 1 0 1 1 0 0 +EDGE2 2646 2606 -0.0201973 -0.114714 0.0423523 1 0 1 1 0 0 +EDGE2 2646 2607 0.933119 -0.00134283 0.0037084 1 0 1 1 0 0 +EDGE2 2646 2507 1.00764 0.0596436 -0.00541543 1 0 1 1 0 0 +EDGE2 2647 2506 -1.0541 0.00496039 -0.0149236 1 0 1 1 0 0 +EDGE2 2647 2606 -1.0351 0.0585972 -0.00305315 1 0 1 1 0 0 +EDGE2 2647 2646 -1.01645 0.0667724 0.0404683 1 0 1 1 0 0 +EDGE2 2647 2607 -0.0154234 -0.0124143 0.00353021 1 0 1 1 0 0 +EDGE2 2647 2507 -0.0648934 0.0670987 0.0435261 1 0 1 1 0 0 +EDGE2 2647 2508 1.02722 -0.0236631 0.00352006 1 0 1 1 0 0 +EDGE2 2647 2608 1.11515 -0.0212511 0.00064335 1 0 1 1 0 0 +EDGE2 2648 2607 -0.895313 -0.092544 0.0265031 1 0 1 1 0 0 +EDGE2 2648 2647 -1.00685 -0.025416 0.00998011 1 0 1 1 0 0 +EDGE2 2648 2507 -0.979574 0.0277594 -0.00971547 1 0 1 1 0 0 +EDGE2 2648 2508 0.075231 0.0667953 0.0106067 1 0 1 1 0 0 +EDGE2 2648 2608 0.024785 0.0947693 -0.0357189 1 0 1 1 0 0 +EDGE2 2648 2609 0.971304 -0.0288994 0.0108412 1 0 1 1 0 0 +EDGE2 2648 2509 1.01404 0.015957 -0.040054 1 0 1 1 0 0 +EDGE2 2649 2508 -1.02543 0.0591614 -0.0311289 1 0 1 1 0 0 +EDGE2 2649 2648 -0.976642 0.0631268 -0.0302453 1 0 1 1 0 0 +EDGE2 2649 2608 -0.952379 -0.043213 0.0123371 1 0 1 1 0 0 +EDGE2 2649 2609 -0.0371087 -0.00973197 0.0127173 1 0 1 1 0 0 +EDGE2 2649 2509 -0.110299 -0.0711101 0.00130045 1 0 1 1 0 0 +EDGE2 2649 2510 0.992689 0.0164782 0.0109413 1 0 1 1 0 0 +EDGE2 2649 2630 0.969226 0.0638408 -3.16168 1 0 1 1 0 0 +EDGE2 2649 2610 0.973835 0.0361105 0.0480387 1 0 1 1 0 0 +EDGE2 2650 2609 -0.995713 0.00777847 0.0175958 1 0 1 1 0 0 +EDGE2 2650 2649 -0.973677 -0.0197494 0.0431094 1 0 1 1 0 0 +EDGE2 2650 2509 -1.07015 0.0254703 -0.0350092 1 0 1 1 0 0 +EDGE2 2650 2631 0.0712162 0.923772 1.54853 1 0 1 1 0 0 +EDGE2 2650 2511 -0.038047 1.02341 1.59491 1 0 1 1 0 0 +EDGE2 2650 2510 0.00480586 -0.0808468 -0.0415472 1 0 1 1 0 0 +EDGE2 2650 2630 0.0288097 0.00809279 -3.14531 1 0 1 1 0 0 +EDGE2 2650 2610 0.00955406 -0.0717137 0.0200537 1 0 1 1 0 0 +EDGE2 2650 2629 0.997232 -0.00646082 -3.14305 1 0 1 1 0 0 +EDGE2 2650 2611 -0.0996895 -0.99732 -1.57581 1 0 1 1 0 0 +EDGE2 2651 2631 0.0182946 0.0404662 -0.00220673 1 0 1 1 0 0 +EDGE2 2651 2512 0.906336 -0.0348513 0.0251134 1 0 1 1 0 0 +EDGE2 2651 2632 1.03158 0.0675403 -0.0583335 1 0 1 1 0 0 +EDGE2 2651 2511 -0.0191849 -0.0368916 -0.0285357 1 0 1 1 0 0 +EDGE2 2651 2510 -1.00401 0.0485025 -1.56811 1 0 1 1 0 0 +EDGE2 2651 2630 -0.977119 -0.0401671 1.54479 1 0 1 1 0 0 +EDGE2 2651 2650 -0.875607 0.0426358 -1.57522 1 0 1 1 0 0 +EDGE2 2651 2610 -0.969121 0.0672789 -1.56606 1 0 1 1 0 0 +EDGE2 2652 2631 -0.980119 0.0359129 -0.0137579 1 0 1 1 0 0 +EDGE2 2652 2513 1.01324 1.55589e-05 -0.00814233 1 0 1 1 0 0 +EDGE2 2652 2633 1.05002 -0.159215 0.0215786 1 0 1 1 0 0 +EDGE2 2652 2512 -0.057643 0.105865 -0.01219 1 0 1 1 0 0 +EDGE2 2652 2632 -0.067296 -0.0196397 -0.0207631 1 0 1 1 0 0 +EDGE2 2652 2651 -1.04135 0.0403556 -0.0120204 1 0 1 1 0 0 +EDGE2 2652 2511 -1.076 -0.0346972 0.0477329 1 0 1 1 0 0 +EDGE2 2653 2513 -0.081212 -0.0989487 0.0103971 1 0 1 1 0 0 +EDGE2 2653 2514 1.03203 0.0204952 0.0103973 1 0 1 1 0 0 +EDGE2 2653 2634 1.02998 -0.0460794 -0.0253093 1 0 1 1 0 0 +EDGE2 2653 2633 -0.00182654 -0.0628784 -0.00811875 1 0 1 1 0 0 +EDGE2 2653 2512 -0.996964 -0.0216287 -0.0165545 1 0 1 1 0 0 +EDGE2 2653 2632 -1.07781 -0.0197338 0.0155786 1 0 1 1 0 0 +EDGE2 2653 2652 -0.92362 -0.0352079 0.00418399 1 0 1 1 0 0 +EDGE2 2654 1295 1.00412 -0.0145755 -3.12046 1 0 1 1 0 0 +EDGE2 2654 2515 1.0013 -0.0595189 -0.0191406 1 0 1 1 0 0 +EDGE2 2654 2635 0.986624 -0.0792602 0.00981431 1 0 1 1 0 0 +EDGE2 2654 1275 1.05809 0.071313 -3.13745 1 0 1 1 0 0 +EDGE2 2654 2513 -1.01798 0.0266781 0.0131461 1 0 1 1 0 0 +EDGE2 2654 2653 -0.97086 0.0068758 -0.0361809 1 0 1 1 0 0 +EDGE2 2654 2514 -0.0721305 0.031041 0.00856202 1 0 1 1 0 0 +EDGE2 2654 2634 0.0652982 0.0183563 0.0227467 1 0 1 1 0 0 +EDGE2 2654 2633 -0.972435 -0.0140208 0.00760409 1 0 1 1 0 0 +EDGE2 2655 2516 0.025505 1.02429 1.53471 1 0 1 1 0 0 +EDGE2 2655 2636 0.0224967 0.982858 1.57006 1 0 1 1 0 0 +EDGE2 2655 2654 -0.973062 -0.00540365 -0.0262801 1 0 1 1 0 0 +EDGE2 2655 1274 0.942361 -0.0614262 -3.16851 1 0 1 1 0 0 +EDGE2 2655 1294 0.971512 0.0644568 -3.15594 1 0 1 1 0 0 +EDGE2 2655 1295 -0.0480008 0.0263116 -3.14125 1 0 1 1 0 0 +EDGE2 2655 2515 0.00702938 -0.0484473 0.0210939 1 0 1 1 0 0 +EDGE2 2655 2635 0.144779 0.0436226 0.0611621 1 0 1 1 0 0 +EDGE2 2655 1275 -0.0630063 0.0109075 -3.13625 1 0 1 1 0 0 +EDGE2 2655 2514 -1.00311 -0.0226201 0.00541876 1 0 1 1 0 0 +EDGE2 2655 2634 -0.95231 -0.0280127 0.00697525 1 0 1 1 0 0 +EDGE2 2655 1296 0.0366036 -0.989025 -1.5888 1 0 1 1 0 0 +EDGE2 2655 1276 0.0297912 -0.973456 -1.56567 1 0 1 1 0 0 +EDGE2 2656 2637 0.91762 -0.034077 0.0277376 1 0 1 1 0 0 +EDGE2 2656 2517 0.922128 -0.0130503 0.0107581 1 0 1 1 0 0 +EDGE2 2656 2516 -0.0363173 -0.0102526 -0.0595376 1 0 1 1 0 0 +EDGE2 2656 2636 -0.00777357 0.0409714 -0.00430812 1 0 1 1 0 0 +EDGE2 2656 2655 -0.971249 -0.0371881 -1.59435 1 0 1 1 0 0 +EDGE2 2656 1295 -0.963609 -0.0777488 1.56287 1 0 1 1 0 0 +EDGE2 2656 2515 -1.02754 -0.0231977 -1.57431 1 0 1 1 0 0 +EDGE2 2656 2635 -1.0277 -0.0741882 -1.55789 1 0 1 1 0 0 +EDGE2 2656 1275 -0.969486 0.0111909 1.60733 1 0 1 1 0 0 +EDGE2 2657 2656 -0.952881 -0.00983474 -0.0104922 1 0 1 1 0 0 +EDGE2 2657 2637 -0.0940211 0.0223149 -0.0118429 1 0 1 1 0 0 +EDGE2 2657 2518 0.907712 0.0332515 -0.00188777 1 0 1 1 0 0 +EDGE2 2657 2638 1.04286 -0.0294199 0.00165184 1 0 1 1 0 0 +EDGE2 2657 2517 0.0133167 0.0548225 -0.00835958 1 0 1 1 0 0 +EDGE2 2657 2516 -0.948744 0.0353933 0.0178831 1 0 1 1 0 0 +EDGE2 2657 2636 -0.964796 0.00705981 -0.0155802 1 0 1 1 0 0 +EDGE2 2658 2639 1.03314 -0.125333 0.010066 1 0 1 1 0 0 +EDGE2 2658 2519 0.957393 -0.00734613 0.0151538 1 0 1 1 0 0 +EDGE2 2658 2637 -0.997009 -0.0245537 -0.0028054 1 0 1 1 0 0 +EDGE2 2658 2518 0.0400751 0.0762606 -0.0336904 1 0 1 1 0 0 +EDGE2 2658 2638 -0.0145435 -0.0537265 0.00429133 1 0 1 1 0 0 +EDGE2 2658 2657 -1.02628 -0.00603842 0.00967705 1 0 1 1 0 0 +EDGE2 2658 2517 -0.972855 -0.0250015 0.0415596 1 0 1 1 0 0 +EDGE2 2659 2420 1.01763 0.024438 -3.16649 1 0 1 1 0 0 +EDGE2 2659 2560 0.927635 -0.000721339 -3.13388 1 0 1 1 0 0 +EDGE2 2659 2600 1.06621 0.0166876 -3.13017 1 0 1 1 0 0 +EDGE2 2659 2640 0.966213 0.0898217 -0.038974 1 0 1 1 0 0 +EDGE2 2659 2580 1.00864 -0.0122471 -3.15341 1 0 1 1 0 0 +EDGE2 2659 2500 1.05021 0.048685 -3.15582 1 0 1 1 0 0 +EDGE2 2659 2520 0.979091 -0.00654346 0.0491886 1 0 1 1 0 0 +EDGE2 2659 2540 1.01417 0.00772653 -3.14869 1 0 1 1 0 0 +EDGE2 2659 2440 1.00682 -0.0195691 -3.14256 1 0 1 1 0 0 +EDGE2 2659 2300 0.938294 -0.0339871 -3.15522 1 0 1 1 0 0 +EDGE2 2659 1260 0.975011 -0.00928376 -3.1639 1 0 1 1 0 0 +EDGE2 2659 2639 -0.130884 0.0398127 0.00487229 1 0 1 1 0 0 +EDGE2 2659 2519 -0.0831503 0.0882603 0.0179906 1 0 1 1 0 0 +EDGE2 2659 2518 -1.03665 0.0359223 0.00742822 1 0 1 1 0 0 +EDGE2 2659 2638 -0.95773 0.0333267 -0.00208011 1 0 1 1 0 0 +EDGE2 2659 2658 -0.926582 0.0637752 -0.00249297 1 0 1 1 0 0 +EDGE2 2660 2441 -0.0363902 1.06661 1.57581 1 0 1 1 0 0 +EDGE2 2660 2521 0.0055758 -1.07562 -1.58314 1 0 1 1 0 0 +EDGE2 2660 2561 -0.00761258 -0.962127 -1.58747 1 0 1 1 0 0 +EDGE2 2660 2581 -0.0164679 -1.04316 -1.56393 1 0 1 1 0 0 +EDGE2 2660 2541 -0.000728678 -0.943464 -1.56239 1 0 1 1 0 0 +EDGE2 2660 2301 0.0114873 -1.08567 -1.56955 1 0 1 1 0 0 +EDGE2 2660 2421 0.0284327 -1.02466 -1.5654 1 0 1 1 0 0 +EDGE2 2660 1261 0.0395921 -1.0729 -1.54904 1 0 1 1 0 0 +EDGE2 2660 2499 0.942423 -0.112491 -3.16383 1 0 1 1 0 0 +EDGE2 2660 2559 0.987766 0.0614728 -3.16553 1 0 1 1 0 0 +EDGE2 2660 2579 0.944785 0.00735742 -3.11582 1 0 1 1 0 0 +EDGE2 2660 2599 0.960964 0.0432007 -3.13315 1 0 1 1 0 0 +EDGE2 2660 2539 1.02271 0.0365468 -3.13011 1 0 1 1 0 0 +EDGE2 2660 2299 1.05615 0.0118158 -3.13137 1 0 1 1 0 0 +EDGE2 2660 2419 0.970276 0.0387435 -3.12546 1 0 1 1 0 0 +EDGE2 2660 2439 1.06711 0.0537289 -3.13144 1 0 1 1 0 0 +EDGE2 2660 1259 1.00434 0.010982 -3.17609 1 0 1 1 0 0 +EDGE2 2660 2420 0.0693975 -0.00771477 -3.1496 1 0 1 1 0 0 +EDGE2 2660 2560 0.152331 -0.000531482 -3.15023 1 0 1 1 0 0 +EDGE2 2660 2600 -0.00268191 -0.103434 -3.14154 1 0 1 1 0 0 +EDGE2 2660 2640 -0.0284842 -0.0624705 -0.00860309 1 0 1 1 0 0 +EDGE2 2660 2580 -0.0264664 0.0113419 -3.14915 1 0 1 1 0 0 +EDGE2 2660 2500 0.089784 0.0404344 -3.1615 1 0 1 1 0 0 +EDGE2 2660 2520 0.0729702 -0.00635134 -0.0061622 1 0 1 1 0 0 +EDGE2 2660 2540 0.0060364 0.0664655 -3.12472 1 0 1 1 0 0 +EDGE2 2660 2440 -0.109067 -0.0811995 -3.09738 1 0 1 1 0 0 +EDGE2 2660 2300 -0.0594858 -0.0512606 -3.14493 1 0 1 1 0 0 +EDGE2 2660 1260 0.0206505 0.0330802 -3.15325 1 0 1 1 0 0 +EDGE2 2660 2601 0.0764017 0.985248 1.58402 1 0 1 1 0 0 +EDGE2 2660 2641 -0.0642383 0.936621 1.59767 1 0 1 1 0 0 +EDGE2 2660 2501 0.0724772 1.03308 1.59082 1 0 1 1 0 0 +EDGE2 2660 2639 -0.909428 0.00443317 -0.0180759 1 0 1 1 0 0 +EDGE2 2660 2659 -0.9933 0.0492231 0.00295254 1 0 1 1 0 0 +EDGE2 2660 2519 -0.88032 0.00110986 -0.00355195 1 0 1 1 0 0 +EDGE2 2661 2441 0.0080674 -0.0607818 0.0408938 1 0 1 1 0 0 +EDGE2 2661 2420 -1.02169 0.0118745 1.55532 1 0 1 1 0 0 +EDGE2 2661 2560 -1.02287 0.0287181 1.5706 1 0 1 1 0 0 +EDGE2 2661 2600 -1.06975 -0.0621409 1.57191 1 0 1 1 0 0 +EDGE2 2661 2640 -0.975805 -0.0234778 -1.56972 1 0 1 1 0 0 +EDGE2 2661 2660 -0.889065 0.0581592 -1.60303 1 0 1 1 0 0 +EDGE2 2661 2580 -1.03433 0.0371501 1.56802 1 0 1 1 0 0 +EDGE2 2661 2500 -0.982413 -0.105049 1.56537 1 0 1 1 0 0 +EDGE2 2661 2520 -1.06598 0.0347217 -1.60981 1 0 1 1 0 0 +EDGE2 2661 2540 -1.04561 -0.0586733 1.57379 1 0 1 1 0 0 +EDGE2 2661 2440 -1.05057 0.0478578 1.6017 1 0 1 1 0 0 +EDGE2 2661 2300 -0.999686 0.0338698 1.57125 1 0 1 1 0 0 +EDGE2 2661 1260 -0.966413 -0.0275124 1.57672 1 0 1 1 0 0 +EDGE2 2661 2601 -0.0157464 0.0105952 -0.0279611 1 0 1 1 0 0 +EDGE2 2661 2641 0.00954532 -0.0341255 0.0194891 1 0 1 1 0 0 +EDGE2 2661 2501 0.0382529 0.0214779 -0.031383 1 0 1 1 0 0 +EDGE2 2661 2442 1.07306 -0.0358989 -0.0204893 1 0 1 1 0 0 +EDGE2 2661 2602 1.07011 0.033572 -0.0130607 1 0 1 1 0 0 +EDGE2 2661 2642 0.980589 -0.0146757 -0.00103353 1 0 1 1 0 0 +EDGE2 2661 2502 1.06665 -0.034226 -0.00288534 1 0 1 1 0 0 +EDGE2 2662 2441 -0.99296 -0.0314121 -0.00462864 1 0 1 1 0 0 +EDGE2 2662 2661 -1.01181 -0.0542265 0.00624613 1 0 1 1 0 0 +EDGE2 2662 2601 -0.984243 -0.0405539 0.0245522 1 0 1 1 0 0 +EDGE2 2662 2641 -1.05203 -0.0259587 0.00666969 1 0 1 1 0 0 +EDGE2 2662 2501 -0.974445 0.0529855 -0.00965869 1 0 1 1 0 0 +EDGE2 2662 2443 0.898297 0.112534 8.59292e-05 1 0 1 1 0 0 +EDGE2 2662 2442 0.0415316 0.0607056 -0.0215883 1 0 1 1 0 0 +EDGE2 2662 2602 0.00245399 -0.0386745 0.0277775 1 0 1 1 0 0 +EDGE2 2662 2642 0.0300588 -0.0423036 0.0231923 1 0 1 1 0 0 +EDGE2 2662 2502 -0.0546526 -0.0364177 0.0249985 1 0 1 1 0 0 +EDGE2 2662 2603 0.995856 0.0197837 -0.00229261 1 0 1 1 0 0 +EDGE2 2662 2643 0.953085 -0.00419695 -0.0106318 1 0 1 1 0 0 +EDGE2 2662 2503 1.02026 0.0112874 0.00246234 1 0 1 1 0 0 +EDGE2 2663 2443 -0.0397071 0.072651 0.0135847 1 0 1 1 0 0 +EDGE2 2663 2442 -0.907809 0.0729657 -0.0291088 1 0 1 1 0 0 +EDGE2 2663 2602 -1.01383 0.0611731 0.0218482 1 0 1 1 0 0 +EDGE2 2663 2642 -0.97487 0.0368096 0.00696151 1 0 1 1 0 0 +EDGE2 2663 2662 -1.06875 -0.0570615 0.013794 1 0 1 1 0 0 +EDGE2 2663 2502 -1.00481 -0.00940187 -0.00305265 1 0 1 1 0 0 +EDGE2 2663 2603 -0.0980225 0.0393503 -0.00826919 1 0 1 1 0 0 +EDGE2 2663 2643 0.0917472 -0.138392 0.0120401 1 0 1 1 0 0 +EDGE2 2663 2503 0.00643489 0.0444725 0.00279426 1 0 1 1 0 0 +EDGE2 2663 2444 1.01752 0.0554451 -0.013434 1 0 1 1 0 0 +EDGE2 2663 2604 0.956901 0.0382013 -0.0182943 1 0 1 1 0 0 +EDGE2 2663 2644 0.906734 -0.0418222 0.0195755 1 0 1 1 0 0 +EDGE2 2663 2504 0.981088 -0.00192256 0.0256179 1 0 1 1 0 0 +EDGE2 2664 2645 1.05119 -0.028136 -0.0238943 1 0 1 1 0 0 +EDGE2 2664 2443 -0.993849 -0.0353476 -0.0124768 1 0 1 1 0 0 +EDGE2 2664 2603 -0.911561 0.0321159 0.0108787 1 0 1 1 0 0 +EDGE2 2664 2643 -0.931172 0.105619 0.013194 1 0 1 1 0 0 +EDGE2 2664 2663 -1.00699 0.0149767 -0.0407581 1 0 1 1 0 0 +EDGE2 2664 2503 -0.957879 -0.090904 -0.0183255 1 0 1 1 0 0 +EDGE2 2664 2444 0.0318898 -0.0639061 0.0138103 1 0 1 1 0 0 +EDGE2 2664 2604 -0.0656893 0.00276389 -0.00236849 1 0 1 1 0 0 +EDGE2 2664 2644 -0.0120611 -0.0207612 0.0229198 1 0 1 1 0 0 +EDGE2 2664 2504 0.0482651 -0.0236334 -0.0515974 1 0 1 1 0 0 +EDGE2 2664 1225 1.07226 -0.0124353 -3.14866 1 0 1 1 0 0 +EDGE2 2664 2485 1.02549 0.00678048 -3.14348 1 0 1 1 0 0 +EDGE2 2664 2505 1.02498 0.061644 -0.0063339 1 0 1 1 0 0 +EDGE2 2664 2605 0.983313 -0.0472376 -0.0165994 1 0 1 1 0 0 +EDGE2 2664 2445 1.00875 0.0488213 -0.0107201 1 0 1 1 0 0 +EDGE2 2665 2446 0.0198384 -1.02463 -1.55328 1 0 1 1 0 0 +EDGE2 2665 2486 0.0016217 -0.957321 -1.56609 1 0 1 1 0 0 +EDGE2 2665 1226 0.0183581 -1.02806 -1.5815 1 0 1 1 0 0 +EDGE2 2665 2645 0.0102728 -0.0693381 0.0491581 1 0 1 1 0 0 +EDGE2 2665 2444 -1.00257 -0.0484439 -0.0238993 1 0 1 1 0 0 +EDGE2 2665 2604 -0.950466 0.0311623 0.0325704 1 0 1 1 0 0 +EDGE2 2665 2644 -0.953483 0.128212 -0.0169724 1 0 1 1 0 0 +EDGE2 2665 2664 -1.01336 0.0837715 -0.022818 1 0 1 1 0 0 +EDGE2 2665 2504 -1.05047 0.0102802 0.0130898 1 0 1 1 0 0 +EDGE2 2665 1225 0.0573527 0.0302586 -3.11323 1 0 1 1 0 0 +EDGE2 2665 2485 -0.0177741 0.00631492 -3.09945 1 0 1 1 0 0 +EDGE2 2665 2505 0.00893233 0.0278152 0.024405 1 0 1 1 0 0 +EDGE2 2665 2605 -0.0292503 0.0555242 -0.0111639 1 0 1 1 0 0 +EDGE2 2665 2445 -0.0286339 0.0392348 0.00684826 1 0 1 1 0 0 +EDGE2 2665 1224 1.02277 -0.000733013 -3.13996 1 0 1 1 0 0 +EDGE2 2665 2484 1.02864 -0.0170807 -3.12744 1 0 1 1 0 0 +EDGE2 2665 2506 0.0188652 0.99592 1.58213 1 0 1 1 0 0 +EDGE2 2665 2606 0.00266655 0.989301 1.57869 1 0 1 1 0 0 +EDGE2 2665 2646 0.0418885 1.0066 1.57231 1 0 1 1 0 0 +EDGE2 2666 2645 -0.946381 -0.00603279 -1.59881 1 0 1 1 0 0 +EDGE2 2666 2665 -1.0061 -0.073034 -1.56665 1 0 1 1 0 0 +EDGE2 2666 1225 -0.87955 -0.13255 1.58163 1 0 1 1 0 0 +EDGE2 2666 2485 -1.06418 -0.041878 1.58697 1 0 1 1 0 0 +EDGE2 2666 2505 -1.00893 -0.0504694 -1.55937 1 0 1 1 0 0 +EDGE2 2666 2605 -0.99694 -0.00314404 -1.55612 1 0 1 1 0 0 +EDGE2 2666 2445 -1.05189 0.0130124 -1.56818 1 0 1 1 0 0 +EDGE2 2666 2506 -0.0451679 0.0431748 0.00178411 1 0 1 1 0 0 +EDGE2 2666 2606 0.0802418 0.0246165 0.000200832 1 0 1 1 0 0 +EDGE2 2666 2646 0.049905 -0.00426883 1.60478e-05 1 0 1 1 0 0 +EDGE2 2666 2607 1.01224 -0.0722099 -0.000603637 1 0 1 1 0 0 +EDGE2 2666 2647 0.915963 0.0373418 0.00728845 1 0 1 1 0 0 +EDGE2 2666 2507 0.9073 0.00451874 -0.00656241 1 0 1 1 0 0 +EDGE2 2667 2666 -1.03585 0.0512481 -0.000306569 1 0 1 1 0 0 +EDGE2 2667 2506 -1.02965 -0.0485363 -0.0276543 1 0 1 1 0 0 +EDGE2 2667 2606 -1.00441 -0.0391755 0.0299888 1 0 1 1 0 0 +EDGE2 2667 2646 -0.916428 -0.0223196 -0.0074071 1 0 1 1 0 0 +EDGE2 2667 2607 -0.0743645 0.040156 -0.0160867 1 0 1 1 0 0 +EDGE2 2667 2647 0.0010501 -0.0746487 0.0147876 1 0 1 1 0 0 +EDGE2 2667 2507 -0.0504178 0.0198204 0.00697136 1 0 1 1 0 0 +EDGE2 2667 2508 0.972079 0.0782869 0.0307891 1 0 1 1 0 0 +EDGE2 2667 2648 1.04423 0.0142433 -0.0280971 1 0 1 1 0 0 +EDGE2 2667 2608 0.891851 0.00608432 -0.0156473 1 0 1 1 0 0 +EDGE2 2668 2607 -0.921047 0.0348624 0.0583277 1 0 1 1 0 0 +EDGE2 2668 2647 -0.983538 -0.0485716 -0.042751 1 0 1 1 0 0 +EDGE2 2668 2667 -0.995982 0.0382289 0.0081627 1 0 1 1 0 0 +EDGE2 2668 2507 -0.875015 0.0625553 0.0301464 1 0 1 1 0 0 +EDGE2 2668 2508 0.00644753 -0.0372946 0.027703 1 0 1 1 0 0 +EDGE2 2668 2648 -0.0593702 0.0291688 0.0283631 1 0 1 1 0 0 +EDGE2 2668 2608 -0.0473641 -0.0602192 0.0206146 1 0 1 1 0 0 +EDGE2 2668 2609 0.96308 -0.110853 0.00917459 1 0 1 1 0 0 +EDGE2 2668 2649 1.01882 -0.0914226 0.00758028 1 0 1 1 0 0 +EDGE2 2668 2509 1.00434 0.0476495 -0.00723666 1 0 1 1 0 0 +EDGE2 2669 2508 -1.00838 -0.0037424 0.0378689 1 0 1 1 0 0 +EDGE2 2669 2648 -1.06082 0.0246845 0.000757402 1 0 1 1 0 0 +EDGE2 2669 2668 -1.04602 -0.0348692 -0.01114 1 0 1 1 0 0 +EDGE2 2669 2608 -0.988228 0.0295847 -0.0262449 1 0 1 1 0 0 +EDGE2 2669 2609 0.00842882 0.0163231 0.00994225 1 0 1 1 0 0 +EDGE2 2669 2649 -0.0207497 -0.0482504 -0.00117578 1 0 1 1 0 0 +EDGE2 2669 2509 0.00719518 -0.0143356 0.00415475 1 0 1 1 0 0 +EDGE2 2669 2510 1.07009 0.0415156 -0.0251863 1 0 1 1 0 0 +EDGE2 2669 2630 0.981437 -0.00529376 -3.10213 1 0 1 1 0 0 +EDGE2 2669 2650 0.959207 -0.0783037 0.0242917 1 0 1 1 0 0 +EDGE2 2669 2610 1.0775 0.0908333 0.0242739 1 0 1 1 0 0 +EDGE2 2670 2609 -0.911157 -0.0233713 -0.0248299 1 0 1 1 0 0 +EDGE2 2670 2649 -1.09801 0.00309262 0.0521048 1 0 1 1 0 0 +EDGE2 2670 2669 -1.06565 -0.00700747 0.0173163 1 0 1 1 0 0 +EDGE2 2670 2509 -0.985333 0.0512584 -0.006719 1 0 1 1 0 0 +EDGE2 2670 2631 -0.0153471 1.00014 1.61162 1 0 1 1 0 0 +EDGE2 2670 2651 -0.0483104 0.978593 1.57912 1 0 1 1 0 0 +EDGE2 2670 2511 0.0317278 0.946113 1.59569 1 0 1 1 0 0 +EDGE2 2670 2510 -0.0601512 -0.0380808 0.0207956 1 0 1 1 0 0 +EDGE2 2670 2630 0.0206793 0.0228519 -3.13302 1 0 1 1 0 0 +EDGE2 2670 2650 -0.00945527 0.00670982 -0.00900162 1 0 1 1 0 0 +EDGE2 2670 2610 0.0043734 -0.0387528 -0.0106784 1 0 1 1 0 0 +EDGE2 2670 2629 0.940747 0.00737718 -3.15433 1 0 1 1 0 0 +EDGE2 2670 2611 0.048101 -1.06863 -1.57549 1 0 1 1 0 0 +EDGE2 2671 2510 -1.052 -0.0398384 1.56952 1 0 1 1 0 0 +EDGE2 2671 2630 -0.95192 0.0419342 -1.57046 1 0 1 1 0 0 +EDGE2 2671 2650 -0.86487 0.0324866 1.58958 1 0 1 1 0 0 +EDGE2 2671 2670 -0.959566 -0.0449467 1.53057 1 0 1 1 0 0 +EDGE2 2671 2610 -0.999293 -0.029739 1.5686 1 0 1 1 0 0 +EDGE2 2671 2611 0.00731958 -0.0175304 0.0260409 1 0 1 1 0 0 +EDGE2 2671 2612 1.06468 0.0119536 0.00353039 1 0 1 1 0 0 +EDGE2 2672 2671 -1.02232 0.0130663 -0.0221564 1 0 1 1 0 0 +EDGE2 2672 2611 -1.00421 0.0232704 -0.0234473 1 0 1 1 0 0 +EDGE2 2672 2612 0.102509 0.0271383 -0.00293989 1 0 1 1 0 0 +EDGE2 2672 2613 0.977407 0.00129268 0.051672 1 0 1 1 0 0 +EDGE2 2673 2612 -1.02846 0.0297889 0.00959624 1 0 1 1 0 0 +EDGE2 2673 2672 -0.938148 -0.0735516 0.0027472 1 0 1 1 0 0 +EDGE2 2673 2613 0.0592042 0.0223868 0.00876871 1 0 1 1 0 0 +EDGE2 2673 2614 1.02695 0.00527329 0.00958741 1 0 1 1 0 0 +EDGE2 2674 2613 -1.05432 0.0241965 -0.0106643 1 0 1 1 0 0 +EDGE2 2674 2673 -1.01102 -0.0402349 0.0114816 1 0 1 1 0 0 +EDGE2 2674 2614 0.0816127 -0.0366536 0.0229436 1 0 1 1 0 0 +EDGE2 2674 2615 1.00738 0.0146309 0.00354427 1 0 1 1 0 0 +EDGE2 2675 2674 -0.974157 0.0254227 -0.00672437 1 0 1 1 0 0 +EDGE2 2675 2614 -0.973212 -0.127654 -0.0379263 1 0 1 1 0 0 +EDGE2 2675 2615 -0.0456942 -0.0107288 0.0195209 1 0 1 1 0 0 +EDGE2 2675 2616 -0.110005 0.995077 1.59307 1 0 1 1 0 0 +EDGE2 2676 2615 -0.9716 -0.0282077 -1.62103 1 0 1 1 0 0 +EDGE2 2676 2675 -1.03763 -0.0345859 -1.57569 1 0 1 1 0 0 +EDGE2 2676 2616 -0.0178935 0.0770843 0.0107427 1 0 1 1 0 0 +EDGE2 2676 2617 1.01101 0.039906 0.0153268 1 0 1 1 0 0 +EDGE2 2677 2676 -0.971635 -0.00764254 -0.0157845 1 0 1 1 0 0 +EDGE2 2677 2616 -0.96693 0.0393413 0.00225399 1 0 1 1 0 0 +EDGE2 2677 2617 0.0176426 0.0680309 -0.0151293 1 0 1 1 0 0 +EDGE2 2677 2618 0.963776 -0.00377647 -0.0244113 1 0 1 1 0 0 +EDGE2 2678 2677 -1.0424 0.0831583 0.0169169 1 0 1 1 0 0 +EDGE2 2678 2617 -1.00925 0.0279644 0.0145854 1 0 1 1 0 0 +EDGE2 2678 2618 0.00297737 -0.0839614 0.00410215 1 0 1 1 0 0 +EDGE2 2678 2619 0.979162 -0.0230902 0.0282215 1 0 1 1 0 0 +EDGE2 2679 2618 -1.09957 0.0716446 0.00674875 1 0 1 1 0 0 +EDGE2 2679 2678 -1.02117 -0.0710832 0.00331428 1 0 1 1 0 0 +EDGE2 2679 2619 -0.0599353 0.0279639 -0.00776587 1 0 1 1 0 0 +EDGE2 2679 2620 0.938315 0.0144086 -0.0174816 1 0 1 1 0 0 +EDGE2 2680 2619 -0.923044 -0.0526957 0.0419846 1 0 1 1 0 0 +EDGE2 2680 2679 -1.04536 0.0230266 0.00579088 1 0 1 1 0 0 +EDGE2 2680 2621 0.00961686 1.02351 1.57537 1 0 1 1 0 0 +EDGE2 2680 2620 0.0581255 0.0221122 -0.000630466 1 0 1 1 0 0 +EDGE2 2681 2622 0.94321 -0.0182924 -0.0156501 1 0 1 1 0 0 +EDGE2 2681 2621 -0.0594632 0.0562038 0.0102362 1 0 1 1 0 0 +EDGE2 2681 2620 -1.08154 0.00538127 -1.58651 1 0 1 1 0 0 +EDGE2 2681 2680 -1.03653 -0.0196484 -1.56839 1 0 1 1 0 0 +EDGE2 2682 2622 0.0369054 -0.0933434 -0.00627089 1 0 1 1 0 0 +EDGE2 2682 2623 1.02614 0.054329 0.00931016 1 0 1 1 0 0 +EDGE2 2682 2681 -0.942844 -0.00277384 -0.0212628 1 0 1 1 0 0 +EDGE2 2682 2621 -0.982076 -0.0688069 -0.0238593 1 0 1 1 0 0 +EDGE2 2683 2624 0.997165 -0.0336586 -0.0160027 1 0 1 1 0 0 +EDGE2 2683 2622 -0.988466 -0.0307702 -0.0529437 1 0 1 1 0 0 +EDGE2 2683 2623 -0.00982706 -0.0812861 0.00450896 1 0 1 1 0 0 +EDGE2 2683 2682 -1.06898 0.045132 -0.0218358 1 0 1 1 0 0 +EDGE2 2684 2624 -0.104299 0.0158977 -0.0150439 1 0 1 1 0 0 +EDGE2 2684 2625 0.964462 -0.0353575 8.37278e-05 1 0 1 1 0 0 +EDGE2 2684 2683 -1.00003 0.0486234 -0.00341527 1 0 1 1 0 0 +EDGE2 2684 2623 -0.994565 -0.084253 0.0302553 1 0 1 1 0 0 +EDGE2 2685 2626 0.0173533 0.85087 1.5702 1 0 1 1 0 0 +EDGE2 2685 2624 -0.942646 -0.0420412 -0.0205426 1 0 1 1 0 0 +EDGE2 2685 2625 0.0116361 0.106812 0.0220387 1 0 1 1 0 0 +EDGE2 2685 2684 -1.03179 -0.0459893 0.0150605 1 0 1 1 0 0 +EDGE2 2686 2627 1.06791 -0.04129 -0.0340634 1 0 1 1 0 0 +EDGE2 2686 2626 0.0621584 0.0377453 -0.0269686 1 0 1 1 0 0 +EDGE2 2686 2685 -0.972573 0.0353471 -1.56951 1 0 1 1 0 0 +EDGE2 2686 2625 -1.09022 0.0380995 -1.56103 1 0 1 1 0 0 +EDGE2 2687 2628 1.01785 -0.00288337 -0.00286055 1 0 1 1 0 0 +EDGE2 2687 2627 -0.0609814 0.0843138 0.00867711 1 0 1 1 0 0 +EDGE2 2687 2686 -0.945343 0.0233977 0.0197959 1 0 1 1 0 0 +EDGE2 2687 2626 -1.14213 -0.00022183 -0.0147071 1 0 1 1 0 0 +EDGE2 2688 2687 -0.955884 -0.0193248 -0.0108526 1 0 1 1 0 0 +EDGE2 2688 2629 0.987076 -0.0598084 -0.0355372 1 0 1 1 0 0 +EDGE2 2688 2628 -0.0086316 0.0729863 0.00202232 1 0 1 1 0 0 +EDGE2 2688 2627 -1.03806 0.00117687 -0.0334876 1 0 1 1 0 0 +EDGE2 2689 2510 1.06347 -0.0983366 -3.1587 1 0 1 1 0 0 +EDGE2 2689 2630 0.981085 -0.0798979 -0.0069771 1 0 1 1 0 0 +EDGE2 2689 2650 1.01693 -0.0271228 -3.12452 1 0 1 1 0 0 +EDGE2 2689 2670 0.95192 0.00970286 -3.16308 1 0 1 1 0 0 +EDGE2 2689 2610 1.03598 0.00336354 -3.12538 1 0 1 1 0 0 +EDGE2 2689 2688 -1.00183 -0.0341912 -0.0204659 1 0 1 1 0 0 +EDGE2 2689 2629 -0.0364193 0.0171965 0.0233487 1 0 1 1 0 0 +EDGE2 2689 2628 -1.08971 -0.0139892 -0.0152939 1 0 1 1 0 0 +EDGE2 2690 2609 0.913376 -0.059235 -3.15426 1 0 1 1 0 0 +EDGE2 2690 2649 0.999786 0.033628 -3.13347 1 0 1 1 0 0 +EDGE2 2690 2669 0.964508 0.0322744 -3.17666 1 0 1 1 0 0 +EDGE2 2690 2509 0.894296 -0.00664716 -3.15454 1 0 1 1 0 0 +EDGE2 2690 2689 -0.907419 0.0261866 0.00292356 1 0 1 1 0 0 +EDGE2 2690 2631 0.00475442 -0.962608 -1.58043 1 0 1 1 0 0 +EDGE2 2690 2651 -0.0655303 -0.950264 -1.56078 1 0 1 1 0 0 +EDGE2 2690 2511 -0.0408765 -0.942417 -1.54903 1 0 1 1 0 0 +EDGE2 2690 2510 0.00750237 0.0470329 -3.11024 1 0 1 1 0 0 +EDGE2 2690 2630 -0.0303683 -0.0433469 0.0050118 1 0 1 1 0 0 +EDGE2 2690 2650 0.00250559 0.0135818 -3.1367 1 0 1 1 0 0 +EDGE2 2690 2670 -0.0241027 0.050371 -3.12214 1 0 1 1 0 0 +EDGE2 2690 2610 0.0218876 -0.024688 -3.14368 1 0 1 1 0 0 +EDGE2 2690 2629 -0.963514 0.0244347 -0.00404947 1 0 1 1 0 0 +EDGE2 2690 2671 0.0973764 1.03007 1.51898 1 0 1 1 0 0 +EDGE2 2690 2611 -0.133732 1.11925 1.59686 1 0 1 1 0 0 +EDGE2 2691 2690 -1.04859 0.10852 -1.58802 1 0 1 1 0 0 +EDGE2 2691 2510 -0.986116 -0.0533667 1.58495 1 0 1 1 0 0 +EDGE2 2691 2630 -0.96427 -0.0195233 -1.55747 1 0 1 1 0 0 +EDGE2 2691 2650 -0.990374 0.0591533 1.58319 1 0 1 1 0 0 +EDGE2 2691 2670 -1.00231 -0.000337798 1.57423 1 0 1 1 0 0 +EDGE2 2691 2610 -1.06051 0.0528744 1.56949 1 0 1 1 0 0 +EDGE2 2691 2671 0.0127816 -0.0176207 -0.0100735 1 0 1 1 0 0 +EDGE2 2691 2611 0.0204984 -0.0405091 0.0148508 1 0 1 1 0 0 +EDGE2 2691 2612 0.981409 -0.0379734 0.019387 1 0 1 1 0 0 +EDGE2 2691 2672 1.03388 -0.0520962 -0.00145332 1 0 1 1 0 0 +EDGE2 2692 2671 -0.914271 -0.0488585 -0.0229366 1 0 1 1 0 0 +EDGE2 2692 2691 -0.967473 0.0119048 -0.0319789 1 0 1 1 0 0 +EDGE2 2692 2611 -0.958471 -0.048852 -0.0195663 1 0 1 1 0 0 +EDGE2 2692 2612 0.0433823 0.0241757 -0.0215802 1 0 1 1 0 0 +EDGE2 2692 2672 -0.0498288 0.021891 0.00527099 1 0 1 1 0 0 +EDGE2 2692 2613 0.972187 -0.0248076 -0.0269731 1 0 1 1 0 0 +EDGE2 2692 2673 0.982681 -0.0491283 0.0184614 1 0 1 1 0 0 +EDGE2 2693 2692 -0.998272 0.0705862 0.0154331 1 0 1 1 0 0 +EDGE2 2693 2612 -1.05576 -0.0034739 -0.00298352 1 0 1 1 0 0 +EDGE2 2693 2672 -0.972971 0.0372606 0.00414746 1 0 1 1 0 0 +EDGE2 2693 2613 -0.020662 -0.0977229 0.0209913 1 0 1 1 0 0 +EDGE2 2693 2673 0.0208205 -0.0759895 0.0111325 1 0 1 1 0 0 +EDGE2 2693 2674 1.02919 0.0166473 0.00508345 1 0 1 1 0 0 +EDGE2 2693 2614 0.986936 0.076317 0.0238361 1 0 1 1 0 0 +EDGE2 2694 2613 -1.06632 -0.0119292 -0.00729465 1 0 1 1 0 0 +EDGE2 2694 2673 -1.02064 0.0781728 0.017803 1 0 1 1 0 0 +EDGE2 2694 2693 -0.933408 -0.101417 -0.0601489 1 0 1 1 0 0 +EDGE2 2694 2674 0.0241681 0.0258623 -0.0354006 1 0 1 1 0 0 +EDGE2 2694 2614 -0.0655781 0.0934369 -0.0168028 1 0 1 1 0 0 +EDGE2 2694 2615 0.987005 0.0070016 -0.00337641 1 0 1 1 0 0 +EDGE2 2694 2675 0.956473 -0.0586434 -0.0209852 1 0 1 1 0 0 +EDGE2 2695 2674 -0.975349 0.00208146 -0.0203413 1 0 1 1 0 0 +EDGE2 2695 2694 -0.916976 0.0217165 0.0021697 1 0 1 1 0 0 +EDGE2 2695 2614 -0.928048 -0.0111487 0.016593 1 0 1 1 0 0 +EDGE2 2695 2615 0.0466374 0.0559661 0.0352451 1 0 1 1 0 0 +EDGE2 2695 2675 0.0572729 -0.053767 0.0341413 1 0 1 1 0 0 +EDGE2 2695 2676 3.77627e-05 1.0496 1.54385 1 0 1 1 0 0 +EDGE2 2695 2616 0.0283061 0.953677 1.52529 1 0 1 1 0 0 +EDGE2 2696 2615 -1.07714 -0.0480082 -1.54424 1 0 1 1 0 0 +EDGE2 2696 2675 -0.982045 0.00252516 -1.57084 1 0 1 1 0 0 +EDGE2 2696 2695 -1.04142 0.0310417 -1.58831 1 0 1 1 0 0 +EDGE2 2696 2677 1.03928 0.00642315 -0.0103982 1 0 1 1 0 0 +EDGE2 2696 2676 -0.0133826 -0.00390895 0.0283361 1 0 1 1 0 0 +EDGE2 2696 2616 -0.0464862 -0.0317691 -0.0111381 1 0 1 1 0 0 +EDGE2 2696 2617 0.950335 0.0735726 0.0191544 1 0 1 1 0 0 +EDGE2 2697 2677 -0.0316509 0.00584248 0.0141355 1 0 1 1 0 0 +EDGE2 2697 2676 -1.04454 0.0136895 0.0023162 1 0 1 1 0 0 +EDGE2 2697 2696 -1.02187 0.0200453 -0.00900511 1 0 1 1 0 0 +EDGE2 2697 2616 -1.03199 0.0279828 0.0248553 1 0 1 1 0 0 +EDGE2 2697 2617 -0.0197105 -0.0325495 -0.0179132 1 0 1 1 0 0 +EDGE2 2697 2618 0.976743 0.0211445 0.0271831 1 0 1 1 0 0 +EDGE2 2697 2678 0.914196 -0.0234659 0.00963201 1 0 1 1 0 0 +EDGE2 2698 2677 -1.00323 0.00999265 0.0165204 1 0 1 1 0 0 +EDGE2 2698 2697 -0.94435 0.0592735 -0.0143077 1 0 1 1 0 0 +EDGE2 2698 2617 -1.01252 0.138346 -0.016222 1 0 1 1 0 0 +EDGE2 2698 2618 -0.0389459 -0.0791953 -0.0111353 1 0 1 1 0 0 +EDGE2 2698 2678 0.0246733 0.00728546 -0.0238555 1 0 1 1 0 0 +EDGE2 2698 2619 0.991048 0.0052561 -0.0196746 1 0 1 1 0 0 +EDGE2 2698 2679 0.978665 -0.00281384 0.0259407 1 0 1 1 0 0 +EDGE2 2699 2698 -0.955363 -0.0109065 0.0302731 1 0 1 1 0 0 +EDGE2 2699 2618 -1.01547 0.0401989 -0.0215449 1 0 1 1 0 0 +EDGE2 2699 2678 -0.997538 0.0370703 0.011511 1 0 1 1 0 0 +EDGE2 2699 2619 6.11367e-05 -0.0737345 -0.00183931 1 0 1 1 0 0 +EDGE2 2699 2679 -0.0637186 0.059075 0.00365635 1 0 1 1 0 0 +EDGE2 2699 2620 0.900754 -0.00301882 0.0257707 1 0 1 1 0 0 +EDGE2 2699 2680 0.921269 -0.0591911 -0.0382972 1 0 1 1 0 0 +EDGE2 2700 2699 -0.987238 0.0449683 -0.00120033 1 0 1 1 0 0 +EDGE2 2700 2619 -0.97319 0.063048 -0.0015539 1 0 1 1 0 0 +EDGE2 2700 2679 -0.989443 0.0261768 0.0270309 1 0 1 1 0 0 +EDGE2 2700 2681 -0.0268131 0.858354 1.60318 1 0 1 1 0 0 +EDGE2 2700 2621 -0.0860971 1.12944 1.58181 1 0 1 1 0 0 +EDGE2 2700 2620 -0.073912 -0.0262301 -0.0060144 1 0 1 1 0 0 +EDGE2 2700 2680 0.0218486 -0.00394849 0.0121921 1 0 1 1 0 0 +EDGE2 2701 2620 -1.02323 -0.0281435 1.5701 1 0 1 1 0 0 +EDGE2 2701 2680 -1.02205 -0.0485596 1.56504 1 0 1 1 0 0 +EDGE2 2701 2700 -0.970982 -0.0381155 1.57781 1 0 1 1 0 0 +EDGE2 2702 2701 -1.04933 0.0058474 0.00687145 1 0 1 1 0 0 +EDGE2 2703 2702 -1.00747 0.0212534 0.0243666 1 0 1 1 0 0 +EDGE2 2704 2703 -1.05994 -0.0016094 -0.0192818 1 0 1 1 0 0 +EDGE2 2705 2704 -1.05336 0.0687373 0.0285919 1 0 1 1 0 0 +EDGE2 2706 2705 -0.940355 0.0370083 1.59533 1 0 1 1 0 0 +EDGE2 2707 2706 -0.962262 0.0567134 -0.0016275 1 0 1 1 0 0 +EDGE2 2708 2707 -1.01167 -0.0527763 0.0435653 1 0 1 1 0 0 +EDGE2 2709 2708 -0.98526 -0.0401149 0.0111527 1 0 1 1 0 0 +EDGE2 2710 2709 -0.990077 -0.0222317 0.00819535 1 0 1 1 0 0 +EDGE2 2711 2710 -0.996624 0.0444945 -1.56373 1 0 1 1 0 0 +EDGE2 2712 2711 -0.967929 -0.0619393 -0.00850168 1 0 1 1 0 0 +EDGE2 2713 2712 -0.924909 0.0870831 0.0399372 1 0 1 1 0 0 +EDGE2 2714 2713 -0.995654 -0.0176097 0.00502599 1 0 1 1 0 0 +EDGE2 2715 2714 -0.983346 -0.141023 -0.00479146 1 0 1 1 0 0 +EDGE2 2716 2715 -0.909777 -0.00420445 -1.59053 1 0 1 1 0 0 +EDGE2 2717 2716 -0.978846 -0.0208924 -0.00327404 1 0 1 1 0 0 +EDGE2 2718 2717 -0.965277 -0.0190059 0.0194238 1 0 1 1 0 0 +EDGE2 2719 2718 -1.0489 -0.0212239 -0.0389103 1 0 1 1 0 0 +EDGE2 2720 2719 -0.89343 -0.0382599 -0.0109788 1 0 1 1 0 0 +EDGE2 2721 2720 -1.09321 0.0275368 1.58914 1 0 1 1 0 0 +EDGE2 2722 2721 -1.0832 -0.0405012 -0.0260416 1 0 1 1 0 0 +EDGE2 2723 2722 -0.957618 -0.045648 0.0543759 1 0 1 1 0 0 +EDGE2 2724 2723 -1.00028 0.0385187 0.00584177 1 0 1 1 0 0 +EDGE2 2725 2724 -1.01366 -0.0293026 0.0255213 1 0 1 1 0 0 +EDGE2 2726 2725 -1.11109 -0.026718 -1.60284 1 0 1 1 0 0 +EDGE2 2727 2726 -1.00185 0.0755163 -0.00716906 1 0 1 1 0 0 +EDGE2 2728 2727 -0.982381 0.00272517 0.0202504 1 0 1 1 0 0 +EDGE2 2729 2728 -1.05817 -0.0167146 -0.00555376 1 0 1 1 0 0 +EDGE2 2730 2729 -1.08607 0.00910683 0.00699674 1 0 1 1 0 0 +EDGE2 2731 2730 -0.988977 -0.0281134 -1.52408 1 0 1 1 0 0 +EDGE2 2732 2731 -0.967875 -0.00348912 -0.0208334 1 0 1 1 0 0 +EDGE2 2733 2732 -1.02372 0.0369897 -0.00948243 1 0 1 1 0 0 +EDGE2 2734 2733 -1.01351 0.0115825 -0.0250794 1 0 1 1 0 0 +EDGE2 2735 2734 -1.02795 -0.0974423 0.00306546 1 0 1 1 0 0 +EDGE2 2736 2735 -1.04254 -0.0387815 -1.60415 1 0 1 1 0 0 +EDGE2 2737 2736 -0.955835 0.0478092 -0.0231995 1 0 1 1 0 0 +EDGE2 2738 2737 -0.998124 0.131098 -0.0156421 1 0 1 1 0 0 +EDGE2 2739 2720 1.00913 -0.0256403 -3.11599 1 0 1 1 0 0 +EDGE2 2739 2738 -1.0729 -0.0348149 0.0338077 1 0 1 1 0 0 +EDGE2 2740 2719 1.00895 0.00186842 -3.13479 1 0 1 1 0 0 +EDGE2 2740 2721 0.0696791 0.963427 1.56039 1 0 1 1 0 0 +EDGE2 2740 2720 0.0583487 -0.0263048 -3.15262 1 0 1 1 0 0 +EDGE2 2740 2739 -1.03994 0.0704365 -0.014424 1 0 1 1 0 0 +EDGE2 2741 2720 -1.05111 0.0382398 -1.56774 1 0 1 1 0 0 +EDGE2 2741 2740 -0.981905 -0.0439605 1.58966 1 0 1 1 0 0 +EDGE2 2742 2741 -1.01596 0.0301616 0.000798523 1 0 1 1 0 0 +EDGE2 2743 2742 -1.00934 0.0337007 0.00848568 1 0 1 1 0 0 +EDGE2 2744 2705 0.964707 -0.0422003 -3.15219 1 0 1 1 0 0 +EDGE2 2744 2743 -0.986041 0.0125357 0.0122473 1 0 1 1 0 0 +EDGE2 2745 2704 1.00773 -0.0169923 -3.15411 1 0 1 1 0 0 +EDGE2 2745 2706 0.0681619 1.10905 1.57421 1 0 1 1 0 0 +EDGE2 2745 2705 0.0792355 -0.00419365 -3.13115 1 0 1 1 0 0 +EDGE2 2745 2744 -0.990239 -0.116083 0.053199 1 0 1 1 0 0 +EDGE2 2746 2705 -1.05906 0.00761669 -1.55307 1 0 1 1 0 0 +EDGE2 2746 2745 -0.976471 -0.00692215 1.55202 1 0 1 1 0 0 +EDGE2 2747 2746 -0.942849 -0.0178964 -0.0369644 1 0 1 1 0 0 +EDGE2 2748 2747 -1.03299 0.00342216 0.0143387 1 0 1 1 0 0 +EDGE2 2749 2748 -1.04981 -0.0255224 -0.00818716 1 0 1 1 0 0 +EDGE2 2750 2749 -0.922282 -0.0195458 0.0230433 1 0 1 1 0 0 +EDGE2 2751 2750 -1.01638 -0.00495422 -1.54693 1 0 1 1 0 0 +EDGE2 2752 2751 -1.06504 -0.00387503 0.0350136 1 0 1 1 0 0 +EDGE2 2753 2752 -0.937601 0.00147884 -0.0155493 1 0 1 1 0 0 +EDGE2 2754 2753 -1.04113 0.00776299 0.00734027 1 0 1 1 0 0 +EDGE2 2755 2754 -0.9494 -0.0504206 0.00150026 1 0 1 1 0 0 +EDGE2 2756 2755 -1.03675 -0.0636242 -1.56006 1 0 1 1 0 0 +EDGE2 2757 2756 -1.01603 0.0289621 -0.0341599 1 0 1 1 0 0 +EDGE2 2758 2757 -1.01949 -0.0633417 0.0156001 1 0 1 1 0 0 +EDGE2 2759 2620 0.924734 0.0349746 -3.15371 1 0 1 1 0 0 +EDGE2 2759 2680 0.993998 0.0027753 -3.15388 1 0 1 1 0 0 +EDGE2 2759 2700 1.00374 0.0330089 -3.15354 1 0 1 1 0 0 +EDGE2 2759 2758 -1.09883 0.158225 0.0290958 1 0 1 1 0 0 +EDGE2 2760 2699 0.999435 0.0266757 -3.11685 1 0 1 1 0 0 +EDGE2 2760 2619 0.972667 -0.0211199 -3.13075 1 0 1 1 0 0 +EDGE2 2760 2679 0.984862 -0.0332529 -3.18107 1 0 1 1 0 0 +EDGE2 2760 2681 0.00174912 -0.936577 -1.56616 1 0 1 1 0 0 +EDGE2 2760 2621 0.0421695 -1.00173 -1.58547 1 0 1 1 0 0 +EDGE2 2760 2620 -0.0965614 -0.0978197 -3.14845 1 0 1 1 0 0 +EDGE2 2760 2680 -0.0436768 0.0347412 -3.12913 1 0 1 1 0 0 +EDGE2 2760 2700 -0.0214001 -0.0107476 -3.18063 1 0 1 1 0 0 +EDGE2 2760 2701 0.0528361 0.96627 1.58752 1 0 1 1 0 0 +EDGE2 2760 2759 -1.03784 -0.0518021 -0.0175968 1 0 1 1 0 0 +EDGE2 2761 2760 -1.00865 -0.0657816 1.5746 1 0 1 1 0 0 +EDGE2 2761 2622 0.936222 0.0385996 0.00383371 1 0 1 1 0 0 +EDGE2 2761 2682 0.97265 -0.0203137 0.0272969 1 0 1 1 0 0 +EDGE2 2761 2681 -0.064424 -0.0182682 -0.0393652 1 0 1 1 0 0 +EDGE2 2761 2621 -0.0694129 -0.0153819 -0.0269416 1 0 1 1 0 0 +EDGE2 2761 2620 -0.988511 0.00279875 -1.60694 1 0 1 1 0 0 +EDGE2 2761 2680 -1.06715 0.0175233 -1.54487 1 0 1 1 0 0 +EDGE2 2761 2700 -0.94768 -0.00623384 -1.53318 1 0 1 1 0 0 +EDGE2 2762 2622 0.0699461 0.0434758 -0.017829 1 0 1 1 0 0 +EDGE2 2762 2683 0.976991 0.00779727 -0.00564171 1 0 1 1 0 0 +EDGE2 2762 2623 1.05592 0.0540559 -0.0244164 1 0 1 1 0 0 +EDGE2 2762 2682 0.0160058 -0.0192002 0.0368934 1 0 1 1 0 0 +EDGE2 2762 2681 -0.990831 -0.0658016 -0.0036922 1 0 1 1 0 0 +EDGE2 2762 2761 -0.934861 0.0322316 -0.0314069 1 0 1 1 0 0 +EDGE2 2762 2621 -1.01448 0.0269524 -0.0107464 1 0 1 1 0 0 +EDGE2 2763 2624 0.983482 -0.031569 -0.0172698 1 0 1 1 0 0 +EDGE2 2763 2684 1.03571 0.0380066 -0.0116703 1 0 1 1 0 0 +EDGE2 2763 2622 -1.11885 0.0700036 -0.026253 1 0 1 1 0 0 +EDGE2 2763 2683 -0.0302024 -0.0309294 0.0115896 1 0 1 1 0 0 +EDGE2 2763 2623 -0.0318913 0.0432476 0.0158204 1 0 1 1 0 0 +EDGE2 2763 2682 -0.979836 0.114825 0.00908489 1 0 1 1 0 0 +EDGE2 2763 2762 -1.04739 0.0302374 0.019277 1 0 1 1 0 0 +EDGE2 2764 2624 -0.0726615 -0.0128805 0.00657688 1 0 1 1 0 0 +EDGE2 2764 2685 0.975855 -0.0623898 -0.00642513 1 0 1 1 0 0 +EDGE2 2764 2625 1.01472 0.00848066 0.00266836 1 0 1 1 0 0 +EDGE2 2764 2684 -0.0431222 0.0232584 -0.00210504 1 0 1 1 0 0 +EDGE2 2764 2683 -0.986129 0.0407643 0.0089783 1 0 1 1 0 0 +EDGE2 2764 2763 -0.960193 -0.0523693 0.0122716 1 0 1 1 0 0 +EDGE2 2764 2623 -1.01073 -0.0326173 0.0258925 1 0 1 1 0 0 +EDGE2 2765 2686 -0.0439944 1.01134 1.58183 1 0 1 1 0 0 +EDGE2 2765 2626 0.0465596 0.968805 1.55974 1 0 1 1 0 0 +EDGE2 2765 2624 -1.06132 0.0382559 0.0116962 1 0 1 1 0 0 +EDGE2 2765 2685 0.0754581 -0.0264211 0.0196246 1 0 1 1 0 0 +EDGE2 2765 2764 -1.04298 0.0460073 -0.00612511 1 0 1 1 0 0 +EDGE2 2765 2625 0.0424909 -0.0423905 -0.0337196 1 0 1 1 0 0 +EDGE2 2765 2684 -0.993504 0.0349715 -0.0273842 1 0 1 1 0 0 +EDGE2 2766 2687 1.0266 -0.0837533 0.017655 1 0 1 1 0 0 +EDGE2 2766 2627 1.09141 0.0126062 0.0149671 1 0 1 1 0 0 +EDGE2 2766 2686 -0.0593934 -0.0422868 0.0218365 1 0 1 1 0 0 +EDGE2 2766 2626 -0.0570195 0.0708805 -0.00921697 1 0 1 1 0 0 +EDGE2 2766 2685 -1.03312 0.0795882 -1.60348 1 0 1 1 0 0 +EDGE2 2766 2765 -1.03061 -0.0586105 -1.61402 1 0 1 1 0 0 +EDGE2 2766 2625 -1.0882 0.0282495 -1.56615 1 0 1 1 0 0 +EDGE2 2767 2766 -0.953019 -0.0361217 0.0227164 1 0 1 1 0 0 +EDGE2 2767 2687 -0.0163683 0.0412532 -0.0184866 1 0 1 1 0 0 +EDGE2 2767 2688 1.00315 0.00142085 -0.0150642 1 0 1 1 0 0 +EDGE2 2767 2628 1.00407 0.0312945 0.00603081 1 0 1 1 0 0 +EDGE2 2767 2627 -0.0909219 0.0171606 -0.0198435 1 0 1 1 0 0 +EDGE2 2767 2686 -1.03057 0.0757276 -0.0128237 1 0 1 1 0 0 +EDGE2 2767 2626 -1.00961 0.0768232 -0.00245614 1 0 1 1 0 0 +EDGE2 2768 2689 0.977123 -0.0633366 -0.0178694 1 0 1 1 0 0 +EDGE2 2768 2687 -1.10041 0.032241 -0.0024185 1 0 1 1 0 0 +EDGE2 2768 2688 -0.0134136 0.000961403 -0.00371784 1 0 1 1 0 0 +EDGE2 2768 2629 0.993731 -0.029619 -0.0149451 1 0 1 1 0 0 +EDGE2 2768 2628 0.113497 0.0177521 0.0120974 1 0 1 1 0 0 +EDGE2 2768 2767 -1.05627 0.015976 -0.0199812 1 0 1 1 0 0 +EDGE2 2768 2627 -0.984703 -0.00334289 0.0173627 1 0 1 1 0 0 +EDGE2 2769 2689 0.0575293 0.0360173 -0.0153764 1 0 1 1 0 0 +EDGE2 2769 2690 1.05346 -0.0364805 -0.026439 1 0 1 1 0 0 +EDGE2 2769 2510 1.08486 0.0589534 -3.139 1 0 1 1 0 0 +EDGE2 2769 2630 0.983728 0.0300409 -0.018886 1 0 1 1 0 0 +EDGE2 2769 2650 1.10986 0.000282326 -3.14173 1 0 1 1 0 0 +EDGE2 2769 2670 1.0586 -0.0145057 -3.1124 1 0 1 1 0 0 +EDGE2 2769 2610 1.0069 -0.0885331 -3.14522 1 0 1 1 0 0 +EDGE2 2769 2688 -1.03161 0.00371712 0.00425186 1 0 1 1 0 0 +EDGE2 2769 2629 0.00359893 -0.0150402 0.00721516 1 0 1 1 0 0 +EDGE2 2769 2768 -0.921 0.0225861 0.0043197 1 0 1 1 0 0 +EDGE2 2769 2628 -0.973211 -0.0253734 -0.027304 1 0 1 1 0 0 +EDGE2 2770 2609 1.04109 0.0075693 -3.11924 1 0 1 1 0 0 +EDGE2 2770 2649 0.966333 -0.00657336 -3.14396 1 0 1 1 0 0 +EDGE2 2770 2669 0.999194 -0.0495427 -3.15606 1 0 1 1 0 0 +EDGE2 2770 2509 0.956077 -0.00694635 -3.1467 1 0 1 1 0 0 +EDGE2 2770 2689 -0.974526 0.050334 -0.0311042 1 0 1 1 0 0 +EDGE2 2770 2631 -0.0824455 -0.918884 -1.57786 1 0 1 1 0 0 +EDGE2 2770 2651 0.0459109 -0.955838 -1.54659 1 0 1 1 0 0 +EDGE2 2770 2690 -0.0716227 0.00355872 0.0191858 1 0 1 1 0 0 +EDGE2 2770 2511 -0.00446184 -0.968819 -1.61175 1 0 1 1 0 0 +EDGE2 2770 2510 0.0242325 0.0792222 -3.13378 1 0 1 1 0 0 +EDGE2 2770 2630 -0.0307035 0.0248839 0.0223953 1 0 1 1 0 0 +EDGE2 2770 2650 0.0297579 0.038615 -3.136 1 0 1 1 0 0 +EDGE2 2770 2670 -0.00284658 -0.0275438 -3.10069 1 0 1 1 0 0 +EDGE2 2770 2610 0.0150806 0.0524678 -3.13717 1 0 1 1 0 0 +EDGE2 2770 2769 -0.93477 0.108181 -0.000881741 1 0 1 1 0 0 +EDGE2 2770 2629 -0.999039 0.0532526 0.0019942 1 0 1 1 0 0 +EDGE2 2770 2671 0.0301207 0.970574 1.57459 1 0 1 1 0 0 +EDGE2 2770 2691 -0.0725076 0.946128 1.59114 1 0 1 1 0 0 +EDGE2 2770 2611 0.0892828 0.92287 1.51259 1 0 1 1 0 0 +EDGE2 2771 2690 -0.992696 0.0177515 -1.59007 1 0 1 1 0 0 +EDGE2 2771 2770 -0.978674 -0.0155193 -1.6048 1 0 1 1 0 0 +EDGE2 2771 2510 -1.0409 0.0385529 1.58175 1 0 1 1 0 0 +EDGE2 2771 2630 -0.995339 0.00556947 -1.57249 1 0 1 1 0 0 +EDGE2 2771 2650 -0.960024 -0.00500457 1.5559 1 0 1 1 0 0 +EDGE2 2771 2670 -1.0215 -0.0454807 1.56058 1 0 1 1 0 0 +EDGE2 2771 2610 -0.965695 -0.0474068 1.53903 1 0 1 1 0 0 +EDGE2 2771 2692 1.00011 -0.0132656 -0.000367904 1 0 1 1 0 0 +EDGE2 2771 2671 0.0656326 -0.0801424 -6.33583e-05 1 0 1 1 0 0 +EDGE2 2771 2691 0.00574884 0.0271202 -0.0521299 1 0 1 1 0 0 +EDGE2 2771 2611 0.00870345 0.020376 -0.0187223 1 0 1 1 0 0 +EDGE2 2771 2612 1.06752 -0.0763488 0.0050325 1 0 1 1 0 0 +EDGE2 2771 2672 0.910095 0.0549098 -0.0196555 1 0 1 1 0 0 +EDGE2 2772 2692 0.0118513 0.0352835 0.00635329 1 0 1 1 0 0 +EDGE2 2772 2671 -1.0436 0.0209401 0.0295532 1 0 1 1 0 0 +EDGE2 2772 2771 -0.986025 -0.0174028 0.00487706 1 0 1 1 0 0 +EDGE2 2772 2691 -1.01941 0.00627972 -0.020341 1 0 1 1 0 0 +EDGE2 2772 2611 -1.0168 -0.0713094 0.00181664 1 0 1 1 0 0 +EDGE2 2772 2612 -0.0678395 0.0639647 0.00814849 1 0 1 1 0 0 +EDGE2 2772 2672 0.0276143 -0.0119188 0.0390237 1 0 1 1 0 0 +EDGE2 2772 2613 1.0597 -0.08307 0.0145123 1 0 1 1 0 0 +EDGE2 2772 2673 1.02194 0.00595382 -0.0175251 1 0 1 1 0 0 +EDGE2 2772 2693 1.00212 -0.0208964 0.0115043 1 0 1 1 0 0 +EDGE2 2773 2692 -0.985719 0.0719659 0.0252444 1 0 1 1 0 0 +EDGE2 2773 2772 -0.967313 -0.110331 -0.00644386 1 0 1 1 0 0 +EDGE2 2773 2612 -1.01823 0.0205951 0.0329743 1 0 1 1 0 0 +EDGE2 2773 2672 -1.0296 0.00948671 -0.0197795 1 0 1 1 0 0 +EDGE2 2773 2613 -0.0188636 0.0441202 0.0326859 1 0 1 1 0 0 +EDGE2 2773 2673 0.0678064 -0.0171847 -0.0130705 1 0 1 1 0 0 +EDGE2 2773 2693 0.0310414 0.0908835 0.00473786 1 0 1 1 0 0 +EDGE2 2773 2674 0.906754 0.0528519 -0.00411969 1 0 1 1 0 0 +EDGE2 2773 2694 1.02843 -0.083429 0.00688741 1 0 1 1 0 0 +EDGE2 2773 2614 1.01382 -0.0022046 -0.0141644 1 0 1 1 0 0 +EDGE2 2774 2773 -1.01179 -0.00235084 -0.0170807 1 0 1 1 0 0 +EDGE2 2774 2613 -0.984209 0.00377656 -0.00600736 1 0 1 1 0 0 +EDGE2 2774 2673 -0.935561 -0.0397016 0.00168 1 0 1 1 0 0 +EDGE2 2774 2693 -1.04317 0.0603541 0.0125987 1 0 1 1 0 0 +EDGE2 2774 2674 0.00199567 -0.0559145 -0.0146383 1 0 1 1 0 0 +EDGE2 2774 2694 -0.0357612 0.0901308 0.00240026 1 0 1 1 0 0 +EDGE2 2774 2614 0.107193 0.043028 0.0044494 1 0 1 1 0 0 +EDGE2 2774 2615 1.03967 -0.00383509 -0.0270093 1 0 1 1 0 0 +EDGE2 2774 2675 0.992029 0.0581579 -0.00988133 1 0 1 1 0 0 +EDGE2 2774 2695 0.962476 -0.0445221 0.018041 1 0 1 1 0 0 +EDGE2 2775 2674 -1.07438 0.0430592 -0.00282978 1 0 1 1 0 0 +EDGE2 2775 2694 -1.05679 -0.0294919 0.0121604 1 0 1 1 0 0 +EDGE2 2775 2774 -1.0223 -0.0478751 0.0394831 1 0 1 1 0 0 +EDGE2 2775 2614 -0.973512 -0.0372927 0.00473448 1 0 1 1 0 0 +EDGE2 2775 2615 0.0221231 -0.0206125 -0.000274821 1 0 1 1 0 0 +EDGE2 2775 2675 -0.0251663 0.0952801 -0.00900028 1 0 1 1 0 0 +EDGE2 2775 2695 0.0111251 -0.0195403 -0.029762 1 0 1 1 0 0 +EDGE2 2775 2676 -0.0168239 0.977122 1.5808 1 0 1 1 0 0 +EDGE2 2775 2696 -0.00334073 1.00458 1.54355 1 0 1 1 0 0 +EDGE2 2775 2616 0.0358895 1.03313 1.56329 1 0 1 1 0 0 +EDGE2 2776 2775 -0.959607 -0.0149197 -1.532 1 0 1 1 0 0 +EDGE2 2776 2615 -0.916893 -0.00427664 -1.569 1 0 1 1 0 0 +EDGE2 2776 2675 -1.02277 0.00582534 -1.58691 1 0 1 1 0 0 +EDGE2 2776 2695 -1.02049 -0.0175 -1.57563 1 0 1 1 0 0 +EDGE2 2776 2677 0.979612 0.0378394 0.0150747 1 0 1 1 0 0 +EDGE2 2776 2697 1.07184 0.00490785 0.0165575 1 0 1 1 0 0 +EDGE2 2776 2676 0.0455628 0.0115243 0.0226692 1 0 1 1 0 0 +EDGE2 2776 2696 0.0353961 -0.00841567 0.00115833 1 0 1 1 0 0 +EDGE2 2776 2616 0.00416153 -0.00406299 -0.0390447 1 0 1 1 0 0 +EDGE2 2776 2617 1.04204 0.0168396 0.0155758 1 0 1 1 0 0 +EDGE2 2777 2677 0.0836123 0.0141255 0.0349771 1 0 1 1 0 0 +EDGE2 2777 2697 -0.0266644 0.040891 0.00226225 1 0 1 1 0 0 +EDGE2 2777 2676 -1.03266 -0.0172852 0.00803429 1 0 1 1 0 0 +EDGE2 2777 2776 -1.01334 -0.0690135 0.00762021 1 0 1 1 0 0 +EDGE2 2777 2696 -0.966292 -0.127233 0.0311971 1 0 1 1 0 0 +EDGE2 2777 2616 -0.939648 -0.0266413 0.0146247 1 0 1 1 0 0 +EDGE2 2777 2698 0.984458 -0.0821199 -0.00277543 1 0 1 1 0 0 +EDGE2 2777 2617 -0.0525035 0.0437848 -0.0118963 1 0 1 1 0 0 +EDGE2 2777 2618 1.10134 0.0716491 -0.0280724 1 0 1 1 0 0 +EDGE2 2777 2678 1.06611 0.0751508 -0.0163455 1 0 1 1 0 0 +EDGE2 2778 2677 -0.943509 0.0197842 0.0129341 1 0 1 1 0 0 +EDGE2 2778 2697 -0.986759 0.0491927 -0.0312605 1 0 1 1 0 0 +EDGE2 2778 2777 -1.00665 -0.0452124 0.015047 1 0 1 1 0 0 +EDGE2 2778 2698 0.0370112 0.0740454 0.0403353 1 0 1 1 0 0 +EDGE2 2778 2617 -0.985855 0.00698641 0.00674448 1 0 1 1 0 0 +EDGE2 2778 2618 -0.00876737 0.0531245 0.000543002 1 0 1 1 0 0 +EDGE2 2778 2678 -0.0499773 -0.0758558 0.0199289 1 0 1 1 0 0 +EDGE2 2778 2699 0.955582 -0.0244498 0.0399518 1 0 1 1 0 0 +EDGE2 2778 2619 1.14152 0.0528825 0.023032 1 0 1 1 0 0 +EDGE2 2778 2679 0.917975 0.0386386 0.00881878 1 0 1 1 0 0 +EDGE2 2779 2698 -1.04123 -0.000966037 0.0321333 1 0 1 1 0 0 +EDGE2 2779 2778 -0.926429 -0.0322808 0.00592622 1 0 1 1 0 0 +EDGE2 2779 2618 -1.05059 -0.00318182 -0.0213636 1 0 1 1 0 0 +EDGE2 2779 2678 -1.03047 -0.017249 -0.0117622 1 0 1 1 0 0 +EDGE2 2779 2699 0.0132155 -0.0857881 0.0293141 1 0 1 1 0 0 +EDGE2 2779 2619 -0.0187599 0.0268334 0.0136895 1 0 1 1 0 0 +EDGE2 2779 2679 0.0941598 -0.0451991 0.0098214 1 0 1 1 0 0 +EDGE2 2779 2760 1.00141 0.0436151 -3.1478 1 0 1 1 0 0 +EDGE2 2779 2620 1.01522 0.0471292 -0.00322323 1 0 1 1 0 0 +EDGE2 2779 2680 1.02131 0.0539217 0.0410505 1 0 1 1 0 0 +EDGE2 2779 2700 1.02282 -0.01015 0.0124414 1 0 1 1 0 0 +EDGE2 2780 2699 -1.07018 -0.0428142 0.00626611 1 0 1 1 0 0 +EDGE2 2780 2779 -0.972385 -0.0042682 0.00438588 1 0 1 1 0 0 +EDGE2 2780 2619 -1.03383 -0.0266284 -0.00635099 1 0 1 1 0 0 +EDGE2 2780 2679 -0.946413 -0.00844737 0.00455789 1 0 1 1 0 0 +EDGE2 2780 2760 -0.00514068 -0.0874457 -3.13097 1 0 1 1 0 0 +EDGE2 2780 2681 0.0405025 0.973235 1.55214 1 0 1 1 0 0 +EDGE2 2780 2761 -0.0819405 0.933524 1.57359 1 0 1 1 0 0 +EDGE2 2780 2621 -0.00525033 1.02171 1.57913 1 0 1 1 0 0 +EDGE2 2780 2620 0.0352951 0.0144349 -0.0108208 1 0 1 1 0 0 +EDGE2 2780 2680 -0.0279009 0.00612596 0.00887163 1 0 1 1 0 0 +EDGE2 2780 2700 0.0370882 -0.0530349 -0.0123401 1 0 1 1 0 0 +EDGE2 2780 2701 -0.0924002 -0.994034 -1.55869 1 0 1 1 0 0 +EDGE2 2780 2759 1.10731 0.0191173 -3.15837 1 0 1 1 0 0 +EDGE2 2781 2760 -1.00804 0.065637 1.5581 1 0 1 1 0 0 +EDGE2 2781 2622 1.00906 0.067913 -0.0244973 1 0 1 1 0 0 +EDGE2 2781 2682 1.0811 -0.0145634 0.0300157 1 0 1 1 0 0 +EDGE2 2781 2762 1.02828 -0.032431 -0.0120137 1 0 1 1 0 0 +EDGE2 2781 2681 0.155667 -0.0600234 -0.00548826 1 0 1 1 0 0 +EDGE2 2781 2761 -0.0303404 0.0117754 0.0111794 1 0 1 1 0 0 +EDGE2 2781 2621 0.0422816 0.0743083 -0.0109318 1 0 1 1 0 0 +EDGE2 2781 2780 -0.931999 -0.0966273 -1.54877 1 0 1 1 0 0 +EDGE2 2781 2620 -0.985408 -0.0340744 -1.55046 1 0 1 1 0 0 +EDGE2 2781 2680 -0.951331 -0.0844175 -1.52897 1 0 1 1 0 0 +EDGE2 2781 2700 -0.969579 0.0464696 -1.58465 1 0 1 1 0 0 +EDGE2 2782 2622 -0.0108373 0.121697 0.00551295 1 0 1 1 0 0 +EDGE2 2782 2683 0.933331 -0.0900296 -0.0133519 1 0 1 1 0 0 +EDGE2 2782 2763 1.02372 -0.0634117 -0.00804635 1 0 1 1 0 0 +EDGE2 2782 2623 1.04256 0.016219 -0.0102004 1 0 1 1 0 0 +EDGE2 2782 2682 0.0368953 -0.081592 0.00872592 1 0 1 1 0 0 +EDGE2 2782 2762 0.00987631 -0.0801009 -0.0211465 1 0 1 1 0 0 +EDGE2 2782 2681 -1.08338 0.0693478 0.00636751 1 0 1 1 0 0 +EDGE2 2782 2761 -0.976435 0.0406731 0.0134363 1 0 1 1 0 0 +EDGE2 2782 2781 -1.04445 -0.00700831 0.0101278 1 0 1 1 0 0 +EDGE2 2782 2621 -0.940837 0.0437257 0.0163924 1 0 1 1 0 0 +EDGE2 2783 2624 1.01024 0.0154103 -0.0099898 1 0 1 1 0 0 +EDGE2 2783 2764 0.994292 -0.0174306 0.0085121 1 0 1 1 0 0 +EDGE2 2783 2684 1.06158 -0.011016 -0.0424622 1 0 1 1 0 0 +EDGE2 2783 2622 -1.00073 0.000709779 0.00960719 1 0 1 1 0 0 +EDGE2 2783 2782 -1.09874 -0.103479 0.00632777 1 0 1 1 0 0 +EDGE2 2783 2683 0.0692092 -0.0554429 0.0226959 1 0 1 1 0 0 +EDGE2 2783 2763 0.0905682 -0.090494 -0.0198023 1 0 1 1 0 0 +EDGE2 2783 2623 0.0781707 -0.000294263 -0.00162125 1 0 1 1 0 0 +EDGE2 2783 2682 -1.0805 -0.0844236 0.00761277 1 0 1 1 0 0 +EDGE2 2783 2762 -1.00536 0.0614883 0.010534 1 0 1 1 0 0 +EDGE2 2784 2624 -0.0137265 -0.0585436 0.0168181 1 0 1 1 0 0 +EDGE2 2784 2685 1.0449 0.0438801 -0.00118306 1 0 1 1 0 0 +EDGE2 2784 2765 0.919127 -0.0622488 -0.0108948 1 0 1 1 0 0 +EDGE2 2784 2764 -0.0309938 -0.0359423 -0.0182171 1 0 1 1 0 0 +EDGE2 2784 2625 0.976219 -0.045659 -0.01083 1 0 1 1 0 0 +EDGE2 2784 2684 0.080752 0.039291 -0.0177445 1 0 1 1 0 0 +EDGE2 2784 2683 -1.09362 -0.02704 0.0132305 1 0 1 1 0 0 +EDGE2 2784 2763 -1.06726 -0.0419958 -0.0208246 1 0 1 1 0 0 +EDGE2 2784 2783 -0.973193 -0.0204756 0.00490548 1 0 1 1 0 0 +EDGE2 2784 2623 -0.982309 -0.0306663 -0.0278804 1 0 1 1 0 0 +EDGE2 2785 2766 0.00632757 0.994383 1.58847 1 0 1 1 0 0 +EDGE2 2785 2686 0.00601071 1.02267 1.55012 1 0 1 1 0 0 +EDGE2 2785 2626 0.0332988 1.07406 1.60904 1 0 1 1 0 0 +EDGE2 2785 2624 -1.00494 0.0253788 0.0162339 1 0 1 1 0 0 +EDGE2 2785 2685 -0.00597987 -0.0213758 0.00488144 1 0 1 1 0 0 +EDGE2 2785 2765 0.0587286 0.0487912 0.0202267 1 0 1 1 0 0 +EDGE2 2785 2764 -1.0717 0.0312648 0.0153787 1 0 1 1 0 0 +EDGE2 2785 2784 -1.0949 0.00835269 0.0244189 1 0 1 1 0 0 +EDGE2 2785 2625 -0.00582269 0.0264668 -0.0171071 1 0 1 1 0 0 +EDGE2 2785 2684 -1.12575 -0.00902482 0.021988 1 0 1 1 0 0 +EDGE2 2786 2685 -0.959487 -0.022635 1.56332 1 0 1 1 0 0 +EDGE2 2786 2785 -1.05936 -0.0123426 1.5773 1 0 1 1 0 0 +EDGE2 2786 2765 -1.0189 0.0448283 1.59436 1 0 1 1 0 0 +EDGE2 2786 2625 -1.0606 0.0366784 1.63206 1 0 1 1 0 0 +EDGE2 2787 2786 -1.12522 0.00614432 0.0180492 1 0 1 1 0 0 +EDGE2 2788 2787 -0.956858 -0.00139296 0.0113545 1 0 1 1 0 0 +EDGE2 2789 2788 -0.954828 -0.00239187 -0.0371977 1 0 1 1 0 0 +EDGE2 2790 2789 -0.989956 0.00105379 0.0318355 1 0 1 1 0 0 +EDGE2 2791 2790 -0.968242 -0.0106604 -1.59395 1 0 1 1 0 0 +EDGE2 2792 2791 -1.04234 -0.0486955 -0.015036 1 0 1 1 0 0 +EDGE2 2793 2792 -0.988311 0.0159998 0.0223343 1 0 1 1 0 0 +EDGE2 2794 2793 -0.922503 0.0519646 -0.00802815 1 0 1 1 0 0 +EDGE2 2795 2794 -1.03584 0.0240813 -0.0070478 1 0 1 1 0 0 +EDGE2 2796 2795 -1.0106 0.0245268 -1.55976 1 0 1 1 0 0 +EDGE2 2797 2796 -1.06482 0.100631 0.0150834 1 0 1 1 0 0 +EDGE2 2798 2797 -0.986145 -0.0526439 0.00333641 1 0 1 1 0 0 +EDGE2 2799 1300 1.01937 0.0888692 -3.12441 1 0 1 1 0 0 +EDGE2 2799 1280 1.02958 -0.00958589 -3.13285 1 0 1 1 0 0 +EDGE2 2799 2798 -0.987343 -0.0530342 0.00631952 1 0 1 1 0 0 +EDGE2 2800 1299 1.01773 0.00644509 -3.15003 1 0 1 1 0 0 +EDGE2 2800 1279 1.00877 -0.0110648 -3.13616 1 0 1 1 0 0 +EDGE2 2800 1281 0.0308786 -1.0732 -1.55248 1 0 1 1 0 0 +EDGE2 2800 1301 -0.0772275 -0.961141 -1.56672 1 0 1 1 0 0 +EDGE2 2800 1300 0.046408 0.0833824 -3.12667 1 0 1 1 0 0 +EDGE2 2800 1280 0.020816 -0.0195207 -3.13615 1 0 1 1 0 0 +EDGE2 2800 2799 -1.00874 -0.0176709 0.0498901 1 0 1 1 0 0 +EDGE2 2801 1300 -1.01957 0.0415979 1.56354 1 0 1 1 0 0 +EDGE2 2801 2800 -1.0587 -0.0248494 -1.57251 1 0 1 1 0 0 +EDGE2 2801 1280 -0.986852 0.0100019 1.55337 1 0 1 1 0 0 +EDGE2 2802 2801 -1.02216 -0.0148139 0.00487422 1 0 1 1 0 0 +EDGE2 2803 2802 -1.0573 -0.0280037 0.0143688 1 0 1 1 0 0 +EDGE2 2804 2803 -0.938685 -0.0897579 -0.0164507 1 0 1 1 0 0 +EDGE2 2804 2685 0.967047 0.000565975 -3.1454 1 0 1 1 0 0 +EDGE2 2804 2785 1.13158 0.0666739 -3.12575 1 0 1 1 0 0 +EDGE2 2804 2765 0.975345 -0.0706265 -3.11351 1 0 1 1 0 0 +EDGE2 2804 2625 0.976595 -0.0285376 -3.16532 1 0 1 1 0 0 +EDGE2 2805 2766 0.00222328 -0.980926 -1.58957 1 0 1 1 0 0 +EDGE2 2805 2686 -0.0364808 -1.01659 -1.62738 1 0 1 1 0 0 +EDGE2 2805 2626 -0.0361344 -0.98515 -1.57163 1 0 1 1 0 0 +EDGE2 2805 2786 -0.0449063 1.04021 1.5547 1 0 1 1 0 0 +EDGE2 2805 2624 0.945744 -0.0642792 -3.14328 1 0 1 1 0 0 +EDGE2 2805 2804 -1.07357 -0.0461174 0.00230119 1 0 1 1 0 0 +EDGE2 2805 2685 0.0165195 -0.0476786 -3.10808 1 0 1 1 0 0 +EDGE2 2805 2785 0.11331 -0.0327447 -3.12829 1 0 1 1 0 0 +EDGE2 2805 2765 0.041322 0.0844448 -3.14818 1 0 1 1 0 0 +EDGE2 2805 2764 0.968496 -0.0296012 -3.17683 1 0 1 1 0 0 +EDGE2 2805 2784 0.964547 0.00824185 -3.11937 1 0 1 1 0 0 +EDGE2 2805 2625 0.0800642 0.0140577 -3.11906 1 0 1 1 0 0 +EDGE2 2805 2684 0.943392 0.0826337 -3.1317 1 0 1 1 0 0 +EDGE2 2806 2786 0.0194916 0.0712921 0.0116862 1 0 1 1 0 0 +EDGE2 2806 2685 -0.978178 -0.0116521 1.55897 1 0 1 1 0 0 +EDGE2 2806 2785 -0.942608 -0.048311 1.5734 1 0 1 1 0 0 +EDGE2 2806 2805 -1.02536 -0.00811961 -1.56799 1 0 1 1 0 0 +EDGE2 2806 2765 -0.985086 0.0157636 1.57368 1 0 1 1 0 0 +EDGE2 2806 2625 -0.973726 0.00206936 1.57922 1 0 1 1 0 0 +EDGE2 2806 2787 0.983643 -0.0379146 -0.00778975 1 0 1 1 0 0 +EDGE2 2807 2786 -0.973588 -0.0527561 0.00596523 1 0 1 1 0 0 +EDGE2 2807 2806 -0.986798 0.0297112 -0.00190994 1 0 1 1 0 0 +EDGE2 2807 2787 0.0265231 0.0827423 0.0182103 1 0 1 1 0 0 +EDGE2 2807 2788 0.988534 0.0100854 -0.0350496 1 0 1 1 0 0 +EDGE2 2808 2787 -1.1126 0.0756324 -0.0150744 1 0 1 1 0 0 +EDGE2 2808 2807 -1.04692 -0.0116845 -0.0230515 1 0 1 1 0 0 +EDGE2 2808 2789 1.03813 0.0681878 0.0419626 1 0 1 1 0 0 +EDGE2 2808 2788 0.00241646 -0.0320125 -0.0370006 1 0 1 1 0 0 +EDGE2 2809 2789 -0.0765336 -0.0525879 0.0153853 1 0 1 1 0 0 +EDGE2 2809 2788 -0.972629 -0.0189847 0.0264176 1 0 1 1 0 0 +EDGE2 2809 2808 -1.0346 -0.0115015 0.0236543 1 0 1 1 0 0 +EDGE2 2809 2790 1.0603 -0.0129159 0.00846642 1 0 1 1 0 0 +EDGE2 2810 2791 0.0156396 1.05536 1.55591 1 0 1 1 0 0 +EDGE2 2810 2789 -1.13149 -0.0171619 -0.00625448 1 0 1 1 0 0 +EDGE2 2810 2809 -0.98304 0.0146401 0.038234 1 0 1 1 0 0 +EDGE2 2810 2790 -0.010991 0.0518996 -0.00752835 1 0 1 1 0 0 +EDGE2 2811 2792 1.03252 -0.0967123 -0.00179046 1 0 1 1 0 0 +EDGE2 2811 2791 0.00226996 0.0869498 -0.0298119 1 0 1 1 0 0 +EDGE2 2811 2810 -0.971688 -0.0105587 -1.56076 1 0 1 1 0 0 +EDGE2 2811 2790 -1.0472 0.0653343 -1.57856 1 0 1 1 0 0 +EDGE2 2812 2793 1.00969 0.0564231 -0.00378223 1 0 1 1 0 0 +EDGE2 2812 2811 -1.03038 -0.0603715 -0.0146096 1 0 1 1 0 0 +EDGE2 2812 2792 -0.0993264 -0.0378051 0.00286155 1 0 1 1 0 0 +EDGE2 2812 2791 -1.03122 0.0159486 0.0157118 1 0 1 1 0 0 +EDGE2 2813 2793 0.0791147 0.035225 -0.0275201 1 0 1 1 0 0 +EDGE2 2813 2794 0.987925 0.00960883 -0.00340542 1 0 1 1 0 0 +EDGE2 2813 2812 -1.0902 0.0301205 0.00398556 1 0 1 1 0 0 +EDGE2 2813 2792 -1.02381 0.0645016 0.00124802 1 0 1 1 0 0 +EDGE2 2814 2793 -1.03116 -0.0332932 0.00714 1 0 1 1 0 0 +EDGE2 2814 2795 1.0251 0.00548812 -0.0211815 1 0 1 1 0 0 +EDGE2 2814 2794 0.0407127 -0.0111813 -0.0060932 1 0 1 1 0 0 +EDGE2 2814 2813 -0.999387 0.0447306 0.00761249 1 0 1 1 0 0 +EDGE2 2815 2796 -0.0140443 1.04744 1.56584 1 0 1 1 0 0 +EDGE2 2815 2814 -0.996667 -0.0704463 -0.00868204 1 0 1 1 0 0 +EDGE2 2815 2795 0.0254222 0.022764 0.0111237 1 0 1 1 0 0 +EDGE2 2815 2794 -1.03368 0.00873382 0.00249583 1 0 1 1 0 0 +EDGE2 2816 2797 0.971451 -0.0470062 0.0115602 1 0 1 1 0 0 +EDGE2 2816 2796 -0.0106332 0.0353605 0.0386631 1 0 1 1 0 0 +EDGE2 2816 2815 -0.95173 -0.0575409 -1.61161 1 0 1 1 0 0 +EDGE2 2816 2795 -1.02192 -0.025512 -1.51622 1 0 1 1 0 0 +EDGE2 2817 2798 0.980542 -0.00164891 0.0129909 1 0 1 1 0 0 +EDGE2 2817 2797 0.0235859 -0.064347 -0.00544989 1 0 1 1 0 0 +EDGE2 2817 2816 -1.15896 0.0408811 0.0111608 1 0 1 1 0 0 +EDGE2 2817 2796 -0.977838 -0.00465296 0.0305079 1 0 1 1 0 0 +EDGE2 2818 2799 0.970759 -0.02878 -0.0213812 1 0 1 1 0 0 +EDGE2 2818 2798 -0.0408233 0.0103008 -0.0223091 1 0 1 1 0 0 +EDGE2 2818 2817 -1.10167 -0.00414552 -0.0210568 1 0 1 1 0 0 +EDGE2 2818 2797 -1.0151 -0.0119805 0.0535751 1 0 1 1 0 0 +EDGE2 2819 1300 1.024 0.0588483 -3.14704 1 0 1 1 0 0 +EDGE2 2819 2800 0.967862 -0.00669551 -0.013687 1 0 1 1 0 0 +EDGE2 2819 1280 0.970291 -0.0498846 -3.1676 1 0 1 1 0 0 +EDGE2 2819 2799 -0.0868461 0.0369316 -0.00517844 1 0 1 1 0 0 +EDGE2 2819 2818 -1.00895 0.0194585 0.036865 1 0 1 1 0 0 +EDGE2 2819 2798 -1.02728 -0.0445335 0.0100199 1 0 1 1 0 0 +EDGE2 2820 1299 1.02285 -0.0133663 -3.16651 1 0 1 1 0 0 +EDGE2 2820 1279 0.932935 0.066972 -3.12761 1 0 1 1 0 0 +EDGE2 2820 1281 -0.00420482 -1.03246 -1.57747 1 0 1 1 0 0 +EDGE2 2820 1301 0.0350679 -0.971199 -1.58816 1 0 1 1 0 0 +EDGE2 2820 1300 0.0280645 -0.0268533 -3.13172 1 0 1 1 0 0 +EDGE2 2820 2800 0.0290801 0.0776731 -0.00409963 1 0 1 1 0 0 +EDGE2 2820 1280 -0.035593 -0.0554762 -3.12539 1 0 1 1 0 0 +EDGE2 2820 2801 -0.053271 1.0652 1.56683 1 0 1 1 0 0 +EDGE2 2820 2819 -1.02786 0.0290009 -0.0100626 1 0 1 1 0 0 +EDGE2 2820 2799 -1.05034 -0.0182355 -0.00947452 1 0 1 1 0 0 +EDGE2 2821 1302 1.06897 0.0486729 -0.0286083 1 0 1 1 0 0 +EDGE2 2821 1282 0.990185 0.018248 0.00266276 1 0 1 1 0 0 +EDGE2 2821 1281 0.0343587 0.112719 0.0203033 1 0 1 1 0 0 +EDGE2 2821 1301 0.0493573 0.0586668 -0.0136044 1 0 1 1 0 0 +EDGE2 2821 1300 -1.06811 0.0181912 -1.57417 1 0 1 1 0 0 +EDGE2 2821 2800 -0.963888 0.0395664 1.57997 1 0 1 1 0 0 +EDGE2 2821 2820 -0.992015 -0.0559641 1.56409 1 0 1 1 0 0 +EDGE2 2821 1280 -0.966633 -0.0136068 -1.6027 1 0 1 1 0 0 +EDGE2 2822 1303 0.979896 -0.0287452 0.0246216 1 0 1 1 0 0 +EDGE2 2822 2821 -1.02171 0.0626856 -0.00551702 1 0 1 1 0 0 +EDGE2 2822 1302 -0.0219489 0.0174325 0.0165887 1 0 1 1 0 0 +EDGE2 2822 1283 0.965355 0.00480025 -0.0166345 1 0 1 1 0 0 +EDGE2 2822 1282 -0.0294409 -0.00355655 0.0119332 1 0 1 1 0 0 +EDGE2 2822 1281 -0.931507 -0.0107374 0.0117279 1 0 1 1 0 0 +EDGE2 2822 1301 -1.08669 0.0560521 -0.00589422 1 0 1 1 0 0 +EDGE2 2823 1303 -0.0298163 0.0169877 -0.0021899 1 0 1 1 0 0 +EDGE2 2823 1304 0.945635 0.00429239 0.000281203 1 0 1 1 0 0 +EDGE2 2823 1284 0.964942 -0.0472179 0.00809678 1 0 1 1 0 0 +EDGE2 2823 1302 -1.04651 0.00713451 -0.0410283 1 0 1 1 0 0 +EDGE2 2823 2822 -0.995238 -0.0604567 -0.0102938 1 0 1 1 0 0 +EDGE2 2823 1283 0.0303871 -0.0919001 0.00160703 1 0 1 1 0 0 +EDGE2 2823 1282 -1.00454 0.00539776 0.0317914 1 0 1 1 0 0 +EDGE2 2824 1303 -0.960673 -0.0814094 0.0148675 1 0 1 1 0 0 +EDGE2 2824 1304 0.0122505 -0.00503596 -0.019187 1 0 1 1 0 0 +EDGE2 2824 1625 1.07036 0.00310323 -3.14083 1 0 1 1 0 0 +EDGE2 2824 1285 1.06716 0.120517 -0.0259876 1 0 1 1 0 0 +EDGE2 2824 1305 1.06294 0.10326 0.0169756 1 0 1 1 0 0 +EDGE2 2824 1605 1.079 -0.0196549 -3.12504 1 0 1 1 0 0 +EDGE2 2824 1284 0.0300886 -0.0646803 0.00563235 1 0 1 1 0 0 +EDGE2 2824 2823 -1.01213 0.010337 8.97944e-05 1 0 1 1 0 0 +EDGE2 2824 1283 -1.00159 0.0377164 0.0486856 1 0 1 1 0 0 +EDGE2 2825 1624 0.973715 0.0617558 -3.17864 1 0 1 1 0 0 +EDGE2 2825 1604 1.00121 0.054293 -3.18183 1 0 1 1 0 0 +EDGE2 2825 1304 -1.0442 0.0177861 -0.0286937 1 0 1 1 0 0 +EDGE2 2825 1625 0.0644052 0.0882818 -3.09707 1 0 1 1 0 0 +EDGE2 2825 1286 0.0452224 0.980209 1.59762 1 0 1 1 0 0 +EDGE2 2825 1285 0.115766 0.0963471 -0.00699495 1 0 1 1 0 0 +EDGE2 2825 1305 0.00280643 0.0585314 -0.0395007 1 0 1 1 0 0 +EDGE2 2825 1605 0.0718736 0.0633394 -3.13829 1 0 1 1 0 0 +EDGE2 2825 2824 -0.977665 -0.0259509 -0.035091 1 0 1 1 0 0 +EDGE2 2825 1284 -0.998912 0.0483703 -0.0150611 1 0 1 1 0 0 +EDGE2 2825 1606 -0.00725248 -1.0637 -1.59751 1 0 1 1 0 0 +EDGE2 2825 1626 -0.0113564 -1.01644 -1.58465 1 0 1 1 0 0 +EDGE2 2825 1306 -0.101164 -1.04267 -1.57502 1 0 1 1 0 0 +EDGE2 2826 1287 1.0287 -0.0362655 -0.02093 1 0 1 1 0 0 +EDGE2 2826 1625 -0.998147 0.00980382 1.60974 1 0 1 1 0 0 +EDGE2 2826 1286 0.06016 -0.0607284 0.00691999 1 0 1 1 0 0 +EDGE2 2826 2825 -1.10769 -0.0454288 -1.52642 1 0 1 1 0 0 +EDGE2 2826 1285 -1.01424 0.0591398 -1.59453 1 0 1 1 0 0 +EDGE2 2826 1305 -0.958194 -0.0210184 -1.56624 1 0 1 1 0 0 +EDGE2 2826 1605 -1.08049 0.0347551 1.5714 1 0 1 1 0 0 +EDGE2 2827 1288 0.976255 -0.0165633 0.00215707 1 0 1 1 0 0 +EDGE2 2827 1287 -0.028419 -0.0672955 -0.00211978 1 0 1 1 0 0 +EDGE2 2827 1286 -0.94706 -0.000376264 -0.0111466 1 0 1 1 0 0 +EDGE2 2827 2826 -0.950439 -0.0875314 -0.0184378 1 0 1 1 0 0 +EDGE2 2828 1289 0.961271 -0.0385672 0.0176248 1 0 1 1 0 0 +EDGE2 2828 1288 0.00986845 0.0375562 -0.00297155 1 0 1 1 0 0 +EDGE2 2828 1287 -1.02825 -0.0255258 0.0273557 1 0 1 1 0 0 +EDGE2 2828 2827 -0.900606 0.0085421 -0.00777254 1 0 1 1 0 0 +EDGE2 2829 1590 0.99848 -0.0395181 -3.14443 1 0 1 1 0 0 +EDGE2 2829 2310 1.13606 0.0339345 -3.15224 1 0 1 1 0 0 +EDGE2 2829 2390 1.02522 -0.00165136 -3.13221 1 0 1 1 0 0 +EDGE2 2829 1850 0.977412 0.0360079 -3.11709 1 0 1 1 0 0 +EDGE2 2829 1270 0.967871 0.0170951 -3.14456 1 0 1 1 0 0 +EDGE2 2829 1290 0.864771 -0.0345203 0.00616769 1 0 1 1 0 0 +EDGE2 2829 1570 1.04825 -0.00145551 -3.12699 1 0 1 1 0 0 +EDGE2 2829 1289 0.0356631 0.053873 0.0224921 1 0 1 1 0 0 +EDGE2 2829 1288 -0.996728 0.00518812 -0.00197289 1 0 1 1 0 0 +EDGE2 2829 2828 -0.929105 -0.0354533 -8.80073e-05 1 0 1 1 0 0 +EDGE2 2830 1851 -0.0192535 -0.955396 -1.55478 1 0 1 1 0 0 +EDGE2 2830 2391 0.0490733 -1.02499 -1.56953 1 0 1 1 0 0 +EDGE2 2830 2311 -0.0841351 -1.00986 -1.53583 1 0 1 1 0 0 +EDGE2 2830 1571 0.00550474 -0.913355 -1.60922 1 0 1 1 0 0 +EDGE2 2830 1591 -0.00300042 -1.01311 -1.54026 1 0 1 1 0 0 +EDGE2 2830 1849 1.00588 0.0326601 -3.14504 1 0 1 1 0 0 +EDGE2 2830 2389 0.938724 -0.0613432 -3.16122 1 0 1 1 0 0 +EDGE2 2830 2309 0.932591 0.0512336 -3.15339 1 0 1 1 0 0 +EDGE2 2830 1569 1.03928 -0.0136395 -3.15038 1 0 1 1 0 0 +EDGE2 2830 1589 0.99321 -0.0830474 -3.17728 1 0 1 1 0 0 +EDGE2 2830 1269 1.02709 0.0877105 -3.12796 1 0 1 1 0 0 +EDGE2 2830 1291 0.0151374 0.988245 1.57241 1 0 1 1 0 0 +EDGE2 2830 1590 0.00785334 0.048134 -3.15102 1 0 1 1 0 0 +EDGE2 2830 2310 -0.0607431 0.0419293 -3.1158 1 0 1 1 0 0 +EDGE2 2830 2390 0.00737705 0.027478 -3.12051 1 0 1 1 0 0 +EDGE2 2830 1850 0.0287235 -0.0413362 -3.09909 1 0 1 1 0 0 +EDGE2 2830 1270 0.0679497 0.0445319 -3.14764 1 0 1 1 0 0 +EDGE2 2830 1290 -0.0037485 0.00863564 -0.0229895 1 0 1 1 0 0 +EDGE2 2830 1570 0.0156291 0.0104503 -3.14563 1 0 1 1 0 0 +EDGE2 2830 1271 -0.018484 0.946911 1.56473 1 0 1 1 0 0 +EDGE2 2830 2829 -1.04999 -0.0906491 -0.00363806 1 0 1 1 0 0 +EDGE2 2830 1289 -1.0338 0.0726339 -0.0104857 1 0 1 1 0 0 +EDGE2 2831 1291 0.114652 -0.0444557 -0.0230273 1 0 1 1 0 0 +EDGE2 2831 1590 -1.0079 -0.0459891 1.60087 1 0 1 1 0 0 +EDGE2 2831 2310 -0.989912 -0.0670097 1.55864 1 0 1 1 0 0 +EDGE2 2831 2390 -1.02568 -0.0276863 1.57834 1 0 1 1 0 0 +EDGE2 2831 2830 -1.00561 -0.105427 -1.58713 1 0 1 1 0 0 +EDGE2 2831 1850 -0.988322 -0.01665 1.49831 1 0 1 1 0 0 +EDGE2 2831 1270 -1.01949 0.0204079 1.53235 1 0 1 1 0 0 +EDGE2 2831 1290 -1.015 -0.0235834 -1.60493 1 0 1 1 0 0 +EDGE2 2831 1570 -1.03625 0.00208714 1.58609 1 0 1 1 0 0 +EDGE2 2831 1292 1.01518 0.0638538 0.00928326 1 0 1 1 0 0 +EDGE2 2831 1271 0.0546575 0.0370674 0.0216593 1 0 1 1 0 0 +EDGE2 2831 1272 0.966953 0.0140845 -0.00184085 1 0 1 1 0 0 +EDGE2 2832 1273 0.994689 0.0299127 -0.0293707 1 0 1 1 0 0 +EDGE2 2832 1291 -0.923234 0.034291 -0.0108837 1 0 1 1 0 0 +EDGE2 2832 2831 -1.0424 0.0297918 -0.0232226 1 0 1 1 0 0 +EDGE2 2832 1292 -0.0319078 0.0134707 0.0371073 1 0 1 1 0 0 +EDGE2 2832 1271 -1.03995 0.0289763 0.0055259 1 0 1 1 0 0 +EDGE2 2832 1272 0.0200891 0.0480849 -0.00186849 1 0 1 1 0 0 +EDGE2 2832 1293 1.06139 -0.0187284 -0.0229717 1 0 1 1 0 0 +EDGE2 2833 1273 -0.0291082 -0.00625823 0.00924995 1 0 1 1 0 0 +EDGE2 2833 1292 -1.01824 0.0493811 -0.0150702 1 0 1 1 0 0 +EDGE2 2833 2832 -1.01641 -0.00863825 0.0182257 1 0 1 1 0 0 +EDGE2 2833 1272 -0.961438 -0.0649219 -0.0154153 1 0 1 1 0 0 +EDGE2 2833 1293 -0.0520062 -0.0604512 -0.0243416 1 0 1 1 0 0 +EDGE2 2833 1274 1.00052 -0.0480384 -0.0268794 1 0 1 1 0 0 +EDGE2 2833 1294 1.01754 -0.0396792 0.0113658 1 0 1 1 0 0 +EDGE2 2834 1273 -1.0301 0.0420643 -0.0184181 1 0 1 1 0 0 +EDGE2 2834 2833 -1.01285 0.0187695 -0.0137207 1 0 1 1 0 0 +EDGE2 2834 1293 -0.974766 -0.00130584 -0.0147503 1 0 1 1 0 0 +EDGE2 2834 2655 1.01163 0.00762259 -3.16523 1 0 1 1 0 0 +EDGE2 2834 1274 -0.0023453 -0.00517344 0.0181371 1 0 1 1 0 0 +EDGE2 2834 1294 -0.0710241 -0.00977861 -0.000726 1 0 1 1 0 0 +EDGE2 2834 1295 1.11726 0.0638031 -0.0083076 1 0 1 1 0 0 +EDGE2 2834 2515 1.00737 0.00476765 -3.1639 1 0 1 1 0 0 +EDGE2 2834 2635 0.953507 -0.0346866 -3.11035 1 0 1 1 0 0 +EDGE2 2834 1275 0.976295 -0.017286 -0.0175734 1 0 1 1 0 0 +EDGE2 2835 2656 0.0383384 -1.04624 -1.57142 1 0 1 1 0 0 +EDGE2 2835 2516 -0.112825 -1.01407 -1.55578 1 0 1 1 0 0 +EDGE2 2835 2636 0.0197902 -0.97886 -1.58752 1 0 1 1 0 0 +EDGE2 2835 2654 0.977091 0.0140951 -3.14062 1 0 1 1 0 0 +EDGE2 2835 2655 0.0242939 -0.0399521 -3.16032 1 0 1 1 0 0 +EDGE2 2835 1274 -1.03204 0.0345293 -0.0412247 1 0 1 1 0 0 +EDGE2 2835 1294 -1.04056 0.0371442 -0.0018641 1 0 1 1 0 0 +EDGE2 2835 2834 -1.01016 0.0381033 -0.00292897 1 0 1 1 0 0 +EDGE2 2835 1295 -0.00823118 0.0468445 0.0247078 1 0 1 1 0 0 +EDGE2 2835 2515 0.0686395 -0.00485516 -3.13775 1 0 1 1 0 0 +EDGE2 2835 2635 -0.0863847 0.053988 -3.1293 1 0 1 1 0 0 +EDGE2 2835 1275 -0.0304143 -0.00972633 0.02163 1 0 1 1 0 0 +EDGE2 2835 2514 0.925525 0.0477246 -3.0899 1 0 1 1 0 0 +EDGE2 2835 2634 1.06364 -0.041801 -3.1684 1 0 1 1 0 0 +EDGE2 2835 1296 0.0325471 0.946343 1.54837 1 0 1 1 0 0 +EDGE2 2835 1276 0.0223148 0.930417 1.56163 1 0 1 1 0 0 +EDGE2 2836 2655 -0.953284 -0.0118867 1.59745 1 0 1 1 0 0 +EDGE2 2836 2835 -1.00663 0.0713141 -1.57462 1 0 1 1 0 0 +EDGE2 2836 1295 -0.934528 -0.0069394 -1.56081 1 0 1 1 0 0 +EDGE2 2836 2515 -1.03681 -0.0408289 1.57128 1 0 1 1 0 0 +EDGE2 2836 2635 -0.98938 0.0191158 1.5564 1 0 1 1 0 0 +EDGE2 2836 1275 -0.98626 -0.0660922 -1.55465 1 0 1 1 0 0 +EDGE2 2836 1296 0.0559013 -0.0480257 0.0089802 1 0 1 1 0 0 +EDGE2 2836 1276 -0.0648737 0.0951238 0.00132109 1 0 1 1 0 0 +EDGE2 2836 1277 0.979547 -0.00876985 -0.0119669 1 0 1 1 0 0 +EDGE2 2836 1297 0.990429 0.0809015 -0.0249183 1 0 1 1 0 0 +EDGE2 2837 1296 -0.966632 0.0547931 0.0146748 1 0 1 1 0 0 +EDGE2 2837 2836 -0.994408 -0.0919898 0.00574937 1 0 1 1 0 0 +EDGE2 2837 1276 -0.967717 -0.0413782 -0.00941105 1 0 1 1 0 0 +EDGE2 2837 1278 0.991007 -0.134422 -0.00967933 1 0 1 1 0 0 +EDGE2 2837 1277 0.00211539 0.107747 0.0394956 1 0 1 1 0 0 +EDGE2 2837 1297 -0.0273097 0.0111661 -0.00362304 1 0 1 1 0 0 +EDGE2 2837 1298 0.855795 0.0446835 -0.000446626 1 0 1 1 0 0 +EDGE2 2838 1278 0.0184174 -0.0178362 -0.00381503 1 0 1 1 0 0 +EDGE2 2838 1277 -0.989267 0.0262251 0.00821645 1 0 1 1 0 0 +EDGE2 2838 2837 -1.05366 -0.0227475 6.69512e-05 1 0 1 1 0 0 +EDGE2 2838 1297 -1.04809 0.00530672 0.0208826 1 0 1 1 0 0 +EDGE2 2838 1298 0.064953 0.103286 -0.0129071 1 0 1 1 0 0 +EDGE2 2838 1299 1.01429 -0.0347714 0.00912789 1 0 1 1 0 0 +EDGE2 2838 1279 1.05469 0.0231602 0.0167407 1 0 1 1 0 0 +EDGE2 2839 1278 -1.06063 -0.00317138 0.00287025 1 0 1 1 0 0 +EDGE2 2839 2838 -1.06826 0.0360315 0.0160661 1 0 1 1 0 0 +EDGE2 2839 1298 -0.995452 0.037306 -0.00026678 1 0 1 1 0 0 +EDGE2 2839 1299 0.04831 -0.00847778 -0.00438891 1 0 1 1 0 0 +EDGE2 2839 1279 -0.0154656 -0.0063663 -0.0044628 1 0 1 1 0 0 +EDGE2 2839 1300 1.00212 -0.0137403 -0.0052965 1 0 1 1 0 0 +EDGE2 2839 2800 0.989002 -0.0310054 -3.10568 1 0 1 1 0 0 +EDGE2 2839 2820 0.989699 -0.0586248 -3.12846 1 0 1 1 0 0 +EDGE2 2839 1280 1.04809 0.0510639 -0.0348916 1 0 1 1 0 0 +EDGE2 2840 1299 -1.0073 -0.104079 0.0308407 1 0 1 1 0 0 +EDGE2 2840 2839 -0.965247 -0.0762147 -0.0545231 1 0 1 1 0 0 +EDGE2 2840 1279 -1.02674 0.0357673 -0.0155811 1 0 1 1 0 0 +EDGE2 2840 2821 0.0772224 0.981956 1.5526 1 0 1 1 0 0 +EDGE2 2840 1281 -0.0709159 0.970105 1.56466 1 0 1 1 0 0 +EDGE2 2840 1301 -0.00335393 0.962779 1.5832 1 0 1 1 0 0 +EDGE2 2840 1300 0.0518565 0.0216668 -0.0103209 1 0 1 1 0 0 +EDGE2 2840 2800 -0.105333 0.00866279 -3.16492 1 0 1 1 0 0 +EDGE2 2840 2820 0.0196938 0.0136321 -3.15215 1 0 1 1 0 0 +EDGE2 2840 1280 -0.0667894 0.0754592 -0.0140731 1 0 1 1 0 0 +EDGE2 2840 2801 -0.0531247 -0.954562 -1.60182 1 0 1 1 0 0 +EDGE2 2840 2819 1.01031 0.0163605 -3.09839 1 0 1 1 0 0 +EDGE2 2840 2799 1.01476 -0.056085 -3.15323 1 0 1 1 0 0 +EDGE2 2841 2840 -0.883524 -0.0173759 1.57473 1 0 1 1 0 0 +EDGE2 2841 1300 -1.03801 0.153595 1.58929 1 0 1 1 0 0 +EDGE2 2841 2800 -1.00115 -0.0693325 -1.5793 1 0 1 1 0 0 +EDGE2 2841 2820 -0.968588 -0.0421228 -1.56908 1 0 1 1 0 0 +EDGE2 2841 1280 -0.917558 0.0489813 1.58846 1 0 1 1 0 0 +EDGE2 2841 2801 -0.000534455 -0.0225782 0.0102175 1 0 1 1 0 0 +EDGE2 2841 2802 1.03623 -0.0900481 0.0254544 1 0 1 1 0 0 +EDGE2 2842 2801 -0.982325 -0.0503502 -0.00219833 1 0 1 1 0 0 +EDGE2 2842 2841 -1.09214 0.0241641 -0.0306792 1 0 1 1 0 0 +EDGE2 2842 2802 0.0158192 0.0165444 0.00893468 1 0 1 1 0 0 +EDGE2 2842 2803 1.01829 0.00390547 0.00425413 1 0 1 1 0 0 +EDGE2 2843 2802 -1.0288 -0.0304982 0.0195658 1 0 1 1 0 0 +EDGE2 2843 2842 -1.02753 0.0329787 -0.0234083 1 0 1 1 0 0 +EDGE2 2843 2803 -0.0700358 0.00186748 0.0020847 1 0 1 1 0 0 +EDGE2 2843 2804 1.1106 -0.068213 -0.0282589 1 0 1 1 0 0 +EDGE2 2844 2843 -0.956792 -0.115708 0.00594907 1 0 1 1 0 0 +EDGE2 2844 2803 -0.867869 0.0649713 0.0132664 1 0 1 1 0 0 +EDGE2 2844 2804 0.0371666 -0.0240386 -0.00583084 1 0 1 1 0 0 +EDGE2 2844 2685 1.04533 -0.0172587 -3.13878 1 0 1 1 0 0 +EDGE2 2844 2785 0.997262 0.037117 -3.12939 1 0 1 1 0 0 +EDGE2 2844 2805 1.01141 0.0538475 -0.0181419 1 0 1 1 0 0 +EDGE2 2844 2765 1.02171 0.0179583 -3.14927 1 0 1 1 0 0 +EDGE2 2844 2625 0.942086 0.0261664 -3.13082 1 0 1 1 0 0 +EDGE2 2845 2766 0.0382481 -0.970337 -1.57212 1 0 1 1 0 0 +EDGE2 2845 2686 0.0556964 -1.04119 -1.55145 1 0 1 1 0 0 +EDGE2 2845 2626 0.0549265 -0.930828 -1.61656 1 0 1 1 0 0 +EDGE2 2845 2786 -0.0272409 1.02209 1.56823 1 0 1 1 0 0 +EDGE2 2845 2624 1.03224 0.0401061 -3.13569 1 0 1 1 0 0 +EDGE2 2845 2804 -1.05485 0.00176681 0.0156305 1 0 1 1 0 0 +EDGE2 2845 2844 -1.0162 -0.109557 0.00962174 1 0 1 1 0 0 +EDGE2 2845 2685 -0.0703299 -0.0818503 -3.1638 1 0 1 1 0 0 +EDGE2 2845 2785 0.00478719 -0.0179465 -3.16114 1 0 1 1 0 0 +EDGE2 2845 2805 0.0830927 0.100152 -0.00518948 1 0 1 1 0 0 +EDGE2 2845 2765 0.0262282 0.0099625 -3.13506 1 0 1 1 0 0 +EDGE2 2845 2764 0.950922 -0.020865 -3.11569 1 0 1 1 0 0 +EDGE2 2845 2784 0.932995 0.0340866 -3.19248 1 0 1 1 0 0 +EDGE2 2845 2625 -0.0120895 0.049963 -3.11964 1 0 1 1 0 0 +EDGE2 2845 2684 1.01839 0.087205 -3.12619 1 0 1 1 0 0 +EDGE2 2845 2806 -0.00847292 0.948723 1.57759 1 0 1 1 0 0 +EDGE2 2846 2766 -0.0960842 -0.0429074 0.00652834 1 0 1 1 0 0 +EDGE2 2846 2687 0.993802 -0.0966122 -0.00504184 1 0 1 1 0 0 +EDGE2 2846 2767 1.00289 0.0560324 0.000476655 1 0 1 1 0 0 +EDGE2 2846 2627 0.995222 0.00378301 0.0163011 1 0 1 1 0 0 +EDGE2 2846 2686 0.0465703 0.0597643 -0.00336766 1 0 1 1 0 0 +EDGE2 2846 2626 -0.00573585 0.0423401 -0.0211436 1 0 1 1 0 0 +EDGE2 2846 2685 -1.02021 -0.02006 -1.55587 1 0 1 1 0 0 +EDGE2 2846 2785 -0.996404 0.0447512 -1.58681 1 0 1 1 0 0 +EDGE2 2846 2805 -1.01436 -0.117092 1.58173 1 0 1 1 0 0 +EDGE2 2846 2845 -1.01945 0.0323423 1.57521 1 0 1 1 0 0 +EDGE2 2846 2765 -0.952443 0.0255662 -1.5642 1 0 1 1 0 0 +EDGE2 2846 2625 -0.973944 -0.0360233 -1.61173 1 0 1 1 0 0 +EDGE2 2847 2766 -0.988621 -0.0528349 -0.0068931 1 0 1 1 0 0 +EDGE2 2847 2687 0.0533852 0.0535859 -0.0283645 1 0 1 1 0 0 +EDGE2 2847 2688 0.932913 0.00515003 -0.0218576 1 0 1 1 0 0 +EDGE2 2847 2768 1.02161 0.0467785 -0.0122768 1 0 1 1 0 0 +EDGE2 2847 2628 1.0374 -0.00450042 -0.0117363 1 0 1 1 0 0 +EDGE2 2847 2767 0.0976207 0.0228053 -0.00709075 1 0 1 1 0 0 +EDGE2 2847 2627 0.039148 0.0478945 0.015361 1 0 1 1 0 0 +EDGE2 2847 2846 -1.07051 0.033344 -0.00551012 1 0 1 1 0 0 +EDGE2 2847 2686 -1.014 -0.0221337 -0.000457709 1 0 1 1 0 0 +EDGE2 2847 2626 -0.994678 -0.0129918 -0.0135898 1 0 1 1 0 0 +EDGE2 2848 2689 0.970903 -0.0201117 -0.0337381 1 0 1 1 0 0 +EDGE2 2848 2769 0.95698 0.0212125 -0.0332056 1 0 1 1 0 0 +EDGE2 2848 2687 -1.05035 0.0141227 -0.00628359 1 0 1 1 0 0 +EDGE2 2848 2688 -0.0252069 -0.0664204 -0.0344163 1 0 1 1 0 0 +EDGE2 2848 2629 0.961668 -0.0154774 -0.00392402 1 0 1 1 0 0 +EDGE2 2848 2768 0.113265 0.0168052 0.0297695 1 0 1 1 0 0 +EDGE2 2848 2847 -0.995566 0.0357688 -0.0148838 1 0 1 1 0 0 +EDGE2 2848 2628 0.0463208 -0.0617772 -0.038797 1 0 1 1 0 0 +EDGE2 2848 2767 -1.07338 0.0345872 0.00697613 1 0 1 1 0 0 +EDGE2 2848 2627 -1.03432 -0.0370354 -0.00264011 1 0 1 1 0 0 +EDGE2 2849 2689 0.0134264 -0.0316779 0.0173882 1 0 1 1 0 0 +EDGE2 2849 2690 1.06027 -0.0155597 0.00155137 1 0 1 1 0 0 +EDGE2 2849 2770 0.999564 -0.080865 -0.0303907 1 0 1 1 0 0 +EDGE2 2849 2510 0.919969 0.0532817 -3.12182 1 0 1 1 0 0 +EDGE2 2849 2630 1.09543 0.00883367 -0.00557015 1 0 1 1 0 0 +EDGE2 2849 2650 1.02402 -0.0175468 -3.14056 1 0 1 1 0 0 +EDGE2 2849 2670 0.96039 0.092913 -3.13416 1 0 1 1 0 0 +EDGE2 2849 2610 0.895534 -0.00988631 -3.12867 1 0 1 1 0 0 +EDGE2 2849 2769 0.0408942 0.00370776 -0.0270954 1 0 1 1 0 0 +EDGE2 2849 2688 -0.905231 -0.0203801 0.00941922 1 0 1 1 0 0 +EDGE2 2849 2848 -0.962611 0.000962739 -0.0143794 1 0 1 1 0 0 +EDGE2 2849 2629 -0.0240166 0.00114038 -0.0103978 1 0 1 1 0 0 +EDGE2 2849 2768 -1.01217 0.123301 0.00419422 1 0 1 1 0 0 +EDGE2 2849 2628 -1.00583 -0.0410726 -0.016045 1 0 1 1 0 0 +EDGE2 2850 2609 1.08897 -0.0672213 -3.13529 1 0 1 1 0 0 +EDGE2 2850 2649 0.956465 -0.00622276 -3.15007 1 0 1 1 0 0 +EDGE2 2850 2669 0.959387 -0.0883403 -3.14142 1 0 1 1 0 0 +EDGE2 2850 2509 1.04788 -0.0361465 -3.15468 1 0 1 1 0 0 +EDGE2 2850 2689 -1.02277 -0.0233844 -0.016657 1 0 1 1 0 0 +EDGE2 2850 2631 -0.0161368 -0.952407 -1.54408 1 0 1 1 0 0 +EDGE2 2850 2651 0.0231123 -0.883732 -1.55742 1 0 1 1 0 0 +EDGE2 2850 2690 0.108133 -0.0057512 -0.00505408 1 0 1 1 0 0 +EDGE2 2850 2511 0.0306515 -0.93281 -1.53788 1 0 1 1 0 0 +EDGE2 2850 2770 -0.0115244 0.0407992 0.00812034 1 0 1 1 0 0 +EDGE2 2850 2510 0.0382321 -0.0747184 -3.15451 1 0 1 1 0 0 +EDGE2 2850 2630 -0.108935 0.0345586 0.0305163 1 0 1 1 0 0 +EDGE2 2850 2650 0.00360889 -0.0323584 -3.1089 1 0 1 1 0 0 +EDGE2 2850 2670 -0.0291842 0.0531027 -3.10578 1 0 1 1 0 0 +EDGE2 2850 2610 -0.142689 0.093655 -3.1431 1 0 1 1 0 0 +EDGE2 2850 2849 -1.02861 0.0367764 -0.0234608 1 0 1 1 0 0 +EDGE2 2850 2769 -0.942675 0.0317648 0.00952884 1 0 1 1 0 0 +EDGE2 2850 2629 -1.02992 0.0823281 -0.00723602 1 0 1 1 0 0 +EDGE2 2850 2671 -0.00324098 0.970859 1.5605 1 0 1 1 0 0 +EDGE2 2850 2771 -0.013741 1.01511 1.5799 1 0 1 1 0 0 +EDGE2 2850 2691 0.102581 1.07773 1.57752 1 0 1 1 0 0 +EDGE2 2850 2611 0.0216389 1.12416 1.56263 1 0 1 1 0 0 +EDGE2 2851 2690 -1.04832 0.0882682 -1.56211 1 0 1 1 0 0 +EDGE2 2851 2850 -1.0385 0.0657439 -1.56966 1 0 1 1 0 0 +EDGE2 2851 2770 -1.03092 -0.0663615 -1.59067 1 0 1 1 0 0 +EDGE2 2851 2510 -1.01909 0.0536607 1.55669 1 0 1 1 0 0 +EDGE2 2851 2630 -1.01318 0.00780296 -1.54842 1 0 1 1 0 0 +EDGE2 2851 2650 -1.06076 -0.0141099 1.60915 1 0 1 1 0 0 +EDGE2 2851 2670 -1.07281 0.0536207 1.53593 1 0 1 1 0 0 +EDGE2 2851 2610 -1.02393 0.060753 1.56069 1 0 1 1 0 0 +EDGE2 2851 2692 0.978667 0.0432758 -0.00233952 1 0 1 1 0 0 +EDGE2 2851 2671 0.00443256 0.00795467 0.00418906 1 0 1 1 0 0 +EDGE2 2851 2771 0.0407678 -0.0453809 -0.0322678 1 0 1 1 0 0 +EDGE2 2851 2691 0.181013 0.0255853 0.00310176 1 0 1 1 0 0 +EDGE2 2851 2611 0.0765326 0.075096 0.0292945 1 0 1 1 0 0 +EDGE2 2851 2772 1.01706 -0.0161142 -0.000337895 1 0 1 1 0 0 +EDGE2 2851 2612 0.952006 0.0511786 -0.0181889 1 0 1 1 0 0 +EDGE2 2851 2672 0.961949 0.0473056 -0.00729855 1 0 1 1 0 0 +EDGE2 2852 2692 -0.0208105 -0.104816 -0.00239991 1 0 1 1 0 0 +EDGE2 2852 2671 -1.13992 -0.0758357 0.00115456 1 0 1 1 0 0 +EDGE2 2852 2771 -1.0271 -0.0553122 0.0149759 1 0 1 1 0 0 +EDGE2 2852 2851 -1.02363 -0.0134627 0.00122331 1 0 1 1 0 0 +EDGE2 2852 2691 -0.943005 0.0181757 0.00870401 1 0 1 1 0 0 +EDGE2 2852 2611 -1.04056 0.0529983 0.0321858 1 0 1 1 0 0 +EDGE2 2852 2772 -0.0427825 0.0823607 -0.028458 1 0 1 1 0 0 +EDGE2 2852 2773 1.05777 -0.0482256 -0.00753336 1 0 1 1 0 0 +EDGE2 2852 2612 -0.0247089 0.0173968 -0.0284019 1 0 1 1 0 0 +EDGE2 2852 2672 -0.0324758 -0.12377 0.0223847 1 0 1 1 0 0 +EDGE2 2852 2613 0.937694 0.0430537 0.0198729 1 0 1 1 0 0 +EDGE2 2852 2673 1.01495 0.00365511 -0.0444131 1 0 1 1 0 0 +EDGE2 2852 2693 1.00209 0.0496102 -0.020907 1 0 1 1 0 0 +EDGE2 2853 2692 -0.965528 -0.0342686 0.00201941 1 0 1 1 0 0 +EDGE2 2853 2852 -1.02569 0.0334289 0.0291722 1 0 1 1 0 0 +EDGE2 2853 2772 -0.978249 -0.0339512 0.0112992 1 0 1 1 0 0 +EDGE2 2853 2773 -0.0140724 -0.0709166 -0.00257551 1 0 1 1 0 0 +EDGE2 2853 2612 -0.977822 -0.0295454 -0.000755059 1 0 1 1 0 0 +EDGE2 2853 2672 -1.01514 -0.0113153 0.005522 1 0 1 1 0 0 +EDGE2 2853 2613 -0.00794919 0.078819 0.0232799 1 0 1 1 0 0 +EDGE2 2853 2673 0.0111756 -0.0126165 0.0219939 1 0 1 1 0 0 +EDGE2 2853 2693 -0.0483683 -0.0577785 0.00689589 1 0 1 1 0 0 +EDGE2 2853 2674 0.990684 -0.048474 0.0159894 1 0 1 1 0 0 +EDGE2 2853 2694 1.02926 0.0763665 -0.0156966 1 0 1 1 0 0 +EDGE2 2853 2774 1.03412 0.0620892 0.0197665 1 0 1 1 0 0 +EDGE2 2853 2614 1.01556 -0.0491274 -0.0088099 1 0 1 1 0 0 +EDGE2 2854 2773 -1.06058 0.0278339 -0.0278009 1 0 1 1 0 0 +EDGE2 2854 2853 -1.01299 -0.0215424 0.02228 1 0 1 1 0 0 +EDGE2 2854 2613 -1.00538 0.0233548 0.0178058 1 0 1 1 0 0 +EDGE2 2854 2673 -0.994186 -0.074829 0.0161518 1 0 1 1 0 0 +EDGE2 2854 2693 -1.0673 -0.0716975 0.0634562 1 0 1 1 0 0 +EDGE2 2854 2775 1.01186 -0.00527138 -0.00593613 1 0 1 1 0 0 +EDGE2 2854 2674 -0.0034599 0.0389668 0.0103244 1 0 1 1 0 0 +EDGE2 2854 2694 -0.0146282 -0.14022 0.0168913 1 0 1 1 0 0 +EDGE2 2854 2774 0.0212829 -0.0444341 -0.0314804 1 0 1 1 0 0 +EDGE2 2854 2614 -0.0573369 0.0624412 0.00214147 1 0 1 1 0 0 +EDGE2 2854 2615 1.00578 -0.0455141 -0.0197802 1 0 1 1 0 0 +EDGE2 2854 2675 0.956088 -0.0963545 -0.0133663 1 0 1 1 0 0 +EDGE2 2854 2695 0.942075 -0.00181171 -0.00215135 1 0 1 1 0 0 +EDGE2 2855 2854 -0.974316 -0.0557353 -0.0045746 1 0 1 1 0 0 +EDGE2 2855 2775 -0.0690183 0.03958 0.00205676 1 0 1 1 0 0 +EDGE2 2855 2674 -1.00045 -0.0779908 0.00862147 1 0 1 1 0 0 +EDGE2 2855 2694 -1.0122 0.0351756 -0.0331223 1 0 1 1 0 0 +EDGE2 2855 2774 -1.02335 0.0109897 0.0145203 1 0 1 1 0 0 +EDGE2 2855 2614 -1.02072 0.0886948 -0.00598838 1 0 1 1 0 0 +EDGE2 2855 2615 -0.0275592 0.0163882 -0.0149332 1 0 1 1 0 0 +EDGE2 2855 2675 -0.00680533 -0.00261736 0.00366036 1 0 1 1 0 0 +EDGE2 2855 2695 0.0157975 0.032046 -0.0122644 1 0 1 1 0 0 +EDGE2 2855 2676 0.102338 0.976403 1.55432 1 0 1 1 0 0 +EDGE2 2855 2776 0.0442303 1.10054 1.56231 1 0 1 1 0 0 +EDGE2 2855 2696 0.0336064 1.01061 1.59259 1 0 1 1 0 0 +EDGE2 2855 2616 0.0577685 0.977438 1.55289 1 0 1 1 0 0 +EDGE2 2856 2775 -0.940304 -0.00483224 -1.56574 1 0 1 1 0 0 +EDGE2 2856 2855 -0.980325 -0.102202 -1.58073 1 0 1 1 0 0 +EDGE2 2856 2615 -1.05772 -0.00905629 -1.5471 1 0 1 1 0 0 +EDGE2 2856 2675 -0.978338 -0.0413508 -1.5578 1 0 1 1 0 0 +EDGE2 2856 2695 -1.07929 -0.00083512 -1.61467 1 0 1 1 0 0 +EDGE2 2856 2677 0.94719 0.0589706 -0.00368802 1 0 1 1 0 0 +EDGE2 2856 2697 0.949767 -0.0399452 -0.00823756 1 0 1 1 0 0 +EDGE2 2856 2676 0.0689616 -0.0657475 -0.0109198 1 0 1 1 0 0 +EDGE2 2856 2776 -0.025511 -0.0813267 -0.0121718 1 0 1 1 0 0 +EDGE2 2856 2696 0.0348215 -0.0504404 -0.0287899 1 0 1 1 0 0 +EDGE2 2856 2616 0.0203588 0.0165823 -0.00106558 1 0 1 1 0 0 +EDGE2 2856 2777 1.02472 -0.0183463 0.0113603 1 0 1 1 0 0 +EDGE2 2856 2617 0.995706 -0.0361037 -0.00145885 1 0 1 1 0 0 +EDGE2 2857 2677 -0.0616078 -0.0111618 -0.0061901 1 0 1 1 0 0 +EDGE2 2857 2697 0.0295516 -0.0730637 -0.00160257 1 0 1 1 0 0 +EDGE2 2857 2676 -0.99095 -0.00216111 0.0114775 1 0 1 1 0 0 +EDGE2 2857 2776 -1.01107 0.100434 0.00240823 1 0 1 1 0 0 +EDGE2 2857 2856 -0.967947 -0.026187 -0.00691237 1 0 1 1 0 0 +EDGE2 2857 2696 -0.906155 0.0407784 -0.0321363 1 0 1 1 0 0 +EDGE2 2857 2616 -0.932381 -0.0350637 0.0248956 1 0 1 1 0 0 +EDGE2 2857 2777 -0.000602579 0.0598577 0.0240542 1 0 1 1 0 0 +EDGE2 2857 2698 1.07732 -0.0165247 -0.00925723 1 0 1 1 0 0 +EDGE2 2857 2617 0.0367135 0.0459979 -0.00494669 1 0 1 1 0 0 +EDGE2 2857 2778 1.00506 0.0609017 0.0130108 1 0 1 1 0 0 +EDGE2 2857 2618 1.08831 -0.0809479 0.00324105 1 0 1 1 0 0 +EDGE2 2857 2678 0.979126 -0.0230505 -0.0378097 1 0 1 1 0 0 +EDGE2 2858 2677 -1.02565 0.0177283 0.0146208 1 0 1 1 0 0 +EDGE2 2858 2697 -0.918026 -0.0387151 0.010234 1 0 1 1 0 0 +EDGE2 2858 2857 -0.979428 -0.0189791 -0.0265109 1 0 1 1 0 0 +EDGE2 2858 2777 -0.927839 -0.0609056 -0.0281716 1 0 1 1 0 0 +EDGE2 2858 2698 0.00157984 -0.00896417 -0.0156656 1 0 1 1 0 0 +EDGE2 2858 2617 -0.93437 0.0243983 -0.0349321 1 0 1 1 0 0 +EDGE2 2858 2778 0.0588448 -0.0246803 -0.0192464 1 0 1 1 0 0 +EDGE2 2858 2618 -0.0434905 -0.000129202 0.00189958 1 0 1 1 0 0 +EDGE2 2858 2678 -0.06741 -0.0187358 -0.00898545 1 0 1 1 0 0 +EDGE2 2858 2699 0.993915 -0.00632367 0.00924149 1 0 1 1 0 0 +EDGE2 2858 2779 0.898133 0.0257636 0.0294997 1 0 1 1 0 0 +EDGE2 2858 2619 1.0051 0.0502011 -0.0208503 1 0 1 1 0 0 +EDGE2 2858 2679 0.966971 -0.00864527 -0.0150834 1 0 1 1 0 0 +EDGE2 2859 2698 -1.10449 0.0189625 0.0311373 1 0 1 1 0 0 +EDGE2 2859 2858 -0.991526 0.0113168 -0.00148025 1 0 1 1 0 0 +EDGE2 2859 2778 -0.981408 0.0363068 0.0252301 1 0 1 1 0 0 +EDGE2 2859 2618 -0.968962 -0.0565024 0.0162074 1 0 1 1 0 0 +EDGE2 2859 2678 -1.03036 -0.0527459 -0.00790208 1 0 1 1 0 0 +EDGE2 2859 2699 -0.012382 0.00948875 0.0182323 1 0 1 1 0 0 +EDGE2 2859 2779 -0.0700353 -0.00961237 -0.0299426 1 0 1 1 0 0 +EDGE2 2859 2619 -0.0286271 -0.014247 0.0172016 1 0 1 1 0 0 +EDGE2 2859 2679 -0.0338941 0.0995336 -0.034648 1 0 1 1 0 0 +EDGE2 2859 2760 1.09423 -0.00988219 -3.14135 1 0 1 1 0 0 +EDGE2 2859 2780 1.0072 -0.0484146 -0.00715741 1 0 1 1 0 0 +EDGE2 2859 2620 0.985428 0.0364811 -0.00755678 1 0 1 1 0 0 +EDGE2 2859 2680 0.945128 -0.0576768 0.00732884 1 0 1 1 0 0 +EDGE2 2859 2700 0.943456 -0.047008 -0.00747108 1 0 1 1 0 0 +EDGE2 2860 2699 -0.984472 -0.0459373 0.00293693 1 0 1 1 0 0 +EDGE2 2860 2859 -0.956127 -0.0178825 0.0362477 1 0 1 1 0 0 +EDGE2 2860 2779 -1.05362 0.0076228 -0.0132148 1 0 1 1 0 0 +EDGE2 2860 2619 -0.974097 -0.0720224 0.0232816 1 0 1 1 0 0 +EDGE2 2860 2679 -1.07611 -0.0547478 -0.00712288 1 0 1 1 0 0 +EDGE2 2860 2760 0.0261512 -0.0149977 -3.127 1 0 1 1 0 0 +EDGE2 2860 2681 -0.0279874 1.04271 1.56114 1 0 1 1 0 0 +EDGE2 2860 2761 -0.0378586 1.03699 1.58344 1 0 1 1 0 0 +EDGE2 2860 2781 0.0303545 1.05412 1.5559 1 0 1 1 0 0 +EDGE2 2860 2621 0.0458318 0.978654 1.58014 1 0 1 1 0 0 +EDGE2 2860 2780 0.0612051 0.11773 -0.0254312 1 0 1 1 0 0 +EDGE2 2860 2620 0.0367649 -0.0988336 -0.0139865 1 0 1 1 0 0 +EDGE2 2860 2680 -0.0287902 0.0426701 -0.0122738 1 0 1 1 0 0 +EDGE2 2860 2700 -0.0210214 -0.0244042 -0.0444029 1 0 1 1 0 0 +EDGE2 2860 2701 -0.0378558 -1.01713 -1.59227 1 0 1 1 0 0 +EDGE2 2860 2759 1.03192 -0.0998704 -3.11699 1 0 1 1 0 0 +EDGE2 2861 2760 -0.936114 -0.0613924 -1.57148 1 0 1 1 0 0 +EDGE2 2861 2860 -0.989762 0.0597582 1.58362 1 0 1 1 0 0 +EDGE2 2861 2780 -0.985724 0.107592 1.58735 1 0 1 1 0 0 +EDGE2 2861 2620 -1.01722 0.0432537 1.58348 1 0 1 1 0 0 +EDGE2 2861 2680 -0.99204 0.00060075 1.55284 1 0 1 1 0 0 +EDGE2 2861 2700 -1.03724 0.0591413 1.57823 1 0 1 1 0 0 +EDGE2 2861 2701 -0.0342676 0.0131481 0.0570779 1 0 1 1 0 0 +EDGE2 2861 2702 1.01454 -0.0317382 0.0102029 1 0 1 1 0 0 +EDGE2 2862 2701 -1.05589 0.0103207 -0.0111133 1 0 1 1 0 0 +EDGE2 2862 2861 -1.0156 -0.0237322 -0.0096865 1 0 1 1 0 0 +EDGE2 2862 2702 0.0234377 0.0413731 -0.0343691 1 0 1 1 0 0 +EDGE2 2862 2703 0.928111 0.0246564 -0.012265 1 0 1 1 0 0 +EDGE2 2863 2702 -1.03495 0.0149571 0.0255662 1 0 1 1 0 0 +EDGE2 2863 2862 -0.992849 0.0216528 -0.0052363 1 0 1 1 0 0 +EDGE2 2863 2703 0.00927474 -0.0792158 -0.0129023 1 0 1 1 0 0 +EDGE2 2863 2704 1.04143 0.0191179 -0.00649178 1 0 1 1 0 0 +EDGE2 2864 2703 -0.914627 -0.0148797 -0.0132948 1 0 1 1 0 0 +EDGE2 2864 2863 -0.963561 -0.005421 0.00452554 1 0 1 1 0 0 +EDGE2 2864 2704 0.0780975 -0.0279247 -0.00409492 1 0 1 1 0 0 +EDGE2 2864 2705 1.03352 -0.0653842 -0.0337728 1 0 1 1 0 0 +EDGE2 2864 2745 1.05774 0.0498387 -3.11714 1 0 1 1 0 0 +EDGE2 2865 2704 -1.04618 0.0512708 0.00808632 1 0 1 1 0 0 +EDGE2 2865 2864 -0.949018 0.0126803 0.0102132 1 0 1 1 0 0 +EDGE2 2865 2706 -0.0151041 -1.05994 -1.56601 1 0 1 1 0 0 +EDGE2 2865 2705 0.00172662 0.10399 -0.0412264 1 0 1 1 0 0 +EDGE2 2865 2745 -0.0379109 0.0251448 -3.14453 1 0 1 1 0 0 +EDGE2 2865 2746 0.0232848 0.907885 1.58128 1 0 1 1 0 0 +EDGE2 2865 2744 1.0665 -0.017522 -3.14035 1 0 1 1 0 0 +EDGE2 2866 2705 -0.960371 0.00258309 -1.56859 1 0 1 1 0 0 +EDGE2 2866 2865 -1.0323 0.0284789 -1.5831 1 0 1 1 0 0 +EDGE2 2866 2745 -0.980983 0.0532404 1.56203 1 0 1 1 0 0 +EDGE2 2866 2746 -0.0335538 0.0677003 0.0155986 1 0 1 1 0 0 +EDGE2 2866 2747 0.99029 0.0156527 -0.0381779 1 0 1 1 0 0 +EDGE2 2867 2746 -0.966791 0.0370535 -0.0222304 1 0 1 1 0 0 +EDGE2 2867 2866 -1.03586 0.012033 -0.00985286 1 0 1 1 0 0 +EDGE2 2867 2747 0.05387 -0.033623 -0.00747539 1 0 1 1 0 0 +EDGE2 2867 2748 0.963488 -0.0257851 -0.0104843 1 0 1 1 0 0 +EDGE2 2868 2867 -1.01555 0.0259822 -0.0137194 1 0 1 1 0 0 +EDGE2 2868 2747 -1.09163 0.0304065 -0.000779454 1 0 1 1 0 0 +EDGE2 2868 2748 -0.0854731 -0.00464271 -0.0144391 1 0 1 1 0 0 +EDGE2 2868 2749 0.920401 0.0273278 -0.00941155 1 0 1 1 0 0 +EDGE2 2869 2748 -0.998916 -0.0180827 0.0354802 1 0 1 1 0 0 +EDGE2 2869 2868 -0.959297 -0.00192606 -6.47042e-05 1 0 1 1 0 0 +EDGE2 2869 2749 -0.103786 -0.0910808 0.0207683 1 0 1 1 0 0 +EDGE2 2869 2750 0.981062 0.0711565 0.00862006 1 0 1 1 0 0 +EDGE2 2870 2751 -0.0006891 0.987989 1.56831 1 0 1 1 0 0 +EDGE2 2870 2869 -1.01903 0.017964 0.0472309 1 0 1 1 0 0 +EDGE2 2870 2749 -1.08946 0.0375848 0.00296016 1 0 1 1 0 0 +EDGE2 2870 2750 -0.0754818 -0.00606549 -0.023317 1 0 1 1 0 0 +EDGE2 2871 2752 1.0204 0.00481794 -0.0217298 1 0 1 1 0 0 +EDGE2 2871 2751 0.0610854 0.0517315 -0.0151561 1 0 1 1 0 0 +EDGE2 2871 2870 -0.977736 -0.00605582 -1.56085 1 0 1 1 0 0 +EDGE2 2871 2750 -0.968725 -0.0575967 -1.57286 1 0 1 1 0 0 +EDGE2 2872 2753 0.968617 -0.0428233 0.0289539 1 0 1 1 0 0 +EDGE2 2872 2871 -0.961854 -0.0582198 0.00409925 1 0 1 1 0 0 +EDGE2 2872 2752 -0.0406489 0.00156968 0.000121841 1 0 1 1 0 0 +EDGE2 2872 2751 -1.05992 -0.0622938 -0.0148004 1 0 1 1 0 0 +EDGE2 2873 2754 0.994966 0.0558457 -0.0316725 1 0 1 1 0 0 +EDGE2 2873 2872 -1.07748 -0.0136207 -0.00147714 1 0 1 1 0 0 +EDGE2 2873 2753 -0.0199759 -0.0171446 -0.0078254 1 0 1 1 0 0 +EDGE2 2873 2752 -0.961433 -0.0277629 0.0215485 1 0 1 1 0 0 +EDGE2 2874 2754 0.0253151 0.100833 0.00525132 1 0 1 1 0 0 +EDGE2 2874 2755 0.98113 -0.0369347 0.0157993 1 0 1 1 0 0 +EDGE2 2874 2753 -0.984074 -0.0393587 0.0316713 1 0 1 1 0 0 +EDGE2 2874 2873 -1.0125 -0.0642706 0.00835442 1 0 1 1 0 0 +EDGE2 2875 2756 -0.000423179 1.02494 1.57235 1 0 1 1 0 0 +EDGE2 2875 2754 -1.03438 0.0328643 0.0232302 1 0 1 1 0 0 +EDGE2 2875 2874 -0.98532 -0.0508401 -0.00711602 1 0 1 1 0 0 +EDGE2 2875 2755 0.025825 0.0414715 0.00203656 1 0 1 1 0 0 +EDGE2 2876 2875 -1.02883 -0.053244 -1.55712 1 0 1 1 0 0 +EDGE2 2876 2757 1.06205 -0.113142 0.0589121 1 0 1 1 0 0 +EDGE2 2876 2756 -0.000837625 0.0428912 -0.0170934 1 0 1 1 0 0 +EDGE2 2876 2755 -0.998936 0.0530358 -1.58403 1 0 1 1 0 0 +EDGE2 2877 2758 1.05093 -0.0245636 0.00755492 1 0 1 1 0 0 +EDGE2 2877 2757 0.0701588 -0.0844318 -0.00890607 1 0 1 1 0 0 +EDGE2 2877 2876 -1.04135 0.00966021 0.00546092 1 0 1 1 0 0 +EDGE2 2877 2756 -0.997041 0.0229739 -0.0184975 1 0 1 1 0 0 +EDGE2 2878 2759 1.00961 0.0452524 0.0152839 1 0 1 1 0 0 +EDGE2 2878 2877 -0.92284 -0.0538243 -0.00222744 1 0 1 1 0 0 +EDGE2 2878 2758 0.0700999 -0.0134205 0.00705259 1 0 1 1 0 0 +EDGE2 2878 2757 -0.972927 0.0558556 -0.0306844 1 0 1 1 0 0 +EDGE2 2879 2760 1.05593 -0.0444066 0.0144719 1 0 1 1 0 0 +EDGE2 2879 2860 0.933812 -0.0889844 -3.12416 1 0 1 1 0 0 +EDGE2 2879 2780 1.06521 0.0184689 -3.15657 1 0 1 1 0 0 +EDGE2 2879 2620 1.06388 -0.0597642 -3.13178 1 0 1 1 0 0 +EDGE2 2879 2680 0.95044 0.00682697 -3.12334 1 0 1 1 0 0 +EDGE2 2879 2700 0.995153 0.0603573 -3.11332 1 0 1 1 0 0 +EDGE2 2879 2878 -0.946363 0.0353457 -0.00537134 1 0 1 1 0 0 +EDGE2 2879 2759 -0.0643138 -0.0334746 -0.00496216 1 0 1 1 0 0 +EDGE2 2879 2758 -1.05683 -0.00536982 -0.0115217 1 0 1 1 0 0 +EDGE2 2880 2699 0.977735 0.042525 -3.13336 1 0 1 1 0 0 +EDGE2 2880 2859 0.976234 -0.00520561 -3.169 1 0 1 1 0 0 +EDGE2 2880 2779 1.03445 0.0503183 -3.14892 1 0 1 1 0 0 +EDGE2 2880 2619 0.965918 -0.0476223 -3.17592 1 0 1 1 0 0 +EDGE2 2880 2679 0.958942 0.00414776 -3.10716 1 0 1 1 0 0 +EDGE2 2880 2760 0.0138583 0.0589076 0.00469443 1 0 1 1 0 0 +EDGE2 2880 2681 0.0930058 -0.98506 -1.5511 1 0 1 1 0 0 +EDGE2 2880 2761 0.0560486 -0.937191 -1.5608 1 0 1 1 0 0 +EDGE2 2880 2781 0.0683898 -0.942913 -1.55131 1 0 1 1 0 0 +EDGE2 2880 2621 0.0957698 -0.960766 -1.55387 1 0 1 1 0 0 +EDGE2 2880 2860 0.0454521 0.0640405 -3.14109 1 0 1 1 0 0 +EDGE2 2880 2780 -0.0459477 0.108575 -3.11299 1 0 1 1 0 0 +EDGE2 2880 2620 0.0105063 0.023245 -3.13445 1 0 1 1 0 0 +EDGE2 2880 2680 -0.0181186 0.00447032 -3.14231 1 0 1 1 0 0 +EDGE2 2880 2700 -0.0380512 0.0479811 -3.15283 1 0 1 1 0 0 +EDGE2 2880 2701 0.0384215 1.01786 1.58691 1 0 1 1 0 0 +EDGE2 2880 2861 -0.106523 1.04416 1.60536 1 0 1 1 0 0 +EDGE2 2880 2759 -1.00605 -0.0172615 0.00288563 1 0 1 1 0 0 +EDGE2 2880 2879 -0.964782 -0.0208042 -0.0361667 1 0 1 1 0 0 +EDGE2 2881 2760 -1.05412 0.0835149 -1.54519 1 0 1 1 0 0 +EDGE2 2881 2860 -0.965563 0.11315 1.56963 1 0 1 1 0 0 +EDGE2 2881 2880 -0.968123 0.00557352 -1.5914 1 0 1 1 0 0 +EDGE2 2881 2780 -1.03988 0.05345 1.55121 1 0 1 1 0 0 +EDGE2 2881 2620 -1.01934 0.0260054 1.59209 1 0 1 1 0 0 +EDGE2 2881 2680 -0.991468 -0.0402234 1.56058 1 0 1 1 0 0 +EDGE2 2881 2700 -1.03569 0.0189937 1.60334 1 0 1 1 0 0 +EDGE2 2881 2701 -0.0538554 0.0998946 -0.0106912 1 0 1 1 0 0 +EDGE2 2881 2861 -0.014623 -0.0830183 -0.0444033 1 0 1 1 0 0 +EDGE2 2881 2702 1.07482 0.0332781 -0.00896786 1 0 1 1 0 0 +EDGE2 2881 2862 0.889416 0.0926927 0.021439 1 0 1 1 0 0 +EDGE2 2882 2701 -0.983299 -0.0177576 -0.00832402 1 0 1 1 0 0 +EDGE2 2882 2861 -0.91567 -0.0783193 -0.0129899 1 0 1 1 0 0 +EDGE2 2882 2881 -0.997778 0.0150417 -0.0050494 1 0 1 1 0 0 +EDGE2 2882 2702 0.0813825 0.0174581 0.0163926 1 0 1 1 0 0 +EDGE2 2882 2862 -0.00672224 0.00820269 0.0641268 1 0 1 1 0 0 +EDGE2 2882 2703 0.961884 -0.0620136 0.0213153 1 0 1 1 0 0 +EDGE2 2882 2863 0.966256 0.0971554 0.00655754 1 0 1 1 0 0 +EDGE2 2883 2702 -1.00511 0.000726761 0.0264299 1 0 1 1 0 0 +EDGE2 2883 2862 -0.911862 -0.0107183 0.00279105 1 0 1 1 0 0 +EDGE2 2883 2882 -1.03917 0.0411226 -0.00421338 1 0 1 1 0 0 +EDGE2 2883 2703 0.0689225 0.100802 0.00126675 1 0 1 1 0 0 +EDGE2 2883 2863 -0.124362 -0.0222337 -0.0215249 1 0 1 1 0 0 +EDGE2 2883 2704 1.11174 0.0553988 0.00527768 1 0 1 1 0 0 +EDGE2 2883 2864 0.942671 0.0318832 0.006238 1 0 1 1 0 0 +EDGE2 2884 2703 -1.13331 0.0507357 0.000705292 1 0 1 1 0 0 +EDGE2 2884 2863 -1.07539 0.084723 0.0322247 1 0 1 1 0 0 +EDGE2 2884 2883 -0.905994 -0.113744 0.00742825 1 0 1 1 0 0 +EDGE2 2884 2704 0.0453438 -0.0457919 0.0147223 1 0 1 1 0 0 +EDGE2 2884 2864 -0.00273001 -0.0316947 0.0167042 1 0 1 1 0 0 +EDGE2 2884 2705 1.05009 0.0484222 -0.0184788 1 0 1 1 0 0 +EDGE2 2884 2865 1.06459 0.0192515 0.0182476 1 0 1 1 0 0 +EDGE2 2884 2745 0.998018 0.0480315 -3.16621 1 0 1 1 0 0 +EDGE2 2885 2704 -0.957712 -0.0165332 0.0025847 1 0 1 1 0 0 +EDGE2 2885 2864 -0.971386 0.0681431 -0.00708101 1 0 1 1 0 0 +EDGE2 2885 2884 -1.02408 0.0529924 0.0165833 1 0 1 1 0 0 +EDGE2 2885 2706 0.000603042 -1.02381 -1.56506 1 0 1 1 0 0 +EDGE2 2885 2705 0.0212193 -0.0599519 0.0196118 1 0 1 1 0 0 +EDGE2 2885 2865 0.062702 0.0145071 0.0203681 1 0 1 1 0 0 +EDGE2 2885 2745 -0.00774571 0.0781716 -3.16718 1 0 1 1 0 0 +EDGE2 2885 2746 -0.0413288 1.05848 1.5753 1 0 1 1 0 0 +EDGE2 2885 2866 0.0739071 0.945647 1.57303 1 0 1 1 0 0 +EDGE2 2885 2744 1.00507 -0.038714 -3.18222 1 0 1 1 0 0 +EDGE2 2886 2867 0.840361 0.0606686 0.0213274 1 0 1 1 0 0 +EDGE2 2886 2705 -0.928585 0.0659503 -1.55276 1 0 1 1 0 0 +EDGE2 2886 2865 -1.06817 -0.00139007 -1.54754 1 0 1 1 0 0 +EDGE2 2886 2885 -0.981755 -0.0258329 -1.55946 1 0 1 1 0 0 +EDGE2 2886 2745 -1.05293 -0.0785246 1.59331 1 0 1 1 0 0 +EDGE2 2886 2746 -0.0584232 -0.0210071 0.0215871 1 0 1 1 0 0 +EDGE2 2886 2866 -0.0507382 0.0168067 0.00842195 1 0 1 1 0 0 +EDGE2 2886 2747 0.974937 -0.0603361 0.046759 1 0 1 1 0 0 +EDGE2 2887 2867 0.0522808 -0.0197766 0.0022057 1 0 1 1 0 0 +EDGE2 2887 2746 -0.991725 -0.0596035 -0.0150337 1 0 1 1 0 0 +EDGE2 2887 2866 -0.94313 -0.0110046 -0.00359426 1 0 1 1 0 0 +EDGE2 2887 2886 -0.990347 -0.0312441 0.0229274 1 0 1 1 0 0 +EDGE2 2887 2747 0.0219064 0.00440154 -0.0100378 1 0 1 1 0 0 +EDGE2 2887 2748 1.11051 -0.0735168 -0.0284511 1 0 1 1 0 0 +EDGE2 2887 2868 0.965084 0.047705 -0.0138097 1 0 1 1 0 0 +EDGE2 2888 2869 0.942955 -0.00428854 0.00190908 1 0 1 1 0 0 +EDGE2 2888 2867 -1.01606 -0.0708934 -0.00419221 1 0 1 1 0 0 +EDGE2 2888 2887 -0.943729 -0.0848666 0.0246625 1 0 1 1 0 0 +EDGE2 2888 2747 -1.02012 -0.0313234 0.013679 1 0 1 1 0 0 +EDGE2 2888 2748 0.0787137 0.0602124 -0.014015 1 0 1 1 0 0 +EDGE2 2888 2868 0.0906154 0.0365465 -0.0206296 1 0 1 1 0 0 +EDGE2 2888 2749 0.982117 0.0444405 0.00894653 1 0 1 1 0 0 +EDGE2 2889 2869 -0.00316831 -0.0163964 0.0101116 1 0 1 1 0 0 +EDGE2 2889 2748 -0.969017 -0.0707954 -0.0228555 1 0 1 1 0 0 +EDGE2 2889 2868 -1.01384 -0.0163982 0.0197951 1 0 1 1 0 0 +EDGE2 2889 2888 -0.978434 0.0409867 0.00202169 1 0 1 1 0 0 +EDGE2 2889 2870 1.06901 -0.0689442 0.0117091 1 0 1 1 0 0 +EDGE2 2889 2749 -0.00151808 0.0735536 -0.00863308 1 0 1 1 0 0 +EDGE2 2889 2750 0.919551 -0.0609033 -0.0225118 1 0 1 1 0 0 +EDGE2 2890 2871 -0.072629 0.952539 1.54854 1 0 1 1 0 0 +EDGE2 2890 2751 0.0379133 1.04939 1.57821 1 0 1 1 0 0 +EDGE2 2890 2869 -0.957356 0.041765 -0.0148878 1 0 1 1 0 0 +EDGE2 2890 2889 -1.00447 -0.0455349 0.0357465 1 0 1 1 0 0 +EDGE2 2890 2870 -0.0404122 0.0523943 0.00465939 1 0 1 1 0 0 +EDGE2 2890 2749 -0.934606 -0.0132821 0.00778328 1 0 1 1 0 0 +EDGE2 2890 2750 -0.0746233 0.0260091 0.0146273 1 0 1 1 0 0 +EDGE2 2891 2870 -0.942634 -0.0752954 1.57813 1 0 1 1 0 0 +EDGE2 2891 2890 -0.985109 -0.0304414 1.58071 1 0 1 1 0 0 +EDGE2 2891 2750 -0.937784 -0.0308362 1.56183 1 0 1 1 0 0 +EDGE2 2892 2891 -1.01583 0.0362801 0.0125058 1 0 1 1 0 0 +EDGE2 2893 2892 -1.01115 -0.0472983 0.00148796 1 0 1 1 0 0 +EDGE2 2894 2893 -0.912289 -0.0117277 0.00722778 1 0 1 1 0 0 +EDGE2 2894 2735 0.938569 -0.0165726 -3.15744 1 0 1 1 0 0 +EDGE2 2895 2894 -1.06482 0.0307568 0.00275502 1 0 1 1 0 0 +EDGE2 2895 2734 0.911252 0.103932 -3.14386 1 0 1 1 0 0 +EDGE2 2895 2736 0.024568 -0.968236 -1.58881 1 0 1 1 0 0 +EDGE2 2895 2735 0.0478826 0.0220138 -3.11871 1 0 1 1 0 0 +EDGE2 2896 2895 -0.955357 -0.0544606 -1.56222 1 0 1 1 0 0 +EDGE2 2896 2735 -1.11966 0.0884091 1.56527 1 0 1 1 0 0 +EDGE2 2897 2896 -0.988272 0.0398329 0.0119851 1 0 1 1 0 0 +EDGE2 2898 2897 -0.964394 -0.0650143 -0.0295667 1 0 1 1 0 0 +EDGE2 2899 2898 -0.952993 0.0554917 0.00566352 1 0 1 1 0 0 +EDGE2 2900 2899 -0.979606 -0.0310784 0.0131514 1 0 1 1 0 0 +EDGE2 2901 2900 -1.04055 -0.0459866 -1.52999 1 0 1 1 0 0 +EDGE2 2902 2901 -0.931317 0.0502599 0.0137017 1 0 1 1 0 0 +EDGE2 2903 2902 -1.06874 0.00645282 -0.0101336 1 0 1 1 0 0 +EDGE2 2904 2903 -1.12361 -0.0156375 7.1839e-06 1 0 1 1 0 0 +EDGE2 2905 2904 -1.02829 0.015688 0.0174044 1 0 1 1 0 0 +EDGE2 2906 2905 -1.06141 0.0446355 1.53861 1 0 1 1 0 0 +EDGE2 2907 2906 -0.974082 -0.0254203 -0.003194 1 0 1 1 0 0 +EDGE2 2908 2907 -1.03106 0.0015619 -0.0217995 1 0 1 1 0 0 +EDGE2 2909 2908 -1.01723 -0.0117199 -0.0015095 1 0 1 1 0 0 +EDGE2 2910 2909 -0.947971 0.0143845 0.0143365 1 0 1 1 0 0 +EDGE2 2911 2910 -0.932979 -0.0243991 -1.58565 1 0 1 1 0 0 +EDGE2 2912 2911 -0.983491 0.0903428 -0.0133308 1 0 1 1 0 0 +EDGE2 2913 2912 -0.948706 -0.0475379 0.033087 1 0 1 1 0 0 +EDGE2 2914 2913 -0.975143 0.00195319 -0.0107076 1 0 1 1 0 0 +EDGE2 2915 2914 -0.969466 -0.0431074 -0.0224459 1 0 1 1 0 0 +EDGE2 2916 2915 -1.01361 0.0241689 -1.55752 1 0 1 1 0 0 +EDGE2 2917 2916 -1.12981 0.0145235 -0.0300428 1 0 1 1 0 0 +EDGE2 2918 2917 -0.901367 0.0045566 -0.0248091 1 0 1 1 0 0 +EDGE2 2919 2918 -1.06949 0.0312426 0.0242354 1 0 1 1 0 0 +EDGE2 2920 2919 -0.950312 -0.0151093 0.0106056 1 0 1 1 0 0 +EDGE2 2921 2920 -0.962598 0.00167253 -1.57756 1 0 1 1 0 0 +EDGE2 2922 2921 -1.01837 0.0536716 -0.00485659 1 0 1 1 0 0 +EDGE2 2923 2922 -1.08621 0.152584 0.0419466 1 0 1 1 0 0 +EDGE2 2924 2923 -1.07411 0.0558219 -0.0222368 1 0 1 1 0 0 +EDGE2 2924 2905 0.954216 0.0529952 -3.09226 1 0 1 1 0 0 +EDGE2 2925 2924 -1.06802 -0.0637089 0.00830712 1 0 1 1 0 0 +EDGE2 2925 2904 1.01116 -0.0825314 -3.14566 1 0 1 1 0 0 +EDGE2 2925 2905 0.0390475 0.0536526 -3.12897 1 0 1 1 0 0 +EDGE2 2925 2906 0.0200991 1.02252 1.60813 1 0 1 1 0 0 +EDGE2 2926 2905 -0.948583 -0.0145496 -1.55215 1 0 1 1 0 0 +EDGE2 2926 2925 -1.02663 0.0714696 1.62251 1 0 1 1 0 0 +EDGE2 2927 2926 -0.911473 0.0578543 0.00669424 1 0 1 1 0 0 +EDGE2 2928 2927 -0.967757 0.0155365 -0.0312713 1 0 1 1 0 0 +EDGE2 2929 2928 -1.00533 0.0171032 0.00953728 1 0 1 1 0 0 +EDGE2 2929 2870 1.02119 -0.020656 -3.15969 1 0 1 1 0 0 +EDGE2 2929 2890 1.00395 -0.0215611 -3.12344 1 0 1 1 0 0 +EDGE2 2929 2750 0.945212 -0.079514 -3.12447 1 0 1 1 0 0 +EDGE2 2930 2871 0.0657157 -1.04291 -1.52204 1 0 1 1 0 0 +EDGE2 2930 2751 -0.026837 -1.04494 -1.55612 1 0 1 1 0 0 +EDGE2 2930 2869 1.00787 -0.0134386 -3.15844 1 0 1 1 0 0 +EDGE2 2930 2889 1.00887 0.0524128 -3.13388 1 0 1 1 0 0 +EDGE2 2930 2870 -0.0462158 -0.0402215 -3.12826 1 0 1 1 0 0 +EDGE2 2930 2749 1.0505 0.0254126 -3.1563 1 0 1 1 0 0 +EDGE2 2930 2890 0.0604679 0.0328542 -3.14535 1 0 1 1 0 0 +EDGE2 2930 2929 -0.987734 0.0545757 0.00847771 1 0 1 1 0 0 +EDGE2 2930 2750 0.0643898 0.0581175 -3.14997 1 0 1 1 0 0 +EDGE2 2930 2891 -0.0506763 0.953461 1.60766 1 0 1 1 0 0 +EDGE2 2931 2870 -0.954338 0.0670306 1.59334 1 0 1 1 0 0 +EDGE2 2931 2930 -0.926958 -0.0116571 -1.58398 1 0 1 1 0 0 +EDGE2 2931 2890 -1.01712 -0.0273327 1.58987 1 0 1 1 0 0 +EDGE2 2931 2750 -1.10279 -0.0439138 1.59044 1 0 1 1 0 0 +EDGE2 2931 2891 -0.0118182 -0.0331337 0.0134705 1 0 1 1 0 0 +EDGE2 2931 2892 0.968439 -0.0420899 -0.000235329 1 0 1 1 0 0 +EDGE2 2932 2891 -1.00322 0.0385124 0.0254911 1 0 1 1 0 0 +EDGE2 2932 2931 -0.869881 0.0622654 -0.029099 1 0 1 1 0 0 +EDGE2 2932 2892 0.0533872 0.0684968 -0.00507925 1 0 1 1 0 0 +EDGE2 2932 2893 0.998384 0.0928533 0.00136886 1 0 1 1 0 0 +EDGE2 2933 2932 -0.948703 -0.0563026 -0.0173492 1 0 1 1 0 0 +EDGE2 2933 2892 -0.979081 0.051316 0.022647 1 0 1 1 0 0 +EDGE2 2933 2893 -0.0444739 -0.0167247 -0.00606824 1 0 1 1 0 0 +EDGE2 2933 2894 0.98335 -0.0451666 -0.0145318 1 0 1 1 0 0 +EDGE2 2934 2933 -1.08767 -0.0902248 -0.0181928 1 0 1 1 0 0 +EDGE2 2934 2893 -1.03312 0.00276596 -0.0343257 1 0 1 1 0 0 +EDGE2 2934 2894 0.0853257 0.0613419 -0.00284798 1 0 1 1 0 0 +EDGE2 2934 2895 1.02336 -0.0364133 0.0056111 1 0 1 1 0 0 +EDGE2 2934 2735 1.04075 -0.0685522 -3.13314 1 0 1 1 0 0 +EDGE2 2935 2934 -0.995998 -0.0231996 -0.0258758 1 0 1 1 0 0 +EDGE2 2935 2894 -0.964777 -0.000853392 -0.0372125 1 0 1 1 0 0 +EDGE2 2935 2734 0.967881 0.0803549 -3.14287 1 0 1 1 0 0 +EDGE2 2935 2895 -0.100412 0.108239 -0.00562287 1 0 1 1 0 0 +EDGE2 2935 2736 0.0143472 -0.910974 -1.56728 1 0 1 1 0 0 +EDGE2 2935 2735 0.0136986 0.0527515 -3.17474 1 0 1 1 0 0 +EDGE2 2935 2896 -0.0809266 1.03763 1.56511 1 0 1 1 0 0 +EDGE2 2936 2895 -1.05308 0.0299117 -1.57643 1 0 1 1 0 0 +EDGE2 2936 2935 -1.08328 -0.0222041 -1.53897 1 0 1 1 0 0 +EDGE2 2936 2735 -1.02262 -0.0264201 1.55395 1 0 1 1 0 0 +EDGE2 2936 2896 0.00221701 0.0650962 0.00293872 1 0 1 1 0 0 +EDGE2 2936 2897 0.980042 -0.0543739 -0.00567572 1 0 1 1 0 0 +EDGE2 2937 2936 -1.00698 -0.0358714 -0.00615104 1 0 1 1 0 0 +EDGE2 2937 2896 -1.04206 0.126437 -0.0279923 1 0 1 1 0 0 +EDGE2 2937 2898 0.922246 -0.0361275 0.0148367 1 0 1 1 0 0 +EDGE2 2937 2897 0.00937924 0.0378735 -0.00278491 1 0 1 1 0 0 +EDGE2 2938 2937 -0.978562 -0.0257653 0.0143083 1 0 1 1 0 0 +EDGE2 2938 2899 1.07492 -0.0678063 -0.00969353 1 0 1 1 0 0 +EDGE2 2938 2898 -0.0217489 0.0869596 -0.0232093 1 0 1 1 0 0 +EDGE2 2938 2897 -1.00332 0.00807212 -0.00981349 1 0 1 1 0 0 +EDGE2 2939 2899 0.0277521 0.037348 -0.00467612 1 0 1 1 0 0 +EDGE2 2939 2898 -1.02874 0.113597 0.0470776 1 0 1 1 0 0 +EDGE2 2939 2938 -1.03073 0.0336137 -0.0100875 1 0 1 1 0 0 +EDGE2 2939 2900 0.950285 0.0365155 0.011774 1 0 1 1 0 0 +EDGE2 2940 2899 -0.95166 -0.0478141 -0.0287015 1 0 1 1 0 0 +EDGE2 2940 2939 -0.983023 -0.0135961 0.0203631 1 0 1 1 0 0 +EDGE2 2940 2901 -0.0236067 1.0334 1.55744 1 0 1 1 0 0 +EDGE2 2940 2900 -0.031507 0.0662726 -0.00103044 1 0 1 1 0 0 +EDGE2 2941 2940 -1.0197 -0.0712659 -1.56903 1 0 1 1 0 0 +EDGE2 2941 2902 1.04191 -0.0188671 0.0173628 1 0 1 1 0 0 +EDGE2 2941 2901 0.0570101 0.0497457 -0.00135395 1 0 1 1 0 0 +EDGE2 2941 2900 -1.04855 -0.010812 -1.53804 1 0 1 1 0 0 +EDGE2 2942 2941 -0.99736 0.0154938 0.00856895 1 0 1 1 0 0 +EDGE2 2942 2903 1.06362 -0.0142536 0.0115681 1 0 1 1 0 0 +EDGE2 2942 2902 0.0510134 -0.065467 0.00872835 1 0 1 1 0 0 +EDGE2 2942 2901 -0.927599 -0.0654273 0.00652707 1 0 1 1 0 0 +EDGE2 2943 2904 1.02114 -0.0234295 -0.00997845 1 0 1 1 0 0 +EDGE2 2943 2942 -0.988374 -0.0293424 0.00820266 1 0 1 1 0 0 +EDGE2 2943 2903 -0.0808775 0.0568905 0.0103541 1 0 1 1 0 0 +EDGE2 2943 2902 -0.970999 -0.104864 -0.0522986 1 0 1 1 0 0 +EDGE2 2944 2904 0.0910159 0.0516051 0.010586 1 0 1 1 0 0 +EDGE2 2944 2905 1.00109 -0.0032635 0.0298481 1 0 1 1 0 0 +EDGE2 2944 2925 0.966147 0.0306981 -3.17973 1 0 1 1 0 0 +EDGE2 2944 2903 -1.0281 0.0294518 0.00593824 1 0 1 1 0 0 +EDGE2 2944 2943 -1.05537 -0.0265872 0.00311321 1 0 1 1 0 0 +EDGE2 2945 2924 1.02894 0.00333426 -3.1651 1 0 1 1 0 0 +EDGE2 2945 2904 -1.07276 0.0997972 -0.0250221 1 0 1 1 0 0 +EDGE2 2945 2926 0.0227235 1.07229 1.59589 1 0 1 1 0 0 +EDGE2 2945 2905 -0.00374369 -0.0159573 0.0156487 1 0 1 1 0 0 +EDGE2 2945 2925 -0.0505955 -0.0716753 -3.15462 1 0 1 1 0 0 +EDGE2 2945 2944 -0.976301 -0.0030467 0.0270329 1 0 1 1 0 0 +EDGE2 2945 2906 0.0490928 -0.998562 -1.55216 1 0 1 1 0 0 +EDGE2 2946 2927 0.939271 0.02156 0.0101801 1 0 1 1 0 0 +EDGE2 2946 2926 -0.007919 -0.0179841 -0.0202131 1 0 1 1 0 0 +EDGE2 2946 2905 -1.03355 0.0461548 -1.57791 1 0 1 1 0 0 +EDGE2 2946 2925 -0.970469 -0.0563155 1.58541 1 0 1 1 0 0 +EDGE2 2946 2945 -1.05213 -0.09044 -1.56812 1 0 1 1 0 0 +EDGE2 2947 2928 1.09688 0.0171881 -0.0295997 1 0 1 1 0 0 +EDGE2 2947 2946 -0.946683 -0.000454731 0.0032371 1 0 1 1 0 0 +EDGE2 2947 2927 0.0145766 -0.048808 -0.0288964 1 0 1 1 0 0 +EDGE2 2947 2926 -0.976094 0.0249485 -3.445e-05 1 0 1 1 0 0 +EDGE2 2948 2928 -0.0172976 -0.0737999 0.00115925 1 0 1 1 0 0 +EDGE2 2948 2929 1.10828 0.0126004 0.0311577 1 0 1 1 0 0 +EDGE2 2948 2927 -1.09297 0.00930311 0.0342952 1 0 1 1 0 0 +EDGE2 2948 2947 -0.941675 0.0213232 -0.0391761 1 0 1 1 0 0 +EDGE2 2949 2928 -1.07534 0.0366002 0.0158868 1 0 1 1 0 0 +EDGE2 2949 2870 1.02994 -0.0281668 -3.10351 1 0 1 1 0 0 +EDGE2 2949 2930 1.04895 -0.114586 -0.0150805 1 0 1 1 0 0 +EDGE2 2949 2890 1.10804 0.0316168 -3.12305 1 0 1 1 0 0 +EDGE2 2949 2929 0.0353588 0.0805355 -0.0200345 1 0 1 1 0 0 +EDGE2 2949 2750 0.982192 0.0401209 -3.1532 1 0 1 1 0 0 +EDGE2 2949 2948 -1.00819 0.0449932 -0.00821513 1 0 1 1 0 0 +EDGE2 2950 2871 -0.0609221 -0.926203 -1.57825 1 0 1 1 0 0 +EDGE2 2950 2751 -0.0509942 -1.06586 -1.58783 1 0 1 1 0 0 +EDGE2 2950 2869 1.02901 0.0415738 -3.12868 1 0 1 1 0 0 +EDGE2 2950 2889 0.988713 0.129143 -3.13349 1 0 1 1 0 0 +EDGE2 2950 2870 -0.0565183 -0.0607824 -3.15046 1 0 1 1 0 0 +EDGE2 2950 2930 -0.00879769 0.00168869 0.00878355 1 0 1 1 0 0 +EDGE2 2950 2749 1.00826 0.075479 -3.1194 1 0 1 1 0 0 +EDGE2 2950 2890 0.0131584 0.0199866 -3.14223 1 0 1 1 0 0 +EDGE2 2950 2929 -0.984628 -0.0799471 1.22011e-05 1 0 1 1 0 0 +EDGE2 2950 2949 -1.054 0.0503625 -0.0215838 1 0 1 1 0 0 +EDGE2 2950 2750 -0.00773049 0.0164878 -3.13765 1 0 1 1 0 0 +EDGE2 2950 2891 -0.10357 0.951738 1.55306 1 0 1 1 0 0 +EDGE2 2950 2931 0.0269286 1.10192 1.58627 1 0 1 1 0 0 +EDGE2 2951 2872 0.967298 0.00601851 -0.0045429 1 0 1 1 0 0 +EDGE2 2951 2871 -0.0693396 0.0499651 0.0143614 1 0 1 1 0 0 +EDGE2 2951 2752 1.03782 0.0679991 -0.00909641 1 0 1 1 0 0 +EDGE2 2951 2751 0.0500152 0.0156845 0.00834194 1 0 1 1 0 0 +EDGE2 2951 2870 -0.972924 0.0491439 -1.59445 1 0 1 1 0 0 +EDGE2 2951 2930 -0.975478 0.0172821 1.5674 1 0 1 1 0 0 +EDGE2 2951 2950 -0.925288 0.0185044 1.56936 1 0 1 1 0 0 +EDGE2 2951 2890 -1.08061 0.073735 -1.56517 1 0 1 1 0 0 +EDGE2 2951 2750 -0.99489 -0.0814769 -1.55099 1 0 1 1 0 0 +EDGE2 2952 2872 0.000255065 0.0493561 -0.0398085 1 0 1 1 0 0 +EDGE2 2952 2753 1.01943 4.70868e-05 -0.0230458 1 0 1 1 0 0 +EDGE2 2952 2873 0.883752 -0.0195192 0.0352815 1 0 1 1 0 0 +EDGE2 2952 2871 -0.985048 -0.0299658 -0.0261675 1 0 1 1 0 0 +EDGE2 2952 2951 -0.979103 -0.0361399 0.0299047 1 0 1 1 0 0 +EDGE2 2952 2752 0.0389415 -0.0256102 -0.0101117 1 0 1 1 0 0 +EDGE2 2952 2751 -0.973564 -0.0339267 -0.0153967 1 0 1 1 0 0 +EDGE2 2953 2754 1.03565 -0.045925 -0.00713411 1 0 1 1 0 0 +EDGE2 2953 2874 0.94766 0.0345658 0.00726066 1 0 1 1 0 0 +EDGE2 2953 2872 -1.02138 -0.0632599 -0.0089532 1 0 1 1 0 0 +EDGE2 2953 2753 0.0709984 0.0903396 0.0225286 1 0 1 1 0 0 +EDGE2 2953 2873 0.0195665 -0.0277122 -0.0235944 1 0 1 1 0 0 +EDGE2 2953 2952 -1.034 -0.00370278 -0.0122619 1 0 1 1 0 0 +EDGE2 2953 2752 -0.952354 0.0428836 0.0365889 1 0 1 1 0 0 +EDGE2 2954 2875 0.942641 0.00350984 -0.0250377 1 0 1 1 0 0 +EDGE2 2954 2754 -0.0468865 0.0245005 -0.000406709 1 0 1 1 0 0 +EDGE2 2954 2874 -0.00234111 0.0362364 0.00868695 1 0 1 1 0 0 +EDGE2 2954 2755 1.0006 0.0138534 0.014213 1 0 1 1 0 0 +EDGE2 2954 2753 -1.00393 0.021342 -0.028787 1 0 1 1 0 0 +EDGE2 2954 2873 -1.04537 0.0685373 -0.00380028 1 0 1 1 0 0 +EDGE2 2954 2953 -0.963917 0.139678 -0.0258514 1 0 1 1 0 0 +EDGE2 2955 2875 -0.0348541 -0.016574 -0.00607422 1 0 1 1 0 0 +EDGE2 2955 2876 -0.023017 0.990451 1.59676 1 0 1 1 0 0 +EDGE2 2955 2756 0.0453304 0.932953 1.57293 1 0 1 1 0 0 +EDGE2 2955 2754 -0.949734 0.000114317 3.29429e-05 1 0 1 1 0 0 +EDGE2 2955 2874 -0.988226 -0.0492822 0.0289451 1 0 1 1 0 0 +EDGE2 2955 2954 -1.01467 0.0114718 0.00052414 1 0 1 1 0 0 +EDGE2 2955 2755 0.0059196 0.0711168 -0.0010259 1 0 1 1 0 0 +EDGE2 2956 2875 -0.919945 -0.107824 -1.56152 1 0 1 1 0 0 +EDGE2 2956 2877 0.989094 -0.00253206 -0.0380012 1 0 1 1 0 0 +EDGE2 2956 2757 1.10677 -0.00505775 -0.0194347 1 0 1 1 0 0 +EDGE2 2956 2876 0.059978 -0.0151275 -0.00291555 1 0 1 1 0 0 +EDGE2 2956 2756 0.0224225 0.0474717 -1.63281e-05 1 0 1 1 0 0 +EDGE2 2956 2955 -0.964023 0.00158314 -1.58473 1 0 1 1 0 0 +EDGE2 2956 2755 -0.929678 -0.0956218 -1.56057 1 0 1 1 0 0 +EDGE2 2957 2956 -1.03823 -0.0480632 -0.0219744 1 0 1 1 0 0 +EDGE2 2957 2878 1.02026 -0.0573953 0.000896682 1 0 1 1 0 0 +EDGE2 2957 2877 -0.0497253 -0.0141394 -0.0127787 1 0 1 1 0 0 +EDGE2 2957 2758 1.00896 0.0233845 0.00737735 1 0 1 1 0 0 +EDGE2 2957 2757 -0.0321909 -0.0150734 -0.043673 1 0 1 1 0 0 +EDGE2 2957 2876 -0.958265 -0.00829729 0.000890016 1 0 1 1 0 0 +EDGE2 2957 2756 -0.942083 0.00193301 -0.0229905 1 0 1 1 0 0 +EDGE2 2958 2878 0.0199706 -0.0364156 0.0236408 1 0 1 1 0 0 +EDGE2 2958 2759 0.96349 -0.0500673 0.0261141 1 0 1 1 0 0 +EDGE2 2958 2879 1.0636 0.0147786 -0.0229409 1 0 1 1 0 0 +EDGE2 2958 2877 -1.02244 0.00182945 0.00638714 1 0 1 1 0 0 +EDGE2 2958 2957 -1.05344 0.0237982 0.0123216 1 0 1 1 0 0 +EDGE2 2958 2758 0.109999 -0.0187427 -0.0139943 1 0 1 1 0 0 +EDGE2 2958 2757 -0.983229 -0.0272778 0.00319992 1 0 1 1 0 0 +EDGE2 2959 2760 1.00748 -0.0457483 0.00116975 1 0 1 1 0 0 +EDGE2 2959 2860 0.968069 -0.0581301 -3.09777 1 0 1 1 0 0 +EDGE2 2959 2880 0.999087 0.0276089 0.00344412 1 0 1 1 0 0 +EDGE2 2959 2780 0.927758 -0.0120253 -3.16208 1 0 1 1 0 0 +EDGE2 2959 2620 0.981229 -0.0187452 -3.15095 1 0 1 1 0 0 +EDGE2 2959 2680 1.01412 0.107155 -3.15424 1 0 1 1 0 0 +EDGE2 2959 2700 1.00849 -0.0535741 -3.1387 1 0 1 1 0 0 +EDGE2 2959 2878 -1.01102 -0.000327764 0.014732 1 0 1 1 0 0 +EDGE2 2959 2759 0.102658 0.0586562 0.0211609 1 0 1 1 0 0 +EDGE2 2959 2879 -0.007575 -0.0128868 -0.00388639 1 0 1 1 0 0 +EDGE2 2959 2958 -1.0165 0.0139642 -0.0187812 1 0 1 1 0 0 +EDGE2 2959 2758 -0.940565 -0.0363462 0.00340551 1 0 1 1 0 0 +EDGE2 2960 2699 1.03141 -0.00575919 -3.14343 1 0 1 1 0 0 +EDGE2 2960 2859 0.888619 -0.0566487 -3.15926 1 0 1 1 0 0 +EDGE2 2960 2779 1.04225 -0.0537008 -3.14079 1 0 1 1 0 0 +EDGE2 2960 2619 1.06719 -0.0321175 -3.15276 1 0 1 1 0 0 +EDGE2 2960 2679 1.00902 -0.00717935 -3.14433 1 0 1 1 0 0 +EDGE2 2960 2760 -0.0211946 0.0533178 0.0140053 1 0 1 1 0 0 +EDGE2 2960 2681 -0.0213086 -0.972814 -1.58511 1 0 1 1 0 0 +EDGE2 2960 2761 -0.0533834 -0.963871 -1.57786 1 0 1 1 0 0 +EDGE2 2960 2781 -0.0144083 -0.920966 -1.56529 1 0 1 1 0 0 +EDGE2 2960 2621 -0.0586031 -1.04936 -1.55298 1 0 1 1 0 0 +EDGE2 2960 2860 0.0788926 0.0224201 -3.14917 1 0 1 1 0 0 +EDGE2 2960 2880 -0.0763004 -0.0628843 -0.00244725 1 0 1 1 0 0 +EDGE2 2960 2780 0.00743088 -0.0913463 -3.1549 1 0 1 1 0 0 +EDGE2 2960 2620 -0.000347751 0.0169951 -3.17592 1 0 1 1 0 0 +EDGE2 2960 2680 -0.039289 0.0484291 -3.11396 1 0 1 1 0 0 +EDGE2 2960 2700 0.032485 0.059039 -3.13547 1 0 1 1 0 0 +EDGE2 2960 2701 -0.101446 1.00073 1.5999 1 0 1 1 0 0 +EDGE2 2960 2861 0.0390064 0.931687 1.58588 1 0 1 1 0 0 +EDGE2 2960 2881 -0.059353 1.00151 1.56351 1 0 1 1 0 0 +EDGE2 2960 2759 -0.985908 0.000338574 -0.0214277 1 0 1 1 0 0 +EDGE2 2960 2879 -0.961386 0.0363646 0.0205638 1 0 1 1 0 0 +EDGE2 2960 2959 -0.983224 0.02131 0.0045029 1 0 1 1 0 0 +EDGE2 2961 2760 -0.94249 -0.0745802 -1.56323 1 0 1 1 0 0 +EDGE2 2961 2860 -1.0956 -0.0341179 1.58419 1 0 1 1 0 0 +EDGE2 2961 2880 -0.984856 -0.00769242 -1.56026 1 0 1 1 0 0 +EDGE2 2961 2960 -0.942999 0.0364139 -1.57895 1 0 1 1 0 0 +EDGE2 2961 2780 -0.966994 -0.0119907 1.57897 1 0 1 1 0 0 +EDGE2 2961 2620 -0.937953 -0.0611736 1.58295 1 0 1 1 0 0 +EDGE2 2961 2680 -1.03837 -0.0423342 1.56282 1 0 1 1 0 0 +EDGE2 2961 2700 -1.00277 0.0207119 1.5626 1 0 1 1 0 0 +EDGE2 2961 2701 0.0168541 0.0229041 0.0104198 1 0 1 1 0 0 +EDGE2 2961 2861 -0.0480591 0.0472651 -0.00730196 1 0 1 1 0 0 +EDGE2 2961 2881 -0.0369628 -0.0863548 -0.0115695 1 0 1 1 0 0 +EDGE2 2961 2702 1.02646 0.0389885 0.0155543 1 0 1 1 0 0 +EDGE2 2961 2862 1.0015 -0.00108368 0.0083989 1 0 1 1 0 0 +EDGE2 2961 2882 1.02017 -0.00174139 0.00840212 1 0 1 1 0 0 +EDGE2 2962 2961 -1.07763 0.0519404 0.00991546 1 0 1 1 0 0 +EDGE2 2962 2701 -0.892244 0.00500587 -0.0193818 1 0 1 1 0 0 +EDGE2 2962 2861 -1.13865 0.0315152 -0.00460726 1 0 1 1 0 0 +EDGE2 2962 2881 -1.05297 -0.0307072 0.0127266 1 0 1 1 0 0 +EDGE2 2962 2702 0.0536065 -0.0239086 0.0108813 1 0 1 1 0 0 +EDGE2 2962 2862 -0.00174808 0.120536 -0.0231313 1 0 1 1 0 0 +EDGE2 2962 2882 0.00615831 -0.0495978 0.0101553 1 0 1 1 0 0 +EDGE2 2962 2703 1.0593 -0.00827847 -0.0397375 1 0 1 1 0 0 +EDGE2 2962 2863 0.94151 -0.0122655 0.0219242 1 0 1 1 0 0 +EDGE2 2962 2883 0.928411 -0.00402426 -0.0100377 1 0 1 1 0 0 +EDGE2 2963 2962 -0.988515 -0.0123151 0.00617007 1 0 1 1 0 0 +EDGE2 2963 2702 -1.02095 -0.0129163 -0.00231346 1 0 1 1 0 0 +EDGE2 2963 2862 -1.00032 0.0178855 -0.0404724 1 0 1 1 0 0 +EDGE2 2963 2882 -0.972929 -0.0514716 0.0166759 1 0 1 1 0 0 +EDGE2 2963 2703 -0.0198345 0.0375908 0.0303661 1 0 1 1 0 0 +EDGE2 2963 2863 0.0182693 -0.0653576 0.0240968 1 0 1 1 0 0 +EDGE2 2963 2883 0.00664127 -0.00496913 0.0011899 1 0 1 1 0 0 +EDGE2 2963 2704 1.04859 0.0305521 0.0493387 1 0 1 1 0 0 +EDGE2 2963 2864 0.917173 -0.0985134 -0.0093535 1 0 1 1 0 0 +EDGE2 2963 2884 0.968529 -0.0358599 -0.0258524 1 0 1 1 0 0 +EDGE2 2964 2963 -0.885948 0.0558508 0.0484898 1 0 1 1 0 0 +EDGE2 2964 2703 -1.03773 -0.107239 -0.00208148 1 0 1 1 0 0 +EDGE2 2964 2863 -1.00059 -0.0941605 0.0135572 1 0 1 1 0 0 +EDGE2 2964 2883 -1.0464 -0.0392266 -0.0528364 1 0 1 1 0 0 +EDGE2 2964 2704 -0.0682516 0.025741 -0.0390819 1 0 1 1 0 0 +EDGE2 2964 2864 -0.0431246 -0.0697964 0.00397962 1 0 1 1 0 0 +EDGE2 2964 2884 -0.0108629 -0.0187034 0.0300143 1 0 1 1 0 0 +EDGE2 2964 2705 1.01046 0.0899273 -0.00311415 1 0 1 1 0 0 +EDGE2 2964 2865 0.994208 -0.0163372 -0.0350896 1 0 1 1 0 0 +EDGE2 2964 2885 1.07468 0.0417071 -0.0234088 1 0 1 1 0 0 +EDGE2 2964 2745 0.927548 -0.0545435 -3.14239 1 0 1 1 0 0 +EDGE2 2965 2964 -0.958882 0.0194591 0.0615051 1 0 1 1 0 0 +EDGE2 2965 2704 -1.06985 0.061552 0.00914728 1 0 1 1 0 0 +EDGE2 2965 2864 -0.996496 -0.00454528 0.0130026 1 0 1 1 0 0 +EDGE2 2965 2884 -1.00486 0.0031035 -0.00189604 1 0 1 1 0 0 +EDGE2 2965 2706 0.0942519 -0.980365 -1.60134 1 0 1 1 0 0 +EDGE2 2965 2705 0.0171898 -0.018835 -0.0284219 1 0 1 1 0 0 +EDGE2 2965 2865 0.0244471 0.00776619 -0.000163557 1 0 1 1 0 0 +EDGE2 2965 2885 0.0929639 0.0369511 0.0243674 1 0 1 1 0 0 +EDGE2 2965 2745 -0.0224303 0.0556717 -3.12577 1 0 1 1 0 0 +EDGE2 2965 2746 -0.00364336 1.01407 1.56345 1 0 1 1 0 0 +EDGE2 2965 2866 0.0341091 1.00198 1.58204 1 0 1 1 0 0 +EDGE2 2965 2886 -0.000389 1.13741 1.54983 1 0 1 1 0 0 +EDGE2 2965 2744 1.10067 0.0234456 -3.1048 1 0 1 1 0 0 +EDGE2 2966 2706 0.0450693 -0.0210178 0.00945488 1 0 1 1 0 0 +EDGE2 2966 2707 1.00925 -0.0766449 0.00309926 1 0 1 1 0 0 +EDGE2 2966 2705 -0.981948 0.00749882 1.55314 1 0 1 1 0 0 +EDGE2 2966 2865 -1.04911 -0.0398341 1.59389 1 0 1 1 0 0 +EDGE2 2966 2885 -1.04105 0.0966175 1.60743 1 0 1 1 0 0 +EDGE2 2966 2965 -1.04079 -0.0067037 1.56928 1 0 1 1 0 0 +EDGE2 2966 2745 -0.979075 0.0227018 -1.59104 1 0 1 1 0 0 +EDGE2 2967 2706 -0.945217 0.0218827 0.0243355 1 0 1 1 0 0 +EDGE2 2967 2707 0.0390158 0.0365401 -0.011037 1 0 1 1 0 0 +EDGE2 2967 2708 1.03602 -0.059599 0.00539933 1 0 1 1 0 0 +EDGE2 2967 2966 -0.938756 -0.0134427 0.0221873 1 0 1 1 0 0 +EDGE2 2968 2709 0.967564 -0.0262405 -0.0329353 1 0 1 1 0 0 +EDGE2 2968 2707 -1.1021 -0.0178503 0.00203483 1 0 1 1 0 0 +EDGE2 2968 2967 -1.05865 -0.0658519 0.0391699 1 0 1 1 0 0 +EDGE2 2968 2708 0.0834142 -0.0255477 -0.0149628 1 0 1 1 0 0 +EDGE2 2969 2710 1.03832 -0.0163979 0.0293238 1 0 1 1 0 0 +EDGE2 2969 2968 -0.98191 0.0011442 0.0171804 1 0 1 1 0 0 +EDGE2 2969 2709 -0.0616257 -0.0287457 0.00875824 1 0 1 1 0 0 +EDGE2 2969 2708 -0.990031 0.0799092 -0.012645 1 0 1 1 0 0 +EDGE2 2970 2711 -0.0041126 0.977786 1.56362 1 0 1 1 0 0 +EDGE2 2970 2710 -0.0336452 0.0284324 0.00879808 1 0 1 1 0 0 +EDGE2 2970 2969 -0.939076 0.0187293 0.0126014 1 0 1 1 0 0 +EDGE2 2970 2709 -1.05161 0.0781523 -0.0236717 1 0 1 1 0 0 +EDGE2 2971 2970 -0.961848 -0.0238982 1.58164 1 0 1 1 0 0 +EDGE2 2971 2710 -1.07867 -0.0503786 1.57265 1 0 1 1 0 0 +EDGE2 2972 2971 -1.00945 0.0625325 0.0355261 1 0 1 1 0 0 +EDGE2 2973 2972 -1.0038 0.00911579 -0.0216447 1 0 1 1 0 0 +EDGE2 2974 2973 -0.983067 -0.0784001 0.00990003 1 0 1 1 0 0 +EDGE2 2974 2775 1.02005 -0.00526091 -3.15366 1 0 1 1 0 0 +EDGE2 2974 2855 0.962447 0.0730431 -3.16428 1 0 1 1 0 0 +EDGE2 2974 2615 1.01775 -0.0865293 -3.12648 1 0 1 1 0 0 +EDGE2 2974 2675 0.98315 -0.0470148 -3.1375 1 0 1 1 0 0 +EDGE2 2974 2695 1.06684 -0.119989 -3.13315 1 0 1 1 0 0 +EDGE2 2975 2854 1.03992 -0.032557 -3.1519 1 0 1 1 0 0 +EDGE2 2975 2775 0.027236 0.0540269 -3.15532 1 0 1 1 0 0 +EDGE2 2975 2674 0.978244 0.00308495 -3.16127 1 0 1 1 0 0 +EDGE2 2975 2694 0.917113 -0.038409 -3.15302 1 0 1 1 0 0 +EDGE2 2975 2774 1.10367 -0.0871657 -3.12086 1 0 1 1 0 0 +EDGE2 2975 2614 0.972491 0.0597676 -3.16322 1 0 1 1 0 0 +EDGE2 2975 2855 0.017111 0.0530796 -3.14651 1 0 1 1 0 0 +EDGE2 2975 2615 -0.0130908 -0.061121 -3.17023 1 0 1 1 0 0 +EDGE2 2975 2675 0.0186613 0.0273159 -3.14712 1 0 1 1 0 0 +EDGE2 2975 2695 0.00119076 0.000239488 -3.13201 1 0 1 1 0 0 +EDGE2 2975 2974 -0.971956 0.0415815 -0.000349687 1 0 1 1 0 0 +EDGE2 2975 2676 -0.0279748 -1.02626 -1.58669 1 0 1 1 0 0 +EDGE2 2975 2776 0.00217535 -1.04114 -1.5959 1 0 1 1 0 0 +EDGE2 2975 2856 -0.0408904 -1.07909 -1.56958 1 0 1 1 0 0 +EDGE2 2975 2696 0.0333315 -0.998526 -1.55782 1 0 1 1 0 0 +EDGE2 2975 2616 -0.00915981 -1.00578 -1.56343 1 0 1 1 0 0 +EDGE2 2976 2775 -0.967843 -0.000744924 1.55411 1 0 1 1 0 0 +EDGE2 2976 2975 -1.02216 0.0232867 -1.53778 1 0 1 1 0 0 +EDGE2 2976 2855 -0.918349 0.0186672 1.59031 1 0 1 1 0 0 +EDGE2 2976 2615 -0.932181 -0.0372978 1.56796 1 0 1 1 0 0 +EDGE2 2976 2675 -0.916251 -0.05395 1.56794 1 0 1 1 0 0 +EDGE2 2976 2695 -0.980934 0.0655081 1.53836 1 0 1 1 0 0 +EDGE2 2977 2976 -1.0205 -0.00564491 -0.00752433 1 0 1 1 0 0 +EDGE2 2978 2977 -0.954344 -0.00508814 0.0047269 1 0 1 1 0 0 +EDGE2 2979 1220 1.04055 -0.0255178 -3.14532 1 0 1 1 0 0 +EDGE2 2979 2480 1.10618 -0.0518485 -3.15531 1 0 1 1 0 0 +EDGE2 2979 720 0.972137 0.0108501 -3.14625 1 0 1 1 0 0 +EDGE2 2979 2978 -1.00998 -0.00267883 0.00517113 1 0 1 1 0 0 +EDGE2 2980 2479 1.00176 -0.00842147 -3.12814 1 0 1 1 0 0 +EDGE2 2980 719 1.02387 -0.00498827 -3.12079 1 0 1 1 0 0 +EDGE2 2980 1219 1.06786 -0.0404744 -3.13391 1 0 1 1 0 0 +EDGE2 2980 1221 0.0741987 -0.941137 -1.58766 1 0 1 1 0 0 +EDGE2 2980 2481 0.0405262 -0.942024 -1.57495 1 0 1 1 0 0 +EDGE2 2980 1220 -0.00985117 -0.0620292 -3.13836 1 0 1 1 0 0 +EDGE2 2980 2480 -0.0313349 -0.0168644 -3.13152 1 0 1 1 0 0 +EDGE2 2980 720 0.00950837 0.0536188 -3.1498 1 0 1 1 0 0 +EDGE2 2980 721 0.0201918 1.01288 1.58597 1 0 1 1 0 0 +EDGE2 2980 2979 -1.03737 0.0509255 -0.0203784 1 0 1 1 0 0 +EDGE2 2981 1221 -0.0313757 0.00433393 0.00870217 1 0 1 1 0 0 +EDGE2 2981 1222 1.0626 0.0785766 -0.0141999 1 0 1 1 0 0 +EDGE2 2981 2482 0.992207 -0.0380017 -0.0109584 1 0 1 1 0 0 +EDGE2 2981 2481 0.0341914 0.0326993 -0.00135733 1 0 1 1 0 0 +EDGE2 2981 1220 -0.971754 -0.0224252 -1.60648 1 0 1 1 0 0 +EDGE2 2981 2480 -0.877573 0.0865394 -1.54798 1 0 1 1 0 0 +EDGE2 2981 2980 -0.968858 0.00729501 1.54547 1 0 1 1 0 0 +EDGE2 2981 720 -1.02407 -0.0306099 -1.59153 1 0 1 1 0 0 +EDGE2 2982 1221 -1.06381 0.0383245 -0.00222046 1 0 1 1 0 0 +EDGE2 2982 1223 1.04197 -0.00923996 0.029088 1 0 1 1 0 0 +EDGE2 2982 2483 0.933759 -0.0212442 -0.0114693 1 0 1 1 0 0 +EDGE2 2982 1222 -0.0272589 -0.032169 0.0147611 1 0 1 1 0 0 +EDGE2 2982 2482 -0.00897834 0.0197325 0.0317308 1 0 1 1 0 0 +EDGE2 2982 2981 -0.944311 -0.0735005 -0.0103963 1 0 1 1 0 0 +EDGE2 2982 2481 -1.06842 -0.0389573 0.0211437 1 0 1 1 0 0 +EDGE2 2983 1223 -0.0147703 -0.0423914 0.0145257 1 0 1 1 0 0 +EDGE2 2983 1224 1.03528 0.0272037 0.0111937 1 0 1 1 0 0 +EDGE2 2983 2484 0.986785 0.062443 0.0193472 1 0 1 1 0 0 +EDGE2 2983 2483 -0.0366397 0.0915067 -0.012845 1 0 1 1 0 0 +EDGE2 2983 1222 -0.974343 -0.0189405 -0.00196087 1 0 1 1 0 0 +EDGE2 2983 2982 -0.995065 -0.0532754 -0.0308067 1 0 1 1 0 0 +EDGE2 2983 2482 -1.04633 0.0357082 -0.0002439 1 0 1 1 0 0 +EDGE2 2984 2645 0.967836 0.0303905 -3.17497 1 0 1 1 0 0 +EDGE2 2984 2665 1.02247 -0.0685178 -3.16435 1 0 1 1 0 0 +EDGE2 2984 1225 0.951965 0.0183404 -0.0167113 1 0 1 1 0 0 +EDGE2 2984 2485 0.933234 0.0102567 0.00968423 1 0 1 1 0 0 +EDGE2 2984 2505 0.946135 -0.0230937 -3.14176 1 0 1 1 0 0 +EDGE2 2984 2605 1.07129 0.0149303 -3.11515 1 0 1 1 0 0 +EDGE2 2984 2445 0.981983 0.0010807 -3.16054 1 0 1 1 0 0 +EDGE2 2984 1223 -1.09616 0.0475952 0.022648 1 0 1 1 0 0 +EDGE2 2984 1224 0.0327768 0.0954402 -0.00477212 1 0 1 1 0 0 +EDGE2 2984 2484 -0.0120022 0.0494955 -0.00710155 1 0 1 1 0 0 +EDGE2 2984 2983 -0.957036 0.0446948 -0.00620508 1 0 1 1 0 0 +EDGE2 2984 2483 -1.01244 -0.0187075 0.0233306 1 0 1 1 0 0 +EDGE2 2985 2446 0.0690957 0.929224 1.56244 1 0 1 1 0 0 +EDGE2 2985 2486 -0.0200654 0.959635 1.63513 1 0 1 1 0 0 +EDGE2 2985 1226 0.00863033 0.949685 1.53584 1 0 1 1 0 0 +EDGE2 2985 2666 0.0516388 -1.00994 -1.5654 1 0 1 1 0 0 +EDGE2 2985 2645 -0.149945 -0.00990223 -3.14828 1 0 1 1 0 0 +EDGE2 2985 2444 1.04734 0.00694231 -3.11876 1 0 1 1 0 0 +EDGE2 2985 2604 0.977727 -0.0269406 -3.11226 1 0 1 1 0 0 +EDGE2 2985 2644 1.06472 0.0427249 -3.10953 1 0 1 1 0 0 +EDGE2 2985 2664 0.997214 -0.115491 -3.15412 1 0 1 1 0 0 +EDGE2 2985 2504 1.09277 0.0575852 -3.16334 1 0 1 1 0 0 +EDGE2 2985 2665 0.0177224 -0.00195903 -3.19202 1 0 1 1 0 0 +EDGE2 2985 1225 0.0127206 -0.0387092 -0.0331782 1 0 1 1 0 0 +EDGE2 2985 2485 -0.0626914 0.0226109 0.0449134 1 0 1 1 0 0 +EDGE2 2985 2505 0.076907 -0.0440222 -3.16225 1 0 1 1 0 0 +EDGE2 2985 2605 -0.0103463 -0.0683577 -3.13612 1 0 1 1 0 0 +EDGE2 2985 2445 -0.0473287 0.00262537 -3.1357 1 0 1 1 0 0 +EDGE2 2985 1224 -0.943438 -0.0585248 -0.0146837 1 0 1 1 0 0 +EDGE2 2985 2984 -1.00327 0.034609 0.0238604 1 0 1 1 0 0 +EDGE2 2985 2484 -0.97527 -0.0485856 -0.00625578 1 0 1 1 0 0 +EDGE2 2985 2506 -0.0534431 -1.00347 -1.56764 1 0 1 1 0 0 +EDGE2 2985 2606 0.00638198 -1.00266 -1.55913 1 0 1 1 0 0 +EDGE2 2985 2646 -0.0541588 -0.980344 -1.5489 1 0 1 1 0 0 +EDGE2 2986 1227 0.961812 0.00659816 -0.00775254 1 0 1 1 0 0 +EDGE2 2986 2487 0.898075 -0.00985099 -0.00458336 1 0 1 1 0 0 +EDGE2 2986 2447 1.08911 -0.0612443 0.0171271 1 0 1 1 0 0 +EDGE2 2986 2446 -0.0531494 0.0718245 -0.00595378 1 0 1 1 0 0 +EDGE2 2986 2486 0.00646787 0.0231152 3.7851e-05 1 0 1 1 0 0 +EDGE2 2986 1226 -0.0281026 0.0137552 -0.00225054 1 0 1 1 0 0 +EDGE2 2986 2645 -0.994903 0.00689826 1.56271 1 0 1 1 0 0 +EDGE2 2986 2985 -0.997772 -0.0216346 -1.57793 1 0 1 1 0 0 +EDGE2 2986 2665 -0.948877 -0.0246095 1.58046 1 0 1 1 0 0 +EDGE2 2986 1225 -0.972283 -0.0582592 -1.54719 1 0 1 1 0 0 +EDGE2 2986 2485 -1.00962 0.0596944 -1.57248 1 0 1 1 0 0 +EDGE2 2986 2505 -1.04534 -0.0500576 1.56676 1 0 1 1 0 0 +EDGE2 2986 2605 -1.05151 0.018271 1.55088 1 0 1 1 0 0 +EDGE2 2986 2445 -0.943004 0.0123492 1.5953 1 0 1 1 0 0 +EDGE2 2987 2488 0.901735 0.0224798 -0.0137367 1 0 1 1 0 0 +EDGE2 2987 1228 1.08966 -0.0147498 -0.00481311 1 0 1 1 0 0 +EDGE2 2987 2448 0.987751 -0.0116744 0.042224 1 0 1 1 0 0 +EDGE2 2987 1227 -0.0764591 0.0274161 -0.0168766 1 0 1 1 0 0 +EDGE2 2987 2487 0.0430232 0.00678872 -0.00339399 1 0 1 1 0 0 +EDGE2 2987 2447 0.0350382 -0.0521758 0.0142355 1 0 1 1 0 0 +EDGE2 2987 2446 -0.981975 0.0501833 -0.00500356 1 0 1 1 0 0 +EDGE2 2987 2986 -1.0011 -0.0375182 0.0111608 1 0 1 1 0 0 +EDGE2 2987 2486 -0.901707 -0.0273716 -0.0050028 1 0 1 1 0 0 +EDGE2 2987 1226 -0.985624 -0.00348791 -0.0205383 1 0 1 1 0 0 +EDGE2 2988 2488 -0.00969648 -0.000322492 0.0131058 1 0 1 1 0 0 +EDGE2 2988 2449 1.07899 0.0597088 0.011525 1 0 1 1 0 0 +EDGE2 2988 2489 1.06396 0.0508338 0.048376 1 0 1 1 0 0 +EDGE2 2988 1229 1.04519 -0.00800102 -0.0239357 1 0 1 1 0 0 +EDGE2 2988 1228 0.021175 0.0382381 0.00317941 1 0 1 1 0 0 +EDGE2 2988 2448 0.000480253 -0.0961783 0.0153215 1 0 1 1 0 0 +EDGE2 2988 1227 -1.03562 -0.00140793 0.0258034 1 0 1 1 0 0 +EDGE2 2988 2487 -1.0704 0.0254739 -0.000724889 1 0 1 1 0 0 +EDGE2 2988 2987 -1.01736 0.0114051 -0.00643638 1 0 1 1 0 0 +EDGE2 2988 2447 -1.08858 -0.0789158 -0.00425339 1 0 1 1 0 0 +EDGE2 2989 1250 1.02993 0.0192078 -3.14464 1 0 1 1 0 0 +EDGE2 2989 2450 0.8885 0.0553844 0.0175328 1 0 1 1 0 0 +EDGE2 2989 2470 1.02348 0.0686035 -3.13934 1 0 1 1 0 0 +EDGE2 2989 2490 1.03094 0.0478169 -0.00297972 1 0 1 1 0 0 +EDGE2 2989 2290 1.04764 -0.076937 -3.10499 1 0 1 1 0 0 +EDGE2 2989 1230 1.05495 -0.00352877 0.010892 1 0 1 1 0 0 +EDGE2 2989 2488 -1.08505 0.0676637 0.0202441 1 0 1 1 0 0 +EDGE2 2989 2449 -0.0506817 -0.0267324 0.0281387 1 0 1 1 0 0 +EDGE2 2989 2489 -0.0425674 0.0319534 0.00832847 1 0 1 1 0 0 +EDGE2 2989 1229 0.0113624 -0.0322977 0.0156325 1 0 1 1 0 0 +EDGE2 2989 2988 -1.01663 0.0419492 -0.000244635 1 0 1 1 0 0 +EDGE2 2989 1228 -0.999834 0.0856498 -0.03074 1 0 1 1 0 0 +EDGE2 2989 2448 -0.986294 0.071169 0.00458226 1 0 1 1 0 0 +EDGE2 2990 2291 -0.0228669 -1.03767 -1.60121 1 0 1 1 0 0 +EDGE2 2990 2289 1.01352 -0.00221058 -3.13672 1 0 1 1 0 0 +EDGE2 2990 2469 0.950037 -0.0255328 -3.13779 1 0 1 1 0 0 +EDGE2 2990 2491 -0.0329893 -0.931078 -1.58979 1 0 1 1 0 0 +EDGE2 2990 2451 0.0642544 -0.99139 -1.53813 1 0 1 1 0 0 +EDGE2 2990 1249 1.06198 0.0183153 -3.12508 1 0 1 1 0 0 +EDGE2 2990 1250 -0.0374557 0.0112044 -3.10662 1 0 1 1 0 0 +EDGE2 2990 1231 -0.105983 -1.01056 -1.55952 1 0 1 1 0 0 +EDGE2 2990 1251 -0.00444354 -0.955278 -1.56563 1 0 1 1 0 0 +EDGE2 2990 2450 -0.0394707 0.0960375 0.00557502 1 0 1 1 0 0 +EDGE2 2990 2470 0.0394086 0.0294282 -3.18392 1 0 1 1 0 0 +EDGE2 2990 2490 -0.0441713 0.00961554 0.0070973 1 0 1 1 0 0 +EDGE2 2990 2290 0.0470074 -0.0996458 -3.13061 1 0 1 1 0 0 +EDGE2 2990 1230 0.0822284 -0.0880757 -0.0529405 1 0 1 1 0 0 +EDGE2 2990 2471 -0.0558887 1.07012 1.5762 1 0 1 1 0 0 +EDGE2 2990 2449 -1.04838 -0.0466137 -0.0210613 1 0 1 1 0 0 +EDGE2 2990 2989 -0.99621 0.0543219 -0.0239902 1 0 1 1 0 0 +EDGE2 2990 2489 -1.02222 0.090309 0.00191505 1 0 1 1 0 0 +EDGE2 2990 1229 -0.935931 -0.00488459 0.0134979 1 0 1 1 0 0 +EDGE2 2991 1250 -1.07208 0.0393923 1.56804 1 0 1 1 0 0 +EDGE2 2991 2990 -0.916875 0.0623759 -1.58038 1 0 1 1 0 0 +EDGE2 2991 2450 -1.08358 -0.0354044 -1.56565 1 0 1 1 0 0 +EDGE2 2991 2470 -1.04708 -0.0112066 1.56276 1 0 1 1 0 0 +EDGE2 2991 2490 -1.10114 -0.0982815 -1.60462 1 0 1 1 0 0 +EDGE2 2991 2290 -1.00023 -0.00633458 1.56642 1 0 1 1 0 0 +EDGE2 2991 1230 -1.07598 -0.0818597 -1.55667 1 0 1 1 0 0 +EDGE2 2991 2471 0.0125749 -0.0252572 0.00431398 1 0 1 1 0 0 +EDGE2 2991 2472 1.01766 -0.0103052 0.0137892 1 0 1 1 0 0 +EDGE2 2992 2991 -0.965387 -0.109883 0.00706957 1 0 1 1 0 0 +EDGE2 2992 2471 -0.941644 0.0292792 0.0325899 1 0 1 1 0 0 +EDGE2 2992 2472 0.122513 0.0757094 0.0109801 1 0 1 1 0 0 +EDGE2 2992 2473 0.961317 -0.0550556 0.0162061 1 0 1 1 0 0 +EDGE2 2993 2472 -0.987961 0.0676216 -0.0305195 1 0 1 1 0 0 +EDGE2 2993 2992 -0.92396 0.0455941 0.00496726 1 0 1 1 0 0 +EDGE2 2993 2473 -0.0239644 0.00666953 0.0123152 1 0 1 1 0 0 +EDGE2 2993 2474 0.983275 0.0238572 -0.00160375 1 0 1 1 0 0 +EDGE2 2994 2993 -1.0236 0.0503291 0.00886139 1 0 1 1 0 0 +EDGE2 2994 2475 0.966296 -0.0202971 0.0105338 1 0 1 1 0 0 +EDGE2 2994 2473 -0.969477 0.00693352 -0.03905 1 0 1 1 0 0 +EDGE2 2994 2474 -0.00838835 0.0501481 -0.0133559 1 0 1 1 0 0 +EDGE2 2994 715 1.0365 0.0929844 -3.12201 1 0 1 1 0 0 +EDGE2 2994 735 0.954059 -0.0502381 -3.16188 1 0 1 1 0 0 +EDGE2 2994 1215 0.997272 0.00358651 -3.16285 1 0 1 1 0 0 +EDGE2 2995 736 -0.0227062 -0.989619 -1.55769 1 0 1 1 0 0 +EDGE2 2995 2475 -0.055688 -0.0271032 -0.00858854 1 0 1 1 0 0 +EDGE2 2995 2994 -1.01992 -0.0483802 -0.00730962 1 0 1 1 0 0 +EDGE2 2995 2474 -1.09215 -0.0342409 -0.00991713 1 0 1 1 0 0 +EDGE2 2995 715 0.0371844 -0.0290246 -3.14551 1 0 1 1 0 0 +EDGE2 2995 735 0.0104412 0.0409841 -3.1618 1 0 1 1 0 0 +EDGE2 2995 1215 0.0943488 -0.0481109 -3.11611 1 0 1 1 0 0 +EDGE2 2995 734 0.971107 0.0561353 -3.11793 1 0 1 1 0 0 +EDGE2 2995 1214 1.00834 -0.00773073 -3.16267 1 0 1 1 0 0 +EDGE2 2995 714 1.00709 0.0561532 -3.18372 1 0 1 1 0 0 +EDGE2 2995 1216 0.0373796 0.940422 1.56251 1 0 1 1 0 0 +EDGE2 2995 2476 -0.0298395 1.01691 1.57355 1 0 1 1 0 0 +EDGE2 2995 716 0.0638162 1.02392 1.57746 1 0 1 1 0 0 +EDGE2 2996 2475 -0.941609 0.0576019 -1.59887 1 0 1 1 0 0 +EDGE2 2996 2995 -1.01634 -0.0318256 -1.58698 1 0 1 1 0 0 +EDGE2 2996 715 -1.03561 -0.0778693 1.57806 1 0 1 1 0 0 +EDGE2 2996 735 -0.954327 0.00679992 1.57553 1 0 1 1 0 0 +EDGE2 2996 1215 -1.06475 0.0617618 1.57264 1 0 1 1 0 0 +EDGE2 2996 1216 0.0143244 -0.0508912 -0.0333426 1 0 1 1 0 0 +EDGE2 2996 2476 -0.0681407 0.00596185 0.0368517 1 0 1 1 0 0 +EDGE2 2996 716 -0.0435213 -0.00531762 -0.0109826 1 0 1 1 0 0 +EDGE2 2996 1217 1.06564 -0.0310203 0.0201625 1 0 1 1 0 0 +EDGE2 2996 2477 1.06159 -0.0315091 -0.0112805 1 0 1 1 0 0 +EDGE2 2996 717 0.891772 -0.0518953 0.016819 1 0 1 1 0 0 +EDGE2 2997 1218 1.0202 -0.00393007 -0.0131606 1 0 1 1 0 0 +EDGE2 2997 1216 -1.02206 0.0199202 -0.0139157 1 0 1 1 0 0 +EDGE2 2997 2996 -0.952428 0.00401698 -0.0157803 1 0 1 1 0 0 +EDGE2 2997 2476 -0.888395 -0.0156303 -0.0223204 1 0 1 1 0 0 +EDGE2 2997 716 -1.04511 0.083744 0.0204726 1 0 1 1 0 0 +EDGE2 2997 1217 -0.0223571 0.0972733 -0.011717 1 0 1 1 0 0 +EDGE2 2997 2477 -0.0711285 -0.0443573 0.0351297 1 0 1 1 0 0 +EDGE2 2997 717 0.0249348 0.0131455 0.0136187 1 0 1 1 0 0 +EDGE2 2997 2478 0.944487 0.0109848 0.0147786 1 0 1 1 0 0 +EDGE2 2997 718 0.988129 0.0106763 0.0174175 1 0 1 1 0 0 +EDGE2 2998 1218 -0.00741426 -0.0303703 0.0212009 1 0 1 1 0 0 +EDGE2 2998 1217 -0.930623 -0.0071607 0.0149068 1 0 1 1 0 0 +EDGE2 2998 2477 -0.908158 0.0110458 -0.0512573 1 0 1 1 0 0 +EDGE2 2998 2997 -1.00708 -0.106064 0.0179294 1 0 1 1 0 0 +EDGE2 2998 717 -1.04348 0.132058 0.00409695 1 0 1 1 0 0 +EDGE2 2998 2478 0.0726735 0.00621832 -0.0504767 1 0 1 1 0 0 +EDGE2 2998 2479 1.03547 -0.054466 0.00171704 1 0 1 1 0 0 +EDGE2 2998 718 -0.0561726 -0.0790469 0.0140764 1 0 1 1 0 0 +EDGE2 2998 719 0.950598 0.0642266 0.00420602 1 0 1 1 0 0 +EDGE2 2998 1219 1.0126 -0.0702074 0.0296794 1 0 1 1 0 0 +EDGE2 2999 1218 -0.942357 -0.0358591 0.0180106 1 0 1 1 0 0 +EDGE2 2999 2998 -0.965776 0.0177975 -0.00664199 1 0 1 1 0 0 +EDGE2 2999 2478 -1.04371 0.0472838 -0.0131212 1 0 1 1 0 0 +EDGE2 2999 2479 0.0626572 0.0382045 -0.0102864 1 0 1 1 0 0 +EDGE2 2999 718 -0.965579 -0.0188711 0.00168208 1 0 1 1 0 0 +EDGE2 2999 719 -0.0533325 0.00526094 0.0372521 1 0 1 1 0 0 +EDGE2 2999 1219 -0.059329 0.0112557 0.00357799 1 0 1 1 0 0 +EDGE2 2999 1220 1.07552 0.0672971 0.0129958 1 0 1 1 0 0 +EDGE2 2999 2480 1.07676 -0.00219251 -0.00681745 1 0 1 1 0 0 +EDGE2 2999 2980 0.978283 -0.0216878 -3.11104 1 0 1 1 0 0 +EDGE2 2999 720 1.00535 0.027087 -0.0256432 1 0 1 1 0 0 +EDGE2 3000 2479 -1.08787 -0.0581847 -0.000855104 1 0 1 1 0 0 +EDGE2 3000 2999 -0.945374 0.0266075 -0.00127226 1 0 1 1 0 0 +EDGE2 3000 719 -0.971905 -0.134418 -0.0240752 1 0 1 1 0 0 +EDGE2 3000 1219 -1.0547 -0.000995709 -0.0180703 1 0 1 1 0 0 +EDGE2 3000 1221 -0.0751389 1.01639 1.5764 1 0 1 1 0 0 +EDGE2 3000 2981 0.0553605 0.955844 1.60637 1 0 1 1 0 0 +EDGE2 3000 2481 -0.0304038 0.957899 1.54985 1 0 1 1 0 0 +EDGE2 3000 1220 -0.0211391 -0.00143202 0.0164482 1 0 1 1 0 0 +EDGE2 3000 2480 0.0333199 -2.17313e-05 0.00313527 1 0 1 1 0 0 +EDGE2 3000 2980 0.00160022 -0.0077093 -3.14221 1 0 1 1 0 0 +EDGE2 3000 720 -0.0498871 0.010654 -0.0264937 1 0 1 1 0 0 +EDGE2 3000 721 0.0155534 -1.05458 -1.56579 1 0 1 1 0 0 +EDGE2 3000 2979 1.07946 0.0189748 -3.13839 1 0 1 1 0 0 +EDGE2 3001 3000 -0.970364 0.0390948 1.56367 1 0 1 1 0 0 +EDGE2 3001 1220 -0.932438 0.0203891 1.59142 1 0 1 1 0 0 +EDGE2 3001 2480 -1.11368 0.00941788 1.57159 1 0 1 1 0 0 +EDGE2 3001 2980 -1.04957 0.015487 -1.5467 1 0 1 1 0 0 +EDGE2 3001 720 -0.906632 0.0831996 1.57119 1 0 1 1 0 0 +EDGE2 3001 721 -0.00958457 -0.0258596 -0.00590877 1 0 1 1 0 0 +EDGE2 3001 722 0.943166 0.010489 -0.0192446 1 0 1 1 0 0 +EDGE2 3002 721 -1.04697 0.014135 0.0370294 1 0 1 1 0 0 +EDGE2 3002 3001 -1.07006 -0.004012 0.0194263 1 0 1 1 0 0 +EDGE2 3002 722 0.0381852 0.0551108 -0.00826952 1 0 1 1 0 0 +EDGE2 3002 723 0.934573 0.0107997 -0.0280165 1 0 1 1 0 0 +EDGE2 3003 722 -0.926559 -0.050759 0.0058013 1 0 1 1 0 0 +EDGE2 3003 3002 -0.966427 -0.0128488 0.023717 1 0 1 1 0 0 +EDGE2 3003 723 0.0459304 0.0181003 0.0138475 1 0 1 1 0 0 +EDGE2 3003 724 0.945078 -0.0410549 -0.00238971 1 0 1 1 0 0 +EDGE2 3004 723 -0.900565 -0.0110797 -0.0156058 1 0 1 1 0 0 +EDGE2 3004 3003 -1.0728 0.0158079 0.0437759 1 0 1 1 0 0 +EDGE2 3004 724 -0.0307314 0.071833 0.0166535 1 0 1 1 0 0 +EDGE2 3004 725 0.976231 -0.00428851 -0.000656556 1 0 1 1 0 0 +EDGE2 3005 3004 -0.910654 0.0210975 -0.0051522 1 0 1 1 0 0 +EDGE2 3005 724 -1.07236 0.123306 0.025438 1 0 1 1 0 0 +EDGE2 3005 726 -0.0751737 -1.06131 -1.57343 1 0 1 1 0 0 +EDGE2 3005 725 -0.0433134 -0.033679 -0.00757534 1 0 1 1 0 0 +EDGE2 3006 3005 -0.940868 0.00786502 -1.56248 1 0 1 1 0 0 +EDGE2 3006 725 -0.920567 -0.0669809 -1.58441 1 0 1 1 0 0 +EDGE2 3007 3006 -1.07555 -0.00352454 0.00474254 1 0 1 1 0 0 +EDGE2 3008 3007 -1.03329 0.0567766 0.0228827 1 0 1 1 0 0 +EDGE2 3009 3008 -0.993541 0.0811547 -0.00168831 1 0 1 1 0 0 +EDGE2 3009 2970 1.03768 0.0175723 -3.1348 1 0 1 1 0 0 +EDGE2 3009 2710 0.972921 0.00199252 -3.1531 1 0 1 1 0 0 +EDGE2 3010 2971 0.0910232 1.0502 1.55207 1 0 1 1 0 0 +EDGE2 3010 2711 0.0036063 -1.03154 -1.58285 1 0 1 1 0 0 +EDGE2 3010 3009 -0.978903 0.106241 0.0140117 1 0 1 1 0 0 +EDGE2 3010 2970 -0.0532269 0.0376889 -3.14206 1 0 1 1 0 0 +EDGE2 3010 2710 0.0210543 -0.104886 -3.11943 1 0 1 1 0 0 +EDGE2 3010 2969 1.0117 -0.0313888 -3.13982 1 0 1 1 0 0 +EDGE2 3010 2709 1.10139 0.0312487 -3.16626 1 0 1 1 0 0 +EDGE2 3011 2711 -0.0554414 -0.00659599 -0.0330832 1 0 1 1 0 0 +EDGE2 3011 2970 -1.06734 0.00693016 -1.56899 1 0 1 1 0 0 +EDGE2 3011 3010 -1.01223 -0.0546669 1.56554 1 0 1 1 0 0 +EDGE2 3011 2710 -1.03761 -0.0951105 -1.56875 1 0 1 1 0 0 +EDGE2 3011 2712 1.02993 -0.0348107 0.0180301 1 0 1 1 0 0 +EDGE2 3012 2711 -1.11015 -0.0579153 -0.0063849 1 0 1 1 0 0 +EDGE2 3012 3011 -0.98772 0.0491739 0.0120515 1 0 1 1 0 0 +EDGE2 3012 2713 0.898232 -0.0771773 0.0157382 1 0 1 1 0 0 +EDGE2 3012 2712 -0.00888998 -0.0365752 0.013859 1 0 1 1 0 0 +EDGE2 3013 3012 -1.08384 -0.0757696 0.0011411 1 0 1 1 0 0 +EDGE2 3013 2713 0.0962081 0.0176468 0.0151051 1 0 1 1 0 0 +EDGE2 3013 2712 -1.03565 -0.021054 -0.000138214 1 0 1 1 0 0 +EDGE2 3013 2714 1.00671 -0.0475124 0.0154536 1 0 1 1 0 0 +EDGE2 3014 2713 -1.01046 0.0368207 0.0166691 1 0 1 1 0 0 +EDGE2 3014 3013 -0.936591 -0.0242373 -0.0109794 1 0 1 1 0 0 +EDGE2 3014 2714 0.032063 -0.00461632 -0.000831744 1 0 1 1 0 0 +EDGE2 3014 2715 1.01889 0.00237127 0.0184801 1 0 1 1 0 0 +EDGE2 3015 3014 -1.01102 -0.0268967 -0.00109612 1 0 1 1 0 0 +EDGE2 3015 2714 -1.02813 -0.00481809 -0.00775035 1 0 1 1 0 0 +EDGE2 3015 2715 0.0512543 -0.0558038 0.0372279 1 0 1 1 0 0 +EDGE2 3015 2716 -0.0302486 0.980367 1.56262 1 0 1 1 0 0 +EDGE2 3016 2715 -1.08376 0.008975 1.58876 1 0 1 1 0 0 +EDGE2 3016 3015 -0.950477 0.0334934 1.56757 1 0 1 1 0 0 +EDGE2 3017 3016 -1.01763 0.0166361 0.00403119 1 0 1 1 0 0 +EDGE2 3018 3017 -1.08026 -0.00639789 0.0274569 1 0 1 1 0 0 +EDGE2 3019 3018 -1.01656 0.0170746 0.0251582 1 0 1 1 0 0 +EDGE2 3020 3019 -1.01679 0.0889718 -0.0249108 1 0 1 1 0 0 +EDGE2 3021 3020 -1.01848 0.0635242 -1.53638 1 0 1 1 0 0 +EDGE2 3022 3021 -0.974258 0.0270379 0.0141198 1 0 1 1 0 0 +EDGE2 3023 3022 -0.936524 -0.0455733 -0.0154358 1 0 1 1 0 0 +EDGE2 3024 3023 -0.996641 0.0549542 0.0396778 1 0 1 1 0 0 +EDGE2 3024 1145 0.958959 -0.075931 -3.11939 1 0 1 1 0 0 +EDGE2 3024 1105 1.05518 0.118973 -3.15608 1 0 1 1 0 0 +EDGE2 3024 1125 0.940629 0.101413 -3.15687 1 0 1 1 0 0 +EDGE2 3025 3024 -0.948498 0.105046 0.0253832 1 0 1 1 0 0 +EDGE2 3025 1126 0.00229494 -1.00854 -1.57175 1 0 1 1 0 0 +EDGE2 3025 1146 0.0203731 -0.985815 -1.55734 1 0 1 1 0 0 +EDGE2 3025 1106 -0.0559122 -1.01172 -1.59606 1 0 1 1 0 0 +EDGE2 3025 1145 -0.0307698 0.0433806 -3.11036 1 0 1 1 0 0 +EDGE2 3025 1105 -0.0584529 0.0142135 -3.16337 1 0 1 1 0 0 +EDGE2 3025 1125 -0.0269773 -0.0882034 -3.16319 1 0 1 1 0 0 +EDGE2 3025 1124 0.992632 0.00265282 -3.15708 1 0 1 1 0 0 +EDGE2 3025 1144 0.95812 0.00900659 -3.12534 1 0 1 1 0 0 +EDGE2 3025 1104 0.991977 -0.0929787 -3.11324 1 0 1 1 0 0 +EDGE2 3026 1127 1.03137 -0.0398058 0.00789779 1 0 1 1 0 0 +EDGE2 3026 1147 1.11049 -0.00890326 0.0469691 1 0 1 1 0 0 +EDGE2 3026 1107 1.06865 -0.0408514 0.0296323 1 0 1 1 0 0 +EDGE2 3026 1126 -0.0182843 -0.0937893 0.000671907 1 0 1 1 0 0 +EDGE2 3026 1146 0.037332 0.0157403 -0.0167679 1 0 1 1 0 0 +EDGE2 3026 1106 -0.0434545 0.0373401 -0.0227535 1 0 1 1 0 0 +EDGE2 3026 1145 -1.06445 -0.041733 -1.57721 1 0 1 1 0 0 +EDGE2 3026 3025 -0.921199 -0.00855994 1.60159 1 0 1 1 0 0 +EDGE2 3026 1105 -0.946273 0.0349951 -1.55934 1 0 1 1 0 0 +EDGE2 3026 1125 -0.961007 -0.0295282 -1.59542 1 0 1 1 0 0 +EDGE2 3027 1108 0.97122 0.022018 0.00643691 1 0 1 1 0 0 +EDGE2 3027 1128 1.00667 -0.038186 -0.00264715 1 0 1 1 0 0 +EDGE2 3027 1148 0.965113 0.0330072 0.000492431 1 0 1 1 0 0 +EDGE2 3027 1127 -0.0401249 0.00445944 0.0110771 1 0 1 1 0 0 +EDGE2 3027 1147 -0.0189302 0.00289255 0.030296 1 0 1 1 0 0 +EDGE2 3027 1107 -0.0265539 0.00305582 -0.0295926 1 0 1 1 0 0 +EDGE2 3027 1126 -1.0301 0.0617673 0.038068 1 0 1 1 0 0 +EDGE2 3027 1146 -1.02229 0.0742934 0.0142172 1 0 1 1 0 0 +EDGE2 3027 3026 -1.01344 -0.0704517 0.00877678 1 0 1 1 0 0 +EDGE2 3027 1106 -1.06383 0.0237514 -0.00143748 1 0 1 1 0 0 +EDGE2 3028 3027 -1.01606 0.00961975 0.0312049 1 0 1 1 0 0 +EDGE2 3028 1109 0.992087 0.0193695 -0.00544837 1 0 1 1 0 0 +EDGE2 3028 1149 1.10727 0.0449172 -0.00938622 1 0 1 1 0 0 +EDGE2 3028 1129 1.02886 0.0259063 0.00469324 1 0 1 1 0 0 +EDGE2 3028 1108 0.0434811 0.109746 -0.0111086 1 0 1 1 0 0 +EDGE2 3028 1128 0.0108384 0.0640043 -0.00148589 1 0 1 1 0 0 +EDGE2 3028 1148 -0.0874228 -0.142528 -0.0144574 1 0 1 1 0 0 +EDGE2 3028 1127 -0.94142 0.0804724 0.0158853 1 0 1 1 0 0 +EDGE2 3028 1147 -0.976798 0.0166828 -0.0167575 1 0 1 1 0 0 +EDGE2 3028 1107 -1.03252 -0.0607155 0.0121523 1 0 1 1 0 0 +EDGE2 3029 1130 1.02307 0.080497 0.0104859 1 0 1 1 0 0 +EDGE2 3029 1170 1.025 -0.0364355 -3.16989 1 0 1 1 0 0 +EDGE2 3029 1190 0.982196 -0.0173291 -3.14333 1 0 1 1 0 0 +EDGE2 3029 1150 0.911636 0.00383781 -0.0100091 1 0 1 1 0 0 +EDGE2 3029 1110 0.966245 -0.0197439 0.0136581 1 0 1 1 0 0 +EDGE2 3029 1109 -0.056035 -0.124386 -0.0250635 1 0 1 1 0 0 +EDGE2 3029 1149 -0.0411742 -0.099841 -0.0176898 1 0 1 1 0 0 +EDGE2 3029 1129 0.0688077 0.0454851 0.0136251 1 0 1 1 0 0 +EDGE2 3029 3028 -0.930716 -0.0256022 0.0356338 1 0 1 1 0 0 +EDGE2 3029 1108 -1.0204 -0.0442699 -0.0134383 1 0 1 1 0 0 +EDGE2 3029 1128 -0.956482 0.0525291 0.00177363 1 0 1 1 0 0 +EDGE2 3029 1148 -0.950985 -0.0312642 0.0101702 1 0 1 1 0 0 +EDGE2 3030 1189 1.07355 0.0194019 -3.12452 1 0 1 1 0 0 +EDGE2 3030 1169 1.02606 -0.0615475 -3.13698 1 0 1 1 0 0 +EDGE2 3030 1151 0.0799935 -0.989183 -1.58253 1 0 1 1 0 0 +EDGE2 3030 1191 -0.0312989 -0.920208 -1.58607 1 0 1 1 0 0 +EDGE2 3030 1171 0.103334 -0.995922 -1.56703 1 0 1 1 0 0 +EDGE2 3030 1130 -0.0989277 0.0347078 -0.00174717 1 0 1 1 0 0 +EDGE2 3030 1170 0.0154297 -0.0537736 -3.1399 1 0 1 1 0 0 +EDGE2 3030 1190 -0.054923 0.0713489 -3.14041 1 0 1 1 0 0 +EDGE2 3030 1150 -0.0564035 0.00866644 -0.0139717 1 0 1 1 0 0 +EDGE2 3030 1110 0.0529487 0.0609084 -0.05178 1 0 1 1 0 0 +EDGE2 3030 1109 -1.05853 0.0947883 0.00143972 1 0 1 1 0 0 +EDGE2 3030 1149 -1.01001 -0.00960997 -0.0172492 1 0 1 1 0 0 +EDGE2 3030 3029 -0.960184 -0.0114166 -0.00732516 1 0 1 1 0 0 +EDGE2 3030 1129 -1.02719 -0.0420713 0.008058 1 0 1 1 0 0 +EDGE2 3030 1111 -0.0172615 0.930544 1.57182 1 0 1 1 0 0 +EDGE2 3030 1131 -0.0543723 0.943043 1.5565 1 0 1 1 0 0 +EDGE2 3031 1130 -0.926169 -0.013916 -1.57334 1 0 1 1 0 0 +EDGE2 3031 1170 -0.991083 0.0083878 1.59524 1 0 1 1 0 0 +EDGE2 3031 1190 -0.91769 -0.0839155 1.57421 1 0 1 1 0 0 +EDGE2 3031 3030 -1.03258 -0.0204639 -1.54369 1 0 1 1 0 0 +EDGE2 3031 1150 -0.956633 0.0199194 -1.56545 1 0 1 1 0 0 +EDGE2 3031 1110 -0.969713 0.0186837 -1.59361 1 0 1 1 0 0 +EDGE2 3031 1111 -0.035923 0.0171136 0.0309078 1 0 1 1 0 0 +EDGE2 3031 1131 -0.0284761 0.0601778 -0.0158699 1 0 1 1 0 0 +EDGE2 3031 1112 0.920335 -0.024117 -0.00517051 1 0 1 1 0 0 +EDGE2 3031 1132 0.973888 -0.01516 0.0096882 1 0 1 1 0 0 +EDGE2 3032 1133 1.03529 -0.0581342 0.0169889 1 0 1 1 0 0 +EDGE2 3032 1111 -0.988244 -0.0050378 0.0375078 1 0 1 1 0 0 +EDGE2 3032 3031 -1.00995 -0.0184763 0.00501308 1 0 1 1 0 0 +EDGE2 3032 1131 -0.954285 0.0513803 -0.0182644 1 0 1 1 0 0 +EDGE2 3032 1112 0.0351917 -0.048659 -0.0476235 1 0 1 1 0 0 +EDGE2 3032 1132 0.00649837 0.0228879 -0.0174001 1 0 1 1 0 0 +EDGE2 3032 1113 1.03809 -0.0572665 0.0115441 1 0 1 1 0 0 +EDGE2 3033 1133 -0.0273256 0.00514117 0.00238762 1 0 1 1 0 0 +EDGE2 3033 1112 -1.02375 -0.0824306 -0.00923655 1 0 1 1 0 0 +EDGE2 3033 1132 -1.04422 -0.0553036 -0.0259745 1 0 1 1 0 0 +EDGE2 3033 3032 -0.986625 -0.0541856 0.0129546 1 0 1 1 0 0 +EDGE2 3033 1113 0.089249 0.0146094 0.00243683 1 0 1 1 0 0 +EDGE2 3033 1134 0.8738 0.00366726 -0.00386231 1 0 1 1 0 0 +EDGE2 3033 1114 0.971513 0.0155876 0.0187715 1 0 1 1 0 0 +EDGE2 3034 1133 -1.05737 0.0655713 0.00878763 1 0 1 1 0 0 +EDGE2 3034 3033 -0.984425 -0.0246621 -0.00454266 1 0 1 1 0 0 +EDGE2 3034 1113 -0.958127 0.0101675 0.0153759 1 0 1 1 0 0 +EDGE2 3034 1134 0.00592006 -0.0226095 0.0249702 1 0 1 1 0 0 +EDGE2 3034 1114 -0.0555375 0.0405396 0.0519164 1 0 1 1 0 0 +EDGE2 3034 1095 1.03824 -0.061426 -3.1739 1 0 1 1 0 0 +EDGE2 3034 1115 1.013 0.0329315 -0.0328165 1 0 1 1 0 0 +EDGE2 3034 1135 1.00438 0.0656325 -0.0375591 1 0 1 1 0 0 +EDGE2 3035 1134 -0.995914 -0.0622661 0.0247458 1 0 1 1 0 0 +EDGE2 3035 3034 -0.992855 -0.0407167 0.00553797 1 0 1 1 0 0 +EDGE2 3035 1114 -1.03607 0.0644346 -0.00475213 1 0 1 1 0 0 +EDGE2 3035 1095 0.0247148 -0.0142478 -3.13264 1 0 1 1 0 0 +EDGE2 3035 1115 -0.0940664 -0.00448047 -0.0149803 1 0 1 1 0 0 +EDGE2 3035 1135 0.0194213 0.0505606 0.00661287 1 0 1 1 0 0 +EDGE2 3035 1094 0.992018 0.067869 -3.12983 1 0 1 1 0 0 +EDGE2 3035 1116 0.0034206 1.01887 1.59424 1 0 1 1 0 0 +EDGE2 3035 1136 0.0271305 1.06483 1.55289 1 0 1 1 0 0 +EDGE2 3035 1096 -0.0450623 0.986557 1.55379 1 0 1 1 0 0 +EDGE2 3036 3035 -0.943682 0.00344364 -1.56498 1 0 1 1 0 0 +EDGE2 3036 1095 -0.950639 -0.00113082 1.56313 1 0 1 1 0 0 +EDGE2 3036 1115 -1.04945 -0.0311628 -1.55741 1 0 1 1 0 0 +EDGE2 3036 1135 -1.01956 -0.0308525 -1.57632 1 0 1 1 0 0 +EDGE2 3036 1116 0.0115861 0.0166542 -0.0374681 1 0 1 1 0 0 +EDGE2 3036 1136 -0.003378 -0.00660252 0.00998471 1 0 1 1 0 0 +EDGE2 3036 1096 -0.0971154 0.00147977 0.00974298 1 0 1 1 0 0 +EDGE2 3036 1097 1.01259 -0.0169534 0.0114596 1 0 1 1 0 0 +EDGE2 3036 1137 1.00084 -0.0608885 0.0214782 1 0 1 1 0 0 +EDGE2 3036 1117 1.06279 0.0100864 0.0338176 1 0 1 1 0 0 +EDGE2 3037 1118 0.913343 0.171759 -0.00548669 1 0 1 1 0 0 +EDGE2 3037 1116 -1.00352 -0.00129986 -0.00827908 1 0 1 1 0 0 +EDGE2 3037 3036 -1.04868 -0.146269 0.0161135 1 0 1 1 0 0 +EDGE2 3037 1136 -0.979257 0.0190304 0.0117248 1 0 1 1 0 0 +EDGE2 3037 1096 -0.977299 0.0624026 0.000146092 1 0 1 1 0 0 +EDGE2 3037 1097 -0.055762 0.0126061 -0.0321432 1 0 1 1 0 0 +EDGE2 3037 1137 0.116418 0.0969026 -0.00352059 1 0 1 1 0 0 +EDGE2 3037 1117 0.0413382 0.00745999 -0.00820869 1 0 1 1 0 0 +EDGE2 3037 1138 1.04695 0.0884059 0.00559548 1 0 1 1 0 0 +EDGE2 3037 1098 1.01743 0.024671 0.00369346 1 0 1 1 0 0 +EDGE2 3038 1118 0.00833734 0.0202703 -0.0033879 1 0 1 1 0 0 +EDGE2 3038 1097 -1.06053 0.0302997 0.0103746 1 0 1 1 0 0 +EDGE2 3038 1137 -1.05113 0.00275842 0.00112728 1 0 1 1 0 0 +EDGE2 3038 3037 -0.987792 0.017904 0.011696 1 0 1 1 0 0 +EDGE2 3038 1117 -1.05238 -0.0458971 -0.0144852 1 0 1 1 0 0 +EDGE2 3038 1138 -0.0236947 0.0939479 0.000980925 1 0 1 1 0 0 +EDGE2 3038 1139 1.01738 0.00692462 -0.0193465 1 0 1 1 0 0 +EDGE2 3038 1098 -0.0289555 -0.03229 0.0151101 1 0 1 1 0 0 +EDGE2 3038 1099 1.06213 0.125886 0.0188851 1 0 1 1 0 0 +EDGE2 3038 1119 0.96639 -0.084607 -0.00697897 1 0 1 1 0 0 +EDGE2 3039 1118 -0.933203 -0.00613918 -0.0121601 1 0 1 1 0 0 +EDGE2 3039 3038 -1.00058 0.0220854 0.0165631 1 0 1 1 0 0 +EDGE2 3039 1138 -1.01358 0.00517974 0.00848251 1 0 1 1 0 0 +EDGE2 3039 1139 -0.0783548 0.0181574 0.00510571 1 0 1 1 0 0 +EDGE2 3039 1098 -1.01 -0.0803538 -0.0210851 1 0 1 1 0 0 +EDGE2 3039 1099 0.0233326 -0.0578746 0.0161111 1 0 1 1 0 0 +EDGE2 3039 1119 0.0364307 -0.0216498 0.0071773 1 0 1 1 0 0 +EDGE2 3039 1100 0.938892 0.0379198 -0.0137158 1 0 1 1 0 0 +EDGE2 3039 1140 0.891884 0.0448667 -0.0267833 1 0 1 1 0 0 +EDGE2 3039 1120 1.00671 -0.0511669 -0.00322735 1 0 1 1 0 0 +EDGE2 3040 1139 -0.915607 -0.157333 -0.0199085 1 0 1 1 0 0 +EDGE2 3040 3039 -1.01996 0.0955717 -0.0308285 1 0 1 1 0 0 +EDGE2 3040 1099 -1.06218 -0.0387013 0.00814607 1 0 1 1 0 0 +EDGE2 3040 1119 -0.943697 0.0450158 -0.0286627 1 0 1 1 0 0 +EDGE2 3040 1121 -0.0271248 0.998826 1.56559 1 0 1 1 0 0 +EDGE2 3040 1141 0.0798918 0.97973 1.56867 1 0 1 1 0 0 +EDGE2 3040 1101 0.0162454 0.968702 1.56241 1 0 1 1 0 0 +EDGE2 3040 1100 -0.0925779 -0.107701 0.0193537 1 0 1 1 0 0 +EDGE2 3040 1140 -0.0219881 -0.112834 0.001821 1 0 1 1 0 0 +EDGE2 3040 1120 0.0202719 0.0669435 -0.00114757 1 0 1 1 0 0 +EDGE2 3041 1102 0.941072 0.00827445 -0.000884906 1 0 1 1 0 0 +EDGE2 3041 1122 0.923364 -0.0322121 -0.0126002 1 0 1 1 0 0 +EDGE2 3041 1142 1.04774 0.0626599 -0.0310314 1 0 1 1 0 0 +EDGE2 3041 1121 0.0061249 0.0556035 0.00802587 1 0 1 1 0 0 +EDGE2 3041 1141 0.054407 -0.0579178 0.038057 1 0 1 1 0 0 +EDGE2 3041 1101 0.0831065 0.016773 -0.00547449 1 0 1 1 0 0 +EDGE2 3041 1100 -0.996203 -0.0614387 -1.54939 1 0 1 1 0 0 +EDGE2 3041 1140 -0.929613 0.029144 -1.55437 1 0 1 1 0 0 +EDGE2 3041 3040 -1.03999 0.0136908 -1.54129 1 0 1 1 0 0 +EDGE2 3041 1120 -0.903231 0.0383318 -1.57591 1 0 1 1 0 0 +EDGE2 3042 1123 0.955002 -0.0135247 -0.0271201 1 0 1 1 0 0 +EDGE2 3042 1143 0.95209 -0.00492564 0.0292776 1 0 1 1 0 0 +EDGE2 3042 1103 1.07625 0.00996055 -0.024951 1 0 1 1 0 0 +EDGE2 3042 1102 0.0282877 -0.0177352 0.0147878 1 0 1 1 0 0 +EDGE2 3042 1122 0.0295316 -0.00949979 0.00294016 1 0 1 1 0 0 +EDGE2 3042 1142 0.0564411 0.0219371 0.00900578 1 0 1 1 0 0 +EDGE2 3042 1121 -0.968302 -0.0774542 0.015376 1 0 1 1 0 0 +EDGE2 3042 3041 -0.977207 -0.0885745 -0.0525154 1 0 1 1 0 0 +EDGE2 3042 1141 -1.07351 -0.00615756 0.00159596 1 0 1 1 0 0 +EDGE2 3042 1101 -0.940546 -0.0158752 0.0096927 1 0 1 1 0 0 +EDGE2 3043 1123 -0.101711 0.0708582 -0.0230766 1 0 1 1 0 0 +EDGE2 3043 1124 0.980849 -0.141808 0.0279212 1 0 1 1 0 0 +EDGE2 3043 1144 1.02661 -0.0362528 -0.0180885 1 0 1 1 0 0 +EDGE2 3043 1104 0.927611 0.00070537 0.0182644 1 0 1 1 0 0 +EDGE2 3043 1143 0.0909508 0.0243546 0.0124911 1 0 1 1 0 0 +EDGE2 3043 3042 -1.00401 -0.0534109 -0.000894919 1 0 1 1 0 0 +EDGE2 3043 1103 0.0475418 0.0749784 -0.00566595 1 0 1 1 0 0 +EDGE2 3043 1102 -1.03308 -0.0351153 -0.0252307 1 0 1 1 0 0 +EDGE2 3043 1122 -0.936251 -0.0348272 0.0109609 1 0 1 1 0 0 +EDGE2 3043 1142 -1.00134 -0.0160903 -0.00856194 1 0 1 1 0 0 +EDGE2 3044 1123 -0.923962 0.0464861 0.0167357 1 0 1 1 0 0 +EDGE2 3044 1145 1.02829 -0.0276495 -0.0242865 1 0 1 1 0 0 +EDGE2 3044 3025 0.997016 0.0618451 -3.14788 1 0 1 1 0 0 +EDGE2 3044 1105 0.969383 0.00746806 -0.0148558 1 0 1 1 0 0 +EDGE2 3044 1125 0.894565 -0.0204959 -0.00428417 1 0 1 1 0 0 +EDGE2 3044 1124 -0.0365584 0.0558826 0.000283918 1 0 1 1 0 0 +EDGE2 3044 1144 -0.0507787 -0.0329003 0.0128126 1 0 1 1 0 0 +EDGE2 3044 1104 0.0495668 -0.0649814 -0.00614168 1 0 1 1 0 0 +EDGE2 3044 3043 -1.08739 0.060256 0.0059947 1 0 1 1 0 0 +EDGE2 3044 1143 -1.0402 0.0443378 -0.00851128 1 0 1 1 0 0 +EDGE2 3044 1103 -0.926203 0.0971324 0.00901822 1 0 1 1 0 0 +EDGE2 3045 3024 1.03107 -0.094264 -3.13176 1 0 1 1 0 0 +EDGE2 3045 1126 -0.0797879 1.06583 1.57273 1 0 1 1 0 0 +EDGE2 3045 1146 -0.0931442 0.892092 1.57756 1 0 1 1 0 0 +EDGE2 3045 3026 0.0421663 0.934193 1.56713 1 0 1 1 0 0 +EDGE2 3045 1106 -0.00316886 1.02842 1.56626 1 0 1 1 0 0 +EDGE2 3045 1145 0.0527308 0.0389432 -0.0159946 1 0 1 1 0 0 +EDGE2 3045 3025 0.00310333 0.0130284 -3.10767 1 0 1 1 0 0 +EDGE2 3045 1105 -0.0417517 0.0078191 -0.00241868 1 0 1 1 0 0 +EDGE2 3045 1125 -0.00578996 0.0306426 0.00255877 1 0 1 1 0 0 +EDGE2 3045 1124 -1.00567 0.025366 -0.00446876 1 0 1 1 0 0 +EDGE2 3045 1144 -1.06079 0.0394709 -0.0103026 1 0 1 1 0 0 +EDGE2 3045 3044 -1.02779 0.0152199 0.00332287 1 0 1 1 0 0 +EDGE2 3045 1104 -1.05586 -0.0036673 -0.00183993 1 0 1 1 0 0 +EDGE2 3046 3027 0.931649 0.0232815 0.0148592 1 0 1 1 0 0 +EDGE2 3046 1127 1.00939 -0.0478597 -0.0127127 1 0 1 1 0 0 +EDGE2 3046 1147 0.985608 0.0228137 -0.0330828 1 0 1 1 0 0 +EDGE2 3046 1107 1.00143 -0.0238286 0.0507098 1 0 1 1 0 0 +EDGE2 3046 1126 -0.0190279 0.0200303 0.011226 1 0 1 1 0 0 +EDGE2 3046 1146 -0.050372 -0.0259231 -0.0222308 1 0 1 1 0 0 +EDGE2 3046 3026 -0.0819688 -0.00591529 -0.0524055 1 0 1 1 0 0 +EDGE2 3046 1106 -0.0372199 0.0259981 -0.0296387 1 0 1 1 0 0 +EDGE2 3046 1145 -1.05053 0.111102 -1.54124 1 0 1 1 0 0 +EDGE2 3046 3045 -0.931801 -0.00578687 -1.54055 1 0 1 1 0 0 +EDGE2 3046 3025 -0.963522 -0.0837599 1.60731 1 0 1 1 0 0 +EDGE2 3046 1105 -1.00683 -0.0952923 -1.57284 1 0 1 1 0 0 +EDGE2 3046 1125 -0.978598 0.00162579 -1.5626 1 0 1 1 0 0 +EDGE2 3047 3027 0.0293434 -0.0954219 0.00195066 1 0 1 1 0 0 +EDGE2 3047 3028 0.954288 0.0804789 -0.0041118 1 0 1 1 0 0 +EDGE2 3047 1108 1.02399 -0.0313828 -0.00353867 1 0 1 1 0 0 +EDGE2 3047 1128 0.936387 0.0144999 0.00755603 1 0 1 1 0 0 +EDGE2 3047 1148 1.04036 -0.00394177 0.0131154 1 0 1 1 0 0 +EDGE2 3047 1127 0.0666253 0.0826049 0.0215742 1 0 1 1 0 0 +EDGE2 3047 1147 -0.0446211 -0.0620548 0.00678971 1 0 1 1 0 0 +EDGE2 3047 1107 0.0624248 -0.027588 0.0488496 1 0 1 1 0 0 +EDGE2 3047 3046 -0.983005 -0.0530968 -0.0139265 1 0 1 1 0 0 +EDGE2 3047 1126 -1.08875 -0.0169969 0.014706 1 0 1 1 0 0 +EDGE2 3047 1146 -1.01092 0.0209277 0.00363206 1 0 1 1 0 0 +EDGE2 3047 3026 -1.03433 -0.0271508 0.000765307 1 0 1 1 0 0 +EDGE2 3047 1106 -0.954907 0.104141 0.00961525 1 0 1 1 0 0 +EDGE2 3048 3027 -1.06178 0.123787 0.00564543 1 0 1 1 0 0 +EDGE2 3048 1109 1.06216 0.00231239 -0.0170026 1 0 1 1 0 0 +EDGE2 3048 1149 1.02728 0.0216549 0.0115311 1 0 1 1 0 0 +EDGE2 3048 3029 0.949445 -0.0327039 0.00306034 1 0 1 1 0 0 +EDGE2 3048 1129 1.00193 0.0345762 -0.0424645 1 0 1 1 0 0 +EDGE2 3048 3028 0.044621 -0.0628231 -0.0382556 1 0 1 1 0 0 +EDGE2 3048 1108 -0.00446849 0.066222 0.00243661 1 0 1 1 0 0 +EDGE2 3048 1128 -0.0267004 -0.0133563 0.00505134 1 0 1 1 0 0 +EDGE2 3048 1148 0.000123704 -0.0503782 -0.0061395 1 0 1 1 0 0 +EDGE2 3048 3047 -0.941857 0.0506452 -0.0111052 1 0 1 1 0 0 +EDGE2 3048 1127 -0.973012 0.0446646 -0.0179873 1 0 1 1 0 0 +EDGE2 3048 1147 -0.99394 0.0311895 -0.0114004 1 0 1 1 0 0 +EDGE2 3048 1107 -0.940662 0.00448364 0.0101174 1 0 1 1 0 0 +EDGE2 3049 3048 -1.01133 -0.0613064 0.017419 1 0 1 1 0 0 +EDGE2 3049 1130 1.03821 0.0240507 -0.00612849 1 0 1 1 0 0 +EDGE2 3049 1170 0.974529 -0.0730865 -3.13641 1 0 1 1 0 0 +EDGE2 3049 1190 0.999947 -0.0159061 -3.18167 1 0 1 1 0 0 +EDGE2 3049 3030 1.01889 0.0243157 -0.0125411 1 0 1 1 0 0 +EDGE2 3049 1150 1.08435 -0.000939947 0.0222907 1 0 1 1 0 0 +EDGE2 3049 1110 0.85182 -0.00786729 -0.0134298 1 0 1 1 0 0 +EDGE2 3049 1109 -0.0169135 0.0568976 0.0152168 1 0 1 1 0 0 +EDGE2 3049 1149 -0.0204933 0.0501573 0.00800148 1 0 1 1 0 0 +EDGE2 3049 3029 -0.0436801 0.0343764 -0.0255111 1 0 1 1 0 0 +EDGE2 3049 1129 0.0186647 0.0201051 -0.0142306 1 0 1 1 0 0 +EDGE2 3049 3028 -0.992892 -0.060413 0.0151696 1 0 1 1 0 0 +EDGE2 3049 1108 -0.997731 -0.114532 -0.00293117 1 0 1 1 0 0 +EDGE2 3049 1128 -0.988346 0.0295333 -0.0373603 1 0 1 1 0 0 +EDGE2 3049 1148 -0.956656 0.0569556 0.0312369 1 0 1 1 0 0 +EDGE2 3050 1189 0.907336 -0.0261852 -3.15024 1 0 1 1 0 0 +EDGE2 3050 1169 1.02196 -0.036589 -3.12289 1 0 1 1 0 0 +EDGE2 3050 1151 0.00703949 -1.00116 -1.5521 1 0 1 1 0 0 +EDGE2 3050 1191 0.0384241 -0.914757 -1.60836 1 0 1 1 0 0 +EDGE2 3050 1171 -0.00419981 -1.00208 -1.5745 1 0 1 1 0 0 +EDGE2 3050 1130 -0.0110157 0.0130926 0.00642257 1 0 1 1 0 0 +EDGE2 3050 1170 0.0142484 0.105089 -3.13312 1 0 1 1 0 0 +EDGE2 3050 1190 -0.0276418 -0.0343393 -3.15331 1 0 1 1 0 0 +EDGE2 3050 3030 0.150505 0.0305083 0.0171566 1 0 1 1 0 0 +EDGE2 3050 1150 0.0518698 0.00521375 -0.00629201 1 0 1 1 0 0 +EDGE2 3050 1110 0.0197152 0.0354796 0.00174329 1 0 1 1 0 0 +EDGE2 3050 1109 -1.08833 0.00657179 -0.00122882 1 0 1 1 0 0 +EDGE2 3050 1149 -1.0203 0.000211895 0.0147669 1 0 1 1 0 0 +EDGE2 3050 3029 -1.06916 0.0236663 0.0167017 1 0 1 1 0 0 +EDGE2 3050 3049 -1.08707 0.0486816 0.0378709 1 0 1 1 0 0 +EDGE2 3050 1129 -0.965557 0.0187485 -0.00513664 1 0 1 1 0 0 +EDGE2 3050 1111 0.0258097 0.987083 1.59481 1 0 1 1 0 0 +EDGE2 3050 3031 0.0285446 0.987164 1.59095 1 0 1 1 0 0 +EDGE2 3050 1131 0.0399016 0.907097 1.60407 1 0 1 1 0 0 +EDGE2 3051 3050 -0.929472 -0.0268906 -1.57063 1 0 1 1 0 0 +EDGE2 3051 1130 -0.887784 -0.0184884 -1.57322 1 0 1 1 0 0 +EDGE2 3051 1170 -1.02938 0.0434284 1.54776 1 0 1 1 0 0 +EDGE2 3051 1190 -1.03515 -0.0236514 1.57857 1 0 1 1 0 0 +EDGE2 3051 3030 -0.995408 0.023199 -1.56166 1 0 1 1 0 0 +EDGE2 3051 1150 -1.03099 0.0241611 -1.5823 1 0 1 1 0 0 +EDGE2 3051 1110 -1.04448 0.0414822 -1.54892 1 0 1 1 0 0 +EDGE2 3051 1111 0.0224559 -0.100209 0.0398612 1 0 1 1 0 0 +EDGE2 3051 3031 -0.0137583 -0.0345416 0.0382984 1 0 1 1 0 0 +EDGE2 3051 1131 -0.0573054 0.077299 0.00926393 1 0 1 1 0 0 +EDGE2 3051 1112 1.01864 -0.0782976 0.00265154 1 0 1 1 0 0 +EDGE2 3051 1132 1.05969 -0.00368827 -0.00563579 1 0 1 1 0 0 +EDGE2 3051 3032 0.993763 0.0557244 0.00888461 1 0 1 1 0 0 +EDGE2 3052 1133 1.01171 -0.0627118 0.00184686 1 0 1 1 0 0 +EDGE2 3052 1111 -1.04052 -0.0596161 -0.0204038 1 0 1 1 0 0 +EDGE2 3052 3031 -0.961055 0.0707214 -0.00240476 1 0 1 1 0 0 +EDGE2 3052 3051 -0.982148 0.0381141 -0.0035873 1 0 1 1 0 0 +EDGE2 3052 1131 -0.97948 0.00424638 -0.0125643 1 0 1 1 0 0 +EDGE2 3052 1112 0.017259 0.0251287 -0.0164603 1 0 1 1 0 0 +EDGE2 3052 1132 -0.0459052 -0.0575499 0.0205798 1 0 1 1 0 0 +EDGE2 3052 3032 -0.0410573 0.00642054 0.0257655 1 0 1 1 0 0 +EDGE2 3052 3033 1.06462 0.0143937 -0.0287579 1 0 1 1 0 0 +EDGE2 3052 1113 1.03293 0.0151466 -0.00350994 1 0 1 1 0 0 +EDGE2 3053 1133 -0.0166371 -0.0600402 0.00641114 1 0 1 1 0 0 +EDGE2 3053 3052 -1.0093 0.0511757 0.0209041 1 0 1 1 0 0 +EDGE2 3053 1112 -1.03548 -0.0229691 0.00335094 1 0 1 1 0 0 +EDGE2 3053 1132 -0.979215 -0.0472439 0.0175405 1 0 1 1 0 0 +EDGE2 3053 3032 -0.928356 0.0347027 0.0280918 1 0 1 1 0 0 +EDGE2 3053 3033 -0.0141581 -0.0384506 -0.00706249 1 0 1 1 0 0 +EDGE2 3053 1113 0.0505106 0.00781498 -0.0203566 1 0 1 1 0 0 +EDGE2 3053 1134 0.98365 0.0179661 -0.0062283 1 0 1 1 0 0 +EDGE2 3053 3034 0.962421 0.0887399 -0.0162772 1 0 1 1 0 0 +EDGE2 3053 1114 1.03771 -0.0423763 -0.00499591 1 0 1 1 0 0 +EDGE2 3054 1133 -0.995445 0.00650677 -0.00464462 1 0 1 1 0 0 +EDGE2 3054 3053 -0.872707 0.0318457 0.0170987 1 0 1 1 0 0 +EDGE2 3054 3033 -0.939588 0.0213138 0.0334317 1 0 1 1 0 0 +EDGE2 3054 1113 -1.01416 0.0667424 -0.012847 1 0 1 1 0 0 +EDGE2 3054 1134 -0.0785369 -0.0129207 -0.00335702 1 0 1 1 0 0 +EDGE2 3054 3034 -0.0344365 -0.0345169 0.00538518 1 0 1 1 0 0 +EDGE2 3054 1114 0.0830661 -0.0469926 0.00775827 1 0 1 1 0 0 +EDGE2 3054 3035 1.01856 0.0549326 0.0414228 1 0 1 1 0 0 +EDGE2 3054 1095 0.971292 0.0793856 -3.17255 1 0 1 1 0 0 +EDGE2 3054 1115 1.01968 -0.0318833 -0.0157224 1 0 1 1 0 0 +EDGE2 3054 1135 0.964816 -0.033129 0.0195645 1 0 1 1 0 0 +EDGE2 3055 1134 -0.90444 -0.0101049 0.00941255 1 0 1 1 0 0 +EDGE2 3055 3034 -1.04677 0.0260393 -0.0253518 1 0 1 1 0 0 +EDGE2 3055 3054 -0.947398 0.0146088 -0.00950881 1 0 1 1 0 0 +EDGE2 3055 1114 -0.993721 -0.127413 0.0303606 1 0 1 1 0 0 +EDGE2 3055 3035 -0.0412391 -0.01819 0.027046 1 0 1 1 0 0 +EDGE2 3055 1095 0.0746111 0.0137486 -3.14428 1 0 1 1 0 0 +EDGE2 3055 1115 -0.0418029 0.022969 0.00480275 1 0 1 1 0 0 +EDGE2 3055 1135 -0.000388307 -0.0438026 0.0184036 1 0 1 1 0 0 +EDGE2 3055 1094 1.01414 -0.0143486 -3.1114 1 0 1 1 0 0 +EDGE2 3055 1116 -0.0635885 0.93638 1.55228 1 0 1 1 0 0 +EDGE2 3055 3036 -0.0882334 1.04 1.54494 1 0 1 1 0 0 +EDGE2 3055 1136 0.0232598 1.00729 1.59815 1 0 1 1 0 0 +EDGE2 3055 1096 0.00918463 0.973042 1.56274 1 0 1 1 0 0 +EDGE2 3056 3035 -0.949349 0.0838519 1.54512 1 0 1 1 0 0 +EDGE2 3056 3055 -0.907032 -0.0918042 1.58088 1 0 1 1 0 0 +EDGE2 3056 1095 -1.01211 0.0370418 -1.61987 1 0 1 1 0 0 +EDGE2 3056 1115 -0.972966 0.0287545 1.57429 1 0 1 1 0 0 +EDGE2 3056 1135 -0.960953 -0.0143981 1.60274 1 0 1 1 0 0 +EDGE2 3057 3056 -1.06661 -0.013874 0.0180635 1 0 1 1 0 0 +EDGE2 3058 3057 -0.986596 0.0479624 -0.0227862 1 0 1 1 0 0 +EDGE2 3059 1080 0.93044 0.0493226 -3.12715 1 0 1 1 0 0 +EDGE2 3059 3058 -1.03958 -0.0167875 0.00515353 1 0 1 1 0 0 +EDGE2 3060 1079 0.922252 0.102731 -3.12377 1 0 1 1 0 0 +EDGE2 3060 1080 -0.0363129 0.0723394 -3.16701 1 0 1 1 0 0 +EDGE2 3060 1081 -0.00397575 1.02455 1.55777 1 0 1 1 0 0 +EDGE2 3060 3059 -1.03734 0.0334322 -0.00375644 1 0 1 1 0 0 +EDGE2 3061 3060 -0.982859 -0.0253789 1.60079 1 0 1 1 0 0 +EDGE2 3061 1080 -1.1742 -0.0880958 -1.59741 1 0 1 1 0 0 +EDGE2 3062 3061 -1.05326 0.0176529 0.00989325 1 0 1 1 0 0 +EDGE2 3063 3062 -0.991883 -0.112389 0.00458893 1 0 1 1 0 0 +EDGE2 3064 1185 1.05249 -0.00161844 -3.14966 1 0 1 1 0 0 +EDGE2 3064 1165 0.991516 0.0255964 -3.12518 1 0 1 1 0 0 +EDGE2 3064 3063 -1.02205 0.000183535 0.00969213 1 0 1 1 0 0 +EDGE2 3065 1184 0.971234 0.00657272 -3.13331 1 0 1 1 0 0 +EDGE2 3065 1164 1.06237 -0.0244457 -3.11398 1 0 1 1 0 0 +EDGE2 3065 1185 0.0487287 0.018083 -3.15695 1 0 1 1 0 0 +EDGE2 3065 1165 0.004775 -0.0558089 -3.16052 1 0 1 1 0 0 +EDGE2 3065 1166 -0.000866551 -1.03729 -1.57429 1 0 1 1 0 0 +EDGE2 3065 1186 0.0238252 -0.979933 -1.55301 1 0 1 1 0 0 +EDGE2 3065 3064 -0.952247 0.0136743 0.0262571 1 0 1 1 0 0 +EDGE2 3066 1185 -0.998104 -0.067982 1.58078 1 0 1 1 0 0 +EDGE2 3066 3065 -1.00378 0.00370588 -1.56311 1 0 1 1 0 0 +EDGE2 3066 1165 -0.957218 0.137314 1.56517 1 0 1 1 0 0 +EDGE2 3067 3066 -1.04554 -0.0455984 0.00181002 1 0 1 1 0 0 +EDGE2 3068 3067 -1.03629 -0.0225694 -0.0112732 1 0 1 1 0 0 +EDGE2 3069 3068 -1.14145 -0.0274715 -0.00422502 1 0 1 1 0 0 +EDGE2 3070 3069 -0.990038 0.0433292 -0.0266733 1 0 1 1 0 0 +EDGE2 3071 3070 -1.05515 0.0288407 -1.55305 1 0 1 1 0 0 +EDGE2 3072 3071 -1.01408 0.0447685 0.0184456 1 0 1 1 0 0 +EDGE2 3073 3072 -0.933699 0.00325745 -0.0244789 1 0 1 1 0 0 +EDGE2 3074 3073 -1.01554 0.0662405 0.0176512 1 0 1 1 0 0 +EDGE2 3074 1075 1.0582 -0.032731 -3.15791 1 0 1 1 0 0 +EDGE2 3074 995 1.07019 -0.122672 -3.17142 1 0 1 1 0 0 +EDGE2 3074 1015 0.947527 0.0395685 -3.16644 1 0 1 1 0 0 +EDGE2 3074 1055 0.972434 0.0712253 -3.13018 1 0 1 1 0 0 +EDGE2 3075 1016 -0.0939885 -1.02189 -1.58643 1 0 1 1 0 0 +EDGE2 3075 1056 -0.00570426 -0.997424 -1.57788 1 0 1 1 0 0 +EDGE2 3075 996 0.000892714 -0.936181 -1.5564 1 0 1 1 0 0 +EDGE2 3075 1075 0.0979365 0.00454591 -3.15741 1 0 1 1 0 0 +EDGE2 3075 3074 -1.02234 -0.0428226 0.0228957 1 0 1 1 0 0 +EDGE2 3075 1074 1.00911 0.063424 -3.16981 1 0 1 1 0 0 +EDGE2 3075 995 0.0480369 0.0177481 -3.12808 1 0 1 1 0 0 +EDGE2 3075 1015 -0.0632225 -0.100562 -3.18505 1 0 1 1 0 0 +EDGE2 3075 1055 -0.00177064 -0.00923196 -3.1613 1 0 1 1 0 0 +EDGE2 3075 1014 1.03358 -0.00631783 -3.13787 1 0 1 1 0 0 +EDGE2 3075 1054 0.995886 0.00552966 -3.1388 1 0 1 1 0 0 +EDGE2 3075 994 1.01632 -0.0121724 -3.15791 1 0 1 1 0 0 +EDGE2 3075 1076 -0.012837 0.880157 1.60011 1 0 1 1 0 0 +EDGE2 3076 1075 -1.03816 0.0343503 1.57745 1 0 1 1 0 0 +EDGE2 3076 3075 -1.07147 0.0607068 -1.58258 1 0 1 1 0 0 +EDGE2 3076 995 -1.02278 0.0205818 1.58905 1 0 1 1 0 0 +EDGE2 3076 1015 -0.98268 -0.0520369 1.57206 1 0 1 1 0 0 +EDGE2 3076 1055 -1.06595 0.00125687 1.57512 1 0 1 1 0 0 +EDGE2 3076 1076 0.0393627 0.0393579 0.0288406 1 0 1 1 0 0 +EDGE2 3076 1077 0.973985 -0.0151443 -0.0352255 1 0 1 1 0 0 +EDGE2 3077 1076 -1.07871 -0.0649345 0.0153581 1 0 1 1 0 0 +EDGE2 3077 3076 -0.996853 0.0504884 -0.0450311 1 0 1 1 0 0 +EDGE2 3077 1077 -0.0544632 -0.0381383 -0.020975 1 0 1 1 0 0 +EDGE2 3077 1078 0.990311 0.0634147 -0.0187642 1 0 1 1 0 0 +EDGE2 3078 3077 -0.961825 -0.0592251 -0.00651113 1 0 1 1 0 0 +EDGE2 3078 1077 -0.983057 -0.0504397 0.00888394 1 0 1 1 0 0 +EDGE2 3078 1078 0.0354869 -0.0189248 -0.0201116 1 0 1 1 0 0 +EDGE2 3078 1079 1.00075 0.0202722 -0.0022245 1 0 1 1 0 0 +EDGE2 3079 3078 -1.15634 0.0481887 0.0239994 1 0 1 1 0 0 +EDGE2 3079 1078 -0.967949 0.0088668 -0.00835549 1 0 1 1 0 0 +EDGE2 3079 1079 -0.0257471 0.0573683 -0.00744324 1 0 1 1 0 0 +EDGE2 3079 3060 0.96373 0.0129559 -3.11748 1 0 1 1 0 0 +EDGE2 3079 1080 0.977529 0.0666756 -0.00560202 1 0 1 1 0 0 +EDGE2 3080 3079 -0.962157 -0.00954427 -0.0055359 1 0 1 1 0 0 +EDGE2 3080 1079 -1.05165 -0.0172264 -0.00937576 1 0 1 1 0 0 +EDGE2 3080 3061 0.00518387 0.961291 1.5444 1 0 1 1 0 0 +EDGE2 3080 3060 -0.051656 0.0878918 -3.11979 1 0 1 1 0 0 +EDGE2 3080 1080 0.0483772 0.0257315 -0.0254003 1 0 1 1 0 0 +EDGE2 3080 1081 -0.0354921 -1.09603 -1.56753 1 0 1 1 0 0 +EDGE2 3080 3059 1.03806 -0.0116176 -3.16304 1 0 1 1 0 0 +EDGE2 3081 3062 0.908235 -0.0204881 -0.00465949 1 0 1 1 0 0 +EDGE2 3081 3061 0.0778428 0.071087 0.00963098 1 0 1 1 0 0 +EDGE2 3081 3060 -0.964848 0.0681388 1.54691 1 0 1 1 0 0 +EDGE2 3081 3080 -0.993092 0.00296588 -1.54091 1 0 1 1 0 0 +EDGE2 3081 1080 -1.01936 -0.0105286 -1.59033 1 0 1 1 0 0 +EDGE2 3082 3063 1.05857 -0.0179526 -0.0220565 1 0 1 1 0 0 +EDGE2 3082 3062 -0.0502157 -0.0402329 -0.00810283 1 0 1 1 0 0 +EDGE2 3082 3081 -0.949449 0.102054 -0.0394733 1 0 1 1 0 0 +EDGE2 3082 3061 -1.00963 -0.0739814 0.00133532 1 0 1 1 0 0 +EDGE2 3083 3064 1.07548 -0.12363 0.0127331 1 0 1 1 0 0 +EDGE2 3083 3063 -0.0645456 -0.0294034 -0.0236175 1 0 1 1 0 0 +EDGE2 3083 3082 -0.939647 0.00418103 0.0118391 1 0 1 1 0 0 +EDGE2 3083 3062 -0.945673 -0.0686039 -0.0153612 1 0 1 1 0 0 +EDGE2 3084 1185 1.03937 0.0823574 -3.16213 1 0 1 1 0 0 +EDGE2 3084 3065 0.995251 0.0400534 -0.00131486 1 0 1 1 0 0 +EDGE2 3084 1165 1.06595 -0.0109416 -3.12011 1 0 1 1 0 0 +EDGE2 3084 3064 0.0226156 0.0191445 -0.00250575 1 0 1 1 0 0 +EDGE2 3084 3083 -1.14263 0.00153724 0.0245211 1 0 1 1 0 0 +EDGE2 3084 3063 -0.929305 0.0218044 -0.0216038 1 0 1 1 0 0 +EDGE2 3085 3066 0.0584401 1.01096 1.57694 1 0 1 1 0 0 +EDGE2 3085 1184 0.956698 -0.0730364 -3.14658 1 0 1 1 0 0 +EDGE2 3085 1164 1.03531 -0.022675 -3.15656 1 0 1 1 0 0 +EDGE2 3085 1185 -0.125735 -0.0121206 -3.12547 1 0 1 1 0 0 +EDGE2 3085 3065 -0.109075 0.0488535 0.00165341 1 0 1 1 0 0 +EDGE2 3085 1165 0.0234139 -0.0528743 -3.13836 1 0 1 1 0 0 +EDGE2 3085 1166 0.0121511 -1.0671 -1.58327 1 0 1 1 0 0 +EDGE2 3085 1186 -0.0512145 -0.999007 -1.56723 1 0 1 1 0 0 +EDGE2 3085 3064 -1.04069 0.0751321 0.0098982 1 0 1 1 0 0 +EDGE2 3085 3084 -1.01173 0.0778597 0.0153192 1 0 1 1 0 0 +EDGE2 3086 1185 -1.03327 0.0622625 -1.58851 1 0 1 1 0 0 +EDGE2 3086 3065 -0.912883 0.0410579 1.56493 1 0 1 1 0 0 +EDGE2 3086 3085 -0.990909 -0.0200502 1.56618 1 0 1 1 0 0 +EDGE2 3086 1165 -1.04352 0.0132367 -1.56699 1 0 1 1 0 0 +EDGE2 3086 1166 0.0497577 0.103831 0.0275584 1 0 1 1 0 0 +EDGE2 3086 1186 -0.0138452 -0.0476211 -0.0128129 1 0 1 1 0 0 +EDGE2 3086 1187 1.02685 -0.0567486 -0.00488534 1 0 1 1 0 0 +EDGE2 3086 1167 1.0033 -0.0166434 -0.00706148 1 0 1 1 0 0 +EDGE2 3087 1166 -0.982151 0.0577116 0.0141313 1 0 1 1 0 0 +EDGE2 3087 3086 -1.04528 -0.0153892 0.021 1 0 1 1 0 0 +EDGE2 3087 1186 -0.997216 -0.0228266 -0.0286856 1 0 1 1 0 0 +EDGE2 3087 1187 0.0344595 -0.0271008 0.00961052 1 0 1 1 0 0 +EDGE2 3087 1167 0.0613774 -0.0349328 0.00203929 1 0 1 1 0 0 +EDGE2 3087 1188 1.05952 0.081305 -0.00248445 1 0 1 1 0 0 +EDGE2 3087 1168 1.02251 -0.106995 -0.0104205 1 0 1 1 0 0 +EDGE2 3088 1187 -0.944603 0.0647825 0.0305684 1 0 1 1 0 0 +EDGE2 3088 3087 -0.943021 -0.131267 0.00297872 1 0 1 1 0 0 +EDGE2 3088 1167 -1.08958 0.00376819 -0.00189263 1 0 1 1 0 0 +EDGE2 3088 1188 0.0238703 0.0520689 0.00269522 1 0 1 1 0 0 +EDGE2 3088 1168 0.0468054 0.0281949 0.00379947 1 0 1 1 0 0 +EDGE2 3088 1189 1.00914 -0.0122049 -0.0133469 1 0 1 1 0 0 +EDGE2 3088 1169 0.945222 -0.0224847 -0.0149405 1 0 1 1 0 0 +EDGE2 3089 1188 -1.08753 -0.0125554 0.00890468 1 0 1 1 0 0 +EDGE2 3089 3088 -0.988818 0.02186 -0.0292773 1 0 1 1 0 0 +EDGE2 3089 1168 -0.891667 -0.00646317 0.0321589 1 0 1 1 0 0 +EDGE2 3089 1189 0.0713228 -0.0046697 -0.00182478 1 0 1 1 0 0 +EDGE2 3089 1169 -0.0358539 -0.0459424 0.00741328 1 0 1 1 0 0 +EDGE2 3089 3050 0.948253 -0.0259816 -3.15324 1 0 1 1 0 0 +EDGE2 3089 1130 1.00633 -0.0443162 -3.15367 1 0 1 1 0 0 +EDGE2 3089 1170 0.977161 0.0560428 -0.00645488 1 0 1 1 0 0 +EDGE2 3089 1190 0.97369 0.0272884 0.00718913 1 0 1 1 0 0 +EDGE2 3089 3030 1.03638 -0.00568189 -3.13726 1 0 1 1 0 0 +EDGE2 3089 1150 0.958167 -0.00908655 -3.14167 1 0 1 1 0 0 +EDGE2 3089 1110 0.971926 -0.0289642 -3.14134 1 0 1 1 0 0 +EDGE2 3090 1189 -0.983949 -0.0540241 -0.00447386 1 0 1 1 0 0 +EDGE2 3090 3089 -0.986 -0.00464262 -0.00241532 1 0 1 1 0 0 +EDGE2 3090 1169 -1.00153 0.0261406 0.0202546 1 0 1 1 0 0 +EDGE2 3090 3050 0.0235286 -0.0573071 -3.15086 1 0 1 1 0 0 +EDGE2 3090 1151 -0.0720398 0.939191 1.61869 1 0 1 1 0 0 +EDGE2 3090 1191 0.0151244 1.02651 1.57241 1 0 1 1 0 0 +EDGE2 3090 1171 0.0169334 0.950568 1.55419 1 0 1 1 0 0 +EDGE2 3090 1130 0.0613071 0.00755717 -3.16163 1 0 1 1 0 0 +EDGE2 3090 1170 -0.0329842 -0.0229571 -0.00415748 1 0 1 1 0 0 +EDGE2 3090 1190 -0.0374228 0.104288 -0.0257372 1 0 1 1 0 0 +EDGE2 3090 3030 0.026719 -0.0073156 -3.12728 1 0 1 1 0 0 +EDGE2 3090 1150 0.0115748 -0.0638332 -3.17123 1 0 1 1 0 0 +EDGE2 3090 1110 0.0156724 0.0141394 -3.13864 1 0 1 1 0 0 +EDGE2 3090 1109 0.968427 -0.0304632 -3.15037 1 0 1 1 0 0 +EDGE2 3090 1149 1.08495 0.0222814 -3.13562 1 0 1 1 0 0 +EDGE2 3090 3029 0.997198 0.00913949 -3.13038 1 0 1 1 0 0 +EDGE2 3090 3049 1.04249 0.0634668 -3.1546 1 0 1 1 0 0 +EDGE2 3090 1129 1.04306 0.0347154 -3.08768 1 0 1 1 0 0 +EDGE2 3090 1111 0.0888144 -1.01669 -1.57659 1 0 1 1 0 0 +EDGE2 3090 3031 0.0537517 -1.0464 -1.56164 1 0 1 1 0 0 +EDGE2 3090 3051 -0.0445354 -0.966857 -1.54511 1 0 1 1 0 0 +EDGE2 3090 1131 0.0643418 -0.992834 -1.56856 1 0 1 1 0 0 +EDGE2 3091 3050 -0.973147 0.00231955 1.54196 1 0 1 1 0 0 +EDGE2 3091 1152 0.919673 -0.0539116 0.000668497 1 0 1 1 0 0 +EDGE2 3091 1172 1.04979 0.0293151 0.00119683 1 0 1 1 0 0 +EDGE2 3091 1192 1.08903 0.00504847 0.00919581 1 0 1 1 0 0 +EDGE2 3091 1151 0.0196515 -0.0622991 -0.0238993 1 0 1 1 0 0 +EDGE2 3091 1191 -0.0193521 -0.0724525 0.0052227 1 0 1 1 0 0 +EDGE2 3091 1171 0.0101395 -0.0908025 0.0261026 1 0 1 1 0 0 +EDGE2 3091 3090 -0.992857 -0.00567414 -1.56459 1 0 1 1 0 0 +EDGE2 3091 1130 -0.982068 0.0328963 1.62158 1 0 1 1 0 0 +EDGE2 3091 1170 -1.02475 -0.0344746 -1.54575 1 0 1 1 0 0 +EDGE2 3091 1190 -1.05605 -0.0345832 -1.55905 1 0 1 1 0 0 +EDGE2 3091 3030 -1.00994 -0.146858 1.58788 1 0 1 1 0 0 +EDGE2 3091 1150 -0.937668 -0.0535759 1.59031 1 0 1 1 0 0 +EDGE2 3091 1110 -0.941538 -0.0296928 1.58517 1 0 1 1 0 0 +EDGE2 3092 1173 1.04187 -0.0453905 0.0345811 1 0 1 1 0 0 +EDGE2 3092 1193 1.04771 0.0527588 -0.00960301 1 0 1 1 0 0 +EDGE2 3092 1153 1.01885 0.0653837 0.0434027 1 0 1 1 0 0 +EDGE2 3092 1152 0.000507847 0.0631582 0.00262897 1 0 1 1 0 0 +EDGE2 3092 1172 0.0507785 -0.0723196 0.013071 1 0 1 1 0 0 +EDGE2 3092 1192 -0.0721027 0.0105713 0.0368106 1 0 1 1 0 0 +EDGE2 3092 1151 -0.917731 0.0874933 -0.00955853 1 0 1 1 0 0 +EDGE2 3092 1191 -0.984866 -0.0458646 0.0214391 1 0 1 1 0 0 +EDGE2 3092 3091 -0.960647 0.00334207 0.0400716 1 0 1 1 0 0 +EDGE2 3092 1171 -0.966117 0.0474042 -0.00636561 1 0 1 1 0 0 +EDGE2 3093 1173 0.0127896 0.0684499 -0.046234 1 0 1 1 0 0 +EDGE2 3093 1174 0.997359 0.0443933 0.0125676 1 0 1 1 0 0 +EDGE2 3093 1194 0.930885 -0.0319788 -0.0166502 1 0 1 1 0 0 +EDGE2 3093 1154 0.958345 -0.0492887 -0.0177245 1 0 1 1 0 0 +EDGE2 3093 1193 0.101082 -0.087233 -0.0133721 1 0 1 1 0 0 +EDGE2 3093 3092 -1.00262 -0.0814731 0.0345821 1 0 1 1 0 0 +EDGE2 3093 1153 -0.0144257 -0.0285359 -0.00664043 1 0 1 1 0 0 +EDGE2 3093 1152 -0.945754 0.0457133 -0.00710289 1 0 1 1 0 0 +EDGE2 3093 1172 -0.956576 0.0537581 0.0210936 1 0 1 1 0 0 +EDGE2 3093 1192 -0.971015 -0.025433 0.0173016 1 0 1 1 0 0 +EDGE2 3094 1173 -1.00776 -0.0236531 0.00839544 1 0 1 1 0 0 +EDGE2 3094 1174 0.0155291 0.0214868 0.00727392 1 0 1 1 0 0 +EDGE2 3094 1175 1.02692 0.0285956 0.00428951 1 0 1 1 0 0 +EDGE2 3094 1195 1.03906 0.0819442 0.011957 1 0 1 1 0 0 +EDGE2 3094 1155 1.02924 0.0319121 -0.0256019 1 0 1 1 0 0 +EDGE2 3094 1194 -0.0638625 -0.0155844 0.01286 1 0 1 1 0 0 +EDGE2 3094 1154 -0.0268734 -0.000196428 0.012275 1 0 1 1 0 0 +EDGE2 3094 3093 -0.942989 0.0423255 -0.0342887 1 0 1 1 0 0 +EDGE2 3094 1193 -0.981437 0.0485802 0.0295484 1 0 1 1 0 0 +EDGE2 3094 1153 -0.987842 -0.0551509 -0.0127895 1 0 1 1 0 0 +EDGE2 3095 1196 0.157542 1.04339 1.62332 1 0 1 1 0 0 +EDGE2 3095 1156 0.0367188 1.00409 1.56244 1 0 1 1 0 0 +EDGE2 3095 1176 0.0318854 1.04486 1.57642 1 0 1 1 0 0 +EDGE2 3095 1174 -0.979463 0.121318 -0.00653829 1 0 1 1 0 0 +EDGE2 3095 1175 -0.00592488 0.0678059 -0.00164637 1 0 1 1 0 0 +EDGE2 3095 1195 0.131512 0.083671 0.0202998 1 0 1 1 0 0 +EDGE2 3095 1155 0.012923 -0.00253917 -0.0414224 1 0 1 1 0 0 +EDGE2 3095 3094 -0.887939 -0.0434667 -0.0296108 1 0 1 1 0 0 +EDGE2 3095 1194 -0.96251 0.0125372 -0.00459349 1 0 1 1 0 0 +EDGE2 3095 1154 -1.04258 0.0367397 0.0340782 1 0 1 1 0 0 +EDGE2 3096 1197 1.01868 -0.0592238 -0.0259912 1 0 1 1 0 0 +EDGE2 3096 1177 0.959479 0.0569005 0.0141631 1 0 1 1 0 0 +EDGE2 3096 1157 0.996794 -0.0551485 0.00533833 1 0 1 1 0 0 +EDGE2 3096 1196 0.103331 -0.0243821 -0.0232058 1 0 1 1 0 0 +EDGE2 3096 1156 0.006658 0.115092 -0.0212321 1 0 1 1 0 0 +EDGE2 3096 1176 -0.0413561 0.035 -0.00514409 1 0 1 1 0 0 +EDGE2 3096 1175 -0.990101 0.0305886 -1.60162 1 0 1 1 0 0 +EDGE2 3096 1195 -0.934368 0.0138232 -1.60028 1 0 1 1 0 0 +EDGE2 3096 3095 -0.981758 -0.0163301 -1.59405 1 0 1 1 0 0 +EDGE2 3096 1155 -0.998028 0.0136409 -1.57209 1 0 1 1 0 0 +EDGE2 3097 1197 -0.0340608 0.0173635 0.00585798 1 0 1 1 0 0 +EDGE2 3097 1178 1.02572 0.0458067 -0.000303534 1 0 1 1 0 0 +EDGE2 3097 1198 1.02689 -0.0213581 -0.0319302 1 0 1 1 0 0 +EDGE2 3097 1158 0.995624 0.00821438 0.0342216 1 0 1 1 0 0 +EDGE2 3097 1177 0.0211894 -0.0636039 -0.029161 1 0 1 1 0 0 +EDGE2 3097 1157 -0.000246507 0.053405 -0.0179707 1 0 1 1 0 0 +EDGE2 3097 1196 -1.08107 0.0752563 -0.0149464 1 0 1 1 0 0 +EDGE2 3097 3096 -1.03899 -0.0735089 0.0109537 1 0 1 1 0 0 +EDGE2 3097 1156 -0.947963 -0.0129169 -0.0251517 1 0 1 1 0 0 +EDGE2 3097 1176 -1.02882 0.127374 -0.00741876 1 0 1 1 0 0 +EDGE2 3098 1197 -1.05286 -0.0110063 0.00394602 1 0 1 1 0 0 +EDGE2 3098 1179 1.03032 -0.0516505 -0.0124396 1 0 1 1 0 0 +EDGE2 3098 1199 0.992759 0.0764537 -0.0236857 1 0 1 1 0 0 +EDGE2 3098 1159 1.07088 0.0686631 0.0306746 1 0 1 1 0 0 +EDGE2 3098 1178 0.0203425 0.0139172 -0.019894 1 0 1 1 0 0 +EDGE2 3098 1198 0.0247953 -0.0414587 -0.00180047 1 0 1 1 0 0 +EDGE2 3098 1158 -0.0564859 -0.0407519 -0.0160513 1 0 1 1 0 0 +EDGE2 3098 3097 -1.00423 0.0612533 -0.00593049 1 0 1 1 0 0 +EDGE2 3098 1177 -0.95643 -0.0137584 -0.0207416 1 0 1 1 0 0 +EDGE2 3098 1157 -1.05822 -0.0301033 -0.0553781 1 0 1 1 0 0 +EDGE2 3099 1160 0.967946 -0.0187009 -0.00580507 1 0 1 1 0 0 +EDGE2 3099 1200 0.961129 -0.00556012 0.0067149 1 0 1 1 0 0 +EDGE2 3099 1180 1.02275 0.03005 0.0234468 1 0 1 1 0 0 +EDGE2 3099 900 0.986857 0.100114 -3.1364 1 0 1 1 0 0 +EDGE2 3099 840 1.06132 0.0715917 -3.13392 1 0 1 1 0 0 +EDGE2 3099 860 1.07397 -0.0445559 -3.13754 1 0 1 1 0 0 +EDGE2 3099 1179 0.0238751 -0.123462 0.0237994 1 0 1 1 0 0 +EDGE2 3099 1199 -0.00763695 0.0567786 -0.0168996 1 0 1 1 0 0 +EDGE2 3099 1159 -0.0506272 0.000976274 0.00358113 1 0 1 1 0 0 +EDGE2 3099 3098 -0.91725 0.0238662 0.011595 1 0 1 1 0 0 +EDGE2 3099 1178 -0.971156 -0.0126607 -0.00236778 1 0 1 1 0 0 +EDGE2 3099 1198 -0.908378 -0.0138423 -0.0168722 1 0 1 1 0 0 +EDGE2 3099 1158 -0.958229 -0.0571034 0.0160256 1 0 1 1 0 0 +EDGE2 3100 839 0.967302 0.0413415 -3.15963 1 0 1 1 0 0 +EDGE2 3100 899 0.948509 0.00278587 -3.14333 1 0 1 1 0 0 +EDGE2 3100 859 0.93927 0.00161825 -3.14605 1 0 1 1 0 0 +EDGE2 3100 841 -0.0175972 -1.05754 -1.59502 1 0 1 1 0 0 +EDGE2 3100 901 -0.0493852 -1.02522 -1.54245 1 0 1 1 0 0 +EDGE2 3100 1201 -0.0485418 -1.00424 -1.58204 1 0 1 1 0 0 +EDGE2 3100 861 0.00909206 -1.06479 -1.5852 1 0 1 1 0 0 +EDGE2 3100 1160 0.0179405 -0.00403023 -0.0247911 1 0 1 1 0 0 +EDGE2 3100 1200 0.0205007 0.0328038 -0.017107 1 0 1 1 0 0 +EDGE2 3100 1180 0.00285206 0.0255513 0.0131356 1 0 1 1 0 0 +EDGE2 3100 900 0.0330244 0.069159 -3.14706 1 0 1 1 0 0 +EDGE2 3100 840 0.00134377 -0.0210334 -3.12422 1 0 1 1 0 0 +EDGE2 3100 860 0.0345909 -0.0208496 -3.13401 1 0 1 1 0 0 +EDGE2 3100 1161 -0.0561465 1.08427 1.56886 1 0 1 1 0 0 +EDGE2 3100 1181 0.0544678 0.972283 1.57696 1 0 1 1 0 0 +EDGE2 3100 1179 -1.08083 -0.00103398 0.00830417 1 0 1 1 0 0 +EDGE2 3100 1199 -1.05129 -0.106847 0.0176819 1 0 1 1 0 0 +EDGE2 3100 3099 -0.921114 -0.0844277 0.0291092 1 0 1 1 0 0 +EDGE2 3100 1159 -1.07178 0.00818128 0.00429923 1 0 1 1 0 0 +EDGE2 3101 1160 -1.00686 0.0472408 -1.54789 1 0 1 1 0 0 +EDGE2 3101 1200 -1.09627 -0.01425 -1.57171 1 0 1 1 0 0 +EDGE2 3101 3100 -0.995075 -0.0241601 -1.61144 1 0 1 1 0 0 +EDGE2 3101 1180 -0.991038 -0.0872785 -1.55141 1 0 1 1 0 0 +EDGE2 3101 900 -0.980101 0.00512881 1.55635 1 0 1 1 0 0 +EDGE2 3101 840 -1.00377 0.038111 1.57585 1 0 1 1 0 0 +EDGE2 3101 860 -1.10311 0.00330589 1.53871 1 0 1 1 0 0 +EDGE2 3101 1161 -0.0301685 -0.129278 0.000360821 1 0 1 1 0 0 +EDGE2 3101 1181 0.00659722 0.0236773 0.0361325 1 0 1 1 0 0 +EDGE2 3101 1182 0.991317 -0.0132472 -0.000390671 1 0 1 1 0 0 +EDGE2 3101 1162 0.955517 -0.0292355 -0.0227099 1 0 1 1 0 0 +EDGE2 3102 3101 -1.01406 0.0757047 -0.00313844 1 0 1 1 0 0 +EDGE2 3102 1161 -1.0337 -0.051785 -0.0396938 1 0 1 1 0 0 +EDGE2 3102 1181 -0.964465 0.00976594 0.0276291 1 0 1 1 0 0 +EDGE2 3102 1182 0.0508854 0.0304604 0.015852 1 0 1 1 0 0 +EDGE2 3102 1162 -0.0157895 -0.0527391 -0.0181781 1 0 1 1 0 0 +EDGE2 3102 1163 0.97235 0.036975 -0.0142576 1 0 1 1 0 0 +EDGE2 3102 1183 1.10851 -0.0782056 -0.0184999 1 0 1 1 0 0 +EDGE2 3103 1182 -0.966997 -0.052801 0.0124282 1 0 1 1 0 0 +EDGE2 3103 3102 -1.03 0.00747153 0.0102929 1 0 1 1 0 0 +EDGE2 3103 1162 -1.02359 0.0769489 -0.0151316 1 0 1 1 0 0 +EDGE2 3103 1163 0.0198947 0.0668569 0.00218166 1 0 1 1 0 0 +EDGE2 3103 1183 -0.0430412 -0.00961242 -0.00345774 1 0 1 1 0 0 +EDGE2 3103 1184 1.03964 -0.0238375 -0.0123048 1 0 1 1 0 0 +EDGE2 3103 1164 1.01715 -0.0490097 -0.00217706 1 0 1 1 0 0 +EDGE2 3104 1163 -1.11672 -0.0486939 -0.0246394 1 0 1 1 0 0 +EDGE2 3104 3103 -0.946461 0.026732 0.0583211 1 0 1 1 0 0 +EDGE2 3104 1183 -0.995325 0.0126126 0.00525733 1 0 1 1 0 0 +EDGE2 3104 1184 -0.0358379 -0.0433704 0.0370345 1 0 1 1 0 0 +EDGE2 3104 1164 0.0115547 0.0604403 -0.0203125 1 0 1 1 0 0 +EDGE2 3104 1185 1.06496 0.0504441 0.0301483 1 0 1 1 0 0 +EDGE2 3104 3065 0.955799 -0.033706 -3.14383 1 0 1 1 0 0 +EDGE2 3104 3085 1.01886 -0.00980625 -3.1474 1 0 1 1 0 0 +EDGE2 3104 1165 0.949009 -0.0991859 0.00290146 1 0 1 1 0 0 +EDGE2 3105 3066 0.00892546 -1.01649 -1.56762 1 0 1 1 0 0 +EDGE2 3105 1184 -0.976119 0.0286646 0.0324987 1 0 1 1 0 0 +EDGE2 3105 3104 -1.00045 0.00150275 0.00720515 1 0 1 1 0 0 +EDGE2 3105 1164 -0.950768 -0.104465 -0.0273997 1 0 1 1 0 0 +EDGE2 3105 1185 -0.00288628 0.0371622 0.0265641 1 0 1 1 0 0 +EDGE2 3105 3065 0.0409526 -0.0398921 -3.13404 1 0 1 1 0 0 +EDGE2 3105 3085 0.0703875 0.0158603 -3.12538 1 0 1 1 0 0 +EDGE2 3105 1165 -0.0330288 0.0833478 -0.0269459 1 0 1 1 0 0 +EDGE2 3105 1166 0.0229257 0.945512 1.55842 1 0 1 1 0 0 +EDGE2 3105 3086 -0.016235 0.93874 1.56492 1 0 1 1 0 0 +EDGE2 3105 1186 0.033138 0.981097 1.57177 1 0 1 1 0 0 +EDGE2 3105 3064 1.03866 -0.0539031 -3.17394 1 0 1 1 0 0 +EDGE2 3105 3084 1.04229 0.022192 -3.1529 1 0 1 1 0 0 +EDGE2 3106 3105 -0.97019 0.00797012 -1.5645 1 0 1 1 0 0 +EDGE2 3106 1185 -0.986657 0.0177953 -1.59075 1 0 1 1 0 0 +EDGE2 3106 3065 -0.959879 0.0351229 1.59323 1 0 1 1 0 0 +EDGE2 3106 3085 -1.02645 -0.0591773 1.55192 1 0 1 1 0 0 +EDGE2 3106 1165 -1.07284 0.0572691 -1.57462 1 0 1 1 0 0 +EDGE2 3106 1166 0.00863789 -0.0434479 -0.0169679 1 0 1 1 0 0 +EDGE2 3106 3086 -0.0342219 -0.0807856 -0.0183285 1 0 1 1 0 0 +EDGE2 3106 1186 0.0399505 0.0195237 0.0106088 1 0 1 1 0 0 +EDGE2 3106 1187 1.06646 -0.0025929 -0.00420703 1 0 1 1 0 0 +EDGE2 3106 3087 1.0077 0.0623467 0.0497312 1 0 1 1 0 0 +EDGE2 3106 1167 0.953345 -0.0238474 -0.0169691 1 0 1 1 0 0 +EDGE2 3107 1166 -0.94058 0.0021907 0.00906879 1 0 1 1 0 0 +EDGE2 3107 3086 -0.998576 0.0533085 -0.00458331 1 0 1 1 0 0 +EDGE2 3107 3106 -1.07834 -0.0181374 -0.033381 1 0 1 1 0 0 +EDGE2 3107 1186 -1.02676 -0.0474887 0.0322109 1 0 1 1 0 0 +EDGE2 3107 1187 0.0167885 0.120417 -0.014834 1 0 1 1 0 0 +EDGE2 3107 3087 0.0174171 0.102239 0.0171578 1 0 1 1 0 0 +EDGE2 3107 1167 -0.0834879 -0.0892445 -0.0228989 1 0 1 1 0 0 +EDGE2 3107 1188 1.04123 -0.0513084 -0.00248044 1 0 1 1 0 0 +EDGE2 3107 3088 0.918377 -0.0541066 0.0131257 1 0 1 1 0 0 +EDGE2 3107 1168 0.889459 -0.0169931 0.0111136 1 0 1 1 0 0 +EDGE2 3108 3107 -0.934995 -0.0190092 -0.0142443 1 0 1 1 0 0 +EDGE2 3108 1187 -1.04942 -0.00272168 0.0210955 1 0 1 1 0 0 +EDGE2 3108 3087 -0.91189 0.0663636 -0.013949 1 0 1 1 0 0 +EDGE2 3108 1167 -1.02344 0.052543 -0.0267302 1 0 1 1 0 0 +EDGE2 3108 1188 0.0275972 -0.0376452 0.0189309 1 0 1 1 0 0 +EDGE2 3108 3088 -0.0244833 0.0321696 0.00361934 1 0 1 1 0 0 +EDGE2 3108 1168 0.111904 0.067331 0.0174366 1 0 1 1 0 0 +EDGE2 3108 1189 1.09163 -0.0528998 -0.0171287 1 0 1 1 0 0 +EDGE2 3108 3089 0.995665 -0.0138284 0.0248478 1 0 1 1 0 0 +EDGE2 3108 1169 0.942041 0.0219776 -0.0150842 1 0 1 1 0 0 +EDGE2 3109 1188 -1.02059 0.00134042 0.0161431 1 0 1 1 0 0 +EDGE2 3109 3088 -1.07223 0.0501938 0.00361988 1 0 1 1 0 0 +EDGE2 3109 3108 -0.958085 0.0563125 -0.00841435 1 0 1 1 0 0 +EDGE2 3109 1168 -1.01382 -0.0431947 -0.00604946 1 0 1 1 0 0 +EDGE2 3109 1189 0.0908053 -0.0153635 -0.0157482 1 0 1 1 0 0 +EDGE2 3109 3089 0.0618048 -0.0216802 0.00786065 1 0 1 1 0 0 +EDGE2 3109 1169 -0.0336538 -0.0129769 0.0199379 1 0 1 1 0 0 +EDGE2 3109 3050 0.938548 -0.025525 -3.10191 1 0 1 1 0 0 +EDGE2 3109 3090 1.10162 -0.0202715 -0.00469542 1 0 1 1 0 0 +EDGE2 3109 1130 1.09234 -0.00359096 -3.18355 1 0 1 1 0 0 +EDGE2 3109 1170 0.874289 -0.0435002 -0.004653 1 0 1 1 0 0 +EDGE2 3109 1190 0.994809 -0.0658848 0.0135781 1 0 1 1 0 0 +EDGE2 3109 3030 1.02495 -0.0226812 -3.13037 1 0 1 1 0 0 +EDGE2 3109 1150 1.05277 -0.0615464 -3.1547 1 0 1 1 0 0 +EDGE2 3109 1110 1.0249 0.0110262 -3.12302 1 0 1 1 0 0 +EDGE2 3110 3109 -1.06233 0.0171569 -0.0178721 1 0 1 1 0 0 +EDGE2 3110 1189 -1.0026 -0.0370548 0.0253896 1 0 1 1 0 0 +EDGE2 3110 3089 -0.985955 -0.0299236 -0.0267348 1 0 1 1 0 0 +EDGE2 3110 1169 -1.06935 0.0242999 -0.0240707 1 0 1 1 0 0 +EDGE2 3110 3050 -0.0305532 0.0224852 -3.15488 1 0 1 1 0 0 +EDGE2 3110 1151 -0.0284924 1.0518 1.57385 1 0 1 1 0 0 +EDGE2 3110 1191 0.0412828 0.940949 1.58256 1 0 1 1 0 0 +EDGE2 3110 3091 0.0454887 1.03987 1.55211 1 0 1 1 0 0 +EDGE2 3110 1171 -0.029389 0.991712 1.56351 1 0 1 1 0 0 +EDGE2 3110 3090 0.038174 0.00328615 -0.00578051 1 0 1 1 0 0 +EDGE2 3110 1130 -0.0412217 -0.0144942 -3.11482 1 0 1 1 0 0 +EDGE2 3110 1170 0.0468997 -0.0614012 0.00139156 1 0 1 1 0 0 +EDGE2 3110 1190 0.0287982 -0.0124609 0.0276729 1 0 1 1 0 0 +EDGE2 3110 3030 0.0394699 0.168999 -3.15618 1 0 1 1 0 0 +EDGE2 3110 1150 -0.0753284 -0.0158889 -3.13345 1 0 1 1 0 0 +EDGE2 3110 1110 -0.0200618 -0.0391233 -3.14663 1 0 1 1 0 0 +EDGE2 3110 1109 1.07463 -0.0232502 -3.11226 1 0 1 1 0 0 +EDGE2 3110 1149 1.00549 0.0431261 -3.16744 1 0 1 1 0 0 +EDGE2 3110 3029 0.965136 -0.0404671 -3.14626 1 0 1 1 0 0 +EDGE2 3110 3049 0.999371 -0.0611991 -3.11723 1 0 1 1 0 0 +EDGE2 3110 1129 0.941469 -0.0030549 -3.15722 1 0 1 1 0 0 +EDGE2 3110 1111 0.0310714 -0.95945 -1.57338 1 0 1 1 0 0 +EDGE2 3110 3031 -0.00513653 -0.980388 -1.53667 1 0 1 1 0 0 +EDGE2 3110 3051 0.0741846 -1.02152 -1.57209 1 0 1 1 0 0 +EDGE2 3110 1131 -0.0321571 -0.978216 -1.57181 1 0 1 1 0 0 +EDGE2 3111 3050 -1.018 0.0785962 1.58231 1 0 1 1 0 0 +EDGE2 3111 3092 0.995913 0.112447 0.00375162 1 0 1 1 0 0 +EDGE2 3111 1152 1.03897 -0.0485982 0.0104464 1 0 1 1 0 0 +EDGE2 3111 1172 1.01014 -0.0290582 0.016711 1 0 1 1 0 0 +EDGE2 3111 1192 1.04331 0.0871235 0.00116069 1 0 1 1 0 0 +EDGE2 3111 1151 -0.0389311 -0.0200617 0.0182905 1 0 1 1 0 0 +EDGE2 3111 1191 -0.0462513 0.0191637 0.00609917 1 0 1 1 0 0 +EDGE2 3111 3091 0.0325535 -0.034262 -0.0354646 1 0 1 1 0 0 +EDGE2 3111 1171 -0.1512 0.0135055 0.0537108 1 0 1 1 0 0 +EDGE2 3111 3110 -0.963347 -0.0687729 -1.57271 1 0 1 1 0 0 +EDGE2 3111 3090 -0.943677 0.0833386 -1.56499 1 0 1 1 0 0 +EDGE2 3111 1130 -1.03073 -0.0195407 1.5628 1 0 1 1 0 0 +EDGE2 3111 1170 -0.946164 -0.0576484 -1.57773 1 0 1 1 0 0 +EDGE2 3111 1190 -0.9914 0.0622166 -1.59434 1 0 1 1 0 0 +EDGE2 3111 3030 -1.03474 0.0861608 1.53884 1 0 1 1 0 0 +EDGE2 3111 1150 -1.08336 -0.0424713 1.56721 1 0 1 1 0 0 +EDGE2 3111 1110 -0.951012 0.0827274 1.57188 1 0 1 1 0 0 +EDGE2 3112 1173 0.911983 -0.0474635 0.0206382 1 0 1 1 0 0 +EDGE2 3112 3093 1.11919 0.0176769 0.00951169 1 0 1 1 0 0 +EDGE2 3112 1193 1.02532 -0.06596 0.00517107 1 0 1 1 0 0 +EDGE2 3112 3092 -0.0354732 -0.00660467 0.0276268 1 0 1 1 0 0 +EDGE2 3112 1153 1.0702 -0.0354886 -0.0112029 1 0 1 1 0 0 +EDGE2 3112 1152 0.0813867 -0.000535176 0.0298133 1 0 1 1 0 0 +EDGE2 3112 1172 0.0985987 0.0514143 -0.0223995 1 0 1 1 0 0 +EDGE2 3112 1192 -0.0493254 0.0661358 -0.0154296 1 0 1 1 0 0 +EDGE2 3112 1151 -1.00244 -0.0486912 0.00848904 1 0 1 1 0 0 +EDGE2 3112 1191 -0.983077 -0.03805 -0.0251621 1 0 1 1 0 0 +EDGE2 3112 3091 -0.983913 0.0191976 -0.0138881 1 0 1 1 0 0 +EDGE2 3112 3111 -1.0076 -0.0426435 0.0142881 1 0 1 1 0 0 +EDGE2 3112 1171 -1.0656 -0.102595 0.0234113 1 0 1 1 0 0 +EDGE2 3113 1173 0.0562955 -0.0243383 -0.0501801 1 0 1 1 0 0 +EDGE2 3113 1174 0.955768 -0.0523505 0.0126629 1 0 1 1 0 0 +EDGE2 3113 3094 1.03463 -0.0653844 0.00122404 1 0 1 1 0 0 +EDGE2 3113 1194 0.986091 0.02738 -0.00810587 1 0 1 1 0 0 +EDGE2 3113 1154 0.899866 -0.0797705 -0.034914 1 0 1 1 0 0 +EDGE2 3113 3093 0.0787939 0.036774 0.0194001 1 0 1 1 0 0 +EDGE2 3113 1193 0.0242403 0.08249 0.0156479 1 0 1 1 0 0 +EDGE2 3113 3092 -0.929656 0.00384296 0.0010555 1 0 1 1 0 0 +EDGE2 3113 1153 0.0454454 -0.0503186 0.0130166 1 0 1 1 0 0 +EDGE2 3113 3112 -1.008 -0.0507475 -0.0156419 1 0 1 1 0 0 +EDGE2 3113 1152 -1.05568 0.021031 0.00263811 1 0 1 1 0 0 +EDGE2 3113 1172 -1.00145 0.0699327 0.00520434 1 0 1 1 0 0 +EDGE2 3113 1192 -0.961586 0.0336492 -0.00509031 1 0 1 1 0 0 +EDGE2 3114 1173 -1.03053 -0.109215 0.0344654 1 0 1 1 0 0 +EDGE2 3114 1174 0.0120286 -0.0236746 -0.00574253 1 0 1 1 0 0 +EDGE2 3114 1175 0.958557 0.0200061 0.00594851 1 0 1 1 0 0 +EDGE2 3114 1195 0.927096 -0.058992 -0.0211691 1 0 1 1 0 0 +EDGE2 3114 3095 1.02876 -0.0321567 0.00239331 1 0 1 1 0 0 +EDGE2 3114 1155 1.05206 -0.123876 -0.0186931 1 0 1 1 0 0 +EDGE2 3114 3094 0.052378 -0.0366011 -0.000798307 1 0 1 1 0 0 +EDGE2 3114 1194 0.0379686 0.043289 -0.0331013 1 0 1 1 0 0 +EDGE2 3114 1154 0.0522094 -0.0190383 0.00756299 1 0 1 1 0 0 +EDGE2 3114 3093 -1.02622 0.0396815 -0.00477609 1 0 1 1 0 0 +EDGE2 3114 3113 -0.988763 -0.0331146 0.000566837 1 0 1 1 0 0 +EDGE2 3114 1193 -0.923779 -0.00410977 -0.0297842 1 0 1 1 0 0 +EDGE2 3114 1153 -0.89861 0.0347261 0.00149107 1 0 1 1 0 0 +EDGE2 3115 1196 0.0221881 1.04557 1.58621 1 0 1 1 0 0 +EDGE2 3115 3096 -0.0672617 1.06068 1.55357 1 0 1 1 0 0 +EDGE2 3115 1156 -0.0434656 1.00782 1.58159 1 0 1 1 0 0 +EDGE2 3115 1176 0.0143365 1.05049 1.56062 1 0 1 1 0 0 +EDGE2 3115 1174 -1.01953 0.0119418 0.0228959 1 0 1 1 0 0 +EDGE2 3115 1175 -0.0453715 0.0697018 -0.0290348 1 0 1 1 0 0 +EDGE2 3115 1195 0.112689 0.0430602 0.0024131 1 0 1 1 0 0 +EDGE2 3115 3095 0.0881637 0.00922612 -0.00565684 1 0 1 1 0 0 +EDGE2 3115 1155 0.027469 0.0497469 0.0114778 1 0 1 1 0 0 +EDGE2 3115 3094 -1.0201 -0.0453873 0.0639202 1 0 1 1 0 0 +EDGE2 3115 3114 -0.948245 0.0278849 -0.00568105 1 0 1 1 0 0 +EDGE2 3115 1194 -1.02722 -0.00759152 0.00141071 1 0 1 1 0 0 +EDGE2 3115 1154 -0.929366 0.0104069 -0.0112362 1 0 1 1 0 0 +EDGE2 3116 1197 0.99373 0.0259592 0.000474762 1 0 1 1 0 0 +EDGE2 3116 3097 1.02901 0.0470884 0.0164487 1 0 1 1 0 0 +EDGE2 3116 1177 0.950819 -0.0861272 0.0121911 1 0 1 1 0 0 +EDGE2 3116 1157 1.05251 -0.021895 -0.00387878 1 0 1 1 0 0 +EDGE2 3116 1196 0.0316992 0.0144156 -0.0119746 1 0 1 1 0 0 +EDGE2 3116 3096 -0.104009 -0.0193272 -0.00127889 1 0 1 1 0 0 +EDGE2 3116 1156 -0.0571 -0.14385 -0.0328438 1 0 1 1 0 0 +EDGE2 3116 1176 0.0751001 -0.0277397 0.00941097 1 0 1 1 0 0 +EDGE2 3116 3115 -1.10836 0.0343072 -1.58779 1 0 1 1 0 0 +EDGE2 3116 1175 -1.00984 0.012743 -1.56334 1 0 1 1 0 0 +EDGE2 3116 1195 -0.93785 -0.0459517 -1.56692 1 0 1 1 0 0 +EDGE2 3116 3095 -0.986929 -0.0493737 -1.56189 1 0 1 1 0 0 +EDGE2 3116 1155 -1.02168 -0.0506353 -1.56006 1 0 1 1 0 0 +EDGE2 3117 1197 0.0178288 0.0677439 0.00720916 1 0 1 1 0 0 +EDGE2 3117 3098 0.996953 -0.00516243 -0.0195154 1 0 1 1 0 0 +EDGE2 3117 1178 1.01546 -0.0308173 -0.00444374 1 0 1 1 0 0 +EDGE2 3117 1198 1.03736 0.0162059 -0.00608741 1 0 1 1 0 0 +EDGE2 3117 1158 1.07814 0.0553648 0.0112028 1 0 1 1 0 0 +EDGE2 3117 3097 0.107206 0.0364197 -0.0300232 1 0 1 1 0 0 +EDGE2 3117 1177 0.00312569 0.0608378 -0.0124206 1 0 1 1 0 0 +EDGE2 3117 1157 0.0247387 0.00865508 -0.0466943 1 0 1 1 0 0 +EDGE2 3117 1196 -0.969827 -0.00868567 0.0149701 1 0 1 1 0 0 +EDGE2 3117 3116 -0.988853 -0.10916 0.00430862 1 0 1 1 0 0 +EDGE2 3117 3096 -0.952681 0.047506 -0.00142801 1 0 1 1 0 0 +EDGE2 3117 1156 -0.959266 -0.00243299 0.0160096 1 0 1 1 0 0 +EDGE2 3117 1176 -0.967662 0.0964807 -0.0237655 1 0 1 1 0 0 +EDGE2 3118 1197 -0.964915 -0.0510603 0.00235582 1 0 1 1 0 0 +EDGE2 3118 1179 1.04477 -0.11509 0.010951 1 0 1 1 0 0 +EDGE2 3118 1199 1.07539 0.0684151 0.0394542 1 0 1 1 0 0 +EDGE2 3118 3099 1.02625 -0.0296782 0.000252762 1 0 1 1 0 0 +EDGE2 3118 1159 1.0429 0.0246644 0.0218469 1 0 1 1 0 0 +EDGE2 3118 3098 -0.10849 0.0127467 0.0243744 1 0 1 1 0 0 +EDGE2 3118 1178 0.0307191 -0.0536017 -0.00490415 1 0 1 1 0 0 +EDGE2 3118 1198 -0.00792886 0.0257709 0.0073868 1 0 1 1 0 0 +EDGE2 3118 1158 0.0023482 -0.00457716 0.0250593 1 0 1 1 0 0 +EDGE2 3118 3117 -1.08535 0.100796 0.00760697 1 0 1 1 0 0 +EDGE2 3118 3097 -0.954287 -0.00519788 0.0239196 1 0 1 1 0 0 +EDGE2 3118 1177 -0.951575 -0.075063 -0.0259154 1 0 1 1 0 0 +EDGE2 3118 1157 -0.917067 -0.0298407 -0.0184497 1 0 1 1 0 0 +EDGE2 3119 1160 0.989095 -0.0279076 0.0175832 1 0 1 1 0 0 +EDGE2 3119 1200 0.997787 0.0901369 -0.0136127 1 0 1 1 0 0 +EDGE2 3119 3100 1.04275 -0.0761648 -0.00908033 1 0 1 1 0 0 +EDGE2 3119 1180 1.05277 -0.013735 -0.0137829 1 0 1 1 0 0 +EDGE2 3119 900 0.934817 -0.00230977 -3.1653 1 0 1 1 0 0 +EDGE2 3119 840 0.880125 -0.0480607 -3.13671 1 0 1 1 0 0 +EDGE2 3119 860 1.01927 0.0855644 -3.12787 1 0 1 1 0 0 +EDGE2 3119 1179 0.0144053 0.0797615 0.0292446 1 0 1 1 0 0 +EDGE2 3119 1199 0.0187628 -0.0342803 0.00495375 1 0 1 1 0 0 +EDGE2 3119 3099 -0.0233893 0.0283964 -0.00768742 1 0 1 1 0 0 +EDGE2 3119 1159 -0.0366943 -0.0257906 -0.0280278 1 0 1 1 0 0 +EDGE2 3119 3098 -1.06481 -0.0592129 -0.0124916 1 0 1 1 0 0 +EDGE2 3119 3118 -1.03686 0.010655 -0.00464438 1 0 1 1 0 0 +EDGE2 3119 1178 -1.08858 -0.0214717 -0.00356703 1 0 1 1 0 0 +EDGE2 3119 1198 -0.94408 -0.0313032 -0.00213634 1 0 1 1 0 0 +EDGE2 3119 1158 -1.05325 -0.014167 0.0210083 1 0 1 1 0 0 +EDGE2 3120 839 1.02751 -0.0102759 -3.14341 1 0 1 1 0 0 +EDGE2 3120 899 0.969988 0.0322653 -3.11401 1 0 1 1 0 0 +EDGE2 3120 859 0.993279 0.112143 -3.13926 1 0 1 1 0 0 +EDGE2 3120 841 0.0268279 -0.98291 -1.59504 1 0 1 1 0 0 +EDGE2 3120 901 0.0122613 -1.05024 -1.62019 1 0 1 1 0 0 +EDGE2 3120 1201 0.0418986 -1.10485 -1.59016 1 0 1 1 0 0 +EDGE2 3120 861 -0.0258095 -1.02663 -1.57696 1 0 1 1 0 0 +EDGE2 3120 1160 0.0360442 0.0183554 -0.0178251 1 0 1 1 0 0 +EDGE2 3120 1200 0.0348346 -0.116199 -0.0201784 1 0 1 1 0 0 +EDGE2 3120 3100 0.00303965 -0.0255633 -0.0133267 1 0 1 1 0 0 +EDGE2 3120 1180 0.107549 -0.0310374 -0.00523389 1 0 1 1 0 0 +EDGE2 3120 900 -0.00232401 -0.0376086 -3.14225 1 0 1 1 0 0 +EDGE2 3120 840 -0.0216549 0.0369359 -3.17792 1 0 1 1 0 0 +EDGE2 3120 860 -0.0881176 -0.0196455 -3.1502 1 0 1 1 0 0 +EDGE2 3120 3101 -0.00189529 0.960711 1.58304 1 0 1 1 0 0 +EDGE2 3120 1161 -0.0166885 1.05106 1.54571 1 0 1 1 0 0 +EDGE2 3120 1181 -0.0510605 1.02928 1.57226 1 0 1 1 0 0 +EDGE2 3120 3119 -1.03974 0.0457358 -0.0036394 1 0 1 1 0 0 +EDGE2 3120 1179 -0.983852 -0.0699978 -0.0363231 1 0 1 1 0 0 +EDGE2 3120 1199 -0.970236 0.0682092 -0.00733641 1 0 1 1 0 0 +EDGE2 3120 3099 -1.0943 -0.000995106 -0.0236104 1 0 1 1 0 0 +EDGE2 3120 1159 -1.02004 0.00398814 -0.0126969 1 0 1 1 0 0 +EDGE2 3121 1160 -1.06019 0.010738 -1.56323 1 0 1 1 0 0 +EDGE2 3121 1200 -1.03216 -0.0400793 -1.52869 1 0 1 1 0 0 +EDGE2 3121 3100 -1.01372 -0.0478061 -1.53573 1 0 1 1 0 0 +EDGE2 3121 3120 -1.01343 0.0198925 -1.52944 1 0 1 1 0 0 +EDGE2 3121 1180 -0.981813 -0.0586939 -1.57882 1 0 1 1 0 0 +EDGE2 3121 900 -1.00676 0.0062135 1.51522 1 0 1 1 0 0 +EDGE2 3121 840 -1.01642 -0.0750733 1.57721 1 0 1 1 0 0 +EDGE2 3121 860 -1.0116 -0.0173777 1.56509 1 0 1 1 0 0 +EDGE2 3121 3101 0.0271673 -0.0106526 -0.00456223 1 0 1 1 0 0 +EDGE2 3121 1161 0.033353 0.117581 0.0518625 1 0 1 1 0 0 +EDGE2 3121 1181 -0.0471596 -0.0225176 0.0118436 1 0 1 1 0 0 +EDGE2 3121 1182 0.980934 -0.0957617 -0.0112116 1 0 1 1 0 0 +EDGE2 3121 3102 0.954114 -0.027107 -0.00541264 1 0 1 1 0 0 +EDGE2 3121 1162 0.954727 0.0424147 0.0112503 1 0 1 1 0 0 +EDGE2 3122 3101 -1.07935 0.0915747 0.0230716 1 0 1 1 0 0 +EDGE2 3122 3121 -0.90975 -0.0149324 -0.00928054 1 0 1 1 0 0 +EDGE2 3122 1161 -0.993126 -0.110417 0.00559819 1 0 1 1 0 0 +EDGE2 3122 1181 -0.890646 -0.0381185 -0.0165698 1 0 1 1 0 0 +EDGE2 3122 1182 0.0316008 -0.0277489 -0.00887899 1 0 1 1 0 0 +EDGE2 3122 3102 0.0293815 -0.015994 0.0315507 1 0 1 1 0 0 +EDGE2 3122 1162 -0.022269 -0.0477091 -0.0125805 1 0 1 1 0 0 +EDGE2 3122 1163 0.99949 -0.0462141 0.0125372 1 0 1 1 0 0 +EDGE2 3122 3103 1.031 -0.0434075 -0.0155225 1 0 1 1 0 0 +EDGE2 3122 1183 1.05802 0.0521398 0.00907839 1 0 1 1 0 0 +EDGE2 3123 1182 -0.993678 0.0118279 0.0349979 1 0 1 1 0 0 +EDGE2 3123 3122 -0.998793 -0.0935022 0.0276741 1 0 1 1 0 0 +EDGE2 3123 3102 -1.04761 0.0553716 -0.019802 1 0 1 1 0 0 +EDGE2 3123 1162 -1.03379 0.00404264 -0.0394664 1 0 1 1 0 0 +EDGE2 3123 1163 0.095131 0.0489952 -0.00743518 1 0 1 1 0 0 +EDGE2 3123 3103 -0.0143787 -0.0843403 0.00381996 1 0 1 1 0 0 +EDGE2 3123 1183 -0.042384 -0.0786441 0.00372969 1 0 1 1 0 0 +EDGE2 3123 1184 0.982216 0.066314 0.023506 1 0 1 1 0 0 +EDGE2 3123 3104 1.00229 0.00352307 -0.00617379 1 0 1 1 0 0 +EDGE2 3123 1164 1.04669 0.04281 0.00976274 1 0 1 1 0 0 +EDGE2 3124 1163 -0.989362 0.0127551 -0.00403122 1 0 1 1 0 0 +EDGE2 3124 3103 -0.980982 0.0952451 0.0132965 1 0 1 1 0 0 +EDGE2 3124 3123 -1.12035 0.0522287 -0.0326056 1 0 1 1 0 0 +EDGE2 3124 1183 -1.06702 0.0316611 0.0218686 1 0 1 1 0 0 +EDGE2 3124 1184 0.0603992 -0.0458181 -0.0345422 1 0 1 1 0 0 +EDGE2 3124 3104 -0.101611 -0.0131772 -0.0417038 1 0 1 1 0 0 +EDGE2 3124 1164 -0.0351926 -0.0235927 -0.0204965 1 0 1 1 0 0 +EDGE2 3124 3105 1.02303 -0.0926638 -0.00560288 1 0 1 1 0 0 +EDGE2 3124 1185 1.06002 -0.0130216 0.017411 1 0 1 1 0 0 +EDGE2 3124 3065 1.04968 0.0696148 -3.13082 1 0 1 1 0 0 +EDGE2 3124 3085 0.973967 0.0483003 -3.10661 1 0 1 1 0 0 +EDGE2 3124 1165 1.00005 0.0202447 -0.00262598 1 0 1 1 0 0 +EDGE2 3125 3066 0.0194748 -1.02893 -1.53997 1 0 1 1 0 0 +EDGE2 3125 1184 -0.995751 -0.00836636 -0.00451641 1 0 1 1 0 0 +EDGE2 3125 3104 -1.01002 0.0996397 -0.0179686 1 0 1 1 0 0 +EDGE2 3125 3124 -0.97611 0.072688 0.0115827 1 0 1 1 0 0 +EDGE2 3125 1164 -0.933165 0.0077076 0.0195119 1 0 1 1 0 0 +EDGE2 3125 3105 -0.010676 0.0416314 0.00968116 1 0 1 1 0 0 +EDGE2 3125 1185 0.0332638 0.112689 -0.0394115 1 0 1 1 0 0 +EDGE2 3125 3065 0.00150287 0.0436195 -3.12611 1 0 1 1 0 0 +EDGE2 3125 3085 0.0227535 -0.0810096 -3.14005 1 0 1 1 0 0 +EDGE2 3125 1165 -0.0378721 0.0124836 -0.00138683 1 0 1 1 0 0 +EDGE2 3125 1166 0.0302327 0.99901 1.59668 1 0 1 1 0 0 +EDGE2 3125 3086 -0.0702403 0.988163 1.60044 1 0 1 1 0 0 +EDGE2 3125 3106 0.0167334 0.991941 1.56738 1 0 1 1 0 0 +EDGE2 3125 1186 0.0263846 0.933301 1.54069 1 0 1 1 0 0 +EDGE2 3125 3064 0.952647 -0.0384023 -3.12982 1 0 1 1 0 0 +EDGE2 3125 3084 1.0323 -0.0102948 -3.18122 1 0 1 1 0 0 +EDGE2 3126 3105 -0.944711 0.0400928 -1.60916 1 0 1 1 0 0 +EDGE2 3126 3125 -1.03713 0.0108146 -1.56308 1 0 1 1 0 0 +EDGE2 3126 1185 -0.928322 -0.00970455 -1.58103 1 0 1 1 0 0 +EDGE2 3126 3065 -1.04368 0.0741889 1.54337 1 0 1 1 0 0 +EDGE2 3126 3085 -0.987104 0.0170723 1.56612 1 0 1 1 0 0 +EDGE2 3126 1165 -0.966621 0.0114877 -1.60784 1 0 1 1 0 0 +EDGE2 3126 1166 0.0184218 0.0345507 -0.00962431 1 0 1 1 0 0 +EDGE2 3126 3086 -0.0308171 0.0315904 0.0296735 1 0 1 1 0 0 +EDGE2 3126 3106 0.0406459 0.0045858 -0.015407 1 0 1 1 0 0 +EDGE2 3126 1186 -0.0946038 0.0129804 -0.000830378 1 0 1 1 0 0 +EDGE2 3126 3107 1.04273 0.0743278 -0.0125829 1 0 1 1 0 0 +EDGE2 3126 1187 1.07383 -0.026228 0.0351005 1 0 1 1 0 0 +EDGE2 3126 3087 0.981147 -0.0345578 0.00966289 1 0 1 1 0 0 +EDGE2 3126 1167 0.991323 -0.0180386 0.0172106 1 0 1 1 0 0 +EDGE2 3127 1166 -0.944212 -0.0250174 -0.0295022 1 0 1 1 0 0 +EDGE2 3127 3086 -0.992274 0.0272208 0.0163592 1 0 1 1 0 0 +EDGE2 3127 3106 -1.0091 -0.051224 0.00624001 1 0 1 1 0 0 +EDGE2 3127 3126 -1.0194 0.0154246 0.00961704 1 0 1 1 0 0 +EDGE2 3127 1186 -0.957659 -0.0753391 -0.0273118 1 0 1 1 0 0 +EDGE2 3127 3107 -0.0750053 -0.0374304 -0.022933 1 0 1 1 0 0 +EDGE2 3127 1187 -0.0489214 0.0225845 0.0401 1 0 1 1 0 0 +EDGE2 3127 3087 -0.0385123 -0.0273449 -0.0113088 1 0 1 1 0 0 +EDGE2 3127 1167 -0.00285325 -0.0200077 -0.00137817 1 0 1 1 0 0 +EDGE2 3127 1188 1.00691 -0.0149467 0.0212226 1 0 1 1 0 0 +EDGE2 3127 3088 0.905113 0.07593 0.0272492 1 0 1 1 0 0 +EDGE2 3127 3108 0.995186 0.085851 -0.0381591 1 0 1 1 0 0 +EDGE2 3127 1168 0.960132 0.0275303 0.0253565 1 0 1 1 0 0 +EDGE2 3128 3107 -1.0718 0.0165392 -0.00906955 1 0 1 1 0 0 +EDGE2 3128 3127 -1.06898 -0.064265 -0.0051855 1 0 1 1 0 0 +EDGE2 3128 1187 -0.95369 -0.0432548 0.0145039 1 0 1 1 0 0 +EDGE2 3128 3087 -1.06987 0.00596899 -0.00943717 1 0 1 1 0 0 +EDGE2 3128 1167 -0.99384 0.0311391 0.0194755 1 0 1 1 0 0 +EDGE2 3128 1188 0.058943 0.0830823 -0.00972217 1 0 1 1 0 0 +EDGE2 3128 3088 0.0177874 0.0559672 -0.0151092 1 0 1 1 0 0 +EDGE2 3128 3108 0.0554936 -0.0946607 0.006422 1 0 1 1 0 0 +EDGE2 3128 1168 -0.11731 0.0479724 -0.0180084 1 0 1 1 0 0 +EDGE2 3128 3109 0.969419 0.0604235 -0.0243453 1 0 1 1 0 0 +EDGE2 3128 1189 1.12858 -0.0534679 -0.0268624 1 0 1 1 0 0 +EDGE2 3128 3089 0.950828 -0.0571597 -0.0106298 1 0 1 1 0 0 +EDGE2 3128 1169 1.03052 -0.0163312 -0.0120466 1 0 1 1 0 0 +EDGE2 3129 3128 -1.0054 0.100632 0.00636166 1 0 1 1 0 0 +EDGE2 3129 1188 -0.936623 -0.0606035 -0.00125869 1 0 1 1 0 0 +EDGE2 3129 3088 -0.992329 -0.0585897 -0.0201746 1 0 1 1 0 0 +EDGE2 3129 3108 -1.08807 -0.0117253 -0.011201 1 0 1 1 0 0 +EDGE2 3129 1168 -1.01841 -0.0281282 -0.0121133 1 0 1 1 0 0 +EDGE2 3129 3109 -0.00954854 0.0105625 -0.0134556 1 0 1 1 0 0 +EDGE2 3129 1189 -0.0445446 0.00342225 0.0115984 1 0 1 1 0 0 +EDGE2 3129 3089 0.0676914 0.0466039 0.00911422 1 0 1 1 0 0 +EDGE2 3129 1169 0.0414441 -0.0388691 0.0290614 1 0 1 1 0 0 +EDGE2 3129 3050 1.06726 -0.0450261 -3.13975 1 0 1 1 0 0 +EDGE2 3129 3110 0.969117 0.076804 -0.00920447 1 0 1 1 0 0 +EDGE2 3129 3090 1.01115 0.0434521 -0.0286297 1 0 1 1 0 0 +EDGE2 3129 1130 1.01221 -0.0537799 -3.13937 1 0 1 1 0 0 +EDGE2 3129 1170 1.03531 0.00202708 0.0115244 1 0 1 1 0 0 +EDGE2 3129 1190 0.996012 0.00526323 -0.0201239 1 0 1 1 0 0 +EDGE2 3129 3030 1.01331 -0.0457346 -3.14119 1 0 1 1 0 0 +EDGE2 3129 1150 1.02959 0.00861098 -3.13102 1 0 1 1 0 0 +EDGE2 3129 1110 1.01551 -0.0722797 -3.14092 1 0 1 1 0 0 +EDGE2 3130 3109 -0.977195 -0.0283372 0.0161079 1 0 1 1 0 0 +EDGE2 3130 3129 -0.997707 -0.00274413 0.00845607 1 0 1 1 0 0 +EDGE2 3130 1189 -0.95822 -0.0457154 -0.0374439 1 0 1 1 0 0 +EDGE2 3130 3089 -0.929256 0.0116379 -0.00701744 1 0 1 1 0 0 +EDGE2 3130 1169 -0.925819 0.00583516 0.00505212 1 0 1 1 0 0 +EDGE2 3130 3050 -0.0199485 -0.0559828 -3.16304 1 0 1 1 0 0 +EDGE2 3130 1151 -0.0143319 1.0504 1.57641 1 0 1 1 0 0 +EDGE2 3130 1191 0.0049524 1.11044 1.53683 1 0 1 1 0 0 +EDGE2 3130 3091 -0.00816951 0.981069 1.5527 1 0 1 1 0 0 +EDGE2 3130 3111 0.00991611 0.950974 1.58786 1 0 1 1 0 0 +EDGE2 3130 1171 -0.0522767 0.970922 1.55863 1 0 1 1 0 0 +EDGE2 3130 3110 0.0181992 0.0214174 -0.0134395 1 0 1 1 0 0 +EDGE2 3130 3090 -0.00264718 -0.00620777 0.00771418 1 0 1 1 0 0 +EDGE2 3130 1130 -0.000609776 -0.0258726 -3.12248 1 0 1 1 0 0 +EDGE2 3130 1170 -0.00685022 -0.0630756 -0.0110562 1 0 1 1 0 0 +EDGE2 3130 1190 -0.0437906 -0.0299226 0.0111087 1 0 1 1 0 0 +EDGE2 3130 3030 -0.0127011 0.00358311 -3.1651 1 0 1 1 0 0 +EDGE2 3130 1150 0.0416021 -0.0860006 -3.14005 1 0 1 1 0 0 +EDGE2 3130 1110 -0.0508128 -0.0324971 -3.13997 1 0 1 1 0 0 +EDGE2 3130 1109 1.09393 -0.0207763 -3.11171 1 0 1 1 0 0 +EDGE2 3130 1149 0.973852 -0.0167574 -3.16532 1 0 1 1 0 0 +EDGE2 3130 3029 1.04631 0.0753653 -3.14268 1 0 1 1 0 0 +EDGE2 3130 3049 0.998468 0.00514361 -3.11159 1 0 1 1 0 0 +EDGE2 3130 1129 1.04695 -0.0483523 -3.12652 1 0 1 1 0 0 +EDGE2 3130 1111 -0.00454149 -0.996032 -1.56018 1 0 1 1 0 0 +EDGE2 3130 3031 0.0756336 -0.941916 -1.6008 1 0 1 1 0 0 +EDGE2 3130 3051 -0.0487522 -1.02634 -1.52254 1 0 1 1 0 0 +EDGE2 3130 1131 -0.01037 -1.0247 -1.60264 1 0 1 1 0 0 +EDGE2 3131 3050 -1.00388 0.0901811 1.55598 1 0 1 1 0 0 +EDGE2 3131 3092 1.00916 -0.0139336 -0.0148385 1 0 1 1 0 0 +EDGE2 3131 3112 1.0769 0.0705461 0.025143 1 0 1 1 0 0 +EDGE2 3131 1152 1.00164 0.0295926 -0.0174126 1 0 1 1 0 0 +EDGE2 3131 1172 1.0973 -0.0105627 -0.0118172 1 0 1 1 0 0 +EDGE2 3131 1192 0.932216 0.0651645 0.0126816 1 0 1 1 0 0 +EDGE2 3131 1151 -0.0168145 -0.0448161 -0.0357083 1 0 1 1 0 0 +EDGE2 3131 1191 -0.040154 -0.0552648 -0.0122936 1 0 1 1 0 0 +EDGE2 3131 3091 0.00899779 0.0931627 0.0387082 1 0 1 1 0 0 +EDGE2 3131 3111 0.0149288 0.0219092 0.019837 1 0 1 1 0 0 +EDGE2 3131 1171 0.0292291 0.0990876 -0.0118179 1 0 1 1 0 0 +EDGE2 3131 3110 -0.930356 0.00895615 -1.59886 1 0 1 1 0 0 +EDGE2 3131 3130 -1.07266 0.0728799 -1.55861 1 0 1 1 0 0 +EDGE2 3131 3090 -1.01852 -0.0206386 -1.57371 1 0 1 1 0 0 +EDGE2 3131 1130 -1.10158 0.00378453 1.56977 1 0 1 1 0 0 +EDGE2 3131 1170 -1.06739 0.0291078 -1.56057 1 0 1 1 0 0 +EDGE2 3131 1190 -0.998241 0.00962968 -1.56965 1 0 1 1 0 0 +EDGE2 3131 3030 -0.924605 -0.0614966 1.55586 1 0 1 1 0 0 +EDGE2 3131 1150 -1.03031 -0.0618311 1.57824 1 0 1 1 0 0 +EDGE2 3131 1110 -0.965145 -0.0208802 1.55575 1 0 1 1 0 0 +EDGE2 3132 1173 0.986965 -0.000252895 0.0456312 1 0 1 1 0 0 +EDGE2 3132 3093 1.05502 0.0310006 0.00700314 1 0 1 1 0 0 +EDGE2 3132 3113 0.992773 -0.049977 -0.000790998 1 0 1 1 0 0 +EDGE2 3132 1193 0.972928 -0.011929 0.0218147 1 0 1 1 0 0 +EDGE2 3132 3131 -0.987086 0.0478036 -0.0118104 1 0 1 1 0 0 +EDGE2 3132 3092 -0.0869273 -0.0123913 0.0155462 1 0 1 1 0 0 +EDGE2 3132 1153 0.913079 0.0242304 0.0294173 1 0 1 1 0 0 +EDGE2 3132 3112 -0.00687267 -0.12655 -0.0134236 1 0 1 1 0 0 +EDGE2 3132 1152 -0.0461848 0.022493 0.0108364 1 0 1 1 0 0 +EDGE2 3132 1172 0.0442229 0.0743768 0.0105789 1 0 1 1 0 0 +EDGE2 3132 1192 0.0473909 -0.0661117 0.017186 1 0 1 1 0 0 +EDGE2 3132 1151 -1.07346 -0.0383101 -0.021524 1 0 1 1 0 0 +EDGE2 3132 1191 -0.960111 -0.112358 -0.00974072 1 0 1 1 0 0 +EDGE2 3132 3091 -1.02563 -0.0740164 -0.00252782 1 0 1 1 0 0 +EDGE2 3132 3111 -1.01518 -0.0393998 -0.014295 1 0 1 1 0 0 +EDGE2 3132 1171 -1.04347 0.0100048 -0.00233659 1 0 1 1 0 0 +EDGE2 3133 1173 -0.044918 0.0131155 0.0052978 1 0 1 1 0 0 +EDGE2 3133 1174 0.985855 0.0245607 0.00616989 1 0 1 1 0 0 +EDGE2 3133 3094 0.930561 0.00928329 0.0168292 1 0 1 1 0 0 +EDGE2 3133 3114 1.06809 -0.0228913 0.0252148 1 0 1 1 0 0 +EDGE2 3133 1194 0.958033 0.0577362 -0.00887879 1 0 1 1 0 0 +EDGE2 3133 1154 1.02858 -0.0605583 -0.0138332 1 0 1 1 0 0 +EDGE2 3133 3093 0.0707926 0.0294859 -0.0090512 1 0 1 1 0 0 +EDGE2 3133 3113 0.0109223 0.006805 0.0429211 1 0 1 1 0 0 +EDGE2 3133 1193 -0.00482808 -0.0497693 -0.00392786 1 0 1 1 0 0 +EDGE2 3133 3092 -0.937527 -0.0666566 0.00377396 1 0 1 1 0 0 +EDGE2 3133 1153 -0.0213744 -0.0686691 -0.0016402 1 0 1 1 0 0 +EDGE2 3133 3132 -0.98618 -0.0693122 0.0182658 1 0 1 1 0 0 +EDGE2 3133 3112 -1.03749 -0.043519 -0.0121387 1 0 1 1 0 0 +EDGE2 3133 1152 -0.952055 0.0382676 0.0380306 1 0 1 1 0 0 +EDGE2 3133 1172 -0.937306 0.00644308 0.0104164 1 0 1 1 0 0 +EDGE2 3133 1192 -1.03367 0.0183849 0.0120619 1 0 1 1 0 0 +EDGE2 3134 1173 -1.04836 -0.00959931 -0.0398911 1 0 1 1 0 0 +EDGE2 3134 1174 0.0450272 -0.0622277 -0.00915 1 0 1 1 0 0 +EDGE2 3134 3115 0.995546 -0.0978448 -0.0102167 1 0 1 1 0 0 +EDGE2 3134 1175 0.995381 0.0526476 -0.00800114 1 0 1 1 0 0 +EDGE2 3134 1195 0.996353 0.025386 0.00126663 1 0 1 1 0 0 +EDGE2 3134 3095 1.04369 0.0895215 0.0156136 1 0 1 1 0 0 +EDGE2 3134 1155 1.04526 -0.104543 0.000453676 1 0 1 1 0 0 +EDGE2 3134 3094 -0.0253526 -0.0443105 0.000519723 1 0 1 1 0 0 +EDGE2 3134 3114 0.0196184 0.0454716 -0.0258073 1 0 1 1 0 0 +EDGE2 3134 1194 -0.0416792 -0.00486559 -0.0149473 1 0 1 1 0 0 +EDGE2 3134 1154 0.0202262 -0.00231856 0.0109521 1 0 1 1 0 0 +EDGE2 3134 3133 -0.98233 0.0123643 0.000948332 1 0 1 1 0 0 +EDGE2 3134 3093 -0.935299 0.034636 0.0107004 1 0 1 1 0 0 +EDGE2 3134 3113 -1.0574 0.0184829 0.013731 1 0 1 1 0 0 +EDGE2 3134 1193 -1.07861 0.0596895 0.0402096 1 0 1 1 0 0 +EDGE2 3134 1153 -0.972576 0.076942 0.0284163 1 0 1 1 0 0 +EDGE2 3135 1196 -0.0484675 1.02188 1.53953 1 0 1 1 0 0 +EDGE2 3135 3116 -0.00242973 1.0033 1.56518 1 0 1 1 0 0 +EDGE2 3135 3096 -0.00783589 1.02448 1.57003 1 0 1 1 0 0 +EDGE2 3135 1156 -0.0758804 1.0268 1.54837 1 0 1 1 0 0 +EDGE2 3135 1176 -0.1285 0.905605 1.57021 1 0 1 1 0 0 +EDGE2 3135 1174 -1.01804 -0.0923071 0.00911856 1 0 1 1 0 0 +EDGE2 3135 3115 0.051138 0.0199313 -0.0327682 1 0 1 1 0 0 +EDGE2 3135 1175 -0.0145897 -0.0933902 -0.00314644 1 0 1 1 0 0 +EDGE2 3135 1195 0.0597924 -0.00747701 0.0295537 1 0 1 1 0 0 +EDGE2 3135 3095 -0.0099247 -0.100116 0.017382 1 0 1 1 0 0 +EDGE2 3135 1155 0.0521715 0.0900108 -0.0248498 1 0 1 1 0 0 +EDGE2 3135 3094 -1.05776 -0.0344124 0.0027957 1 0 1 1 0 0 +EDGE2 3135 3114 -0.918881 0.0451236 -0.0157265 1 0 1 1 0 0 +EDGE2 3135 3134 -0.961384 -0.0408447 0.0217673 1 0 1 1 0 0 +EDGE2 3135 1194 -1.01988 -0.0306358 -0.0340778 1 0 1 1 0 0 +EDGE2 3135 1154 -1.15024 -0.0581491 0.0269831 1 0 1 1 0 0 +EDGE2 3136 1197 0.971781 0.043901 0.0116185 1 0 1 1 0 0 +EDGE2 3136 3117 0.986787 -0.0342893 -0.00134697 1 0 1 1 0 0 +EDGE2 3136 3097 0.971447 -0.0544581 -0.0149555 1 0 1 1 0 0 +EDGE2 3136 1177 1.07658 0.0552094 0.00881381 1 0 1 1 0 0 +EDGE2 3136 1157 1.01944 -0.00512092 -0.00667715 1 0 1 1 0 0 +EDGE2 3136 1196 0.0530602 -0.0813684 -0.00133223 1 0 1 1 0 0 +EDGE2 3136 3116 -0.013474 0.0164901 0.00133527 1 0 1 1 0 0 +EDGE2 3136 3096 -0.0288146 0.0752533 0.00739339 1 0 1 1 0 0 +EDGE2 3136 1156 -0.0292713 0.0220275 -0.0269158 1 0 1 1 0 0 +EDGE2 3136 1176 -0.0942694 -0.027736 0.0185416 1 0 1 1 0 0 +EDGE2 3136 3115 -1.0934 0.0392072 -1.58241 1 0 1 1 0 0 +EDGE2 3136 3135 -0.986642 0.0255561 -1.57432 1 0 1 1 0 0 +EDGE2 3136 1175 -0.980468 0.0665634 -1.58868 1 0 1 1 0 0 +EDGE2 3136 1195 -1.05588 -0.00441579 -1.5737 1 0 1 1 0 0 +EDGE2 3136 3095 -1.02739 -0.0892162 -1.56811 1 0 1 1 0 0 +EDGE2 3136 1155 -1.02509 -0.118711 -1.55515 1 0 1 1 0 0 +EDGE2 3137 1197 0.0593464 0.0177088 0.0340611 1 0 1 1 0 0 +EDGE2 3137 3098 0.942137 0.0517652 -0.0145196 1 0 1 1 0 0 +EDGE2 3137 3118 0.988921 0.0422397 0.0225834 1 0 1 1 0 0 +EDGE2 3137 1178 1.00575 0.0187192 -0.00769022 1 0 1 1 0 0 +EDGE2 3137 1198 1.06705 -0.0725527 0.0646137 1 0 1 1 0 0 +EDGE2 3137 1158 0.965454 -0.0271369 0.0225168 1 0 1 1 0 0 +EDGE2 3137 3117 0.0111111 0.0226687 -0.00392719 1 0 1 1 0 0 +EDGE2 3137 3097 -0.0528411 0.117817 0.00202781 1 0 1 1 0 0 +EDGE2 3137 1177 -0.0432587 -0.0375322 -0.00402074 1 0 1 1 0 0 +EDGE2 3137 1157 0.0955374 -0.0363545 0.021604 1 0 1 1 0 0 +EDGE2 3137 1196 -0.964521 0.0635245 -0.00848924 1 0 1 1 0 0 +EDGE2 3137 3116 -0.947882 -0.0311839 -0.0356228 1 0 1 1 0 0 +EDGE2 3137 3136 -0.9413 -0.0910562 -0.0117801 1 0 1 1 0 0 +EDGE2 3137 3096 -1.02411 0.0374747 0.042172 1 0 1 1 0 0 +EDGE2 3137 1156 -1.03581 -0.0243325 -0.00561966 1 0 1 1 0 0 +EDGE2 3137 1176 -1.04265 0.0561362 -0.00327612 1 0 1 1 0 0 +EDGE2 3138 1197 -1.02701 0.0199366 -0.00429297 1 0 1 1 0 0 +EDGE2 3138 3119 1.09787 -0.0651782 -0.0178791 1 0 1 1 0 0 +EDGE2 3138 1179 1.01085 0.139089 -0.0111561 1 0 1 1 0 0 +EDGE2 3138 1199 0.972212 -0.0696479 0.0387206 1 0 1 1 0 0 +EDGE2 3138 3099 1.01319 0.0735097 -0.00133238 1 0 1 1 0 0 +EDGE2 3138 1159 1.00602 0.00428236 -0.0192242 1 0 1 1 0 0 +EDGE2 3138 3098 0.0463263 -0.0598751 0.0286215 1 0 1 1 0 0 +EDGE2 3138 3118 -0.00316478 -0.0864784 0.00633741 1 0 1 1 0 0 +EDGE2 3138 1178 -0.13439 -0.0541625 0.0189457 1 0 1 1 0 0 +EDGE2 3138 1198 -0.0237123 -0.0289374 -0.0192183 1 0 1 1 0 0 +EDGE2 3138 1158 0.0506731 0.0305853 -0.00177397 1 0 1 1 0 0 +EDGE2 3138 3117 -1.0025 0.0117235 -0.0117588 1 0 1 1 0 0 +EDGE2 3138 3137 -0.945231 0.0599822 -0.022979 1 0 1 1 0 0 +EDGE2 3138 3097 -1.03924 -0.00621761 -0.000860506 1 0 1 1 0 0 +EDGE2 3138 1177 -0.90651 0.0611623 -0.00430447 1 0 1 1 0 0 +EDGE2 3138 1157 -1.01809 0.00261281 0.0212562 1 0 1 1 0 0 +EDGE2 3139 1160 0.931611 -0.0116788 -0.00417195 1 0 1 1 0 0 +EDGE2 3139 1200 0.968089 -0.0158151 0.0125768 1 0 1 1 0 0 +EDGE2 3139 3100 0.990735 0.0172471 -0.0444058 1 0 1 1 0 0 +EDGE2 3139 3120 1.10601 -0.0433181 -0.0140975 1 0 1 1 0 0 +EDGE2 3139 1180 0.958222 0.0309327 -0.00950657 1 0 1 1 0 0 +EDGE2 3139 900 1.05197 0.0779821 -3.11719 1 0 1 1 0 0 +EDGE2 3139 840 1.05467 -0.0352608 -3.15015 1 0 1 1 0 0 +EDGE2 3139 860 1.02505 -0.0427007 -3.11382 1 0 1 1 0 0 +EDGE2 3139 3119 -0.103451 -0.0570415 -0.0196137 1 0 1 1 0 0 +EDGE2 3139 1179 0.0272816 0.0425129 -0.00710184 1 0 1 1 0 0 +EDGE2 3139 1199 -0.120657 -0.115816 -0.0163735 1 0 1 1 0 0 +EDGE2 3139 3099 0.0190443 0.000762782 0.000834619 1 0 1 1 0 0 +EDGE2 3139 1159 -0.04846 0.0366936 0.0242625 1 0 1 1 0 0 +EDGE2 3139 3098 -1.07912 -0.0200755 0.00696756 1 0 1 1 0 0 +EDGE2 3139 3138 -0.994127 -0.0844961 -0.00674789 1 0 1 1 0 0 +EDGE2 3139 3118 -1.0434 0.0610078 -0.00450897 1 0 1 1 0 0 +EDGE2 3139 1178 -0.989974 -0.0879524 0.0315338 1 0 1 1 0 0 +EDGE2 3139 1198 -1.05055 -0.0359531 0.0259255 1 0 1 1 0 0 +EDGE2 3139 1158 -0.911329 -0.0814389 -0.00589287 1 0 1 1 0 0 +EDGE2 3140 839 0.970036 0.0401489 -3.16811 1 0 1 1 0 0 +EDGE2 3140 899 0.988092 -0.0273001 -3.17057 1 0 1 1 0 0 +EDGE2 3140 859 1.05067 -0.0486931 -3.1395 1 0 1 1 0 0 +EDGE2 3140 841 -0.00116598 -0.97406 -1.56418 1 0 1 1 0 0 +EDGE2 3140 901 -0.116692 -1.01844 -1.56873 1 0 1 1 0 0 +EDGE2 3140 1201 0.00866543 -0.996975 -1.56704 1 0 1 1 0 0 +EDGE2 3140 861 -0.0303228 -1.061 -1.58638 1 0 1 1 0 0 +EDGE2 3140 1160 0.0248292 0.0143868 0.0152211 1 0 1 1 0 0 +EDGE2 3140 1200 -0.0392714 0.0448958 -0.054994 1 0 1 1 0 0 +EDGE2 3140 3100 -0.0414356 0.0648656 -0.00436008 1 0 1 1 0 0 +EDGE2 3140 3120 0.00250352 0.0870662 0.0645665 1 0 1 1 0 0 +EDGE2 3140 1180 -0.0692061 0.0841227 0.0176059 1 0 1 1 0 0 +EDGE2 3140 900 -0.0344937 0.017662 -3.11952 1 0 1 1 0 0 +EDGE2 3140 840 0.0142968 0.046485 -3.14906 1 0 1 1 0 0 +EDGE2 3140 860 -0.0391816 -0.0318086 -3.1695 1 0 1 1 0 0 +EDGE2 3140 3101 0.0161152 1.01741 1.60703 1 0 1 1 0 0 +EDGE2 3140 3121 0.00759265 0.997574 1.52379 1 0 1 1 0 0 +EDGE2 3140 1161 -0.0358174 0.950952 1.5785 1 0 1 1 0 0 +EDGE2 3140 1181 0.0492036 1.04921 1.56196 1 0 1 1 0 0 +EDGE2 3140 3119 -0.992238 -0.0550053 0.0092301 1 0 1 1 0 0 +EDGE2 3140 3139 -0.964801 -0.086086 -0.000317256 1 0 1 1 0 0 +EDGE2 3140 1179 -0.99462 0.0773744 0.0281931 1 0 1 1 0 0 +EDGE2 3140 1199 -1.01418 -0.0203898 -0.00964445 1 0 1 1 0 0 +EDGE2 3140 3099 -1.0205 -0.0836363 -0.0109086 1 0 1 1 0 0 +EDGE2 3140 1159 -0.981995 -0.0206429 -0.00638933 1 0 1 1 0 0 +EDGE2 3141 1160 -0.948336 0.00351121 -1.55482 1 0 1 1 0 0 +EDGE2 3141 3140 -0.981405 0.0227807 -1.57068 1 0 1 1 0 0 +EDGE2 3141 1200 -1.01088 -0.0374303 -1.53712 1 0 1 1 0 0 +EDGE2 3141 3100 -1.0353 0.0260993 -1.57697 1 0 1 1 0 0 +EDGE2 3141 3120 -0.981727 0.090103 -1.60192 1 0 1 1 0 0 +EDGE2 3141 1180 -1.04189 -0.058648 -1.59922 1 0 1 1 0 0 +EDGE2 3141 900 -0.979706 -0.0411836 1.58414 1 0 1 1 0 0 +EDGE2 3141 840 -1.03338 -0.0465844 1.54296 1 0 1 1 0 0 +EDGE2 3141 860 -0.933919 -0.00349399 1.54923 1 0 1 1 0 0 +EDGE2 3141 3101 -0.0255158 -0.0309064 -0.00834301 1 0 1 1 0 0 +EDGE2 3141 3121 0.0507264 -0.0307925 0.0215682 1 0 1 1 0 0 +EDGE2 3141 1161 -0.0515354 0.085025 -0.0274731 1 0 1 1 0 0 +EDGE2 3141 1181 0.00530385 -0.0661637 -0.00441461 1 0 1 1 0 0 +EDGE2 3141 1182 1.04274 0.0200664 -0.000157765 1 0 1 1 0 0 +EDGE2 3141 3122 0.954128 0.0879537 -0.0539784 1 0 1 1 0 0 +EDGE2 3141 3102 1.11973 -0.00998962 0.0321764 1 0 1 1 0 0 +EDGE2 3141 1162 1.00992 0.0903677 0.0298134 1 0 1 1 0 0 +EDGE2 3142 3101 -1.00532 -0.0815742 0.00359292 1 0 1 1 0 0 +EDGE2 3142 3141 -0.976008 -0.095504 0.000343242 1 0 1 1 0 0 +EDGE2 3142 3121 -0.997898 -0.0321243 0.0121127 1 0 1 1 0 0 +EDGE2 3142 1161 -1.01502 0.022358 0.0045937 1 0 1 1 0 0 +EDGE2 3142 1181 -0.997329 0.0113771 0.0153403 1 0 1 1 0 0 +EDGE2 3142 1182 0.0886229 -0.086999 -0.00753337 1 0 1 1 0 0 +EDGE2 3142 3122 0.0196836 -0.0373428 -0.00632893 1 0 1 1 0 0 +EDGE2 3142 3102 0.0276288 0.00183451 0.0285439 1 0 1 1 0 0 +EDGE2 3142 1162 -0.0162192 0.032992 -0.0285974 1 0 1 1 0 0 +EDGE2 3142 1163 1.12874 -0.0802479 0.0147848 1 0 1 1 0 0 +EDGE2 3142 3103 1.04402 0.0445167 -0.00192638 1 0 1 1 0 0 +EDGE2 3142 3123 1.06717 -0.000154463 -0.0378873 1 0 1 1 0 0 +EDGE2 3142 1183 1.12938 -0.0279459 0.00794162 1 0 1 1 0 0 +EDGE2 3143 1182 -0.995665 0.0318567 0.0210442 1 0 1 1 0 0 +EDGE2 3143 3122 -1.02086 -0.0666091 -0.00637338 1 0 1 1 0 0 +EDGE2 3143 3142 -1.0996 0.0878528 -0.030892 1 0 1 1 0 0 +EDGE2 3143 3102 -1.01065 -0.00660937 -0.0160042 1 0 1 1 0 0 +EDGE2 3143 1162 -1.00581 -0.0537188 -0.00878229 1 0 1 1 0 0 +EDGE2 3143 1163 -0.0415737 -0.109657 -0.0166135 1 0 1 1 0 0 +EDGE2 3143 3103 -0.0199082 0.0847791 -0.0093915 1 0 1 1 0 0 +EDGE2 3143 3123 0.0335888 0.0651016 0.00040107 1 0 1 1 0 0 +EDGE2 3143 1183 -0.0471473 -0.0429874 -0.0149316 1 0 1 1 0 0 +EDGE2 3143 1184 0.975981 -0.0408829 -0.0122504 1 0 1 1 0 0 +EDGE2 3143 3104 0.899145 0.0631131 0.00968281 1 0 1 1 0 0 +EDGE2 3143 3124 1.04639 -0.105529 0.0169429 1 0 1 1 0 0 +EDGE2 3143 1164 0.98572 -0.0205482 -0.0484262 1 0 1 1 0 0 +EDGE2 3144 1163 -1.01554 0.0135347 0.021742 1 0 1 1 0 0 +EDGE2 3144 3103 -0.920732 0.0526802 0.00348428 1 0 1 1 0 0 +EDGE2 3144 3123 -1.00664 -0.0133535 -0.000787951 1 0 1 1 0 0 +EDGE2 3144 3143 -0.969683 0.108955 0.0207464 1 0 1 1 0 0 +EDGE2 3144 1183 -0.970612 0.043943 -0.00398419 1 0 1 1 0 0 +EDGE2 3144 1184 0.151067 0.111396 0.0361019 1 0 1 1 0 0 +EDGE2 3144 3104 0.0140245 -0.00426155 -0.00432751 1 0 1 1 0 0 +EDGE2 3144 3124 0.012009 0.0314335 0.0221425 1 0 1 1 0 0 +EDGE2 3144 1164 -0.105953 -0.0356907 0.0133155 1 0 1 1 0 0 +EDGE2 3144 3105 0.921003 -0.0642959 -0.0226107 1 0 1 1 0 0 +EDGE2 3144 3125 0.960328 -0.00387973 -0.0593326 1 0 1 1 0 0 +EDGE2 3144 1185 1.03649 0.00167481 0.0296805 1 0 1 1 0 0 +EDGE2 3144 3065 0.959341 0.0891107 -3.1633 1 0 1 1 0 0 +EDGE2 3144 3085 1.13868 -0.0271776 -3.14249 1 0 1 1 0 0 +EDGE2 3144 1165 0.914261 -0.0265286 -0.0145923 1 0 1 1 0 0 +EDGE2 3145 3066 0.0443293 -1.0214 -1.59781 1 0 1 1 0 0 +EDGE2 3145 3144 -1.02978 -0.0391685 0.0166336 1 0 1 1 0 0 +EDGE2 3145 1184 -0.944609 0.0342045 0.0276537 1 0 1 1 0 0 +EDGE2 3145 3104 -0.931366 0.0694984 0.00798916 1 0 1 1 0 0 +EDGE2 3145 3124 -0.991802 -0.0282165 0.0222895 1 0 1 1 0 0 +EDGE2 3145 1164 -0.989807 0.0288276 -0.00114675 1 0 1 1 0 0 +EDGE2 3145 3105 0.00635024 0.0353814 0.000893241 1 0 1 1 0 0 +EDGE2 3145 3125 0.054849 -0.023824 0.00281327 1 0 1 1 0 0 +EDGE2 3145 1185 -0.0257553 -0.00972873 0.000287381 1 0 1 1 0 0 +EDGE2 3145 3065 -0.0394245 -0.0231717 -3.14309 1 0 1 1 0 0 +EDGE2 3145 3085 0.0534475 -0.0681178 -3.16492 1 0 1 1 0 0 +EDGE2 3145 1165 -0.00944476 0.042709 -0.0229036 1 0 1 1 0 0 +EDGE2 3145 1166 0.0958051 1.03899 1.60343 1 0 1 1 0 0 +EDGE2 3145 3086 0.0557719 0.923832 1.57947 1 0 1 1 0 0 +EDGE2 3145 3106 -0.0345144 1.00749 1.57512 1 0 1 1 0 0 +EDGE2 3145 3126 0.099405 0.996649 1.56861 1 0 1 1 0 0 +EDGE2 3145 1186 -0.0639509 1.06247 1.59869 1 0 1 1 0 0 +EDGE2 3145 3064 0.959865 -0.0364822 -3.16013 1 0 1 1 0 0 +EDGE2 3145 3084 1.01952 -0.0358436 -3.15404 1 0 1 1 0 0 +EDGE2 3146 3067 1.03104 -0.0333347 -0.0147038 1 0 1 1 0 0 +EDGE2 3146 3066 0.00155063 -0.122629 -0.0128028 1 0 1 1 0 0 +EDGE2 3146 3105 -0.982426 0.0429655 1.58688 1 0 1 1 0 0 +EDGE2 3146 3145 -0.988411 0.0436499 1.59027 1 0 1 1 0 0 +EDGE2 3146 3125 -0.998953 0.00602966 1.57784 1 0 1 1 0 0 +EDGE2 3146 1185 -0.918902 -0.0323935 1.59519 1 0 1 1 0 0 +EDGE2 3146 3065 -0.928261 -0.0138994 -1.56036 1 0 1 1 0 0 +EDGE2 3146 3085 -0.965141 0.0710099 -1.5536 1 0 1 1 0 0 +EDGE2 3146 1165 -0.946195 -0.0376982 1.55932 1 0 1 1 0 0 +EDGE2 3147 3068 0.899995 -0.00380379 -0.0205456 1 0 1 1 0 0 +EDGE2 3147 3067 0.0504037 -0.0511331 0.0488272 1 0 1 1 0 0 +EDGE2 3147 3146 -0.995705 -0.0327769 -0.0111823 1 0 1 1 0 0 +EDGE2 3147 3066 -1.02943 -0.0208597 -0.0131505 1 0 1 1 0 0 +EDGE2 3148 3069 1.03847 -0.0860988 -0.0307464 1 0 1 1 0 0 +EDGE2 3148 3068 -0.064436 -0.0277377 -0.0146049 1 0 1 1 0 0 +EDGE2 3148 3147 -1.01904 -0.0038581 -0.00302749 1 0 1 1 0 0 +EDGE2 3148 3067 -1.07504 0.00735625 -0.0260645 1 0 1 1 0 0 +EDGE2 3149 3070 1.02217 0.0482265 -0.0255506 1 0 1 1 0 0 +EDGE2 3149 3069 -0.01508 0.0122282 -0.00108194 1 0 1 1 0 0 +EDGE2 3149 3068 -1.03806 -0.00461645 0.00796663 1 0 1 1 0 0 +EDGE2 3149 3148 -0.992342 0.0916516 -0.00194085 1 0 1 1 0 0 +EDGE2 3150 3070 -0.0308708 -0.0304048 -0.0234581 1 0 1 1 0 0 +EDGE2 3150 3149 -1.0125 0.0150383 -0.0335111 1 0 1 1 0 0 +EDGE2 3150 3069 -0.983116 -0.0487463 -0.0409738 1 0 1 1 0 0 +EDGE2 3150 3071 -0.0282904 0.981046 1.57948 1 0 1 1 0 0 +EDGE2 3151 3070 -0.92228 0.0528985 -1.57608 1 0 1 1 0 0 +EDGE2 3151 3150 -1.06522 -0.0359037 -1.57431 1 0 1 1 0 0 +EDGE2 3151 3072 1.00112 0.0131499 0.0180212 1 0 1 1 0 0 +EDGE2 3151 3071 -0.0431542 0.00442038 0.0148609 1 0 1 1 0 0 +EDGE2 3152 3072 0.0198713 0.0183487 0.015247 1 0 1 1 0 0 +EDGE2 3152 3151 -1.03278 0.00224316 0.000543055 1 0 1 1 0 0 +EDGE2 3152 3071 -0.997758 0.00922231 0.041222 1 0 1 1 0 0 +EDGE2 3152 3073 0.934915 0.0194433 0.0183259 1 0 1 1 0 0 +EDGE2 3153 3072 -0.982084 0.0951747 -0.0102818 1 0 1 1 0 0 +EDGE2 3153 3152 -0.889184 0.106878 -0.0143666 1 0 1 1 0 0 +EDGE2 3153 3073 0.0656449 0.00262358 0.00294157 1 0 1 1 0 0 +EDGE2 3153 3074 1.00711 -0.00332277 0.0181496 1 0 1 1 0 0 +EDGE2 3154 3153 -0.975219 0.0160881 0.0155484 1 0 1 1 0 0 +EDGE2 3154 3073 -0.95863 -0.122792 0.0290363 1 0 1 1 0 0 +EDGE2 3154 1075 0.931026 0.0531235 -3.15978 1 0 1 1 0 0 +EDGE2 3154 3074 -0.0123394 -0.0430334 0.00356438 1 0 1 1 0 0 +EDGE2 3154 3075 1.02695 0.00372126 -0.00329122 1 0 1 1 0 0 +EDGE2 3154 995 0.96515 0.0292569 -3.13678 1 0 1 1 0 0 +EDGE2 3154 1015 1.02268 -0.0337657 -3.13069 1 0 1 1 0 0 +EDGE2 3154 1055 1.01903 -0.0472922 -3.14998 1 0 1 1 0 0 +EDGE2 3155 1016 -0.0194279 -0.934375 -1.56006 1 0 1 1 0 0 +EDGE2 3155 1056 -0.00559049 -1.00073 -1.56766 1 0 1 1 0 0 +EDGE2 3155 996 0.0160093 -0.97862 -1.60409 1 0 1 1 0 0 +EDGE2 3155 1075 -0.00622451 -0.00595116 -3.14989 1 0 1 1 0 0 +EDGE2 3155 3074 -0.97284 -0.0492524 0.0189504 1 0 1 1 0 0 +EDGE2 3155 3154 -0.940695 0.0368912 0.0240216 1 0 1 1 0 0 +EDGE2 3155 3075 -0.0143787 -0.0306211 0.0261281 1 0 1 1 0 0 +EDGE2 3155 1074 1.04007 0.0251794 -3.13492 1 0 1 1 0 0 +EDGE2 3155 995 -0.0178278 -0.0593046 -3.14097 1 0 1 1 0 0 +EDGE2 3155 1015 0.0716022 0.063137 -3.15349 1 0 1 1 0 0 +EDGE2 3155 1055 0.0324806 -0.00406974 -3.16365 1 0 1 1 0 0 +EDGE2 3155 1014 1.03395 0.0456207 -3.1168 1 0 1 1 0 0 +EDGE2 3155 1054 0.954776 0.0110783 -3.15401 1 0 1 1 0 0 +EDGE2 3155 994 0.979822 -0.0155077 -3.14577 1 0 1 1 0 0 +EDGE2 3155 1076 0.0736412 0.993203 1.58299 1 0 1 1 0 0 +EDGE2 3155 3076 0.00475362 1.02664 1.54858 1 0 1 1 0 0 +EDGE2 3156 1075 -1.12198 -0.0135964 1.58617 1 0 1 1 0 0 +EDGE2 3156 3155 -0.994349 -0.0423163 -1.58749 1 0 1 1 0 0 +EDGE2 3156 3075 -1.0398 -0.0412255 -1.61109 1 0 1 1 0 0 +EDGE2 3156 995 -0.983339 0.0461225 1.57421 1 0 1 1 0 0 +EDGE2 3156 1015 -1.02675 -0.0487056 1.59169 1 0 1 1 0 0 +EDGE2 3156 1055 -1.06316 0.0560612 1.53804 1 0 1 1 0 0 +EDGE2 3156 1076 -0.0464018 0.0255194 -0.00532415 1 0 1 1 0 0 +EDGE2 3156 3076 0.0301494 -0.00615769 0.0218365 1 0 1 1 0 0 +EDGE2 3156 3077 1.05651 0.014906 0.00914684 1 0 1 1 0 0 +EDGE2 3156 1077 1.05227 0.0232793 0.00715074 1 0 1 1 0 0 +EDGE2 3157 3078 0.884501 -0.0447799 -0.00547679 1 0 1 1 0 0 +EDGE2 3157 3156 -1.04625 -0.00291768 -0.00555044 1 0 1 1 0 0 +EDGE2 3157 1076 -1.00838 0.0239544 -0.0105439 1 0 1 1 0 0 +EDGE2 3157 3076 -1.03356 0.0276252 -0.0122331 1 0 1 1 0 0 +EDGE2 3157 3077 0.0508433 0.0262351 -0.0212323 1 0 1 1 0 0 +EDGE2 3157 1077 -0.0563092 -0.0226638 -0.00260297 1 0 1 1 0 0 +EDGE2 3157 1078 1.02568 -0.026823 -0.0468144 1 0 1 1 0 0 +EDGE2 3158 3078 0.0963264 0.0544233 -0.00173958 1 0 1 1 0 0 +EDGE2 3158 3077 -1.02587 -0.0603783 0.0150221 1 0 1 1 0 0 +EDGE2 3158 3157 -0.953699 0.00854181 -0.0335917 1 0 1 1 0 0 +EDGE2 3158 1077 -1.05624 0.00554773 -0.00110221 1 0 1 1 0 0 +EDGE2 3158 1078 0.03634 0.00708104 -0.0167257 1 0 1 1 0 0 +EDGE2 3158 3079 0.931124 0.0164387 0.0261152 1 0 1 1 0 0 +EDGE2 3158 1079 1.04292 -0.0390646 -0.023122 1 0 1 1 0 0 +EDGE2 3159 3078 -1.02369 -0.0680633 -0.00445703 1 0 1 1 0 0 +EDGE2 3159 3158 -1.03905 -0.0340699 0.0260946 1 0 1 1 0 0 +EDGE2 3159 1078 -0.977532 -0.0534683 0.027362 1 0 1 1 0 0 +EDGE2 3159 3079 0.0477877 -0.0083874 -0.0262119 1 0 1 1 0 0 +EDGE2 3159 1079 -0.0713267 -0.0427341 -0.0110674 1 0 1 1 0 0 +EDGE2 3159 3060 0.944916 -0.0252201 -3.13539 1 0 1 1 0 0 +EDGE2 3159 3080 0.968234 0.00891883 -0.0143779 1 0 1 1 0 0 +EDGE2 3159 1080 1.03808 0.0181639 -0.0199649 1 0 1 1 0 0 +EDGE2 3160 3079 -0.972272 -0.0678002 0.0264499 1 0 1 1 0 0 +EDGE2 3160 3159 -0.941357 -0.0784231 0.0353929 1 0 1 1 0 0 +EDGE2 3160 1079 -0.967573 -0.0382999 -0.0115998 1 0 1 1 0 0 +EDGE2 3160 3081 0.00229169 0.965678 1.61094 1 0 1 1 0 0 +EDGE2 3160 3061 -0.0100885 0.988086 1.60402 1 0 1 1 0 0 +EDGE2 3160 3060 -0.0372447 -0.0128384 -3.15659 1 0 1 1 0 0 +EDGE2 3160 3080 -0.0406051 -0.0697047 0.0225275 1 0 1 1 0 0 +EDGE2 3160 1080 0.0427118 0.0423644 0.00985705 1 0 1 1 0 0 +EDGE2 3160 1081 -0.100489 -1.05275 -1.53667 1 0 1 1 0 0 +EDGE2 3160 3059 1.0513 -0.0275376 -3.11281 1 0 1 1 0 0 +EDGE2 3161 3082 0.996681 0.050206 0.0552693 1 0 1 1 0 0 +EDGE2 3161 3062 0.978095 -0.0747071 0.0113748 1 0 1 1 0 0 +EDGE2 3161 3081 0.0589209 0.0104297 -0.0250078 1 0 1 1 0 0 +EDGE2 3161 3061 -0.0160703 0.00835731 0.0232158 1 0 1 1 0 0 +EDGE2 3161 3060 -1.06291 0.0117868 1.56409 1 0 1 1 0 0 +EDGE2 3161 3160 -1.05773 -0.104942 -1.56314 1 0 1 1 0 0 +EDGE2 3161 3080 -0.948831 0.00761268 -1.55883 1 0 1 1 0 0 +EDGE2 3161 1080 -1.075 -0.0754324 -1.58244 1 0 1 1 0 0 +EDGE2 3162 3083 0.999815 -0.0121812 0.023343 1 0 1 1 0 0 +EDGE2 3162 3063 1.04195 -0.0245156 0.0073115 1 0 1 1 0 0 +EDGE2 3162 3082 0.0374214 0.0152209 0.00472455 1 0 1 1 0 0 +EDGE2 3162 3062 -0.0299867 0.0986618 0.0136449 1 0 1 1 0 0 +EDGE2 3162 3081 -1.07961 -0.0682462 -0.0281639 1 0 1 1 0 0 +EDGE2 3162 3161 -1.01242 0.0738527 -0.0180841 1 0 1 1 0 0 +EDGE2 3162 3061 -1.09105 0.035219 -0.00265897 1 0 1 1 0 0 +EDGE2 3163 3064 0.938346 -0.0766965 0.0266273 1 0 1 1 0 0 +EDGE2 3163 3084 1.01954 -0.0984529 -0.0160242 1 0 1 1 0 0 +EDGE2 3163 3083 -0.0417008 -0.0310368 -0.0147568 1 0 1 1 0 0 +EDGE2 3163 3063 0.00793836 -0.0179977 0.0103637 1 0 1 1 0 0 +EDGE2 3163 3082 -1.01222 0.0543789 0.000255829 1 0 1 1 0 0 +EDGE2 3163 3162 -0.955784 -0.0520359 0.036082 1 0 1 1 0 0 +EDGE2 3163 3062 -0.997222 -0.0993556 -0.00744895 1 0 1 1 0 0 +EDGE2 3164 3105 1.01053 0.00227043 -3.14205 1 0 1 1 0 0 +EDGE2 3164 3145 1.01363 -0.00970722 -3.14238 1 0 1 1 0 0 +EDGE2 3164 3125 1.03121 0.0392444 -3.1568 1 0 1 1 0 0 +EDGE2 3164 1185 0.9881 0.0418384 -3.16561 1 0 1 1 0 0 +EDGE2 3164 3065 0.904065 -0.0455411 0.00411368 1 0 1 1 0 0 +EDGE2 3164 3085 0.99458 0.0238196 0.0263489 1 0 1 1 0 0 +EDGE2 3164 1165 1.03314 0.0404574 -3.19385 1 0 1 1 0 0 +EDGE2 3164 3064 0.102998 -0.0157574 0.000306145 1 0 1 1 0 0 +EDGE2 3164 3084 0.0474337 -0.013032 -0.00795512 1 0 1 1 0 0 +EDGE2 3164 3083 -1.05137 0.0131383 -0.00773334 1 0 1 1 0 0 +EDGE2 3164 3163 -0.942459 0.0841484 -0.01014 1 0 1 1 0 0 +EDGE2 3164 3063 -0.91081 -0.0144961 0.00302224 1 0 1 1 0 0 +EDGE2 3165 3146 0.0392112 0.959237 1.53092 1 0 1 1 0 0 +EDGE2 3165 3066 -0.0167164 0.948377 1.58934 1 0 1 1 0 0 +EDGE2 3165 3144 0.94988 -0.00912715 -3.12254 1 0 1 1 0 0 +EDGE2 3165 1184 0.984079 0.0113776 -3.13571 1 0 1 1 0 0 +EDGE2 3165 3104 1.05248 0.0754325 -3.1737 1 0 1 1 0 0 +EDGE2 3165 3124 1.02574 -0.0275527 -3.15825 1 0 1 1 0 0 +EDGE2 3165 1164 0.960353 0.0849138 -3.14229 1 0 1 1 0 0 +EDGE2 3165 3105 0.0259619 0.0216593 -3.16698 1 0 1 1 0 0 +EDGE2 3165 3145 0.0421819 0.0685747 -3.14929 1 0 1 1 0 0 +EDGE2 3165 3125 0.0186068 -0.00337898 -3.15313 1 0 1 1 0 0 +EDGE2 3165 1185 -0.0678458 -0.0356668 -3.15708 1 0 1 1 0 0 +EDGE2 3165 3065 0.0566836 -0.00761792 0.0133452 1 0 1 1 0 0 +EDGE2 3165 3085 0.0184731 -0.00689276 0.0216324 1 0 1 1 0 0 +EDGE2 3165 1165 0.00769479 -0.0129101 -3.15456 1 0 1 1 0 0 +EDGE2 3165 1166 0.00747373 -1.04739 -1.56329 1 0 1 1 0 0 +EDGE2 3165 3086 -0.0594043 -1.08072 -1.56545 1 0 1 1 0 0 +EDGE2 3165 3106 -0.0185243 -0.964827 -1.57358 1 0 1 1 0 0 +EDGE2 3165 3126 -0.0221984 -0.868938 -1.57869 1 0 1 1 0 0 +EDGE2 3165 1186 0.068168 -1.09108 -1.57575 1 0 1 1 0 0 +EDGE2 3165 3064 -1.00459 0.0089002 0.000478975 1 0 1 1 0 0 +EDGE2 3165 3164 -0.962506 0.0280238 -0.0145361 1 0 1 1 0 0 +EDGE2 3165 3084 -0.984229 0.0466877 0.0205446 1 0 1 1 0 0 +EDGE2 3166 3105 -1.02204 0.00986103 -1.54431 1 0 1 1 0 0 +EDGE2 3166 3145 -0.949523 0.0501264 -1.55463 1 0 1 1 0 0 +EDGE2 3166 3165 -1.08618 0.00657749 1.57039 1 0 1 1 0 0 +EDGE2 3166 3125 -1.14164 -0.0408698 -1.59011 1 0 1 1 0 0 +EDGE2 3166 1185 -1.03801 -0.020922 -1.5425 1 0 1 1 0 0 +EDGE2 3166 3065 -1.01807 0.0349904 1.56145 1 0 1 1 0 0 +EDGE2 3166 3085 -1.03482 0.0378445 1.56505 1 0 1 1 0 0 +EDGE2 3166 1165 -0.948844 -0.137067 -1.56902 1 0 1 1 0 0 +EDGE2 3166 1166 0.0179213 -0.0651341 -0.00424117 1 0 1 1 0 0 +EDGE2 3166 3086 -0.00571501 -0.0501168 -0.0395513 1 0 1 1 0 0 +EDGE2 3166 3106 -0.0270248 -0.0948697 -0.0170849 1 0 1 1 0 0 +EDGE2 3166 3126 -0.0564111 -0.122135 0.0217776 1 0 1 1 0 0 +EDGE2 3166 1186 -0.0285833 -0.123962 -0.0285918 1 0 1 1 0 0 +EDGE2 3166 3107 0.881513 -0.0810008 0.00992583 1 0 1 1 0 0 +EDGE2 3166 3127 1.02349 0.0243715 0.00137798 1 0 1 1 0 0 +EDGE2 3166 1187 0.921046 -0.00894323 0.00907889 1 0 1 1 0 0 +EDGE2 3166 3087 1.01555 -0.00441466 -0.00339037 1 0 1 1 0 0 +EDGE2 3166 1167 0.965836 0.0946619 -0.00689553 1 0 1 1 0 0 +EDGE2 3167 3166 -0.989717 0.00783919 0.0133441 1 0 1 1 0 0 +EDGE2 3167 1166 -1.10115 0.0292383 0.0245365 1 0 1 1 0 0 +EDGE2 3167 3086 -1.10559 -0.0313921 0.0168843 1 0 1 1 0 0 +EDGE2 3167 3106 -1.02258 -0.0267258 0.011618 1 0 1 1 0 0 +EDGE2 3167 3126 -1.04061 0.0790997 0.0306487 1 0 1 1 0 0 +EDGE2 3167 1186 -0.879372 -0.0955635 -0.00889773 1 0 1 1 0 0 +EDGE2 3167 3107 -0.00857201 0.0314892 0.022076 1 0 1 1 0 0 +EDGE2 3167 3127 -0.0101991 -0.00276335 -0.00687365 1 0 1 1 0 0 +EDGE2 3167 1187 0.00857777 -0.0257028 0.0245948 1 0 1 1 0 0 +EDGE2 3167 3087 -0.00819382 -0.0151903 0.0103765 1 0 1 1 0 0 +EDGE2 3167 1167 -0.0331156 0.123886 0.00251876 1 0 1 1 0 0 +EDGE2 3167 3128 0.980098 0.03776 0.0247748 1 0 1 1 0 0 +EDGE2 3167 1188 0.995818 0.0207794 0.00503039 1 0 1 1 0 0 +EDGE2 3167 3088 0.936341 -0.0218285 -0.0231412 1 0 1 1 0 0 +EDGE2 3167 3108 0.953961 0.00125604 0.000984147 1 0 1 1 0 0 +EDGE2 3167 1168 0.956638 -0.035238 0.0020492 1 0 1 1 0 0 +EDGE2 3168 3107 -1.03717 -0.0297723 0.0121877 1 0 1 1 0 0 +EDGE2 3168 3167 -0.995715 -0.0154196 -0.00986208 1 0 1 1 0 0 +EDGE2 3168 3127 -0.927021 -0.0444516 -0.0312084 1 0 1 1 0 0 +EDGE2 3168 1187 -1.0229 0.027638 -0.0385246 1 0 1 1 0 0 +EDGE2 3168 3087 -0.975397 -0.0371647 0.00984928 1 0 1 1 0 0 +EDGE2 3168 1167 -1.04686 -0.0195496 -0.00442236 1 0 1 1 0 0 +EDGE2 3168 3128 0.0985286 -0.0929687 0.0106389 1 0 1 1 0 0 +EDGE2 3168 1188 -0.0558406 -0.0407678 -0.0223048 1 0 1 1 0 0 +EDGE2 3168 3088 0.00369958 -0.053173 0.00398612 1 0 1 1 0 0 +EDGE2 3168 3108 0.0242602 0.0221795 0.0311784 1 0 1 1 0 0 +EDGE2 3168 1168 -0.0120404 0.000512593 -0.0085767 1 0 1 1 0 0 +EDGE2 3168 3109 1.04706 -0.0126665 0.0111368 1 0 1 1 0 0 +EDGE2 3168 3129 1.06045 -0.0275035 0.00753907 1 0 1 1 0 0 +EDGE2 3168 1189 0.944948 0.0773406 0.0119228 1 0 1 1 0 0 +EDGE2 3168 3089 1.05544 0.0223928 -0.0257337 1 0 1 1 0 0 +EDGE2 3168 1169 0.97723 -0.017581 0.0160117 1 0 1 1 0 0 +EDGE2 3169 3128 -1.0116 -0.0194624 -0.00718235 1 0 1 1 0 0 +EDGE2 3169 3168 -1.03563 0.0928618 -0.0398308 1 0 1 1 0 0 +EDGE2 3169 1188 -0.981462 0.0216775 0.00341589 1 0 1 1 0 0 +EDGE2 3169 3088 -0.983827 0.00442579 -0.017878 1 0 1 1 0 0 +EDGE2 3169 3108 -0.972263 -0.00507584 -0.0128734 1 0 1 1 0 0 +EDGE2 3169 1168 -1.06119 0.0479086 0.00187157 1 0 1 1 0 0 +EDGE2 3169 3109 -0.0022129 0.0296505 0.0198605 1 0 1 1 0 0 +EDGE2 3169 3129 -0.0651431 -0.0600253 -0.00790648 1 0 1 1 0 0 +EDGE2 3169 1189 -0.070224 -0.0412819 0.00434228 1 0 1 1 0 0 +EDGE2 3169 3089 0.0307119 0.0214365 0.00641903 1 0 1 1 0 0 +EDGE2 3169 1169 -0.0984251 0.107396 0.021431 1 0 1 1 0 0 +EDGE2 3169 3050 1.03815 0.0124015 -3.14097 1 0 1 1 0 0 +EDGE2 3169 3110 1.01866 -0.0371588 -0.00742752 1 0 1 1 0 0 +EDGE2 3169 3130 1.00112 -0.0321108 -0.033529 1 0 1 1 0 0 +EDGE2 3169 3090 0.955151 0.0358367 0.016615 1 0 1 1 0 0 +EDGE2 3169 1130 1.0194 0.0452878 -3.17585 1 0 1 1 0 0 +EDGE2 3169 1170 1.00215 0.0459063 0.0204179 1 0 1 1 0 0 +EDGE2 3169 1190 1.02472 -0.00469961 -0.000674306 1 0 1 1 0 0 +EDGE2 3169 3030 0.97948 -0.0223167 -3.16289 1 0 1 1 0 0 +EDGE2 3169 1150 1.05634 -0.0630211 -3.15629 1 0 1 1 0 0 +EDGE2 3169 1110 1.0061 -0.0203933 -3.1572 1 0 1 1 0 0 +EDGE2 3170 3109 -1.05246 0.0147346 0.0293362 1 0 1 1 0 0 +EDGE2 3170 3169 -1.04963 -0.0138293 -0.012001 1 0 1 1 0 0 +EDGE2 3170 3129 -1.04328 0.0430953 -0.0142457 1 0 1 1 0 0 +EDGE2 3170 1189 -0.993473 0.0217006 -0.00365975 1 0 1 1 0 0 +EDGE2 3170 3089 -1.04297 -0.0159814 0.00800284 1 0 1 1 0 0 +EDGE2 3170 1169 -1.00195 0.00864525 0.00733178 1 0 1 1 0 0 +EDGE2 3170 3050 0.00838551 -0.0246663 -3.13787 1 0 1 1 0 0 +EDGE2 3170 3131 0.0536842 0.927726 1.56077 1 0 1 1 0 0 +EDGE2 3170 1151 -0.0294682 0.991555 1.57003 1 0 1 1 0 0 +EDGE2 3170 1191 0.0327235 1.06071 1.57987 1 0 1 1 0 0 +EDGE2 3170 3091 -0.0810581 0.936761 1.56943 1 0 1 1 0 0 +EDGE2 3170 3111 -0.0245107 0.976416 1.57421 1 0 1 1 0 0 +EDGE2 3170 1171 0.0519158 1.06078 1.54928 1 0 1 1 0 0 +EDGE2 3170 3110 -0.0956445 0.0905747 0.0325326 1 0 1 1 0 0 +EDGE2 3170 3130 -0.00836671 0.031416 -0.00162107 1 0 1 1 0 0 +EDGE2 3170 3090 -0.0585348 -0.0445046 0.0246279 1 0 1 1 0 0 +EDGE2 3170 1130 -0.0252505 -0.0301184 -3.15696 1 0 1 1 0 0 +EDGE2 3170 1170 0.0662666 0.0253625 0.0101265 1 0 1 1 0 0 +EDGE2 3170 1190 -0.0154295 0.0108265 0.01473 1 0 1 1 0 0 +EDGE2 3170 3030 0.0236395 -2.46947e-05 -3.15871 1 0 1 1 0 0 +EDGE2 3170 1150 -0.0495841 0.100988 -3.09421 1 0 1 1 0 0 +EDGE2 3170 1110 0.0257649 0.038156 -3.16355 1 0 1 1 0 0 +EDGE2 3170 1109 1.00791 -0.0376761 -3.14011 1 0 1 1 0 0 +EDGE2 3170 1149 1.00161 -0.00861055 -3.16649 1 0 1 1 0 0 +EDGE2 3170 3029 1.00109 -0.108544 -3.16636 1 0 1 1 0 0 +EDGE2 3170 3049 0.977107 0.0105048 -3.16184 1 0 1 1 0 0 +EDGE2 3170 1129 1.0195 -0.0294964 -3.15681 1 0 1 1 0 0 +EDGE2 3170 1111 -0.0420924 -0.949091 -1.55223 1 0 1 1 0 0 +EDGE2 3170 3031 -0.0126073 -1.04512 -1.56799 1 0 1 1 0 0 +EDGE2 3170 3051 0.00428877 -1.02005 -1.60923 1 0 1 1 0 0 +EDGE2 3170 1131 -0.0262235 -0.993582 -1.5643 1 0 1 1 0 0 +EDGE2 3171 3050 -1.06452 -0.105096 1.53892 1 0 1 1 0 0 +EDGE2 3171 3131 -0.0317846 -0.0761848 -0.0257148 1 0 1 1 0 0 +EDGE2 3171 3092 1.04907 -0.0168966 0.0221853 1 0 1 1 0 0 +EDGE2 3171 3132 1.01577 0.0776644 0.0258626 1 0 1 1 0 0 +EDGE2 3171 3112 1.02673 -0.0209315 0.0270979 1 0 1 1 0 0 +EDGE2 3171 1152 1.03672 0.0234525 0.0323433 1 0 1 1 0 0 +EDGE2 3171 1172 0.967812 -0.0193404 -0.0262698 1 0 1 1 0 0 +EDGE2 3171 1192 1.04973 0.0907543 0.0023262 1 0 1 1 0 0 +EDGE2 3171 1151 0.0293993 0.0365945 0.00680812 1 0 1 1 0 0 +EDGE2 3171 1191 0.122494 0.0253643 0.0126694 1 0 1 1 0 0 +EDGE2 3171 3091 -0.0654962 0.00449766 0.0097811 1 0 1 1 0 0 +EDGE2 3171 3111 -0.00880566 -0.0297151 0.0322498 1 0 1 1 0 0 +EDGE2 3171 1171 -0.00338565 -0.0147919 0.00170915 1 0 1 1 0 0 +EDGE2 3171 3170 -0.989174 -0.0442478 -1.53367 1 0 1 1 0 0 +EDGE2 3171 3110 -1.08639 -0.0727622 -1.56043 1 0 1 1 0 0 +EDGE2 3171 3130 -0.978378 0.0033282 -1.51058 1 0 1 1 0 0 +EDGE2 3171 3090 -1.00275 0.0864707 -1.58495 1 0 1 1 0 0 +EDGE2 3171 1130 -1.08115 0.00701124 1.5646 1 0 1 1 0 0 +EDGE2 3171 1170 -1.03112 -0.0370351 -1.59705 1 0 1 1 0 0 +EDGE2 3171 1190 -1.01591 0.0131046 -1.56782 1 0 1 1 0 0 +EDGE2 3171 3030 -0.967867 -0.0318928 1.55976 1 0 1 1 0 0 +EDGE2 3171 1150 -0.991647 -0.0100194 1.59537 1 0 1 1 0 0 +EDGE2 3171 1110 -1.02517 0.0626187 1.55531 1 0 1 1 0 0 +EDGE2 3172 1173 1.09594 0.0336911 0.0216023 1 0 1 1 0 0 +EDGE2 3172 3133 1.0897 0.0258511 0.00669304 1 0 1 1 0 0 +EDGE2 3172 3093 0.983789 -0.00925793 -0.0382873 1 0 1 1 0 0 +EDGE2 3172 3113 0.951334 0.0335642 0.00765649 1 0 1 1 0 0 +EDGE2 3172 1193 1.06523 0.0746585 -0.0104841 1 0 1 1 0 0 +EDGE2 3172 3131 -1.08009 0.00299223 0.0313744 1 0 1 1 0 0 +EDGE2 3172 3092 0.0270964 0.0197959 -0.0289801 1 0 1 1 0 0 +EDGE2 3172 1153 0.916608 0.00581057 -0.0340363 1 0 1 1 0 0 +EDGE2 3172 3132 0.0376455 -0.0184001 -0.0233946 1 0 1 1 0 0 +EDGE2 3172 3112 -0.0232906 -0.0836381 -0.00512103 1 0 1 1 0 0 +EDGE2 3172 1152 0.0100561 -0.0372074 0.000888143 1 0 1 1 0 0 +EDGE2 3172 1172 -0.135402 0.0414825 -0.00242759 1 0 1 1 0 0 +EDGE2 3172 1192 -0.0671224 0.0283564 -0.00980561 1 0 1 1 0 0 +EDGE2 3172 3171 -1.05003 0.0357237 -0.0020998 1 0 1 1 0 0 +EDGE2 3172 1151 -0.957476 -0.135942 -0.0183123 1 0 1 1 0 0 +EDGE2 3172 1191 -0.988738 0.0254688 -0.00157012 1 0 1 1 0 0 +EDGE2 3172 3091 -0.965867 -0.0438093 0.00831286 1 0 1 1 0 0 +EDGE2 3172 3111 -1.06474 0.0183564 0.0122794 1 0 1 1 0 0 +EDGE2 3172 1171 -1.0205 0.0245244 -0.0156625 1 0 1 1 0 0 +EDGE2 3173 1173 -0.0564207 0.00192061 -0.0157589 1 0 1 1 0 0 +EDGE2 3173 1174 0.991533 0.00402678 0.00793018 1 0 1 1 0 0 +EDGE2 3173 3094 0.982539 0.0202022 0.0252271 1 0 1 1 0 0 +EDGE2 3173 3114 0.955476 0.00797798 -0.0134231 1 0 1 1 0 0 +EDGE2 3173 3134 1.03026 -0.0349886 0.0205037 1 0 1 1 0 0 +EDGE2 3173 1194 0.988431 0.0255124 -0.00888267 1 0 1 1 0 0 +EDGE2 3173 1154 0.972441 0.0366088 -0.0201059 1 0 1 1 0 0 +EDGE2 3173 3133 0.0608187 0.111914 0.00584699 1 0 1 1 0 0 +EDGE2 3173 3093 0.0993934 0.0568787 0.0122948 1 0 1 1 0 0 +EDGE2 3173 3113 0.0210871 -0.0326048 -0.0119521 1 0 1 1 0 0 +EDGE2 3173 1193 0.0174357 0.000841952 -0.0114682 1 0 1 1 0 0 +EDGE2 3173 3092 -1.07879 -0.0191633 -0.0196851 1 0 1 1 0 0 +EDGE2 3173 1153 -0.018864 -0.0036339 -0.0204027 1 0 1 1 0 0 +EDGE2 3173 3132 -1.01416 0.0385415 -0.00564576 1 0 1 1 0 0 +EDGE2 3173 3172 -1.07959 0.0618072 -0.0109804 1 0 1 1 0 0 +EDGE2 3173 3112 -1.04584 0.0541744 -0.0264025 1 0 1 1 0 0 +EDGE2 3173 1152 -0.960344 -0.071036 -0.00606982 1 0 1 1 0 0 +EDGE2 3173 1172 -1.00754 0.0106122 0.000508089 1 0 1 1 0 0 +EDGE2 3173 1192 -1.03884 0.0485554 0.00567262 1 0 1 1 0 0 +EDGE2 3174 1173 -1.09148 0.0292125 -0.0119295 1 0 1 1 0 0 +EDGE2 3174 1174 0.0613947 -0.0292263 0.0135368 1 0 1 1 0 0 +EDGE2 3174 3115 1.06005 0.0195839 0.031926 1 0 1 1 0 0 +EDGE2 3174 3135 0.92831 -0.0249697 -0.0196788 1 0 1 1 0 0 +EDGE2 3174 1175 1.04503 0.000695599 0.00683782 1 0 1 1 0 0 +EDGE2 3174 1195 0.995651 -0.0182344 -0.00994063 1 0 1 1 0 0 +EDGE2 3174 3095 0.992194 0.0594551 0.0244065 1 0 1 1 0 0 +EDGE2 3174 1155 1.02518 -0.019209 -0.0039124 1 0 1 1 0 0 +EDGE2 3174 3094 -0.0891253 -0.00243651 0.0208872 1 0 1 1 0 0 +EDGE2 3174 3114 -0.0541882 0.011555 -0.0216029 1 0 1 1 0 0 +EDGE2 3174 3134 -0.0162859 0.0152257 -0.00879899 1 0 1 1 0 0 +EDGE2 3174 1194 0.00502666 -0.00786243 0.012135 1 0 1 1 0 0 +EDGE2 3174 1154 -0.0434733 0.0733824 -0.0120192 1 0 1 1 0 0 +EDGE2 3174 3133 -1.00802 0.0783054 0.0109204 1 0 1 1 0 0 +EDGE2 3174 3173 -1.06376 -0.000832235 -0.0122883 1 0 1 1 0 0 +EDGE2 3174 3093 -1.02638 0.0311907 0.00505168 1 0 1 1 0 0 +EDGE2 3174 3113 -0.991063 -0.0279169 -0.00610443 1 0 1 1 0 0 +EDGE2 3174 1193 -0.959789 -0.0157852 -0.0186988 1 0 1 1 0 0 +EDGE2 3174 1153 -1.03354 0.0204636 -0.00303436 1 0 1 1 0 0 +EDGE2 3175 1196 -0.0128161 1.02643 1.59973 1 0 1 1 0 0 +EDGE2 3175 3116 -0.0541023 1.02614 1.58192 1 0 1 1 0 0 +EDGE2 3175 3136 0.00591582 0.986213 1.60283 1 0 1 1 0 0 +EDGE2 3175 3096 0.00259257 0.937297 1.5451 1 0 1 1 0 0 +EDGE2 3175 1156 0.0215859 0.958886 1.57674 1 0 1 1 0 0 +EDGE2 3175 1176 -0.0278125 1.06445 1.58826 1 0 1 1 0 0 +EDGE2 3175 1174 -0.929171 -0.00290532 0.00560793 1 0 1 1 0 0 +EDGE2 3175 3115 -0.0772738 -0.0373436 0.0277827 1 0 1 1 0 0 +EDGE2 3175 3135 0.0220142 0.0915367 0.0608713 1 0 1 1 0 0 +EDGE2 3175 1175 -0.0237777 0.010825 0.0193384 1 0 1 1 0 0 +EDGE2 3175 1195 -0.054586 0.0478275 -3.53209e-05 1 0 1 1 0 0 +EDGE2 3175 3095 -0.0789528 0.0598917 0.015187 1 0 1 1 0 0 +EDGE2 3175 1155 -0.041388 -0.0446036 0.0242022 1 0 1 1 0 0 +EDGE2 3175 3174 -1.04656 0.0390029 0.0115113 1 0 1 1 0 0 +EDGE2 3175 3094 -1.04936 -0.0109009 -0.0102834 1 0 1 1 0 0 +EDGE2 3175 3114 -0.939439 -0.0257854 -0.0229715 1 0 1 1 0 0 +EDGE2 3175 3134 -1.05628 0.000344398 -0.0165814 1 0 1 1 0 0 +EDGE2 3175 1194 -0.963067 -0.000235133 0.0117616 1 0 1 1 0 0 +EDGE2 3175 1154 -1.01901 0.0186815 0.0205791 1 0 1 1 0 0 +EDGE2 3176 3115 -1.03699 0.0298962 1.56678 1 0 1 1 0 0 +EDGE2 3176 3175 -0.985098 5.3131e-05 1.60401 1 0 1 1 0 0 +EDGE2 3176 3135 -0.999358 -0.0906434 1.56953 1 0 1 1 0 0 +EDGE2 3176 1175 -1.01683 -0.0381792 1.59048 1 0 1 1 0 0 +EDGE2 3176 1195 -1.01351 -0.00652519 1.55501 1 0 1 1 0 0 +EDGE2 3176 3095 -0.989386 -0.00274024 1.57771 1 0 1 1 0 0 +EDGE2 3176 1155 -1.01416 -0.0564967 1.54644 1 0 1 1 0 0 +EDGE2 3177 3176 -0.98015 -0.0129828 -0.00652806 1 0 1 1 0 0 +EDGE2 3178 3177 -1.09893 -0.00713021 -0.0023715 1 0 1 1 0 0 +EDGE2 3179 3178 -0.956127 -0.00227605 -0.0266942 1 0 1 1 0 0 +EDGE2 3179 3020 1.04863 -0.0145432 -3.15563 1 0 1 1 0 0 +EDGE2 3180 3179 -1.09268 -0.00757163 0.0275682 1 0 1 1 0 0 +EDGE2 3180 3020 0.0433498 0.0724771 -3.11235 1 0 1 1 0 0 +EDGE2 3180 3021 -0.0212545 -1.02832 -1.53421 1 0 1 1 0 0 +EDGE2 3180 3019 0.923501 0.0222523 -3.17282 1 0 1 1 0 0 +EDGE2 3181 3020 -1.08534 -0.0516737 1.60814 1 0 1 1 0 0 +EDGE2 3181 3180 -0.927346 -0.00968431 -1.56 1 0 1 1 0 0 +EDGE2 3182 3181 -0.983874 0.044264 0.0287499 1 0 1 1 0 0 +EDGE2 3183 3182 -0.982221 0.0492424 -0.00651848 1 0 1 1 0 0 +EDGE2 3184 3005 1.05887 0.0235823 -3.12601 1 0 1 1 0 0 +EDGE2 3184 725 0.941808 -0.0666487 -3.1738 1 0 1 1 0 0 +EDGE2 3184 3183 -1.00785 0.015107 -0.0269175 1 0 1 1 0 0 +EDGE2 3185 3004 0.927599 0.0695213 -3.13512 1 0 1 1 0 0 +EDGE2 3185 724 1.00112 0.0307572 -3.1159 1 0 1 1 0 0 +EDGE2 3185 726 0.00424445 0.955495 1.56627 1 0 1 1 0 0 +EDGE2 3185 3005 -0.087894 -0.0288112 -3.10563 1 0 1 1 0 0 +EDGE2 3185 725 0.106749 0.0819474 -3.14289 1 0 1 1 0 0 +EDGE2 3185 3184 -1.08508 0.0100244 0.00138145 1 0 1 1 0 0 +EDGE2 3185 3006 0.0974191 -1.02186 -1.59322 1 0 1 1 0 0 +EDGE2 3186 727 0.927052 -0.0518653 -0.0267144 1 0 1 1 0 0 +EDGE2 3186 726 0.0106227 0.00098939 -0.000491431 1 0 1 1 0 0 +EDGE2 3186 3005 -1.06918 0.111475 1.59563 1 0 1 1 0 0 +EDGE2 3186 3185 -1.00058 -0.0017668 -1.53921 1 0 1 1 0 0 +EDGE2 3186 725 -1.03111 0.0274006 1.56919 1 0 1 1 0 0 +EDGE2 3187 728 0.985889 -0.0726417 -0.000678545 1 0 1 1 0 0 +EDGE2 3187 3186 -1.059 0.0495063 0.0184983 1 0 1 1 0 0 +EDGE2 3187 727 -0.00393283 0.0174572 -0.00271876 1 0 1 1 0 0 +EDGE2 3187 726 -0.954379 -0.047028 0.0128245 1 0 1 1 0 0 +EDGE2 3188 729 1.01194 0.0391278 -0.00650715 1 0 1 1 0 0 +EDGE2 3188 728 -0.0680146 -0.0159727 -0.0298813 1 0 1 1 0 0 +EDGE2 3188 727 -1.07087 -0.0373772 0.00220424 1 0 1 1 0 0 +EDGE2 3188 3187 -1.07175 0.0157099 -0.0175729 1 0 1 1 0 0 +EDGE2 3189 730 0.981062 0.0024958 0.0308582 1 0 1 1 0 0 +EDGE2 3189 1210 0.972828 0.0499578 -3.16111 1 0 1 1 0 0 +EDGE2 3189 710 1.07817 0.0150695 -3.19275 1 0 1 1 0 0 +EDGE2 3189 729 -0.00134261 0.017951 0.00461608 1 0 1 1 0 0 +EDGE2 3189 3188 -1.05476 0.019766 0.00492113 1 0 1 1 0 0 +EDGE2 3189 728 -1.02903 0.0105054 0.0129532 1 0 1 1 0 0 +EDGE2 3190 1211 -0.0333962 -1.04474 -1.56528 1 0 1 1 0 0 +EDGE2 3190 711 -0.118709 -1.05075 -1.58567 1 0 1 1 0 0 +EDGE2 3190 731 0.0205563 -1.03266 -1.5785 1 0 1 1 0 0 +EDGE2 3190 1209 0.984802 0.0100899 -3.13492 1 0 1 1 0 0 +EDGE2 3190 709 0.945412 0.0889047 -3.13622 1 0 1 1 0 0 +EDGE2 3190 730 -0.00374058 -0.0360214 0.0316123 1 0 1 1 0 0 +EDGE2 3190 1210 0.0539695 -0.0710711 -3.15506 1 0 1 1 0 0 +EDGE2 3190 710 0.040362 0.046152 -3.18486 1 0 1 1 0 0 +EDGE2 3190 3189 -0.970537 0.0390856 -0.00547988 1 0 1 1 0 0 +EDGE2 3190 729 -1.031 -0.0866169 0.00666733 1 0 1 1 0 0 +EDGE2 3191 732 0.960564 -0.0332035 0.00939585 1 0 1 1 0 0 +EDGE2 3191 1212 0.949164 0.0099487 0.0059896 1 0 1 1 0 0 +EDGE2 3191 1211 0.0882999 0.0371045 0.00372092 1 0 1 1 0 0 +EDGE2 3191 712 1.02761 -0.140101 -0.0161409 1 0 1 1 0 0 +EDGE2 3191 711 0.00916513 -0.00306143 0.00697101 1 0 1 1 0 0 +EDGE2 3191 731 0.0818512 0.0528429 -0.0116746 1 0 1 1 0 0 +EDGE2 3191 730 -1.04129 0.0395446 1.58289 1 0 1 1 0 0 +EDGE2 3191 3190 -0.99857 -0.000502849 1.58227 1 0 1 1 0 0 +EDGE2 3191 1210 -1.08718 -0.0165692 -1.57649 1 0 1 1 0 0 +EDGE2 3191 710 -1.04808 0.0405836 -1.55552 1 0 1 1 0 0 +EDGE2 3192 732 0.026316 0.000388722 -0.0166711 1 0 1 1 0 0 +EDGE2 3192 713 0.98002 0.01631 0.00504535 1 0 1 1 0 0 +EDGE2 3192 1213 0.956326 -0.0244027 -0.0217219 1 0 1 1 0 0 +EDGE2 3192 733 1.01837 0.0662665 -0.0156831 1 0 1 1 0 0 +EDGE2 3192 1212 -0.0370825 0.00978584 -0.0246084 1 0 1 1 0 0 +EDGE2 3192 1211 -0.97919 -0.0972664 -0.0104863 1 0 1 1 0 0 +EDGE2 3192 712 0.0133509 0.00678168 0.0340154 1 0 1 1 0 0 +EDGE2 3192 3191 -1.0262 -0.0950887 -0.00106505 1 0 1 1 0 0 +EDGE2 3192 711 -1.10893 -0.0628621 -0.0344168 1 0 1 1 0 0 +EDGE2 3192 731 -1.01379 0.0693328 0.0413601 1 0 1 1 0 0 +EDGE2 3193 734 0.974109 0.019016 -0.0031334 1 0 1 1 0 0 +EDGE2 3193 1214 1.01554 0.000468445 -0.0146752 1 0 1 1 0 0 +EDGE2 3193 714 0.940928 0.0337377 0.00710025 1 0 1 1 0 0 +EDGE2 3193 732 -1.01038 -0.0432506 -0.010778 1 0 1 1 0 0 +EDGE2 3193 713 -0.0334311 0.0250773 -0.00711234 1 0 1 1 0 0 +EDGE2 3193 1213 -0.0456925 -0.0934091 -0.017417 1 0 1 1 0 0 +EDGE2 3193 733 -0.00284433 0.0301762 -0.0108755 1 0 1 1 0 0 +EDGE2 3193 3192 -0.966582 0.0922824 -0.00552725 1 0 1 1 0 0 +EDGE2 3193 1212 -0.991771 0.0639349 -0.0253459 1 0 1 1 0 0 +EDGE2 3193 712 -1.06119 -0.0721238 0.013776 1 0 1 1 0 0 +EDGE2 3194 2475 0.971132 -0.10659 -3.16741 1 0 1 1 0 0 +EDGE2 3194 2995 1.07514 -0.0361169 -3.16265 1 0 1 1 0 0 +EDGE2 3194 715 0.940798 -0.0218835 0.00506987 1 0 1 1 0 0 +EDGE2 3194 735 0.963322 -0.0361535 -0.0166476 1 0 1 1 0 0 +EDGE2 3194 1215 1.00803 -0.0107323 0.00544391 1 0 1 1 0 0 +EDGE2 3194 734 -0.00863501 -0.0549266 -0.0308379 1 0 1 1 0 0 +EDGE2 3194 1214 0.0197763 0.0187863 -0.0141352 1 0 1 1 0 0 +EDGE2 3194 714 -0.0265295 0.000858489 -0.022892 1 0 1 1 0 0 +EDGE2 3194 713 -0.940045 -0.0802864 0.0168829 1 0 1 1 0 0 +EDGE2 3194 1213 -0.952802 -0.0350051 0.0466526 1 0 1 1 0 0 +EDGE2 3194 3193 -1.02655 0.0912369 0.000613462 1 0 1 1 0 0 +EDGE2 3194 733 -1.09391 -0.104914 0.02924 1 0 1 1 0 0 +EDGE2 3195 736 -0.0347386 0.916788 1.60362 1 0 1 1 0 0 +EDGE2 3195 2475 -0.0429443 -0.0165838 -3.12158 1 0 1 1 0 0 +EDGE2 3195 2994 1.01213 -0.132531 -3.15013 1 0 1 1 0 0 +EDGE2 3195 2474 0.954627 0.0587572 -3.14824 1 0 1 1 0 0 +EDGE2 3195 2995 0.023713 0.00124145 -3.12875 1 0 1 1 0 0 +EDGE2 3195 715 0.0404165 0.00426141 -3.69487e-05 1 0 1 1 0 0 +EDGE2 3195 735 -0.0684948 0.0778948 0.00655695 1 0 1 1 0 0 +EDGE2 3195 1215 -0.058629 -0.0267841 0.048628 1 0 1 1 0 0 +EDGE2 3195 734 -1.00717 0.0852879 0.00692688 1 0 1 1 0 0 +EDGE2 3195 1214 -1.07493 0.0106333 -0.00330996 1 0 1 1 0 0 +EDGE2 3195 3194 -1.01166 0.0598251 0.0064139 1 0 1 1 0 0 +EDGE2 3195 714 -0.982806 -0.0721566 0.0318131 1 0 1 1 0 0 +EDGE2 3195 1216 0.015936 -0.988276 -1.55326 1 0 1 1 0 0 +EDGE2 3195 2996 -0.0819676 -0.939252 -1.55794 1 0 1 1 0 0 +EDGE2 3195 2476 0.120175 -1.04024 -1.59519 1 0 1 1 0 0 +EDGE2 3195 716 -0.0722176 -1.0374 -1.56012 1 0 1 1 0 0 +EDGE2 3196 737 1.03633 -0.0662249 -0.00170328 1 0 1 1 0 0 +EDGE2 3196 736 0.0435612 0.0336116 0.00136867 1 0 1 1 0 0 +EDGE2 3196 2475 -1.04284 0.0365317 1.57407 1 0 1 1 0 0 +EDGE2 3196 3195 -0.969354 -0.00700105 -1.54884 1 0 1 1 0 0 +EDGE2 3196 2995 -1.06467 -0.000822788 1.55657 1 0 1 1 0 0 +EDGE2 3196 715 -0.99577 -0.0256079 -1.57016 1 0 1 1 0 0 +EDGE2 3196 735 -1.06621 0.00582907 -1.56078 1 0 1 1 0 0 +EDGE2 3196 1215 -1.0471 -0.0636002 -1.5936 1 0 1 1 0 0 +EDGE2 3197 738 0.908857 0.0207907 -0.0216601 1 0 1 1 0 0 +EDGE2 3197 737 0.0908549 0.0274855 0.0151244 1 0 1 1 0 0 +EDGE2 3197 736 -0.963764 0.0362342 0.012139 1 0 1 1 0 0 +EDGE2 3197 3196 -0.95366 -0.00962175 0.0226026 1 0 1 1 0 0 +EDGE2 3198 739 1.0028 -0.0910209 -0.00569596 1 0 1 1 0 0 +EDGE2 3198 738 0.0343144 0.0811981 0.0372844 1 0 1 1 0 0 +EDGE2 3198 737 -0.958772 -0.00221213 -0.0210853 1 0 1 1 0 0 +EDGE2 3198 3197 -0.947368 0.0483948 -0.012069 1 0 1 1 0 0 +EDGE2 3199 800 0.980356 0.0191685 -3.14002 1 0 1 1 0 0 +EDGE2 3199 820 0.993106 0.0306651 -3.14481 1 0 1 1 0 0 +EDGE2 3199 740 1.02144 0.0506838 -0.0230267 1 0 1 1 0 0 +EDGE2 3199 760 0.978489 -0.0309553 -3.136 1 0 1 1 0 0 +EDGE2 3199 780 0.98099 0.0684331 -3.17235 1 0 1 1 0 0 +EDGE2 3199 700 1.012 -0.0451395 -3.13068 1 0 1 1 0 0 +EDGE2 3199 3198 -1.04686 -0.0352837 -0.000385049 1 0 1 1 0 0 +EDGE2 3199 739 -0.015832 0.0421212 -0.0335978 1 0 1 1 0 0 +EDGE2 3199 738 -0.968465 0.0356928 0.0442963 1 0 1 1 0 0 +EDGE2 3200 801 0.00214952 -1.03361 -1.60034 1 0 1 1 0 0 +EDGE2 3200 761 -0.0363008 -1.05221 -1.55392 1 0 1 1 0 0 +EDGE2 3200 781 -0.0137338 -1.02023 -1.54572 1 0 1 1 0 0 +EDGE2 3200 741 0.0709708 -1.04235 -1.5923 1 0 1 1 0 0 +EDGE2 3200 800 0.00311584 0.0430645 -3.12527 1 0 1 1 0 0 +EDGE2 3200 699 0.966147 -0.00652831 -3.13815 1 0 1 1 0 0 +EDGE2 3200 779 0.932362 0.0568429 -3.16842 1 0 1 1 0 0 +EDGE2 3200 799 1.00679 -0.0253697 -3.12255 1 0 1 1 0 0 +EDGE2 3200 819 1.01723 -0.126252 -3.1382 1 0 1 1 0 0 +EDGE2 3200 759 1.01013 0.010797 -3.13945 1 0 1 1 0 0 +EDGE2 3200 820 -0.0460417 -0.0531768 -3.15058 1 0 1 1 0 0 +EDGE2 3200 701 0.0693745 1.00057 1.57579 1 0 1 1 0 0 +EDGE2 3200 740 -0.0225376 0.0776595 -0.00705318 1 0 1 1 0 0 +EDGE2 3200 760 -0.0139693 0.0808603 -3.15358 1 0 1 1 0 0 +EDGE2 3200 780 0.00328153 -0.0024772 -3.15485 1 0 1 1 0 0 +EDGE2 3200 700 -0.0434003 0.0469225 -3.11872 1 0 1 1 0 0 +EDGE2 3200 821 -0.0596433 1.04045 1.58602 1 0 1 1 0 0 +EDGE2 3200 3199 -1.02672 -0.00710405 0.0101422 1 0 1 1 0 0 +EDGE2 3200 739 -1.00306 -0.123899 0.0303273 1 0 1 1 0 0 +EDGE2 3201 800 -0.986854 -0.041424 1.58626 1 0 1 1 0 0 +EDGE2 3201 3200 -0.945755 -0.100593 -1.5759 1 0 1 1 0 0 +EDGE2 3201 820 -1.13191 -0.0255583 1.59559 1 0 1 1 0 0 +EDGE2 3201 701 -0.0505667 -0.0417656 0.00850861 1 0 1 1 0 0 +EDGE2 3201 740 -0.983492 0.0147095 -1.58689 1 0 1 1 0 0 +EDGE2 3201 760 -1.01714 -0.14998 1.51994 1 0 1 1 0 0 +EDGE2 3201 780 -1.01993 -0.00982547 1.53993 1 0 1 1 0 0 +EDGE2 3201 700 -0.927724 -0.00930557 1.58197 1 0 1 1 0 0 +EDGE2 3201 821 0.0475819 0.128439 -0.0411813 1 0 1 1 0 0 +EDGE2 3201 822 1.03517 0.00962147 -0.00302835 1 0 1 1 0 0 +EDGE2 3201 702 0.96847 -0.0304516 0.0145306 1 0 1 1 0 0 +EDGE2 3202 701 -1.04997 -0.0766358 0.00731463 1 0 1 1 0 0 +EDGE2 3202 3201 -1.04507 0.0855974 0.00246402 1 0 1 1 0 0 +EDGE2 3202 821 -1.01858 -0.0121491 0.00736767 1 0 1 1 0 0 +EDGE2 3202 822 -0.0570888 -0.0581154 0.000633352 1 0 1 1 0 0 +EDGE2 3202 702 -0.0430202 -0.0404259 -0.000658827 1 0 1 1 0 0 +EDGE2 3202 703 1.08294 -0.0769169 0.0159881 1 0 1 1 0 0 +EDGE2 3202 823 0.971416 -0.00872705 0.0116803 1 0 1 1 0 0 +EDGE2 3203 822 -0.906889 0.0163982 0.00221778 1 0 1 1 0 0 +EDGE2 3203 3202 -0.933864 -0.0640072 -0.000979392 1 0 1 1 0 0 +EDGE2 3203 702 -1.05239 0.0570356 -0.0128692 1 0 1 1 0 0 +EDGE2 3203 703 -0.0498827 -0.0056079 -0.0180387 1 0 1 1 0 0 +EDGE2 3203 823 0.0360039 -0.033905 0.0102391 1 0 1 1 0 0 +EDGE2 3203 824 0.988531 -0.0439958 0.0312123 1 0 1 1 0 0 +EDGE2 3203 704 1.06464 0.00725521 -0.0164594 1 0 1 1 0 0 +EDGE2 3204 3203 -0.971247 -0.0716945 0.034531 1 0 1 1 0 0 +EDGE2 3204 703 -1.0273 -0.00282959 0.0249472 1 0 1 1 0 0 +EDGE2 3204 823 -0.990335 -0.0814048 -0.00132052 1 0 1 1 0 0 +EDGE2 3204 824 0.0488243 0.0219542 0.00230953 1 0 1 1 0 0 +EDGE2 3204 704 -0.0425185 -0.0138081 -0.0175565 1 0 1 1 0 0 +EDGE2 3204 865 0.983615 -0.04292 -3.16054 1 0 1 1 0 0 +EDGE2 3204 1205 1.02651 -0.0559399 -3.13483 1 0 1 1 0 0 +EDGE2 3204 905 0.958538 -0.041516 -3.1481 1 0 1 1 0 0 +EDGE2 3204 705 0.953132 0.0383942 0.0109245 1 0 1 1 0 0 +EDGE2 3204 825 1.0216 -0.0871619 0.0200642 1 0 1 1 0 0 +EDGE2 3204 845 1.03442 -0.00364227 -3.13481 1 0 1 1 0 0 +EDGE2 3205 824 -0.953589 0.0116708 -0.0104846 1 0 1 1 0 0 +EDGE2 3205 3204 -1.09543 -0.0443103 0.00317533 1 0 1 1 0 0 +EDGE2 3205 704 -0.980774 -0.0805657 0.00453285 1 0 1 1 0 0 +EDGE2 3205 865 -0.045885 0.0343082 -3.15951 1 0 1 1 0 0 +EDGE2 3205 826 0.0780138 -0.959467 -1.57697 1 0 1 1 0 0 +EDGE2 3205 866 0.0719942 -0.967058 -1.52654 1 0 1 1 0 0 +EDGE2 3205 906 0.0603114 -0.919625 -1.58958 1 0 1 1 0 0 +EDGE2 3205 846 -0.0320426 -0.943196 -1.54419 1 0 1 1 0 0 +EDGE2 3205 1205 -0.0214989 0.0833308 -3.15081 1 0 1 1 0 0 +EDGE2 3205 905 0.0225648 0.0116987 -3.15128 1 0 1 1 0 0 +EDGE2 3205 864 0.881555 0.050163 -3.16744 1 0 1 1 0 0 +EDGE2 3205 705 -0.0316602 0.0714068 -0.0189124 1 0 1 1 0 0 +EDGE2 3205 825 -0.0174466 -0.0214031 -0.0118938 1 0 1 1 0 0 +EDGE2 3205 845 0.0244479 0.134721 -3.14906 1 0 1 1 0 0 +EDGE2 3205 1204 1.01612 -0.070021 -3.13767 1 0 1 1 0 0 +EDGE2 3205 904 1.05145 0.0237837 -3.14044 1 0 1 1 0 0 +EDGE2 3205 844 1.05953 -0.00707828 -3.12468 1 0 1 1 0 0 +EDGE2 3205 1206 0.0153683 1.0271 1.57963 1 0 1 1 0 0 +EDGE2 3205 706 -0.0793092 1.0654 1.54691 1 0 1 1 0 0 +EDGE2 3206 865 -1.00607 -0.00488363 1.58215 1 0 1 1 0 0 +EDGE2 3206 1205 -1.02356 -0.00791167 1.56278 1 0 1 1 0 0 +EDGE2 3206 3205 -1.0653 -0.0615476 -1.57098 1 0 1 1 0 0 +EDGE2 3206 905 -0.918193 -0.00872974 1.55975 1 0 1 1 0 0 +EDGE2 3206 705 -0.924809 -0.0375773 -1.57381 1 0 1 1 0 0 +EDGE2 3206 825 -1.02278 0.00198527 -1.56624 1 0 1 1 0 0 +EDGE2 3206 845 -1.02691 0.020686 1.56527 1 0 1 1 0 0 +EDGE2 3206 1206 -0.0214021 0.0213234 -0.00909229 1 0 1 1 0 0 +EDGE2 3206 706 -0.0195982 0.0155433 -0.0146865 1 0 1 1 0 0 +EDGE2 3206 1207 0.966242 0.0240066 0.00759347 1 0 1 1 0 0 +EDGE2 3206 707 1.00252 0.0577605 0.0270363 1 0 1 1 0 0 +EDGE2 3207 1206 -0.972876 0.0308417 0.0338394 1 0 1 1 0 0 +EDGE2 3207 3206 -1.01073 -0.0353523 -0.0139625 1 0 1 1 0 0 +EDGE2 3207 706 -1.01527 0.0187114 -0.0271953 1 0 1 1 0 0 +EDGE2 3207 1207 0.0618339 0.00710299 0.00790242 1 0 1 1 0 0 +EDGE2 3207 707 0.0420756 0.0181743 -0.0237543 1 0 1 1 0 0 +EDGE2 3207 708 1.03588 -0.00710842 0.01626 1 0 1 1 0 0 +EDGE2 3207 1208 1.01764 0.0540361 -0.00526105 1 0 1 1 0 0 +EDGE2 3208 1207 -0.974531 0.0471292 0.0110122 1 0 1 1 0 0 +EDGE2 3208 3207 -1.02314 -0.0319682 0.0723876 1 0 1 1 0 0 +EDGE2 3208 707 -0.95555 0.0453124 -0.0348476 1 0 1 1 0 0 +EDGE2 3208 708 -0.0161762 -0.035942 -0.00569576 1 0 1 1 0 0 +EDGE2 3208 1208 0.0152496 -0.04816 0.00573182 1 0 1 1 0 0 +EDGE2 3208 1209 1.02345 0.0452753 0.014289 1 0 1 1 0 0 +EDGE2 3208 709 1.02877 0.0987433 -0.00836462 1 0 1 1 0 0 +EDGE2 3209 708 -1.06118 0.0626738 0.00364539 1 0 1 1 0 0 +EDGE2 3209 1208 -1.00099 0.0248572 -0.0168456 1 0 1 1 0 0 +EDGE2 3209 3208 -0.904404 0.0316833 0.00202134 1 0 1 1 0 0 +EDGE2 3209 1209 0.0982058 -0.0319433 0.00880718 1 0 1 1 0 0 +EDGE2 3209 709 0.0343183 -0.0556113 -0.00273128 1 0 1 1 0 0 +EDGE2 3209 730 1.00074 -0.0394158 -3.12415 1 0 1 1 0 0 +EDGE2 3209 3190 0.959112 -0.0503123 -3.15908 1 0 1 1 0 0 +EDGE2 3209 1210 0.997433 -0.00295062 -0.00520682 1 0 1 1 0 0 +EDGE2 3209 710 0.956068 0.00973438 -0.0140244 1 0 1 1 0 0 +EDGE2 3210 1211 0.0807503 1.03835 1.53191 1 0 1 1 0 0 +EDGE2 3210 3191 -0.0730736 1.01285 1.57263 1 0 1 1 0 0 +EDGE2 3210 711 0.0631468 0.925898 1.56537 1 0 1 1 0 0 +EDGE2 3210 731 0.0840707 1.04499 1.5541 1 0 1 1 0 0 +EDGE2 3210 1209 -1.14668 -0.0593637 -0.0230717 1 0 1 1 0 0 +EDGE2 3210 3209 -0.981921 -0.0521678 0.00862673 1 0 1 1 0 0 +EDGE2 3210 709 -1.06219 0.0222925 0.0180291 1 0 1 1 0 0 +EDGE2 3210 730 0.0105122 -0.0437722 -3.13719 1 0 1 1 0 0 +EDGE2 3210 3190 0.057119 -0.0450127 -3.16598 1 0 1 1 0 0 +EDGE2 3210 1210 0.0541953 0.0189385 0.006642 1 0 1 1 0 0 +EDGE2 3210 710 -0.0331813 -0.094177 -0.048356 1 0 1 1 0 0 +EDGE2 3210 3189 0.915101 0.00670472 -3.14533 1 0 1 1 0 0 +EDGE2 3210 729 1.02583 0.0425115 -3.14904 1 0 1 1 0 0 +EDGE2 3211 732 0.998356 -0.040406 -0.0110401 1 0 1 1 0 0 +EDGE2 3211 3192 1.05134 0.00680629 -0.0159114 1 0 1 1 0 0 +EDGE2 3211 1212 0.971568 0.0424037 -0.0222063 1 0 1 1 0 0 +EDGE2 3211 1211 0.0119747 0.071567 -0.00500766 1 0 1 1 0 0 +EDGE2 3211 712 1.01175 -0.00842979 -0.00962138 1 0 1 1 0 0 +EDGE2 3211 3191 -0.0386785 0.0202956 0.00975894 1 0 1 1 0 0 +EDGE2 3211 711 -0.0119017 0.023439 0.00520297 1 0 1 1 0 0 +EDGE2 3211 731 0.00348856 0.0524007 0.0241255 1 0 1 1 0 0 +EDGE2 3211 730 -0.852758 -0.0785553 1.58108 1 0 1 1 0 0 +EDGE2 3211 3190 -0.91906 0.0150155 1.57449 1 0 1 1 0 0 +EDGE2 3211 3210 -1.01041 -0.0136856 -1.55842 1 0 1 1 0 0 +EDGE2 3211 1210 -1.02982 0.0951633 -1.58705 1 0 1 1 0 0 +EDGE2 3211 710 -0.897242 0.00551999 -1.54442 1 0 1 1 0 0 +EDGE2 3212 732 0.0752983 0.0440172 -0.00193285 1 0 1 1 0 0 +EDGE2 3212 713 0.983601 -0.0397211 -0.0422546 1 0 1 1 0 0 +EDGE2 3212 1213 0.980788 0.0529412 0.0134686 1 0 1 1 0 0 +EDGE2 3212 3193 0.923634 -0.0430007 -0.02368 1 0 1 1 0 0 +EDGE2 3212 733 0.924676 -0.0191925 -0.00297148 1 0 1 1 0 0 +EDGE2 3212 3192 0.0577062 -0.065231 0.000158597 1 0 1 1 0 0 +EDGE2 3212 1212 -0.0164956 0.0442131 -0.000725204 1 0 1 1 0 0 +EDGE2 3212 1211 -1.05707 -0.0887389 -0.0046925 1 0 1 1 0 0 +EDGE2 3212 3211 -1.01855 0.00659486 -0.00337712 1 0 1 1 0 0 +EDGE2 3212 712 -0.013062 -0.0757218 0.016411 1 0 1 1 0 0 +EDGE2 3212 3191 -0.985785 0.0544437 -0.0043572 1 0 1 1 0 0 +EDGE2 3212 711 -0.886222 -0.00548751 -0.0282182 1 0 1 1 0 0 +EDGE2 3212 731 -1.03362 -0.0886021 -0.00669187 1 0 1 1 0 0 +EDGE2 3213 734 1.01771 -0.0288151 0.0380918 1 0 1 1 0 0 +EDGE2 3213 1214 1.0253 -0.0363213 -0.0216498 1 0 1 1 0 0 +EDGE2 3213 3194 1.03887 -0.00477403 -0.00671501 1 0 1 1 0 0 +EDGE2 3213 714 0.96069 -0.0373773 0.0426957 1 0 1 1 0 0 +EDGE2 3213 732 -0.993958 -0.0057091 -0.0325744 1 0 1 1 0 0 +EDGE2 3213 713 0.0112888 -0.0405689 -0.0139414 1 0 1 1 0 0 +EDGE2 3213 1213 -0.0715543 0.00429252 -0.0253607 1 0 1 1 0 0 +EDGE2 3213 3193 0.0318094 0.0319263 0.0167696 1 0 1 1 0 0 +EDGE2 3213 733 0.0323219 -0.0670337 0.0542476 1 0 1 1 0 0 +EDGE2 3213 3192 -0.986445 0.0863317 0.00409065 1 0 1 1 0 0 +EDGE2 3213 3212 -0.961604 0.0257421 -0.00423989 1 0 1 1 0 0 +EDGE2 3213 1212 -0.975523 -0.0876559 0.0108858 1 0 1 1 0 0 +EDGE2 3213 712 -1.00794 0.00866003 -0.0108794 1 0 1 1 0 0 +EDGE2 3214 2475 1.02585 -0.0670437 -3.12244 1 0 1 1 0 0 +EDGE2 3214 3195 0.994535 -0.00402473 0.00337265 1 0 1 1 0 0 +EDGE2 3214 2995 1.00814 0.011392 -3.17342 1 0 1 1 0 0 +EDGE2 3214 715 0.94741 0.0141036 -0.0137433 1 0 1 1 0 0 +EDGE2 3214 735 1.00698 -0.0612201 -0.018016 1 0 1 1 0 0 +EDGE2 3214 1215 1.00952 -0.00966026 -0.00936005 1 0 1 1 0 0 +EDGE2 3214 734 -0.03643 -0.0207457 -0.023267 1 0 1 1 0 0 +EDGE2 3214 1214 -0.00303172 -0.0207339 0.0118755 1 0 1 1 0 0 +EDGE2 3214 3194 0.0153056 0.0233536 -0.00883224 1 0 1 1 0 0 +EDGE2 3214 714 -0.00414049 -0.0412481 0.0259656 1 0 1 1 0 0 +EDGE2 3214 713 -0.954557 0.0893892 -0.00751749 1 0 1 1 0 0 +EDGE2 3214 1213 -0.950547 -0.106991 -0.00179491 1 0 1 1 0 0 +EDGE2 3214 3193 -1.07605 0.0471099 0.0179827 1 0 1 1 0 0 +EDGE2 3214 3213 -0.907098 0.0292103 0.00398507 1 0 1 1 0 0 +EDGE2 3214 733 -0.959656 0.0635482 -0.0155496 1 0 1 1 0 0 +EDGE2 3215 736 -0.136635 0.935375 1.55066 1 0 1 1 0 0 +EDGE2 3215 3196 -0.0665583 1.02199 1.55769 1 0 1 1 0 0 +EDGE2 3215 2475 -0.00864758 0.0302359 -3.13648 1 0 1 1 0 0 +EDGE2 3215 2994 1.06083 -0.0364005 -3.11111 1 0 1 1 0 0 +EDGE2 3215 2474 1.0714 0.0530076 -3.14008 1 0 1 1 0 0 +EDGE2 3215 3195 -0.00359938 0.0189539 -0.0128683 1 0 1 1 0 0 +EDGE2 3215 2995 0.0264278 -0.0279947 -3.14825 1 0 1 1 0 0 +EDGE2 3215 3214 -1.01016 -0.0367222 0.0216349 1 0 1 1 0 0 +EDGE2 3215 715 0.0328082 0.106785 -0.00949086 1 0 1 1 0 0 +EDGE2 3215 735 -0.0618798 -0.0432099 0.00560141 1 0 1 1 0 0 +EDGE2 3215 1215 -0.105139 0.00906254 0.00603601 1 0 1 1 0 0 +EDGE2 3215 734 -1.06081 -0.0342868 0.00826063 1 0 1 1 0 0 +EDGE2 3215 1214 -0.941004 -0.00769047 0.0314868 1 0 1 1 0 0 +EDGE2 3215 3194 -0.888082 -0.00313051 0.00113782 1 0 1 1 0 0 +EDGE2 3215 714 -1.01849 0.0128561 -0.00715308 1 0 1 1 0 0 +EDGE2 3215 1216 -0.053779 -1.09484 -1.59918 1 0 1 1 0 0 +EDGE2 3215 2996 0.088226 -1.10218 -1.62097 1 0 1 1 0 0 +EDGE2 3215 2476 0.0771158 -1.06808 -1.53085 1 0 1 1 0 0 +EDGE2 3215 716 -0.0704986 -0.965344 -1.58695 1 0 1 1 0 0 +EDGE2 3216 737 0.993688 0.0357161 -0.000861003 1 0 1 1 0 0 +EDGE2 3216 3197 0.998876 -0.022851 0.014743 1 0 1 1 0 0 +EDGE2 3216 736 -0.0091615 -0.104961 -0.0215652 1 0 1 1 0 0 +EDGE2 3216 3196 -0.0105876 0.00932164 -0.00266925 1 0 1 1 0 0 +EDGE2 3216 2475 -0.966389 -0.0368905 1.55091 1 0 1 1 0 0 +EDGE2 3216 3195 -0.973343 -0.0231183 -1.58256 1 0 1 1 0 0 +EDGE2 3216 3215 -0.964271 0.0532837 -1.55872 1 0 1 1 0 0 +EDGE2 3216 2995 -1.07924 0.0191082 1.56303 1 0 1 1 0 0 +EDGE2 3216 715 -0.997583 -0.11395 -1.56036 1 0 1 1 0 0 +EDGE2 3216 735 -0.920158 -0.0877524 -1.58355 1 0 1 1 0 0 +EDGE2 3216 1215 -0.936991 0.00952214 -1.57597 1 0 1 1 0 0 +EDGE2 3217 3198 0.98521 -0.039311 0.0121358 1 0 1 1 0 0 +EDGE2 3217 738 1.06323 -0.0101632 -0.00361647 1 0 1 1 0 0 +EDGE2 3217 737 0.095751 0.041597 0.00552095 1 0 1 1 0 0 +EDGE2 3217 3197 -0.0043255 0.0060651 -0.0105057 1 0 1 1 0 0 +EDGE2 3217 736 -0.92687 0.0163067 0.00185955 1 0 1 1 0 0 +EDGE2 3217 3196 -0.929907 0.0345523 -0.00334367 1 0 1 1 0 0 +EDGE2 3217 3216 -0.936954 0.00427225 -0.0279616 1 0 1 1 0 0 +EDGE2 3218 3199 1.10644 -0.0644652 -0.0117529 1 0 1 1 0 0 +EDGE2 3218 3198 -0.0849214 0.0569184 0.0268134 1 0 1 1 0 0 +EDGE2 3218 739 1.0346 -0.0200185 -0.0220419 1 0 1 1 0 0 +EDGE2 3218 738 0.00746614 -0.0722085 -0.0185772 1 0 1 1 0 0 +EDGE2 3218 737 -1.01842 0.0794018 0.00220279 1 0 1 1 0 0 +EDGE2 3218 3197 -0.952099 0.133948 -0.000106541 1 0 1 1 0 0 +EDGE2 3218 3217 -0.902542 -0.0409283 -0.00599304 1 0 1 1 0 0 +EDGE2 3219 800 0.988037 0.0124927 -3.11179 1 0 1 1 0 0 +EDGE2 3219 3200 1.03999 0.0477793 0.0168029 1 0 1 1 0 0 +EDGE2 3219 820 1.00516 0.035653 -3.11796 1 0 1 1 0 0 +EDGE2 3219 740 0.999505 0.0162707 -0.040788 1 0 1 1 0 0 +EDGE2 3219 760 1.07526 0.0358884 -3.17122 1 0 1 1 0 0 +EDGE2 3219 780 0.878319 0.0693968 -3.14733 1 0 1 1 0 0 +EDGE2 3219 700 0.98791 -0.0261282 -3.10974 1 0 1 1 0 0 +EDGE2 3219 3199 0.00418196 -0.0366029 -0.00201957 1 0 1 1 0 0 +EDGE2 3219 3198 -1.03456 -0.00710515 -0.0347231 1 0 1 1 0 0 +EDGE2 3219 3218 -1.05035 -0.00594625 -0.0139389 1 0 1 1 0 0 +EDGE2 3219 739 -0.000411569 0.0339388 -0.016942 1 0 1 1 0 0 +EDGE2 3219 738 -1.06422 0.0361129 -0.00229308 1 0 1 1 0 0 +EDGE2 3220 801 0.0162314 -0.996397 -1.55598 1 0 1 1 0 0 +EDGE2 3220 761 -0.0219481 -1.05056 -1.57477 1 0 1 1 0 0 +EDGE2 3220 781 0.00700902 -1.00056 -1.56276 1 0 1 1 0 0 +EDGE2 3220 741 0.0605587 -0.8901 -1.61054 1 0 1 1 0 0 +EDGE2 3220 800 -0.0624258 0.0166138 -3.12828 1 0 1 1 0 0 +EDGE2 3220 699 0.948265 -0.0487036 -3.15417 1 0 1 1 0 0 +EDGE2 3220 779 0.985724 0.0732625 -3.13613 1 0 1 1 0 0 +EDGE2 3220 799 1.03215 -0.0213823 -3.15842 1 0 1 1 0 0 +EDGE2 3220 819 0.964679 -0.101994 -3.15977 1 0 1 1 0 0 +EDGE2 3220 759 0.97657 -0.0398792 -3.11906 1 0 1 1 0 0 +EDGE2 3220 3200 -0.000116244 -0.0741841 0.0345039 1 0 1 1 0 0 +EDGE2 3220 820 -0.0472398 -0.0297287 -3.13019 1 0 1 1 0 0 +EDGE2 3220 701 0.0842367 1.0045 1.57708 1 0 1 1 0 0 +EDGE2 3220 740 -0.0457127 0.0447414 0.0134814 1 0 1 1 0 0 +EDGE2 3220 760 -0.0350452 -0.0440042 -3.14294 1 0 1 1 0 0 +EDGE2 3220 780 -0.0569437 -0.0566258 -3.1464 1 0 1 1 0 0 +EDGE2 3220 700 0.0227704 -0.0637788 -3.09991 1 0 1 1 0 0 +EDGE2 3220 3201 0.0375102 1.02036 1.52633 1 0 1 1 0 0 +EDGE2 3220 821 0.0212283 0.949444 1.54035 1 0 1 1 0 0 +EDGE2 3220 3199 -0.967615 0.00477192 -0.0287521 1 0 1 1 0 0 +EDGE2 3220 3219 -0.974438 -0.0289848 0.0200191 1 0 1 1 0 0 +EDGE2 3220 739 -1.0301 -0.0349033 -0.00514383 1 0 1 1 0 0 +EDGE2 3221 800 -0.981175 0.056485 1.60205 1 0 1 1 0 0 +EDGE2 3221 3200 -0.967134 -0.0570105 -1.55543 1 0 1 1 0 0 +EDGE2 3221 3220 -0.985002 0.0491924 -1.59548 1 0 1 1 0 0 +EDGE2 3221 820 -1.00672 0.0276886 1.57558 1 0 1 1 0 0 +EDGE2 3221 701 0.000294975 0.102042 -0.00147736 1 0 1 1 0 0 +EDGE2 3221 740 -1.02246 0.0342868 -1.58545 1 0 1 1 0 0 +EDGE2 3221 760 -0.942574 0.0542925 1.56708 1 0 1 1 0 0 +EDGE2 3221 780 -1.00852 0.0374144 1.56194 1 0 1 1 0 0 +EDGE2 3221 700 -0.938031 0.0810489 1.57962 1 0 1 1 0 0 +EDGE2 3221 3201 0.0262234 0.0337461 -0.0202768 1 0 1 1 0 0 +EDGE2 3221 821 0.00293966 -0.0258367 -0.00314842 1 0 1 1 0 0 +EDGE2 3221 822 0.928313 -0.104311 -0.00804841 1 0 1 1 0 0 +EDGE2 3221 3202 0.918533 0.0118063 -0.0419592 1 0 1 1 0 0 +EDGE2 3221 702 1.05913 -0.105998 -0.0164929 1 0 1 1 0 0 +EDGE2 3222 3203 0.966629 -0.0420233 0.0156319 1 0 1 1 0 0 +EDGE2 3222 701 -0.906705 0.015694 -0.0258545 1 0 1 1 0 0 +EDGE2 3222 3201 -0.955634 -0.0152174 0.0381196 1 0 1 1 0 0 +EDGE2 3222 3221 -1.07002 0.00965084 -0.0174091 1 0 1 1 0 0 +EDGE2 3222 821 -1.11796 0.0151313 -0.0254169 1 0 1 1 0 0 +EDGE2 3222 822 0.0171669 0.00885992 0.0234319 1 0 1 1 0 0 +EDGE2 3222 3202 0.0493126 -0.0296301 -0.00679943 1 0 1 1 0 0 +EDGE2 3222 702 0.0232796 0.0954283 0.0182281 1 0 1 1 0 0 +EDGE2 3222 703 0.979531 0.00536252 0.011201 1 0 1 1 0 0 +EDGE2 3222 823 1.00572 0.0247279 -0.0125275 1 0 1 1 0 0 +EDGE2 3223 3203 0.0347012 -0.0771166 0.0025508 1 0 1 1 0 0 +EDGE2 3223 822 -0.90391 0.0518593 -0.0183185 1 0 1 1 0 0 +EDGE2 3223 3222 -0.997817 0.00145437 0.016004 1 0 1 1 0 0 +EDGE2 3223 3202 -1.0568 0.0461477 -0.0024261 1 0 1 1 0 0 +EDGE2 3223 702 -0.985357 -0.0846097 -0.0454419 1 0 1 1 0 0 +EDGE2 3223 703 0.0233181 -0.0275598 0.0196434 1 0 1 1 0 0 +EDGE2 3223 823 0.0535145 0.0139104 -0.0365532 1 0 1 1 0 0 +EDGE2 3223 824 1.02998 0.00669257 0.0190675 1 0 1 1 0 0 +EDGE2 3223 3204 1.02609 0.00487576 0.0195544 1 0 1 1 0 0 +EDGE2 3223 704 0.9921 0.0199406 0.0348844 1 0 1 1 0 0 +EDGE2 3224 3203 -0.986725 -0.0411225 0.00590449 1 0 1 1 0 0 +EDGE2 3224 3223 -1.06488 -0.0147209 0.00300986 1 0 1 1 0 0 +EDGE2 3224 703 -0.98588 -0.0276631 -0.0153489 1 0 1 1 0 0 +EDGE2 3224 823 -0.935163 0.00931905 -0.0149681 1 0 1 1 0 0 +EDGE2 3224 824 -0.0646169 0.0234899 -0.000879415 1 0 1 1 0 0 +EDGE2 3224 3204 0.0379489 -0.0197572 0.030351 1 0 1 1 0 0 +EDGE2 3224 704 0.0081971 0.0674697 -0.0259571 1 0 1 1 0 0 +EDGE2 3224 865 0.942285 0.0553111 -3.1296 1 0 1 1 0 0 +EDGE2 3224 1205 0.997667 0.0746825 -3.16394 1 0 1 1 0 0 +EDGE2 3224 3205 0.951376 -0.0084041 0.0284948 1 0 1 1 0 0 +EDGE2 3224 905 0.928156 0.00707358 -3.11397 1 0 1 1 0 0 +EDGE2 3224 705 1.08689 -0.0190057 0.0247599 1 0 1 1 0 0 +EDGE2 3224 825 0.995681 -0.0801615 -0.00578687 1 0 1 1 0 0 +EDGE2 3224 845 0.994235 0.0501638 -3.1044 1 0 1 1 0 0 +EDGE2 3225 824 -1.08514 0.0166834 0.0135957 1 0 1 1 0 0 +EDGE2 3225 3204 -0.965571 -0.0394777 -0.00586015 1 0 1 1 0 0 +EDGE2 3225 3224 -0.988487 -0.00314669 -0.0082837 1 0 1 1 0 0 +EDGE2 3225 704 -0.991225 -0.0376605 -0.01945 1 0 1 1 0 0 +EDGE2 3225 865 -0.0370375 0.0708296 -3.14608 1 0 1 1 0 0 +EDGE2 3225 826 0.0254002 -1.00379 -1.58666 1 0 1 1 0 0 +EDGE2 3225 866 -0.0727885 -0.95717 -1.58769 1 0 1 1 0 0 +EDGE2 3225 906 0.0391289 -1.00253 -1.56383 1 0 1 1 0 0 +EDGE2 3225 846 0.0594747 -0.933858 -1.58162 1 0 1 1 0 0 +EDGE2 3225 1205 0.0675738 0.0238157 -3.16729 1 0 1 1 0 0 +EDGE2 3225 3205 -0.0353011 -0.020235 0.00223346 1 0 1 1 0 0 +EDGE2 3225 905 0.0407575 0.0279171 -3.1379 1 0 1 1 0 0 +EDGE2 3225 864 0.995592 -0.0100667 -3.12952 1 0 1 1 0 0 +EDGE2 3225 705 0.00996699 -0.0416539 0.0157525 1 0 1 1 0 0 +EDGE2 3225 825 -0.0518581 -0.0428866 0.0194678 1 0 1 1 0 0 +EDGE2 3225 845 0.0657794 0.0318964 -3.13938 1 0 1 1 0 0 +EDGE2 3225 1204 1.02396 -0.0253818 -3.12999 1 0 1 1 0 0 +EDGE2 3225 904 1.07072 -0.0376282 -3.1352 1 0 1 1 0 0 +EDGE2 3225 844 0.983052 -0.0293908 -3.12096 1 0 1 1 0 0 +EDGE2 3225 1206 -0.00877454 0.950377 1.55907 1 0 1 1 0 0 +EDGE2 3225 3206 -0.00563303 0.980387 1.58195 1 0 1 1 0 0 +EDGE2 3225 706 0.0886991 1.08754 1.58405 1 0 1 1 0 0 +EDGE2 3226 865 -0.990639 -0.138767 1.55102 1 0 1 1 0 0 +EDGE2 3226 3225 -0.934356 0.0254464 -1.55112 1 0 1 1 0 0 +EDGE2 3226 1205 -1.0125 0.014845 1.61795 1 0 1 1 0 0 +EDGE2 3226 3205 -1.03228 -0.0353882 -1.57563 1 0 1 1 0 0 +EDGE2 3226 905 -1.09075 -0.0272003 1.58021 1 0 1 1 0 0 +EDGE2 3226 705 -0.984851 0.0160339 -1.59829 1 0 1 1 0 0 +EDGE2 3226 825 -0.950684 -0.0203534 -1.57761 1 0 1 1 0 0 +EDGE2 3226 845 -0.97172 0.0515913 1.58264 1 0 1 1 0 0 +EDGE2 3226 1206 0.113892 -0.0284284 -0.0256189 1 0 1 1 0 0 +EDGE2 3226 3206 0.0481163 0.0311481 0.0131614 1 0 1 1 0 0 +EDGE2 3226 706 -0.0237375 0.00160803 0.00931626 1 0 1 1 0 0 +EDGE2 3226 1207 0.958156 0.0232085 -0.0276183 1 0 1 1 0 0 +EDGE2 3226 3207 0.962637 -0.0539802 -0.00390046 1 0 1 1 0 0 +EDGE2 3226 707 0.950739 0.0354218 -0.00668683 1 0 1 1 0 0 +EDGE2 3227 1206 -1.07436 -0.00514489 0.0293528 1 0 1 1 0 0 +EDGE2 3227 3226 -0.985714 0.0241019 0.0114569 1 0 1 1 0 0 +EDGE2 3227 3206 -1.01259 0.147205 0.0488816 1 0 1 1 0 0 +EDGE2 3227 706 -1.0382 -0.0317018 -0.000155416 1 0 1 1 0 0 +EDGE2 3227 1207 0.0120362 -0.0422811 0.0185865 1 0 1 1 0 0 +EDGE2 3227 3207 0.0381307 -0.0376892 0.0141814 1 0 1 1 0 0 +EDGE2 3227 707 -0.00420789 -0.0597648 0.011328 1 0 1 1 0 0 +EDGE2 3227 708 0.944696 0.0173026 -0.0180755 1 0 1 1 0 0 +EDGE2 3227 1208 1.00997 -0.0276247 0.012032 1 0 1 1 0 0 +EDGE2 3227 3208 0.888636 -0.0452175 0.012852 1 0 1 1 0 0 +EDGE2 3228 1207 -1.05514 -0.0661105 -0.0208995 1 0 1 1 0 0 +EDGE2 3228 3207 -0.93899 0.0216445 0.00908597 1 0 1 1 0 0 +EDGE2 3228 3227 -0.981546 0.0220597 0.0276048 1 0 1 1 0 0 +EDGE2 3228 707 -0.988188 0.0066283 0.0289243 1 0 1 1 0 0 +EDGE2 3228 708 0.116415 -0.0810466 0.0032395 1 0 1 1 0 0 +EDGE2 3228 1208 -0.0974091 -0.0181763 0.0201127 1 0 1 1 0 0 +EDGE2 3228 3208 -0.069838 -0.0161986 -0.0216112 1 0 1 1 0 0 +EDGE2 3228 1209 0.930333 -0.107098 -0.0104515 1 0 1 1 0 0 +EDGE2 3228 3209 0.996693 -0.0139083 -0.00119602 1 0 1 1 0 0 +EDGE2 3228 709 0.845975 -0.0512913 0.0205009 1 0 1 1 0 0 +EDGE2 3229 3228 -1.01084 0.0603438 0.00941157 1 0 1 1 0 0 +EDGE2 3229 708 -0.944106 0.00332231 -0.0348628 1 0 1 1 0 0 +EDGE2 3229 1208 -0.957404 -0.0035409 0.00603059 1 0 1 1 0 0 +EDGE2 3229 3208 -0.997923 0.041236 0.000773791 1 0 1 1 0 0 +EDGE2 3229 1209 -0.00126394 -0.0360598 -0.0216134 1 0 1 1 0 0 +EDGE2 3229 3209 -0.0983471 0.0141294 0.00121814 1 0 1 1 0 0 +EDGE2 3229 709 0.083122 0.0431944 0.0195544 1 0 1 1 0 0 +EDGE2 3229 730 0.975289 -0.00510202 -3.12496 1 0 1 1 0 0 +EDGE2 3229 3190 1.07059 -0.0450334 -3.13853 1 0 1 1 0 0 +EDGE2 3229 3210 1.0288 0.0705425 0.00891616 1 0 1 1 0 0 +EDGE2 3229 1210 1.03895 -0.00284281 0.0109018 1 0 1 1 0 0 +EDGE2 3229 710 1.00146 -0.0300121 -0.037859 1 0 1 1 0 0 +EDGE2 3230 1211 -0.014094 0.980484 1.59463 1 0 1 1 0 0 +EDGE2 3230 3211 -0.0199615 1.01818 1.55692 1 0 1 1 0 0 +EDGE2 3230 3191 0.0091786 1.06369 1.57794 1 0 1 1 0 0 +EDGE2 3230 711 -0.099916 1.01771 1.57042 1 0 1 1 0 0 +EDGE2 3230 731 0.0311512 0.965003 1.57722 1 0 1 1 0 0 +EDGE2 3230 1209 -0.971016 0.0248454 0.0189926 1 0 1 1 0 0 +EDGE2 3230 3209 -0.963172 -0.0744905 -0.0248996 1 0 1 1 0 0 +EDGE2 3230 3229 -0.954127 -0.0178935 -0.00340663 1 0 1 1 0 0 +EDGE2 3230 709 -0.992612 -0.0285447 0.00575407 1 0 1 1 0 0 +EDGE2 3230 730 0.0232353 -0.0303287 -3.15465 1 0 1 1 0 0 +EDGE2 3230 3190 0.0206333 -0.0102722 -3.12766 1 0 1 1 0 0 +EDGE2 3230 3210 0.00294199 -0.0360286 -0.0140463 1 0 1 1 0 0 +EDGE2 3230 1210 -0.00311784 -0.0590016 -0.0306005 1 0 1 1 0 0 +EDGE2 3230 710 0.106556 -0.151459 -0.000993796 1 0 1 1 0 0 +EDGE2 3230 3189 1.03748 -0.0761444 -3.14296 1 0 1 1 0 0 +EDGE2 3230 729 1.04555 0.0093483 -3.09846 1 0 1 1 0 0 +EDGE2 3231 732 1.0402 0.0433445 0.0149898 1 0 1 1 0 0 +EDGE2 3231 3192 1.08541 0.00708931 0.0228935 1 0 1 1 0 0 +EDGE2 3231 3212 0.983681 -0.0277441 -0.00353401 1 0 1 1 0 0 +EDGE2 3231 1212 1.00254 0.0495451 0.00028255 1 0 1 1 0 0 +EDGE2 3231 1211 -0.0409251 0.0613077 0.0306849 1 0 1 1 0 0 +EDGE2 3231 3211 -0.0342114 -0.0515072 0.0461746 1 0 1 1 0 0 +EDGE2 3231 712 1.06807 0.0739673 -0.0496216 1 0 1 1 0 0 +EDGE2 3231 3191 0.0260163 0.0234526 -0.00321698 1 0 1 1 0 0 +EDGE2 3231 711 -0.104886 0.0156185 0.0133781 1 0 1 1 0 0 +EDGE2 3231 731 0.0607777 0.019456 -0.0019684 1 0 1 1 0 0 +EDGE2 3231 730 -1.10259 0.0167544 1.55291 1 0 1 1 0 0 +EDGE2 3231 3190 -1.01689 -0.00963219 1.57442 1 0 1 1 0 0 +EDGE2 3231 3210 -0.992472 0.0838216 -1.5877 1 0 1 1 0 0 +EDGE2 3231 3230 -0.982444 -0.035098 -1.58669 1 0 1 1 0 0 +EDGE2 3231 1210 -0.978088 -0.00406122 -1.58318 1 0 1 1 0 0 +EDGE2 3231 710 -1.02619 0.0346605 -1.54646 1 0 1 1 0 0 +EDGE2 3232 732 -0.0615545 -0.0223302 0.0173147 1 0 1 1 0 0 +EDGE2 3232 713 1.04499 -0.0621311 0.00107246 1 0 1 1 0 0 +EDGE2 3232 1213 0.955913 0.0890246 0.000847105 1 0 1 1 0 0 +EDGE2 3232 3193 1.1208 -0.0704044 0.0418742 1 0 1 1 0 0 +EDGE2 3232 3213 0.974471 -0.00977855 -0.0633229 1 0 1 1 0 0 +EDGE2 3232 733 1.08513 -0.0163048 0.00941022 1 0 1 1 0 0 +EDGE2 3232 3192 -0.0473814 0.0563155 -0.0234779 1 0 1 1 0 0 +EDGE2 3232 3212 -0.0374262 0.0080218 -0.038055 1 0 1 1 0 0 +EDGE2 3232 1212 0.0361057 0.0404451 -0.0235124 1 0 1 1 0 0 +EDGE2 3232 1211 -0.916663 0.0479875 -0.0102131 1 0 1 1 0 0 +EDGE2 3232 3211 -0.976077 -0.0311842 -0.00245387 1 0 1 1 0 0 +EDGE2 3232 3231 -1.08428 0.0214628 -0.00644997 1 0 1 1 0 0 +EDGE2 3232 712 -0.00355022 -0.0192197 -0.0251154 1 0 1 1 0 0 +EDGE2 3232 3191 -0.904478 0.0206795 -0.0146936 1 0 1 1 0 0 +EDGE2 3232 711 -1.0505 0.0662787 -0.0147945 1 0 1 1 0 0 +EDGE2 3232 731 -1.06492 -0.0250077 0.0100616 1 0 1 1 0 0 +EDGE2 3233 3214 0.972763 0.00258644 -0.0391522 1 0 1 1 0 0 +EDGE2 3233 734 0.975118 -0.0305622 0.0318362 1 0 1 1 0 0 +EDGE2 3233 1214 1.05598 -0.00284583 0.00657075 1 0 1 1 0 0 +EDGE2 3233 3194 1.05231 -0.0341853 -0.021751 1 0 1 1 0 0 +EDGE2 3233 714 1.00064 -0.00957313 0.0122797 1 0 1 1 0 0 +EDGE2 3233 732 -0.990861 -0.0494188 -0.029433 1 0 1 1 0 0 +EDGE2 3233 713 0.0247419 0.0413624 -0.0266801 1 0 1 1 0 0 +EDGE2 3233 1213 0.0585763 0.00611241 0.00892711 1 0 1 1 0 0 +EDGE2 3233 3193 -0.0397719 0.0890653 0.0174893 1 0 1 1 0 0 +EDGE2 3233 3213 0.0365117 0.00388054 -0.0108247 1 0 1 1 0 0 +EDGE2 3233 733 0.0127773 0.1194 0.0265361 1 0 1 1 0 0 +EDGE2 3233 3192 -0.950176 0.0364937 -0.0566179 1 0 1 1 0 0 +EDGE2 3233 3212 -1.01917 -0.0354843 -0.000901117 1 0 1 1 0 0 +EDGE2 3233 3232 -1.1097 0.0154704 -0.020264 1 0 1 1 0 0 +EDGE2 3233 1212 -1.02716 -0.0674522 0.015561 1 0 1 1 0 0 +EDGE2 3233 712 -0.915041 0.025147 0.003719 1 0 1 1 0 0 +EDGE2 3234 3233 -0.977689 0.0362948 0.00836262 1 0 1 1 0 0 +EDGE2 3234 2475 0.931014 -0.0592928 -3.13724 1 0 1 1 0 0 +EDGE2 3234 3195 1.07428 0.0535153 0.0241742 1 0 1 1 0 0 +EDGE2 3234 3215 1.00489 -0.0679473 -0.0286412 1 0 1 1 0 0 +EDGE2 3234 2995 0.991119 -0.00803046 -3.15508 1 0 1 1 0 0 +EDGE2 3234 3214 0.0485407 0.0987639 0.0310093 1 0 1 1 0 0 +EDGE2 3234 715 1.05145 0.0272205 0.00162718 1 0 1 1 0 0 +EDGE2 3234 735 0.936937 -0.00035697 -0.0172584 1 0 1 1 0 0 +EDGE2 3234 1215 1.06806 -0.0296881 -0.0168377 1 0 1 1 0 0 +EDGE2 3234 734 0.02407 0.0717796 -0.00366404 1 0 1 1 0 0 +EDGE2 3234 1214 -0.0627445 -0.0364601 0.012656 1 0 1 1 0 0 +EDGE2 3234 3194 -0.108044 0.0484354 -0.0164373 1 0 1 1 0 0 +EDGE2 3234 714 0.00925647 -0.0861866 0.00160526 1 0 1 1 0 0 +EDGE2 3234 713 -0.970507 -0.0624461 -0.00849241 1 0 1 1 0 0 +EDGE2 3234 1213 -1.01094 0.0614227 0.00363272 1 0 1 1 0 0 +EDGE2 3234 3193 -0.925741 0.0771715 -0.0149834 1 0 1 1 0 0 +EDGE2 3234 3213 -1.06899 0.0114542 0.00113966 1 0 1 1 0 0 +EDGE2 3234 733 -1.08927 0.069321 0.0123464 1 0 1 1 0 0 +EDGE2 3235 736 0.053213 0.977355 1.542 1 0 1 1 0 0 +EDGE2 3235 3196 -0.0135418 0.998136 1.56213 1 0 1 1 0 0 +EDGE2 3235 3216 0.0255023 1.01395 1.55719 1 0 1 1 0 0 +EDGE2 3235 2475 -0.0339989 0.0871063 -3.14594 1 0 1 1 0 0 +EDGE2 3235 2994 1.0577 -0.0027296 -3.10614 1 0 1 1 0 0 +EDGE2 3235 2474 0.999006 0.000433807 -3.14953 1 0 1 1 0 0 +EDGE2 3235 3195 0.0605962 0.00459016 0.0210095 1 0 1 1 0 0 +EDGE2 3235 3215 0.0315963 -0.0149424 -0.0455127 1 0 1 1 0 0 +EDGE2 3235 2995 -0.0211468 0.0566099 -3.15911 1 0 1 1 0 0 +EDGE2 3235 3214 -1.01797 0.00551625 -0.0143774 1 0 1 1 0 0 +EDGE2 3235 715 0.0720526 -0.0546931 0.0389062 1 0 1 1 0 0 +EDGE2 3235 735 -0.0450864 0.0437152 -0.00481761 1 0 1 1 0 0 +EDGE2 3235 1215 0.00707336 0.00801448 0.0181574 1 0 1 1 0 0 +EDGE2 3235 3234 -0.982398 0.0407072 0.0277583 1 0 1 1 0 0 +EDGE2 3235 734 -0.938861 -0.0351169 -0.00996175 1 0 1 1 0 0 +EDGE2 3235 1214 -1.0547 0.0881856 -0.012709 1 0 1 1 0 0 +EDGE2 3235 3194 -1.00061 0.0148041 0.00608229 1 0 1 1 0 0 +EDGE2 3235 714 -0.942974 -0.00498676 -0.0135433 1 0 1 1 0 0 +EDGE2 3235 1216 0.0830049 -1.02599 -1.526 1 0 1 1 0 0 +EDGE2 3235 2996 -0.0975125 -1.03158 -1.551 1 0 1 1 0 0 +EDGE2 3235 2476 0.0223045 -0.969645 -1.60362 1 0 1 1 0 0 +EDGE2 3235 716 0.0180619 -1.08339 -1.56867 1 0 1 1 0 0 +EDGE2 3236 2475 -0.922586 -0.0042004 -1.5396 1 0 1 1 0 0 +EDGE2 3236 3195 -0.97768 -0.0977611 1.59415 1 0 1 1 0 0 +EDGE2 3236 3215 -1.00889 -0.0249298 1.60258 1 0 1 1 0 0 +EDGE2 3236 3235 -0.986505 0.0351231 1.55145 1 0 1 1 0 0 +EDGE2 3236 2995 -1.10094 0.0708798 -1.57756 1 0 1 1 0 0 +EDGE2 3236 715 -0.976225 -0.0607499 1.54487 1 0 1 1 0 0 +EDGE2 3236 735 -0.954716 0.0265467 1.56565 1 0 1 1 0 0 +EDGE2 3236 1215 -0.924924 -0.00354712 1.57652 1 0 1 1 0 0 +EDGE2 3236 1216 0.0172679 -0.081764 -0.0160512 1 0 1 1 0 0 +EDGE2 3236 2996 0.0143474 -0.106306 -0.0200591 1 0 1 1 0 0 +EDGE2 3236 2476 0.0116403 0.0159177 -0.00869948 1 0 1 1 0 0 +EDGE2 3236 716 -0.0616056 -0.0554652 0.00417593 1 0 1 1 0 0 +EDGE2 3236 1217 0.97593 -0.00424946 -0.00679752 1 0 1 1 0 0 +EDGE2 3236 2477 0.964893 0.0245645 -0.00136994 1 0 1 1 0 0 +EDGE2 3236 2997 0.930637 -0.0352857 0.00760919 1 0 1 1 0 0 +EDGE2 3236 717 1.07141 -0.0105915 -0.018936 1 0 1 1 0 0 +EDGE2 3237 1218 1.04681 -0.0266427 0.0346441 1 0 1 1 0 0 +EDGE2 3237 1216 -0.978038 0.0179864 -0.0257501 1 0 1 1 0 0 +EDGE2 3237 2996 -0.999497 0.0481342 -0.00765225 1 0 1 1 0 0 +EDGE2 3237 3236 -1.04381 -0.0327113 0.0164562 1 0 1 1 0 0 +EDGE2 3237 2476 -0.997176 -0.00468522 -0.00831721 1 0 1 1 0 0 +EDGE2 3237 716 -0.985444 0.0132232 -0.0185906 1 0 1 1 0 0 +EDGE2 3237 1217 0.081485 -0.0294695 -0.00313312 1 0 1 1 0 0 +EDGE2 3237 2477 0.00349599 -0.113706 0.00917997 1 0 1 1 0 0 +EDGE2 3237 2997 -0.036245 -0.0131437 -0.0289184 1 0 1 1 0 0 +EDGE2 3237 717 -0.0094997 0.011754 -0.00659218 1 0 1 1 0 0 +EDGE2 3237 2998 1.05443 -0.000452697 0.0118242 1 0 1 1 0 0 +EDGE2 3237 2478 0.962281 -0.0697495 -0.00571302 1 0 1 1 0 0 +EDGE2 3237 718 1.01553 -0.0389217 0.0393534 1 0 1 1 0 0 +EDGE2 3238 1218 0.0486219 0.0113781 -0.000205006 1 0 1 1 0 0 +EDGE2 3238 3237 -0.920861 -0.015864 0.0198192 1 0 1 1 0 0 +EDGE2 3238 1217 -0.927093 -0.0418897 0.00947713 1 0 1 1 0 0 +EDGE2 3238 2477 -0.986912 -0.044719 -0.0291583 1 0 1 1 0 0 +EDGE2 3238 2997 -0.986306 -0.0250259 0.0359305 1 0 1 1 0 0 +EDGE2 3238 717 -1.02868 -0.0132086 0.0158208 1 0 1 1 0 0 +EDGE2 3238 2998 -0.0478298 -0.0183657 0.0143901 1 0 1 1 0 0 +EDGE2 3238 2478 -0.0390643 -0.0171774 -0.0244617 1 0 1 1 0 0 +EDGE2 3238 2479 0.998873 0.0504909 -0.0248355 1 0 1 1 0 0 +EDGE2 3238 718 0.0372058 -0.0149496 -0.00697446 1 0 1 1 0 0 +EDGE2 3238 2999 0.931673 -0.054364 -0.00471255 1 0 1 1 0 0 +EDGE2 3238 719 0.942878 -0.0146977 0.0291538 1 0 1 1 0 0 +EDGE2 3238 1219 0.892295 -0.0533448 0.0345688 1 0 1 1 0 0 +EDGE2 3239 1218 -1.00264 -0.00511247 0.0455418 1 0 1 1 0 0 +EDGE2 3239 2998 -1.05619 0.00677732 0.0254143 1 0 1 1 0 0 +EDGE2 3239 3238 -0.988092 -0.00231207 0.0125049 1 0 1 1 0 0 +EDGE2 3239 2478 -1.08775 -0.0137043 0.0413723 1 0 1 1 0 0 +EDGE2 3239 2479 0.051098 -0.0219041 -0.0152764 1 0 1 1 0 0 +EDGE2 3239 718 -1.03805 -0.123243 -0.000151302 1 0 1 1 0 0 +EDGE2 3239 2999 0.0431583 -0.000150389 0.0522201 1 0 1 1 0 0 +EDGE2 3239 719 -0.0324551 0.0182675 0.0175567 1 0 1 1 0 0 +EDGE2 3239 1219 -0.0402717 0.049924 -0.00447893 1 0 1 1 0 0 +EDGE2 3239 3000 1.0008 0.0439283 0.0167387 1 0 1 1 0 0 +EDGE2 3239 1220 0.941935 -0.078813 -0.00236276 1 0 1 1 0 0 +EDGE2 3239 2480 1.05319 0.0349098 0.00221509 1 0 1 1 0 0 +EDGE2 3239 2980 0.990895 -0.0294715 -3.12083 1 0 1 1 0 0 +EDGE2 3239 720 0.971136 -0.0352496 0.0131301 1 0 1 1 0 0 +EDGE2 3240 2479 -0.910978 0.0374816 -0.00109856 1 0 1 1 0 0 +EDGE2 3240 3239 -0.961637 -0.0427617 -0.0126028 1 0 1 1 0 0 +EDGE2 3240 2999 -0.956603 -0.0031728 -0.0228555 1 0 1 1 0 0 +EDGE2 3240 719 -1.13802 -0.0511011 0.0159883 1 0 1 1 0 0 +EDGE2 3240 1219 -1.06496 0.0363538 -0.00789178 1 0 1 1 0 0 +EDGE2 3240 1221 0.145622 1.03709 1.58166 1 0 1 1 0 0 +EDGE2 3240 2981 -0.142709 0.959872 1.55027 1 0 1 1 0 0 +EDGE2 3240 2481 0.0450708 0.999178 1.59414 1 0 1 1 0 0 +EDGE2 3240 3000 -0.107125 0.0332744 0.0247908 1 0 1 1 0 0 +EDGE2 3240 1220 -0.0399473 0.0453448 0.0062297 1 0 1 1 0 0 +EDGE2 3240 2480 -0.0143587 0.00273328 0.020768 1 0 1 1 0 0 +EDGE2 3240 2980 -0.0612995 -0.00184096 -3.15487 1 0 1 1 0 0 +EDGE2 3240 720 -0.021717 -0.0665129 -0.0269294 1 0 1 1 0 0 +EDGE2 3240 721 -0.112045 -1.04155 -1.59275 1 0 1 1 0 0 +EDGE2 3240 3001 -0.0141219 -1.01103 -1.5635 1 0 1 1 0 0 +EDGE2 3240 2979 0.878877 0.0660323 -3.16141 1 0 1 1 0 0 +EDGE2 3241 1221 0.075736 -0.00383043 -0.00137403 1 0 1 1 0 0 +EDGE2 3241 1222 0.99054 0.0446318 -0.0274119 1 0 1 1 0 0 +EDGE2 3241 2982 0.994695 -0.0476362 0.0269429 1 0 1 1 0 0 +EDGE2 3241 2482 1.02701 -0.0672492 -0.0277857 1 0 1 1 0 0 +EDGE2 3241 2981 -0.051594 0.0939754 -0.0143222 1 0 1 1 0 0 +EDGE2 3241 2481 -0.046122 0.0265419 -0.00883309 1 0 1 1 0 0 +EDGE2 3241 3000 -1.00926 -0.0958682 -1.55792 1 0 1 1 0 0 +EDGE2 3241 3240 -0.985603 -0.0308726 -1.54658 1 0 1 1 0 0 +EDGE2 3241 1220 -0.93966 -0.0252059 -1.58402 1 0 1 1 0 0 +EDGE2 3241 2480 -1.04444 -0.00541768 -1.59207 1 0 1 1 0 0 +EDGE2 3241 2980 -0.955614 0.00922402 1.61691 1 0 1 1 0 0 +EDGE2 3241 720 -1.04214 0.0445143 -1.55661 1 0 1 1 0 0 +EDGE2 3242 1221 -0.939981 -0.00806311 -0.00835118 1 0 1 1 0 0 +EDGE2 3242 1223 0.901045 0.057712 -0.00491952 1 0 1 1 0 0 +EDGE2 3242 2983 1.00133 -0.029699 -0.0194351 1 0 1 1 0 0 +EDGE2 3242 2483 0.942101 -0.0379319 -0.0239108 1 0 1 1 0 0 +EDGE2 3242 1222 0.053347 0.00616448 0.0331775 1 0 1 1 0 0 +EDGE2 3242 2982 -0.0901484 0.0477215 -0.00220352 1 0 1 1 0 0 +EDGE2 3242 2482 0.0443937 0.0177588 0.0135167 1 0 1 1 0 0 +EDGE2 3242 2981 -1.01869 -0.0717576 -0.0260953 1 0 1 1 0 0 +EDGE2 3242 3241 -1.00854 0.017977 0.032574 1 0 1 1 0 0 +EDGE2 3242 2481 -0.991899 0.108832 -0.0169804 1 0 1 1 0 0 +EDGE2 3243 1223 0.00667289 -0.0543779 -0.0343892 1 0 1 1 0 0 +EDGE2 3243 1224 1.04227 0.0340158 -0.000307867 1 0 1 1 0 0 +EDGE2 3243 2984 0.990843 0.032473 -0.00865948 1 0 1 1 0 0 +EDGE2 3243 2484 1.00919 0.0396427 0.013362 1 0 1 1 0 0 +EDGE2 3243 2983 -0.0840345 -0.061206 0.0266726 1 0 1 1 0 0 +EDGE2 3243 2483 -0.0392734 0.0096844 0.0159016 1 0 1 1 0 0 +EDGE2 3243 1222 -0.984364 -0.0362304 -0.0363177 1 0 1 1 0 0 +EDGE2 3243 2982 -1.07459 0.0158927 0.0064448 1 0 1 1 0 0 +EDGE2 3243 3242 -1.04357 -0.0597576 0.0011358 1 0 1 1 0 0 +EDGE2 3243 2482 -0.902667 -0.0170058 -0.00975351 1 0 1 1 0 0 +EDGE2 3244 2645 1.04053 0.00111167 -3.14792 1 0 1 1 0 0 +EDGE2 3244 2985 1.01887 -0.0343521 -0.013884 1 0 1 1 0 0 +EDGE2 3244 2665 1.01447 -0.00971032 -3.12896 1 0 1 1 0 0 +EDGE2 3244 1225 1.00495 0.0105508 0.0272776 1 0 1 1 0 0 +EDGE2 3244 2485 0.960446 0.0178895 -0.00117937 1 0 1 1 0 0 +EDGE2 3244 2505 0.993946 0.033734 -3.15566 1 0 1 1 0 0 +EDGE2 3244 2605 1.01171 0.00490914 -3.16323 1 0 1 1 0 0 +EDGE2 3244 2445 0.99946 0.115195 -3.15813 1 0 1 1 0 0 +EDGE2 3244 1223 -0.987121 0.0518606 0.00527065 1 0 1 1 0 0 +EDGE2 3244 1224 0.0111693 -0.0147554 -0.011236 1 0 1 1 0 0 +EDGE2 3244 2984 -0.000962309 -0.0701486 -0.00731993 1 0 1 1 0 0 +EDGE2 3244 2484 0.0602163 0.0299156 -0.0403629 1 0 1 1 0 0 +EDGE2 3244 2983 -0.996971 -0.001101 0.0109191 1 0 1 1 0 0 +EDGE2 3244 3243 -1.07536 0.0707114 0.0468644 1 0 1 1 0 0 +EDGE2 3244 2483 -0.980955 0.0408588 -0.00722181 1 0 1 1 0 0 +EDGE2 3245 2446 0.00615531 1.08522 1.60711 1 0 1 1 0 0 +EDGE2 3245 2986 0.0621067 0.960764 1.58161 1 0 1 1 0 0 +EDGE2 3245 2486 0.0017408 1.00303 1.57328 1 0 1 1 0 0 +EDGE2 3245 1226 0.000820522 0.888415 1.56956 1 0 1 1 0 0 +EDGE2 3245 2666 0.0451148 -1.01008 -1.55951 1 0 1 1 0 0 +EDGE2 3245 2645 0.0840969 -0.0152792 -3.14657 1 0 1 1 0 0 +EDGE2 3245 2444 0.967271 0.0772915 -3.16534 1 0 1 1 0 0 +EDGE2 3245 2604 0.985462 0.00704203 -3.13955 1 0 1 1 0 0 +EDGE2 3245 2644 0.916104 0.00605624 -3.14779 1 0 1 1 0 0 +EDGE2 3245 2664 0.921522 -0.00672891 -3.15335 1 0 1 1 0 0 +EDGE2 3245 2504 0.997647 -0.0830769 -3.15012 1 0 1 1 0 0 +EDGE2 3245 2985 -0.0417262 -0.0760528 -0.00431946 1 0 1 1 0 0 +EDGE2 3245 2665 0.0335101 0.0223974 -3.15797 1 0 1 1 0 0 +EDGE2 3245 1225 0.0643232 -0.0251653 0.0135557 1 0 1 1 0 0 +EDGE2 3245 2485 -0.0100104 -0.11135 0.00258185 1 0 1 1 0 0 +EDGE2 3245 2505 0.0376924 -0.0803762 -3.14822 1 0 1 1 0 0 +EDGE2 3245 2605 -0.0612054 0.0240488 -3.16477 1 0 1 1 0 0 +EDGE2 3245 2445 -0.0222255 -0.0647408 -3.16223 1 0 1 1 0 0 +EDGE2 3245 1224 -1.03354 0.0203183 0.0104635 1 0 1 1 0 0 +EDGE2 3245 2984 -1.05443 0.0960258 0.0088574 1 0 1 1 0 0 +EDGE2 3245 3244 -0.976381 -0.0533519 -0.00206989 1 0 1 1 0 0 +EDGE2 3245 2484 -0.985518 -0.0329969 0.010474 1 0 1 1 0 0 +EDGE2 3245 2506 0.0184884 -0.965557 -1.60083 1 0 1 1 0 0 +EDGE2 3245 2606 -0.103862 -1.04015 -1.54528 1 0 1 1 0 0 +EDGE2 3245 2646 0.0156128 -1.02633 -1.5849 1 0 1 1 0 0 +EDGE2 3246 1227 0.985152 -0.0291477 0.00575971 1 0 1 1 0 0 +EDGE2 3246 2487 0.957932 0.0204576 0.00084713 1 0 1 1 0 0 +EDGE2 3246 2987 0.953587 -0.0407662 -0.0123434 1 0 1 1 0 0 +EDGE2 3246 2447 0.994296 0.0258361 -0.00812858 1 0 1 1 0 0 +EDGE2 3246 2446 -0.00588004 -0.106411 0.00129892 1 0 1 1 0 0 +EDGE2 3246 2986 -0.0887878 0.0348756 -0.0500856 1 0 1 1 0 0 +EDGE2 3246 2486 0.0381563 0.0269067 -0.00994543 1 0 1 1 0 0 +EDGE2 3246 1226 0.0489285 0.0185587 -0.010557 1 0 1 1 0 0 +EDGE2 3246 2645 -1.00804 0.0701657 1.58387 1 0 1 1 0 0 +EDGE2 3246 2985 -1.02995 0.0041433 -1.58488 1 0 1 1 0 0 +EDGE2 3246 3245 -1.01987 0.0439303 -1.56512 1 0 1 1 0 0 +EDGE2 3246 2665 -1.0163 0.0969796 1.57729 1 0 1 1 0 0 +EDGE2 3246 1225 -0.990744 0.0359754 -1.50781 1 0 1 1 0 0 +EDGE2 3246 2485 -1.07554 -0.0231647 -1.57839 1 0 1 1 0 0 +EDGE2 3246 2505 -1.03555 0.0236269 1.53407 1 0 1 1 0 0 +EDGE2 3246 2605 -1.03794 0.0522129 1.55644 1 0 1 1 0 0 +EDGE2 3246 2445 -1.02447 0.00867241 1.59216 1 0 1 1 0 0 +EDGE2 3247 2488 0.955937 0.010114 0.00381718 1 0 1 1 0 0 +EDGE2 3247 2988 0.983006 -0.0263217 -0.0304745 1 0 1 1 0 0 +EDGE2 3247 1228 0.989046 -0.0161123 0.0212823 1 0 1 1 0 0 +EDGE2 3247 2448 0.987882 -0.0235555 -0.0272689 1 0 1 1 0 0 +EDGE2 3247 1227 -0.0488829 -0.0184448 -0.0143868 1 0 1 1 0 0 +EDGE2 3247 2487 -0.0536977 0.0190178 -0.0165183 1 0 1 1 0 0 +EDGE2 3247 2987 -0.0384253 0.0807268 0.00359147 1 0 1 1 0 0 +EDGE2 3247 2447 0.0411979 0.0341346 0.000107038 1 0 1 1 0 0 +EDGE2 3247 2446 -0.991501 -0.00724781 -0.0279537 1 0 1 1 0 0 +EDGE2 3247 2986 -1.05092 0.0534119 0.00186053 1 0 1 1 0 0 +EDGE2 3247 3246 -1.0954 0.0387868 -0.0206011 1 0 1 1 0 0 +EDGE2 3247 2486 -1.06717 -0.0140581 -0.0256481 1 0 1 1 0 0 +EDGE2 3247 1226 -1.08476 -0.0218219 -0.0139757 1 0 1 1 0 0 +EDGE2 3248 2488 -0.0149848 -0.0666696 -0.0250624 1 0 1 1 0 0 +EDGE2 3248 2449 1.0417 -0.0428432 -0.014082 1 0 1 1 0 0 +EDGE2 3248 2989 0.967806 0.0141338 -0.00264647 1 0 1 1 0 0 +EDGE2 3248 2489 1.01166 -0.0461865 -0.0222552 1 0 1 1 0 0 +EDGE2 3248 1229 0.98487 0.00079609 0.0326578 1 0 1 1 0 0 +EDGE2 3248 2988 0.069564 -0.00385516 -0.00186554 1 0 1 1 0 0 +EDGE2 3248 1228 -0.00205007 0.0351334 0.0181237 1 0 1 1 0 0 +EDGE2 3248 2448 0.0229033 0.0396211 0.00179515 1 0 1 1 0 0 +EDGE2 3248 1227 -1.06746 -0.0502461 0.0217293 1 0 1 1 0 0 +EDGE2 3248 2487 -0.99902 -0.0340226 -0.014305 1 0 1 1 0 0 +EDGE2 3248 2987 -1.00907 0.0284844 0.00969451 1 0 1 1 0 0 +EDGE2 3248 3247 -0.959997 0.0255108 -0.00504642 1 0 1 1 0 0 +EDGE2 3248 2447 -0.997177 0.0377411 0.0262309 1 0 1 1 0 0 +EDGE2 3249 1250 0.978079 0.0073533 -3.13001 1 0 1 1 0 0 +EDGE2 3249 2990 0.97373 0.00149817 0.0470889 1 0 1 1 0 0 +EDGE2 3249 2450 1.03533 -0.00252445 0.0118547 1 0 1 1 0 0 +EDGE2 3249 2470 0.957244 0.0478579 -3.16471 1 0 1 1 0 0 +EDGE2 3249 2490 0.999442 0.0755532 0.00110371 1 0 1 1 0 0 +EDGE2 3249 2290 1.02371 -0.0162792 -3.10422 1 0 1 1 0 0 +EDGE2 3249 1230 0.993201 0.0213808 -0.0298464 1 0 1 1 0 0 +EDGE2 3249 2488 -1.06337 -0.0477263 -0.0103245 1 0 1 1 0 0 +EDGE2 3249 2449 0.0460112 -0.0646242 0.0161415 1 0 1 1 0 0 +EDGE2 3249 2989 0.0545406 -0.0182091 -6.35175e-05 1 0 1 1 0 0 +EDGE2 3249 2489 -0.0393303 -0.0593841 0.0127459 1 0 1 1 0 0 +EDGE2 3249 3248 -1.04075 -0.00582098 0.0274291 1 0 1 1 0 0 +EDGE2 3249 1229 -0.00480041 -0.0255069 0.01227 1 0 1 1 0 0 +EDGE2 3249 2988 -1.06545 0.029426 -0.00417528 1 0 1 1 0 0 +EDGE2 3249 1228 -1.03525 0.0218478 -0.00716934 1 0 1 1 0 0 +EDGE2 3249 2448 -1.02937 -0.0148999 0.00837486 1 0 1 1 0 0 +EDGE2 3250 2291 0.00406622 -1.07551 -1.58462 1 0 1 1 0 0 +EDGE2 3250 2289 1.01778 0.0099249 -3.15234 1 0 1 1 0 0 +EDGE2 3250 2469 1.09559 0.0252643 -3.16835 1 0 1 1 0 0 +EDGE2 3250 2491 -0.0675725 -0.979845 -1.55663 1 0 1 1 0 0 +EDGE2 3250 2451 -0.124156 -1.0913 -1.57366 1 0 1 1 0 0 +EDGE2 3250 1249 1.06884 -0.0870587 -3.13697 1 0 1 1 0 0 +EDGE2 3250 1250 -0.0685996 0.00193345 -3.1438 1 0 1 1 0 0 +EDGE2 3250 2990 -0.0150143 0.024688 0.0204853 1 0 1 1 0 0 +EDGE2 3250 1231 -0.0194127 -1.04997 -1.56534 1 0 1 1 0 0 +EDGE2 3250 1251 0.0482022 -1.00676 -1.55314 1 0 1 1 0 0 +EDGE2 3250 2450 0.0169102 0.00438197 -0.0414373 1 0 1 1 0 0 +EDGE2 3250 2470 -0.0458741 0.00840291 -3.19096 1 0 1 1 0 0 +EDGE2 3250 2490 -0.00869087 0.00220987 -0.0122371 1 0 1 1 0 0 +EDGE2 3250 2290 -0.0257534 0.0631907 -3.15203 1 0 1 1 0 0 +EDGE2 3250 2991 0.00530727 0.994934 1.56532 1 0 1 1 0 0 +EDGE2 3250 1230 -0.0314352 0.0727053 -0.019502 1 0 1 1 0 0 +EDGE2 3250 2471 -0.0081727 0.935997 1.55951 1 0 1 1 0 0 +EDGE2 3250 2449 -0.982687 0.0324239 -0.00708519 1 0 1 1 0 0 +EDGE2 3250 2989 -0.934871 0.0309915 0.0135407 1 0 1 1 0 0 +EDGE2 3250 3249 -1.09579 -0.0046952 -0.0153774 1 0 1 1 0 0 +EDGE2 3250 2489 -0.979932 -0.00849876 0.0201257 1 0 1 1 0 0 +EDGE2 3250 1229 -1.06501 0.00289873 -0.0103536 1 0 1 1 0 0 +EDGE2 3251 1250 -1.06472 -0.0066551 1.59165 1 0 1 1 0 0 +EDGE2 3251 2990 -0.863806 0.0704701 -1.55496 1 0 1 1 0 0 +EDGE2 3251 3250 -0.998992 -0.0562417 -1.55596 1 0 1 1 0 0 +EDGE2 3251 2450 -0.978181 -0.0255395 -1.59764 1 0 1 1 0 0 +EDGE2 3251 2470 -0.964488 0.0682551 1.58241 1 0 1 1 0 0 +EDGE2 3251 2490 -1.02779 -0.0101414 -1.60162 1 0 1 1 0 0 +EDGE2 3251 2290 -0.943936 -0.0128383 1.5624 1 0 1 1 0 0 +EDGE2 3251 2991 0.0820803 0.0299874 0.0188024 1 0 1 1 0 0 +EDGE2 3251 1230 -1.04375 -0.0230043 -1.56617 1 0 1 1 0 0 +EDGE2 3251 2471 0.0082864 -0.0965055 -0.0218102 1 0 1 1 0 0 +EDGE2 3251 2472 1.01211 0.0458464 0.0112914 1 0 1 1 0 0 +EDGE2 3251 2992 1.0258 -0.108944 -0.0200378 1 0 1 1 0 0 +EDGE2 3252 2993 1.01299 0.0541166 -0.0118068 1 0 1 1 0 0 +EDGE2 3252 2991 -0.97821 0.013451 0.00532679 1 0 1 1 0 0 +EDGE2 3252 3251 -0.94546 0.0344077 -0.00638594 1 0 1 1 0 0 +EDGE2 3252 2471 -1.00071 -0.02571 0.0207831 1 0 1 1 0 0 +EDGE2 3252 2472 -0.104166 0.01872 -0.00270004 1 0 1 1 0 0 +EDGE2 3252 2992 -0.00407893 0.10661 -0.0175342 1 0 1 1 0 0 +EDGE2 3252 2473 0.939517 0.0268098 0.00734388 1 0 1 1 0 0 +EDGE2 3253 2993 -0.0364014 -0.0625083 0.0142923 1 0 1 1 0 0 +EDGE2 3253 3252 -0.950656 -0.0303139 -0.0207898 1 0 1 1 0 0 +EDGE2 3253 2472 -0.968103 0.0168295 -0.0256169 1 0 1 1 0 0 +EDGE2 3253 2992 -0.900867 -0.0197809 -0.0210606 1 0 1 1 0 0 +EDGE2 3253 2994 0.975478 0.0135384 -0.0153335 1 0 1 1 0 0 +EDGE2 3253 2473 -0.0458759 -0.00359402 -0.0259351 1 0 1 1 0 0 +EDGE2 3253 2474 0.971776 -0.0876729 0.0450354 1 0 1 1 0 0 +EDGE2 3254 2993 -0.943211 -0.017559 -0.014243 1 0 1 1 0 0 +EDGE2 3254 3253 -0.966483 0.0556715 0.0444885 1 0 1 1 0 0 +EDGE2 3254 2475 1.00222 0.129399 0.0169844 1 0 1 1 0 0 +EDGE2 3254 2994 0.0260045 0.0116747 -0.010301 1 0 1 1 0 0 +EDGE2 3254 2473 -1.03112 -0.0179776 0.028915 1 0 1 1 0 0 +EDGE2 3254 2474 -0.0506761 -0.0209162 0.00450075 1 0 1 1 0 0 +EDGE2 3254 3195 0.989979 -0.0794643 -3.11223 1 0 1 1 0 0 +EDGE2 3254 3215 1.02952 0.0280442 -3.14928 1 0 1 1 0 0 +EDGE2 3254 3235 1.02666 -0.100858 -3.17185 1 0 1 1 0 0 +EDGE2 3254 2995 0.965034 0.00303928 0.000410815 1 0 1 1 0 0 +EDGE2 3254 715 1.0876 0.0638949 -3.1243 1 0 1 1 0 0 +EDGE2 3254 735 1.00256 -0.0277576 -3.13118 1 0 1 1 0 0 +EDGE2 3254 1215 0.963366 0.0535109 -3.15218 1 0 1 1 0 0 +EDGE2 3255 736 -0.0276004 -0.957626 -1.58913 1 0 1 1 0 0 +EDGE2 3255 3196 -0.0575622 -1.00202 -1.60223 1 0 1 1 0 0 +EDGE2 3255 3216 -0.0647945 -1.07574 -1.58122 1 0 1 1 0 0 +EDGE2 3255 2475 -0.05134 0.0046812 -0.0221419 1 0 1 1 0 0 +EDGE2 3255 2994 -0.945902 -0.0195749 0.0185895 1 0 1 1 0 0 +EDGE2 3255 3254 -1.05824 -0.0119583 0.0191987 1 0 1 1 0 0 +EDGE2 3255 2474 -1.11453 0.138672 0.00664413 1 0 1 1 0 0 +EDGE2 3255 3195 0.0228457 -0.07337 -3.17909 1 0 1 1 0 0 +EDGE2 3255 3215 -0.0414706 0.00272897 -3.12775 1 0 1 1 0 0 +EDGE2 3255 3235 -0.0138143 -0.0192149 -3.13896 1 0 1 1 0 0 +EDGE2 3255 2995 -0.0417265 -0.0616036 -0.0104833 1 0 1 1 0 0 +EDGE2 3255 3214 0.989709 -0.0771503 -3.10472 1 0 1 1 0 0 +EDGE2 3255 715 0.0749534 -0.0848086 -3.15596 1 0 1 1 0 0 +EDGE2 3255 735 -0.017488 -0.0233401 -3.12654 1 0 1 1 0 0 +EDGE2 3255 1215 -0.016486 0.0298176 -3.11373 1 0 1 1 0 0 +EDGE2 3255 3234 1.03752 0.00644132 -3.12957 1 0 1 1 0 0 +EDGE2 3255 734 0.927814 0.0236263 -3.13935 1 0 1 1 0 0 +EDGE2 3255 1214 0.993083 -0.0299727 -3.1394 1 0 1 1 0 0 +EDGE2 3255 3194 1.05604 0.0392469 -3.17392 1 0 1 1 0 0 +EDGE2 3255 714 1.03225 -0.0342361 -3.17852 1 0 1 1 0 0 +EDGE2 3255 1216 -0.00752091 1.08213 1.55598 1 0 1 1 0 0 +EDGE2 3255 2996 0.0689683 1.03076 1.59765 1 0 1 1 0 0 +EDGE2 3255 3236 -0.0990885 0.994436 1.59046 1 0 1 1 0 0 +EDGE2 3255 2476 0.0102657 1.05684 1.53878 1 0 1 1 0 0 +EDGE2 3255 716 0.050286 1.01817 1.56584 1 0 1 1 0 0 +EDGE2 3256 2475 -0.958498 -0.0268199 -1.58365 1 0 1 1 0 0 +EDGE2 3256 3255 -1.02413 0.0922281 -1.55777 1 0 1 1 0 0 +EDGE2 3256 3195 -1.01629 0.0342876 1.57455 1 0 1 1 0 0 +EDGE2 3256 3215 -0.946565 0.055552 1.57453 1 0 1 1 0 0 +EDGE2 3256 3235 -0.975346 0.0175925 1.57054 1 0 1 1 0 0 +EDGE2 3256 2995 -1.00611 0.0596825 -1.57107 1 0 1 1 0 0 +EDGE2 3256 715 -1.01826 -0.0135239 1.55566 1 0 1 1 0 0 +EDGE2 3256 735 -1.02659 0.00967988 1.5698 1 0 1 1 0 0 +EDGE2 3256 1215 -1.01491 -0.0364574 1.55558 1 0 1 1 0 0 +EDGE2 3256 3237 1.00292 0.0322678 0.0143789 1 0 1 1 0 0 +EDGE2 3256 1216 -0.0115409 0.00688643 -0.00349375 1 0 1 1 0 0 +EDGE2 3256 2996 0.057667 -0.00575697 0.0278401 1 0 1 1 0 0 +EDGE2 3256 3236 -0.00171963 0.0482853 0.0147148 1 0 1 1 0 0 +EDGE2 3256 2476 -0.100313 -0.0146264 0.0219539 1 0 1 1 0 0 +EDGE2 3256 716 0.00614108 -0.0825305 0.0018558 1 0 1 1 0 0 +EDGE2 3256 1217 0.940132 -0.00483961 -0.0168023 1 0 1 1 0 0 +EDGE2 3256 2477 0.992495 0.0445049 -0.0399148 1 0 1 1 0 0 +EDGE2 3256 2997 0.928485 -0.0755387 -0.0181295 1 0 1 1 0 0 +EDGE2 3256 717 0.996385 0.0462952 -0.000240742 1 0 1 1 0 0 +EDGE2 3257 1218 1.0203 -0.0669719 -0.0119884 1 0 1 1 0 0 +EDGE2 3257 3237 0.0732971 -0.0239229 0.016118 1 0 1 1 0 0 +EDGE2 3257 1216 -0.873077 -0.0648575 0.0116967 1 0 1 1 0 0 +EDGE2 3257 2996 -1.06622 0.0177743 0.00738604 1 0 1 1 0 0 +EDGE2 3257 3236 -1.00049 -0.0940029 -0.0163294 1 0 1 1 0 0 +EDGE2 3257 3256 -0.96909 -0.00556638 -0.000320561 1 0 1 1 0 0 +EDGE2 3257 2476 -0.997154 0.033669 0.00455413 1 0 1 1 0 0 +EDGE2 3257 716 -1.03945 0.0468134 0.00941507 1 0 1 1 0 0 +EDGE2 3257 1217 0.0248955 0.0739041 0.0179296 1 0 1 1 0 0 +EDGE2 3257 2477 0.00140028 0.0201218 0.0111465 1 0 1 1 0 0 +EDGE2 3257 2997 0.0446426 -0.0654915 0.0276474 1 0 1 1 0 0 +EDGE2 3257 717 -0.00512248 0.0648379 0.0105866 1 0 1 1 0 0 +EDGE2 3257 2998 1.00359 -0.0869618 0.00321914 1 0 1 1 0 0 +EDGE2 3257 3238 0.957876 0.0563486 0.0211948 1 0 1 1 0 0 +EDGE2 3257 2478 0.923635 0.00491056 0.0181809 1 0 1 1 0 0 +EDGE2 3257 718 1.035 0.0605126 0.00417719 1 0 1 1 0 0 +EDGE2 3258 1218 0.00428777 -0.0372977 -0.0350797 1 0 1 1 0 0 +EDGE2 3258 3237 -1.034 -0.0423576 -0.0145264 1 0 1 1 0 0 +EDGE2 3258 3257 -0.967812 0.0123298 0.00158358 1 0 1 1 0 0 +EDGE2 3258 1217 -0.979678 0.0555304 -0.0277301 1 0 1 1 0 0 +EDGE2 3258 2477 -1.08252 0.00357478 -0.00502138 1 0 1 1 0 0 +EDGE2 3258 2997 -1.08162 0.0477595 -0.0451354 1 0 1 1 0 0 +EDGE2 3258 717 -1.07797 0.0791676 0.0109511 1 0 1 1 0 0 +EDGE2 3258 2998 0.0512683 0.00517375 0.0109409 1 0 1 1 0 0 +EDGE2 3258 3238 0.0404739 -0.0230431 0.00178712 1 0 1 1 0 0 +EDGE2 3258 2478 0.0582328 0.0545518 0.00161359 1 0 1 1 0 0 +EDGE2 3258 2479 0.886364 0.0294906 -0.0160641 1 0 1 1 0 0 +EDGE2 3258 718 -0.0112818 0.0220563 0.0282121 1 0 1 1 0 0 +EDGE2 3258 3239 0.965716 -0.00511127 -0.00123598 1 0 1 1 0 0 +EDGE2 3258 2999 1.03513 -0.0175476 0.0247951 1 0 1 1 0 0 +EDGE2 3258 719 1.00556 -0.0678204 -0.0229417 1 0 1 1 0 0 +EDGE2 3258 1219 1.01225 0.0683974 -0.0236758 1 0 1 1 0 0 +EDGE2 3259 1218 -0.999069 -0.069262 -0.000109377 1 0 1 1 0 0 +EDGE2 3259 3258 -1.06024 -0.0279296 0.00267672 1 0 1 1 0 0 +EDGE2 3259 2998 -1.00856 -0.0148331 -0.00426737 1 0 1 1 0 0 +EDGE2 3259 3238 -1.05051 -0.0276001 0.00284571 1 0 1 1 0 0 +EDGE2 3259 2478 -0.9553 0.0311795 0.00683448 1 0 1 1 0 0 +EDGE2 3259 2479 -0.0146346 -0.0348498 -0.0234327 1 0 1 1 0 0 +EDGE2 3259 718 -1.01304 -0.0480925 0.0227755 1 0 1 1 0 0 +EDGE2 3259 3239 -0.0741735 0.0184691 -0.00731927 1 0 1 1 0 0 +EDGE2 3259 2999 0.145297 -0.146171 -0.0186994 1 0 1 1 0 0 +EDGE2 3259 719 -0.0441876 -0.00809577 -8.54767e-05 1 0 1 1 0 0 +EDGE2 3259 1219 -0.0564561 0.0558942 -0.0297749 1 0 1 1 0 0 +EDGE2 3259 3000 0.999996 0.0551821 0.0111504 1 0 1 1 0 0 +EDGE2 3259 3240 0.982739 0.025004 -0.0190799 1 0 1 1 0 0 +EDGE2 3259 1220 0.966197 0.0887671 0.0128179 1 0 1 1 0 0 +EDGE2 3259 2480 0.966863 -0.0684845 0.00145966 1 0 1 1 0 0 +EDGE2 3259 2980 1.07739 0.00217959 -3.13669 1 0 1 1 0 0 +EDGE2 3259 720 0.952895 -0.0896123 -0.00598987 1 0 1 1 0 0 +EDGE2 3260 2479 -0.92075 0.0189006 -0.0524034 1 0 1 1 0 0 +EDGE2 3260 3239 -0.887348 -0.0963477 -0.00581116 1 0 1 1 0 0 +EDGE2 3260 3259 -1.08518 -0.0237933 0.0134957 1 0 1 1 0 0 +EDGE2 3260 2999 -0.96662 0.0587665 -0.026528 1 0 1 1 0 0 +EDGE2 3260 719 -0.933477 0.00203847 -0.00595605 1 0 1 1 0 0 +EDGE2 3260 1219 -0.947319 0.0287969 -0.0226327 1 0 1 1 0 0 +EDGE2 3260 1221 -0.0286921 0.953387 1.56751 1 0 1 1 0 0 +EDGE2 3260 2981 -0.0157258 1.05083 1.56627 1 0 1 1 0 0 +EDGE2 3260 3241 0.0478272 1.01643 1.55253 1 0 1 1 0 0 +EDGE2 3260 2481 -0.00462645 1.00309 1.56798 1 0 1 1 0 0 +EDGE2 3260 3000 0.0232185 0.0438999 -0.012264 1 0 1 1 0 0 +EDGE2 3260 3240 0.0867382 0.0015046 -0.00266965 1 0 1 1 0 0 +EDGE2 3260 1220 0.0309352 0.0271065 0.00725818 1 0 1 1 0 0 +EDGE2 3260 2480 0.0248026 0.039173 -0.0200691 1 0 1 1 0 0 +EDGE2 3260 2980 0.102471 0.0234167 -3.14698 1 0 1 1 0 0 +EDGE2 3260 720 -0.00665767 -0.00141316 -0.00774531 1 0 1 1 0 0 +EDGE2 3260 721 0.0374358 -1.01699 -1.53668 1 0 1 1 0 0 +EDGE2 3260 3001 -0.0527174 -0.969545 -1.57172 1 0 1 1 0 0 +EDGE2 3260 2979 0.998971 -0.0234806 -3.12725 1 0 1 1 0 0 +EDGE2 3261 3000 -1.04617 -0.000544012 1.60654 1 0 1 1 0 0 +EDGE2 3261 3260 -1.00093 0.03987 1.53889 1 0 1 1 0 0 +EDGE2 3261 3240 -0.916223 0.0107792 1.54603 1 0 1 1 0 0 +EDGE2 3261 1220 -1.00152 0.0259658 1.58984 1 0 1 1 0 0 +EDGE2 3261 2480 -0.982066 -0.0641368 1.57222 1 0 1 1 0 0 +EDGE2 3261 2980 -1.05946 -0.0277143 -1.5444 1 0 1 1 0 0 +EDGE2 3261 720 -0.973707 -0.0670674 1.58356 1 0 1 1 0 0 +EDGE2 3261 721 0.0219654 -0.0717086 -0.0305555 1 0 1 1 0 0 +EDGE2 3261 3001 0.0218068 -0.0239996 0.0512836 1 0 1 1 0 0 +EDGE2 3261 722 0.904232 -0.042051 0.00454438 1 0 1 1 0 0 +EDGE2 3261 3002 0.97936 -0.0437559 0.0225974 1 0 1 1 0 0 +EDGE2 3262 721 -1.0693 0.0381399 -0.0202065 1 0 1 1 0 0 +EDGE2 3262 3001 -0.895666 -0.0262576 -0.013019 1 0 1 1 0 0 +EDGE2 3262 3261 -1.00468 0.0329866 -0.023053 1 0 1 1 0 0 +EDGE2 3262 722 0.066553 -0.0193787 -0.0165069 1 0 1 1 0 0 +EDGE2 3262 3002 0.0996697 0.0358696 -0.000826525 1 0 1 1 0 0 +EDGE2 3262 723 1.02023 0.01575 -0.0103982 1 0 1 1 0 0 +EDGE2 3262 3003 1.03268 0.034418 0.0314125 1 0 1 1 0 0 +EDGE2 3263 3262 -1.05771 -0.0806252 -0.0155838 1 0 1 1 0 0 +EDGE2 3263 722 -1.06731 0.00683882 -0.00600065 1 0 1 1 0 0 +EDGE2 3263 3002 -1.02623 0.0294663 0.0102594 1 0 1 1 0 0 +EDGE2 3263 3004 0.98662 -0.0689185 -0.0188201 1 0 1 1 0 0 +EDGE2 3263 723 -0.0154956 -0.0586879 -0.0186762 1 0 1 1 0 0 +EDGE2 3263 3003 -0.0025164 0.0677019 0.0164752 1 0 1 1 0 0 +EDGE2 3263 724 1.08848 -0.0649895 -0.0276698 1 0 1 1 0 0 +EDGE2 3264 3263 -0.944051 -0.0756871 -0.00313876 1 0 1 1 0 0 +EDGE2 3264 3004 0.0119134 0.0902956 0.0104731 1 0 1 1 0 0 +EDGE2 3264 723 -0.974821 0.0317819 0.00843788 1 0 1 1 0 0 +EDGE2 3264 3003 -0.977742 -0.00640799 0.00984889 1 0 1 1 0 0 +EDGE2 3264 724 -0.000343539 -0.0226731 -0.00710796 1 0 1 1 0 0 +EDGE2 3264 3005 1.04685 -0.0295066 0.00378347 1 0 1 1 0 0 +EDGE2 3264 3185 1.01958 0.0208431 -3.13178 1 0 1 1 0 0 +EDGE2 3264 725 0.962151 0.0712663 -0.00327921 1 0 1 1 0 0 +EDGE2 3265 3004 -0.965608 0.0272209 -0.0128307 1 0 1 1 0 0 +EDGE2 3265 3264 -0.88597 -0.0382639 -0.0438054 1 0 1 1 0 0 +EDGE2 3265 724 -0.993963 -0.0205457 4.48404e-06 1 0 1 1 0 0 +EDGE2 3265 3186 0.0188591 -1.09775 -1.53626 1 0 1 1 0 0 +EDGE2 3265 726 0.0125765 -0.970811 -1.58296 1 0 1 1 0 0 +EDGE2 3265 3005 -0.00320095 0.00647584 -0.0016185 1 0 1 1 0 0 +EDGE2 3265 3185 -0.0124532 -0.0435536 -3.11417 1 0 1 1 0 0 +EDGE2 3265 725 -0.0206342 -0.0418427 0.0180346 1 0 1 1 0 0 +EDGE2 3265 3184 1.03646 -0.0564548 -3.14331 1 0 1 1 0 0 +EDGE2 3265 3006 0.0417586 0.99323 1.55701 1 0 1 1 0 0 +EDGE2 3266 3005 -1.01244 -0.0678943 -1.56167 1 0 1 1 0 0 +EDGE2 3266 3185 -1.06693 0.0307661 1.54084 1 0 1 1 0 0 +EDGE2 3266 3265 -1.05228 0.0207971 -1.54625 1 0 1 1 0 0 +EDGE2 3266 725 -1.04971 0.0516952 -1.55835 1 0 1 1 0 0 +EDGE2 3266 3006 0.0255428 0.0290052 -0.0237898 1 0 1 1 0 0 +EDGE2 3266 3007 0.877386 0.00160771 0.000863971 1 0 1 1 0 0 +EDGE2 3267 3266 -0.983525 0.0791606 -0.0328175 1 0 1 1 0 0 +EDGE2 3267 3006 -1.03761 0.0904858 -0.031651 1 0 1 1 0 0 +EDGE2 3267 3007 -0.0386615 0.0487624 0.0305099 1 0 1 1 0 0 +EDGE2 3267 3008 0.940428 0.0554884 -0.0130036 1 0 1 1 0 0 +EDGE2 3268 3007 -0.981674 0.0401893 0.0130807 1 0 1 1 0 0 +EDGE2 3268 3267 -1.09391 0.00830256 -0.00751971 1 0 1 1 0 0 +EDGE2 3268 3008 0.0033858 0.0716831 0.000562828 1 0 1 1 0 0 +EDGE2 3268 3009 0.974232 0.023531 0.0147652 1 0 1 1 0 0 +EDGE2 3269 3268 -0.937742 -0.0110079 -0.0209305 1 0 1 1 0 0 +EDGE2 3269 3008 -0.93334 0.0111496 -0.00187817 1 0 1 1 0 0 +EDGE2 3269 3009 0.0192931 -0.0316107 -0.0107241 1 0 1 1 0 0 +EDGE2 3269 2970 1.02737 0.0167235 -3.14374 1 0 1 1 0 0 +EDGE2 3269 3010 0.960127 0.0353239 0.0222443 1 0 1 1 0 0 +EDGE2 3269 2710 0.980117 -0.076129 -3.14092 1 0 1 1 0 0 +EDGE2 3270 2971 -0.0296303 1.03971 1.56643 1 0 1 1 0 0 +EDGE2 3270 2711 -0.0655748 -0.98556 -1.56484 1 0 1 1 0 0 +EDGE2 3270 3269 -1.05918 -0.0575243 0.00434934 1 0 1 1 0 0 +EDGE2 3270 3009 -1.01891 -0.0366416 0.0136648 1 0 1 1 0 0 +EDGE2 3270 2970 0.00911174 -0.0243652 -3.15374 1 0 1 1 0 0 +EDGE2 3270 3010 -0.00116489 -0.0198801 -0.00849526 1 0 1 1 0 0 +EDGE2 3270 2710 0.00282127 -0.0138465 -3.16122 1 0 1 1 0 0 +EDGE2 3270 3011 -0.0498802 -1.0906 -1.58826 1 0 1 1 0 0 +EDGE2 3270 2969 0.925705 0.0141217 -3.13564 1 0 1 1 0 0 +EDGE2 3270 2709 1.00146 -0.0543156 -3.11997 1 0 1 1 0 0 +EDGE2 3271 2972 1.09238 0.047494 -0.0314414 1 0 1 1 0 0 +EDGE2 3271 2971 -0.00405254 -0.0226408 0.0214816 1 0 1 1 0 0 +EDGE2 3271 2970 -1.07696 -0.0951802 1.6006 1 0 1 1 0 0 +EDGE2 3271 3270 -0.962011 -0.0630124 -1.56859 1 0 1 1 0 0 +EDGE2 3271 3010 -0.996607 -0.00984559 -1.57218 1 0 1 1 0 0 +EDGE2 3271 2710 -0.997591 -0.0535325 1.59916 1 0 1 1 0 0 +EDGE2 3272 2973 1.00936 -0.00402914 0.0171277 1 0 1 1 0 0 +EDGE2 3272 3271 -1.03085 -0.0779412 0.00395103 1 0 1 1 0 0 +EDGE2 3272 2972 0.0275722 -0.0134245 -0.00661274 1 0 1 1 0 0 +EDGE2 3272 2971 -1.00891 -0.0138959 -0.0184192 1 0 1 1 0 0 +EDGE2 3273 2973 -0.000231878 -0.00587119 -0.0115269 1 0 1 1 0 0 +EDGE2 3273 2974 0.970401 0.0245583 0.00590454 1 0 1 1 0 0 +EDGE2 3273 2972 -0.957502 0.0400269 -0.0126054 1 0 1 1 0 0 +EDGE2 3273 3272 -0.998372 0.0136306 -0.000105169 1 0 1 1 0 0 +EDGE2 3274 2973 -1.03667 0.0169999 0.0050076 1 0 1 1 0 0 +EDGE2 3274 2775 0.963326 -0.025698 -3.09579 1 0 1 1 0 0 +EDGE2 3274 2975 1.06797 0.00358955 0.0107345 1 0 1 1 0 0 +EDGE2 3274 2855 1.06354 -0.00793551 -3.12895 1 0 1 1 0 0 +EDGE2 3274 2615 0.957045 0.00465307 -3.14836 1 0 1 1 0 0 +EDGE2 3274 2675 1.12172 0.0061811 -3.0949 1 0 1 1 0 0 +EDGE2 3274 2695 1.04327 -0.0364738 -3.1215 1 0 1 1 0 0 +EDGE2 3274 2974 -0.0531533 -0.0418146 -0.0110463 1 0 1 1 0 0 +EDGE2 3274 3273 -1.02912 -0.0624867 0.0128651 1 0 1 1 0 0 +EDGE2 3275 2976 -0.017019 1.02249 1.58408 1 0 1 1 0 0 +EDGE2 3275 2854 0.928559 0.0369601 -3.12109 1 0 1 1 0 0 +EDGE2 3275 2775 0.123202 -0.058864 -3.16928 1 0 1 1 0 0 +EDGE2 3275 2674 1.0177 0.00938096 -3.11189 1 0 1 1 0 0 +EDGE2 3275 2694 1.00485 -0.0424076 -3.14246 1 0 1 1 0 0 +EDGE2 3275 2774 1.06527 0.079183 -3.15438 1 0 1 1 0 0 +EDGE2 3275 2614 1.02793 0.0111005 -3.11715 1 0 1 1 0 0 +EDGE2 3275 2975 0.00741307 0.0458499 0.00549917 1 0 1 1 0 0 +EDGE2 3275 2855 -0.0398131 0.0239452 -3.12226 1 0 1 1 0 0 +EDGE2 3275 3274 -1.02016 0.00342747 -0.00758187 1 0 1 1 0 0 +EDGE2 3275 2615 0.00826645 -0.0586648 -3.14163 1 0 1 1 0 0 +EDGE2 3275 2675 -0.0272848 -0.0139956 -3.12603 1 0 1 1 0 0 +EDGE2 3275 2695 0.0719681 -0.0512609 -3.15793 1 0 1 1 0 0 +EDGE2 3275 2974 -1.00162 -0.0488689 0.0354012 1 0 1 1 0 0 +EDGE2 3275 2676 -0.0182351 -1.00322 -1.57711 1 0 1 1 0 0 +EDGE2 3275 2776 0.0375107 -1.00488 -1.55819 1 0 1 1 0 0 +EDGE2 3275 2856 0.0658683 -1.01445 -1.56123 1 0 1 1 0 0 +EDGE2 3275 2696 0.00725723 -1.0504 -1.58671 1 0 1 1 0 0 +EDGE2 3275 2616 0.0259658 -1.03172 -1.5834 1 0 1 1 0 0 +EDGE2 3276 2977 0.919842 -0.0088544 0.00737995 1 0 1 1 0 0 +EDGE2 3276 2976 0.0082199 0.00932796 -0.0125995 1 0 1 1 0 0 +EDGE2 3276 2775 -0.958361 -0.0284968 1.55157 1 0 1 1 0 0 +EDGE2 3276 2975 -1.04653 0.0123935 -1.57826 1 0 1 1 0 0 +EDGE2 3276 3275 -0.992012 0.0410674 -1.58525 1 0 1 1 0 0 +EDGE2 3276 2855 -0.969574 -0.00949006 1.54115 1 0 1 1 0 0 +EDGE2 3276 2615 -1.00629 -0.0544185 1.5648 1 0 1 1 0 0 +EDGE2 3276 2675 -0.970479 0.0871917 1.57068 1 0 1 1 0 0 +EDGE2 3276 2695 -1.00618 0.00950243 1.54346 1 0 1 1 0 0 +EDGE2 3277 2978 1.03708 -0.00660726 0.0371023 1 0 1 1 0 0 +EDGE2 3277 2977 -0.00913092 0.0802979 0.0239201 1 0 1 1 0 0 +EDGE2 3277 2976 -1.05958 -0.0855002 0.00649969 1 0 1 1 0 0 +EDGE2 3277 3276 -0.95618 -0.022698 0.00746344 1 0 1 1 0 0 +EDGE2 3278 2979 0.976169 0.016479 -0.00544678 1 0 1 1 0 0 +EDGE2 3278 2978 -0.0538085 0.0770121 0.00821824 1 0 1 1 0 0 +EDGE2 3278 2977 -0.960941 0.00689813 -0.0242479 1 0 1 1 0 0 +EDGE2 3278 3277 -1.02808 0.0701913 -0.0333838 1 0 1 1 0 0 +EDGE2 3279 3000 1.07685 -0.055495 -3.14564 1 0 1 1 0 0 +EDGE2 3279 3260 1.04045 0.0150966 -3.16661 1 0 1 1 0 0 +EDGE2 3279 3240 1.0516 0.0795391 -3.15247 1 0 1 1 0 0 +EDGE2 3279 1220 0.997718 0.0419313 -3.14234 1 0 1 1 0 0 +EDGE2 3279 2480 1.01992 0.022423 -3.13926 1 0 1 1 0 0 +EDGE2 3279 2980 0.939874 -0.0154172 0.00499201 1 0 1 1 0 0 +EDGE2 3279 720 0.965379 0.0179042 -3.09283 1 0 1 1 0 0 +EDGE2 3279 3278 -1.02205 -0.0678275 -0.0310163 1 0 1 1 0 0 +EDGE2 3279 2979 -0.0115241 0.062735 -0.00388432 1 0 1 1 0 0 +EDGE2 3279 2978 -0.975522 -0.0337287 -0.0120221 1 0 1 1 0 0 +EDGE2 3280 2479 1.02311 -0.0181924 -3.12798 1 0 1 1 0 0 +EDGE2 3280 3239 1.02409 0.00291285 -3.14404 1 0 1 1 0 0 +EDGE2 3280 3259 0.998119 -0.0546977 -3.15035 1 0 1 1 0 0 +EDGE2 3280 2999 1.04931 0.0217572 -3.19065 1 0 1 1 0 0 +EDGE2 3280 719 1.01962 -0.00462812 -3.10838 1 0 1 1 0 0 +EDGE2 3280 1219 1.07262 0.0943526 -3.15251 1 0 1 1 0 0 +EDGE2 3280 1221 -0.032033 -0.943384 -1.59238 1 0 1 1 0 0 +EDGE2 3280 2981 0.0490363 -0.903672 -1.59805 1 0 1 1 0 0 +EDGE2 3280 3241 -0.0842081 -1.0048 -1.58597 1 0 1 1 0 0 +EDGE2 3280 2481 -0.0132825 -1.06387 -1.56615 1 0 1 1 0 0 +EDGE2 3280 3000 0.0488929 -0.00569743 -3.14106 1 0 1 1 0 0 +EDGE2 3280 3260 0.0310481 0.0010981 -3.14826 1 0 1 1 0 0 +EDGE2 3280 3240 -0.0220541 0.0378301 -3.13836 1 0 1 1 0 0 +EDGE2 3280 1220 -0.0112488 -0.0140955 -3.17283 1 0 1 1 0 0 +EDGE2 3280 2480 -0.0158842 -0.0104939 -3.1321 1 0 1 1 0 0 +EDGE2 3280 2980 -0.026583 -0.0257234 0.0217136 1 0 1 1 0 0 +EDGE2 3280 720 -0.0519184 0.0530356 -3.11968 1 0 1 1 0 0 +EDGE2 3280 721 0.0325169 0.942796 1.59192 1 0 1 1 0 0 +EDGE2 3280 3001 0.118117 0.925376 1.58061 1 0 1 1 0 0 +EDGE2 3280 3261 -0.0221272 0.949786 1.60293 1 0 1 1 0 0 +EDGE2 3280 2979 -0.990664 0.0172229 -0.0249659 1 0 1 1 0 0 +EDGE2 3280 3279 -0.935206 -0.0187175 0.00414605 1 0 1 1 0 0 +EDGE2 3281 3000 -1.01733 0.0533507 1.56614 1 0 1 1 0 0 +EDGE2 3281 3260 -0.948841 -0.026616 1.56807 1 0 1 1 0 0 +EDGE2 3281 3280 -0.988558 0.0230607 -1.53525 1 0 1 1 0 0 +EDGE2 3281 3240 -1.03863 -0.0413629 1.60372 1 0 1 1 0 0 +EDGE2 3281 1220 -1.04914 -0.0109493 1.58073 1 0 1 1 0 0 +EDGE2 3281 2480 -0.980113 -0.086917 1.59073 1 0 1 1 0 0 +EDGE2 3281 2980 -0.954656 -0.0655537 -1.56887 1 0 1 1 0 0 +EDGE2 3281 720 -0.996311 0.0131099 1.56575 1 0 1 1 0 0 +EDGE2 3281 3262 0.983581 0.0359244 0.0462673 1 0 1 1 0 0 +EDGE2 3281 721 -0.0811204 -0.0444608 -0.0223476 1 0 1 1 0 0 +EDGE2 3281 3001 -0.0156757 -0.116128 0.0135322 1 0 1 1 0 0 +EDGE2 3281 3261 -0.0241084 0.0476191 -0.00609295 1 0 1 1 0 0 +EDGE2 3281 722 1.02366 0.00642333 -0.0196819 1 0 1 1 0 0 +EDGE2 3281 3002 0.990594 0.00605664 0.0012444 1 0 1 1 0 0 +EDGE2 3282 3263 0.998381 -0.00927939 -0.0151624 1 0 1 1 0 0 +EDGE2 3282 3281 -0.94689 0.0295715 -0.0251626 1 0 1 1 0 0 +EDGE2 3282 3262 0.00847589 0.00258756 -0.015591 1 0 1 1 0 0 +EDGE2 3282 721 -0.960565 -0.122331 -0.00757419 1 0 1 1 0 0 +EDGE2 3282 3001 -0.966493 0.10879 -0.0262711 1 0 1 1 0 0 +EDGE2 3282 3261 -0.918334 -0.0226598 0.0012197 1 0 1 1 0 0 +EDGE2 3282 722 -0.0476316 -0.00157022 0.00894894 1 0 1 1 0 0 +EDGE2 3282 3002 -0.00933771 -0.0994867 0.0366094 1 0 1 1 0 0 +EDGE2 3282 723 0.964212 0.00615754 -0.0150273 1 0 1 1 0 0 +EDGE2 3282 3003 1.02944 0.0714522 0.0153713 1 0 1 1 0 0 +EDGE2 3283 3263 0.0100882 0.0327221 0.00174371 1 0 1 1 0 0 +EDGE2 3283 3262 -0.970168 -0.0212207 -0.0272957 1 0 1 1 0 0 +EDGE2 3283 3282 -0.964335 0.0317382 -0.000433872 1 0 1 1 0 0 +EDGE2 3283 722 -1.08606 0.00270172 0.00693971 1 0 1 1 0 0 +EDGE2 3283 3002 -1.01419 0.00539815 -0.0134026 1 0 1 1 0 0 +EDGE2 3283 3004 0.932326 -0.0107616 0.0176822 1 0 1 1 0 0 +EDGE2 3283 723 -0.13661 0.026749 0.0147515 1 0 1 1 0 0 +EDGE2 3283 3003 -0.0613617 -0.0463325 -0.0323745 1 0 1 1 0 0 +EDGE2 3283 3264 0.941152 -0.00888708 -0.0172141 1 0 1 1 0 0 +EDGE2 3283 724 1.08611 -0.0112209 -5.77191e-05 1 0 1 1 0 0 +EDGE2 3284 3263 -0.936176 -0.0317566 -0.0341268 1 0 1 1 0 0 +EDGE2 3284 3283 -1.00588 -0.0609876 -0.021703 1 0 1 1 0 0 +EDGE2 3284 3004 0.0255398 0.0141064 0.0247453 1 0 1 1 0 0 +EDGE2 3284 723 -1.04749 -0.0467657 -0.0203005 1 0 1 1 0 0 +EDGE2 3284 3003 -1.03946 0.0349351 0.018564 1 0 1 1 0 0 +EDGE2 3284 3264 0.0675071 -0.0230066 0.0334241 1 0 1 1 0 0 +EDGE2 3284 724 -0.0332396 0.0200669 -0.0211299 1 0 1 1 0 0 +EDGE2 3284 3005 0.969623 0.123764 -0.0146864 1 0 1 1 0 0 +EDGE2 3284 3185 0.992886 0.00205115 -3.12106 1 0 1 1 0 0 +EDGE2 3284 3265 0.965886 0.00198799 0.0188958 1 0 1 1 0 0 +EDGE2 3284 725 0.981264 -0.0672505 -0.0155698 1 0 1 1 0 0 +EDGE2 3285 3004 -1.01141 0.0618891 -0.00398329 1 0 1 1 0 0 +EDGE2 3285 3284 -0.950004 -0.101557 0.0123292 1 0 1 1 0 0 +EDGE2 3285 3264 -1.01879 0.0603132 -0.00578909 1 0 1 1 0 0 +EDGE2 3285 724 -0.926196 -0.0254502 -0.0172561 1 0 1 1 0 0 +EDGE2 3285 3186 5.94039e-05 -0.891825 -1.56553 1 0 1 1 0 0 +EDGE2 3285 726 -0.00459154 -0.911143 -1.60117 1 0 1 1 0 0 +EDGE2 3285 3005 -0.0405528 -0.00417245 -0.00550268 1 0 1 1 0 0 +EDGE2 3285 3185 -0.0806247 0.016551 -3.10273 1 0 1 1 0 0 +EDGE2 3285 3265 -0.0185285 0.0256983 0.0269226 1 0 1 1 0 0 +EDGE2 3285 725 -0.0555344 -0.0204859 -0.00827189 1 0 1 1 0 0 +EDGE2 3285 3184 1.00656 -0.0223151 -3.16313 1 0 1 1 0 0 +EDGE2 3285 3266 0.0288752 0.941528 1.59903 1 0 1 1 0 0 +EDGE2 3285 3006 -0.0519988 1.00624 1.5727 1 0 1 1 0 0 +EDGE2 3286 3285 -0.973462 -0.00260953 -1.58859 1 0 1 1 0 0 +EDGE2 3286 3005 -1.05587 -0.0456096 -1.59274 1 0 1 1 0 0 +EDGE2 3286 3185 -0.94351 -0.0762996 1.53523 1 0 1 1 0 0 +EDGE2 3286 3265 -0.981174 -0.0629642 -1.59456 1 0 1 1 0 0 +EDGE2 3286 725 -0.934676 -0.0423165 -1.56083 1 0 1 1 0 0 +EDGE2 3286 3266 -0.0744928 -0.0534679 -0.00968252 1 0 1 1 0 0 +EDGE2 3286 3006 0.0228713 -0.00136638 0.011294 1 0 1 1 0 0 +EDGE2 3286 3007 1.06183 -0.0206822 0.0205945 1 0 1 1 0 0 +EDGE2 3286 3267 1.02027 0.0206769 -0.0125644 1 0 1 1 0 0 +EDGE2 3287 3266 -0.973924 -0.0123423 0.000336895 1 0 1 1 0 0 +EDGE2 3287 3286 -0.991835 -0.0434335 0.0276117 1 0 1 1 0 0 +EDGE2 3287 3006 -1.06251 0.0576587 0.00490406 1 0 1 1 0 0 +EDGE2 3287 3268 1.04263 -0.00653298 -0.0272194 1 0 1 1 0 0 +EDGE2 3287 3007 -0.0354596 -0.00478642 -0.0272537 1 0 1 1 0 0 +EDGE2 3287 3267 -0.0893046 0.0503097 -0.0222565 1 0 1 1 0 0 +EDGE2 3287 3008 0.96627 -0.0208051 -0.0414974 1 0 1 1 0 0 +EDGE2 3288 3268 -0.0639253 -0.0826417 -0.0070448 1 0 1 1 0 0 +EDGE2 3288 3007 -1.00906 -0.0602103 -0.00531612 1 0 1 1 0 0 +EDGE2 3288 3267 -1.00811 0.0454783 -0.00969407 1 0 1 1 0 0 +EDGE2 3288 3287 -0.918924 0.0485043 -0.0331749 1 0 1 1 0 0 +EDGE2 3288 3269 0.926253 -0.131865 -0.0121073 1 0 1 1 0 0 +EDGE2 3288 3008 -0.106054 0.0294343 -0.0263729 1 0 1 1 0 0 +EDGE2 3288 3009 1.00872 -0.0652537 0.0168225 1 0 1 1 0 0 +EDGE2 3289 3268 -1.01404 0.0949815 0.0246152 1 0 1 1 0 0 +EDGE2 3289 3288 -1.08604 0.0546119 -0.0201452 1 0 1 1 0 0 +EDGE2 3289 3269 -0.0387413 0.0709932 -0.00859189 1 0 1 1 0 0 +EDGE2 3289 3008 -1.02514 -0.0404976 0.0298182 1 0 1 1 0 0 +EDGE2 3289 3009 0.0202945 0.0235012 -0.0127042 1 0 1 1 0 0 +EDGE2 3289 2970 1.02432 -0.0486955 -3.14529 1 0 1 1 0 0 +EDGE2 3289 3270 0.986315 0.0170135 0.0174844 1 0 1 1 0 0 +EDGE2 3289 3010 0.980882 -0.0121544 -0.0191757 1 0 1 1 0 0 +EDGE2 3289 2710 0.99207 -0.0510328 -3.13632 1 0 1 1 0 0 +EDGE2 3290 3271 0.0072686 1.08927 1.55437 1 0 1 1 0 0 +EDGE2 3290 2971 -0.0228578 0.970811 1.60371 1 0 1 1 0 0 +EDGE2 3290 2711 -0.0666007 -1.00759 -1.56434 1 0 1 1 0 0 +EDGE2 3290 3269 -0.978559 -0.0329213 -0.0106137 1 0 1 1 0 0 +EDGE2 3290 3289 -1.07921 -0.0193479 -0.0143204 1 0 1 1 0 0 +EDGE2 3290 3009 -1.07086 -0.0132646 -0.0171609 1 0 1 1 0 0 +EDGE2 3290 2970 0.0813009 -0.0117908 -3.17034 1 0 1 1 0 0 +EDGE2 3290 3270 -0.0295626 0.0599755 -0.00574855 1 0 1 1 0 0 +EDGE2 3290 3010 0.0408887 -0.0999244 0.0250272 1 0 1 1 0 0 +EDGE2 3290 2710 -0.0147689 -0.0415257 -3.16043 1 0 1 1 0 0 +EDGE2 3290 3011 -0.0249847 -1.02203 -1.58609 1 0 1 1 0 0 +EDGE2 3290 2969 1.01229 0.0306984 -3.13575 1 0 1 1 0 0 +EDGE2 3290 2709 1.04936 0.00252888 -3.15638 1 0 1 1 0 0 +EDGE2 3291 3271 0.00401056 -0.016176 0.0297194 1 0 1 1 0 0 +EDGE2 3291 2972 0.959903 0.0379547 0.00577034 1 0 1 1 0 0 +EDGE2 3291 3272 0.982892 -0.0576297 -0.0138035 1 0 1 1 0 0 +EDGE2 3291 2971 -0.0119652 0.0576748 0.0270323 1 0 1 1 0 0 +EDGE2 3291 3290 -1.04662 0.0566479 -1.55125 1 0 1 1 0 0 +EDGE2 3291 2970 -0.932918 0.0318726 1.58418 1 0 1 1 0 0 +EDGE2 3291 3270 -1.00858 -0.0814484 -1.58301 1 0 1 1 0 0 +EDGE2 3291 3010 -1.03794 0.0117898 -1.56226 1 0 1 1 0 0 +EDGE2 3291 2710 -1.07239 -0.0190114 1.5651 1 0 1 1 0 0 +EDGE2 3292 2973 1.09716 0.0631288 -0.00172465 1 0 1 1 0 0 +EDGE2 3292 3273 0.993663 -0.0226877 0.000528103 1 0 1 1 0 0 +EDGE2 3292 3271 -0.967272 -0.0631795 -0.00854654 1 0 1 1 0 0 +EDGE2 3292 2972 0.0532377 -0.0385258 -0.00610641 1 0 1 1 0 0 +EDGE2 3292 3272 -0.0416681 -0.0494371 0.0263407 1 0 1 1 0 0 +EDGE2 3292 3291 -1.03853 0.0439595 0.00504581 1 0 1 1 0 0 +EDGE2 3292 2971 -1.04023 0.10334 0.0109095 1 0 1 1 0 0 +EDGE2 3293 2973 -0.0415781 0.0734698 -0.0135191 1 0 1 1 0 0 +EDGE2 3293 3274 0.907325 -0.015504 0.0133987 1 0 1 1 0 0 +EDGE2 3293 2974 0.954641 0.0337525 -0.00812985 1 0 1 1 0 0 +EDGE2 3293 3273 0.0286992 -0.0191323 0.0230628 1 0 1 1 0 0 +EDGE2 3293 2972 -1.08746 -0.0131206 0.000199563 1 0 1 1 0 0 +EDGE2 3293 3272 -1.03354 0.0851221 -0.0200365 1 0 1 1 0 0 +EDGE2 3293 3292 -0.996985 0.0115571 0.0240587 1 0 1 1 0 0 +EDGE2 3294 2973 -1.01467 -0.0403739 0.00484988 1 0 1 1 0 0 +EDGE2 3294 2775 0.954986 0.0616662 -3.1412 1 0 1 1 0 0 +EDGE2 3294 2975 0.977035 0.017617 -0.0133472 1 0 1 1 0 0 +EDGE2 3294 3275 1.10206 -0.0661643 0.0316119 1 0 1 1 0 0 +EDGE2 3294 2855 0.953848 0.100532 -3.15212 1 0 1 1 0 0 +EDGE2 3294 3274 -0.0504971 -0.0143223 -0.0399155 1 0 1 1 0 0 +EDGE2 3294 2615 1.05986 -0.107493 -3.12304 1 0 1 1 0 0 +EDGE2 3294 2675 1.00889 0.00986133 -3.13746 1 0 1 1 0 0 +EDGE2 3294 2695 0.961399 -0.0159543 -3.14957 1 0 1 1 0 0 +EDGE2 3294 3293 -0.970318 -0.0985212 0.0196545 1 0 1 1 0 0 +EDGE2 3294 2974 0.0107931 0.0363129 -0.00224716 1 0 1 1 0 0 +EDGE2 3294 3273 -1.07262 0.038213 -0.00991513 1 0 1 1 0 0 +EDGE2 3295 2976 0.0766551 1.07177 1.58503 1 0 1 1 0 0 +EDGE2 3295 3276 -0.0112562 0.993304 1.57825 1 0 1 1 0 0 +EDGE2 3295 2854 0.946471 0.00876249 -3.1453 1 0 1 1 0 0 +EDGE2 3295 2775 -0.0277243 0.0237779 -3.16741 1 0 1 1 0 0 +EDGE2 3295 2674 1.07916 0.074146 -3.11758 1 0 1 1 0 0 +EDGE2 3295 2694 1.09094 0.007197 -3.11944 1 0 1 1 0 0 +EDGE2 3295 2774 0.944987 -0.0858806 -3.17948 1 0 1 1 0 0 +EDGE2 3295 2614 1.02919 -0.0068051 -3.13165 1 0 1 1 0 0 +EDGE2 3295 2975 -0.0255949 0.0592024 -0.0137906 1 0 1 1 0 0 +EDGE2 3295 3275 0.0308176 0.0220173 0.0354821 1 0 1 1 0 0 +EDGE2 3295 2855 -0.0702147 -0.0388945 -3.131 1 0 1 1 0 0 +EDGE2 3295 3274 -0.990101 0.0901322 0.0273825 1 0 1 1 0 0 +EDGE2 3295 2615 -0.0374189 0.0371167 -3.18112 1 0 1 1 0 0 +EDGE2 3295 2675 -0.0284373 -0.100964 -3.12126 1 0 1 1 0 0 +EDGE2 3295 2695 0.0846073 -0.126465 -3.16007 1 0 1 1 0 0 +EDGE2 3295 3294 -1.03759 0.0901497 0.0250748 1 0 1 1 0 0 +EDGE2 3295 2974 -1.02631 -0.0447066 0.0373484 1 0 1 1 0 0 +EDGE2 3295 2676 0.0999949 -1.06554 -1.5753 1 0 1 1 0 0 +EDGE2 3295 2776 -0.0242763 -0.974953 -1.59919 1 0 1 1 0 0 +EDGE2 3295 2856 -0.0349989 -1.05017 -1.55868 1 0 1 1 0 0 +EDGE2 3295 2696 0.0192805 -1.02533 -1.60611 1 0 1 1 0 0 +EDGE2 3295 2616 0.0399507 -0.982956 -1.54002 1 0 1 1 0 0 +EDGE2 3296 2977 0.998767 -0.00877546 0.0216772 1 0 1 1 0 0 +EDGE2 3296 3277 1.06195 -0.0350035 0.00581532 1 0 1 1 0 0 +EDGE2 3296 2976 0.00598599 -0.00481582 -0.0115662 1 0 1 1 0 0 +EDGE2 3296 3276 0.0876773 0.0499906 0.0285276 1 0 1 1 0 0 +EDGE2 3296 2775 -1.02232 0.034748 1.55575 1 0 1 1 0 0 +EDGE2 3296 2975 -1.07686 -0.0299934 -1.56653 1 0 1 1 0 0 +EDGE2 3296 3275 -1.02974 0.0113363 -1.56249 1 0 1 1 0 0 +EDGE2 3296 3295 -0.913062 -0.0441924 -1.60822 1 0 1 1 0 0 +EDGE2 3296 2855 -0.943846 -0.0281252 1.5674 1 0 1 1 0 0 +EDGE2 3296 2615 -0.963681 -0.0110083 1.57406 1 0 1 1 0 0 +EDGE2 3296 2675 -1.0069 -0.0767665 1.58214 1 0 1 1 0 0 +EDGE2 3296 2695 -1.01466 -0.120794 1.56952 1 0 1 1 0 0 +EDGE2 3297 3278 0.909962 -0.0115755 -0.00542581 1 0 1 1 0 0 +EDGE2 3297 2978 1.03133 -0.0509315 -0.0141905 1 0 1 1 0 0 +EDGE2 3297 3296 -1.02003 -0.00710441 0.00612303 1 0 1 1 0 0 +EDGE2 3297 2977 -0.0167572 -0.020253 -0.00148654 1 0 1 1 0 0 +EDGE2 3297 3277 0.015693 0.0774037 -0.00160474 1 0 1 1 0 0 +EDGE2 3297 2976 -0.997703 0.0402736 0.0195434 1 0 1 1 0 0 +EDGE2 3297 3276 -0.878546 -0.147969 -0.0251169 1 0 1 1 0 0 +EDGE2 3298 3278 0.046646 -0.0484566 0.0171236 1 0 1 1 0 0 +EDGE2 3298 2979 1.01847 0.0215968 0.0141578 1 0 1 1 0 0 +EDGE2 3298 3279 1.00947 0.0135423 0.00237573 1 0 1 1 0 0 +EDGE2 3298 3297 -1.09238 -0.12894 -0.0212606 1 0 1 1 0 0 +EDGE2 3298 2978 0.0241009 0.0507165 -0.0203934 1 0 1 1 0 0 +EDGE2 3298 2977 -0.951732 0.0146403 -0.00354426 1 0 1 1 0 0 +EDGE2 3298 3277 -0.970405 -0.0389206 -0.0273111 1 0 1 1 0 0 +EDGE2 3299 3000 1.03776 -0.0447264 -3.14043 1 0 1 1 0 0 +EDGE2 3299 3260 1.02225 -0.0338495 -3.13585 1 0 1 1 0 0 +EDGE2 3299 3280 1.00019 0.0162483 -0.000183651 1 0 1 1 0 0 +EDGE2 3299 3240 1.04648 0.118017 -3.13911 1 0 1 1 0 0 +EDGE2 3299 1220 1.0549 0.093371 -3.11652 1 0 1 1 0 0 +EDGE2 3299 2480 0.995778 0.0335865 -3.13039 1 0 1 1 0 0 +EDGE2 3299 2980 1.03283 0.0256349 -0.00568617 1 0 1 1 0 0 +EDGE2 3299 720 0.94812 -0.0186198 -3.15091 1 0 1 1 0 0 +EDGE2 3299 3278 -0.932264 -0.00846724 -0.000406785 1 0 1 1 0 0 +EDGE2 3299 2979 0.0889891 -0.063144 -0.00239566 1 0 1 1 0 0 +EDGE2 3299 3279 -0.00327284 -0.0277529 0.0186796 1 0 1 1 0 0 +EDGE2 3299 3298 -1.0469 -0.028967 0.0533489 1 0 1 1 0 0 +EDGE2 3299 2978 -0.998494 -0.0149965 0.00522299 1 0 1 1 0 0 +EDGE2 3300 2479 1.04102 0.0622394 -3.13732 1 0 1 1 0 0 +EDGE2 3300 3239 0.963837 0.132245 -3.14864 1 0 1 1 0 0 +EDGE2 3300 3259 0.966655 -0.0280318 -3.13572 1 0 1 1 0 0 +EDGE2 3300 2999 0.971239 0.0496222 -3.16426 1 0 1 1 0 0 +EDGE2 3300 719 0.990312 -0.056224 -3.16778 1 0 1 1 0 0 +EDGE2 3300 1219 0.936764 -0.023466 -3.17384 1 0 1 1 0 0 +EDGE2 3300 1221 -0.0294624 -1.10125 -1.57373 1 0 1 1 0 0 +EDGE2 3300 2981 0.116209 -1.01567 -1.53116 1 0 1 1 0 0 +EDGE2 3300 3241 0.0438757 -1.07006 -1.5885 1 0 1 1 0 0 +EDGE2 3300 2481 -0.0334084 -1.00266 -1.58439 1 0 1 1 0 0 +EDGE2 3300 3281 0.036506 0.969612 1.55702 1 0 1 1 0 0 +EDGE2 3300 3000 -0.0595151 0.0311809 -3.1583 1 0 1 1 0 0 +EDGE2 3300 3260 0.0422369 -0.093238 -3.15293 1 0 1 1 0 0 +EDGE2 3300 3280 0.0184103 -0.0754547 -0.0389392 1 0 1 1 0 0 +EDGE2 3300 3240 0.0600885 0.00139002 -3.13638 1 0 1 1 0 0 +EDGE2 3300 1220 -0.0100523 0.0755215 -3.12868 1 0 1 1 0 0 +EDGE2 3300 2480 -0.0122144 0.00519322 -3.13367 1 0 1 1 0 0 +EDGE2 3300 2980 -0.0020719 0.0764984 0.02602 1 0 1 1 0 0 +EDGE2 3300 720 0.0642892 -0.0767212 -3.12088 1 0 1 1 0 0 +EDGE2 3300 721 -0.0466107 1.05438 1.55376 1 0 1 1 0 0 +EDGE2 3300 3001 0.00620175 1.03904 1.57596 1 0 1 1 0 0 +EDGE2 3300 3261 -0.0566543 1.05408 1.59913 1 0 1 1 0 0 +EDGE2 3300 2979 -1.00872 -0.00181382 -0.0331667 1 0 1 1 0 0 +EDGE2 3300 3279 -1.13142 0.0128419 -0.0060313 1 0 1 1 0 0 +EDGE2 3300 3299 -0.988823 -0.00946411 -0.0417427 1 0 1 1 0 0 +EDGE2 3301 1221 0.0351661 -0.0187304 -0.0279824 1 0 1 1 0 0 +EDGE2 3301 1222 0.929362 -0.097988 -0.0335413 1 0 1 1 0 0 +EDGE2 3301 2982 1.08321 -0.0311354 0.0220104 1 0 1 1 0 0 +EDGE2 3301 3242 1.07363 -0.00412312 0.00995925 1 0 1 1 0 0 +EDGE2 3301 2482 0.986423 -0.0556821 -0.0143339 1 0 1 1 0 0 +EDGE2 3301 2981 0.0149056 0.00507137 -0.0222135 1 0 1 1 0 0 +EDGE2 3301 3241 -0.0373196 -0.0254759 0.0145523 1 0 1 1 0 0 +EDGE2 3301 2481 -0.0187026 -0.0162307 -0.011734 1 0 1 1 0 0 +EDGE2 3301 3000 -0.971184 -0.0142201 -1.57229 1 0 1 1 0 0 +EDGE2 3301 3260 -1.0471 0.0546427 -1.5563 1 0 1 1 0 0 +EDGE2 3301 3280 -1.105 0.0125212 1.56778 1 0 1 1 0 0 +EDGE2 3301 3300 -0.933946 0.0143309 1.56674 1 0 1 1 0 0 +EDGE2 3301 3240 -0.997042 -0.0757357 -1.5725 1 0 1 1 0 0 +EDGE2 3301 1220 -1.0139 -0.0151494 -1.52852 1 0 1 1 0 0 +EDGE2 3301 2480 -0.986642 -0.0561446 -1.55246 1 0 1 1 0 0 +EDGE2 3301 2980 -1.0322 -0.00943358 1.55295 1 0 1 1 0 0 +EDGE2 3301 720 -1.07507 -0.00138863 -1.57393 1 0 1 1 0 0 +EDGE2 3302 1221 -0.99695 -0.0118127 0.00846828 1 0 1 1 0 0 +EDGE2 3302 1223 0.971963 0.0255686 -0.00614736 1 0 1 1 0 0 +EDGE2 3302 2983 0.966149 -0.0249833 -0.0368966 1 0 1 1 0 0 +EDGE2 3302 3243 0.999831 0.113541 -0.021247 1 0 1 1 0 0 +EDGE2 3302 2483 0.962863 0.0233671 0.0035148 1 0 1 1 0 0 +EDGE2 3302 1222 -0.0141039 -0.00184041 0.000730615 1 0 1 1 0 0 +EDGE2 3302 2982 0.0401236 -0.00655785 0.00945554 1 0 1 1 0 0 +EDGE2 3302 3242 0.0611959 -0.0131569 0.00109588 1 0 1 1 0 0 +EDGE2 3302 2482 -0.00318808 -0.0183671 0.0243389 1 0 1 1 0 0 +EDGE2 3302 2981 -0.942494 0.0113389 -0.0189964 1 0 1 1 0 0 +EDGE2 3302 3241 -1.00661 -0.0159158 0.0173656 1 0 1 1 0 0 +EDGE2 3302 3301 -1.04646 0.0725097 -0.00656022 1 0 1 1 0 0 +EDGE2 3302 2481 -1.02467 0.0502233 0.0122254 1 0 1 1 0 0 +EDGE2 3303 1223 -0.0379755 0.0160513 -0.0250315 1 0 1 1 0 0 +EDGE2 3303 1224 1.02146 -0.0258327 -0.00627419 1 0 1 1 0 0 +EDGE2 3303 2984 1.01043 0.0442027 0.000952174 1 0 1 1 0 0 +EDGE2 3303 3244 1.04166 0.0308252 0.0282946 1 0 1 1 0 0 +EDGE2 3303 2484 1.01516 -0.0258199 -0.0053118 1 0 1 1 0 0 +EDGE2 3303 2983 0.0490746 -0.00191055 0.00236135 1 0 1 1 0 0 +EDGE2 3303 3243 -0.0639758 0.044076 -0.00959214 1 0 1 1 0 0 +EDGE2 3303 2483 -0.0678013 -0.036659 0.0250891 1 0 1 1 0 0 +EDGE2 3303 1222 -0.952418 -0.0333534 0.00427651 1 0 1 1 0 0 +EDGE2 3303 2982 -0.973008 -0.0983351 0.0448534 1 0 1 1 0 0 +EDGE2 3303 3242 -1.02534 0.0161756 -0.0238946 1 0 1 1 0 0 +EDGE2 3303 3302 -0.925635 0.0415064 0.000744426 1 0 1 1 0 0 +EDGE2 3303 2482 -1.02052 0.019013 0.00942489 1 0 1 1 0 0 +EDGE2 3304 2645 0.992365 0.0373408 -3.15821 1 0 1 1 0 0 +EDGE2 3304 2985 0.99703 -0.0318796 0.0138168 1 0 1 1 0 0 +EDGE2 3304 3245 0.969359 -0.0498676 0.0235482 1 0 1 1 0 0 +EDGE2 3304 2665 1.04333 0.0790461 -3.12389 1 0 1 1 0 0 +EDGE2 3304 1225 1.03747 0.0448934 -0.00176633 1 0 1 1 0 0 +EDGE2 3304 2485 0.999145 0.0507758 -0.0237193 1 0 1 1 0 0 +EDGE2 3304 2505 0.919684 -0.0203743 -3.13773 1 0 1 1 0 0 +EDGE2 3304 2605 0.935053 -0.125391 -3.16133 1 0 1 1 0 0 +EDGE2 3304 2445 0.999845 0.00570859 -3.13797 1 0 1 1 0 0 +EDGE2 3304 1223 -1.01582 -0.0206466 -0.00824016 1 0 1 1 0 0 +EDGE2 3304 1224 0.0780553 0.0486952 -0.00814773 1 0 1 1 0 0 +EDGE2 3304 2984 -0.0574326 0.0569763 0.0181212 1 0 1 1 0 0 +EDGE2 3304 3244 -0.0445212 -0.0384288 0.00681415 1 0 1 1 0 0 +EDGE2 3304 2484 -0.0929938 -0.0763693 0.0284557 1 0 1 1 0 0 +EDGE2 3304 2983 -0.924829 -0.0278333 0.00305056 1 0 1 1 0 0 +EDGE2 3304 3243 -0.948359 -0.035043 -0.00684876 1 0 1 1 0 0 +EDGE2 3304 3303 -0.976087 -0.0331921 0.0046916 1 0 1 1 0 0 +EDGE2 3304 2483 -1.02158 0.053458 0.00282583 1 0 1 1 0 0 +EDGE2 3305 2446 0.0523023 1.06381 1.58037 1 0 1 1 0 0 +EDGE2 3305 2986 0.0170355 0.967734 1.54208 1 0 1 1 0 0 +EDGE2 3305 3246 0.0422532 1.00133 1.57125 1 0 1 1 0 0 +EDGE2 3305 2486 0.0771586 0.999843 1.59503 1 0 1 1 0 0 +EDGE2 3305 1226 -0.032463 0.968025 1.58717 1 0 1 1 0 0 +EDGE2 3305 2666 0.0672439 -0.945779 -1.56483 1 0 1 1 0 0 +EDGE2 3305 2645 -0.0820528 -0.0206701 -3.11638 1 0 1 1 0 0 +EDGE2 3305 2444 1.06833 -0.0480587 -3.13693 1 0 1 1 0 0 +EDGE2 3305 2604 1.05385 -0.0485199 -3.1133 1 0 1 1 0 0 +EDGE2 3305 2644 1.06744 -0.00277665 -3.12713 1 0 1 1 0 0 +EDGE2 3305 2664 0.952275 0.0930762 -3.16195 1 0 1 1 0 0 +EDGE2 3305 2504 1.0098 -0.0483769 -3.14968 1 0 1 1 0 0 +EDGE2 3305 2985 0.0516984 0.034744 -0.0172199 1 0 1 1 0 0 +EDGE2 3305 3245 0.0126343 -0.0472263 -0.00206351 1 0 1 1 0 0 +EDGE2 3305 2665 0.0218607 -0.0796338 -3.17095 1 0 1 1 0 0 +EDGE2 3305 1225 -0.0267463 -0.020437 -0.014663 1 0 1 1 0 0 +EDGE2 3305 2485 -0.024556 -0.036805 0.00997458 1 0 1 1 0 0 +EDGE2 3305 2505 0.0399099 0.0165168 -3.14762 1 0 1 1 0 0 +EDGE2 3305 2605 0.114741 0.00252026 -3.18089 1 0 1 1 0 0 +EDGE2 3305 2445 -0.0160364 0.0186492 -3.11521 1 0 1 1 0 0 +EDGE2 3305 1224 -0.997147 0.0188602 0.0109255 1 0 1 1 0 0 +EDGE2 3305 2984 -0.960001 -0.0137559 0.0352216 1 0 1 1 0 0 +EDGE2 3305 3244 -0.965542 -0.00367885 -0.0102652 1 0 1 1 0 0 +EDGE2 3305 3304 -1.07276 -0.0235988 0.00540645 1 0 1 1 0 0 +EDGE2 3305 2484 -0.961486 -0.0137053 -0.0176426 1 0 1 1 0 0 +EDGE2 3305 2506 -0.00176451 -1.0042 -1.57038 1 0 1 1 0 0 +EDGE2 3305 2606 -0.0125813 -0.92571 -1.5719 1 0 1 1 0 0 +EDGE2 3305 2646 0.0384018 -0.931569 -1.57492 1 0 1 1 0 0 +EDGE2 3306 1227 0.975938 0.0126398 -0.0153832 1 0 1 1 0 0 +EDGE2 3306 2487 1.08427 0.0178589 -0.0229168 1 0 1 1 0 0 +EDGE2 3306 2987 0.984299 0.0318883 -0.00642426 1 0 1 1 0 0 +EDGE2 3306 3247 0.968961 -0.0323863 0.00283567 1 0 1 1 0 0 +EDGE2 3306 2447 1.01537 0.0145362 0.0244613 1 0 1 1 0 0 +EDGE2 3306 2446 0.0885039 -0.104586 -0.000304565 1 0 1 1 0 0 +EDGE2 3306 2986 -0.00414832 0.00972967 -0.00515054 1 0 1 1 0 0 +EDGE2 3306 3246 0.0157203 -0.00464535 -0.013753 1 0 1 1 0 0 +EDGE2 3306 2486 -0.0714652 -0.0309125 0.0376811 1 0 1 1 0 0 +EDGE2 3306 1226 0.0294519 0.146343 0.00292563 1 0 1 1 0 0 +EDGE2 3306 2645 -0.997752 0.0421964 1.58799 1 0 1 1 0 0 +EDGE2 3306 2985 -0.896751 -0.0248968 -1.53204 1 0 1 1 0 0 +EDGE2 3306 3245 -1.07483 -0.100548 -1.57958 1 0 1 1 0 0 +EDGE2 3306 3305 -1.02309 0.00799773 -1.55145 1 0 1 1 0 0 +EDGE2 3306 2665 -0.93271 -0.0310444 1.59137 1 0 1 1 0 0 +EDGE2 3306 1225 -0.969171 0.0348301 -1.56659 1 0 1 1 0 0 +EDGE2 3306 2485 -0.988851 -0.0383688 -1.55592 1 0 1 1 0 0 +EDGE2 3306 2505 -1.04699 -0.0807786 1.57879 1 0 1 1 0 0 +EDGE2 3306 2605 -0.998414 0.0117006 1.59511 1 0 1 1 0 0 +EDGE2 3306 2445 -1.03141 -0.00456086 1.55026 1 0 1 1 0 0 +EDGE2 3307 2488 1.01868 -0.134133 -0.0416415 1 0 1 1 0 0 +EDGE2 3307 3248 1.02332 0.00397234 -0.00264516 1 0 1 1 0 0 +EDGE2 3307 2988 1.05196 -0.00571237 -0.0390363 1 0 1 1 0 0 +EDGE2 3307 1228 0.961577 -0.00958085 -0.015046 1 0 1 1 0 0 +EDGE2 3307 2448 0.948659 0.0826409 -0.00529742 1 0 1 1 0 0 +EDGE2 3307 1227 0.0207117 -0.0539615 -0.0216492 1 0 1 1 0 0 +EDGE2 3307 2487 -0.0388699 0.0146329 -0.0264917 1 0 1 1 0 0 +EDGE2 3307 2987 -0.0175838 -0.012404 0.00897334 1 0 1 1 0 0 +EDGE2 3307 3247 0.0661625 0.0159616 0.00931296 1 0 1 1 0 0 +EDGE2 3307 2447 -0.0467849 -0.03424 0.0115214 1 0 1 1 0 0 +EDGE2 3307 3306 -0.962492 -0.00560695 0.0229959 1 0 1 1 0 0 +EDGE2 3307 2446 -1.01191 0.0518727 0.0180493 1 0 1 1 0 0 +EDGE2 3307 2986 -0.972566 -0.0100434 0.00890294 1 0 1 1 0 0 +EDGE2 3307 3246 -1.02473 -0.0180221 0.020345 1 0 1 1 0 0 +EDGE2 3307 2486 -0.960081 -0.054461 -0.041246 1 0 1 1 0 0 +EDGE2 3307 1226 -0.985442 0.0229516 0.0313268 1 0 1 1 0 0 +EDGE2 3308 2488 -0.00595372 0.00109734 -0.0134606 1 0 1 1 0 0 +EDGE2 3308 2449 1.0503 -0.0595957 0.00513426 1 0 1 1 0 0 +EDGE2 3308 2989 1.01124 -0.0301019 0.0160104 1 0 1 1 0 0 +EDGE2 3308 3249 0.925774 -0.0739545 -0.0510532 1 0 1 1 0 0 +EDGE2 3308 2489 1.01378 -0.0920024 -0.0140052 1 0 1 1 0 0 +EDGE2 3308 3248 -0.0355274 -0.0689132 0.0127403 1 0 1 1 0 0 +EDGE2 3308 1229 0.987952 -0.0106444 0.00349197 1 0 1 1 0 0 +EDGE2 3308 2988 0.0150556 -0.0446193 0.00571535 1 0 1 1 0 0 +EDGE2 3308 1228 -0.0732431 -0.004644 -0.0084807 1 0 1 1 0 0 +EDGE2 3308 2448 0.0464954 -0.0252079 -0.0123104 1 0 1 1 0 0 +EDGE2 3308 1227 -0.919205 -0.0270807 -0.00393157 1 0 1 1 0 0 +EDGE2 3308 3307 -0.999501 0.0946207 -0.0037892 1 0 1 1 0 0 +EDGE2 3308 2487 -1.02485 0.00726476 0.0157821 1 0 1 1 0 0 +EDGE2 3308 2987 -0.958773 -0.086104 0.0402872 1 0 1 1 0 0 +EDGE2 3308 3247 -0.972939 0.0213261 -0.0187932 1 0 1 1 0 0 +EDGE2 3308 2447 -1.06024 -0.00499336 0.000923903 1 0 1 1 0 0 +EDGE2 3309 1250 0.985263 0.0238891 -3.1541 1 0 1 1 0 0 +EDGE2 3309 2990 0.947656 0.00633295 -0.0247791 1 0 1 1 0 0 +EDGE2 3309 3250 0.972268 0.071836 -0.0245145 1 0 1 1 0 0 +EDGE2 3309 2450 1.05625 0.0591189 -0.0292519 1 0 1 1 0 0 +EDGE2 3309 2470 1.01838 -0.0215404 -3.12473 1 0 1 1 0 0 +EDGE2 3309 2490 1.16253 -0.0557934 -0.00387784 1 0 1 1 0 0 +EDGE2 3309 2290 0.951743 -0.0544802 -3.12888 1 0 1 1 0 0 +EDGE2 3309 1230 1.03161 0.0751377 -0.0140174 1 0 1 1 0 0 +EDGE2 3309 2488 -1.0265 -0.0452509 0.0057934 1 0 1 1 0 0 +EDGE2 3309 2449 -0.011126 0.11155 -0.0191753 1 0 1 1 0 0 +EDGE2 3309 2989 -0.100233 -0.0116066 -0.0291582 1 0 1 1 0 0 +EDGE2 3309 3249 0.0175749 0.00229373 0.0276349 1 0 1 1 0 0 +EDGE2 3309 2489 0.0446322 0.0258597 -0.00471356 1 0 1 1 0 0 +EDGE2 3309 3248 -1.02424 0.0713268 -0.00577176 1 0 1 1 0 0 +EDGE2 3309 3308 -0.955634 0.0174514 0.0376543 1 0 1 1 0 0 +EDGE2 3309 1229 -0.0629103 -0.0551877 -0.0134156 1 0 1 1 0 0 +EDGE2 3309 2988 -0.955737 -0.0561405 -0.0220439 1 0 1 1 0 0 +EDGE2 3309 1228 -0.92805 -0.0197638 0.00515382 1 0 1 1 0 0 +EDGE2 3309 2448 -0.965492 0.00615246 -0.00638508 1 0 1 1 0 0 +EDGE2 3310 2291 -0.0235354 -0.949995 -1.55939 1 0 1 1 0 0 +EDGE2 3310 2289 1.02546 -0.0665843 -3.15836 1 0 1 1 0 0 +EDGE2 3310 2469 0.836186 0.00145892 -3.12966 1 0 1 1 0 0 +EDGE2 3310 2491 0.0594704 -0.938617 -1.57323 1 0 1 1 0 0 +EDGE2 3310 2451 -0.00481982 -1.01828 -1.59891 1 0 1 1 0 0 +EDGE2 3310 1249 1.01416 0.0175824 -3.14006 1 0 1 1 0 0 +EDGE2 3310 1250 0.0152125 -0.0204583 -3.14444 1 0 1 1 0 0 +EDGE2 3310 2990 -0.0935632 0.0259011 0.0141323 1 0 1 1 0 0 +EDGE2 3310 1231 -0.00140383 -1.08614 -1.59724 1 0 1 1 0 0 +EDGE2 3310 1251 -0.00610373 -0.987952 -1.57183 1 0 1 1 0 0 +EDGE2 3310 3250 0.00262034 -0.0486275 0.0102067 1 0 1 1 0 0 +EDGE2 3310 2450 0.0162691 0.084627 0.0531351 1 0 1 1 0 0 +EDGE2 3310 2470 0.0431409 0.0272042 -3.13546 1 0 1 1 0 0 +EDGE2 3310 2490 6.90124e-06 -0.0395704 -0.016718 1 0 1 1 0 0 +EDGE2 3310 2290 0.0653418 0.0203287 -3.11752 1 0 1 1 0 0 +EDGE2 3310 2991 -0.0406982 1.05345 1.60283 1 0 1 1 0 0 +EDGE2 3310 3251 0.0613355 1.07876 1.54747 1 0 1 1 0 0 +EDGE2 3310 1230 -0.0331987 -0.0327984 -0.0240377 1 0 1 1 0 0 +EDGE2 3310 2471 -0.0104406 0.967328 1.56821 1 0 1 1 0 0 +EDGE2 3310 2449 -0.912694 -0.0461621 -0.0156322 1 0 1 1 0 0 +EDGE2 3310 2989 -0.951292 -0.0506881 0.00650355 1 0 1 1 0 0 +EDGE2 3310 3249 -1.01476 -0.0830916 -0.00347294 1 0 1 1 0 0 +EDGE2 3310 3309 -0.966098 -0.00769772 0.0261489 1 0 1 1 0 0 +EDGE2 3310 2489 -0.944857 0.0447373 -0.0168471 1 0 1 1 0 0 +EDGE2 3310 1229 -0.972711 -0.0482663 0.0195192 1 0 1 1 0 0 +EDGE2 3311 2292 1.02396 0.022563 -0.0356502 1 0 1 1 0 0 +EDGE2 3311 2452 0.974717 -0.0521355 -0.0118641 1 0 1 1 0 0 +EDGE2 3311 2492 1.05801 0.0446589 -0.0283459 1 0 1 1 0 0 +EDGE2 3311 2291 0.0407314 0.0125504 -0.0459716 1 0 1 1 0 0 +EDGE2 3311 1252 1.02275 0.0680162 -0.0157114 1 0 1 1 0 0 +EDGE2 3311 2491 -0.0517521 -0.0113577 0.0178126 1 0 1 1 0 0 +EDGE2 3311 1232 0.908973 0.0215079 -0.0200971 1 0 1 1 0 0 +EDGE2 3311 2451 0.101411 -0.0275078 -0.0222126 1 0 1 1 0 0 +EDGE2 3311 1250 -0.911483 0.055646 -1.58291 1 0 1 1 0 0 +EDGE2 3311 2990 -1.00488 -0.0145909 1.58021 1 0 1 1 0 0 +EDGE2 3311 3310 -1.07419 0.0356225 1.53789 1 0 1 1 0 0 +EDGE2 3311 1231 -0.0258672 -0.0748846 -0.024855 1 0 1 1 0 0 +EDGE2 3311 1251 -0.0733967 0.0217332 0.0057359 1 0 1 1 0 0 +EDGE2 3311 3250 -1.02842 0.0789605 1.57061 1 0 1 1 0 0 +EDGE2 3311 2450 -0.962946 -0.0324934 1.55575 1 0 1 1 0 0 +EDGE2 3311 2470 -1.04238 0.0275107 -1.56929 1 0 1 1 0 0 +EDGE2 3311 2490 -1.04307 -0.00445881 1.5624 1 0 1 1 0 0 +EDGE2 3311 2290 -1.00788 -0.0341802 -1.56683 1 0 1 1 0 0 +EDGE2 3311 1230 -1.06193 -0.0429364 1.57576 1 0 1 1 0 0 +EDGE2 3312 2292 -0.031795 0.0962149 0.00837746 1 0 1 1 0 0 +EDGE2 3312 2293 1.07937 -0.0690788 0.0156211 1 0 1 1 0 0 +EDGE2 3312 2493 1.04079 0.0563201 -0.0232907 1 0 1 1 0 0 +EDGE2 3312 2453 1.12097 -0.017759 -0.018027 1 0 1 1 0 0 +EDGE2 3312 2452 0.0224417 0.026745 0.0286562 1 0 1 1 0 0 +EDGE2 3312 1233 0.999204 0.0154089 -0.0118722 1 0 1 1 0 0 +EDGE2 3312 1253 0.984636 -0.0305224 0.00585851 1 0 1 1 0 0 +EDGE2 3312 2492 0.0299347 -0.0476936 0.00603527 1 0 1 1 0 0 +EDGE2 3312 2291 -1.00126 0.0577067 -0.00393294 1 0 1 1 0 0 +EDGE2 3312 1252 -0.0217183 -0.0114469 -0.0155421 1 0 1 1 0 0 +EDGE2 3312 2491 -1.06248 0.0804224 0.0414024 1 0 1 1 0 0 +EDGE2 3312 3311 -0.970534 0.00773519 -0.0220335 1 0 1 1 0 0 +EDGE2 3312 1232 -0.077641 -0.0311107 0.00981586 1 0 1 1 0 0 +EDGE2 3312 2451 -1.00035 -0.0575573 0.00130602 1 0 1 1 0 0 +EDGE2 3312 1231 -1.06731 -0.0849483 0.00141607 1 0 1 1 0 0 +EDGE2 3312 1251 -1.04933 -0.0128394 -0.0162924 1 0 1 1 0 0 +EDGE2 3313 2292 -1.05248 -0.0238921 0.06501 1 0 1 1 0 0 +EDGE2 3313 2293 -0.0505055 0.0663459 0.0183798 1 0 1 1 0 0 +EDGE2 3313 1254 1.0566 0.0225622 -0.0045866 1 0 1 1 0 0 +EDGE2 3313 2454 1.06956 0.108964 -0.028655 1 0 1 1 0 0 +EDGE2 3313 2494 1.07496 -0.0399902 -0.00881849 1 0 1 1 0 0 +EDGE2 3313 2294 0.925285 0.0355485 0.0119077 1 0 1 1 0 0 +EDGE2 3313 2493 -0.0860179 0.0495612 -0.0166324 1 0 1 1 0 0 +EDGE2 3313 1234 0.961593 -0.0076817 0.0243746 1 0 1 1 0 0 +EDGE2 3313 2453 -0.0205465 0.102422 -0.0281528 1 0 1 1 0 0 +EDGE2 3313 2452 -0.927251 0.00301162 0.00667789 1 0 1 1 0 0 +EDGE2 3313 3312 -1.02765 -0.0423899 -0.00264125 1 0 1 1 0 0 +EDGE2 3313 1233 0.0731195 0.00912528 0.0251503 1 0 1 1 0 0 +EDGE2 3313 1253 -0.0275406 -0.0359728 -0.00470126 1 0 1 1 0 0 +EDGE2 3313 2492 -0.955836 -0.0170725 0.0290645 1 0 1 1 0 0 +EDGE2 3313 1252 -0.981302 -0.050245 0.0232774 1 0 1 1 0 0 +EDGE2 3313 1232 -0.973171 -0.0918681 0.00915728 1 0 1 1 0 0 +EDGE2 3314 2595 0.999282 -0.0500671 -3.16954 1 0 1 1 0 0 +EDGE2 3314 2293 -1.02766 -0.0676823 0.00294346 1 0 1 1 0 0 +EDGE2 3314 1235 1.00502 0.0148031 0.00775668 1 0 1 1 0 0 +EDGE2 3314 2455 1.00215 0.013246 0.00852303 1 0 1 1 0 0 +EDGE2 3314 2535 0.953931 -0.0132084 -3.13005 1 0 1 1 0 0 +EDGE2 3314 2555 0.99734 0.0105538 -3.12296 1 0 1 1 0 0 +EDGE2 3314 2575 0.949575 0.0767387 -3.12866 1 0 1 1 0 0 +EDGE2 3314 2495 1.0081 -0.12489 0.00823621 1 0 1 1 0 0 +EDGE2 3314 2295 1.05031 -0.0467774 0.0129851 1 0 1 1 0 0 +EDGE2 3314 2415 1.01172 -0.0615913 -3.17668 1 0 1 1 0 0 +EDGE2 3314 2435 1.06214 -0.00609999 -3.11989 1 0 1 1 0 0 +EDGE2 3314 1255 1.05342 -0.0452681 -4.75017e-05 1 0 1 1 0 0 +EDGE2 3314 1254 0.0326913 0.0179872 0.000443354 1 0 1 1 0 0 +EDGE2 3314 2454 0.00930025 0.0210019 -0.0371642 1 0 1 1 0 0 +EDGE2 3314 2494 0.0852072 0.0337896 0.0229615 1 0 1 1 0 0 +EDGE2 3314 2294 -0.0773629 0.0210236 0.0137265 1 0 1 1 0 0 +EDGE2 3314 2493 -0.995207 0.0859097 -0.0166019 1 0 1 1 0 0 +EDGE2 3314 3313 -1.00403 -0.0141424 -0.0062012 1 0 1 1 0 0 +EDGE2 3314 1234 0.0124886 -0.0188591 0.031355 1 0 1 1 0 0 +EDGE2 3314 2453 -1.02022 0.0319977 0.0118835 1 0 1 1 0 0 +EDGE2 3314 1233 -0.944303 0.0167361 -0.00591321 1 0 1 1 0 0 +EDGE2 3314 1253 -1.08279 -0.0614024 -0.0393549 1 0 1 1 0 0 +EDGE2 3315 2416 0.0460254 -0.952821 -1.6033 1 0 1 1 0 0 +EDGE2 3315 2595 0.121318 0.0204775 -3.12169 1 0 1 1 0 0 +EDGE2 3315 2456 -0.0266147 0.974289 1.55661 1 0 1 1 0 0 +EDGE2 3315 1236 -0.0384365 0.886283 1.56013 1 0 1 1 0 0 +EDGE2 3315 2554 0.99562 0.037142 -3.16281 1 0 1 1 0 0 +EDGE2 3315 2594 0.976878 0.00913443 -3.15284 1 0 1 1 0 0 +EDGE2 3315 2574 1.03108 0.0215068 -3.1421 1 0 1 1 0 0 +EDGE2 3315 2414 0.993003 -0.00789133 -3.14779 1 0 1 1 0 0 +EDGE2 3315 2434 1.06583 -0.00564665 -3.16013 1 0 1 1 0 0 +EDGE2 3315 2534 1.06078 -0.0319614 -3.13623 1 0 1 1 0 0 +EDGE2 3315 1235 0.0105372 -0.0326227 0.00967511 1 0 1 1 0 0 +EDGE2 3315 2455 -0.0311542 -0.00235473 -0.0193693 1 0 1 1 0 0 +EDGE2 3315 2535 0.0163329 0.038754 -3.15588 1 0 1 1 0 0 +EDGE2 3315 2555 -0.000650436 0.054329 -3.16669 1 0 1 1 0 0 +EDGE2 3315 2575 -0.0401851 -0.0478209 -3.12716 1 0 1 1 0 0 +EDGE2 3315 2495 -0.0368352 0.0833595 -0.0122767 1 0 1 1 0 0 +EDGE2 3315 2295 -0.0605251 -0.0351379 -0.0217439 1 0 1 1 0 0 +EDGE2 3315 2415 0.00835525 0.123293 -3.14746 1 0 1 1 0 0 +EDGE2 3315 2435 -0.0332513 -0.0310671 -3.14662 1 0 1 1 0 0 +EDGE2 3315 1255 0.0989654 0.022817 -0.0159604 1 0 1 1 0 0 +EDGE2 3315 1254 -0.953935 -0.0167728 0.0266229 1 0 1 1 0 0 +EDGE2 3315 2454 -0.939377 0.0799069 -0.00752285 1 0 1 1 0 0 +EDGE2 3315 2494 -0.965201 -0.0289262 -0.0528461 1 0 1 1 0 0 +EDGE2 3315 3314 -1.08376 -0.0114878 0.00488446 1 0 1 1 0 0 +EDGE2 3315 2294 -0.999422 0.0711985 0.00500489 1 0 1 1 0 0 +EDGE2 3315 1234 -0.958674 -0.0782162 0.0112696 1 0 1 1 0 0 +EDGE2 3315 2556 -0.0891614 -0.918898 -1.55807 1 0 1 1 0 0 +EDGE2 3315 2596 0.0620318 -0.988017 -1.59141 1 0 1 1 0 0 +EDGE2 3315 2576 0.0610318 -0.968667 -1.56493 1 0 1 1 0 0 +EDGE2 3315 2496 0.0570755 -1.00836 -1.55852 1 0 1 1 0 0 +EDGE2 3315 2536 0.00910376 -0.996907 -1.59906 1 0 1 1 0 0 +EDGE2 3315 2436 -0.0586788 -0.923769 -1.57283 1 0 1 1 0 0 +EDGE2 3315 1256 -0.017188 -1.04013 -1.56459 1 0 1 1 0 0 +EDGE2 3315 2296 -0.0182661 -0.956662 -1.54508 1 0 1 1 0 0 +EDGE2 3316 2595 -1.06039 0.0485347 1.59232 1 0 1 1 0 0 +EDGE2 3316 2456 0.00546074 -0.0100044 0.00832802 1 0 1 1 0 0 +EDGE2 3316 1237 1.03457 -0.0441682 0.0178601 1 0 1 1 0 0 +EDGE2 3316 2457 0.948908 -0.0576459 -0.0134535 1 0 1 1 0 0 +EDGE2 3316 1236 -0.00780186 -0.0298797 0.0360182 1 0 1 1 0 0 +EDGE2 3316 3315 -0.988557 0.0504248 -1.58657 1 0 1 1 0 0 +EDGE2 3316 1235 -1.02137 0.0800423 -1.54764 1 0 1 1 0 0 +EDGE2 3316 2455 -0.972305 0.00242878 -1.56222 1 0 1 1 0 0 +EDGE2 3316 2535 -1.05056 -0.0214851 1.58352 1 0 1 1 0 0 +EDGE2 3316 2555 -1.09892 -0.0564258 1.56521 1 0 1 1 0 0 +EDGE2 3316 2575 -1.03415 -0.0222048 1.57585 1 0 1 1 0 0 +EDGE2 3316 2495 -0.992191 -0.0501542 -1.58351 1 0 1 1 0 0 +EDGE2 3316 2295 -1.06261 -0.129816 -1.57177 1 0 1 1 0 0 +EDGE2 3316 2415 -0.987074 -0.0445414 1.55572 1 0 1 1 0 0 +EDGE2 3316 2435 -0.925695 0.0649523 1.56994 1 0 1 1 0 0 +EDGE2 3316 1255 -1.03002 -0.0423285 -1.59218 1 0 1 1 0 0 +EDGE2 3317 2458 1.00633 0.0931927 -0.0212971 1 0 1 1 0 0 +EDGE2 3317 1238 0.962416 -0.0164739 -0.0143108 1 0 1 1 0 0 +EDGE2 3317 2456 -1.08562 0.0956475 0.00906911 1 0 1 1 0 0 +EDGE2 3317 1237 -0.00710988 -0.0366054 -0.0162729 1 0 1 1 0 0 +EDGE2 3317 2457 -0.0777526 0.012788 -0.0130122 1 0 1 1 0 0 +EDGE2 3317 3316 -0.961032 -0.133478 0.0128185 1 0 1 1 0 0 +EDGE2 3317 1236 -1.00563 -0.0606579 0.0112324 1 0 1 1 0 0 +EDGE2 3318 1239 1.0171 -0.0220403 0.0435665 1 0 1 1 0 0 +EDGE2 3318 2459 0.956632 0.0120971 -0.00282152 1 0 1 1 0 0 +EDGE2 3318 2458 0.0947221 -0.0132483 -0.00849084 1 0 1 1 0 0 +EDGE2 3318 1238 -0.0252942 -0.00222435 0.0278636 1 0 1 1 0 0 +EDGE2 3318 1237 -0.977106 0.0759503 0.00719493 1 0 1 1 0 0 +EDGE2 3318 2457 -0.987325 0.0131712 0.0132721 1 0 1 1 0 0 +EDGE2 3318 3317 -1.05283 -0.0037357 -0.00776322 1 0 1 1 0 0 +EDGE2 3319 2460 0.972941 0.0613885 0.000338892 1 0 1 1 0 0 +EDGE2 3319 1820 1.10416 -0.0994444 -3.12878 1 0 1 1 0 0 +EDGE2 3319 2240 0.960592 0.0289952 -3.15195 1 0 1 1 0 0 +EDGE2 3319 2280 1.03002 -0.0649053 -3.14613 1 0 1 1 0 0 +EDGE2 3319 1240 0.968866 -0.0234519 -0.037504 1 0 1 1 0 0 +EDGE2 3319 1239 -0.0691544 0.0343132 -0.0171756 1 0 1 1 0 0 +EDGE2 3319 2459 0.0296619 0.0337655 -0.0202828 1 0 1 1 0 0 +EDGE2 3319 2458 -1.049 -0.0129186 -0.0107526 1 0 1 1 0 0 +EDGE2 3319 3318 -0.940215 0.00742549 0.0130985 1 0 1 1 0 0 +EDGE2 3319 1238 -0.949838 -0.00954356 -0.0251562 1 0 1 1 0 0 +EDGE2 3320 2239 1.04991 -0.0314306 -3.15238 1 0 1 1 0 0 +EDGE2 3320 2279 1.05894 0.0486932 -3.16614 1 0 1 1 0 0 +EDGE2 3320 1819 0.999487 -0.0544954 -3.10162 1 0 1 1 0 0 +EDGE2 3320 2460 0.0443542 -0.0336981 0.00271398 1 0 1 1 0 0 +EDGE2 3320 1821 -0.00981966 -0.966363 -1.5435 1 0 1 1 0 0 +EDGE2 3320 2241 0.0672712 -1.03898 -1.57005 1 0 1 1 0 0 +EDGE2 3320 1820 0.0152963 0.0271037 -3.16514 1 0 1 1 0 0 +EDGE2 3320 2240 0.00722524 -0.0100537 -3.15458 1 0 1 1 0 0 +EDGE2 3320 2280 0.0286146 -0.0243479 -3.13729 1 0 1 1 0 0 +EDGE2 3320 1240 0.0446443 -0.07027 0.00873288 1 0 1 1 0 0 +EDGE2 3320 1241 0.0417037 1.06407 1.5959 1 0 1 1 0 0 +EDGE2 3320 2281 -0.00352857 1.00858 1.60809 1 0 1 1 0 0 +EDGE2 3320 2461 -0.0424383 1.01639 1.56232 1 0 1 1 0 0 +EDGE2 3320 1239 -0.973117 0.0429065 0.000662066 1 0 1 1 0 0 +EDGE2 3320 3319 -1.05367 -0.0602865 0.0252102 1 0 1 1 0 0 +EDGE2 3320 2459 -0.927753 -0.0722823 -0.0122606 1 0 1 1 0 0 +EDGE2 3321 2462 0.96254 -0.0463623 -0.00788096 1 0 1 1 0 0 +EDGE2 3321 2460 -1.03935 -0.0214944 -1.56015 1 0 1 1 0 0 +EDGE2 3321 3320 -0.992419 -0.0845402 -1.56172 1 0 1 1 0 0 +EDGE2 3321 1820 -1.00268 -0.0797316 1.56149 1 0 1 1 0 0 +EDGE2 3321 2240 -0.952636 -0.0826866 1.53328 1 0 1 1 0 0 +EDGE2 3321 2280 -0.939945 -0.0201754 1.54894 1 0 1 1 0 0 +EDGE2 3321 1240 -1.05224 0.00352769 -1.57396 1 0 1 1 0 0 +EDGE2 3321 1241 -0.0141597 -0.0303769 -0.00966057 1 0 1 1 0 0 +EDGE2 3321 2281 0.00245146 0.0356292 -0.0344279 1 0 1 1 0 0 +EDGE2 3321 2461 -0.0622805 0.0597103 -0.00987734 1 0 1 1 0 0 +EDGE2 3321 1242 1.00301 0.00557894 -0.0311233 1 0 1 1 0 0 +EDGE2 3321 2282 1.00682 0.0587771 0.000834889 1 0 1 1 0 0 +EDGE2 3322 2462 0.0757182 -0.0325782 0.0138951 1 0 1 1 0 0 +EDGE2 3322 3321 -0.950301 -0.0528633 0.0232553 1 0 1 1 0 0 +EDGE2 3322 1241 -0.991685 -0.0535568 -0.0419102 1 0 1 1 0 0 +EDGE2 3322 2281 -1.00393 0.0142368 0.0212404 1 0 1 1 0 0 +EDGE2 3322 2461 -0.934291 -0.0196201 0.00483988 1 0 1 1 0 0 +EDGE2 3322 1242 -0.0798438 -0.070335 -0.0167709 1 0 1 1 0 0 +EDGE2 3322 2282 0.0134139 0.012807 0.00886222 1 0 1 1 0 0 +EDGE2 3322 2283 0.939309 0.0262616 -0.00415073 1 0 1 1 0 0 +EDGE2 3322 2463 1.05501 -0.0218599 -0.00801052 1 0 1 1 0 0 +EDGE2 3322 1243 0.924832 -0.021559 -0.0112365 1 0 1 1 0 0 +EDGE2 3323 2462 -1.04679 0.088318 0.000316145 1 0 1 1 0 0 +EDGE2 3323 3322 -1.01903 -0.0516774 -0.0113234 1 0 1 1 0 0 +EDGE2 3323 1242 -1.02692 -0.0597623 0.0177208 1 0 1 1 0 0 +EDGE2 3323 2282 -1.01892 -0.0165663 0.00860542 1 0 1 1 0 0 +EDGE2 3323 2283 0.0220592 -0.0524576 -3.58267e-05 1 0 1 1 0 0 +EDGE2 3323 2463 -0.0432079 0.0378471 -0.023117 1 0 1 1 0 0 +EDGE2 3323 1243 -0.0149013 -0.0204494 0.00332905 1 0 1 1 0 0 +EDGE2 3323 1244 0.963784 0.0187308 0.0173745 1 0 1 1 0 0 +EDGE2 3323 2284 0.999356 -0.019808 0.0144706 1 0 1 1 0 0 +EDGE2 3323 2464 1.07764 -0.00119657 -0.00323688 1 0 1 1 0 0 +EDGE2 3324 2283 -1.04544 -0.0322219 -0.00239024 1 0 1 1 0 0 +EDGE2 3324 2463 -0.992501 0.0291548 -0.00625201 1 0 1 1 0 0 +EDGE2 3324 3323 -1.1117 0.0539132 0.00178663 1 0 1 1 0 0 +EDGE2 3324 1243 -0.965448 -0.0106587 0.0138519 1 0 1 1 0 0 +EDGE2 3324 785 1.00725 -0.00260135 -3.14873 1 0 1 1 0 0 +EDGE2 3324 1244 -0.0650317 -0.0673991 -0.000384273 1 0 1 1 0 0 +EDGE2 3324 2284 0.0335866 -0.0489418 -0.000667861 1 0 1 1 0 0 +EDGE2 3324 2464 0.019085 0.0263792 0.00587721 1 0 1 1 0 0 +EDGE2 3324 1245 1.07589 0.0210965 -0.0177229 1 0 1 1 0 0 +EDGE2 3324 2285 1.01479 0.0791584 -0.00829919 1 0 1 1 0 0 +EDGE2 3324 2465 0.999986 -0.000515196 0.0242417 1 0 1 1 0 0 +EDGE2 3324 805 1.07168 0.0616988 -3.17257 1 0 1 1 0 0 +EDGE2 3324 745 1.02167 0.0424794 -3.14999 1 0 1 1 0 0 +EDGE2 3324 765 1.11652 0.0332389 -3.12199 1 0 1 1 0 0 +EDGE2 3325 3324 -0.928702 -0.0426225 0.0384264 1 0 1 1 0 0 +EDGE2 3325 806 0.0778347 -0.967534 -1.59266 1 0 1 1 0 0 +EDGE2 3325 766 0.0207124 -0.987073 -1.59609 1 0 1 1 0 0 +EDGE2 3325 786 -0.0417799 -1.00279 -1.55591 1 0 1 1 0 0 +EDGE2 3325 746 -0.0336057 -0.974465 -1.54004 1 0 1 1 0 0 +EDGE2 3325 785 0.0112827 0.0454252 -3.12064 1 0 1 1 0 0 +EDGE2 3325 1244 -1.11899 0.0353009 -0.00463916 1 0 1 1 0 0 +EDGE2 3325 2284 -0.998981 -0.129317 0.0364608 1 0 1 1 0 0 +EDGE2 3325 2464 -0.997436 0.00863474 -0.0126817 1 0 1 1 0 0 +EDGE2 3325 1245 -0.0132301 0.0630206 -0.003649 1 0 1 1 0 0 +EDGE2 3325 2285 0.00542649 -0.00358937 0.0328992 1 0 1 1 0 0 +EDGE2 3325 2465 -0.0842099 0.0358564 0.0352779 1 0 1 1 0 0 +EDGE2 3325 805 0.00224523 -0.00474787 -3.15446 1 0 1 1 0 0 +EDGE2 3325 784 1.00448 0.0286191 -3.1489 1 0 1 1 0 0 +EDGE2 3325 745 -0.034615 -0.0794056 -3.18396 1 0 1 1 0 0 +EDGE2 3325 765 -0.02449 -0.0123258 -3.13538 1 0 1 1 0 0 +EDGE2 3325 804 1.01296 0.0554236 -3.12434 1 0 1 1 0 0 +EDGE2 3325 744 1.05234 -0.11607 -3.14525 1 0 1 1 0 0 +EDGE2 3325 764 1.0541 0.107754 -3.15994 1 0 1 1 0 0 +EDGE2 3325 2286 -0.0340374 1.02317 1.55776 1 0 1 1 0 0 +EDGE2 3325 2466 0.0626305 1.01869 1.53903 1 0 1 1 0 0 +EDGE2 3325 1246 -0.0152224 0.948014 1.58896 1 0 1 1 0 0 +EDGE2 3326 747 1.04606 0.0476765 -0.00532169 1 0 1 1 0 0 +EDGE2 3326 767 1.0023 -0.045589 0.0452275 1 0 1 1 0 0 +EDGE2 3326 807 1.00206 0.0124888 -0.013025 1 0 1 1 0 0 +EDGE2 3326 787 0.979021 0.0662641 0.0165625 1 0 1 1 0 0 +EDGE2 3326 806 -0.00888033 0.00512602 -0.00792122 1 0 1 1 0 0 +EDGE2 3326 766 0.0116508 -0.0388929 0.00971959 1 0 1 1 0 0 +EDGE2 3326 786 -0.043242 -0.0340783 -0.0389305 1 0 1 1 0 0 +EDGE2 3326 746 -0.0070529 0.0447766 0.0128071 1 0 1 1 0 0 +EDGE2 3326 785 -1.01651 0.0425264 -1.58191 1 0 1 1 0 0 +EDGE2 3326 3325 -1.03173 0.0631567 1.56462 1 0 1 1 0 0 +EDGE2 3326 1245 -1.01394 0.0383021 1.59324 1 0 1 1 0 0 +EDGE2 3326 2285 -1.11546 0.00164591 1.57156 1 0 1 1 0 0 +EDGE2 3326 2465 -0.944034 0.0405892 1.59433 1 0 1 1 0 0 +EDGE2 3326 805 -0.982043 -0.00259942 -1.55199 1 0 1 1 0 0 +EDGE2 3326 745 -1.04098 -0.00377271 -1.56515 1 0 1 1 0 0 +EDGE2 3326 765 -1.06981 -0.0634721 -1.58301 1 0 1 1 0 0 +EDGE2 3327 748 0.989113 -0.0658083 0.0271827 1 0 1 1 0 0 +EDGE2 3327 788 1.04891 -0.0542694 0.010509 1 0 1 1 0 0 +EDGE2 3327 808 0.940853 -0.0177654 -0.0240545 1 0 1 1 0 0 +EDGE2 3327 768 0.994981 -0.000267873 -0.0462945 1 0 1 1 0 0 +EDGE2 3327 747 -0.0399196 -0.000121974 -0.00248601 1 0 1 1 0 0 +EDGE2 3327 767 -0.0207378 -0.0443436 0.00948871 1 0 1 1 0 0 +EDGE2 3327 807 0.00986876 -0.0637764 -0.0275612 1 0 1 1 0 0 +EDGE2 3327 787 0.00242101 0.0289465 0.00675582 1 0 1 1 0 0 +EDGE2 3327 806 -0.985036 -0.086349 0.00624378 1 0 1 1 0 0 +EDGE2 3327 3326 -1.03627 0.00789033 0.0010477 1 0 1 1 0 0 +EDGE2 3327 766 -0.935456 0.00524421 -0.0711142 1 0 1 1 0 0 +EDGE2 3327 786 -0.953358 -0.0308408 -0.00480505 1 0 1 1 0 0 +EDGE2 3327 746 -1.07674 0.0492971 0.0187878 1 0 1 1 0 0 +EDGE2 3328 748 -0.0306005 -0.0391436 -0.0226923 1 0 1 1 0 0 +EDGE2 3328 788 0.00872395 0.0123468 -0.00173957 1 0 1 1 0 0 +EDGE2 3328 769 0.950586 0.0492348 0.0367135 1 0 1 1 0 0 +EDGE2 3328 809 0.930182 0.0592356 -0.00308586 1 0 1 1 0 0 +EDGE2 3328 789 0.942417 0.0400563 0.0155951 1 0 1 1 0 0 +EDGE2 3328 749 1.06643 -0.0202527 0.0156258 1 0 1 1 0 0 +EDGE2 3328 808 0.00832367 0.054693 0.00729255 1 0 1 1 0 0 +EDGE2 3328 768 0.0151303 -0.0614019 0.0118836 1 0 1 1 0 0 +EDGE2 3328 747 -1.0368 -0.0422559 0.0212278 1 0 1 1 0 0 +EDGE2 3328 767 -0.948394 0.000105435 -0.031079 1 0 1 1 0 0 +EDGE2 3328 807 -0.955698 0.0264671 0.00673881 1 0 1 1 0 0 +EDGE2 3328 3327 -0.956353 -0.0800766 0.0128583 1 0 1 1 0 0 +EDGE2 3328 787 -0.976421 0.0233713 -0.0131454 1 0 1 1 0 0 +EDGE2 3329 790 0.993632 0.0287734 -0.0402879 1 0 1 1 0 0 +EDGE2 3329 810 0.966427 0.0574136 0.0119617 1 0 1 1 0 0 +EDGE2 3329 750 1.01551 -0.0233503 0.0151094 1 0 1 1 0 0 +EDGE2 3329 770 1.00778 -0.0796309 -0.0014557 1 0 1 1 0 0 +EDGE2 3329 748 -0.990992 -0.101553 -0.00122063 1 0 1 1 0 0 +EDGE2 3329 788 -1.02095 -0.0269771 -0.038692 1 0 1 1 0 0 +EDGE2 3329 769 -0.00948069 0.00132906 0.0135517 1 0 1 1 0 0 +EDGE2 3329 809 0.111309 -0.00617019 -0.0144485 1 0 1 1 0 0 +EDGE2 3329 789 -0.0392782 0.0581464 -0.0112109 1 0 1 1 0 0 +EDGE2 3329 3328 -0.992226 -0.00307445 0.000796666 1 0 1 1 0 0 +EDGE2 3329 749 -0.0669964 0.0581953 -0.0152839 1 0 1 1 0 0 +EDGE2 3329 808 -1.05072 -0.0334146 0.00338081 1 0 1 1 0 0 +EDGE2 3329 768 -1.0901 -0.0142366 0.00675865 1 0 1 1 0 0 +EDGE2 3330 790 -0.0280944 -0.0694492 0.0187696 1 0 1 1 0 0 +EDGE2 3330 810 0.0859103 0.0242436 -0.0343517 1 0 1 1 0 0 +EDGE2 3330 811 0.0721496 1.05091 1.60789 1 0 1 1 0 0 +EDGE2 3330 750 0.0510436 -0.0224006 -0.0101293 1 0 1 1 0 0 +EDGE2 3330 770 0.022266 -0.00192459 -0.0216566 1 0 1 1 0 0 +EDGE2 3330 751 0.0358097 1.05706 1.57213 1 0 1 1 0 0 +EDGE2 3330 771 0.0329489 0.95727 1.55787 1 0 1 1 0 0 +EDGE2 3330 791 0.00496228 1.09287 1.61188 1 0 1 1 0 0 +EDGE2 3330 769 -1.00614 0.0463384 0.0207074 1 0 1 1 0 0 +EDGE2 3330 809 -1.07899 -0.00977461 -0.016395 1 0 1 1 0 0 +EDGE2 3330 3329 -0.895135 0.06163 -0.00867381 1 0 1 1 0 0 +EDGE2 3330 789 -1.07156 0.000618088 -0.0177791 1 0 1 1 0 0 +EDGE2 3330 749 -0.981818 0.0130474 0.0233961 1 0 1 1 0 0 +EDGE2 3331 790 -0.987877 -0.0486674 -1.54471 1 0 1 1 0 0 +EDGE2 3331 3330 -0.910158 0.00496734 -1.53647 1 0 1 1 0 0 +EDGE2 3331 810 -1.09265 0.0422082 -1.5597 1 0 1 1 0 0 +EDGE2 3331 811 -0.05277 0.0285081 0.0162341 1 0 1 1 0 0 +EDGE2 3331 750 -0.888759 -0.116302 -1.57405 1 0 1 1 0 0 +EDGE2 3331 770 -0.9906 -0.0513468 -1.58305 1 0 1 1 0 0 +EDGE2 3331 751 -0.038105 0.0121942 0.00290387 1 0 1 1 0 0 +EDGE2 3331 771 0.0563511 0.000471904 -0.0107792 1 0 1 1 0 0 +EDGE2 3331 791 -0.0307391 0.0340075 -0.0269885 1 0 1 1 0 0 +EDGE2 3331 772 0.954869 0.0254537 -0.0108245 1 0 1 1 0 0 +EDGE2 3331 792 0.990176 -0.028821 -0.0137442 1 0 1 1 0 0 +EDGE2 3331 812 0.922347 -0.0220906 -0.0250549 1 0 1 1 0 0 +EDGE2 3331 752 1.0733 0.0020042 -0.0043442 1 0 1 1 0 0 +EDGE2 3332 753 0.987845 -0.067223 -0.0379827 1 0 1 1 0 0 +EDGE2 3332 811 -0.995603 0.00892223 0.0062568 1 0 1 1 0 0 +EDGE2 3332 3331 -1.06042 -0.0132299 0.00114594 1 0 1 1 0 0 +EDGE2 3332 751 -0.97124 0.0376777 0.0124064 1 0 1 1 0 0 +EDGE2 3332 771 -0.963856 0.0250105 -0.00309214 1 0 1 1 0 0 +EDGE2 3332 791 -0.968991 -0.00811737 -0.00217982 1 0 1 1 0 0 +EDGE2 3332 772 -0.025213 0.0711555 -0.00348895 1 0 1 1 0 0 +EDGE2 3332 792 0.00772191 -0.0280074 0.00588346 1 0 1 1 0 0 +EDGE2 3332 812 0.0451022 0.0220507 0.017416 1 0 1 1 0 0 +EDGE2 3332 752 0.0156661 -0.0552535 -0.0137213 1 0 1 1 0 0 +EDGE2 3332 793 1.00106 -0.00099074 -0.00240844 1 0 1 1 0 0 +EDGE2 3332 813 1.03289 0.00873408 -0.0204233 1 0 1 1 0 0 +EDGE2 3332 773 0.980176 0.0560921 -0.025625 1 0 1 1 0 0 +EDGE2 3333 753 -0.036531 0.109218 -0.00544307 1 0 1 1 0 0 +EDGE2 3333 3332 -1.04285 -0.018897 0.0381201 1 0 1 1 0 0 +EDGE2 3333 772 -1.03182 -0.0372187 0.0525261 1 0 1 1 0 0 +EDGE2 3333 792 -1.04887 -0.046912 -0.0344434 1 0 1 1 0 0 +EDGE2 3333 812 -0.98178 -0.0826944 -0.00335813 1 0 1 1 0 0 +EDGE2 3333 752 -0.913633 0.0474934 0.00103985 1 0 1 1 0 0 +EDGE2 3333 793 0.0436266 0.0083826 0.0354073 1 0 1 1 0 0 +EDGE2 3333 813 -0.114526 0.0132848 -0.00954806 1 0 1 1 0 0 +EDGE2 3333 773 0.0636097 0.0359898 -0.0129855 1 0 1 1 0 0 +EDGE2 3333 774 0.940632 -0.023627 -0.000450538 1 0 1 1 0 0 +EDGE2 3333 814 1.06255 0.0153428 -0.0135515 1 0 1 1 0 0 +EDGE2 3333 794 1.02835 -0.0098575 -0.0277179 1 0 1 1 0 0 +EDGE2 3333 754 1.0693 -0.0523431 -0.0170512 1 0 1 1 0 0 +EDGE2 3334 753 -0.943444 -0.0722408 -0.0121056 1 0 1 1 0 0 +EDGE2 3334 793 -0.992201 0.0128291 -0.00435708 1 0 1 1 0 0 +EDGE2 3334 813 -0.984442 -0.0784194 -0.00384382 1 0 1 1 0 0 +EDGE2 3334 3333 -0.943439 -0.0271369 -0.0601968 1 0 1 1 0 0 +EDGE2 3334 773 -0.999683 0.00712019 -0.00925691 1 0 1 1 0 0 +EDGE2 3334 774 -0.0663933 -0.0329753 -0.0106969 1 0 1 1 0 0 +EDGE2 3334 814 0.0137727 -0.0658847 0.0261083 1 0 1 1 0 0 +EDGE2 3334 794 -0.0550629 0.0787032 -0.0275363 1 0 1 1 0 0 +EDGE2 3334 754 0.0115235 0.0628009 0.0396417 1 0 1 1 0 0 +EDGE2 3334 795 0.978885 0.0102963 -0.00560648 1 0 1 1 0 0 +EDGE2 3334 875 0.909154 -0.00668023 -3.17292 1 0 1 1 0 0 +EDGE2 3334 815 1.01411 0.0107104 -0.00793784 1 0 1 1 0 0 +EDGE2 3334 755 1.08043 -0.00186261 0.0239289 1 0 1 1 0 0 +EDGE2 3334 775 0.989773 -0.0874935 -0.0172857 1 0 1 1 0 0 +EDGE2 3334 695 0.952738 0.0219468 -3.17033 1 0 1 1 0 0 +EDGE2 3335 876 -0.0168299 -1.01992 -1.58336 1 0 1 1 0 0 +EDGE2 3335 774 -0.987671 -0.0255887 0.0106371 1 0 1 1 0 0 +EDGE2 3335 814 -1.00018 0.122949 0.0235622 1 0 1 1 0 0 +EDGE2 3335 3334 -0.996864 0.00270773 0.00907132 1 0 1 1 0 0 +EDGE2 3335 794 -1.03302 0.0736955 -0.00982254 1 0 1 1 0 0 +EDGE2 3335 754 -1.10019 -0.0196726 0.000915045 1 0 1 1 0 0 +EDGE2 3335 795 0.0123425 0.0133834 0.0184039 1 0 1 1 0 0 +EDGE2 3335 875 0.103674 -0.00275669 -3.1591 1 0 1 1 0 0 +EDGE2 3335 815 0.018219 -0.104563 -0.0147727 1 0 1 1 0 0 +EDGE2 3335 755 0.0371662 -0.0190514 0.00419087 1 0 1 1 0 0 +EDGE2 3335 775 0.106297 0.000795789 0.0197709 1 0 1 1 0 0 +EDGE2 3335 695 0.00135488 0.0111958 -3.14575 1 0 1 1 0 0 +EDGE2 3335 874 1.01966 0.101437 -3.15735 1 0 1 1 0 0 +EDGE2 3335 694 0.990552 -0.00191111 -3.14528 1 0 1 1 0 0 +EDGE2 3335 796 -0.0440198 0.949004 1.5836 1 0 1 1 0 0 +EDGE2 3335 816 -0.0709775 0.930615 1.55149 1 0 1 1 0 0 +EDGE2 3335 696 0.0664216 0.950794 1.56218 1 0 1 1 0 0 +EDGE2 3335 756 -0.0143222 0.956151 1.59753 1 0 1 1 0 0 +EDGE2 3335 776 0.00588411 1.01145 1.58829 1 0 1 1 0 0 +EDGE2 3336 795 -1.07019 -0.131682 -1.54183 1 0 1 1 0 0 +EDGE2 3336 875 -1.0166 0.0104463 1.57622 1 0 1 1 0 0 +EDGE2 3336 3335 -1.02306 0.0568989 -1.56581 1 0 1 1 0 0 +EDGE2 3336 815 -1.0042 -0.0366827 -1.58296 1 0 1 1 0 0 +EDGE2 3336 755 -1.05623 -0.0292194 -1.55749 1 0 1 1 0 0 +EDGE2 3336 775 -1.12087 0.0119665 -1.56308 1 0 1 1 0 0 +EDGE2 3336 695 -0.989413 -0.00611311 1.53497 1 0 1 1 0 0 +EDGE2 3336 796 -0.00508361 -0.0203408 -0.00579576 1 0 1 1 0 0 +EDGE2 3336 816 -0.0297106 0.00646502 0.0288231 1 0 1 1 0 0 +EDGE2 3336 696 -0.042618 0.0297057 -0.0206744 1 0 1 1 0 0 +EDGE2 3336 756 -0.0697439 0.00677789 0.0495642 1 0 1 1 0 0 +EDGE2 3336 776 -0.0102146 -0.069108 -0.012118 1 0 1 1 0 0 +EDGE2 3336 697 1.00905 -0.0637843 0.0023977 1 0 1 1 0 0 +EDGE2 3336 777 0.925409 0.0241757 -0.00518168 1 0 1 1 0 0 +EDGE2 3336 797 1.0997 0.00550169 0.0086601 1 0 1 1 0 0 +EDGE2 3336 817 0.957716 0.0842977 0.00273967 1 0 1 1 0 0 +EDGE2 3336 757 0.969767 -0.0441157 0.00551132 1 0 1 1 0 0 +EDGE2 3337 796 -1.03211 -0.0102906 0.0163908 1 0 1 1 0 0 +EDGE2 3337 3336 -1.06585 0.0642705 -0.00914484 1 0 1 1 0 0 +EDGE2 3337 816 -1.00613 0.0743414 0.0335251 1 0 1 1 0 0 +EDGE2 3337 696 -0.901156 0.000874524 -0.0053281 1 0 1 1 0 0 +EDGE2 3337 756 -0.987749 -0.0108268 -0.00816527 1 0 1 1 0 0 +EDGE2 3337 776 -0.955924 0.0466358 -0.00432802 1 0 1 1 0 0 +EDGE2 3337 778 0.991025 -0.0400657 0.012 1 0 1 1 0 0 +EDGE2 3337 798 0.985925 -0.00720985 0.0193332 1 0 1 1 0 0 +EDGE2 3337 697 -0.0252343 0.00180364 -0.00269331 1 0 1 1 0 0 +EDGE2 3337 777 0.0935667 0.0126151 0.0274155 1 0 1 1 0 0 +EDGE2 3337 797 0.12123 0.0506619 0.00605273 1 0 1 1 0 0 +EDGE2 3337 817 0.147819 0.0201502 0.00431349 1 0 1 1 0 0 +EDGE2 3337 757 -0.0138525 0.00704927 -0.0475621 1 0 1 1 0 0 +EDGE2 3337 818 0.9513 0.035867 0.00861165 1 0 1 1 0 0 +EDGE2 3337 698 1.05549 0.0531642 -0.0479419 1 0 1 1 0 0 +EDGE2 3337 758 1.08508 -0.0498131 -0.0199156 1 0 1 1 0 0 +EDGE2 3338 3337 -0.998674 0.00233721 -0.0197189 1 0 1 1 0 0 +EDGE2 3338 778 -0.0200085 -0.00416056 0.0257184 1 0 1 1 0 0 +EDGE2 3338 798 -0.0393323 -0.0601518 -0.00374112 1 0 1 1 0 0 +EDGE2 3338 697 -0.920958 0.0467864 -0.0146515 1 0 1 1 0 0 +EDGE2 3338 777 -0.966849 0.100529 0.0131738 1 0 1 1 0 0 +EDGE2 3338 797 -0.994763 0.0388931 0.0145804 1 0 1 1 0 0 +EDGE2 3338 817 -1.01875 0.00365196 0.00465483 1 0 1 1 0 0 +EDGE2 3338 757 -0.968781 0.0494602 -0.0444067 1 0 1 1 0 0 +EDGE2 3338 818 0.0233776 0.0108713 0.015959 1 0 1 1 0 0 +EDGE2 3338 699 1.05007 0.0181123 -0.0159056 1 0 1 1 0 0 +EDGE2 3338 698 0.0429757 -0.0938536 0.0254852 1 0 1 1 0 0 +EDGE2 3338 758 -0.0115976 -0.00755166 -0.000750083 1 0 1 1 0 0 +EDGE2 3338 779 0.924176 0.030666 0.0371044 1 0 1 1 0 0 +EDGE2 3338 799 1.03123 -0.0745627 0.0130984 1 0 1 1 0 0 +EDGE2 3338 819 1.01974 0.00472621 -0.01406 1 0 1 1 0 0 +EDGE2 3338 759 0.907851 -0.0310498 0.0326088 1 0 1 1 0 0 +EDGE2 3339 800 0.98278 -0.0693133 -0.0108119 1 0 1 1 0 0 +EDGE2 3339 778 -1.03872 -0.0509944 -0.00300103 1 0 1 1 0 0 +EDGE2 3339 798 -0.908745 0.0626163 -0.0247019 1 0 1 1 0 0 +EDGE2 3339 3338 -0.983002 0.0364827 -0.0146113 1 0 1 1 0 0 +EDGE2 3339 818 -0.95577 -0.0730231 0.00514346 1 0 1 1 0 0 +EDGE2 3339 699 -0.0691968 0.0703333 -0.0144631 1 0 1 1 0 0 +EDGE2 3339 698 -1.02014 -0.0757981 0.00393472 1 0 1 1 0 0 +EDGE2 3339 758 -1.00099 -0.0800791 -0.0141715 1 0 1 1 0 0 +EDGE2 3339 779 0.0805417 0.0448286 0.0131614 1 0 1 1 0 0 +EDGE2 3339 799 -0.0860676 0.00245996 0.00409027 1 0 1 1 0 0 +EDGE2 3339 819 -0.0045142 -0.0254835 0.000311993 1 0 1 1 0 0 +EDGE2 3339 759 -0.0627557 -0.0487355 0.0031603 1 0 1 1 0 0 +EDGE2 3339 3200 1.00839 0.115568 -3.14978 1 0 1 1 0 0 +EDGE2 3339 3220 0.973735 -0.0614589 -3.15507 1 0 1 1 0 0 +EDGE2 3339 820 1.00074 -0.0562707 -0.023086 1 0 1 1 0 0 +EDGE2 3339 740 1.0416 0.0521594 -3.13158 1 0 1 1 0 0 +EDGE2 3339 760 0.928541 0.00902031 -0.0177512 1 0 1 1 0 0 +EDGE2 3339 780 0.989172 0.0672963 0.00113199 1 0 1 1 0 0 +EDGE2 3339 700 0.994908 0.0495093 0.000244695 1 0 1 1 0 0 +EDGE2 3340 801 -0.0342889 0.997439 1.58507 1 0 1 1 0 0 +EDGE2 3340 761 -0.0135826 1.08198 1.61384 1 0 1 1 0 0 +EDGE2 3340 781 -0.0269235 0.937261 1.52567 1 0 1 1 0 0 +EDGE2 3340 741 -0.0848134 1.01394 1.5755 1 0 1 1 0 0 +EDGE2 3340 800 0.0267464 0.00734836 0.0175876 1 0 1 1 0 0 +EDGE2 3340 699 -1.08335 -0.0580738 -0.0122614 1 0 1 1 0 0 +EDGE2 3340 3339 -0.98895 -0.0475629 0.00313988 1 0 1 1 0 0 +EDGE2 3340 779 -1.03691 -0.0300762 -0.0021079 1 0 1 1 0 0 +EDGE2 3340 799 -1.01132 0.106055 -0.0107188 1 0 1 1 0 0 +EDGE2 3340 819 -0.970152 0.0650958 -0.00406257 1 0 1 1 0 0 +EDGE2 3340 759 -0.962833 0.0189923 -0.00632375 1 0 1 1 0 0 +EDGE2 3340 3200 0.124544 0.0302566 -3.12249 1 0 1 1 0 0 +EDGE2 3340 3220 -0.0621637 -0.0507523 -3.11598 1 0 1 1 0 0 +EDGE2 3340 820 -0.0488998 -0.0502274 0.0116128 1 0 1 1 0 0 +EDGE2 3340 701 -0.159287 -0.994259 -1.56559 1 0 1 1 0 0 +EDGE2 3340 740 -0.0421548 -0.0304874 -3.14819 1 0 1 1 0 0 +EDGE2 3340 760 0.031874 0.0450759 0.0219114 1 0 1 1 0 0 +EDGE2 3340 780 -0.037334 -0.0301552 -0.0112329 1 0 1 1 0 0 +EDGE2 3340 700 -0.0589309 -0.0622638 0.0248036 1 0 1 1 0 0 +EDGE2 3340 3201 -0.047765 -1.0699 -1.57065 1 0 1 1 0 0 +EDGE2 3340 3221 0.0110738 -1.00008 -1.55585 1 0 1 1 0 0 +EDGE2 3340 821 -0.0951058 -1.00561 -1.54085 1 0 1 1 0 0 +EDGE2 3340 3199 1.05711 -0.080978 -3.14558 1 0 1 1 0 0 +EDGE2 3340 3219 0.94125 0.0117983 -3.14288 1 0 1 1 0 0 +EDGE2 3340 739 1.0514 0.0783987 -3.15768 1 0 1 1 0 0 +EDGE2 3341 802 1.06814 0.031784 0.00542005 1 0 1 1 0 0 +EDGE2 3341 801 0.00551727 0.0830041 -0.00564206 1 0 1 1 0 0 +EDGE2 3341 742 1.0068 -0.0136032 0.0195973 1 0 1 1 0 0 +EDGE2 3341 762 0.992032 -0.128326 -0.000887883 1 0 1 1 0 0 +EDGE2 3341 782 0.918995 -0.0477762 0.0300882 1 0 1 1 0 0 +EDGE2 3341 761 -0.0227654 0.0471954 -0.0189349 1 0 1 1 0 0 +EDGE2 3341 781 -0.0686333 -0.00448529 -0.0191168 1 0 1 1 0 0 +EDGE2 3341 741 -0.0359945 -0.0250564 0.00527527 1 0 1 1 0 0 +EDGE2 3341 800 -0.960236 -0.10276 -1.55459 1 0 1 1 0 0 +EDGE2 3341 3340 -0.844107 -0.0358359 -1.60322 1 0 1 1 0 0 +EDGE2 3341 3200 -0.999253 0.0273276 1.53689 1 0 1 1 0 0 +EDGE2 3341 3220 -0.986017 0.0125496 1.57165 1 0 1 1 0 0 +EDGE2 3341 820 -1.04104 -0.0419619 -1.56011 1 0 1 1 0 0 +EDGE2 3341 740 -0.984445 0.0346438 1.6072 1 0 1 1 0 0 +EDGE2 3341 760 -0.959512 -0.0388703 -1.57805 1 0 1 1 0 0 +EDGE2 3341 780 -1.02337 0.0793795 -1.54336 1 0 1 1 0 0 +EDGE2 3341 700 -0.915097 0.0277915 -1.6058 1 0 1 1 0 0 +EDGE2 3342 783 1.03164 -0.0259286 0.0244081 1 0 1 1 0 0 +EDGE2 3342 803 0.993844 -0.0450795 -0.0222621 1 0 1 1 0 0 +EDGE2 3342 802 -0.00257755 -0.00128051 -0.00347512 1 0 1 1 0 0 +EDGE2 3342 743 1.02687 -0.124184 0.010971 1 0 1 1 0 0 +EDGE2 3342 763 1.02739 -0.0607336 -0.0225993 1 0 1 1 0 0 +EDGE2 3342 801 -1.00785 -0.0329682 0.00344826 1 0 1 1 0 0 +EDGE2 3342 742 0.030501 0.0716807 0.0233269 1 0 1 1 0 0 +EDGE2 3342 762 -0.0130623 -0.00118558 0.0167133 1 0 1 1 0 0 +EDGE2 3342 782 -0.0121682 -0.0815798 -0.0137772 1 0 1 1 0 0 +EDGE2 3342 3341 -1.04874 0.0807566 0.0156231 1 0 1 1 0 0 +EDGE2 3342 761 -1.05519 0.00137295 -0.013937 1 0 1 1 0 0 +EDGE2 3342 781 -1.04344 -0.002622 0.0110164 1 0 1 1 0 0 +EDGE2 3342 741 -1.01224 0.0266291 0.00636758 1 0 1 1 0 0 +EDGE2 3343 783 -0.0423149 -0.0779494 0.00788712 1 0 1 1 0 0 +EDGE2 3343 784 1.0454 -0.0276348 0.00835488 1 0 1 1 0 0 +EDGE2 3343 804 0.930244 0.0164028 -0.0107647 1 0 1 1 0 0 +EDGE2 3343 744 1.09191 -0.106491 0.00688439 1 0 1 1 0 0 +EDGE2 3343 764 0.976575 0.00277239 -0.00864591 1 0 1 1 0 0 +EDGE2 3343 803 -0.00827768 -0.0913957 0.0219153 1 0 1 1 0 0 +EDGE2 3343 802 -1.00549 0.0237327 0.00174893 1 0 1 1 0 0 +EDGE2 3343 3342 -0.968168 -0.0180291 0.0361338 1 0 1 1 0 0 +EDGE2 3343 743 -0.0385068 -0.0111303 0.0170802 1 0 1 1 0 0 +EDGE2 3343 763 -0.000947974 -0.106126 -0.0152177 1 0 1 1 0 0 +EDGE2 3343 742 -0.958273 0.0165597 -0.0335169 1 0 1 1 0 0 +EDGE2 3343 762 -0.974768 -0.0412533 -0.0377835 1 0 1 1 0 0 +EDGE2 3343 782 -1.03715 -0.00998336 0.0131594 1 0 1 1 0 0 +EDGE2 3344 783 -0.935463 0.0162057 0.00972171 1 0 1 1 0 0 +EDGE2 3344 785 1.00849 0.000921734 0.00278285 1 0 1 1 0 0 +EDGE2 3344 3325 0.951686 0.0191645 -3.15305 1 0 1 1 0 0 +EDGE2 3344 1245 0.964558 0.00165057 -3.15401 1 0 1 1 0 0 +EDGE2 3344 2285 0.893387 -0.0136811 -3.16613 1 0 1 1 0 0 +EDGE2 3344 2465 0.920469 -0.0532226 -3.14244 1 0 1 1 0 0 +EDGE2 3344 805 0.919208 -0.0200286 0.00316454 1 0 1 1 0 0 +EDGE2 3344 784 -0.0963715 0.0067512 0.0159421 1 0 1 1 0 0 +EDGE2 3344 745 0.9474 -0.0621493 -0.0223761 1 0 1 1 0 0 +EDGE2 3344 765 1.03493 0.00645458 -0.00150688 1 0 1 1 0 0 +EDGE2 3344 804 -0.0332953 -0.0843159 0.0052993 1 0 1 1 0 0 +EDGE2 3344 3343 -0.954867 0.0910106 0.0131692 1 0 1 1 0 0 +EDGE2 3344 744 0.00666115 0.00893391 0.00933684 1 0 1 1 0 0 +EDGE2 3344 764 -0.0471681 0.0487117 -0.0155088 1 0 1 1 0 0 +EDGE2 3344 803 -0.951432 0.0643724 -0.00010889 1 0 1 1 0 0 +EDGE2 3344 743 -1.04703 -0.0326826 -0.0361074 1 0 1 1 0 0 +EDGE2 3344 763 -1.04661 -0.0307149 0.0357033 1 0 1 1 0 0 +EDGE2 3345 3324 1.00779 0.047143 -3.13665 1 0 1 1 0 0 +EDGE2 3345 806 -0.0169779 1.02706 1.56118 1 0 1 1 0 0 +EDGE2 3345 3326 0.0210604 1.02134 1.56955 1 0 1 1 0 0 +EDGE2 3345 766 -0.0502556 0.959985 1.54362 1 0 1 1 0 0 +EDGE2 3345 786 0.00543093 1.03048 1.54173 1 0 1 1 0 0 +EDGE2 3345 746 -0.0289081 0.948159 1.57817 1 0 1 1 0 0 +EDGE2 3345 785 -0.0798347 0.0125066 0.0344836 1 0 1 1 0 0 +EDGE2 3345 3325 -0.0310355 -0.143343 -3.13104 1 0 1 1 0 0 +EDGE2 3345 1244 0.941955 -0.038338 -3.11661 1 0 1 1 0 0 +EDGE2 3345 2284 0.968324 -0.0123118 -3.15802 1 0 1 1 0 0 +EDGE2 3345 2464 1.02269 0.0614874 -3.14828 1 0 1 1 0 0 +EDGE2 3345 1245 -0.0536595 0.126491 -3.13973 1 0 1 1 0 0 +EDGE2 3345 2285 0.0143064 -0.0720198 -3.18053 1 0 1 1 0 0 +EDGE2 3345 2465 0.0292168 0.00908188 -3.15494 1 0 1 1 0 0 +EDGE2 3345 805 -0.0355393 0.0468191 -0.0208073 1 0 1 1 0 0 +EDGE2 3345 784 -1.11463 -0.0228948 -0.0185512 1 0 1 1 0 0 +EDGE2 3345 3344 -1.04056 0.0163191 0.0371676 1 0 1 1 0 0 +EDGE2 3345 745 0.0658925 0.0128068 -0.0101835 1 0 1 1 0 0 +EDGE2 3345 765 0.00509476 -0.0295539 -0.000538336 1 0 1 1 0 0 +EDGE2 3345 804 -1.03803 -0.008869 -0.00859731 1 0 1 1 0 0 +EDGE2 3345 744 -1.07548 -0.013626 0.0206295 1 0 1 1 0 0 +EDGE2 3345 764 -0.988179 0.0790712 0.018683 1 0 1 1 0 0 +EDGE2 3345 2286 0.0184134 -0.928115 -1.53791 1 0 1 1 0 0 +EDGE2 3345 2466 0.078242 -0.886955 -1.58157 1 0 1 1 0 0 +EDGE2 3345 1246 0.0143645 -0.968034 -1.55172 1 0 1 1 0 0 +EDGE2 3346 747 1.10773 -0.0134206 -0.0116533 1 0 1 1 0 0 +EDGE2 3346 767 0.98789 0.0102763 -0.0132361 1 0 1 1 0 0 +EDGE2 3346 807 0.989893 -0.0533932 -0.000203003 1 0 1 1 0 0 +EDGE2 3346 3327 0.944411 -0.0395561 -0.0221258 1 0 1 1 0 0 +EDGE2 3346 787 0.970754 0.00178745 -0.0309263 1 0 1 1 0 0 +EDGE2 3346 806 -0.026899 0.0545275 0.0238251 1 0 1 1 0 0 +EDGE2 3346 3326 0.00954311 -0.00156806 -0.0323552 1 0 1 1 0 0 +EDGE2 3346 766 -0.0533069 -0.074171 -0.0312294 1 0 1 1 0 0 +EDGE2 3346 786 0.030008 -0.032332 -0.045666 1 0 1 1 0 0 +EDGE2 3346 746 -0.0202476 0.00416253 0.0309511 1 0 1 1 0 0 +EDGE2 3346 785 -1.0478 -0.019708 -1.62307 1 0 1 1 0 0 +EDGE2 3346 3325 -1.00289 -0.0476629 1.60398 1 0 1 1 0 0 +EDGE2 3346 3345 -0.952044 -0.0443239 -1.58247 1 0 1 1 0 0 +EDGE2 3346 1245 -0.985282 0.00420843 1.56089 1 0 1 1 0 0 +EDGE2 3346 2285 -0.955219 0.0217303 1.57067 1 0 1 1 0 0 +EDGE2 3346 2465 -1.0221 -0.0440792 1.58444 1 0 1 1 0 0 +EDGE2 3346 805 -0.94879 0.0212162 -1.59181 1 0 1 1 0 0 +EDGE2 3346 745 -0.952242 0.0215728 -1.56427 1 0 1 1 0 0 +EDGE2 3346 765 -1.00529 0.0381982 -1.54479 1 0 1 1 0 0 +EDGE2 3347 748 0.980372 -0.0105575 0.0116905 1 0 1 1 0 0 +EDGE2 3347 788 1.03058 0.0635105 -0.0230371 1 0 1 1 0 0 +EDGE2 3347 3328 0.998348 0.0127663 -0.014054 1 0 1 1 0 0 +EDGE2 3347 808 0.924635 -0.0800433 -0.0110677 1 0 1 1 0 0 +EDGE2 3347 768 0.97866 0.107134 -0.00584656 1 0 1 1 0 0 +EDGE2 3347 747 0.00536612 -0.0471848 0.0162164 1 0 1 1 0 0 +EDGE2 3347 767 -0.000831978 -0.00829306 -0.00188106 1 0 1 1 0 0 +EDGE2 3347 807 -0.0216549 -0.0276648 -0.00154852 1 0 1 1 0 0 +EDGE2 3347 3327 0.0508552 -0.0598068 -0.0253555 1 0 1 1 0 0 +EDGE2 3347 787 0.124219 -0.0279397 -0.0401837 1 0 1 1 0 0 +EDGE2 3347 806 -0.930365 0.00692396 -0.0167039 1 0 1 1 0 0 +EDGE2 3347 3346 -0.985808 -0.0338989 -0.00611456 1 0 1 1 0 0 +EDGE2 3347 3326 -1.12143 0.0592523 0.00165667 1 0 1 1 0 0 +EDGE2 3347 766 -1.01132 -0.0758795 0.0289045 1 0 1 1 0 0 +EDGE2 3347 786 -1.03044 0.0260252 -0.0135139 1 0 1 1 0 0 +EDGE2 3347 746 -0.966643 -0.0012933 0.0410819 1 0 1 1 0 0 +EDGE2 3348 748 -0.0338746 0.00187689 -0.0221133 1 0 1 1 0 0 +EDGE2 3348 788 0.0313993 0.010719 0.0175947 1 0 1 1 0 0 +EDGE2 3348 769 1.00301 -0.0443933 0.011251 1 0 1 1 0 0 +EDGE2 3348 809 0.953883 -0.0870727 -0.0295279 1 0 1 1 0 0 +EDGE2 3348 3329 0.932314 0.0805513 -0.00269597 1 0 1 1 0 0 +EDGE2 3348 789 1.11119 -0.0088153 0.0126942 1 0 1 1 0 0 +EDGE2 3348 3328 0.0601028 0.0325122 -0.011277 1 0 1 1 0 0 +EDGE2 3348 749 0.939903 -0.0169925 0.0209795 1 0 1 1 0 0 +EDGE2 3348 808 -0.0533837 -0.0307103 0.0310222 1 0 1 1 0 0 +EDGE2 3348 768 -0.0116972 -0.0601913 -0.000609049 1 0 1 1 0 0 +EDGE2 3348 747 -0.9293 0.00247096 -0.0109831 1 0 1 1 0 0 +EDGE2 3348 767 -1.07991 0.0703059 -0.00570032 1 0 1 1 0 0 +EDGE2 3348 807 -0.930415 0.0578001 -0.0151117 1 0 1 1 0 0 +EDGE2 3348 3327 -1.0075 0.0236397 0.00278242 1 0 1 1 0 0 +EDGE2 3348 3347 -0.948602 -0.077547 -0.0114541 1 0 1 1 0 0 +EDGE2 3348 787 -1.0128 -0.053693 0.02207 1 0 1 1 0 0 +EDGE2 3349 790 0.929356 0.0182412 0.0221176 1 0 1 1 0 0 +EDGE2 3349 3330 1.00058 0.0149744 -0.0280273 1 0 1 1 0 0 +EDGE2 3349 810 0.960791 0.00238313 -0.0189918 1 0 1 1 0 0 +EDGE2 3349 750 0.968722 0.00331663 0.0183623 1 0 1 1 0 0 +EDGE2 3349 770 0.997413 -0.0199432 0.0162883 1 0 1 1 0 0 +EDGE2 3349 748 -0.964931 0.0620114 0.0141488 1 0 1 1 0 0 +EDGE2 3349 788 -1.03117 -0.00832319 0.0201857 1 0 1 1 0 0 +EDGE2 3349 769 -0.000229205 0.0551426 -0.0103876 1 0 1 1 0 0 +EDGE2 3349 809 -0.0925977 -0.0852179 -0.0107415 1 0 1 1 0 0 +EDGE2 3349 3329 -0.101538 0.0296421 -0.00626691 1 0 1 1 0 0 +EDGE2 3349 789 -0.0331712 -0.130868 0.00778201 1 0 1 1 0 0 +EDGE2 3349 3328 -1.01292 0.0444498 -0.0160086 1 0 1 1 0 0 +EDGE2 3349 3348 -1.08768 -0.0203913 -0.00194317 1 0 1 1 0 0 +EDGE2 3349 749 0.0441068 0.0374123 -0.0316248 1 0 1 1 0 0 +EDGE2 3349 808 -0.968788 -0.0893818 -0.00926758 1 0 1 1 0 0 +EDGE2 3349 768 -0.981722 0.122149 0.00829838 1 0 1 1 0 0 +EDGE2 3350 790 0.0478524 -0.0380134 -0.00174768 1 0 1 1 0 0 +EDGE2 3350 3330 0.0416527 -0.0607938 0.00702534 1 0 1 1 0 0 +EDGE2 3350 810 0.0338901 0.006669 0.0121303 1 0 1 1 0 0 +EDGE2 3350 811 0.0522008 1.0445 1.56343 1 0 1 1 0 0 +EDGE2 3350 750 0.0679467 -0.0343173 0.013529 1 0 1 1 0 0 +EDGE2 3350 770 0.0282163 -0.0118324 0.0353431 1 0 1 1 0 0 +EDGE2 3350 3331 -0.0425673 1.025 1.55594 1 0 1 1 0 0 +EDGE2 3350 751 0.126064 0.989326 1.56842 1 0 1 1 0 0 +EDGE2 3350 771 0.0401526 1.00214 1.62099 1 0 1 1 0 0 +EDGE2 3350 791 -0.0333365 0.987885 1.57734 1 0 1 1 0 0 +EDGE2 3350 769 -1.03247 0.119228 0.0161014 1 0 1 1 0 0 +EDGE2 3350 809 -1.02204 -0.0416845 0.016449 1 0 1 1 0 0 +EDGE2 3350 3329 -1.00112 0.0014262 -0.0240113 1 0 1 1 0 0 +EDGE2 3350 3349 -0.95063 0.0531159 0.00276555 1 0 1 1 0 0 +EDGE2 3350 789 -0.972462 0.121612 -0.0140127 1 0 1 1 0 0 +EDGE2 3350 749 -1.00521 -0.0929047 -0.00660835 1 0 1 1 0 0 +EDGE2 3351 790 -0.988295 0.0117866 -1.58151 1 0 1 1 0 0 +EDGE2 3351 3330 -1.01146 -0.062794 -1.5804 1 0 1 1 0 0 +EDGE2 3351 3350 -1.02611 0.0347676 -1.55147 1 0 1 1 0 0 +EDGE2 3351 810 -1.04132 -0.0223492 -1.56166 1 0 1 1 0 0 +EDGE2 3351 3332 0.999009 -0.034068 0.0377951 1 0 1 1 0 0 +EDGE2 3351 811 -0.0473822 -0.0121016 -0.000141234 1 0 1 1 0 0 +EDGE2 3351 750 -0.989125 -0.0448988 -1.53857 1 0 1 1 0 0 +EDGE2 3351 770 -1.02405 -0.0237873 -1.59343 1 0 1 1 0 0 +EDGE2 3351 3331 -0.0600547 -0.039864 0.0218077 1 0 1 1 0 0 +EDGE2 3351 751 -0.0503795 0.0337129 -0.0265262 1 0 1 1 0 0 +EDGE2 3351 771 -0.0389891 0.0777815 -0.00797846 1 0 1 1 0 0 +EDGE2 3351 791 0.056228 0.00931892 -0.0207972 1 0 1 1 0 0 +EDGE2 3351 772 1.0586 -0.0345262 0.00529607 1 0 1 1 0 0 +EDGE2 3351 792 1.07668 -0.0210693 -0.0225438 1 0 1 1 0 0 +EDGE2 3351 812 1.02624 -0.0630383 0.0111189 1 0 1 1 0 0 +EDGE2 3351 752 1.01803 0.0936534 -0.0215644 1 0 1 1 0 0 +EDGE2 3352 753 1.04299 -0.07927 -0.0160487 1 0 1 1 0 0 +EDGE2 3352 3332 0.0967 0.113544 -0.0108787 1 0 1 1 0 0 +EDGE2 3352 811 -1.0795 0.0761263 0.0493478 1 0 1 1 0 0 +EDGE2 3352 3351 -0.876645 -0.0172268 0.00374171 1 0 1 1 0 0 +EDGE2 3352 3331 -1.04038 -0.0630856 0.0261069 1 0 1 1 0 0 +EDGE2 3352 751 -1.04296 -0.078593 -0.0161488 1 0 1 1 0 0 +EDGE2 3352 771 -0.995603 0.0441661 0.00408844 1 0 1 1 0 0 +EDGE2 3352 791 -1.01448 0.0246599 0.0347198 1 0 1 1 0 0 +EDGE2 3352 772 -0.0652913 0.0075228 -0.0211609 1 0 1 1 0 0 +EDGE2 3352 792 -0.00325004 0.0691918 0.00913347 1 0 1 1 0 0 +EDGE2 3352 812 -0.121012 -0.021139 0.0254377 1 0 1 1 0 0 +EDGE2 3352 752 0.0584657 0.00374283 -0.0307406 1 0 1 1 0 0 +EDGE2 3352 793 0.964473 -0.0328548 -0.0215598 1 0 1 1 0 0 +EDGE2 3352 813 1.05268 0.00953081 0.0260881 1 0 1 1 0 0 +EDGE2 3352 3333 0.950097 -0.0614144 -0.0195332 1 0 1 1 0 0 +EDGE2 3352 773 1.09717 0.0202036 0.00862308 1 0 1 1 0 0 +EDGE2 3353 753 -0.0117015 -0.110043 -0.0254916 1 0 1 1 0 0 +EDGE2 3353 3332 -1.00642 -0.0260228 0.00682888 1 0 1 1 0 0 +EDGE2 3353 3352 -1.11171 -0.00921988 0.00641632 1 0 1 1 0 0 +EDGE2 3353 772 -0.913618 -0.0121636 -0.014307 1 0 1 1 0 0 +EDGE2 3353 792 -0.903329 -0.0506184 0.00942924 1 0 1 1 0 0 +EDGE2 3353 812 -0.993302 0.0615587 0.00759344 1 0 1 1 0 0 +EDGE2 3353 752 -0.985369 0.0251311 0.00297599 1 0 1 1 0 0 +EDGE2 3353 793 -0.0906693 -0.0171407 0.0507923 1 0 1 1 0 0 +EDGE2 3353 813 -0.0539349 0.0794497 0.0404733 1 0 1 1 0 0 +EDGE2 3353 3333 -0.0510347 0.0422168 -0.00504682 1 0 1 1 0 0 +EDGE2 3353 773 0.0644981 0.0324461 0.0184705 1 0 1 1 0 0 +EDGE2 3353 774 0.991463 -0.0356919 0.0138024 1 0 1 1 0 0 +EDGE2 3353 814 1.04766 0.029082 0.0184708 1 0 1 1 0 0 +EDGE2 3353 3334 0.997432 0.0522936 0.0110508 1 0 1 1 0 0 +EDGE2 3353 794 1.02635 0.0289047 -0.0452396 1 0 1 1 0 0 +EDGE2 3353 754 1.04428 0.0369816 -0.0350584 1 0 1 1 0 0 +EDGE2 3354 753 -1.06515 0.0136972 0.00209922 1 0 1 1 0 0 +EDGE2 3354 3353 -0.955373 0.0350459 0.00572868 1 0 1 1 0 0 +EDGE2 3354 793 -1.04403 0.00981964 0.0285978 1 0 1 1 0 0 +EDGE2 3354 813 -0.957815 0.010759 -0.0218287 1 0 1 1 0 0 +EDGE2 3354 3333 -1.01588 0.0118337 -0.0207908 1 0 1 1 0 0 +EDGE2 3354 773 -0.971571 -0.00578791 0.00586817 1 0 1 1 0 0 +EDGE2 3354 774 -0.037772 -0.0638147 0.0219745 1 0 1 1 0 0 +EDGE2 3354 814 0.078114 0.0501762 0.0194866 1 0 1 1 0 0 +EDGE2 3354 3334 -0.0670342 -0.0396481 0.0569492 1 0 1 1 0 0 +EDGE2 3354 794 0.0185861 0.00119884 -0.000266937 1 0 1 1 0 0 +EDGE2 3354 754 0.0977847 -0.0260605 0.0188619 1 0 1 1 0 0 +EDGE2 3354 795 1.0534 -0.0220975 -0.0201043 1 0 1 1 0 0 +EDGE2 3354 875 1.0399 0.0021398 -3.14487 1 0 1 1 0 0 +EDGE2 3354 3335 0.957168 -0.0968376 -0.00275952 1 0 1 1 0 0 +EDGE2 3354 815 1.02139 0.073446 0.00307498 1 0 1 1 0 0 +EDGE2 3354 755 0.986857 -0.0736172 -0.01142 1 0 1 1 0 0 +EDGE2 3354 775 1.02187 0.0253498 0.0127267 1 0 1 1 0 0 +EDGE2 3354 695 1.00629 -0.0320749 -3.12128 1 0 1 1 0 0 +EDGE2 3355 876 0.0447024 -0.944507 -1.57551 1 0 1 1 0 0 +EDGE2 3355 774 -1.00575 0.00863826 -0.0225095 1 0 1 1 0 0 +EDGE2 3355 814 -0.944394 -0.0621883 0.00304894 1 0 1 1 0 0 +EDGE2 3355 3334 -1.06461 -0.0723378 -0.00595102 1 0 1 1 0 0 +EDGE2 3355 3354 -0.987853 -0.0342699 -0.00759775 1 0 1 1 0 0 +EDGE2 3355 794 -1.04056 -0.0616419 -0.00282009 1 0 1 1 0 0 +EDGE2 3355 754 -1.07472 -0.0460152 0.0195959 1 0 1 1 0 0 +EDGE2 3355 795 -0.0781542 -0.0274631 -0.00367853 1 0 1 1 0 0 +EDGE2 3355 875 0.0873782 -0.0269811 -3.15936 1 0 1 1 0 0 +EDGE2 3355 3335 0.0437353 -0.0856271 -0.00171673 1 0 1 1 0 0 +EDGE2 3355 815 0.00138117 -0.0611032 -0.035715 1 0 1 1 0 0 +EDGE2 3355 755 -0.0282326 -0.0376241 -0.0347504 1 0 1 1 0 0 +EDGE2 3355 775 0.0240123 -0.0632771 -0.00567128 1 0 1 1 0 0 +EDGE2 3355 695 -0.0202378 0.0453339 -3.15516 1 0 1 1 0 0 +EDGE2 3355 874 0.940241 -0.0342052 -3.12758 1 0 1 1 0 0 +EDGE2 3355 694 1.04382 0.00478771 -3.13143 1 0 1 1 0 0 +EDGE2 3355 796 -0.021333 0.980314 1.59556 1 0 1 1 0 0 +EDGE2 3355 3336 -0.00970388 0.970626 1.59978 1 0 1 1 0 0 +EDGE2 3355 816 0.041777 1.03854 1.58017 1 0 1 1 0 0 +EDGE2 3355 696 -0.00232931 0.99387 1.57698 1 0 1 1 0 0 +EDGE2 3355 756 0.0104339 0.92198 1.57261 1 0 1 1 0 0 +EDGE2 3355 776 -0.00541632 0.921442 1.57893 1 0 1 1 0 0 +EDGE2 3356 795 -0.910267 -0.0726431 -1.5685 1 0 1 1 0 0 +EDGE2 3356 875 -0.915342 -0.0793117 1.57879 1 0 1 1 0 0 +EDGE2 3356 3335 -1.0238 -0.0148917 -1.59563 1 0 1 1 0 0 +EDGE2 3356 3355 -1.01103 0.0291926 -1.57861 1 0 1 1 0 0 +EDGE2 3356 815 -0.967818 -0.0146624 -1.542 1 0 1 1 0 0 +EDGE2 3356 755 -1.01888 -0.0292668 -1.57424 1 0 1 1 0 0 +EDGE2 3356 775 -1.03101 0.0687408 -1.57759 1 0 1 1 0 0 +EDGE2 3356 695 -1.02071 0.0141403 1.57861 1 0 1 1 0 0 +EDGE2 3356 3337 1.01239 0.0800062 0.000818484 1 0 1 1 0 0 +EDGE2 3356 796 0.0102588 -0.040092 -0.00188144 1 0 1 1 0 0 +EDGE2 3356 3336 0.0366208 -0.00553163 -0.012211 1 0 1 1 0 0 +EDGE2 3356 816 0.0161009 -0.0496026 0.0381077 1 0 1 1 0 0 +EDGE2 3356 696 -0.0594144 0.0257507 -0.0309095 1 0 1 1 0 0 +EDGE2 3356 756 0.0437869 -0.0239561 -0.0220293 1 0 1 1 0 0 +EDGE2 3356 776 -0.0265143 0.0636923 0.00334151 1 0 1 1 0 0 +EDGE2 3356 697 0.972831 -0.0565886 0.000384119 1 0 1 1 0 0 +EDGE2 3356 777 1.01195 -0.00440093 0.00783314 1 0 1 1 0 0 +EDGE2 3356 797 1.06561 0.0924738 0.000343326 1 0 1 1 0 0 +EDGE2 3356 817 1.02431 0.0262037 -0.011099 1 0 1 1 0 0 +EDGE2 3356 757 1.00596 -0.0451004 0.0294795 1 0 1 1 0 0 +EDGE2 3357 3337 0.0126302 -0.0180678 -0.0426278 1 0 1 1 0 0 +EDGE2 3357 796 -1.05151 0.0283881 0.0058123 1 0 1 1 0 0 +EDGE2 3357 3336 -0.957451 -0.0583231 -0.00201719 1 0 1 1 0 0 +EDGE2 3357 3356 -0.995704 0.100292 0.0111149 1 0 1 1 0 0 +EDGE2 3357 816 -1.02403 0.0110534 -0.0227472 1 0 1 1 0 0 +EDGE2 3357 696 -1.12869 0.0474052 -0.0108693 1 0 1 1 0 0 +EDGE2 3357 756 -0.900675 -0.0149521 0.0242574 1 0 1 1 0 0 +EDGE2 3357 776 -0.985859 0.027169 0.0023821 1 0 1 1 0 0 +EDGE2 3357 778 1.01601 -0.0425174 -0.0322795 1 0 1 1 0 0 +EDGE2 3357 798 0.981946 -0.024189 0.0105074 1 0 1 1 0 0 +EDGE2 3357 697 0.060113 0.0755261 0.0202926 1 0 1 1 0 0 +EDGE2 3357 777 -0.0274954 -0.00994649 0.00388907 1 0 1 1 0 0 +EDGE2 3357 797 -0.00464876 0.00431522 0.00369543 1 0 1 1 0 0 +EDGE2 3357 817 0.0346749 0.0332528 0.00935079 1 0 1 1 0 0 +EDGE2 3357 757 -0.027885 -0.0121899 -0.00146384 1 0 1 1 0 0 +EDGE2 3357 3338 1.08382 0.00369551 0.0436717 1 0 1 1 0 0 +EDGE2 3357 818 1.0045 0.0647005 0.00889752 1 0 1 1 0 0 +EDGE2 3357 698 0.988533 0.0451149 -0.0465436 1 0 1 1 0 0 +EDGE2 3357 758 1.00909 -0.0238896 0.0145363 1 0 1 1 0 0 +EDGE2 3358 3337 -0.981272 -0.0597545 0.0206612 1 0 1 1 0 0 +EDGE2 3358 3357 -0.88696 -0.0134827 0.0139315 1 0 1 1 0 0 +EDGE2 3358 778 -0.00378633 -0.0551901 0.0128396 1 0 1 1 0 0 +EDGE2 3358 798 -0.0138246 -0.0371412 -0.00859159 1 0 1 1 0 0 +EDGE2 3358 697 -1.02072 0.0262836 -0.0304061 1 0 1 1 0 0 +EDGE2 3358 777 -1.02311 0.0489818 0.0101417 1 0 1 1 0 0 +EDGE2 3358 797 -0.987858 0.0267571 -0.0155733 1 0 1 1 0 0 +EDGE2 3358 817 -1.00032 -0.0303744 -0.0348308 1 0 1 1 0 0 +EDGE2 3358 757 -1.0133 0.0901291 -0.0215574 1 0 1 1 0 0 +EDGE2 3358 3338 0.0115456 0.0548326 -0.0205726 1 0 1 1 0 0 +EDGE2 3358 818 -0.107212 -0.0307713 0.0208492 1 0 1 1 0 0 +EDGE2 3358 699 1.04024 0.0469549 0.0328737 1 0 1 1 0 0 +EDGE2 3358 3339 1.08261 -0.0132452 -0.0248631 1 0 1 1 0 0 +EDGE2 3358 698 -0.117659 -0.00147904 -0.00995082 1 0 1 1 0 0 +EDGE2 3358 758 0.0171298 0.00814122 0.00182421 1 0 1 1 0 0 +EDGE2 3358 779 0.957922 -0.0447733 0.000670153 1 0 1 1 0 0 +EDGE2 3358 799 0.918893 -0.0330673 0.00944284 1 0 1 1 0 0 +EDGE2 3358 819 1.0275 -0.00229384 -0.0104449 1 0 1 1 0 0 +EDGE2 3358 759 0.986789 0.0906446 0.000221392 1 0 1 1 0 0 +EDGE2 3359 800 0.988968 -0.0433622 0.00297982 1 0 1 1 0 0 +EDGE2 3359 778 -1.00885 -0.101822 0.00728689 1 0 1 1 0 0 +EDGE2 3359 798 -0.943544 0.0789533 -0.00277148 1 0 1 1 0 0 +EDGE2 3359 3338 -1.00105 -0.00478797 -0.00834711 1 0 1 1 0 0 +EDGE2 3359 3358 -0.983496 0.113489 -0.0122633 1 0 1 1 0 0 +EDGE2 3359 818 -1.02288 -0.103568 0.0214426 1 0 1 1 0 0 +EDGE2 3359 699 0.0209052 0.0137726 -0.0295391 1 0 1 1 0 0 +EDGE2 3359 3339 0.0104043 -0.0418285 -0.0004037 1 0 1 1 0 0 +EDGE2 3359 698 -0.980877 -0.0194195 0.00879327 1 0 1 1 0 0 +EDGE2 3359 758 -1.11607 -0.0033227 0.0283311 1 0 1 1 0 0 +EDGE2 3359 779 -0.0364827 -0.0377796 -0.0170716 1 0 1 1 0 0 +EDGE2 3359 799 -0.0629887 -0.0210865 0.0160008 1 0 1 1 0 0 +EDGE2 3359 819 -0.0121878 0.076806 0.00839818 1 0 1 1 0 0 +EDGE2 3359 759 -0.0154548 0.0100827 0.0161644 1 0 1 1 0 0 +EDGE2 3359 3340 1.00655 -0.0010252 0.0136608 1 0 1 1 0 0 +EDGE2 3359 3200 1.01218 -0.0136469 -3.17462 1 0 1 1 0 0 +EDGE2 3359 3220 0.956126 -0.0103564 -3.09312 1 0 1 1 0 0 +EDGE2 3359 820 0.899371 -0.0547699 0.0134585 1 0 1 1 0 0 +EDGE2 3359 740 0.95141 0.0930141 -3.1596 1 0 1 1 0 0 +EDGE2 3359 760 1.08407 -0.000632643 -0.025985 1 0 1 1 0 0 +EDGE2 3359 780 1.01469 -0.00155715 0.0109557 1 0 1 1 0 0 +EDGE2 3359 700 0.870313 0.00694686 0.00382428 1 0 1 1 0 0 +EDGE2 3360 801 0.0510182 1.07375 1.52925 1 0 1 1 0 0 +EDGE2 3360 3341 0.0100136 0.978853 1.56005 1 0 1 1 0 0 +EDGE2 3360 761 0.0101816 0.935246 1.57823 1 0 1 1 0 0 +EDGE2 3360 781 0.0456186 0.996379 1.54315 1 0 1 1 0 0 +EDGE2 3360 741 -0.00425155 1.07156 1.55859 1 0 1 1 0 0 +EDGE2 3360 800 0.0257738 0.0335634 -0.0105376 1 0 1 1 0 0 +EDGE2 3360 699 -1.01125 -0.00170043 -0.010965 1 0 1 1 0 0 +EDGE2 3360 3339 -0.984374 -0.0112937 -0.0252397 1 0 1 1 0 0 +EDGE2 3360 3359 -1.14808 -0.132407 -0.0222885 1 0 1 1 0 0 +EDGE2 3360 779 -1.05436 0.061806 -0.00765814 1 0 1 1 0 0 +EDGE2 3360 799 -1.03418 0.0854774 0.0148684 1 0 1 1 0 0 +EDGE2 3360 819 -0.912405 0.0792686 -0.0230403 1 0 1 1 0 0 +EDGE2 3360 759 -0.984831 -0.0205315 7.74976e-05 1 0 1 1 0 0 +EDGE2 3360 3340 0.000296339 -0.0528872 0.0203458 1 0 1 1 0 0 +EDGE2 3360 3200 0.0135595 0.0679572 -3.14217 1 0 1 1 0 0 +EDGE2 3360 3220 0.0183163 0.0807764 -3.14096 1 0 1 1 0 0 +EDGE2 3360 820 0.049883 -0.0437986 -0.0201257 1 0 1 1 0 0 +EDGE2 3360 701 0.0111657 -1.06352 -1.58346 1 0 1 1 0 0 +EDGE2 3360 740 -0.0378859 0.0159156 -3.12104 1 0 1 1 0 0 +EDGE2 3360 760 -0.00102797 -0.0316262 0.0122975 1 0 1 1 0 0 +EDGE2 3360 780 -0.0665539 -0.0229686 0.00151503 1 0 1 1 0 0 +EDGE2 3360 700 -0.0357886 0.0428095 0.00137059 1 0 1 1 0 0 +EDGE2 3360 3201 0.11165 -0.96004 -1.54292 1 0 1 1 0 0 +EDGE2 3360 3221 -0.0375603 -0.966904 -1.57644 1 0 1 1 0 0 +EDGE2 3360 821 -0.0342056 -0.865597 -1.54874 1 0 1 1 0 0 +EDGE2 3360 3199 0.995965 -0.0756211 -3.16544 1 0 1 1 0 0 +EDGE2 3360 3219 0.950303 0.0576277 -3.14497 1 0 1 1 0 0 +EDGE2 3360 739 0.96782 -0.0197651 -3.16287 1 0 1 1 0 0 +EDGE2 3361 800 -0.949845 -0.00816181 1.58489 1 0 1 1 0 0 +EDGE2 3361 3340 -1.00838 0.030713 1.57424 1 0 1 1 0 0 +EDGE2 3361 3360 -0.982209 -0.0304795 1.56633 1 0 1 1 0 0 +EDGE2 3361 3200 -0.91629 -0.0227908 -1.56639 1 0 1 1 0 0 +EDGE2 3361 3220 -0.993662 -0.0117623 -1.60319 1 0 1 1 0 0 +EDGE2 3361 820 -1.01007 0.0243937 1.56162 1 0 1 1 0 0 +EDGE2 3361 701 0.00156338 -0.0154154 -0.00120646 1 0 1 1 0 0 +EDGE2 3361 740 -0.930832 0.0611683 -1.55982 1 0 1 1 0 0 +EDGE2 3361 760 -0.998642 -0.0296839 1.57368 1 0 1 1 0 0 +EDGE2 3361 780 -1.02567 0.0367338 1.60555 1 0 1 1 0 0 +EDGE2 3361 700 -0.980654 -0.0569715 1.57684 1 0 1 1 0 0 +EDGE2 3361 3201 0.025216 -0.0513693 -0.0169731 1 0 1 1 0 0 +EDGE2 3361 3221 -0.0311128 -0.0182121 0.0255097 1 0 1 1 0 0 +EDGE2 3361 821 -0.0565008 -0.0132814 0.0243093 1 0 1 1 0 0 +EDGE2 3361 822 1.07537 0.015168 -0.0044416 1 0 1 1 0 0 +EDGE2 3361 3222 0.993878 0.100831 0.00365148 1 0 1 1 0 0 +EDGE2 3361 3202 1.02244 -0.0694954 0.00360218 1 0 1 1 0 0 +EDGE2 3361 702 1.04842 0.0378021 0.0156792 1 0 1 1 0 0 +EDGE2 3362 3203 0.984608 0.00327399 0.0412862 1 0 1 1 0 0 +EDGE2 3362 701 -1.05147 -0.08729 0.00987891 1 0 1 1 0 0 +EDGE2 3362 3201 -1.07006 0.00265217 -0.0186621 1 0 1 1 0 0 +EDGE2 3362 3221 -1.01674 -0.104761 0.0272148 1 0 1 1 0 0 +EDGE2 3362 3361 -0.953626 0.0465192 0.0152634 1 0 1 1 0 0 +EDGE2 3362 821 -0.989284 0.0962998 0.0199375 1 0 1 1 0 0 +EDGE2 3362 822 0.0579083 0.0179726 -0.00652658 1 0 1 1 0 0 +EDGE2 3362 3222 -0.0353707 0.00896734 0.00633513 1 0 1 1 0 0 +EDGE2 3362 3202 -0.0525096 -0.0187235 0.0101039 1 0 1 1 0 0 +EDGE2 3362 702 0.0481239 0.0266157 -0.00542572 1 0 1 1 0 0 +EDGE2 3362 3223 1.06969 -0.00679386 0.0103949 1 0 1 1 0 0 +EDGE2 3362 703 1.0725 0.0290236 0.00104835 1 0 1 1 0 0 +EDGE2 3362 823 0.950829 0.0287794 0.00366427 1 0 1 1 0 0 +EDGE2 3363 3203 0.050524 0.090441 0.0212942 1 0 1 1 0 0 +EDGE2 3363 822 -1.06321 0.0993273 0.017156 1 0 1 1 0 0 +EDGE2 3363 3222 -0.903513 0.0118304 0.0129047 1 0 1 1 0 0 +EDGE2 3363 3362 -0.982339 -0.0530579 0.00350208 1 0 1 1 0 0 +EDGE2 3363 3202 -1.0394 0.00346325 -0.00540254 1 0 1 1 0 0 +EDGE2 3363 702 -1.01476 0.0875396 -0.0407986 1 0 1 1 0 0 +EDGE2 3363 3223 0.0707133 -0.0523943 0.0125234 1 0 1 1 0 0 +EDGE2 3363 703 -0.0495478 0.0202989 0.00539631 1 0 1 1 0 0 +EDGE2 3363 823 -0.0536255 -0.00281927 0.0214691 1 0 1 1 0 0 +EDGE2 3363 824 0.933238 -0.0195452 0.0452042 1 0 1 1 0 0 +EDGE2 3363 3204 0.971041 0.0289519 0.00981392 1 0 1 1 0 0 +EDGE2 3363 3224 0.924402 -0.095748 -0.0397588 1 0 1 1 0 0 +EDGE2 3363 704 1.01056 0.0353791 -0.00928957 1 0 1 1 0 0 +EDGE2 3364 3203 -0.986246 0.00442251 -0.0220875 1 0 1 1 0 0 +EDGE2 3364 3363 -1.0055 0.0878294 0.00500615 1 0 1 1 0 0 +EDGE2 3364 3223 -1.03132 -0.0211518 -0.0130428 1 0 1 1 0 0 +EDGE2 3364 703 -0.996944 -0.0117163 -0.00309583 1 0 1 1 0 0 +EDGE2 3364 823 -1.00562 0.0593971 0.0234192 1 0 1 1 0 0 +EDGE2 3364 824 -0.0173973 0.031555 -0.00557681 1 0 1 1 0 0 +EDGE2 3364 3204 -0.0546806 -0.0343111 -0.000210021 1 0 1 1 0 0 +EDGE2 3364 3224 -0.0275765 0.0315803 -0.0112719 1 0 1 1 0 0 +EDGE2 3364 704 -0.107865 -0.0825622 -0.00528422 1 0 1 1 0 0 +EDGE2 3364 865 1.01257 -0.00462612 -3.14721 1 0 1 1 0 0 +EDGE2 3364 3225 1.00412 -0.0168143 0.0280204 1 0 1 1 0 0 +EDGE2 3364 1205 0.979651 -0.0171858 -3.15976 1 0 1 1 0 0 +EDGE2 3364 3205 1.01742 -0.0904938 0.01452 1 0 1 1 0 0 +EDGE2 3364 905 0.92082 0.0384969 -3.14451 1 0 1 1 0 0 +EDGE2 3364 705 1.10896 -0.000354079 0.0123906 1 0 1 1 0 0 +EDGE2 3364 825 0.981919 -0.00950951 -0.0183791 1 0 1 1 0 0 +EDGE2 3364 845 1.03085 0.0311075 -3.14514 1 0 1 1 0 0 +EDGE2 3365 3364 -1.11408 0.0891476 0.0212285 1 0 1 1 0 0 +EDGE2 3365 824 -1.02081 0.0295363 0.0135151 1 0 1 1 0 0 +EDGE2 3365 3204 -1.05441 -0.00457978 -0.0252026 1 0 1 1 0 0 +EDGE2 3365 3224 -0.955009 0.0021535 -0.0115458 1 0 1 1 0 0 +EDGE2 3365 704 -0.949973 0.0285596 0.0264312 1 0 1 1 0 0 +EDGE2 3365 865 0.0791831 0.0258696 -3.13319 1 0 1 1 0 0 +EDGE2 3365 3225 -0.00118723 4.86231e-05 -0.00952055 1 0 1 1 0 0 +EDGE2 3365 826 0.0421996 -1.03502 -1.5838 1 0 1 1 0 0 +EDGE2 3365 866 -0.0627426 -0.947515 -1.55462 1 0 1 1 0 0 +EDGE2 3365 906 -0.042571 -1.02052 -1.59632 1 0 1 1 0 0 +EDGE2 3365 846 -0.0245821 -1.00027 -1.5601 1 0 1 1 0 0 +EDGE2 3365 1205 0.0592251 -0.00831005 -3.14907 1 0 1 1 0 0 +EDGE2 3365 3205 -0.103337 0.0556615 -0.0142241 1 0 1 1 0 0 +EDGE2 3365 905 0.0157611 -0.00865363 -3.12277 1 0 1 1 0 0 +EDGE2 3365 864 0.983845 0.0574365 -3.13244 1 0 1 1 0 0 +EDGE2 3365 705 0.00589516 -0.0394194 0.00087069 1 0 1 1 0 0 +EDGE2 3365 825 -0.0608771 -0.01969 0.00863396 1 0 1 1 0 0 +EDGE2 3365 845 0.0225347 0.00671838 -3.12526 1 0 1 1 0 0 +EDGE2 3365 1204 1.0129 -0.00991498 -3.20003 1 0 1 1 0 0 +EDGE2 3365 904 1.06666 -0.0836568 -3.12685 1 0 1 1 0 0 +EDGE2 3365 844 1.03405 0.00322351 -3.1444 1 0 1 1 0 0 +EDGE2 3365 1206 -0.00538722 1.01178 1.57866 1 0 1 1 0 0 +EDGE2 3365 3226 -0.0602298 0.968362 1.57488 1 0 1 1 0 0 +EDGE2 3365 3206 0.058646 0.944147 1.59082 1 0 1 1 0 0 +EDGE2 3365 706 -0.132161 1.03162 1.5909 1 0 1 1 0 0 +EDGE2 3366 865 -1.02616 -0.0493022 1.55992 1 0 1 1 0 0 +EDGE2 3366 3225 -1.0396 -0.00265792 -1.60999 1 0 1 1 0 0 +EDGE2 3366 3365 -0.985029 0.0102234 -1.51923 1 0 1 1 0 0 +EDGE2 3366 1205 -1.00233 0.0342693 1.55923 1 0 1 1 0 0 +EDGE2 3366 3205 -0.972496 0.111161 -1.57758 1 0 1 1 0 0 +EDGE2 3366 905 -0.989777 0.0058866 1.56527 1 0 1 1 0 0 +EDGE2 3366 705 -0.989146 -0.0921364 -1.61238 1 0 1 1 0 0 +EDGE2 3366 825 -0.946922 -0.0221976 -1.57379 1 0 1 1 0 0 +EDGE2 3366 845 -1.01033 0.0300544 1.54286 1 0 1 1 0 0 +EDGE2 3366 1206 0.00830862 -0.059387 0.0232503 1 0 1 1 0 0 +EDGE2 3366 3226 0.11624 0.0205104 0.0042981 1 0 1 1 0 0 +EDGE2 3366 3206 0.0498312 -0.166805 -0.00270181 1 0 1 1 0 0 +EDGE2 3366 706 -0.0656538 -0.0102316 0.00250353 1 0 1 1 0 0 +EDGE2 3366 1207 1.04973 0.141418 0.0241552 1 0 1 1 0 0 +EDGE2 3366 3207 0.991831 0.094084 -0.00776145 1 0 1 1 0 0 +EDGE2 3366 3227 1.01265 -0.0428618 0.00884355 1 0 1 1 0 0 +EDGE2 3366 707 0.992863 -6.07565e-05 0.000360579 1 0 1 1 0 0 +EDGE2 3367 3228 0.965692 -0.0349557 0.0284867 1 0 1 1 0 0 +EDGE2 3367 1206 -1.05578 -0.00763933 0.0326782 1 0 1 1 0 0 +EDGE2 3367 3226 -1.01009 -0.130048 -0.00222526 1 0 1 1 0 0 +EDGE2 3367 3366 -1.0302 -0.00429883 0.00295761 1 0 1 1 0 0 +EDGE2 3367 3206 -0.974992 0.0750953 -0.0240479 1 0 1 1 0 0 +EDGE2 3367 706 -0.932539 -0.0168833 0.0225137 1 0 1 1 0 0 +EDGE2 3367 1207 0.03193 0.015326 -0.0014754 1 0 1 1 0 0 +EDGE2 3367 3207 0.0215546 -0.0616965 -0.00961397 1 0 1 1 0 0 +EDGE2 3367 3227 -0.0027981 0.0223986 0.029089 1 0 1 1 0 0 +EDGE2 3367 707 -0.0388186 0.0413948 -0.0226962 1 0 1 1 0 0 +EDGE2 3367 708 1.00467 -0.00511012 -0.00718081 1 0 1 1 0 0 +EDGE2 3367 1208 1.11959 0.0152156 0.0170159 1 0 1 1 0 0 +EDGE2 3367 3208 1.02824 -0.109927 -0.000737051 1 0 1 1 0 0 +EDGE2 3368 3228 0.0315474 -0.0830594 -0.027048 1 0 1 1 0 0 +EDGE2 3368 3367 -0.970009 -0.00326062 0.00971046 1 0 1 1 0 0 +EDGE2 3368 1207 -0.99509 0.0550504 0.0210421 1 0 1 1 0 0 +EDGE2 3368 3207 -0.919398 0.0484405 -0.00798931 1 0 1 1 0 0 +EDGE2 3368 3227 -1.07187 -0.000933959 -0.00850695 1 0 1 1 0 0 +EDGE2 3368 707 -1.06143 -0.0282486 -0.0167544 1 0 1 1 0 0 +EDGE2 3368 708 -0.00776909 0.0212494 -0.0160268 1 0 1 1 0 0 +EDGE2 3368 1208 0.0419633 0.0313119 0.026673 1 0 1 1 0 0 +EDGE2 3368 3208 -0.00225874 -0.0163014 0.00975003 1 0 1 1 0 0 +EDGE2 3368 1209 0.924756 0.0233011 -0.0177941 1 0 1 1 0 0 +EDGE2 3368 3209 0.954615 0.0190894 0.032084 1 0 1 1 0 0 +EDGE2 3368 3229 1.05494 -0.0342914 -0.0178958 1 0 1 1 0 0 +EDGE2 3368 709 1.01859 0.0773531 -0.0251698 1 0 1 1 0 0 +EDGE2 3369 3228 -1.02518 0.0348344 -0.0149741 1 0 1 1 0 0 +EDGE2 3369 3368 -0.972779 0.017124 -0.016836 1 0 1 1 0 0 +EDGE2 3369 708 -0.90562 -0.0178529 -0.0193711 1 0 1 1 0 0 +EDGE2 3369 1208 -1.02828 0.0126828 0.00538459 1 0 1 1 0 0 +EDGE2 3369 3208 -0.926525 -0.0537916 0.0254189 1 0 1 1 0 0 +EDGE2 3369 1209 0.0256918 -0.119337 -0.059453 1 0 1 1 0 0 +EDGE2 3369 3209 -0.00761323 0.0148379 -0.00761123 1 0 1 1 0 0 +EDGE2 3369 3229 -0.0603733 -0.00665301 0.0222723 1 0 1 1 0 0 +EDGE2 3369 709 -0.0231268 0.112605 -0.0157247 1 0 1 1 0 0 +EDGE2 3369 730 0.993787 0.0353039 -3.14995 1 0 1 1 0 0 +EDGE2 3369 3190 0.978383 0.030982 -3.15863 1 0 1 1 0 0 +EDGE2 3369 3210 1.07658 0.0614541 0.0163003 1 0 1 1 0 0 +EDGE2 3369 3230 0.996815 0.0659081 0.0172352 1 0 1 1 0 0 +EDGE2 3369 1210 1.00792 0.104903 -0.001223 1 0 1 1 0 0 +EDGE2 3369 710 0.914553 -0.0531363 0.0230131 1 0 1 1 0 0 +EDGE2 3370 1211 0.0597023 0.902614 1.58345 1 0 1 1 0 0 +EDGE2 3370 3211 0.0730842 0.936917 1.58265 1 0 1 1 0 0 +EDGE2 3370 3231 -0.0729573 1.06679 1.59699 1 0 1 1 0 0 +EDGE2 3370 3191 0.0335478 0.938981 1.61121 1 0 1 1 0 0 +EDGE2 3370 711 -0.0182232 0.983845 1.58681 1 0 1 1 0 0 +EDGE2 3370 731 0.0173838 1.14829 1.57705 1 0 1 1 0 0 +EDGE2 3370 3369 -1.01421 0.0144069 -0.0258786 1 0 1 1 0 0 +EDGE2 3370 1209 -1.02797 0.0607199 -0.0105522 1 0 1 1 0 0 +EDGE2 3370 3209 -0.991794 0.0899957 0.0102245 1 0 1 1 0 0 +EDGE2 3370 3229 -0.884764 -0.0391223 0.00195283 1 0 1 1 0 0 +EDGE2 3370 709 -1.12363 -0.044107 0.00545349 1 0 1 1 0 0 +EDGE2 3370 730 -0.0474995 -0.00283837 -3.12902 1 0 1 1 0 0 +EDGE2 3370 3190 -0.0405212 0.0202139 -3.15775 1 0 1 1 0 0 +EDGE2 3370 3210 0.0681331 -0.0346424 0.0210426 1 0 1 1 0 0 +EDGE2 3370 3230 0.0449661 -0.0472403 -0.0164627 1 0 1 1 0 0 +EDGE2 3370 1210 -0.00308897 -0.00281753 0.016894 1 0 1 1 0 0 +EDGE2 3370 710 -0.0582677 0.025176 -0.0195484 1 0 1 1 0 0 +EDGE2 3370 3189 0.946341 0.0456689 -3.12981 1 0 1 1 0 0 +EDGE2 3370 729 1.00963 0.0602035 -3.11663 1 0 1 1 0 0 +EDGE2 3371 3370 -1.12368 -0.0475367 1.55052 1 0 1 1 0 0 +EDGE2 3371 730 -1.04389 -0.0326073 -1.55813 1 0 1 1 0 0 +EDGE2 3371 3190 -0.869291 0.0618418 -1.57414 1 0 1 1 0 0 +EDGE2 3371 3210 -0.995094 0.0732314 1.5691 1 0 1 1 0 0 +EDGE2 3371 3230 -1.08925 -0.0845679 1.57011 1 0 1 1 0 0 +EDGE2 3371 1210 -0.967728 0.0766913 1.60009 1 0 1 1 0 0 +EDGE2 3371 710 -0.932277 0.104582 1.53283 1 0 1 1 0 0 +EDGE2 3372 3371 -0.996745 0.0677216 0.0211882 1 0 1 1 0 0 +EDGE2 3373 3372 -0.997346 -0.00655903 -0.0178086 1 0 1 1 0 0 +EDGE2 3374 3373 -1.00318 0.0330366 0.00983388 1 0 1 1 0 0 +EDGE2 3374 3115 0.993082 -0.0308875 -3.14622 1 0 1 1 0 0 +EDGE2 3374 3175 0.959809 0.0513428 -3.16116 1 0 1 1 0 0 +EDGE2 3374 3135 0.979768 0.000991526 -3.14438 1 0 1 1 0 0 +EDGE2 3374 1175 0.909281 -0.00479329 -3.1447 1 0 1 1 0 0 +EDGE2 3374 1195 0.976293 0.0393203 -3.16371 1 0 1 1 0 0 +EDGE2 3374 3095 0.955398 0.0650224 -3.15631 1 0 1 1 0 0 +EDGE2 3374 1155 1.01053 0.0240475 -3.14194 1 0 1 1 0 0 +EDGE2 3375 3374 -0.978279 -0.0981372 0.0100283 1 0 1 1 0 0 +EDGE2 3375 1196 0.0459698 -0.950127 -1.56617 1 0 1 1 0 0 +EDGE2 3375 3116 0.00512819 -0.964396 -1.59393 1 0 1 1 0 0 +EDGE2 3375 3136 0.0763742 -1.0181 -1.55009 1 0 1 1 0 0 +EDGE2 3375 3096 0.0152968 -1.0779 -1.54589 1 0 1 1 0 0 +EDGE2 3375 1156 0.00879931 -1.0007 -1.56605 1 0 1 1 0 0 +EDGE2 3375 1176 0.0396195 -1.00649 -1.57699 1 0 1 1 0 0 +EDGE2 3375 1174 1.00789 0.0145076 -3.12842 1 0 1 1 0 0 +EDGE2 3375 3115 0.0689445 -0.00314325 -3.13925 1 0 1 1 0 0 +EDGE2 3375 3175 -0.0258754 -0.0378265 -3.14443 1 0 1 1 0 0 +EDGE2 3375 3135 -0.00166088 -0.0256126 -3.12938 1 0 1 1 0 0 +EDGE2 3375 1175 -0.00101733 -0.0287064 -3.14208 1 0 1 1 0 0 +EDGE2 3375 1195 0.098795 0.0535104 -3.1208 1 0 1 1 0 0 +EDGE2 3375 3095 0.0196291 -0.0129726 -3.12854 1 0 1 1 0 0 +EDGE2 3375 1155 -0.133451 -0.0666759 -3.14249 1 0 1 1 0 0 +EDGE2 3375 3174 1.0616 0.0350247 -3.1386 1 0 1 1 0 0 +EDGE2 3375 3094 0.947846 -0.0287355 -3.12537 1 0 1 1 0 0 +EDGE2 3375 3114 1.00387 -0.09177 -3.13186 1 0 1 1 0 0 +EDGE2 3375 3134 0.954719 -0.0189612 -3.1317 1 0 1 1 0 0 +EDGE2 3375 1194 0.965212 -0.0969622 -3.11775 1 0 1 1 0 0 +EDGE2 3375 1154 1.01231 -0.0245876 -3.15073 1 0 1 1 0 0 +EDGE2 3375 3176 -0.0142171 0.994603 1.57131 1 0 1 1 0 0 +EDGE2 3376 1197 0.963234 -0.0876301 -0.0133167 1 0 1 1 0 0 +EDGE2 3376 3117 0.998048 0.036064 0.0087295 1 0 1 1 0 0 +EDGE2 3376 3137 1.04532 -0.0791747 0.00528732 1 0 1 1 0 0 +EDGE2 3376 3097 0.944511 -0.00145906 -0.0281314 1 0 1 1 0 0 +EDGE2 3376 1177 0.979579 0.00745848 -0.00689997 1 0 1 1 0 0 +EDGE2 3376 1157 0.980463 0.0229105 0.0191323 1 0 1 1 0 0 +EDGE2 3376 1196 -0.0407346 0.116127 -0.0230717 1 0 1 1 0 0 +EDGE2 3376 3116 0.014412 -0.011284 0.00118175 1 0 1 1 0 0 +EDGE2 3376 3136 0.00106541 0.038895 -0.00492561 1 0 1 1 0 0 +EDGE2 3376 3096 0.0592333 -0.0594632 -0.00580277 1 0 1 1 0 0 +EDGE2 3376 1156 -0.0505231 -0.0154285 -0.0256396 1 0 1 1 0 0 +EDGE2 3376 1176 -0.0306823 0.0209287 -0.0143891 1 0 1 1 0 0 +EDGE2 3376 3115 -1.03889 0.0554602 -1.58605 1 0 1 1 0 0 +EDGE2 3376 3175 -0.967511 -0.091141 -1.54439 1 0 1 1 0 0 +EDGE2 3376 3375 -0.963881 -0.0400978 1.57084 1 0 1 1 0 0 +EDGE2 3376 3135 -0.950133 0.0190754 -1.58758 1 0 1 1 0 0 +EDGE2 3376 1175 -0.985126 0.0561584 -1.54465 1 0 1 1 0 0 +EDGE2 3376 1195 -0.908846 0.0459091 -1.55254 1 0 1 1 0 0 +EDGE2 3376 3095 -1.08636 -0.0244726 -1.57796 1 0 1 1 0 0 +EDGE2 3376 1155 -1.00807 -0.0331465 -1.57278 1 0 1 1 0 0 +EDGE2 3377 1197 -0.0342016 0.0311915 0.0224677 1 0 1 1 0 0 +EDGE2 3377 3098 1.01457 -0.031905 -0.0288832 1 0 1 1 0 0 +EDGE2 3377 3138 0.943984 -0.0408738 0.0422757 1 0 1 1 0 0 +EDGE2 3377 3118 1.05088 -0.0571748 -0.0126151 1 0 1 1 0 0 +EDGE2 3377 1178 1.04428 0.0405945 -0.00952286 1 0 1 1 0 0 +EDGE2 3377 1198 0.933232 -0.0395138 0.0254418 1 0 1 1 0 0 +EDGE2 3377 1158 1.08614 -0.00377406 -0.0116511 1 0 1 1 0 0 +EDGE2 3377 3117 -0.016991 -0.00427456 0.0167135 1 0 1 1 0 0 +EDGE2 3377 3137 0.0123613 -0.105422 -0.023345 1 0 1 1 0 0 +EDGE2 3377 3097 0.0429511 0.0294283 -0.00202335 1 0 1 1 0 0 +EDGE2 3377 1177 0.0129682 -0.0214725 -0.0450048 1 0 1 1 0 0 +EDGE2 3377 1157 0.0399815 -0.0942481 0.00163898 1 0 1 1 0 0 +EDGE2 3377 1196 -1.08574 -0.0212251 -0.0220658 1 0 1 1 0 0 +EDGE2 3377 3116 -1.01328 -0.0296168 -0.0205653 1 0 1 1 0 0 +EDGE2 3377 3136 -0.974573 0.0273065 0.0122799 1 0 1 1 0 0 +EDGE2 3377 3376 -1.0509 0.0193071 -0.0459198 1 0 1 1 0 0 +EDGE2 3377 3096 -0.942413 0.0433725 0.00631152 1 0 1 1 0 0 +EDGE2 3377 1156 -0.99747 0.0865035 0.0139783 1 0 1 1 0 0 +EDGE2 3377 1176 -0.938902 -0.0461794 0.00712257 1 0 1 1 0 0 +EDGE2 3378 1197 -0.985129 -0.0704665 0.0214926 1 0 1 1 0 0 +EDGE2 3378 3119 0.961009 -0.00648946 -0.0238628 1 0 1 1 0 0 +EDGE2 3378 3139 0.999434 -0.0191831 0.0206045 1 0 1 1 0 0 +EDGE2 3378 1179 1.05038 -0.0781382 -0.0224335 1 0 1 1 0 0 +EDGE2 3378 1199 0.966457 -0.00054203 -0.0134769 1 0 1 1 0 0 +EDGE2 3378 3099 1.06817 0.0773343 -0.0166534 1 0 1 1 0 0 +EDGE2 3378 1159 1.06122 0.0612627 -0.00411106 1 0 1 1 0 0 +EDGE2 3378 3098 -0.0239127 0.00141429 -0.0106002 1 0 1 1 0 0 +EDGE2 3378 3138 0.104513 -0.0112961 -0.0114434 1 0 1 1 0 0 +EDGE2 3378 3118 0.00337235 -0.0137308 0.0201013 1 0 1 1 0 0 +EDGE2 3378 1178 0.0654677 -0.0485513 0.0228117 1 0 1 1 0 0 +EDGE2 3378 1198 0.0523494 -0.102726 0.0106231 1 0 1 1 0 0 +EDGE2 3378 1158 -0.0458359 0.0339238 -0.0321544 1 0 1 1 0 0 +EDGE2 3378 3117 -0.964465 0.0369766 0.0121577 1 0 1 1 0 0 +EDGE2 3378 3137 -1.0137 -0.000780326 -0.0247274 1 0 1 1 0 0 +EDGE2 3378 3377 -0.97484 -0.0166141 -0.00154618 1 0 1 1 0 0 +EDGE2 3378 3097 -0.945443 -0.0316718 0.00315145 1 0 1 1 0 0 +EDGE2 3378 1177 -0.942022 0.022124 -0.0110612 1 0 1 1 0 0 +EDGE2 3378 1157 -1.03819 0.0359057 -0.00153981 1 0 1 1 0 0 +EDGE2 3379 1160 1.05854 -0.0116556 0.00434697 1 0 1 1 0 0 +EDGE2 3379 3140 0.909198 -0.018709 0.0389515 1 0 1 1 0 0 +EDGE2 3379 1200 0.99121 0.0850563 -0.0228509 1 0 1 1 0 0 +EDGE2 3379 3100 0.941302 0.023439 -0.0367097 1 0 1 1 0 0 +EDGE2 3379 3120 0.979373 0.00819393 0.0206665 1 0 1 1 0 0 +EDGE2 3379 1180 1.01903 0.0116359 -0.010801 1 0 1 1 0 0 +EDGE2 3379 900 1.0378 0.0337396 -3.12399 1 0 1 1 0 0 +EDGE2 3379 840 1.03308 -0.0240496 -3.18182 1 0 1 1 0 0 +EDGE2 3379 860 0.991648 -0.0581224 -3.1767 1 0 1 1 0 0 +EDGE2 3379 3119 -0.0225988 -0.0147438 -0.0333662 1 0 1 1 0 0 +EDGE2 3379 3139 -0.0263732 0.0852777 0.0113707 1 0 1 1 0 0 +EDGE2 3379 1179 0.0480252 0.021218 -0.0205302 1 0 1 1 0 0 +EDGE2 3379 1199 -0.0384477 -0.0743563 0.00721942 1 0 1 1 0 0 +EDGE2 3379 3099 -0.100685 -0.0241317 0.0288414 1 0 1 1 0 0 +EDGE2 3379 1159 0.0650428 -0.0194968 -0.0150715 1 0 1 1 0 0 +EDGE2 3379 3098 -0.892322 0.0271717 -0.0181956 1 0 1 1 0 0 +EDGE2 3379 3138 -1.02797 -0.027025 -0.0351709 1 0 1 1 0 0 +EDGE2 3379 3378 -0.912538 0.0431699 0.00284352 1 0 1 1 0 0 +EDGE2 3379 3118 -0.994595 -0.0915655 0.00801018 1 0 1 1 0 0 +EDGE2 3379 1178 -0.958777 -0.0389688 -0.0053817 1 0 1 1 0 0 +EDGE2 3379 1198 -0.936157 -0.0156895 0.0400765 1 0 1 1 0 0 +EDGE2 3379 1158 -0.962507 0.078051 0.00757356 1 0 1 1 0 0 +EDGE2 3380 839 0.985203 0.0888101 -3.09747 1 0 1 1 0 0 +EDGE2 3380 899 1.02424 -0.0125156 -3.15735 1 0 1 1 0 0 +EDGE2 3380 859 0.984717 0.0445131 -3.12333 1 0 1 1 0 0 +EDGE2 3380 841 0.0249252 -1.05749 -1.53819 1 0 1 1 0 0 +EDGE2 3380 901 -0.0288604 -1.06668 -1.55924 1 0 1 1 0 0 +EDGE2 3380 1201 -0.0679883 -0.988365 -1.54466 1 0 1 1 0 0 +EDGE2 3380 861 -0.0631673 -0.985305 -1.55237 1 0 1 1 0 0 +EDGE2 3380 1160 -0.0585291 -0.0648051 -0.0118091 1 0 1 1 0 0 +EDGE2 3380 3140 0.0524995 0.055319 -0.00684521 1 0 1 1 0 0 +EDGE2 3380 1200 -0.0643833 -0.0634745 0.0254366 1 0 1 1 0 0 +EDGE2 3380 3100 0.0658057 0.0210276 -0.0174225 1 0 1 1 0 0 +EDGE2 3380 3120 -0.0425378 0.0736632 0.00546966 1 0 1 1 0 0 +EDGE2 3380 1180 0.0211382 -0.0471708 -0.0207907 1 0 1 1 0 0 +EDGE2 3380 900 -0.0313735 -0.0467008 -3.11484 1 0 1 1 0 0 +EDGE2 3380 840 -0.0658746 -0.0823301 -3.16359 1 0 1 1 0 0 +EDGE2 3380 860 -0.0532986 0.050761 -3.16556 1 0 1 1 0 0 +EDGE2 3380 3101 0.00903982 0.954779 1.5513 1 0 1 1 0 0 +EDGE2 3380 3141 0.0115748 1.00274 1.58232 1 0 1 1 0 0 +EDGE2 3380 3121 0.104434 1.04749 1.59525 1 0 1 1 0 0 +EDGE2 3380 1161 -0.00259333 1.0268 1.55887 1 0 1 1 0 0 +EDGE2 3380 1181 0.047232 0.956722 1.58293 1 0 1 1 0 0 +EDGE2 3380 3119 -0.945502 -0.0213998 -0.00821128 1 0 1 1 0 0 +EDGE2 3380 3379 -1.03119 -0.0136076 -0.00565228 1 0 1 1 0 0 +EDGE2 3380 3139 -1.03258 0.00113211 -0.00796568 1 0 1 1 0 0 +EDGE2 3380 1179 -0.964654 0.0203197 -0.0342981 1 0 1 1 0 0 +EDGE2 3380 1199 -1.00401 0.0154847 0.00903541 1 0 1 1 0 0 +EDGE2 3380 3099 -0.954738 -0.0164472 -0.0438704 1 0 1 1 0 0 +EDGE2 3380 1159 -1.00205 -0.0862351 -0.0222455 1 0 1 1 0 0 +EDGE2 3381 1160 -1.02559 0.0525854 -1.56904 1 0 1 1 0 0 +EDGE2 3381 3140 -1.02394 -0.00192827 -1.59247 1 0 1 1 0 0 +EDGE2 3381 3380 -1.06568 -0.0580149 -1.57101 1 0 1 1 0 0 +EDGE2 3381 1200 -1.01994 0.0275862 -1.53961 1 0 1 1 0 0 +EDGE2 3381 3100 -0.973687 -0.0841826 -1.57237 1 0 1 1 0 0 +EDGE2 3381 3120 -1.02165 0.078087 -1.572 1 0 1 1 0 0 +EDGE2 3381 1180 -0.94185 0.014837 -1.5799 1 0 1 1 0 0 +EDGE2 3381 900 -1.0327 -0.0579047 1.59899 1 0 1 1 0 0 +EDGE2 3381 840 -1.02704 0.0249349 1.57528 1 0 1 1 0 0 +EDGE2 3381 860 -0.904847 0.0271768 1.59482 1 0 1 1 0 0 +EDGE2 3381 3101 -0.0303243 0.0760626 -0.00925196 1 0 1 1 0 0 +EDGE2 3381 3141 -0.0768212 -0.0720825 0.0169049 1 0 1 1 0 0 +EDGE2 3381 3121 -0.114566 -0.0633522 0.0167173 1 0 1 1 0 0 +EDGE2 3381 1161 -0.0184704 -0.014354 0.00823665 1 0 1 1 0 0 +EDGE2 3381 1181 -0.0715266 -0.0739808 -0.0268531 1 0 1 1 0 0 +EDGE2 3381 1182 1.02017 -0.0105895 0.0199321 1 0 1 1 0 0 +EDGE2 3381 3122 0.948466 -0.0451006 0.000652488 1 0 1 1 0 0 +EDGE2 3381 3142 0.994959 -0.0265206 -0.0153094 1 0 1 1 0 0 +EDGE2 3381 3102 1.0417 -0.0486172 0.016542 1 0 1 1 0 0 +EDGE2 3381 1162 1.0184 0.0664322 -0.0209089 1 0 1 1 0 0 +EDGE2 3382 3101 -1.03614 0.0777825 -0.00193084 1 0 1 1 0 0 +EDGE2 3382 3141 -0.943929 -0.0416233 -0.0130231 1 0 1 1 0 0 +EDGE2 3382 3381 -1.02675 -0.0210944 0.00669641 1 0 1 1 0 0 +EDGE2 3382 3121 -1.00952 -0.00241337 -0.000575654 1 0 1 1 0 0 +EDGE2 3382 1161 -0.965389 -0.0745593 -0.0221259 1 0 1 1 0 0 +EDGE2 3382 1181 -0.992008 -0.00212619 -0.00167471 1 0 1 1 0 0 +EDGE2 3382 1182 0.0357901 -0.0630672 0.000335421 1 0 1 1 0 0 +EDGE2 3382 3122 0.0207101 -0.00826078 -0.0165426 1 0 1 1 0 0 +EDGE2 3382 3142 -0.00543272 0.0651874 0.0213362 1 0 1 1 0 0 +EDGE2 3382 3102 0.0528841 -0.0260608 -0.0102758 1 0 1 1 0 0 +EDGE2 3382 1162 -0.094003 -0.0700223 -0.0271845 1 0 1 1 0 0 +EDGE2 3382 1163 1.02981 -0.0209768 0.0329028 1 0 1 1 0 0 +EDGE2 3382 3103 0.944406 -0.03299 0.0100824 1 0 1 1 0 0 +EDGE2 3382 3123 0.968682 0.00528807 -0.000152983 1 0 1 1 0 0 +EDGE2 3382 3143 0.962847 0.126199 0.000908581 1 0 1 1 0 0 +EDGE2 3382 1183 1.03781 0.0194179 -0.0138116 1 0 1 1 0 0 +EDGE2 3383 1182 -1.02589 0.0218957 -0.0351919 1 0 1 1 0 0 +EDGE2 3383 3122 -0.90753 0.0475131 0.0271598 1 0 1 1 0 0 +EDGE2 3383 3142 -1.00594 -0.0105669 -0.000644681 1 0 1 1 0 0 +EDGE2 3383 3382 -1.00095 0.0182364 0.0353806 1 0 1 1 0 0 +EDGE2 3383 3102 -1.06766 0.040958 -0.00126796 1 0 1 1 0 0 +EDGE2 3383 1162 -0.939639 -0.0646606 -0.013708 1 0 1 1 0 0 +EDGE2 3383 3144 1.05061 -0.00111254 0.0131242 1 0 1 1 0 0 +EDGE2 3383 1163 0.00237914 -0.0482921 0.0146902 1 0 1 1 0 0 +EDGE2 3383 3103 -0.0748495 0.0524137 -0.0396593 1 0 1 1 0 0 +EDGE2 3383 3123 -0.00412659 0.0377469 0.0218838 1 0 1 1 0 0 +EDGE2 3383 3143 0.066001 0.0600729 0.00454972 1 0 1 1 0 0 +EDGE2 3383 1183 7.17025e-05 -0.0726008 -0.0232342 1 0 1 1 0 0 +EDGE2 3383 1184 0.985035 0.00929298 -0.0153546 1 0 1 1 0 0 +EDGE2 3383 3104 1.07014 0.0131862 0.00198897 1 0 1 1 0 0 +EDGE2 3383 3124 0.985295 -0.0668469 -0.0116686 1 0 1 1 0 0 +EDGE2 3383 1164 0.958004 -0.00455049 0.00284756 1 0 1 1 0 0 +EDGE2 3384 3383 -0.951876 -0.0381527 -0.0110913 1 0 1 1 0 0 +EDGE2 3384 3144 0.0153547 0.0369215 0.0331682 1 0 1 1 0 0 +EDGE2 3384 1163 -1.0087 0.0415639 0.00608017 1 0 1 1 0 0 +EDGE2 3384 3103 -1.01073 0.0110889 -0.0104452 1 0 1 1 0 0 +EDGE2 3384 3123 -1.09476 -0.0465043 0.0294999 1 0 1 1 0 0 +EDGE2 3384 3143 -0.989962 0.0312643 -0.0146372 1 0 1 1 0 0 +EDGE2 3384 1183 -0.934755 0.0695531 -0.00382378 1 0 1 1 0 0 +EDGE2 3384 1184 0.0185427 0.0591126 0.012135 1 0 1 1 0 0 +EDGE2 3384 3104 -0.0119505 0.00242703 -0.00612695 1 0 1 1 0 0 +EDGE2 3384 3124 0.0246868 0.032714 0.0232891 1 0 1 1 0 0 +EDGE2 3384 1164 -0.123543 0.0327996 -0.0032793 1 0 1 1 0 0 +EDGE2 3384 3105 1.02651 0.0282481 -0.026468 1 0 1 1 0 0 +EDGE2 3384 3145 1.05816 0.00760096 -0.0193792 1 0 1 1 0 0 +EDGE2 3384 3165 0.920065 -0.0330673 -3.14275 1 0 1 1 0 0 +EDGE2 3384 3125 1.02047 0.00308286 -0.0311778 1 0 1 1 0 0 +EDGE2 3384 1185 0.965296 0.019687 0.00134181 1 0 1 1 0 0 +EDGE2 3384 3065 1.07334 -0.0164653 -3.10833 1 0 1 1 0 0 +EDGE2 3384 3085 0.963892 -0.0226219 -3.14366 1 0 1 1 0 0 +EDGE2 3384 1165 0.975989 0.0198155 0.00159853 1 0 1 1 0 0 +EDGE2 3385 3146 0.00862259 -0.977387 -1.57598 1 0 1 1 0 0 +EDGE2 3385 3066 0.126191 -0.970137 -1.5851 1 0 1 1 0 0 +EDGE2 3385 3144 -1.02888 -0.00125336 -0.0047556 1 0 1 1 0 0 +EDGE2 3385 3384 -1.09816 0.0628657 0.0141733 1 0 1 1 0 0 +EDGE2 3385 1184 -1.06122 -0.13439 0.0288116 1 0 1 1 0 0 +EDGE2 3385 3104 -1.00886 0.00691463 0.0270515 1 0 1 1 0 0 +EDGE2 3385 3124 -0.901135 -0.0160304 0.0306381 1 0 1 1 0 0 +EDGE2 3385 1164 -0.902058 -0.0490052 0.0280458 1 0 1 1 0 0 +EDGE2 3385 3166 -0.0296681 0.939099 1.56487 1 0 1 1 0 0 +EDGE2 3385 3105 0.0271069 -0.0783405 -0.0285362 1 0 1 1 0 0 +EDGE2 3385 3145 -0.0236574 0.102769 -0.0409943 1 0 1 1 0 0 +EDGE2 3385 3165 -0.0658902 0.0271132 -3.13792 1 0 1 1 0 0 +EDGE2 3385 3125 -0.0399567 -0.0741837 0.00764049 1 0 1 1 0 0 +EDGE2 3385 1185 -0.0676374 -0.113382 0.0658218 1 0 1 1 0 0 +EDGE2 3385 3065 -0.0758508 0.0516875 -3.15735 1 0 1 1 0 0 +EDGE2 3385 3085 0.0324872 -0.0552882 -3.13961 1 0 1 1 0 0 +EDGE2 3385 1165 0.07216 0.0757195 -0.0166582 1 0 1 1 0 0 +EDGE2 3385 1166 0.0726912 1.06784 1.57142 1 0 1 1 0 0 +EDGE2 3385 3086 -0.00646633 1.02398 1.59629 1 0 1 1 0 0 +EDGE2 3385 3106 -0.0395542 1.07293 1.58272 1 0 1 1 0 0 +EDGE2 3385 3126 0.0584564 1.03999 1.58634 1 0 1 1 0 0 +EDGE2 3385 1186 0.00828319 1.10108 1.57254 1 0 1 1 0 0 +EDGE2 3385 3064 1.02339 0.00925326 -3.16344 1 0 1 1 0 0 +EDGE2 3385 3164 0.981382 -0.0261182 -3.16613 1 0 1 1 0 0 +EDGE2 3385 3084 0.983575 0.0752332 -3.1747 1 0 1 1 0 0 +EDGE2 3386 3147 0.979198 -0.00191151 -0.0241178 1 0 1 1 0 0 +EDGE2 3386 3067 1.01719 0.0469965 -0.0037278 1 0 1 1 0 0 +EDGE2 3386 3146 -0.0665681 -0.0120618 0.0328959 1 0 1 1 0 0 +EDGE2 3386 3066 0.0560213 0.0159442 -0.000924485 1 0 1 1 0 0 +EDGE2 3386 3105 -0.942013 0.0388162 1.56647 1 0 1 1 0 0 +EDGE2 3386 3145 -1.06449 -0.023283 1.57293 1 0 1 1 0 0 +EDGE2 3386 3165 -1.0233 0.0659521 -1.56383 1 0 1 1 0 0 +EDGE2 3386 3385 -0.968205 -0.0259474 1.58191 1 0 1 1 0 0 +EDGE2 3386 3125 -0.945688 -0.0843312 1.57863 1 0 1 1 0 0 +EDGE2 3386 1185 -1.00467 0.0414354 1.55639 1 0 1 1 0 0 +EDGE2 3386 3065 -1.01197 0.00805483 -1.56809 1 0 1 1 0 0 +EDGE2 3386 3085 -1.03291 0.00399728 -1.58586 1 0 1 1 0 0 +EDGE2 3386 1165 -1.04061 -0.0572743 1.54737 1 0 1 1 0 0 +EDGE2 3387 3068 1.01283 -0.0688828 0.0137837 1 0 1 1 0 0 +EDGE2 3387 3148 0.957097 -0.044076 0.00884378 1 0 1 1 0 0 +EDGE2 3387 3147 -0.0409579 -0.0448661 0.0365208 1 0 1 1 0 0 +EDGE2 3387 3067 0.0459688 -0.0412442 -0.0282919 1 0 1 1 0 0 +EDGE2 3387 3146 -1.11214 -0.0636479 -0.0371555 1 0 1 1 0 0 +EDGE2 3387 3386 -0.978474 0.0207532 0.0101403 1 0 1 1 0 0 +EDGE2 3387 3066 -1.06267 0.00946852 -0.00315306 1 0 1 1 0 0 +EDGE2 3388 3149 1.01741 0.00513052 -0.00263658 1 0 1 1 0 0 +EDGE2 3388 3069 0.953841 -0.0663557 -0.0107007 1 0 1 1 0 0 +EDGE2 3388 3068 0.0125628 -0.0415524 -0.00550129 1 0 1 1 0 0 +EDGE2 3388 3148 0.04156 0.036978 -0.0134334 1 0 1 1 0 0 +EDGE2 3388 3147 -1.06541 -0.0793289 -0.00206627 1 0 1 1 0 0 +EDGE2 3388 3387 -0.88978 -0.0632856 -0.0367832 1 0 1 1 0 0 +EDGE2 3388 3067 -1.02806 -0.0753437 0.0291176 1 0 1 1 0 0 +EDGE2 3389 3070 0.985713 0.0301418 0.0166064 1 0 1 1 0 0 +EDGE2 3389 3150 0.978478 0.00506627 -0.000212067 1 0 1 1 0 0 +EDGE2 3389 3149 -0.0156898 -0.0193607 0.000259961 1 0 1 1 0 0 +EDGE2 3389 3069 0.0357497 -0.0361575 -0.0277732 1 0 1 1 0 0 +EDGE2 3389 3068 -0.875271 0.129749 -0.0169403 1 0 1 1 0 0 +EDGE2 3389 3148 -1.00078 0.0508266 0.0106319 1 0 1 1 0 0 +EDGE2 3389 3388 -1.05834 -0.0128343 -0.00632251 1 0 1 1 0 0 +EDGE2 3390 3070 -0.0655428 0.0525738 0.00580457 1 0 1 1 0 0 +EDGE2 3390 3150 -0.0153617 0.0387015 -0.0172295 1 0 1 1 0 0 +EDGE2 3390 3149 -1.05565 -0.0797324 0.00424707 1 0 1 1 0 0 +EDGE2 3390 3389 -0.950407 0.00978582 0.012621 1 0 1 1 0 0 +EDGE2 3390 3069 -1.0659 0.0541445 0.0197337 1 0 1 1 0 0 +EDGE2 3390 3151 -0.0358738 1.0071 1.60285 1 0 1 1 0 0 +EDGE2 3390 3071 0.00866373 0.949157 1.59154 1 0 1 1 0 0 +EDGE2 3391 3070 -1.00036 0.0284318 1.59531 1 0 1 1 0 0 +EDGE2 3391 3390 -1.02752 0.0206685 1.53919 1 0 1 1 0 0 +EDGE2 3391 3150 -1.04363 -0.0437626 1.54927 1 0 1 1 0 0 +EDGE2 3392 3391 -0.975534 -0.0295678 0.0317841 1 0 1 1 0 0 +EDGE2 3393 3392 -0.919601 -0.0825241 0.0291125 1 0 1 1 0 0 +EDGE2 3394 855 1.05589 -0.0951208 -3.12376 1 0 1 1 0 0 +EDGE2 3394 895 0.995904 -0.0825272 -3.14023 1 0 1 1 0 0 +EDGE2 3394 915 0.964833 -0.0472617 -3.17335 1 0 1 1 0 0 +EDGE2 3394 835 0.942947 -0.0140762 -3.16427 1 0 1 1 0 0 +EDGE2 3394 3393 -0.991219 0.0249725 -0.00143127 1 0 1 1 0 0 +EDGE2 3395 916 0.0917136 1.02734 1.5916 1 0 1 1 0 0 +EDGE2 3395 894 1.01624 0.0373565 -3.13831 1 0 1 1 0 0 +EDGE2 3395 914 1.02075 0.000806427 -3.14319 1 0 1 1 0 0 +EDGE2 3395 834 0.968686 -0.0933172 -3.13211 1 0 1 1 0 0 +EDGE2 3395 854 1.07587 -0.00137091 -3.13431 1 0 1 1 0 0 +EDGE2 3395 855 -0.0293184 -0.0207512 -3.14987 1 0 1 1 0 0 +EDGE2 3395 895 -0.0527213 0.0530651 -3.13454 1 0 1 1 0 0 +EDGE2 3395 915 0.0165954 -0.11078 -3.16952 1 0 1 1 0 0 +EDGE2 3395 835 -0.00686329 0.0216802 -3.13933 1 0 1 1 0 0 +EDGE2 3395 3394 -0.95666 -0.0109031 0.00205358 1 0 1 1 0 0 +EDGE2 3395 856 -0.0236701 -1.02243 -1.57863 1 0 1 1 0 0 +EDGE2 3395 896 -0.0250743 -0.975629 -1.57707 1 0 1 1 0 0 +EDGE2 3395 836 0.0250626 -1.0571 -1.5613 1 0 1 1 0 0 +EDGE2 3396 3395 -1.06217 -0.0606417 -1.5533 1 0 1 1 0 0 +EDGE2 3396 917 1.00686 -0.0457794 0.0150496 1 0 1 1 0 0 +EDGE2 3396 916 -0.00528224 0.0225196 0.0070434 1 0 1 1 0 0 +EDGE2 3396 855 -0.95565 0.0119589 1.58393 1 0 1 1 0 0 +EDGE2 3396 895 -1.08253 -0.0140715 1.56205 1 0 1 1 0 0 +EDGE2 3396 915 -0.897175 0.00395089 1.57673 1 0 1 1 0 0 +EDGE2 3396 835 -1.02432 0.0374883 1.5754 1 0 1 1 0 0 +EDGE2 3397 918 0.946631 -0.0529941 0.00313012 1 0 1 1 0 0 +EDGE2 3397 917 -0.0189141 -0.128986 -0.00474872 1 0 1 1 0 0 +EDGE2 3397 3396 -0.9727 -0.00456047 -0.0250277 1 0 1 1 0 0 +EDGE2 3397 916 -0.904153 -0.0135614 0.0279751 1 0 1 1 0 0 +EDGE2 3398 919 1.0469 0.0180062 0.0125369 1 0 1 1 0 0 +EDGE2 3398 918 0.00343091 -0.000567336 -0.00584432 1 0 1 1 0 0 +EDGE2 3398 917 -1.12218 -0.0177975 -0.00817494 1 0 1 1 0 0 +EDGE2 3398 3397 -0.981991 0.028546 -0.0285057 1 0 1 1 0 0 +EDGE2 3399 920 1.03134 -0.0696508 0.0398266 1 0 1 1 0 0 +EDGE2 3399 680 0.999611 -0.0218247 -3.13041 1 0 1 1 0 0 +EDGE2 3399 919 0.0301405 -0.050986 0.0372612 1 0 1 1 0 0 +EDGE2 3399 918 -1.10806 0.0535623 0.0294929 1 0 1 1 0 0 +EDGE2 3399 3398 -0.983723 -0.00390871 -0.0120007 1 0 1 1 0 0 +EDGE2 3400 921 0.0516724 0.966541 1.55394 1 0 1 1 0 0 +EDGE2 3400 679 0.911368 0.0857273 -3.11929 1 0 1 1 0 0 +EDGE2 3400 681 0.100049 -0.950653 -1.58861 1 0 1 1 0 0 +EDGE2 3400 920 -0.0367873 0.0465918 -0.0299306 1 0 1 1 0 0 +EDGE2 3400 680 -0.0644002 -0.096308 -3.15343 1 0 1 1 0 0 +EDGE2 3400 919 -0.908673 0.0244265 0.0165659 1 0 1 1 0 0 +EDGE2 3400 3399 -0.993273 -0.0397095 -0.00217239 1 0 1 1 0 0 +EDGE2 3401 921 0.0166609 0.00821275 -0.00285809 1 0 1 1 0 0 +EDGE2 3401 920 -0.954876 0.0264056 -1.54657 1 0 1 1 0 0 +EDGE2 3401 3400 -0.998462 -0.00417744 -1.53801 1 0 1 1 0 0 +EDGE2 3401 680 -1.03587 0.0784543 1.55646 1 0 1 1 0 0 +EDGE2 3401 922 1.0714 -0.0536678 0.0346021 1 0 1 1 0 0 +EDGE2 3402 921 -1.00469 0.00159018 0.0126598 1 0 1 1 0 0 +EDGE2 3402 3401 -1.06736 0.0233989 -0.00949053 1 0 1 1 0 0 +EDGE2 3402 922 -0.0288594 0.0677877 0.00161051 1 0 1 1 0 0 +EDGE2 3402 923 0.947225 -0.00791903 0.0159537 1 0 1 1 0 0 +EDGE2 3403 3402 -0.959091 0.0393238 0.00701946 1 0 1 1 0 0 +EDGE2 3403 922 -0.974066 -0.0121602 0.0487231 1 0 1 1 0 0 +EDGE2 3403 923 -0.0528692 0.0273822 0.0177115 1 0 1 1 0 0 +EDGE2 3403 924 1.00016 -0.0130555 0.0424957 1 0 1 1 0 0 +EDGE2 3404 923 -1.04428 -0.0284913 -0.00245025 1 0 1 1 0 0 +EDGE2 3404 3403 -1.0094 -0.0638845 0.0142207 1 0 1 1 0 0 +EDGE2 3404 924 0.0866883 -0.0340977 0.03593 1 0 1 1 0 0 +EDGE2 3404 925 1.09536 -0.0517845 -0.0253017 1 0 1 1 0 0 +EDGE2 3405 926 -0.0210083 -1.01816 -1.5877 1 0 1 1 0 0 +EDGE2 3405 924 -0.941447 0.0170879 0.0346982 1 0 1 1 0 0 +EDGE2 3405 3404 -1.06358 0.0597683 0.0197026 1 0 1 1 0 0 +EDGE2 3405 925 -0.028863 -0.0480115 -0.0317395 1 0 1 1 0 0 +EDGE2 3406 925 -0.944971 -0.0473575 -1.58339 1 0 1 1 0 0 +EDGE2 3406 3405 -0.954663 -0.0305872 -1.57771 1 0 1 1 0 0 +EDGE2 3407 3406 -1.0782 -0.0230179 -0.00998839 1 0 1 1 0 0 +EDGE2 3408 3407 -1.04682 0.0294808 0.0345137 1 0 1 1 0 0 +EDGE2 3409 3408 -0.945347 0.08413 -0.036064 1 0 1 1 0 0 +EDGE2 3409 3070 1.03033 -0.100961 -3.15284 1 0 1 1 0 0 +EDGE2 3409 3390 0.967326 0.028541 -3.11686 1 0 1 1 0 0 +EDGE2 3409 3150 0.99244 0.0415025 -3.15687 1 0 1 1 0 0 +EDGE2 3410 3409 -1.04287 0.0219909 -0.00668524 1 0 1 1 0 0 +EDGE2 3410 3391 0.0172617 0.991154 1.54432 1 0 1 1 0 0 +EDGE2 3410 3070 -0.0253029 -0.0157125 -3.16031 1 0 1 1 0 0 +EDGE2 3410 3390 0.0234349 -0.0347723 -3.13382 1 0 1 1 0 0 +EDGE2 3410 3150 -0.0688534 -0.0665098 -3.09966 1 0 1 1 0 0 +EDGE2 3410 3149 1.02954 0.0210792 -3.11641 1 0 1 1 0 0 +EDGE2 3410 3389 1.0473 0.118679 -3.15376 1 0 1 1 0 0 +EDGE2 3410 3069 0.986534 0.0666778 -3.12873 1 0 1 1 0 0 +EDGE2 3410 3151 0.000607088 -1.00455 -1.58561 1 0 1 1 0 0 +EDGE2 3410 3071 -0.0695852 -0.980599 -1.5793 1 0 1 1 0 0 +EDGE2 3411 3392 1.00931 -0.0585103 0.0265679 1 0 1 1 0 0 +EDGE2 3411 3391 0.0608582 0.038445 -0.00785496 1 0 1 1 0 0 +EDGE2 3411 3070 -0.957068 0.0186945 1.58982 1 0 1 1 0 0 +EDGE2 3411 3390 -0.973252 0.0206603 1.58062 1 0 1 1 0 0 +EDGE2 3411 3410 -1.048 0.0639341 -1.57307 1 0 1 1 0 0 +EDGE2 3411 3150 -1.00834 0.0182676 1.59458 1 0 1 1 0 0 +EDGE2 3412 3393 0.958321 0.068769 -0.0190362 1 0 1 1 0 0 +EDGE2 3412 3392 0.0382011 0.0564917 0.0231482 1 0 1 1 0 0 +EDGE2 3412 3411 -0.962864 0.0328067 0.00857779 1 0 1 1 0 0 +EDGE2 3412 3391 -0.944242 0.0172037 0.0183508 1 0 1 1 0 0 +EDGE2 3413 3394 1.04721 0.0368281 0.0396975 1 0 1 1 0 0 +EDGE2 3413 3393 0.113225 0.0401067 0.0297929 1 0 1 1 0 0 +EDGE2 3413 3412 -0.928249 0.0186368 -0.00535374 1 0 1 1 0 0 +EDGE2 3413 3392 -1.07024 -0.00887795 -0.00580409 1 0 1 1 0 0 +EDGE2 3414 3395 1.00163 -0.00906712 -0.000661147 1 0 1 1 0 0 +EDGE2 3414 855 0.974561 -0.00530006 -3.12066 1 0 1 1 0 0 +EDGE2 3414 895 1.00226 -0.0699354 -3.17349 1 0 1 1 0 0 +EDGE2 3414 915 0.92459 -0.000104778 -3.15331 1 0 1 1 0 0 +EDGE2 3414 835 0.916932 0.0586718 -3.11248 1 0 1 1 0 0 +EDGE2 3414 3394 0.0155556 -0.0326351 -0.00923723 1 0 1 1 0 0 +EDGE2 3414 3413 -0.99944 -0.0163876 -0.0115907 1 0 1 1 0 0 +EDGE2 3414 3393 -1.02968 -0.0874383 -0.00238976 1 0 1 1 0 0 +EDGE2 3415 3395 0.0335354 -0.0833286 -0.0147235 1 0 1 1 0 0 +EDGE2 3415 3396 -0.0149579 0.993967 1.57936 1 0 1 1 0 0 +EDGE2 3415 916 -0.0243635 0.989465 1.5774 1 0 1 1 0 0 +EDGE2 3415 894 1.01899 -0.0027424 -3.14843 1 0 1 1 0 0 +EDGE2 3415 914 1.00789 -0.000950768 -3.14274 1 0 1 1 0 0 +EDGE2 3415 834 0.958653 -0.0150604 -3.16819 1 0 1 1 0 0 +EDGE2 3415 854 1.06012 0.0646523 -3.13795 1 0 1 1 0 0 +EDGE2 3415 855 0.00489657 -0.0187569 -3.14595 1 0 1 1 0 0 +EDGE2 3415 895 0.0112048 -0.0148633 -3.13687 1 0 1 1 0 0 +EDGE2 3415 915 -0.00877257 0.0287693 -3.12133 1 0 1 1 0 0 +EDGE2 3415 835 -0.000760634 0.0297685 -3.12132 1 0 1 1 0 0 +EDGE2 3415 3414 -1.00536 0.0206098 -0.0149036 1 0 1 1 0 0 +EDGE2 3415 3394 -0.915787 0.010647 0.00363379 1 0 1 1 0 0 +EDGE2 3415 856 -0.0356257 -0.953368 -1.57527 1 0 1 1 0 0 +EDGE2 3415 896 0.00067825 -1.00225 -1.56232 1 0 1 1 0 0 +EDGE2 3415 836 -0.0780769 -0.994257 -1.55579 1 0 1 1 0 0 +EDGE2 3416 3395 -1.01811 0.0619563 1.59864 1 0 1 1 0 0 +EDGE2 3416 3415 -1.01705 -0.108217 1.55665 1 0 1 1 0 0 +EDGE2 3416 855 -0.917347 0.00190554 -1.55477 1 0 1 1 0 0 +EDGE2 3416 895 -0.974247 -0.0874286 -1.54859 1 0 1 1 0 0 +EDGE2 3416 915 -0.987317 -0.0327778 -1.57122 1 0 1 1 0 0 +EDGE2 3416 835 -0.996786 -0.0505478 -1.56362 1 0 1 1 0 0 +EDGE2 3416 856 -0.0212165 -0.0523759 0.0112629 1 0 1 1 0 0 +EDGE2 3416 896 0.09783 -0.0831 9.49711e-06 1 0 1 1 0 0 +EDGE2 3416 836 0.0133453 -0.0993376 0.0340159 1 0 1 1 0 0 +EDGE2 3416 857 0.963773 -0.0612107 0.00721422 1 0 1 1 0 0 +EDGE2 3416 897 0.955328 0.00737658 -0.00943947 1 0 1 1 0 0 +EDGE2 3416 837 1.1148 -0.0702789 0.019091 1 0 1 1 0 0 +EDGE2 3417 856 -0.938126 0.00329356 -0.0180148 1 0 1 1 0 0 +EDGE2 3417 896 -1.09105 0.0658894 0.0319191 1 0 1 1 0 0 +EDGE2 3417 3416 -0.959563 0.058044 -0.0258181 1 0 1 1 0 0 +EDGE2 3417 836 -0.97646 -0.0352421 0.00077562 1 0 1 1 0 0 +EDGE2 3417 857 -0.0975683 0.0240729 0.0119821 1 0 1 1 0 0 +EDGE2 3417 897 0.0434605 0.036468 0.00658343 1 0 1 1 0 0 +EDGE2 3417 837 -0.0649538 -0.0225943 0.0349222 1 0 1 1 0 0 +EDGE2 3417 858 1.05523 -0.0630876 0.0151077 1 0 1 1 0 0 +EDGE2 3417 898 1.01931 -0.000229994 -0.0186691 1 0 1 1 0 0 +EDGE2 3417 838 1.04189 -0.0425267 0.00433707 1 0 1 1 0 0 +EDGE2 3418 857 -0.931163 -0.070284 -0.0108823 1 0 1 1 0 0 +EDGE2 3418 897 -1.02875 -0.0226672 0.0152638 1 0 1 1 0 0 +EDGE2 3418 3417 -0.941576 -0.0673613 -0.0416441 1 0 1 1 0 0 +EDGE2 3418 837 -1.0095 0.0231822 0.0231996 1 0 1 1 0 0 +EDGE2 3418 858 0.118202 -0.0125383 -0.0241214 1 0 1 1 0 0 +EDGE2 3418 898 -0.0720511 0.0293633 0.0132059 1 0 1 1 0 0 +EDGE2 3418 838 0.0370626 0.0227169 0.0141528 1 0 1 1 0 0 +EDGE2 3418 839 0.970588 -0.0426448 0.0097055 1 0 1 1 0 0 +EDGE2 3418 899 1.00655 0.0997243 -0.0145246 1 0 1 1 0 0 +EDGE2 3418 859 1.03413 -0.0323568 -0.0174621 1 0 1 1 0 0 +EDGE2 3419 858 -1.01694 -0.07218 0.0284997 1 0 1 1 0 0 +EDGE2 3419 898 -0.996181 -0.0416407 -0.0021715 1 0 1 1 0 0 +EDGE2 3419 3418 -0.988597 -0.0861881 -0.0137935 1 0 1 1 0 0 +EDGE2 3419 838 -1.04713 -0.0355042 0.0196931 1 0 1 1 0 0 +EDGE2 3419 839 0.0100692 -0.0440457 -0.00320087 1 0 1 1 0 0 +EDGE2 3419 899 0.00784315 0.0244213 0.0195952 1 0 1 1 0 0 +EDGE2 3419 859 0.0516034 0.0140924 -0.00547916 1 0 1 1 0 0 +EDGE2 3419 1160 1.03733 -0.0484039 -3.16843 1 0 1 1 0 0 +EDGE2 3419 3140 1.04667 -0.0402389 -3.13093 1 0 1 1 0 0 +EDGE2 3419 3380 0.909023 0.0608127 -3.16417 1 0 1 1 0 0 +EDGE2 3419 1200 0.909034 0.00742414 -3.14956 1 0 1 1 0 0 +EDGE2 3419 3100 0.961442 0.0168586 -3.12084 1 0 1 1 0 0 +EDGE2 3419 3120 1.02306 0.00949181 -3.15757 1 0 1 1 0 0 +EDGE2 3419 1180 1.00495 -0.0438206 -3.16261 1 0 1 1 0 0 +EDGE2 3419 900 0.981056 0.0504861 0.0404919 1 0 1 1 0 0 +EDGE2 3419 840 0.95884 0.00868217 0.0130478 1 0 1 1 0 0 +EDGE2 3419 860 0.995587 -0.0458813 -0.0361054 1 0 1 1 0 0 +EDGE2 3420 839 -0.951134 0.00374279 0.0160466 1 0 1 1 0 0 +EDGE2 3420 899 -0.940193 -0.00434285 -0.00439324 1 0 1 1 0 0 +EDGE2 3420 3419 -0.978916 -0.054494 -0.00073043 1 0 1 1 0 0 +EDGE2 3420 859 -0.973969 -0.018627 -0.0143369 1 0 1 1 0 0 +EDGE2 3420 841 -0.0470126 1.01074 1.55056 1 0 1 1 0 0 +EDGE2 3420 901 0.000263228 0.951288 1.56535 1 0 1 1 0 0 +EDGE2 3420 1201 -0.0466443 1.0513 1.56865 1 0 1 1 0 0 +EDGE2 3420 861 0.0568972 0.988281 1.59226 1 0 1 1 0 0 +EDGE2 3420 1160 0.0355278 0.0137208 -3.15114 1 0 1 1 0 0 +EDGE2 3420 3140 -0.0464818 -0.000871368 -3.17264 1 0 1 1 0 0 +EDGE2 3420 3380 -0.0752823 -0.0152428 -3.12385 1 0 1 1 0 0 +EDGE2 3420 1200 -0.0375089 -0.063106 -3.14619 1 0 1 1 0 0 +EDGE2 3420 3100 -0.076763 -0.0365576 -3.13048 1 0 1 1 0 0 +EDGE2 3420 3120 0.0273833 0.0034575 -3.16732 1 0 1 1 0 0 +EDGE2 3420 1180 0.074074 0.0152756 -3.17532 1 0 1 1 0 0 +EDGE2 3420 900 0.0681771 -0.0362947 0.0080619 1 0 1 1 0 0 +EDGE2 3420 840 -0.0366999 -0.0349461 -0.0234009 1 0 1 1 0 0 +EDGE2 3420 860 -0.097476 0.0542482 -0.0278202 1 0 1 1 0 0 +EDGE2 3420 3101 -0.0545344 -1.00842 -1.58633 1 0 1 1 0 0 +EDGE2 3420 3141 -0.00245026 -1.02948 -1.59087 1 0 1 1 0 0 +EDGE2 3420 3381 -0.0333248 -1.00518 -1.56591 1 0 1 1 0 0 +EDGE2 3420 3121 0.0544155 -1.07848 -1.55705 1 0 1 1 0 0 +EDGE2 3420 1161 -0.0781521 -1.04966 -1.59614 1 0 1 1 0 0 +EDGE2 3420 1181 -0.0660221 -1.03591 -1.55818 1 0 1 1 0 0 +EDGE2 3420 3119 1.02839 -0.0673935 -3.16637 1 0 1 1 0 0 +EDGE2 3420 3379 0.984256 -0.0402639 -3.15172 1 0 1 1 0 0 +EDGE2 3420 3139 1.03325 -0.0219349 -3.13608 1 0 1 1 0 0 +EDGE2 3420 1179 1.02706 -0.0613096 -3.15889 1 0 1 1 0 0 +EDGE2 3420 1199 1.01579 -0.0952888 -3.15134 1 0 1 1 0 0 +EDGE2 3420 3099 0.967598 0.00286941 -3.16544 1 0 1 1 0 0 +EDGE2 3420 1159 1.04484 0.0302547 -3.14806 1 0 1 1 0 0 +EDGE2 3421 902 0.988088 -0.0380699 -0.0306329 1 0 1 1 0 0 +EDGE2 3421 1202 0.980426 -0.00524915 0.0466438 1 0 1 1 0 0 +EDGE2 3421 842 1.03562 0.0361822 0.0112182 1 0 1 1 0 0 +EDGE2 3421 862 1.00659 -0.0499494 0.014398 1 0 1 1 0 0 +EDGE2 3421 841 -0.00514989 0.0485977 -0.0232312 1 0 1 1 0 0 +EDGE2 3421 901 0.0230596 -0.0423502 -0.00480281 1 0 1 1 0 0 +EDGE2 3421 1201 -0.00212189 -0.0673372 0.0363816 1 0 1 1 0 0 +EDGE2 3421 861 -0.0178974 -0.0456016 -0.0188891 1 0 1 1 0 0 +EDGE2 3421 1160 -1.02239 0.0530356 1.60255 1 0 1 1 0 0 +EDGE2 3421 3140 -1.04375 -0.0153639 1.59511 1 0 1 1 0 0 +EDGE2 3421 3420 -1.01439 0.00851327 -1.59964 1 0 1 1 0 0 +EDGE2 3421 3380 -0.905479 -0.0175896 1.5787 1 0 1 1 0 0 +EDGE2 3421 1200 -1.0023 -0.0863572 1.58859 1 0 1 1 0 0 +EDGE2 3421 3100 -0.954335 0.080196 1.56825 1 0 1 1 0 0 +EDGE2 3421 3120 -1.02426 0.0653609 1.55935 1 0 1 1 0 0 +EDGE2 3421 1180 -0.936912 0.0194757 1.58064 1 0 1 1 0 0 +EDGE2 3421 900 -0.95965 0.0361828 -1.58841 1 0 1 1 0 0 +EDGE2 3421 840 -1.03913 0.0478977 -1.57383 1 0 1 1 0 0 +EDGE2 3421 860 -0.970152 -0.0509141 -1.54202 1 0 1 1 0 0 +EDGE2 3422 863 1.01054 -0.0020507 0.00431013 1 0 1 1 0 0 +EDGE2 3422 903 1.07183 -0.00419764 -0.0074014 1 0 1 1 0 0 +EDGE2 3422 1203 1.01173 -0.0492044 -0.00192129 1 0 1 1 0 0 +EDGE2 3422 843 0.987192 0.00429477 0.00841768 1 0 1 1 0 0 +EDGE2 3422 902 -0.0316155 0.00472468 -0.019904 1 0 1 1 0 0 +EDGE2 3422 1202 0.0788413 0.0359372 0.0314754 1 0 1 1 0 0 +EDGE2 3422 842 -0.0783874 0.0545358 -0.00151318 1 0 1 1 0 0 +EDGE2 3422 862 0.040759 0.0154551 -0.00348702 1 0 1 1 0 0 +EDGE2 3422 841 -1.00395 0.00284504 -0.0123468 1 0 1 1 0 0 +EDGE2 3422 901 -1.04645 -0.0205524 0.0051275 1 0 1 1 0 0 +EDGE2 3422 1201 -0.921715 0.0958611 -0.0355517 1 0 1 1 0 0 +EDGE2 3422 3421 -1.0341 -0.00305788 -0.00764809 1 0 1 1 0 0 +EDGE2 3422 861 -0.976019 -0.031421 0.0143634 1 0 1 1 0 0 +EDGE2 3423 864 0.950513 -0.0179339 -0.0157424 1 0 1 1 0 0 +EDGE2 3423 1204 1.05766 0.0137123 0.0289128 1 0 1 1 0 0 +EDGE2 3423 904 0.942828 -0.0605994 -0.0383919 1 0 1 1 0 0 +EDGE2 3423 844 0.982005 -0.115191 0.00336414 1 0 1 1 0 0 +EDGE2 3423 863 -0.0168527 0.0200283 -0.054105 1 0 1 1 0 0 +EDGE2 3423 903 -0.000914666 0.00940549 0.0218782 1 0 1 1 0 0 +EDGE2 3423 1203 0.0484729 -0.00964241 0.015398 1 0 1 1 0 0 +EDGE2 3423 843 0.0376749 -0.0458516 0.0258665 1 0 1 1 0 0 +EDGE2 3423 902 -1.01287 -0.0443071 -0.0141583 1 0 1 1 0 0 +EDGE2 3423 3422 -0.999929 0.0277096 -0.019067 1 0 1 1 0 0 +EDGE2 3423 1202 -0.938782 -0.00879898 0.0112707 1 0 1 1 0 0 +EDGE2 3423 842 -0.948147 -0.054405 0.02446 1 0 1 1 0 0 +EDGE2 3423 862 -0.946711 -0.00521558 -0.00534747 1 0 1 1 0 0 +EDGE2 3424 865 0.964272 -0.120359 0.00586776 1 0 1 1 0 0 +EDGE2 3424 3225 0.983492 0.0777784 -3.1104 1 0 1 1 0 0 +EDGE2 3424 3365 1.03028 0.00387206 -3.13193 1 0 1 1 0 0 +EDGE2 3424 1205 0.940413 0.0139176 0.0260468 1 0 1 1 0 0 +EDGE2 3424 3205 0.967455 -0.0934466 -3.16412 1 0 1 1 0 0 +EDGE2 3424 905 0.916867 0.0910882 -0.0222611 1 0 1 1 0 0 +EDGE2 3424 864 -0.0214451 0.0590892 -0.00199847 1 0 1 1 0 0 +EDGE2 3424 705 0.973571 0.0850233 -3.14505 1 0 1 1 0 0 +EDGE2 3424 825 1.01126 -0.0532799 -3.16843 1 0 1 1 0 0 +EDGE2 3424 845 1.0298 -0.0182968 -0.0262285 1 0 1 1 0 0 +EDGE2 3424 1204 -0.070166 -0.043058 0.0194779 1 0 1 1 0 0 +EDGE2 3424 904 0.016583 0.0325368 0.0149566 1 0 1 1 0 0 +EDGE2 3424 3423 -1.05681 -0.0388449 -0.0048856 1 0 1 1 0 0 +EDGE2 3424 844 0.0605233 -0.0135555 0.0119435 1 0 1 1 0 0 +EDGE2 3424 863 -0.979578 -0.0186143 0.00785277 1 0 1 1 0 0 +EDGE2 3424 903 -1.1078 -0.0114512 -0.00947497 1 0 1 1 0 0 +EDGE2 3424 1203 -0.950453 0.068451 0.00152038 1 0 1 1 0 0 +EDGE2 3424 843 -1.06276 -0.00342097 0.022149 1 0 1 1 0 0 +EDGE2 3425 3364 1.01613 0.0162807 -3.16821 1 0 1 1 0 0 +EDGE2 3425 824 0.968438 -0.0679913 -3.13684 1 0 1 1 0 0 +EDGE2 3425 3204 1.0672 -0.0514963 -3.14345 1 0 1 1 0 0 +EDGE2 3425 3224 1.04091 -0.00491291 -3.13732 1 0 1 1 0 0 +EDGE2 3425 704 1.04304 0.0072369 -3.16717 1 0 1 1 0 0 +EDGE2 3425 865 0.0244687 -0.0166462 0.0348115 1 0 1 1 0 0 +EDGE2 3425 3225 -0.0533394 -0.0980309 -3.14316 1 0 1 1 0 0 +EDGE2 3425 826 -0.0379172 0.946253 1.55953 1 0 1 1 0 0 +EDGE2 3425 866 0.0932579 0.967493 1.56601 1 0 1 1 0 0 +EDGE2 3425 906 -0.022526 0.94467 1.59037 1 0 1 1 0 0 +EDGE2 3425 846 -0.0522809 1.00779 1.57687 1 0 1 1 0 0 +EDGE2 3425 3365 -4.64401e-05 0.0208005 -3.10227 1 0 1 1 0 0 +EDGE2 3425 1205 0.0289469 0.0492286 0.000552931 1 0 1 1 0 0 +EDGE2 3425 3205 -0.106195 0.0189779 -3.09128 1 0 1 1 0 0 +EDGE2 3425 905 -0.0963274 -0.0129576 -0.0128514 1 0 1 1 0 0 +EDGE2 3425 864 -1.09294 0.013769 -0.00070046 1 0 1 1 0 0 +EDGE2 3425 705 0.0118128 -0.0044498 -3.14806 1 0 1 1 0 0 +EDGE2 3425 825 0.0231294 -0.0648478 -3.15271 1 0 1 1 0 0 +EDGE2 3425 845 -0.0396596 -0.0262796 0.0138996 1 0 1 1 0 0 +EDGE2 3425 1204 -0.973439 0.0563276 0.0113187 1 0 1 1 0 0 +EDGE2 3425 3424 -1.05282 0.0727704 -0.0198073 1 0 1 1 0 0 +EDGE2 3425 904 -1.0048 0.0198336 0.0190399 1 0 1 1 0 0 +EDGE2 3425 844 -0.944961 0.0165658 -5.49212e-05 1 0 1 1 0 0 +EDGE2 3425 1206 0.0215809 -0.974352 -1.53189 1 0 1 1 0 0 +EDGE2 3425 3226 -0.0883788 -0.919252 -1.60586 1 0 1 1 0 0 +EDGE2 3425 3366 0.018927 -1.04188 -1.57231 1 0 1 1 0 0 +EDGE2 3425 3206 -0.0175665 -1.02333 -1.56177 1 0 1 1 0 0 +EDGE2 3425 706 0.0945982 -1.0661 -1.56611 1 0 1 1 0 0 +EDGE2 3426 865 -0.945427 -0.0409499 -1.55553 1 0 1 1 0 0 +EDGE2 3426 847 1.01768 0.0361553 -0.0437981 1 0 1 1 0 0 +EDGE2 3426 867 0.962168 0.00181792 0.00476779 1 0 1 1 0 0 +EDGE2 3426 907 0.956282 0.0353351 0.0199791 1 0 1 1 0 0 +EDGE2 3426 827 0.962801 -0.0303619 0.0114724 1 0 1 1 0 0 +EDGE2 3426 3225 -1.03751 0.0188429 1.58978 1 0 1 1 0 0 +EDGE2 3426 826 0.0736719 -0.00899939 0.0152512 1 0 1 1 0 0 +EDGE2 3426 866 -0.0502787 -0.0110406 -0.0114562 1 0 1 1 0 0 +EDGE2 3426 906 -0.0358199 -0.0136902 0.0113331 1 0 1 1 0 0 +EDGE2 3426 846 0.0770213 -0.0069397 -0.00775435 1 0 1 1 0 0 +EDGE2 3426 3425 -1.11778 0.0203819 -1.58231 1 0 1 1 0 0 +EDGE2 3426 3365 -0.97803 0.0762911 1.55762 1 0 1 1 0 0 +EDGE2 3426 1205 -1.04342 0.090101 -1.57114 1 0 1 1 0 0 +EDGE2 3426 3205 -0.986631 -0.00953406 1.5885 1 0 1 1 0 0 +EDGE2 3426 905 -0.899967 -0.00156728 -1.59504 1 0 1 1 0 0 +EDGE2 3426 705 -1.08591 0.0258625 1.52733 1 0 1 1 0 0 +EDGE2 3426 825 -0.995805 0.00907461 1.56235 1 0 1 1 0 0 +EDGE2 3426 845 -1.06968 0.0742964 -1.54801 1 0 1 1 0 0 +EDGE2 3427 908 1.05374 -0.0146174 -0.00811859 1 0 1 1 0 0 +EDGE2 3427 828 1.03879 0.0105919 -0.0370506 1 0 1 1 0 0 +EDGE2 3427 848 1.00318 -0.0660323 -0.0105601 1 0 1 1 0 0 +EDGE2 3427 868 0.996779 0.0459858 -0.0140271 1 0 1 1 0 0 +EDGE2 3427 847 -0.0380165 -0.0334161 -0.05581 1 0 1 1 0 0 +EDGE2 3427 867 0.0620566 -0.0442485 -0.0192459 1 0 1 1 0 0 +EDGE2 3427 907 0.0619665 0.0251213 0.00357816 1 0 1 1 0 0 +EDGE2 3427 827 0.0192194 -0.0278295 0.00204497 1 0 1 1 0 0 +EDGE2 3427 826 -1.05332 -0.008591 0.0108303 1 0 1 1 0 0 +EDGE2 3427 866 -0.992048 -0.0105094 0.0168173 1 0 1 1 0 0 +EDGE2 3427 906 -0.90463 -0.0113476 -0.0314726 1 0 1 1 0 0 +EDGE2 3427 3426 -1.00531 -0.108404 0.0342261 1 0 1 1 0 0 +EDGE2 3427 846 -0.920565 0.0419081 -0.0237912 1 0 1 1 0 0 +EDGE2 3428 908 0.0231079 0.0890665 0.017798 1 0 1 1 0 0 +EDGE2 3428 869 1.00472 -0.0518443 -0.0148624 1 0 1 1 0 0 +EDGE2 3428 909 0.995376 0.0156743 0.0129955 1 0 1 1 0 0 +EDGE2 3428 829 0.943354 -0.0309285 0.0241399 1 0 1 1 0 0 +EDGE2 3428 849 0.981378 0.024805 0.0156077 1 0 1 1 0 0 +EDGE2 3428 3427 -0.947705 -0.0711547 0.0102821 1 0 1 1 0 0 +EDGE2 3428 828 -0.0308747 0.0488741 0.000702468 1 0 1 1 0 0 +EDGE2 3428 848 0.0129269 -0.0269783 0.0163673 1 0 1 1 0 0 +EDGE2 3428 868 0.0382624 0.0977362 0.0233879 1 0 1 1 0 0 +EDGE2 3428 847 -0.998706 0.0163183 -0.0304168 1 0 1 1 0 0 +EDGE2 3428 867 -1.04607 -0.0389746 0.0118622 1 0 1 1 0 0 +EDGE2 3428 907 -0.972429 -0.0738832 -0.0215067 1 0 1 1 0 0 +EDGE2 3428 827 -0.986558 -0.0479678 0.0189306 1 0 1 1 0 0 +EDGE2 3429 908 -1.05439 0.0578386 0.014729 1 0 1 1 0 0 +EDGE2 3429 690 0.93859 -0.0585677 -3.15689 1 0 1 1 0 0 +EDGE2 3429 910 1.01482 0.0316084 -0.0120128 1 0 1 1 0 0 +EDGE2 3429 850 1.0535 0.0565767 0.00528687 1 0 1 1 0 0 +EDGE2 3429 870 1.02046 0.0517409 0.0223423 1 0 1 1 0 0 +EDGE2 3429 890 0.962349 -0.00209133 -3.11868 1 0 1 1 0 0 +EDGE2 3429 830 1.02633 0.0923208 -0.0129117 1 0 1 1 0 0 +EDGE2 3429 869 -0.0154185 -0.0723601 -0.000520814 1 0 1 1 0 0 +EDGE2 3429 909 0.0917995 -0.0103072 -0.00940717 1 0 1 1 0 0 +EDGE2 3429 829 -0.101582 0.054733 -0.00955048 1 0 1 1 0 0 +EDGE2 3429 849 -0.0352253 0.0423247 0.0196264 1 0 1 1 0 0 +EDGE2 3429 3428 -1.02822 -0.0383298 0.0259205 1 0 1 1 0 0 +EDGE2 3429 828 -1.02698 -0.00785402 0.0083193 1 0 1 1 0 0 +EDGE2 3429 848 -0.991269 -0.0681033 0.0123905 1 0 1 1 0 0 +EDGE2 3429 868 -0.973051 0.0114225 -0.0153894 1 0 1 1 0 0 +EDGE2 3430 691 0.0127888 -0.964117 -1.6038 1 0 1 1 0 0 +EDGE2 3430 871 0.00418307 -0.904228 -1.56163 1 0 1 1 0 0 +EDGE2 3430 690 0.000143178 -0.0209047 -3.15431 1 0 1 1 0 0 +EDGE2 3430 910 -0.00600279 0.0122219 0.0487318 1 0 1 1 0 0 +EDGE2 3430 689 1.03856 -0.0715451 -3.15243 1 0 1 1 0 0 +EDGE2 3430 889 1.08699 0.0457572 -3.14557 1 0 1 1 0 0 +EDGE2 3430 850 0.0688335 -0.00995606 0.00734953 1 0 1 1 0 0 +EDGE2 3430 870 -0.0292099 0.028403 0.00166722 1 0 1 1 0 0 +EDGE2 3430 890 0.0556038 0.0792037 -3.14681 1 0 1 1 0 0 +EDGE2 3430 830 -0.0670947 0.0604285 -0.00947933 1 0 1 1 0 0 +EDGE2 3430 851 0.0224016 0.94335 1.55608 1 0 1 1 0 0 +EDGE2 3430 911 -0.021819 1.02586 1.5502 1 0 1 1 0 0 +EDGE2 3430 891 0.0218421 0.934923 1.56275 1 0 1 1 0 0 +EDGE2 3430 831 -0.028586 1.04406 1.54897 1 0 1 1 0 0 +EDGE2 3430 869 -0.932183 0.0231821 -0.00844463 1 0 1 1 0 0 +EDGE2 3430 3429 -1.03148 0.10027 0.0177931 1 0 1 1 0 0 +EDGE2 3430 909 -0.951642 0.00601709 0.0079817 1 0 1 1 0 0 +EDGE2 3430 829 -1.07602 0.00269111 -0.0153135 1 0 1 1 0 0 +EDGE2 3430 849 -0.945106 0.0369531 0.00703255 1 0 1 1 0 0 +EDGE2 3431 690 -1.08146 -0.0431147 1.54285 1 0 1 1 0 0 +EDGE2 3431 910 -0.969239 0.0116813 -1.56712 1 0 1 1 0 0 +EDGE2 3431 3430 -1.03658 -0.0362924 -1.56291 1 0 1 1 0 0 +EDGE2 3431 850 -1.05222 -0.0164221 -1.55076 1 0 1 1 0 0 +EDGE2 3431 870 -1.05492 0.00445838 -1.58908 1 0 1 1 0 0 +EDGE2 3431 890 -0.995596 -0.0177964 1.56224 1 0 1 1 0 0 +EDGE2 3431 830 -1.05289 -0.0554889 -1.58608 1 0 1 1 0 0 +EDGE2 3431 892 1.06494 -0.0774346 0.0197743 1 0 1 1 0 0 +EDGE2 3431 851 0.0104174 -0.00630274 0.0166558 1 0 1 1 0 0 +EDGE2 3431 911 0.0539823 -0.00207721 -0.0359542 1 0 1 1 0 0 +EDGE2 3431 891 -0.00827396 -0.0513819 -0.00476558 1 0 1 1 0 0 +EDGE2 3431 831 -0.110058 -0.0717484 -0.0111938 1 0 1 1 0 0 +EDGE2 3431 912 0.979934 -0.0160743 0.0396558 1 0 1 1 0 0 +EDGE2 3431 832 0.977188 0.0135554 -0.0505501 1 0 1 1 0 0 +EDGE2 3431 852 1.0198 -0.0409526 0.00867094 1 0 1 1 0 0 +EDGE2 3432 892 0.0989236 -0.0817642 -0.0188799 1 0 1 1 0 0 +EDGE2 3432 851 -0.920068 0.0447672 0.0229806 1 0 1 1 0 0 +EDGE2 3432 911 -0.99415 -0.0566618 -0.00735129 1 0 1 1 0 0 +EDGE2 3432 3431 -0.986736 -0.0507842 -0.00830605 1 0 1 1 0 0 +EDGE2 3432 891 -0.940179 -0.0550034 -0.0126487 1 0 1 1 0 0 +EDGE2 3432 831 -1.02758 0.0168156 -0.0374527 1 0 1 1 0 0 +EDGE2 3432 912 0.00725194 0.0473286 0.00604729 1 0 1 1 0 0 +EDGE2 3432 913 0.936982 -0.0331521 0.0383852 1 0 1 1 0 0 +EDGE2 3432 832 -0.0418099 -0.0463782 -0.0123552 1 0 1 1 0 0 +EDGE2 3432 852 -0.0394228 0.00100315 0.00885967 1 0 1 1 0 0 +EDGE2 3432 833 0.974329 -0.0466314 -0.0303857 1 0 1 1 0 0 +EDGE2 3432 853 0.876303 -0.00444473 -0.00907942 1 0 1 1 0 0 +EDGE2 3432 893 0.871009 -0.0301121 0.0206497 1 0 1 1 0 0 +EDGE2 3433 892 -1.04886 0.0224442 -0.0266949 1 0 1 1 0 0 +EDGE2 3433 3432 -0.964543 0.0110302 0.0281746 1 0 1 1 0 0 +EDGE2 3433 912 -0.964101 0.0710219 0.0115915 1 0 1 1 0 0 +EDGE2 3433 913 -0.00235751 -0.0535995 -0.016892 1 0 1 1 0 0 +EDGE2 3433 832 -0.990097 0.0328459 -0.0481928 1 0 1 1 0 0 +EDGE2 3433 852 -0.971005 -0.00182951 0.0203368 1 0 1 1 0 0 +EDGE2 3433 833 -0.0549811 -0.0500181 0.00299713 1 0 1 1 0 0 +EDGE2 3433 853 -0.0449575 0.0596193 -0.00200675 1 0 1 1 0 0 +EDGE2 3433 893 -0.0222872 -0.00426401 0.0141331 1 0 1 1 0 0 +EDGE2 3433 894 0.99675 -0.0750873 -0.0112724 1 0 1 1 0 0 +EDGE2 3433 914 1.0674 -0.00959651 0.0185132 1 0 1 1 0 0 +EDGE2 3433 834 1.0085 -0.000603539 0.0169412 1 0 1 1 0 0 +EDGE2 3433 854 1.02107 -0.00431776 -0.00919702 1 0 1 1 0 0 +EDGE2 3434 3395 0.923003 -0.0311979 -3.15135 1 0 1 1 0 0 +EDGE2 3434 913 -0.976227 0.0571626 -0.0203607 1 0 1 1 0 0 +EDGE2 3434 3433 -0.935327 -0.0449296 -0.0282148 1 0 1 1 0 0 +EDGE2 3434 833 -1.09211 0.0842365 0.0177349 1 0 1 1 0 0 +EDGE2 3434 853 -1.0267 0.022626 0.00666365 1 0 1 1 0 0 +EDGE2 3434 893 -1.0047 0.00413902 0.00682742 1 0 1 1 0 0 +EDGE2 3434 894 0.0215405 -0.0126157 -0.0354673 1 0 1 1 0 0 +EDGE2 3434 914 0.067797 -0.0155203 0.00478873 1 0 1 1 0 0 +EDGE2 3434 834 0.0274022 -0.0113078 0.00406689 1 0 1 1 0 0 +EDGE2 3434 854 0.0123193 0.0185475 0.0263776 1 0 1 1 0 0 +EDGE2 3434 3415 0.974835 0.0142201 -3.14694 1 0 1 1 0 0 +EDGE2 3434 855 1.0008 -0.0442503 0.00414387 1 0 1 1 0 0 +EDGE2 3434 895 0.999811 0.034961 0.00320139 1 0 1 1 0 0 +EDGE2 3434 915 1.01695 0.0276027 0.0200965 1 0 1 1 0 0 +EDGE2 3434 835 1.05309 -0.0817399 0.0109067 1 0 1 1 0 0 +EDGE2 3435 3395 0.0456288 -0.0173608 -3.15077 1 0 1 1 0 0 +EDGE2 3435 3396 0.0099141 -1.0708 -1.57153 1 0 1 1 0 0 +EDGE2 3435 916 -0.064705 -1.03901 -1.55266 1 0 1 1 0 0 +EDGE2 3435 3434 -1.03249 -0.0606642 -0.00598467 1 0 1 1 0 0 +EDGE2 3435 894 -1.01071 0.0326013 -0.0361978 1 0 1 1 0 0 +EDGE2 3435 914 -1.06454 -0.0284244 -0.0180914 1 0 1 1 0 0 +EDGE2 3435 834 -0.934346 0.0552364 -0.00808676 1 0 1 1 0 0 +EDGE2 3435 854 -1.03625 0.0348388 -0.00304501 1 0 1 1 0 0 +EDGE2 3435 3415 -0.0198435 -0.0309589 -3.15752 1 0 1 1 0 0 +EDGE2 3435 855 -0.00322877 -0.0400195 0.0173753 1 0 1 1 0 0 +EDGE2 3435 895 -0.0683824 0.014062 0.0146767 1 0 1 1 0 0 +EDGE2 3435 915 -0.0754289 -0.0248832 0.00777447 1 0 1 1 0 0 +EDGE2 3435 835 -0.0727665 -0.00308296 0.00385801 1 0 1 1 0 0 +EDGE2 3435 3414 0.948998 -0.00575657 -3.15929 1 0 1 1 0 0 +EDGE2 3435 3394 0.979777 -0.047607 -3.13279 1 0 1 1 0 0 +EDGE2 3435 856 -0.0296564 1.14229 1.57883 1 0 1 1 0 0 +EDGE2 3435 896 0.113013 0.93809 1.57136 1 0 1 1 0 0 +EDGE2 3435 3416 -0.0403425 1.07559 1.60417 1 0 1 1 0 0 +EDGE2 3435 836 -0.0442324 0.958094 1.54885 1 0 1 1 0 0 +EDGE2 3436 3395 -0.995398 -0.122208 1.59182 1 0 1 1 0 0 +EDGE2 3436 3435 -1.00005 -0.0431908 -1.59359 1 0 1 1 0 0 +EDGE2 3436 3415 -0.942135 -0.0140804 1.56293 1 0 1 1 0 0 +EDGE2 3436 855 -1.06128 0.0265168 -1.58048 1 0 1 1 0 0 +EDGE2 3436 895 -0.916147 -0.0551288 -1.5877 1 0 1 1 0 0 +EDGE2 3436 915 -1.02317 -0.0125318 -1.57199 1 0 1 1 0 0 +EDGE2 3436 835 -0.987034 -0.0252013 -1.53326 1 0 1 1 0 0 +EDGE2 3436 856 0.0679212 -0.0252629 0.0104581 1 0 1 1 0 0 +EDGE2 3436 896 -0.0421457 0.132755 -0.0328051 1 0 1 1 0 0 +EDGE2 3436 3416 -0.0576883 -0.0120543 0.01332 1 0 1 1 0 0 +EDGE2 3436 836 -0.0475917 0.0149376 -0.0145098 1 0 1 1 0 0 +EDGE2 3436 857 0.977022 -0.0021095 -0.0183089 1 0 1 1 0 0 +EDGE2 3436 897 0.974716 0.0189092 0.0138343 1 0 1 1 0 0 +EDGE2 3436 3417 1.00681 -0.0345923 0.0137479 1 0 1 1 0 0 +EDGE2 3436 837 0.994399 -0.0099827 -0.0559818 1 0 1 1 0 0 +EDGE2 3437 3436 -1.10067 -0.0963355 0.012867 1 0 1 1 0 0 +EDGE2 3437 856 -0.930403 -0.045519 -0.0138363 1 0 1 1 0 0 +EDGE2 3437 896 -1.07859 0.0697699 0.00514668 1 0 1 1 0 0 +EDGE2 3437 3416 -0.998437 -0.0597796 0.00648506 1 0 1 1 0 0 +EDGE2 3437 836 -0.968913 -0.0383262 -0.0144384 1 0 1 1 0 0 +EDGE2 3437 857 -0.0791536 0.00695925 0.00566912 1 0 1 1 0 0 +EDGE2 3437 897 0.0447767 -0.0311827 -0.00742327 1 0 1 1 0 0 +EDGE2 3437 3417 -0.0556578 0.049127 -0.00307693 1 0 1 1 0 0 +EDGE2 3437 837 -0.0403511 -0.0713507 -0.0250834 1 0 1 1 0 0 +EDGE2 3437 858 1.06936 -0.00751014 -0.0146918 1 0 1 1 0 0 +EDGE2 3437 898 0.935577 -0.0836817 -0.0431114 1 0 1 1 0 0 +EDGE2 3437 3418 1.00778 -0.0507572 -0.022457 1 0 1 1 0 0 +EDGE2 3437 838 0.966822 0.0186052 -0.0190464 1 0 1 1 0 0 +EDGE2 3438 3437 -1.00653 0.00862939 -0.0267398 1 0 1 1 0 0 +EDGE2 3438 857 -0.991416 -0.0255791 0.0314738 1 0 1 1 0 0 +EDGE2 3438 897 -0.975158 -0.0520502 -0.0149369 1 0 1 1 0 0 +EDGE2 3438 3417 -0.959277 -0.0263118 0.00606962 1 0 1 1 0 0 +EDGE2 3438 837 -0.903611 -0.0340574 -0.00640756 1 0 1 1 0 0 +EDGE2 3438 858 -0.0510861 0.000989573 -0.0311029 1 0 1 1 0 0 +EDGE2 3438 898 0.028241 0.0411578 -0.0190085 1 0 1 1 0 0 +EDGE2 3438 3418 -0.0112209 -0.0512828 0.0170756 1 0 1 1 0 0 +EDGE2 3438 838 0.0927619 -0.0709593 -0.0277689 1 0 1 1 0 0 +EDGE2 3438 839 0.98711 -0.0322467 0.0198031 1 0 1 1 0 0 +EDGE2 3438 899 1.12514 -0.00349203 0.000178948 1 0 1 1 0 0 +EDGE2 3438 3419 1.03971 -0.0176284 -0.034647 1 0 1 1 0 0 +EDGE2 3438 859 0.978715 -0.0138656 0.00364251 1 0 1 1 0 0 +EDGE2 3439 3438 -0.945512 0.013959 0.0204976 1 0 1 1 0 0 +EDGE2 3439 858 -0.992791 -0.0384943 -0.0202967 1 0 1 1 0 0 +EDGE2 3439 898 -0.876706 0.0376825 -0.00775492 1 0 1 1 0 0 +EDGE2 3439 3418 -0.990748 -0.068259 -0.0178319 1 0 1 1 0 0 +EDGE2 3439 838 -0.934888 -0.17103 0.0175726 1 0 1 1 0 0 +EDGE2 3439 839 0.0602486 -0.000100604 -0.0150221 1 0 1 1 0 0 +EDGE2 3439 899 -0.0365671 -0.0491478 0.0182323 1 0 1 1 0 0 +EDGE2 3439 3419 -0.0493998 -0.0165346 0.00375826 1 0 1 1 0 0 +EDGE2 3439 859 0.00661963 -0.0465338 -0.00328987 1 0 1 1 0 0 +EDGE2 3439 1160 0.942427 -0.0215223 -3.13783 1 0 1 1 0 0 +EDGE2 3439 3140 1.00852 -0.104373 -3.175 1 0 1 1 0 0 +EDGE2 3439 3420 0.989985 -0.0366953 -0.0108567 1 0 1 1 0 0 +EDGE2 3439 3380 0.931015 -0.0396395 -3.15667 1 0 1 1 0 0 +EDGE2 3439 1200 0.969474 0.0172075 -3.12032 1 0 1 1 0 0 +EDGE2 3439 3100 1.07165 -0.0314332 -3.11947 1 0 1 1 0 0 +EDGE2 3439 3120 0.975113 0.0158424 -3.15261 1 0 1 1 0 0 +EDGE2 3439 1180 0.856888 -0.0164593 -3.14892 1 0 1 1 0 0 +EDGE2 3439 900 1.08311 -0.0438338 -0.0170415 1 0 1 1 0 0 +EDGE2 3439 840 0.989783 -0.000498718 0.0158862 1 0 1 1 0 0 +EDGE2 3439 860 0.916764 0.0361082 -0.040353 1 0 1 1 0 0 +EDGE2 3440 839 -0.970474 -0.00601863 0.011312 1 0 1 1 0 0 +EDGE2 3440 899 -1.0481 -0.0461919 -0.0150749 1 0 1 1 0 0 +EDGE2 3440 3419 -1.05648 -0.0428958 -0.0004479 1 0 1 1 0 0 +EDGE2 3440 3439 -0.956558 0.0581914 -0.00813257 1 0 1 1 0 0 +EDGE2 3440 859 -1.04108 -0.00528957 0.00887971 1 0 1 1 0 0 +EDGE2 3440 841 0.00423295 1.06965 1.58912 1 0 1 1 0 0 +EDGE2 3440 901 0.0193209 0.955511 1.52502 1 0 1 1 0 0 +EDGE2 3440 1201 -0.0045824 1.02834 1.56117 1 0 1 1 0 0 +EDGE2 3440 3421 0.071823 0.91848 1.55097 1 0 1 1 0 0 +EDGE2 3440 861 0.104473 1.00059 1.57729 1 0 1 1 0 0 +EDGE2 3440 1160 -0.0932167 0.0321592 -3.13453 1 0 1 1 0 0 +EDGE2 3440 3140 -0.0246525 0.0397741 -3.14583 1 0 1 1 0 0 +EDGE2 3440 3420 0.00387214 0.0652901 0.0172518 1 0 1 1 0 0 +EDGE2 3440 3380 -0.0509325 0.000415616 -3.12693 1 0 1 1 0 0 +EDGE2 3440 1200 -0.0514002 -0.0150454 -3.13958 1 0 1 1 0 0 +EDGE2 3440 3100 -0.027186 -0.0676727 -3.12971 1 0 1 1 0 0 +EDGE2 3440 3120 0.0239236 -0.0210025 -3.1521 1 0 1 1 0 0 +EDGE2 3440 1180 0.0212755 0.0218023 -3.11301 1 0 1 1 0 0 +EDGE2 3440 900 -0.0908506 0.0628578 0.00893972 1 0 1 1 0 0 +EDGE2 3440 840 0.00243765 0.0836041 -0.000978631 1 0 1 1 0 0 +EDGE2 3440 860 -0.00983266 -0.0876798 0.00837498 1 0 1 1 0 0 +EDGE2 3440 3101 0.0415167 -1.03305 -1.56136 1 0 1 1 0 0 +EDGE2 3440 3141 0.0660441 -1.0623 -1.5244 1 0 1 1 0 0 +EDGE2 3440 3381 0.0289164 -1.023 -1.5602 1 0 1 1 0 0 +EDGE2 3440 3121 -0.0859015 -0.886392 -1.55356 1 0 1 1 0 0 +EDGE2 3440 1161 -0.0382015 -1.12947 -1.5765 1 0 1 1 0 0 +EDGE2 3440 1181 0.12995 -1.0672 -1.58478 1 0 1 1 0 0 +EDGE2 3440 3119 0.975071 -0.0492362 -3.13739 1 0 1 1 0 0 +EDGE2 3440 3379 1.02956 -0.0409992 -3.12924 1 0 1 1 0 0 +EDGE2 3440 3139 1.0542 0.0592769 -3.16203 1 0 1 1 0 0 +EDGE2 3440 1179 0.991553 -0.0139166 -3.14296 1 0 1 1 0 0 +EDGE2 3440 1199 0.953908 -0.047983 -3.1246 1 0 1 1 0 0 +EDGE2 3440 3099 0.920353 0.00273267 -3.12314 1 0 1 1 0 0 +EDGE2 3440 1159 1.03279 -0.0202017 -3.16086 1 0 1 1 0 0 +EDGE2 3441 902 0.969258 0.0424004 -0.0162884 1 0 1 1 0 0 +EDGE2 3441 3422 0.99109 -0.0294883 0.0366908 1 0 1 1 0 0 +EDGE2 3441 1202 1.04421 0.000464025 -0.0136092 1 0 1 1 0 0 +EDGE2 3441 842 0.936046 -0.0506101 -0.0229292 1 0 1 1 0 0 +EDGE2 3441 862 1.04661 -0.0729535 -0.0252319 1 0 1 1 0 0 +EDGE2 3441 841 0.0242081 0.0239652 -0.000507642 1 0 1 1 0 0 +EDGE2 3441 901 -0.0983226 0.00420563 -0.0270392 1 0 1 1 0 0 +EDGE2 3441 1201 -0.0693858 -0.0765543 -0.0118948 1 0 1 1 0 0 +EDGE2 3441 3421 0.0179379 0.0649072 -0.00887874 1 0 1 1 0 0 +EDGE2 3441 861 0.00549875 0.0708171 0.0420368 1 0 1 1 0 0 +EDGE2 3441 1160 -0.992374 -0.0241709 1.57361 1 0 1 1 0 0 +EDGE2 3441 3140 -1.02179 -0.0368947 1.56015 1 0 1 1 0 0 +EDGE2 3441 3420 -1.04069 -0.0689865 -1.56336 1 0 1 1 0 0 +EDGE2 3441 3440 -1.02434 0.0312744 -1.56905 1 0 1 1 0 0 +EDGE2 3441 3380 -0.999852 0.0476675 1.56978 1 0 1 1 0 0 +EDGE2 3441 1200 -1.04755 -0.0150504 1.61422 1 0 1 1 0 0 +EDGE2 3441 3100 -1.04877 0.0198169 1.58954 1 0 1 1 0 0 +EDGE2 3441 3120 -0.902636 -0.0814489 1.5874 1 0 1 1 0 0 +EDGE2 3441 1180 -0.982459 0.0169624 1.56386 1 0 1 1 0 0 +EDGE2 3441 900 -0.990811 0.0209784 -1.56102 1 0 1 1 0 0 +EDGE2 3441 840 -0.95648 0.0274646 -1.55247 1 0 1 1 0 0 +EDGE2 3441 860 -0.9514 0.0226507 -1.58654 1 0 1 1 0 0 +EDGE2 3442 3423 1.01304 0.0404834 0.0127201 1 0 1 1 0 0 +EDGE2 3442 863 1.05087 -0.0459691 0.0397139 1 0 1 1 0 0 +EDGE2 3442 903 1.07713 0.06047 0.0163413 1 0 1 1 0 0 +EDGE2 3442 1203 0.993894 0.0584993 -0.0100898 1 0 1 1 0 0 +EDGE2 3442 843 0.960243 -0.02295 -0.0207022 1 0 1 1 0 0 +EDGE2 3442 3441 -1.09987 -0.0540951 -0.00542154 1 0 1 1 0 0 +EDGE2 3442 902 -0.0864853 0.023062 -0.000222738 1 0 1 1 0 0 +EDGE2 3442 3422 -0.0347764 0.0769199 0.026025 1 0 1 1 0 0 +EDGE2 3442 1202 -0.0970162 0.0194687 -0.0166634 1 0 1 1 0 0 +EDGE2 3442 842 0.0213123 0.0357434 0.030686 1 0 1 1 0 0 +EDGE2 3442 862 -0.0451813 -0.0747701 0.00692268 1 0 1 1 0 0 +EDGE2 3442 841 -1.05632 -0.00351674 0.0129646 1 0 1 1 0 0 +EDGE2 3442 901 -0.968075 -0.0167021 -0.000411717 1 0 1 1 0 0 +EDGE2 3442 1201 -0.944549 -0.0512904 -0.00221402 1 0 1 1 0 0 +EDGE2 3442 3421 -1.02513 0.0579394 0.0145488 1 0 1 1 0 0 +EDGE2 3442 861 -0.96982 -0.0821537 -0.0175802 1 0 1 1 0 0 +EDGE2 3443 864 0.939973 0.000878083 -0.0113812 1 0 1 1 0 0 +EDGE2 3443 1204 0.975406 0.0109818 -0.00792293 1 0 1 1 0 0 +EDGE2 3443 3424 1.00999 -0.106843 0.0174522 1 0 1 1 0 0 +EDGE2 3443 904 0.964084 -0.0589973 0.00834404 1 0 1 1 0 0 +EDGE2 3443 3423 0.00273002 0.082581 0.027167 1 0 1 1 0 0 +EDGE2 3443 844 1.01036 0.0660506 0.0180728 1 0 1 1 0 0 +EDGE2 3443 863 0.0433736 0.012736 -0.00520555 1 0 1 1 0 0 +EDGE2 3443 903 0.00229028 -0.0237694 0.0125672 1 0 1 1 0 0 +EDGE2 3443 1203 -0.074776 0.000662396 -0.0202575 1 0 1 1 0 0 +EDGE2 3443 843 0.0661183 -0.00225334 -0.00480975 1 0 1 1 0 0 +EDGE2 3443 902 -1.04088 0.0141622 0.0123633 1 0 1 1 0 0 +EDGE2 3443 3422 -0.972109 -0.0403858 0.0273716 1 0 1 1 0 0 +EDGE2 3443 3442 -1.00573 0.000682939 0.0160882 1 0 1 1 0 0 +EDGE2 3443 1202 -0.982218 -0.0566855 -0.0072755 1 0 1 1 0 0 +EDGE2 3443 842 -1.09839 0.0409438 0.0112736 1 0 1 1 0 0 +EDGE2 3443 862 -1.05306 -0.00016055 -0.00822114 1 0 1 1 0 0 +EDGE2 3444 865 1.06902 0.0111973 -0.0386464 1 0 1 1 0 0 +EDGE2 3444 3225 1.13915 0.0381858 -3.10479 1 0 1 1 0 0 +EDGE2 3444 3425 1.00944 0.0472797 -0.0197856 1 0 1 1 0 0 +EDGE2 3444 3365 1.01243 0.0213805 -3.13331 1 0 1 1 0 0 +EDGE2 3444 1205 0.93959 0.0395368 0.0113986 1 0 1 1 0 0 +EDGE2 3444 3205 1.0269 -0.0790892 -3.13671 1 0 1 1 0 0 +EDGE2 3444 905 0.989599 -0.00735891 -0.0282412 1 0 1 1 0 0 +EDGE2 3444 864 -0.00983538 -0.0151207 0.0239373 1 0 1 1 0 0 +EDGE2 3444 705 0.994386 0.0315706 -3.15512 1 0 1 1 0 0 +EDGE2 3444 825 0.964149 0.0297127 -3.15991 1 0 1 1 0 0 +EDGE2 3444 845 0.946581 0.0213216 -0.00401732 1 0 1 1 0 0 +EDGE2 3444 1204 -0.0241148 0.0319992 0.000329098 1 0 1 1 0 0 +EDGE2 3444 3424 -0.00474736 8.48258e-05 -0.0101509 1 0 1 1 0 0 +EDGE2 3444 904 -0.0892316 0.0179509 0.00691499 1 0 1 1 0 0 +EDGE2 3444 3423 -0.988266 -0.0039002 0.00316742 1 0 1 1 0 0 +EDGE2 3444 844 0.0161123 -0.0146329 -0.0132855 1 0 1 1 0 0 +EDGE2 3444 3443 -1.03642 0.0290044 0.0258513 1 0 1 1 0 0 +EDGE2 3444 863 -1.03159 -0.0159607 0.00888704 1 0 1 1 0 0 +EDGE2 3444 903 -0.969464 -0.00757785 0.0400281 1 0 1 1 0 0 +EDGE2 3444 1203 -0.978943 0.0195732 -0.0227828 1 0 1 1 0 0 +EDGE2 3444 843 -0.948034 0.000942984 0.0314781 1 0 1 1 0 0 +EDGE2 3445 3364 1.04106 -0.0392883 -3.14899 1 0 1 1 0 0 +EDGE2 3445 824 1.05565 0.0566181 -3.1678 1 0 1 1 0 0 +EDGE2 3445 3204 1.01573 -0.00836138 -3.12472 1 0 1 1 0 0 +EDGE2 3445 3224 1.02613 -0.0869866 -3.13899 1 0 1 1 0 0 +EDGE2 3445 704 1.03674 -0.0197482 -3.14286 1 0 1 1 0 0 +EDGE2 3445 865 0.0103679 -0.0419146 0.0150478 1 0 1 1 0 0 +EDGE2 3445 3225 0.0810351 0.0399777 -3.14519 1 0 1 1 0 0 +EDGE2 3445 826 -0.0812506 0.959796 1.5877 1 0 1 1 0 0 +EDGE2 3445 866 -0.109301 1.08333 1.54759 1 0 1 1 0 0 +EDGE2 3445 906 0.00993797 1.04899 1.53744 1 0 1 1 0 0 +EDGE2 3445 3426 0.0349866 0.982668 1.56343 1 0 1 1 0 0 +EDGE2 3445 846 0.0721701 0.95883 1.594 1 0 1 1 0 0 +EDGE2 3445 3425 -0.0473434 0.0612871 0.00722331 1 0 1 1 0 0 +EDGE2 3445 3365 0.0448961 -0.0229177 -3.16351 1 0 1 1 0 0 +EDGE2 3445 1205 -0.00328543 -0.0424483 0.0341146 1 0 1 1 0 0 +EDGE2 3445 3205 -0.0156138 0.0543388 -3.14652 1 0 1 1 0 0 +EDGE2 3445 905 -0.0195859 0.064462 -0.0024642 1 0 1 1 0 0 +EDGE2 3445 864 -1.01887 -0.0353687 -0.0059071 1 0 1 1 0 0 +EDGE2 3445 705 0.0495215 0.0149141 -3.15108 1 0 1 1 0 0 +EDGE2 3445 825 0.0773256 -0.0542408 -3.15466 1 0 1 1 0 0 +EDGE2 3445 845 -0.053927 -0.0400661 0.0134251 1 0 1 1 0 0 +EDGE2 3445 1204 -1.04174 -0.020697 0.000276416 1 0 1 1 0 0 +EDGE2 3445 3424 -1.00973 0.0731053 -0.0257653 1 0 1 1 0 0 +EDGE2 3445 3444 -0.994394 -0.0136655 -0.0478245 1 0 1 1 0 0 +EDGE2 3445 904 -0.990376 -0.0199671 -0.00874304 1 0 1 1 0 0 +EDGE2 3445 844 -1.05026 0.0394175 0.0190381 1 0 1 1 0 0 +EDGE2 3445 1206 0.0268782 -1.00909 -1.56168 1 0 1 1 0 0 +EDGE2 3445 3226 -0.00172265 -1.03158 -1.56324 1 0 1 1 0 0 +EDGE2 3445 3366 -0.0143606 -1.03709 -1.54832 1 0 1 1 0 0 +EDGE2 3445 3206 -0.0135501 -1.03072 -1.56835 1 0 1 1 0 0 +EDGE2 3445 706 -0.029916 -1.0244 -1.62731 1 0 1 1 0 0 +EDGE2 3446 865 -0.979514 -0.0700683 -1.5634 1 0 1 1 0 0 +EDGE2 3446 3427 1.01033 -0.0699655 -0.024333 1 0 1 1 0 0 +EDGE2 3446 847 1.02948 -0.0410953 0.0162868 1 0 1 1 0 0 +EDGE2 3446 867 0.909572 0.0128425 -0.0041832 1 0 1 1 0 0 +EDGE2 3446 907 1.10388 -0.0589552 -0.000665414 1 0 1 1 0 0 +EDGE2 3446 827 1.03358 -0.00074947 0.0082452 1 0 1 1 0 0 +EDGE2 3446 3225 -1.06752 0.0134885 1.59944 1 0 1 1 0 0 +EDGE2 3446 826 0.014409 0.0282434 0.0280661 1 0 1 1 0 0 +EDGE2 3446 866 0.00967247 0.0121349 0.0267268 1 0 1 1 0 0 +EDGE2 3446 906 0.0145997 0.020377 0.0101124 1 0 1 1 0 0 +EDGE2 3446 3426 0.0610087 0.0284989 -0.00693094 1 0 1 1 0 0 +EDGE2 3446 846 -0.0278306 0.0355805 -0.00460634 1 0 1 1 0 0 +EDGE2 3446 3425 -0.929424 0.0831277 -1.56656 1 0 1 1 0 0 +EDGE2 3446 3445 -1.01078 -0.0400051 -1.55317 1 0 1 1 0 0 +EDGE2 3446 3365 -1.0338 0.0789762 1.59322 1 0 1 1 0 0 +EDGE2 3446 1205 -0.937202 0.038552 -1.58325 1 0 1 1 0 0 +EDGE2 3446 3205 -1.06174 -0.0509184 1.56594 1 0 1 1 0 0 +EDGE2 3446 905 -1.02442 0.0215353 -1.56326 1 0 1 1 0 0 +EDGE2 3446 705 -1.06795 -0.0330596 1.56329 1 0 1 1 0 0 +EDGE2 3446 825 -0.929814 0.0136918 1.54793 1 0 1 1 0 0 +EDGE2 3446 845 -1.0189 -0.052838 -1.56319 1 0 1 1 0 0 +EDGE2 3447 908 1.02236 -0.0158239 -0.00732012 1 0 1 1 0 0 +EDGE2 3447 3428 0.992781 0.123921 0.0308072 1 0 1 1 0 0 +EDGE2 3447 3446 -1.04273 0.0268225 -0.00817163 1 0 1 1 0 0 +EDGE2 3447 3427 0.0455585 0.0670686 0.0093394 1 0 1 1 0 0 +EDGE2 3447 828 1.01836 -0.00405015 0.00270632 1 0 1 1 0 0 +EDGE2 3447 848 1.01683 -0.016464 -0.000144735 1 0 1 1 0 0 +EDGE2 3447 868 0.998102 0.0519366 -0.0101477 1 0 1 1 0 0 +EDGE2 3447 847 -0.0765876 -0.0298712 -0.00117988 1 0 1 1 0 0 +EDGE2 3447 867 0.00328205 -0.0530481 -0.0287142 1 0 1 1 0 0 +EDGE2 3447 907 0.0682039 0.0539602 -0.0191772 1 0 1 1 0 0 +EDGE2 3447 827 -0.0494545 -0.000669986 0.00744745 1 0 1 1 0 0 +EDGE2 3447 826 -0.92924 -0.0450362 0.0183051 1 0 1 1 0 0 +EDGE2 3447 866 -1.06091 0.0036546 0.00887554 1 0 1 1 0 0 +EDGE2 3447 906 -0.954247 0.0211139 -0.0213946 1 0 1 1 0 0 +EDGE2 3447 3426 -1.0467 0.0226077 0.0067109 1 0 1 1 0 0 +EDGE2 3447 846 -1.04153 0.0105554 0.00614045 1 0 1 1 0 0 +EDGE2 3448 908 -0.0310765 0.0379574 -0.0038185 1 0 1 1 0 0 +EDGE2 3448 869 1.02208 0.0146477 0.00266335 1 0 1 1 0 0 +EDGE2 3448 3429 0.995944 0.0273999 -0.0028378 1 0 1 1 0 0 +EDGE2 3448 909 0.937421 0.0478486 -0.00450057 1 0 1 1 0 0 +EDGE2 3448 829 1.00899 -0.0655197 -0.00544113 1 0 1 1 0 0 +EDGE2 3448 849 0.915017 -0.0172873 -0.00515278 1 0 1 1 0 0 +EDGE2 3448 3428 -0.043949 0.0207943 -0.0112588 1 0 1 1 0 0 +EDGE2 3448 3427 -1.01409 0.0567011 0.018717 1 0 1 1 0 0 +EDGE2 3448 828 0.0281495 -0.0419105 -0.00542586 1 0 1 1 0 0 +EDGE2 3448 848 -0.0164792 -0.0489676 -0.000863653 1 0 1 1 0 0 +EDGE2 3448 868 -0.108514 -0.0538046 -0.0125655 1 0 1 1 0 0 +EDGE2 3448 3447 -1.00908 -0.0281001 9.00559e-05 1 0 1 1 0 0 +EDGE2 3448 847 -0.908845 -0.0780995 -0.0183621 1 0 1 1 0 0 +EDGE2 3448 867 -0.993132 -0.0954063 0.0113631 1 0 1 1 0 0 +EDGE2 3448 907 -1.05361 0.0544243 -0.00680031 1 0 1 1 0 0 +EDGE2 3448 827 -1.0061 0.118728 -0.00828566 1 0 1 1 0 0 +EDGE2 3449 908 -0.918172 -0.0113922 0.0120326 1 0 1 1 0 0 +EDGE2 3449 690 0.992712 -0.0907328 -3.13692 1 0 1 1 0 0 +EDGE2 3449 910 1.03552 0.118658 0.0387807 1 0 1 1 0 0 +EDGE2 3449 3430 0.94852 -0.0397938 -0.0214459 1 0 1 1 0 0 +EDGE2 3449 850 0.942984 -0.00540501 0.0177114 1 0 1 1 0 0 +EDGE2 3449 870 0.943788 0.0636502 -0.0183651 1 0 1 1 0 0 +EDGE2 3449 890 0.920862 -0.0248739 -3.1656 1 0 1 1 0 0 +EDGE2 3449 830 0.973997 -0.000282003 -0.00705782 1 0 1 1 0 0 +EDGE2 3449 869 -0.0138896 0.0808174 -0.0151497 1 0 1 1 0 0 +EDGE2 3449 3429 0.00369219 0.00466442 0.0182262 1 0 1 1 0 0 +EDGE2 3449 909 -0.00689218 -0.0794491 -0.0123185 1 0 1 1 0 0 +EDGE2 3449 3448 -0.96428 -0.00719223 -0.00528165 1 0 1 1 0 0 +EDGE2 3449 829 -0.0264717 -0.00750839 0.0313146 1 0 1 1 0 0 +EDGE2 3449 849 -0.0186957 0.127153 0.0150149 1 0 1 1 0 0 +EDGE2 3449 3428 -1.06801 -0.0286406 0.00426333 1 0 1 1 0 0 +EDGE2 3449 828 -1.0063 -0.0405728 -0.0378403 1 0 1 1 0 0 +EDGE2 3449 848 -0.938414 0.0468711 0.0158314 1 0 1 1 0 0 +EDGE2 3449 868 -0.997656 0.0356862 0.000877103 1 0 1 1 0 0 +EDGE2 3450 691 -0.0690124 -1.03316 -1.595 1 0 1 1 0 0 +EDGE2 3450 871 0.0273427 -0.938015 -1.58071 1 0 1 1 0 0 +EDGE2 3450 690 -0.0152354 0.0052266 -3.15299 1 0 1 1 0 0 +EDGE2 3450 910 0.0127403 -0.0405769 -0.0086687 1 0 1 1 0 0 +EDGE2 3450 689 0.981121 -0.040956 -3.16587 1 0 1 1 0 0 +EDGE2 3450 889 1.00442 0.0852188 -3.1235 1 0 1 1 0 0 +EDGE2 3450 3430 0.0365233 -0.0436273 -0.0209083 1 0 1 1 0 0 +EDGE2 3450 850 0.0601059 0.044549 -0.00337278 1 0 1 1 0 0 +EDGE2 3450 870 0.0265353 -0.0984504 -0.0186422 1 0 1 1 0 0 +EDGE2 3450 890 0.0349949 -0.122129 -3.16133 1 0 1 1 0 0 +EDGE2 3450 830 0.0218884 0.0100125 -0.00782064 1 0 1 1 0 0 +EDGE2 3450 851 -0.066236 0.99244 1.55974 1 0 1 1 0 0 +EDGE2 3450 911 -0.0686918 0.955667 1.56909 1 0 1 1 0 0 +EDGE2 3450 3431 0.0750358 0.948643 1.53444 1 0 1 1 0 0 +EDGE2 3450 891 0.0196381 0.979507 1.57424 1 0 1 1 0 0 +EDGE2 3450 831 -0.0515092 0.948875 1.554 1 0 1 1 0 0 +EDGE2 3450 869 -1.0431 0.0302504 -0.0254257 1 0 1 1 0 0 +EDGE2 3450 3429 -1.00817 0.0549811 0.0197864 1 0 1 1 0 0 +EDGE2 3450 3449 -1.01174 0.0155643 0.000528197 1 0 1 1 0 0 +EDGE2 3450 909 -0.915585 0.0143573 0.0288799 1 0 1 1 0 0 +EDGE2 3450 829 -1.00585 0.0100523 0.0081119 1 0 1 1 0 0 +EDGE2 3450 849 -1.02762 0.0698991 0.0107378 1 0 1 1 0 0 +EDGE2 3451 872 1.09147 -0.10776 -0.0467067 1 0 1 1 0 0 +EDGE2 3451 692 0.951439 0.00465186 0.0382256 1 0 1 1 0 0 +EDGE2 3451 691 -0.0490541 -0.110393 0.0135448 1 0 1 1 0 0 +EDGE2 3451 871 -0.0451053 -0.0413264 -0.0125307 1 0 1 1 0 0 +EDGE2 3451 690 -1.05026 0.0748502 -1.56505 1 0 1 1 0 0 +EDGE2 3451 910 -1.07462 0.0447539 1.55309 1 0 1 1 0 0 +EDGE2 3451 3450 -0.870786 -0.0574351 1.54619 1 0 1 1 0 0 +EDGE2 3451 3430 -1.0666 0.0437134 1.56873 1 0 1 1 0 0 +EDGE2 3451 850 -1.02849 -0.0062951 1.57072 1 0 1 1 0 0 +EDGE2 3451 870 -0.985652 0.0493462 1.54624 1 0 1 1 0 0 +EDGE2 3451 890 -0.972487 0.0130867 -1.55669 1 0 1 1 0 0 +EDGE2 3451 830 -0.928644 0.00312381 1.56803 1 0 1 1 0 0 +EDGE2 3452 693 0.985424 0.124335 -0.044326 1 0 1 1 0 0 +EDGE2 3452 873 1.03557 -0.105669 0.00294687 1 0 1 1 0 0 +EDGE2 3452 872 -0.0224039 -0.0282123 0.029304 1 0 1 1 0 0 +EDGE2 3452 692 0.0585821 -0.0485281 0.0153764 1 0 1 1 0 0 +EDGE2 3452 691 -0.978427 -0.0380211 0.00365362 1 0 1 1 0 0 +EDGE2 3452 871 -0.963083 0.0666007 -0.00537799 1 0 1 1 0 0 +EDGE2 3452 3451 -1.08943 -0.047539 0.0291787 1 0 1 1 0 0 +EDGE2 3453 693 0.00897881 -0.00847177 0.00836443 1 0 1 1 0 0 +EDGE2 3453 874 1.03343 0.0180611 0.0141042 1 0 1 1 0 0 +EDGE2 3453 694 1.07496 -0.0184825 0.00647236 1 0 1 1 0 0 +EDGE2 3453 873 -0.0133973 0.0407094 0.0102843 1 0 1 1 0 0 +EDGE2 3453 872 -0.944574 -0.0107803 0.0016184 1 0 1 1 0 0 +EDGE2 3453 3452 -0.954835 0.0273865 -0.025313 1 0 1 1 0 0 +EDGE2 3453 692 -0.978584 0.0355714 0.0124845 1 0 1 1 0 0 +EDGE2 3454 795 1.05054 -0.00142779 -3.15775 1 0 1 1 0 0 +EDGE2 3454 875 0.930765 -0.0155378 0.0190509 1 0 1 1 0 0 +EDGE2 3454 3335 0.925462 -0.115342 -3.14599 1 0 1 1 0 0 +EDGE2 3454 3355 1.01381 -0.0178861 -3.12699 1 0 1 1 0 0 +EDGE2 3454 815 0.913754 0.0393141 -3.15249 1 0 1 1 0 0 +EDGE2 3454 755 1.05682 0.0137662 -3.16324 1 0 1 1 0 0 +EDGE2 3454 775 1.08588 -0.0582269 -3.14584 1 0 1 1 0 0 +EDGE2 3454 695 0.969076 0.0136282 0.0161878 1 0 1 1 0 0 +EDGE2 3454 693 -0.949364 -0.00185891 0.0412482 1 0 1 1 0 0 +EDGE2 3454 874 0.00826321 0.0369656 -0.0117802 1 0 1 1 0 0 +EDGE2 3454 694 0.112297 -0.0203781 0.0367378 1 0 1 1 0 0 +EDGE2 3454 3453 -1.01172 -0.0376085 0.000558698 1 0 1 1 0 0 +EDGE2 3454 873 -1.01297 0.00144527 -0.0104682 1 0 1 1 0 0 +EDGE2 3455 876 -0.0321925 0.988247 1.5901 1 0 1 1 0 0 +EDGE2 3455 774 1.00254 0.046525 -3.17167 1 0 1 1 0 0 +EDGE2 3455 814 0.979838 0.0372506 -3.14368 1 0 1 1 0 0 +EDGE2 3455 3334 1.04519 0.0227845 -3.12351 1 0 1 1 0 0 +EDGE2 3455 3354 0.964597 -0.0306763 -3.12934 1 0 1 1 0 0 +EDGE2 3455 794 1.00758 -0.0145902 -3.12544 1 0 1 1 0 0 +EDGE2 3455 754 0.966517 -0.00195997 -3.1288 1 0 1 1 0 0 +EDGE2 3455 795 0.0499253 -0.0152318 -3.1303 1 0 1 1 0 0 +EDGE2 3455 875 -0.0422952 0.0557989 0.0439864 1 0 1 1 0 0 +EDGE2 3455 3335 -0.0494748 -0.0250894 -3.10716 1 0 1 1 0 0 +EDGE2 3455 3355 0.0720549 0.0477365 -3.13931 1 0 1 1 0 0 +EDGE2 3455 815 -0.057207 0.0710309 -3.15262 1 0 1 1 0 0 +EDGE2 3455 755 0.0112166 -0.0778758 -3.147 1 0 1 1 0 0 +EDGE2 3455 775 0.0273695 -0.0320332 -3.1644 1 0 1 1 0 0 +EDGE2 3455 695 0.140719 -0.0831416 0.0360623 1 0 1 1 0 0 +EDGE2 3455 874 -0.928468 0.121405 0.00724742 1 0 1 1 0 0 +EDGE2 3455 3454 -0.970606 -0.0398678 -0.0076458 1 0 1 1 0 0 +EDGE2 3455 694 -0.916448 -0.109256 -0.00294529 1 0 1 1 0 0 +EDGE2 3455 796 0.0140152 -1.0119 -1.55836 1 0 1 1 0 0 +EDGE2 3455 3336 0.0954151 -0.995719 -1.55154 1 0 1 1 0 0 +EDGE2 3455 3356 0.0630796 -1.00631 -1.54459 1 0 1 1 0 0 +EDGE2 3455 816 -0.0694978 -1.05516 -1.53997 1 0 1 1 0 0 +EDGE2 3455 696 0.0294296 -1.02945 -1.53409 1 0 1 1 0 0 +EDGE2 3455 756 0.0863683 -1.03205 -1.55817 1 0 1 1 0 0 +EDGE2 3455 776 0.039102 -0.983075 -1.58778 1 0 1 1 0 0 +EDGE2 3456 3455 -0.796106 -0.00696599 1.5891 1 0 1 1 0 0 +EDGE2 3456 795 -0.89129 0.0191441 -1.55427 1 0 1 1 0 0 +EDGE2 3456 875 -0.993561 0.00270695 1.59162 1 0 1 1 0 0 +EDGE2 3456 3335 -0.949709 0.0247859 -1.58401 1 0 1 1 0 0 +EDGE2 3456 3355 -0.966802 -0.0404116 -1.59163 1 0 1 1 0 0 +EDGE2 3456 815 -0.952904 -0.0680445 -1.57127 1 0 1 1 0 0 +EDGE2 3456 755 -1.03258 0.0221091 -1.5657 1 0 1 1 0 0 +EDGE2 3456 775 -1.01737 0.0553924 -1.53511 1 0 1 1 0 0 +EDGE2 3456 695 -1.03634 -0.0109298 1.57572 1 0 1 1 0 0 +EDGE2 3456 3337 0.954566 0.000872403 0.00962904 1 0 1 1 0 0 +EDGE2 3456 796 0.0100901 -0.04671 -0.0412446 1 0 1 1 0 0 +EDGE2 3456 3336 -0.0514914 0.01161 -0.0135569 1 0 1 1 0 0 +EDGE2 3456 3356 0.0215694 0.0980416 -0.033923 1 0 1 1 0 0 +EDGE2 3456 816 -0.00954749 0.0895799 0.0285018 1 0 1 1 0 0 +EDGE2 3456 696 0.082238 0.0860618 -0.0325219 1 0 1 1 0 0 +EDGE2 3456 756 0.0178676 0.0246943 0.00385412 1 0 1 1 0 0 +EDGE2 3456 776 -0.0662852 -0.0413254 0.0197253 1 0 1 1 0 0 +EDGE2 3456 3357 1.00947 0.0304265 -0.0104753 1 0 1 1 0 0 +EDGE2 3456 697 1.03531 0.0556347 -0.0155224 1 0 1 1 0 0 +EDGE2 3456 777 1.04808 -0.0254404 0.0087802 1 0 1 1 0 0 +EDGE2 3456 797 1.04738 -0.034394 -0.0145324 1 0 1 1 0 0 +EDGE2 3456 817 0.951381 0.0403657 0.0433241 1 0 1 1 0 0 +EDGE2 3456 757 1.00364 0.122972 0.0376652 1 0 1 1 0 0 +EDGE2 3457 3337 0.0272945 0.00398459 0.0110894 1 0 1 1 0 0 +EDGE2 3457 796 -0.992873 0.0881869 0.0158343 1 0 1 1 0 0 +EDGE2 3457 3336 -1.00721 -0.0115814 0.00481524 1 0 1 1 0 0 +EDGE2 3457 3356 -0.978123 0.000410352 -0.0153809 1 0 1 1 0 0 +EDGE2 3457 3456 -1.00897 0.0345739 0.00424046 1 0 1 1 0 0 +EDGE2 3457 816 -1.05763 -0.132644 -0.0293445 1 0 1 1 0 0 +EDGE2 3457 696 -0.987506 0.00253273 0.0192396 1 0 1 1 0 0 +EDGE2 3457 756 -0.985313 0.0172743 -0.049613 1 0 1 1 0 0 +EDGE2 3457 776 -0.991865 -0.00681306 -0.051739 1 0 1 1 0 0 +EDGE2 3457 3357 0.0246238 0.0159559 0.0139113 1 0 1 1 0 0 +EDGE2 3457 778 1.02121 0.0161813 -0.00337353 1 0 1 1 0 0 +EDGE2 3457 798 0.994769 -0.0371014 0.0189182 1 0 1 1 0 0 +EDGE2 3457 697 -0.128309 0.0164179 -0.00141166 1 0 1 1 0 0 +EDGE2 3457 777 0.04328 0.0439532 -0.0112263 1 0 1 1 0 0 +EDGE2 3457 797 0.0209318 -0.0261244 0.0125443 1 0 1 1 0 0 +EDGE2 3457 817 -0.0509798 0.0338353 -0.0255567 1 0 1 1 0 0 +EDGE2 3457 757 -0.0299414 -0.0630763 -0.0253693 1 0 1 1 0 0 +EDGE2 3457 3338 0.942817 0.0160194 -0.0283641 1 0 1 1 0 0 +EDGE2 3457 3358 1.03645 -0.0764289 -0.0186869 1 0 1 1 0 0 +EDGE2 3457 818 0.979044 0.083863 0.00312457 1 0 1 1 0 0 +EDGE2 3457 698 0.949485 -0.0085391 0.0351713 1 0 1 1 0 0 +EDGE2 3457 758 1.00347 0.00259731 -0.039367 1 0 1 1 0 0 +EDGE2 3458 3337 -0.990832 -0.030572 -0.0236897 1 0 1 1 0 0 +EDGE2 3458 3357 -0.994893 0.0605964 0.000153467 1 0 1 1 0 0 +EDGE2 3458 3457 -0.981425 -0.00991504 0.00859608 1 0 1 1 0 0 +EDGE2 3458 778 -0.008003 -0.0158714 0.00502076 1 0 1 1 0 0 +EDGE2 3458 798 -0.0165967 0.0755607 0.0127451 1 0 1 1 0 0 +EDGE2 3458 697 -1.04079 0.0841033 -0.00402156 1 0 1 1 0 0 +EDGE2 3458 777 -1.00391 -0.0874946 0.00752178 1 0 1 1 0 0 +EDGE2 3458 797 -0.961491 0.0114711 -0.0254217 1 0 1 1 0 0 +EDGE2 3458 817 -0.931275 -0.00810274 -0.00961562 1 0 1 1 0 0 +EDGE2 3458 757 -0.901674 -0.0016082 -0.00886795 1 0 1 1 0 0 +EDGE2 3458 3338 -0.0689638 -0.0141381 -0.00290999 1 0 1 1 0 0 +EDGE2 3458 3358 -0.00452504 -0.0109245 -0.00552591 1 0 1 1 0 0 +EDGE2 3458 818 -0.0639843 0.00233337 -0.0520578 1 0 1 1 0 0 +EDGE2 3458 699 1.00831 0.033217 -0.0243436 1 0 1 1 0 0 +EDGE2 3458 3339 1.00094 0.023174 0.00829628 1 0 1 1 0 0 +EDGE2 3458 698 -0.0536442 0.0372119 -0.00786987 1 0 1 1 0 0 +EDGE2 3458 758 0.0348576 -0.0564893 -0.0180061 1 0 1 1 0 0 +EDGE2 3458 3359 1.02883 -0.0659916 0.0250994 1 0 1 1 0 0 +EDGE2 3458 779 0.942616 0.00164371 -0.00141202 1 0 1 1 0 0 +EDGE2 3458 799 0.952488 -0.0324405 -0.0231599 1 0 1 1 0 0 +EDGE2 3458 819 1.02127 0.0453244 0.0248772 1 0 1 1 0 0 +EDGE2 3458 759 1.05785 0.0468105 -0.0432461 1 0 1 1 0 0 +EDGE2 3459 800 0.920716 0.0072415 -0.0209254 1 0 1 1 0 0 +EDGE2 3459 778 -1.04502 0.0252236 -0.0310042 1 0 1 1 0 0 +EDGE2 3459 798 -0.980441 0.105949 -0.0247431 1 0 1 1 0 0 +EDGE2 3459 3338 -0.905345 0.002805 0.048379 1 0 1 1 0 0 +EDGE2 3459 3358 -0.973198 -0.0143499 -0.00739201 1 0 1 1 0 0 +EDGE2 3459 3458 -1.03538 0.0232436 -0.0175988 1 0 1 1 0 0 +EDGE2 3459 818 -1.08085 0.00374241 -0.00483733 1 0 1 1 0 0 +EDGE2 3459 699 -0.0242568 -0.0384061 0.0123031 1 0 1 1 0 0 +EDGE2 3459 3339 -0.062297 -0.050817 0.0313046 1 0 1 1 0 0 +EDGE2 3459 698 -1.04861 -0.0113231 -0.00378653 1 0 1 1 0 0 +EDGE2 3459 758 -1.01021 -0.0301679 0.0248453 1 0 1 1 0 0 +EDGE2 3459 3359 -0.0537573 0.0217211 -0.0516832 1 0 1 1 0 0 +EDGE2 3459 779 0.0144219 0.0758157 -0.0319473 1 0 1 1 0 0 +EDGE2 3459 799 0.0123201 -0.0665978 -0.0254482 1 0 1 1 0 0 +EDGE2 3459 819 -0.0352684 0.0175689 -0.00765081 1 0 1 1 0 0 +EDGE2 3459 759 -0.0704643 0.0455636 -0.00631454 1 0 1 1 0 0 +EDGE2 3459 3340 1.03365 -0.0424253 -0.0156487 1 0 1 1 0 0 +EDGE2 3459 3360 0.975333 -0.0189505 0.003 1 0 1 1 0 0 +EDGE2 3459 3200 0.930128 0.0367584 -3.18136 1 0 1 1 0 0 +EDGE2 3459 3220 0.967808 0.0479697 -3.13544 1 0 1 1 0 0 +EDGE2 3459 820 1.03358 0.118832 0.000181804 1 0 1 1 0 0 +EDGE2 3459 740 1.02787 0.0142881 -3.13904 1 0 1 1 0 0 +EDGE2 3459 760 0.902286 0.0326163 0.00309863 1 0 1 1 0 0 +EDGE2 3459 780 0.925362 0.0431028 0.0297804 1 0 1 1 0 0 +EDGE2 3459 700 1.03995 -0.0992789 0.0193191 1 0 1 1 0 0 +EDGE2 3460 801 -0.00354455 0.905492 1.5633 1 0 1 1 0 0 +EDGE2 3460 3341 -0.024461 1.02225 1.60138 1 0 1 1 0 0 +EDGE2 3460 761 0.0261424 0.959968 1.55336 1 0 1 1 0 0 +EDGE2 3460 781 0.0346107 0.930555 1.57365 1 0 1 1 0 0 +EDGE2 3460 741 0.0172651 1.02174 1.58251 1 0 1 1 0 0 +EDGE2 3460 800 -0.0244647 0.128908 0.00448745 1 0 1 1 0 0 +EDGE2 3460 699 -1.05276 -0.0818822 0.00204633 1 0 1 1 0 0 +EDGE2 3460 3339 -0.924802 0.0555689 -0.0182868 1 0 1 1 0 0 +EDGE2 3460 3459 -0.963076 0.00502737 0.0072768 1 0 1 1 0 0 +EDGE2 3460 3359 -0.941086 -0.0568712 0.00874555 1 0 1 1 0 0 +EDGE2 3460 779 -1.03958 -0.002567 -0.00348502 1 0 1 1 0 0 +EDGE2 3460 799 -1.03969 -0.0600986 0.0233034 1 0 1 1 0 0 +EDGE2 3460 819 -1.04141 0.0109413 0.0331587 1 0 1 1 0 0 +EDGE2 3460 759 -0.948568 -0.0276065 -0.0103307 1 0 1 1 0 0 +EDGE2 3460 3340 0.000959901 0.0700039 0.0441433 1 0 1 1 0 0 +EDGE2 3460 3360 -0.0381465 0.0691468 0.0218987 1 0 1 1 0 0 +EDGE2 3460 3200 0.0422687 0.00751087 -3.1566 1 0 1 1 0 0 +EDGE2 3460 3220 -0.0628581 -0.0165009 -3.14144 1 0 1 1 0 0 +EDGE2 3460 820 -0.0384146 0.031107 0.0130464 1 0 1 1 0 0 +EDGE2 3460 701 0.032868 -0.950505 -1.55412 1 0 1 1 0 0 +EDGE2 3460 740 0.0381513 0.0429681 -3.14187 1 0 1 1 0 0 +EDGE2 3460 760 -0.0211993 -0.0268071 -0.0222353 1 0 1 1 0 0 +EDGE2 3460 780 0.148831 0.00179481 0.0157331 1 0 1 1 0 0 +EDGE2 3460 700 -0.0281492 0.00802842 0.0115745 1 0 1 1 0 0 +EDGE2 3460 3201 -0.0209153 -1.08608 -1.56496 1 0 1 1 0 0 +EDGE2 3460 3221 0.00480342 -1.06049 -1.57559 1 0 1 1 0 0 +EDGE2 3460 3361 0.0309576 -0.963021 -1.59432 1 0 1 1 0 0 +EDGE2 3460 821 0.0759642 -1.01652 -1.57418 1 0 1 1 0 0 +EDGE2 3460 3199 1.03749 -0.00314159 -3.16733 1 0 1 1 0 0 +EDGE2 3460 3219 1.02463 0.0517024 -3.14716 1 0 1 1 0 0 +EDGE2 3460 739 0.940097 0.0465885 -3.16939 1 0 1 1 0 0 +EDGE2 3461 800 -0.965985 0.00763841 1.59711 1 0 1 1 0 0 +EDGE2 3461 3340 -1.03188 0.0182175 1.57862 1 0 1 1 0 0 +EDGE2 3461 3460 -1.05853 -0.0685898 1.53736 1 0 1 1 0 0 +EDGE2 3461 3360 -0.996303 0.0148376 1.55784 1 0 1 1 0 0 +EDGE2 3461 3200 -0.973896 -0.0132624 -1.60346 1 0 1 1 0 0 +EDGE2 3461 3220 -0.964712 -0.0344201 -1.54717 1 0 1 1 0 0 +EDGE2 3461 820 -1.0386 -0.127012 1.57714 1 0 1 1 0 0 +EDGE2 3461 701 0.0125015 -0.0109933 0.0160415 1 0 1 1 0 0 +EDGE2 3461 740 -0.9788 -0.0366275 -1.57732 1 0 1 1 0 0 +EDGE2 3461 760 -0.951173 -0.0601221 1.54707 1 0 1 1 0 0 +EDGE2 3461 780 -1.07259 -0.0160844 1.54967 1 0 1 1 0 0 +EDGE2 3461 700 -1.0086 -0.000416529 1.56307 1 0 1 1 0 0 +EDGE2 3461 3201 -0.00307983 -0.0214034 -0.0167132 1 0 1 1 0 0 +EDGE2 3461 3221 -0.0101758 0.0338561 -0.0423864 1 0 1 1 0 0 +EDGE2 3461 3361 0.0242853 -0.0581706 -0.0307434 1 0 1 1 0 0 +EDGE2 3461 821 -0.00426163 -0.0104064 0.0124912 1 0 1 1 0 0 +EDGE2 3461 822 1.08516 -0.0488856 0.0241135 1 0 1 1 0 0 +EDGE2 3461 3222 1.08514 -0.0331168 -0.0307663 1 0 1 1 0 0 +EDGE2 3461 3362 0.997153 -0.00531135 0.028385 1 0 1 1 0 0 +EDGE2 3461 3202 0.946568 -0.0580896 -0.0102127 1 0 1 1 0 0 +EDGE2 3461 702 1.0068 -0.028082 -0.00940458 1 0 1 1 0 0 +EDGE2 3462 3203 0.912823 0.0531949 0.0334444 1 0 1 1 0 0 +EDGE2 3462 701 -0.996135 -0.05316 0.00248552 1 0 1 1 0 0 +EDGE2 3462 3461 -0.94998 0.0594459 -0.0180296 1 0 1 1 0 0 +EDGE2 3462 3201 -0.984686 -0.00823683 0.0152876 1 0 1 1 0 0 +EDGE2 3462 3221 -1.00691 -0.0502029 0.0132063 1 0 1 1 0 0 +EDGE2 3462 3361 -0.929412 -0.00193089 -0.00664849 1 0 1 1 0 0 +EDGE2 3462 821 -1.10004 -0.034426 0.0049664 1 0 1 1 0 0 +EDGE2 3462 822 0.0207188 -0.0450792 -0.0222395 1 0 1 1 0 0 +EDGE2 3462 3222 0.00455402 0.0704147 -0.0106376 1 0 1 1 0 0 +EDGE2 3462 3362 -0.00642007 -0.0528121 0.0157581 1 0 1 1 0 0 +EDGE2 3462 3202 0.026417 -0.00929684 0.0010304 1 0 1 1 0 0 +EDGE2 3462 3363 1.03213 0.0460226 -0.0182191 1 0 1 1 0 0 +EDGE2 3462 702 0.129218 0.0284305 0.00981263 1 0 1 1 0 0 +EDGE2 3462 3223 0.994619 -0.0160368 0.00340646 1 0 1 1 0 0 +EDGE2 3462 703 0.930957 -0.0276538 -0.0133023 1 0 1 1 0 0 +EDGE2 3462 823 0.957404 0.0634413 -0.00638451 1 0 1 1 0 0 +EDGE2 3463 3203 -0.0165981 0.0341648 -0.0298316 1 0 1 1 0 0 +EDGE2 3463 822 -1.024 0.0203523 -0.00393655 1 0 1 1 0 0 +EDGE2 3463 3222 -0.984094 -0.0501953 -0.0220537 1 0 1 1 0 0 +EDGE2 3463 3362 -1.05761 0.0332539 -0.0058416 1 0 1 1 0 0 +EDGE2 3463 3462 -0.99669 0.0380167 0.00449322 1 0 1 1 0 0 +EDGE2 3463 3202 -1.0321 -0.088563 -0.0187487 1 0 1 1 0 0 +EDGE2 3463 3363 -0.00764901 0.103224 0.0213926 1 0 1 1 0 0 +EDGE2 3463 702 -1.10469 -0.0352911 0.0168022 1 0 1 1 0 0 +EDGE2 3463 3223 -0.0417731 0.013845 0.0215435 1 0 1 1 0 0 +EDGE2 3463 3364 1.08633 -0.127246 -0.0578899 1 0 1 1 0 0 +EDGE2 3463 703 -0.00673808 -0.0420412 0.0135705 1 0 1 1 0 0 +EDGE2 3463 823 -0.0262137 -0.0175456 0.0125699 1 0 1 1 0 0 +EDGE2 3463 824 1.10092 0.0140476 -0.00859267 1 0 1 1 0 0 +EDGE2 3463 3204 1.05549 0.00657459 -0.00565987 1 0 1 1 0 0 +EDGE2 3463 3224 1.01567 0.0224524 -0.0100005 1 0 1 1 0 0 +EDGE2 3463 704 1.0513 -0.0479198 -0.00172925 1 0 1 1 0 0 +EDGE2 3464 3203 -0.966423 -0.0510041 0.00572723 1 0 1 1 0 0 +EDGE2 3464 3363 -1.00525 -0.0534606 0.0336402 1 0 1 1 0 0 +EDGE2 3464 3463 -0.982217 -0.000117886 -0.0122581 1 0 1 1 0 0 +EDGE2 3464 3223 -1.0658 0.106801 0.0476122 1 0 1 1 0 0 +EDGE2 3464 3364 0.0535556 -0.0166952 -0.000352384 1 0 1 1 0 0 +EDGE2 3464 703 -1.01439 -0.0111161 0.00910924 1 0 1 1 0 0 +EDGE2 3464 823 -0.99927 0.0610455 0.0164814 1 0 1 1 0 0 +EDGE2 3464 824 0.0149383 0.0577355 -0.011319 1 0 1 1 0 0 +EDGE2 3464 3204 0.0562844 -0.0839077 0.0358421 1 0 1 1 0 0 +EDGE2 3464 3224 0.0391725 0.0788581 -0.00558005 1 0 1 1 0 0 +EDGE2 3464 704 0.046046 0.0460979 0.000348439 1 0 1 1 0 0 +EDGE2 3464 865 0.962354 0.0166214 -3.10042 1 0 1 1 0 0 +EDGE2 3464 3225 1.02298 -0.000385786 -0.0119568 1 0 1 1 0 0 +EDGE2 3464 3425 1.04056 -0.000134652 -3.13006 1 0 1 1 0 0 +EDGE2 3464 3445 0.903907 0.0759805 -3.18333 1 0 1 1 0 0 +EDGE2 3464 3365 1.0051 0.00499736 0.000329181 1 0 1 1 0 0 +EDGE2 3464 1205 1.05298 0.0564813 -3.15329 1 0 1 1 0 0 +EDGE2 3464 3205 1.05871 0.00922242 0.0309424 1 0 1 1 0 0 +EDGE2 3464 905 0.919347 -0.00338607 -3.13659 1 0 1 1 0 0 +EDGE2 3464 705 1.04071 0.0817093 -0.0102768 1 0 1 1 0 0 +EDGE2 3464 825 1.03716 -0.100146 0.000246528 1 0 1 1 0 0 +EDGE2 3464 845 1.0473 -0.0233471 -3.14388 1 0 1 1 0 0 +EDGE2 3465 3364 -0.978031 -0.0170915 -0.000317308 1 0 1 1 0 0 +EDGE2 3465 3464 -0.982178 -0.0103741 -0.00922582 1 0 1 1 0 0 +EDGE2 3465 824 -1.10381 -0.0325046 -0.0239638 1 0 1 1 0 0 +EDGE2 3465 3204 -0.937545 0.0419335 -0.00760375 1 0 1 1 0 0 +EDGE2 3465 3224 -0.984612 0.0505564 -0.00102278 1 0 1 1 0 0 +EDGE2 3465 704 -1.07577 -0.00336593 0.0134245 1 0 1 1 0 0 +EDGE2 3465 865 -0.0328202 -0.0222466 -3.11896 1 0 1 1 0 0 +EDGE2 3465 3446 -0.0888941 -0.954971 -1.59224 1 0 1 1 0 0 +EDGE2 3465 3225 0.0122266 -0.0609967 0.0484948 1 0 1 1 0 0 +EDGE2 3465 826 0.0221965 -1.04169 -1.57921 1 0 1 1 0 0 +EDGE2 3465 866 0.050224 -1.04923 -1.54472 1 0 1 1 0 0 +EDGE2 3465 906 -0.0532885 -0.902246 -1.55623 1 0 1 1 0 0 +EDGE2 3465 3426 -0.0612875 -0.96605 -1.56355 1 0 1 1 0 0 +EDGE2 3465 846 0.045919 -1.0035 -1.55232 1 0 1 1 0 0 +EDGE2 3465 3425 -0.010667 -0.0388983 -3.1364 1 0 1 1 0 0 +EDGE2 3465 3445 0.0382064 -0.0646455 -3.14424 1 0 1 1 0 0 +EDGE2 3465 3365 -0.0510537 -0.00779975 0.0308867 1 0 1 1 0 0 +EDGE2 3465 1205 0.00326402 -0.0182626 -3.15956 1 0 1 1 0 0 +EDGE2 3465 3205 -0.0867544 -0.010526 0.00131664 1 0 1 1 0 0 +EDGE2 3465 905 0.00526747 -0.0122277 -3.13637 1 0 1 1 0 0 +EDGE2 3465 864 0.935923 0.0384476 -3.16029 1 0 1 1 0 0 +EDGE2 3465 705 -0.0700445 -0.0157318 -0.00868106 1 0 1 1 0 0 +EDGE2 3465 825 0.136165 -0.0174351 0.00767375 1 0 1 1 0 0 +EDGE2 3465 845 0.00293193 0.0630856 -3.1531 1 0 1 1 0 0 +EDGE2 3465 1204 0.999244 0.0371095 -3.12232 1 0 1 1 0 0 +EDGE2 3465 3424 1.04027 -0.0279154 -3.09519 1 0 1 1 0 0 +EDGE2 3465 3444 0.961831 -0.00626059 -3.13682 1 0 1 1 0 0 +EDGE2 3465 904 1.02981 0.0330549 -3.11807 1 0 1 1 0 0 +EDGE2 3465 844 0.975111 0.0640678 -3.13028 1 0 1 1 0 0 +EDGE2 3465 1206 0.00910088 0.990343 1.60056 1 0 1 1 0 0 +EDGE2 3465 3226 0.0431266 1.03614 1.58534 1 0 1 1 0 0 +EDGE2 3465 3366 0.0110043 0.97344 1.5445 1 0 1 1 0 0 +EDGE2 3465 3206 -0.0249909 0.987338 1.54187 1 0 1 1 0 0 +EDGE2 3465 706 0.115191 1.02142 1.61614 1 0 1 1 0 0 +EDGE2 3466 865 -0.942851 -0.0626273 1.5627 1 0 1 1 0 0 +EDGE2 3466 3225 -0.918827 -0.0290018 -1.54722 1 0 1 1 0 0 +EDGE2 3466 3425 -1.06576 0.016811 1.59771 1 0 1 1 0 0 +EDGE2 3466 3445 -1.07986 0.00384056 1.60383 1 0 1 1 0 0 +EDGE2 3466 3465 -1.04423 0.0121486 -1.54789 1 0 1 1 0 0 +EDGE2 3466 3365 -0.940997 -0.0429914 -1.5684 1 0 1 1 0 0 +EDGE2 3466 1205 -1.01331 0.176905 1.55616 1 0 1 1 0 0 +EDGE2 3466 3205 -0.975986 -0.01753 -1.57801 1 0 1 1 0 0 +EDGE2 3466 905 -0.938632 -0.063102 1.54225 1 0 1 1 0 0 +EDGE2 3466 705 -1.0732 0.0157824 -1.54932 1 0 1 1 0 0 +EDGE2 3466 825 -1.01982 0.00523872 -1.57477 1 0 1 1 0 0 +EDGE2 3466 845 -0.920351 0.0334912 1.5704 1 0 1 1 0 0 +EDGE2 3466 3367 1.01967 -0.0144731 0.0259314 1 0 1 1 0 0 +EDGE2 3466 1206 -0.130094 0.0440369 -0.0148134 1 0 1 1 0 0 +EDGE2 3466 3226 0.05838 -0.0327702 0.00214797 1 0 1 1 0 0 +EDGE2 3466 3366 -0.0291222 0.00388099 0.00185783 1 0 1 1 0 0 +EDGE2 3466 3206 -0.0256699 -0.0110916 0.0301083 1 0 1 1 0 0 +EDGE2 3466 706 -0.0470253 0.0229695 0.0376513 1 0 1 1 0 0 +EDGE2 3466 1207 0.978895 -0.0397281 -0.00450079 1 0 1 1 0 0 +EDGE2 3466 3207 1.0402 0.0531444 0.00510426 1 0 1 1 0 0 +EDGE2 3466 3227 1.01605 0.0467347 -0.0230099 1 0 1 1 0 0 +EDGE2 3466 707 0.994841 0.0206434 -0.0180795 1 0 1 1 0 0 +EDGE2 3467 3228 0.977932 0.00956127 0.0269617 1 0 1 1 0 0 +EDGE2 3467 3367 0.021352 0.0444048 0.000653094 1 0 1 1 0 0 +EDGE2 3467 1206 -0.921327 0.0375375 -0.024985 1 0 1 1 0 0 +EDGE2 3467 3226 -0.942212 0.0248127 0.00908943 1 0 1 1 0 0 +EDGE2 3467 3366 -1.04 0.0307841 0.00594012 1 0 1 1 0 0 +EDGE2 3467 3466 -0.990027 -0.0562229 0.0064505 1 0 1 1 0 0 +EDGE2 3467 3206 -0.951382 -0.0169987 -0.0508528 1 0 1 1 0 0 +EDGE2 3467 706 -0.951713 -0.0522098 0.0184702 1 0 1 1 0 0 +EDGE2 3467 1207 -0.0244868 0.0272999 0.0361814 1 0 1 1 0 0 +EDGE2 3467 3207 -0.0235618 0.00936806 -0.00753575 1 0 1 1 0 0 +EDGE2 3467 3227 0.0647506 -0.0966807 -0.00348324 1 0 1 1 0 0 +EDGE2 3467 707 0.0271104 -0.0469383 0.00190414 1 0 1 1 0 0 +EDGE2 3467 3368 1.03885 -0.0104727 -0.01054 1 0 1 1 0 0 +EDGE2 3467 708 1.04624 -0.0290052 -0.0198597 1 0 1 1 0 0 +EDGE2 3467 1208 0.995518 -0.0612433 0.0211745 1 0 1 1 0 0 +EDGE2 3467 3208 0.968576 -0.00350235 0.00159142 1 0 1 1 0 0 +EDGE2 3468 3228 0.00666145 0.0792552 -0.0007253 1 0 1 1 0 0 +EDGE2 3468 3367 -1.02715 -0.0386215 -0.0215145 1 0 1 1 0 0 +EDGE2 3468 3467 -1.05203 0.0475583 0.00701407 1 0 1 1 0 0 +EDGE2 3468 1207 -0.941295 -0.017767 0.00078966 1 0 1 1 0 0 +EDGE2 3468 3207 -0.949487 -0.00319251 0.00652929 1 0 1 1 0 0 +EDGE2 3468 3227 -1.05616 0.0329026 0.044684 1 0 1 1 0 0 +EDGE2 3468 707 -0.992708 0.0556453 -0.0293968 1 0 1 1 0 0 +EDGE2 3468 3368 -0.0569889 0.00755594 -0.0317273 1 0 1 1 0 0 +EDGE2 3468 3369 1.01102 -0.0192546 -0.0116582 1 0 1 1 0 0 +EDGE2 3468 708 -0.00642924 -0.0310999 -0.0210655 1 0 1 1 0 0 +EDGE2 3468 1208 0.0206992 -0.00496415 0.0341971 1 0 1 1 0 0 +EDGE2 3468 3208 -0.0344268 -0.0224195 -0.018461 1 0 1 1 0 0 +EDGE2 3468 1209 0.929618 -0.0883198 0.0203492 1 0 1 1 0 0 +EDGE2 3468 3209 0.97391 0.0183319 -0.00748021 1 0 1 1 0 0 +EDGE2 3468 3229 0.957439 -0.0833835 0.00253195 1 0 1 1 0 0 +EDGE2 3468 709 0.98653 0.050217 -0.0475014 1 0 1 1 0 0 +EDGE2 3469 3228 -0.963611 -0.0139065 -0.0304145 1 0 1 1 0 0 +EDGE2 3469 3468 -0.995457 0.0388252 0.0122795 1 0 1 1 0 0 +EDGE2 3469 3368 -1.05048 0.0347534 -0.00914437 1 0 1 1 0 0 +EDGE2 3469 3370 1.00908 0.0184477 0.0470646 1 0 1 1 0 0 +EDGE2 3469 3369 0.0506485 -0.0406112 0.00699285 1 0 1 1 0 0 +EDGE2 3469 708 -1.05113 0.0186173 0.0123138 1 0 1 1 0 0 +EDGE2 3469 1208 -0.994747 -0.0289991 -0.0346529 1 0 1 1 0 0 +EDGE2 3469 3208 -0.99999 0.0953825 -0.00562862 1 0 1 1 0 0 +EDGE2 3469 1209 -0.00959915 0.0571018 -0.00569757 1 0 1 1 0 0 +EDGE2 3469 3209 0.0533102 -0.0643014 -0.00295617 1 0 1 1 0 0 +EDGE2 3469 3229 -0.0746409 0.0154188 -0.0183128 1 0 1 1 0 0 +EDGE2 3469 709 -0.0207945 -0.0391831 -0.0525697 1 0 1 1 0 0 +EDGE2 3469 730 0.914588 0.0493364 -3.15252 1 0 1 1 0 0 +EDGE2 3469 3190 1.02224 0.0429823 -3.14808 1 0 1 1 0 0 +EDGE2 3469 3210 1.10433 -0.00748489 0.0112845 1 0 1 1 0 0 +EDGE2 3469 3230 1.0635 0.00117133 -0.0187545 1 0 1 1 0 0 +EDGE2 3469 1210 0.943313 0.00667667 0.00928208 1 0 1 1 0 0 +EDGE2 3469 710 1.06434 -0.117847 0.0166287 1 0 1 1 0 0 +EDGE2 3470 1211 0.0636554 0.99639 1.57282 1 0 1 1 0 0 +EDGE2 3470 3211 -0.0605335 1.03944 1.54934 1 0 1 1 0 0 +EDGE2 3470 3231 -0.0061193 0.933934 1.57916 1 0 1 1 0 0 +EDGE2 3470 3191 0.0671955 0.979683 1.56476 1 0 1 1 0 0 +EDGE2 3470 711 0.01875 0.98282 1.58038 1 0 1 1 0 0 +EDGE2 3470 731 0.0542731 0.953927 1.58514 1 0 1 1 0 0 +EDGE2 3470 3370 0.0136747 -0.0918694 0.0179615 1 0 1 1 0 0 +EDGE2 3470 3369 -1.00391 -0.0352686 0.00432434 1 0 1 1 0 0 +EDGE2 3470 3469 -0.906826 -0.0602125 0.00976375 1 0 1 1 0 0 +EDGE2 3470 1209 -0.959068 -0.0721417 0.0126059 1 0 1 1 0 0 +EDGE2 3470 3209 -0.92767 -0.053546 0.0124132 1 0 1 1 0 0 +EDGE2 3470 3229 -1.05879 -0.0510497 -0.0216451 1 0 1 1 0 0 +EDGE2 3470 709 -1.0145 -0.0104735 -0.0256445 1 0 1 1 0 0 +EDGE2 3470 730 0.0418844 -0.0388119 -3.12386 1 0 1 1 0 0 +EDGE2 3470 3190 -0.00558025 0.0566592 -3.16345 1 0 1 1 0 0 +EDGE2 3470 3210 0.0118207 0.0127257 0.0084629 1 0 1 1 0 0 +EDGE2 3470 3230 -0.00791343 0.0886182 0.0103022 1 0 1 1 0 0 +EDGE2 3470 1210 0.0319086 -0.0117149 0.00165569 1 0 1 1 0 0 +EDGE2 3470 710 -0.00754324 -0.005722 0.0212975 1 0 1 1 0 0 +EDGE2 3470 3371 0.0825265 -1.02966 -1.58208 1 0 1 1 0 0 +EDGE2 3470 3189 1.02997 -0.00246228 -3.12093 1 0 1 1 0 0 +EDGE2 3470 729 0.965461 0.00144387 -3.13832 1 0 1 1 0 0 +EDGE2 3471 3370 -1.0279 -0.0204923 1.59644 1 0 1 1 0 0 +EDGE2 3471 3470 -1.02321 -0.0736128 1.54874 1 0 1 1 0 0 +EDGE2 3471 730 -1.01745 -0.0205296 -1.53882 1 0 1 1 0 0 +EDGE2 3471 3190 -1.04084 0.0220336 -1.54617 1 0 1 1 0 0 +EDGE2 3471 3210 -0.927634 0.0248402 1.57575 1 0 1 1 0 0 +EDGE2 3471 3230 -0.981165 -0.0110934 1.55988 1 0 1 1 0 0 +EDGE2 3471 1210 -0.937515 0.002699 1.57968 1 0 1 1 0 0 +EDGE2 3471 710 -0.953089 0.0298446 1.61305 1 0 1 1 0 0 +EDGE2 3471 3371 0.0112215 0.138901 0.0136882 1 0 1 1 0 0 +EDGE2 3471 3372 0.980937 0.0453978 0.00545283 1 0 1 1 0 0 +EDGE2 3472 3471 -1.04601 0.060214 0.00326683 1 0 1 1 0 0 +EDGE2 3472 3371 -0.977242 -0.101218 0.00840559 1 0 1 1 0 0 +EDGE2 3472 3373 1.04774 0.0199201 0.016651 1 0 1 1 0 0 +EDGE2 3472 3372 0.0339362 0.00600107 -0.028396 1 0 1 1 0 0 +EDGE2 3473 3373 0.0302143 0.0296347 0.0200751 1 0 1 1 0 0 +EDGE2 3473 3372 -0.969845 0.040304 0.00421045 1 0 1 1 0 0 +EDGE2 3473 3472 -1.06767 0.0230089 0.0330303 1 0 1 1 0 0 +EDGE2 3473 3374 1.03968 -0.033735 -0.00429131 1 0 1 1 0 0 +EDGE2 3474 3373 -0.943399 0.00784255 -0.00485763 1 0 1 1 0 0 +EDGE2 3474 3473 -1.02048 0.00183409 0.0140625 1 0 1 1 0 0 +EDGE2 3474 3374 0.00501378 -0.0318475 0.00200276 1 0 1 1 0 0 +EDGE2 3474 3115 1.06883 -0.0208005 -3.11555 1 0 1 1 0 0 +EDGE2 3474 3175 0.913143 -0.0478693 -3.15255 1 0 1 1 0 0 +EDGE2 3474 3375 1.05646 0.0180577 -0.0291219 1 0 1 1 0 0 +EDGE2 3474 3135 1.07862 -0.00321271 -3.12062 1 0 1 1 0 0 +EDGE2 3474 1175 0.925316 -0.0117166 -3.14001 1 0 1 1 0 0 +EDGE2 3474 1195 1.0109 0.0441855 -3.17764 1 0 1 1 0 0 +EDGE2 3474 3095 1.06227 -0.0283655 -3.14243 1 0 1 1 0 0 +EDGE2 3474 1155 0.998796 0.0472892 -3.12516 1 0 1 1 0 0 +EDGE2 3475 3474 -1.00961 -0.0369806 -0.0110015 1 0 1 1 0 0 +EDGE2 3475 3374 -1.05596 0.0661547 0.0429345 1 0 1 1 0 0 +EDGE2 3475 1196 0.0857194 -0.942056 -1.53438 1 0 1 1 0 0 +EDGE2 3475 3116 0.0722975 -0.988842 -1.60512 1 0 1 1 0 0 +EDGE2 3475 3136 -0.0331443 -0.911291 -1.53747 1 0 1 1 0 0 +EDGE2 3475 3376 0.0981694 -1.0964 -1.55388 1 0 1 1 0 0 +EDGE2 3475 3096 0.135627 -0.944144 -1.57785 1 0 1 1 0 0 +EDGE2 3475 1156 0.00893132 -0.968752 -1.58232 1 0 1 1 0 0 +EDGE2 3475 1176 -0.0706572 -0.974654 -1.58165 1 0 1 1 0 0 +EDGE2 3475 1174 1.05324 0.0761676 -3.1389 1 0 1 1 0 0 +EDGE2 3475 3115 -0.0370544 0.0444659 -3.14937 1 0 1 1 0 0 +EDGE2 3475 3175 -0.0314292 -0.0714299 -3.11655 1 0 1 1 0 0 +EDGE2 3475 3375 0.00676296 -0.0283719 0.0245533 1 0 1 1 0 0 +EDGE2 3475 3135 0.00963876 0.0466019 -3.17781 1 0 1 1 0 0 +EDGE2 3475 1175 0.0890716 -0.0395436 -3.14193 1 0 1 1 0 0 +EDGE2 3475 1195 -0.0268596 6.10801e-05 -3.16883 1 0 1 1 0 0 +EDGE2 3475 3095 -0.0446356 0.0303793 -3.15347 1 0 1 1 0 0 +EDGE2 3475 1155 0.0664383 0.0409612 -3.15183 1 0 1 1 0 0 +EDGE2 3475 3174 1.08111 -0.0421437 -3.12911 1 0 1 1 0 0 +EDGE2 3475 3094 1.06657 -0.0309155 -3.13533 1 0 1 1 0 0 +EDGE2 3475 3114 1.06421 0.0225965 -3.12177 1 0 1 1 0 0 +EDGE2 3475 3134 1.04932 -0.0922438 -3.1426 1 0 1 1 0 0 +EDGE2 3475 1194 1.01782 -0.0401724 -3.12719 1 0 1 1 0 0 +EDGE2 3475 1154 0.974243 -0.0693319 -3.11699 1 0 1 1 0 0 +EDGE2 3475 3176 -0.0913302 0.992796 1.57222 1 0 1 1 0 0 +EDGE2 3476 1197 1.0493 -0.0202389 0.00715957 1 0 1 1 0 0 +EDGE2 3476 3117 1.05715 -0.108443 0.0376118 1 0 1 1 0 0 +EDGE2 3476 3137 0.980958 -0.0430985 -0.0441186 1 0 1 1 0 0 +EDGE2 3476 3377 1.1019 0.0425448 -0.00487509 1 0 1 1 0 0 +EDGE2 3476 3097 0.975504 0.00698341 -0.0183872 1 0 1 1 0 0 +EDGE2 3476 1177 1.02197 -0.120683 0.00318295 1 0 1 1 0 0 +EDGE2 3476 1157 0.952546 0.0119372 0.000110588 1 0 1 1 0 0 +EDGE2 3476 1196 0.0274743 0.0163402 -0.0255904 1 0 1 1 0 0 +EDGE2 3476 3116 0.113448 0.00148569 -0.00578866 1 0 1 1 0 0 +EDGE2 3476 3136 -0.00700816 -0.0415938 0.0104095 1 0 1 1 0 0 +EDGE2 3476 3376 -0.00141117 -0.0802947 0.0398218 1 0 1 1 0 0 +EDGE2 3476 3096 0.0656318 0.0566216 0.0197701 1 0 1 1 0 0 +EDGE2 3476 1156 0.0265608 0.0138795 0.030523 1 0 1 1 0 0 +EDGE2 3476 1176 0.0141437 0.125695 0.00621305 1 0 1 1 0 0 +EDGE2 3476 3115 -0.976128 0.00931174 -1.58573 1 0 1 1 0 0 +EDGE2 3476 3175 -1.00712 0.08016 -1.55563 1 0 1 1 0 0 +EDGE2 3476 3375 -1.06419 0.0976172 1.55159 1 0 1 1 0 0 +EDGE2 3476 3475 -0.936296 -0.0629482 1.5396 1 0 1 1 0 0 +EDGE2 3476 3135 -1.06279 0.0102855 -1.5571 1 0 1 1 0 0 +EDGE2 3476 1175 -1.00134 -0.000608823 -1.54893 1 0 1 1 0 0 +EDGE2 3476 1195 -0.961008 0.0479855 -1.58701 1 0 1 1 0 0 +EDGE2 3476 3095 -0.971573 -0.00985028 -1.55101 1 0 1 1 0 0 +EDGE2 3476 1155 -1.00352 0.0545027 -1.58058 1 0 1 1 0 0 +EDGE2 3477 1197 0.0393551 0.0459263 -0.0117576 1 0 1 1 0 0 +EDGE2 3477 3098 1.04676 -0.00995312 0.00383084 1 0 1 1 0 0 +EDGE2 3477 3138 0.991758 0.0264457 -0.0078882 1 0 1 1 0 0 +EDGE2 3477 3378 0.980948 0.0664108 0.00901739 1 0 1 1 0 0 +EDGE2 3477 3118 0.987316 -0.0728716 -0.00916899 1 0 1 1 0 0 +EDGE2 3477 1178 0.983136 0.0154297 -0.0190958 1 0 1 1 0 0 +EDGE2 3477 1198 1.08076 0.0981111 0.0100139 1 0 1 1 0 0 +EDGE2 3477 1158 0.991393 -0.0453075 0.023727 1 0 1 1 0 0 +EDGE2 3477 3117 -0.00652149 0.0896432 -0.00910144 1 0 1 1 0 0 +EDGE2 3477 3137 -0.0332431 0.0347067 0.0084097 1 0 1 1 0 0 +EDGE2 3477 3377 -0.0215067 0.0135556 0.0138574 1 0 1 1 0 0 +EDGE2 3477 3097 -0.0184597 0.0385445 -0.00546053 1 0 1 1 0 0 +EDGE2 3477 1177 0.054185 -0.0235611 0.0134408 1 0 1 1 0 0 +EDGE2 3477 1157 0.0157891 -0.0348387 -0.0235732 1 0 1 1 0 0 +EDGE2 3477 1196 -1.04204 -0.0226478 -0.010194 1 0 1 1 0 0 +EDGE2 3477 3476 -1.0362 0.0244283 0.00987156 1 0 1 1 0 0 +EDGE2 3477 3116 -0.986243 -0.0220505 0.0204152 1 0 1 1 0 0 +EDGE2 3477 3136 -0.991511 0.0127939 -0.00589014 1 0 1 1 0 0 +EDGE2 3477 3376 -1.03891 -0.0565272 -0.0176155 1 0 1 1 0 0 +EDGE2 3477 3096 -0.985669 -0.015364 -0.00798911 1 0 1 1 0 0 +EDGE2 3477 1156 -1.00263 -0.0129025 0.0113802 1 0 1 1 0 0 +EDGE2 3477 1176 -0.933434 -0.00819096 -0.00298984 1 0 1 1 0 0 +EDGE2 3478 1197 -0.936692 0.0779305 0.00897749 1 0 1 1 0 0 +EDGE2 3478 3119 0.838414 0.0209496 0.0117676 1 0 1 1 0 0 +EDGE2 3478 3379 0.93983 0.0156077 -0.0264763 1 0 1 1 0 0 +EDGE2 3478 3139 0.962164 0.021969 0.0118108 1 0 1 1 0 0 +EDGE2 3478 1179 1.02451 -0.0308416 -0.00104418 1 0 1 1 0 0 +EDGE2 3478 1199 0.994981 -0.0118753 0.00336858 1 0 1 1 0 0 +EDGE2 3478 3099 0.983547 -0.00712363 -0.0105592 1 0 1 1 0 0 +EDGE2 3478 1159 0.96541 0.0138335 -0.029292 1 0 1 1 0 0 +EDGE2 3478 3098 -0.0460612 -0.0307965 -0.00326912 1 0 1 1 0 0 +EDGE2 3478 3138 -0.093834 0.00283364 -0.00679382 1 0 1 1 0 0 +EDGE2 3478 3378 -0.00442116 0.0521873 0.0189933 1 0 1 1 0 0 +EDGE2 3478 3118 0.00139705 0.0193754 -0.0100932 1 0 1 1 0 0 +EDGE2 3478 1178 -0.0190472 -0.0212077 0.0122883 1 0 1 1 0 0 +EDGE2 3478 1198 0.068799 0.0103425 -0.00460382 1 0 1 1 0 0 +EDGE2 3478 1158 -0.0219156 0.0403016 -0.0433249 1 0 1 1 0 0 +EDGE2 3478 3477 -0.992214 0.0733693 -0.0210602 1 0 1 1 0 0 +EDGE2 3478 3117 -0.949653 0.025457 -0.0137984 1 0 1 1 0 0 +EDGE2 3478 3137 -1.02775 -0.074008 0.0174354 1 0 1 1 0 0 +EDGE2 3478 3377 -1.0228 0.0679462 0.00116315 1 0 1 1 0 0 +EDGE2 3478 3097 -1.03835 0.0635861 0.00548933 1 0 1 1 0 0 +EDGE2 3478 1177 -1.0022 0.0146603 -0.0136653 1 0 1 1 0 0 +EDGE2 3478 1157 -1.05293 0.0511633 0.0151162 1 0 1 1 0 0 +EDGE2 3479 1160 0.932353 -0.0376539 0.00947707 1 0 1 1 0 0 +EDGE2 3479 3140 0.968755 0.00586298 0.0251988 1 0 1 1 0 0 +EDGE2 3479 3420 0.955509 0.0273181 -3.12188 1 0 1 1 0 0 +EDGE2 3479 3440 0.919454 0.00441263 -3.13347 1 0 1 1 0 0 +EDGE2 3479 3380 1.04147 -0.0170683 0.0142789 1 0 1 1 0 0 +EDGE2 3479 1200 0.985586 -0.0693338 -4.06765e-05 1 0 1 1 0 0 +EDGE2 3479 3100 1.0053 -0.165658 0.0170171 1 0 1 1 0 0 +EDGE2 3479 3120 1.07455 -0.0207796 0.0141841 1 0 1 1 0 0 +EDGE2 3479 1180 1.0919 0.0410613 0.010596 1 0 1 1 0 0 +EDGE2 3479 900 0.963375 0.0354089 -3.15412 1 0 1 1 0 0 +EDGE2 3479 840 0.957471 0.00225368 -3.13406 1 0 1 1 0 0 +EDGE2 3479 860 0.98696 0.0303466 -3.157 1 0 1 1 0 0 +EDGE2 3479 3119 0.026363 0.0359007 0.0227998 1 0 1 1 0 0 +EDGE2 3479 3379 0.105884 -0.000608254 -0.00147232 1 0 1 1 0 0 +EDGE2 3479 3139 0.0860562 0.0464361 -0.00159667 1 0 1 1 0 0 +EDGE2 3479 1179 0.0127108 0.0101896 0.0345141 1 0 1 1 0 0 +EDGE2 3479 1199 -0.002652 0.0390413 -0.0374884 1 0 1 1 0 0 +EDGE2 3479 3099 -0.0483629 0.0125945 0.0130939 1 0 1 1 0 0 +EDGE2 3479 1159 -0.014934 -0.00218816 0.0167299 1 0 1 1 0 0 +EDGE2 3479 3098 -1.00891 -0.0450119 0.0156379 1 0 1 1 0 0 +EDGE2 3479 3138 -1.03928 0.00535875 -0.00143589 1 0 1 1 0 0 +EDGE2 3479 3378 -1.01079 -0.03241 -0.00786946 1 0 1 1 0 0 +EDGE2 3479 3478 -1.06006 -0.0223011 0.00701099 1 0 1 1 0 0 +EDGE2 3479 3118 -1.01694 -0.0242792 0.028882 1 0 1 1 0 0 +EDGE2 3479 1178 -1.04284 0.0834809 -0.00586612 1 0 1 1 0 0 +EDGE2 3479 1198 -1.04661 -0.011738 -0.0016979 1 0 1 1 0 0 +EDGE2 3479 1158 -1.10773 0.0644641 -0.0188793 1 0 1 1 0 0 +EDGE2 3480 839 0.978266 0.0147324 -3.17344 1 0 1 1 0 0 +EDGE2 3480 899 1.08771 0.0206033 -3.14344 1 0 1 1 0 0 +EDGE2 3480 3419 0.999525 -0.0214388 -3.1828 1 0 1 1 0 0 +EDGE2 3480 3439 0.94636 0.0437536 -3.13108 1 0 1 1 0 0 +EDGE2 3480 859 1.01883 -0.0499085 -3.14382 1 0 1 1 0 0 +EDGE2 3480 3441 0.0368643 -1.0101 -1.55126 1 0 1 1 0 0 +EDGE2 3480 841 0.0672763 -1.08249 -1.5813 1 0 1 1 0 0 +EDGE2 3480 901 0.00751743 -0.992722 -1.56565 1 0 1 1 0 0 +EDGE2 3480 1201 0.0700098 -1.08565 -1.53569 1 0 1 1 0 0 +EDGE2 3480 3421 0.00473809 -1.07023 -1.57195 1 0 1 1 0 0 +EDGE2 3480 861 -0.0344903 -1.02523 -1.5692 1 0 1 1 0 0 +EDGE2 3480 1160 -0.019469 -0.0259989 0.0181295 1 0 1 1 0 0 +EDGE2 3480 3140 -0.0522575 0.0529801 0.00803384 1 0 1 1 0 0 +EDGE2 3480 3420 -0.0376743 -0.0221665 -3.13791 1 0 1 1 0 0 +EDGE2 3480 3440 0.0352271 0.03847 -3.16566 1 0 1 1 0 0 +EDGE2 3480 3380 -0.0963808 0.0327203 0.00136725 1 0 1 1 0 0 +EDGE2 3480 1200 0.0672023 0.0407551 0.00959315 1 0 1 1 0 0 +EDGE2 3480 3100 -0.0185748 0.0657964 0.0436572 1 0 1 1 0 0 +EDGE2 3480 3120 -0.022398 0.0213433 -0.0104868 1 0 1 1 0 0 +EDGE2 3480 1180 0.0511569 0.100104 0.00420533 1 0 1 1 0 0 +EDGE2 3480 900 -0.0411684 0.0788418 -3.18623 1 0 1 1 0 0 +EDGE2 3480 840 -0.0671127 -0.00566664 -3.1253 1 0 1 1 0 0 +EDGE2 3480 860 0.00880047 -0.0303502 -3.11494 1 0 1 1 0 0 +EDGE2 3480 3101 0.0236579 0.920536 1.56775 1 0 1 1 0 0 +EDGE2 3480 3141 0.0147996 1.01717 1.55535 1 0 1 1 0 0 +EDGE2 3480 3381 0.109608 0.939522 1.57234 1 0 1 1 0 0 +EDGE2 3480 3121 -0.073887 0.931402 1.57277 1 0 1 1 0 0 +EDGE2 3480 1161 -0.0845376 1.05208 1.56082 1 0 1 1 0 0 +EDGE2 3480 1181 -0.050754 0.974342 1.59281 1 0 1 1 0 0 +EDGE2 3480 3119 -1.09437 -0.00803576 -0.0240055 1 0 1 1 0 0 +EDGE2 3480 3379 -0.975501 -0.0141601 0.0116704 1 0 1 1 0 0 +EDGE2 3480 3479 -1.04381 0.0210123 0.0265095 1 0 1 1 0 0 +EDGE2 3480 3139 -1.00877 -0.00502612 -0.0255085 1 0 1 1 0 0 +EDGE2 3480 1179 -1.08581 -0.00858462 -0.00475823 1 0 1 1 0 0 +EDGE2 3480 1199 -0.98833 -0.0239273 -0.0317418 1 0 1 1 0 0 +EDGE2 3480 3099 -0.929719 -0.0711227 -0.00251972 1 0 1 1 0 0 +EDGE2 3480 1159 -0.894197 0.0318083 0.0135486 1 0 1 1 0 0 +EDGE2 3481 1160 -1.10712 0.044214 -1.58502 1 0 1 1 0 0 +EDGE2 3481 3140 -0.968709 0.0157373 -1.59618 1 0 1 1 0 0 +EDGE2 3481 3420 -1.05137 0.0497044 1.55115 1 0 1 1 0 0 +EDGE2 3481 3440 -1.0565 -0.0349549 1.59686 1 0 1 1 0 0 +EDGE2 3481 3480 -0.870701 -0.030621 -1.56647 1 0 1 1 0 0 +EDGE2 3481 3380 -1.03709 -0.0183871 -1.56685 1 0 1 1 0 0 +EDGE2 3481 1200 -0.954019 0.0868678 -1.53577 1 0 1 1 0 0 +EDGE2 3481 3100 -0.997999 -0.0695802 -1.5235 1 0 1 1 0 0 +EDGE2 3481 3120 -1.02549 0.00393441 -1.57424 1 0 1 1 0 0 +EDGE2 3481 1180 -1.03612 0.0236727 -1.60467 1 0 1 1 0 0 +EDGE2 3481 900 -0.990552 -0.0346032 1.57392 1 0 1 1 0 0 +EDGE2 3481 840 -0.995959 -0.0879169 1.58508 1 0 1 1 0 0 +EDGE2 3481 860 -1.08914 0.0764543 1.60417 1 0 1 1 0 0 +EDGE2 3481 3101 -0.105488 -0.0916852 -0.00752902 1 0 1 1 0 0 +EDGE2 3481 3141 0.0194105 -0.0392586 -0.00165718 1 0 1 1 0 0 +EDGE2 3481 3381 0.076386 0.0224878 -0.00748138 1 0 1 1 0 0 +EDGE2 3481 3121 0.0533905 -0.0674085 -0.0470014 1 0 1 1 0 0 +EDGE2 3481 1161 -0.0387185 -0.0166893 -0.00649333 1 0 1 1 0 0 +EDGE2 3481 1181 -0.0509988 -0.0521032 -0.00709545 1 0 1 1 0 0 +EDGE2 3481 1182 0.953056 0.0147776 0.00991417 1 0 1 1 0 0 +EDGE2 3481 3122 0.918648 -0.0405855 0.00103541 1 0 1 1 0 0 +EDGE2 3481 3142 1.06591 -0.058817 0.0245152 1 0 1 1 0 0 +EDGE2 3481 3382 1.06132 0.023566 -0.0236406 1 0 1 1 0 0 +EDGE2 3481 3102 1.10702 -0.0434691 0.0131424 1 0 1 1 0 0 +EDGE2 3481 1162 0.898925 0.0536938 -0.0329903 1 0 1 1 0 0 +EDGE2 3482 3383 0.974144 0.0106105 0.000454542 1 0 1 1 0 0 +EDGE2 3482 3101 -0.99967 -0.0268269 -0.0334794 1 0 1 1 0 0 +EDGE2 3482 3141 -0.969865 -0.00856721 0.0207578 1 0 1 1 0 0 +EDGE2 3482 3381 -1.0783 0.0247878 -0.0330753 1 0 1 1 0 0 +EDGE2 3482 3481 -0.895621 0.000381909 -0.0267411 1 0 1 1 0 0 +EDGE2 3482 3121 -0.916143 0.0103591 -0.0380315 1 0 1 1 0 0 +EDGE2 3482 1161 -1.06644 -0.00402568 0.0110258 1 0 1 1 0 0 +EDGE2 3482 1181 -1.04465 -0.0576793 0.0195164 1 0 1 1 0 0 +EDGE2 3482 1182 0.0349375 0.0188271 -0.0231271 1 0 1 1 0 0 +EDGE2 3482 3122 -0.0287532 -0.0516479 -0.0182203 1 0 1 1 0 0 +EDGE2 3482 3142 0.0140019 -0.0822003 0.00787572 1 0 1 1 0 0 +EDGE2 3482 3382 -0.00533262 0.0633897 0.0327583 1 0 1 1 0 0 +EDGE2 3482 3102 0.0749888 -0.0551822 -0.00722366 1 0 1 1 0 0 +EDGE2 3482 1162 0.0569758 0.00248376 0.0118794 1 0 1 1 0 0 +EDGE2 3482 1163 1.04933 -0.000338748 -0.0356894 1 0 1 1 0 0 +EDGE2 3482 3103 1.00532 0.0678805 0.0508951 1 0 1 1 0 0 +EDGE2 3482 3123 1.03475 -0.0706497 -0.0193567 1 0 1 1 0 0 +EDGE2 3482 3143 1.03205 -0.0481449 -0.0226238 1 0 1 1 0 0 +EDGE2 3482 1183 0.999347 0.00893098 0.014658 1 0 1 1 0 0 +EDGE2 3483 3383 -0.110002 -0.0646598 -0.00696151 1 0 1 1 0 0 +EDGE2 3483 3482 -0.997117 -0.0491252 -0.00625577 1 0 1 1 0 0 +EDGE2 3483 1182 -1.01311 0.0119669 -0.0146831 1 0 1 1 0 0 +EDGE2 3483 3122 -0.931995 0.0760277 -0.00626114 1 0 1 1 0 0 +EDGE2 3483 3142 -1.02868 -0.0673066 -0.00432702 1 0 1 1 0 0 +EDGE2 3483 3382 -0.987072 0.0216425 -0.0147104 1 0 1 1 0 0 +EDGE2 3483 3102 -0.964798 0.0194056 0.0118377 1 0 1 1 0 0 +EDGE2 3483 1162 -1.07751 0.0592216 0.0307114 1 0 1 1 0 0 +EDGE2 3483 3144 1.03438 0.00930699 0.052047 1 0 1 1 0 0 +EDGE2 3483 1163 0.00155106 -0.0953829 0.00124933 1 0 1 1 0 0 +EDGE2 3483 3103 0.0507287 0.00544284 0.0103057 1 0 1 1 0 0 +EDGE2 3483 3123 0.0315647 -0.0329367 0.0238119 1 0 1 1 0 0 +EDGE2 3483 3143 -0.0598893 -0.0282596 0.00348096 1 0 1 1 0 0 +EDGE2 3483 1183 -0.0364871 0.0250212 0.0116405 1 0 1 1 0 0 +EDGE2 3483 3384 0.976538 -0.00973764 -0.000111581 1 0 1 1 0 0 +EDGE2 3483 1184 0.949727 -0.027246 -0.0203856 1 0 1 1 0 0 +EDGE2 3483 3104 1.07421 -0.0328467 0.0261834 1 0 1 1 0 0 +EDGE2 3483 3124 1.03916 -0.00912591 0.0264728 1 0 1 1 0 0 +EDGE2 3483 1164 0.987424 -0.0504104 0.00569808 1 0 1 1 0 0 +EDGE2 3484 3383 -0.929476 0.0453316 -0.0187534 1 0 1 1 0 0 +EDGE2 3484 3483 -1.03559 -0.138851 -0.00327423 1 0 1 1 0 0 +EDGE2 3484 3144 0.0513125 0.0642788 -0.0238445 1 0 1 1 0 0 +EDGE2 3484 1163 -1.05274 0.106471 0.0101011 1 0 1 1 0 0 +EDGE2 3484 3103 -0.844553 -0.0105966 -0.0107423 1 0 1 1 0 0 +EDGE2 3484 3123 -0.962035 0.14419 -0.00600315 1 0 1 1 0 0 +EDGE2 3484 3143 -0.928956 -0.0774507 -0.0152501 1 0 1 1 0 0 +EDGE2 3484 1183 -0.903767 0.042182 -0.0169035 1 0 1 1 0 0 +EDGE2 3484 3384 -0.0466183 -0.0331613 -0.0255016 1 0 1 1 0 0 +EDGE2 3484 1184 0.061592 0.0241312 0.0247168 1 0 1 1 0 0 +EDGE2 3484 3104 0.0578686 0.0347202 -0.0223878 1 0 1 1 0 0 +EDGE2 3484 3124 -0.0321401 -0.0184021 0.0154112 1 0 1 1 0 0 +EDGE2 3484 1164 0.051282 0.00725065 0.00578363 1 0 1 1 0 0 +EDGE2 3484 3105 0.931705 0.0861825 0.029509 1 0 1 1 0 0 +EDGE2 3484 3145 1.05009 -0.0494606 0.00237457 1 0 1 1 0 0 +EDGE2 3484 3165 1.03963 -0.050066 -3.13126 1 0 1 1 0 0 +EDGE2 3484 3385 0.990692 -0.0212785 0.0136231 1 0 1 1 0 0 +EDGE2 3484 3125 1.0797 0.0571149 -0.0456022 1 0 1 1 0 0 +EDGE2 3484 1185 0.966658 0.032929 0.00326419 1 0 1 1 0 0 +EDGE2 3484 3065 0.948136 -0.0628418 -3.13821 1 0 1 1 0 0 +EDGE2 3484 3085 0.934505 0.0276773 -3.12378 1 0 1 1 0 0 +EDGE2 3484 1165 0.960573 -0.0400254 -0.0213797 1 0 1 1 0 0 +EDGE2 3485 3146 0.101377 -0.992354 -1.5265 1 0 1 1 0 0 +EDGE2 3485 3386 -0.0965358 -1.0294 -1.53886 1 0 1 1 0 0 +EDGE2 3485 3066 0.0213227 -1.02986 -1.5801 1 0 1 1 0 0 +EDGE2 3485 3144 -0.998531 0.0770875 -0.0237751 1 0 1 1 0 0 +EDGE2 3485 3484 -0.941532 -0.0358928 0.0290388 1 0 1 1 0 0 +EDGE2 3485 3384 -1.02327 -0.00670253 -0.0194475 1 0 1 1 0 0 +EDGE2 3485 1184 -1.01496 -0.0552567 -0.0284341 1 0 1 1 0 0 +EDGE2 3485 3104 -1.06895 -0.0359622 0.0198744 1 0 1 1 0 0 +EDGE2 3485 3124 -0.979254 -0.0353972 -0.00070725 1 0 1 1 0 0 +EDGE2 3485 1164 -1.03749 -0.0165163 -0.0358832 1 0 1 1 0 0 +EDGE2 3485 3166 0.0805555 1.00264 1.58827 1 0 1 1 0 0 +EDGE2 3485 3105 -0.0554872 -0.0427739 0.00687268 1 0 1 1 0 0 +EDGE2 3485 3145 0.0041122 -0.0118156 -0.0363754 1 0 1 1 0 0 +EDGE2 3485 3165 -0.0203593 -0.012007 -3.1134 1 0 1 1 0 0 +EDGE2 3485 3385 0.0322741 0.0107872 0.0285716 1 0 1 1 0 0 +EDGE2 3485 3125 0.0857908 0.0395479 0.00849296 1 0 1 1 0 0 +EDGE2 3485 1185 -0.047621 -0.0364104 0.00259801 1 0 1 1 0 0 +EDGE2 3485 3065 -0.00537135 0.0269196 -3.1319 1 0 1 1 0 0 +EDGE2 3485 3085 -0.0263077 -0.0279797 -3.12313 1 0 1 1 0 0 +EDGE2 3485 1165 -0.00540445 -0.0238801 0.0104519 1 0 1 1 0 0 +EDGE2 3485 1166 -0.0357343 1.05501 1.58046 1 0 1 1 0 0 +EDGE2 3485 3086 -0.0863723 1.02975 1.54706 1 0 1 1 0 0 +EDGE2 3485 3106 0.00384215 0.991556 1.54544 1 0 1 1 0 0 +EDGE2 3485 3126 -0.0147697 1.08685 1.60376 1 0 1 1 0 0 +EDGE2 3485 1186 -0.0186498 0.986439 1.58324 1 0 1 1 0 0 +EDGE2 3485 3064 1.0389 0.0345751 -3.13617 1 0 1 1 0 0 +EDGE2 3485 3164 0.956178 -0.0569417 -3.13598 1 0 1 1 0 0 +EDGE2 3485 3084 0.897823 -0.0612097 -3.15194 1 0 1 1 0 0 +EDGE2 3486 3166 -0.0918061 -0.102919 -0.0430035 1 0 1 1 0 0 +EDGE2 3486 3105 -0.980692 -0.0304865 -1.56717 1 0 1 1 0 0 +EDGE2 3486 3485 -1.02017 0.000630792 -1.59675 1 0 1 1 0 0 +EDGE2 3486 3145 -0.991781 0.0994014 -1.58568 1 0 1 1 0 0 +EDGE2 3486 3165 -1.04502 -0.00508594 1.5603 1 0 1 1 0 0 +EDGE2 3486 3385 -0.998143 0.0459237 -1.54356 1 0 1 1 0 0 +EDGE2 3486 3125 -1.01403 0.0836063 -1.55123 1 0 1 1 0 0 +EDGE2 3486 1185 -0.96652 0.0166487 -1.55575 1 0 1 1 0 0 +EDGE2 3486 3065 -1.02608 0.0493171 1.53758 1 0 1 1 0 0 +EDGE2 3486 3085 -1.02957 -0.015073 1.55833 1 0 1 1 0 0 +EDGE2 3486 1165 -0.952674 -0.00820703 -1.60557 1 0 1 1 0 0 +EDGE2 3486 1166 0.0627181 -0.0526567 0.00905365 1 0 1 1 0 0 +EDGE2 3486 3086 0.0195533 0.0147044 -0.00693312 1 0 1 1 0 0 +EDGE2 3486 3106 0.0653004 0.0109074 0.00221785 1 0 1 1 0 0 +EDGE2 3486 3126 0.0851749 0.0171745 -0.0118796 1 0 1 1 0 0 +EDGE2 3486 1186 0.0338317 -0.0610249 -0.0273269 1 0 1 1 0 0 +EDGE2 3486 3107 1.05387 0.0742661 -0.00194189 1 0 1 1 0 0 +EDGE2 3486 3167 1.00676 -0.0539718 0.0318547 1 0 1 1 0 0 +EDGE2 3486 3127 0.98257 0.0205451 0.000520705 1 0 1 1 0 0 +EDGE2 3486 1187 1.02785 -0.0354497 -0.0262757 1 0 1 1 0 0 +EDGE2 3486 3087 1.05907 0.0503057 -0.0147918 1 0 1 1 0 0 +EDGE2 3486 1167 0.941381 -0.00389104 0.000136567 1 0 1 1 0 0 +EDGE2 3487 3166 -0.911008 0.0362841 -0.0354746 1 0 1 1 0 0 +EDGE2 3487 3486 -1.01087 0.0166419 -0.0133437 1 0 1 1 0 0 +EDGE2 3487 1166 -0.950163 -0.139192 -0.0246481 1 0 1 1 0 0 +EDGE2 3487 3086 -1.00553 0.0556377 -0.0154566 1 0 1 1 0 0 +EDGE2 3487 3106 -1.0569 -0.00236006 -0.0221624 1 0 1 1 0 0 +EDGE2 3487 3126 -0.955213 0.0479036 -0.00130629 1 0 1 1 0 0 +EDGE2 3487 1186 -1.04241 -0.00406324 0.00157599 1 0 1 1 0 0 +EDGE2 3487 3107 -0.0126157 0.0916056 -0.00771107 1 0 1 1 0 0 +EDGE2 3487 3167 -0.0407874 -0.0113719 -0.0117055 1 0 1 1 0 0 +EDGE2 3487 3127 -0.00570738 -0.0690187 -0.0106505 1 0 1 1 0 0 +EDGE2 3487 1187 0.0368493 -0.016015 -0.0249382 1 0 1 1 0 0 +EDGE2 3487 3087 -0.0854716 -0.0155801 -0.0265555 1 0 1 1 0 0 +EDGE2 3487 1167 0.0326211 0.014802 0.00362969 1 0 1 1 0 0 +EDGE2 3487 3128 1.07699 0.102022 -0.00729156 1 0 1 1 0 0 +EDGE2 3487 3168 0.975372 -0.0536225 -0.0218169 1 0 1 1 0 0 +EDGE2 3487 1188 1.0362 0.047893 0.00433888 1 0 1 1 0 0 +EDGE2 3487 3088 0.910236 -0.0243888 -0.0160089 1 0 1 1 0 0 +EDGE2 3487 3108 1.02826 -0.0281706 0.0464233 1 0 1 1 0 0 +EDGE2 3487 1168 0.982065 0.00685784 0.021693 1 0 1 1 0 0 +EDGE2 3488 3107 -0.956955 -0.0721995 -0.0420491 1 0 1 1 0 0 +EDGE2 3488 3167 -0.996298 -0.00851587 0.0157466 1 0 1 1 0 0 +EDGE2 3488 3487 -0.94739 0.0385675 0.000988121 1 0 1 1 0 0 +EDGE2 3488 3127 -0.991197 0.0147366 -0.0332786 1 0 1 1 0 0 +EDGE2 3488 1187 -1.07496 0.0608742 -0.000318893 1 0 1 1 0 0 +EDGE2 3488 3087 -0.929485 0.0260462 -0.026799 1 0 1 1 0 0 +EDGE2 3488 1167 -1.01014 -0.0555156 0.026194 1 0 1 1 0 0 +EDGE2 3488 3128 0.0750027 -0.0555236 -0.00969289 1 0 1 1 0 0 +EDGE2 3488 3168 0.000271775 -0.0830665 0.0184202 1 0 1 1 0 0 +EDGE2 3488 1188 0.0850804 -0.0497798 -0.0221326 1 0 1 1 0 0 +EDGE2 3488 3088 -0.019676 0.0529264 0.00290068 1 0 1 1 0 0 +EDGE2 3488 3108 -0.014024 -0.0529312 -0.00100407 1 0 1 1 0 0 +EDGE2 3488 1168 0.0385901 0.0157638 -0.0278438 1 0 1 1 0 0 +EDGE2 3488 3109 1.06053 0.0535018 0.0103019 1 0 1 1 0 0 +EDGE2 3488 3169 0.979882 -0.0395732 -0.00497341 1 0 1 1 0 0 +EDGE2 3488 3129 0.966562 0.0398651 -0.0229955 1 0 1 1 0 0 +EDGE2 3488 1189 1.01679 0.0164674 -0.00461851 1 0 1 1 0 0 +EDGE2 3488 3089 0.957728 -0.039153 -0.0107727 1 0 1 1 0 0 +EDGE2 3488 1169 0.973955 0.0610943 -0.00759267 1 0 1 1 0 0 +EDGE2 3489 3128 -0.997904 -0.0640356 -0.00431233 1 0 1 1 0 0 +EDGE2 3489 3488 -1.03712 -0.0356536 0.00551557 1 0 1 1 0 0 +EDGE2 3489 3168 -0.965048 0.00834082 -0.00195574 1 0 1 1 0 0 +EDGE2 3489 1188 -1.06772 0.0224218 -0.00818513 1 0 1 1 0 0 +EDGE2 3489 3088 -1.03389 0.0268844 -0.0298502 1 0 1 1 0 0 +EDGE2 3489 3108 -1.08206 -0.0985627 0.0161313 1 0 1 1 0 0 +EDGE2 3489 1168 -0.990708 0.0342625 -0.0304602 1 0 1 1 0 0 +EDGE2 3489 3109 -0.0412466 0.015933 0.0109386 1 0 1 1 0 0 +EDGE2 3489 3169 -0.0217455 0.00333756 -0.0442037 1 0 1 1 0 0 +EDGE2 3489 3129 0.0425274 0.0218214 -0.0450437 1 0 1 1 0 0 +EDGE2 3489 1189 0.0236366 -0.0203733 -0.00203299 1 0 1 1 0 0 +EDGE2 3489 3089 0.0868941 -0.0533606 0.00110672 1 0 1 1 0 0 +EDGE2 3489 1169 -0.0518 0.0457155 -0.0235064 1 0 1 1 0 0 +EDGE2 3489 3050 1.05062 0.0506542 -3.15373 1 0 1 1 0 0 +EDGE2 3489 3170 0.99099 0.0210984 0.0469311 1 0 1 1 0 0 +EDGE2 3489 3110 1.04821 0.0395031 0.00999843 1 0 1 1 0 0 +EDGE2 3489 3130 0.890921 -0.018235 -0.0243652 1 0 1 1 0 0 +EDGE2 3489 3090 1.01914 -0.0314066 0.0174829 1 0 1 1 0 0 +EDGE2 3489 1130 1.11037 0.0732696 -3.16655 1 0 1 1 0 0 +EDGE2 3489 1170 1.06462 -0.00581145 0.0140655 1 0 1 1 0 0 +EDGE2 3489 1190 1.00209 -0.00798984 -0.00773126 1 0 1 1 0 0 +EDGE2 3489 3030 0.99822 0.037859 -3.16482 1 0 1 1 0 0 +EDGE2 3489 1150 0.919682 0.0112843 -3.18069 1 0 1 1 0 0 +EDGE2 3489 1110 0.991684 0.019698 -3.12042 1 0 1 1 0 0 +EDGE2 3490 3109 -1.0233 -0.0647236 0.0032229 1 0 1 1 0 0 +EDGE2 3490 3169 -0.954591 0.0379152 -0.0350903 1 0 1 1 0 0 +EDGE2 3490 3489 -0.964949 -0.00567222 0.0453549 1 0 1 1 0 0 +EDGE2 3490 3129 -0.923968 0.0489836 0.0253576 1 0 1 1 0 0 +EDGE2 3490 1189 -1.05608 -0.0026326 -0.0272491 1 0 1 1 0 0 +EDGE2 3490 3089 -0.972842 -0.0461711 -0.0249934 1 0 1 1 0 0 +EDGE2 3490 1169 -1.00318 -0.0923537 -0.0323425 1 0 1 1 0 0 +EDGE2 3490 3050 -0.0385209 -0.0444333 -3.14008 1 0 1 1 0 0 +EDGE2 3490 3131 0.051157 1.01905 1.56875 1 0 1 1 0 0 +EDGE2 3490 3171 0.00947276 0.952548 1.58732 1 0 1 1 0 0 +EDGE2 3490 1151 -0.00807008 1.01905 1.54284 1 0 1 1 0 0 +EDGE2 3490 1191 -0.000827908 1.039 1.56251 1 0 1 1 0 0 +EDGE2 3490 3091 -0.010945 0.9437 1.54375 1 0 1 1 0 0 +EDGE2 3490 3111 0.0403865 0.994057 1.60282 1 0 1 1 0 0 +EDGE2 3490 1171 -0.0626795 0.991593 1.56168 1 0 1 1 0 0 +EDGE2 3490 3170 0.0179133 0.0810622 0.00750687 1 0 1 1 0 0 +EDGE2 3490 3110 0.0333176 0.0097427 -0.00802946 1 0 1 1 0 0 +EDGE2 3490 3130 -0.0229323 0.0756078 0.00777036 1 0 1 1 0 0 +EDGE2 3490 3090 -0.0276378 -0.0294194 0.00826992 1 0 1 1 0 0 +EDGE2 3490 1130 -0.0228626 -0.0171196 -3.10814 1 0 1 1 0 0 +EDGE2 3490 1170 0.00428582 0.0487445 -0.00621315 1 0 1 1 0 0 +EDGE2 3490 1190 -0.105539 0.00806451 0.00264228 1 0 1 1 0 0 +EDGE2 3490 3030 0.0283868 -0.0324267 -3.17672 1 0 1 1 0 0 +EDGE2 3490 1150 0.0443982 -0.155323 -3.14 1 0 1 1 0 0 +EDGE2 3490 1110 -0.0134124 0.025339 -3.14436 1 0 1 1 0 0 +EDGE2 3490 1109 0.979141 -0.0538606 -3.14317 1 0 1 1 0 0 +EDGE2 3490 1149 0.920513 -0.0184424 -3.14094 1 0 1 1 0 0 +EDGE2 3490 3029 1.02352 -0.0236169 -3.14592 1 0 1 1 0 0 +EDGE2 3490 3049 1.00152 -0.0677461 -3.15797 1 0 1 1 0 0 +EDGE2 3490 1129 0.927376 0.0136913 -3.13269 1 0 1 1 0 0 +EDGE2 3490 1111 -0.0206184 -1.02506 -1.5835 1 0 1 1 0 0 +EDGE2 3490 3031 -0.00340348 -0.858622 -1.55962 1 0 1 1 0 0 +EDGE2 3490 3051 -0.0161327 -1.02087 -1.5674 1 0 1 1 0 0 +EDGE2 3490 1131 -0.0760576 -0.995178 -1.53941 1 0 1 1 0 0 +EDGE2 3491 3050 -0.956586 -0.0549068 1.58953 1 0 1 1 0 0 +EDGE2 3491 3131 -0.0342006 -0.072827 0.0353499 1 0 1 1 0 0 +EDGE2 3491 3092 0.986995 -0.039815 -0.037776 1 0 1 1 0 0 +EDGE2 3491 3132 0.919373 0.0315298 -0.00336075 1 0 1 1 0 0 +EDGE2 3491 3172 0.921463 0.104416 0.0167891 1 0 1 1 0 0 +EDGE2 3491 3112 0.972628 -0.0766345 0.0104982 1 0 1 1 0 0 +EDGE2 3491 1152 0.936901 0.0222175 -0.000915181 1 0 1 1 0 0 +EDGE2 3491 1172 1.00948 -0.0159166 -0.00382526 1 0 1 1 0 0 +EDGE2 3491 1192 1.01511 0.00937239 -0.0119337 1 0 1 1 0 0 +EDGE2 3491 3171 -0.0169044 -0.00901655 0.00740355 1 0 1 1 0 0 +EDGE2 3491 1151 0.0631816 -0.0122786 -0.0261542 1 0 1 1 0 0 +EDGE2 3491 1191 0.0301001 0.01654 -0.0344146 1 0 1 1 0 0 +EDGE2 3491 3091 -0.0396627 -0.00874413 -0.0428275 1 0 1 1 0 0 +EDGE2 3491 3111 -0.0843522 -0.0257727 -0.0189769 1 0 1 1 0 0 +EDGE2 3491 1171 0.0400463 -0.0173708 0.0079713 1 0 1 1 0 0 +EDGE2 3491 3170 -1.06811 0.0168546 -1.59264 1 0 1 1 0 0 +EDGE2 3491 3490 -0.945985 0.0304361 -1.56849 1 0 1 1 0 0 +EDGE2 3491 3110 -0.993209 -0.0125012 -1.61739 1 0 1 1 0 0 +EDGE2 3491 3130 -0.999558 -0.063219 -1.56733 1 0 1 1 0 0 +EDGE2 3491 3090 -1.01045 -0.0325597 -1.5741 1 0 1 1 0 0 +EDGE2 3491 1130 -1.04651 0.00825992 1.60332 1 0 1 1 0 0 +EDGE2 3491 1170 -1.06067 0.00189528 -1.5882 1 0 1 1 0 0 +EDGE2 3491 1190 -1.02729 -0.0143385 -1.56703 1 0 1 1 0 0 +EDGE2 3491 3030 -1.00407 -0.012327 1.57221 1 0 1 1 0 0 +EDGE2 3491 1150 -0.997634 0.0206193 1.56851 1 0 1 1 0 0 +EDGE2 3491 1110 -1.05535 -0.109437 1.58258 1 0 1 1 0 0 +EDGE2 3492 1173 0.961987 -0.0608761 -0.00721038 1 0 1 1 0 0 +EDGE2 3492 3133 0.903707 -0.0520568 -0.00284385 1 0 1 1 0 0 +EDGE2 3492 3173 0.954582 0.122885 0.0179036 1 0 1 1 0 0 +EDGE2 3492 3093 1.09151 0.0196442 0.0269559 1 0 1 1 0 0 +EDGE2 3492 3113 1.01366 0.0523142 -0.0118513 1 0 1 1 0 0 +EDGE2 3492 1193 0.896472 0.00807883 0.0237644 1 0 1 1 0 0 +EDGE2 3492 3131 -0.939731 -0.005258 0.0124155 1 0 1 1 0 0 +EDGE2 3492 3092 -0.0918207 0.0302287 -0.00748394 1 0 1 1 0 0 +EDGE2 3492 1153 1.05386 -0.0279952 0.00474437 1 0 1 1 0 0 +EDGE2 3492 3132 0.0155322 -0.0255676 -0.00343878 1 0 1 1 0 0 +EDGE2 3492 3172 -0.0173285 -0.0263983 -0.00116122 1 0 1 1 0 0 +EDGE2 3492 3112 0.00643746 -0.0119332 0.0292753 1 0 1 1 0 0 +EDGE2 3492 1152 0.000446798 -0.0197996 -0.0063588 1 0 1 1 0 0 +EDGE2 3492 1172 -0.0872856 -0.0227497 0.0253185 1 0 1 1 0 0 +EDGE2 3492 1192 0.101769 -0.0276151 -0.00375151 1 0 1 1 0 0 +EDGE2 3492 3491 -0.929104 -0.0141182 0.0320288 1 0 1 1 0 0 +EDGE2 3492 3171 -1.01922 0.0380469 0.0153645 1 0 1 1 0 0 +EDGE2 3492 1151 -0.927849 -0.0155139 0.00250542 1 0 1 1 0 0 +EDGE2 3492 1191 -0.968876 -0.0483159 0.00748928 1 0 1 1 0 0 +EDGE2 3492 3091 -1.05327 -0.043161 -0.0196147 1 0 1 1 0 0 +EDGE2 3492 3111 -0.935664 0.0798213 -0.00716897 1 0 1 1 0 0 +EDGE2 3492 1171 -1.00194 0.0528579 -0.0390389 1 0 1 1 0 0 +EDGE2 3493 1173 0.0187258 0.0606423 -0.0129352 1 0 1 1 0 0 +EDGE2 3493 1174 0.960874 0.0765151 0.00754095 1 0 1 1 0 0 +EDGE2 3493 3174 1.0289 -0.0359892 -0.0238548 1 0 1 1 0 0 +EDGE2 3493 3094 1.01862 -0.0339265 0.0138324 1 0 1 1 0 0 +EDGE2 3493 3114 0.947563 0.0528983 -0.0421867 1 0 1 1 0 0 +EDGE2 3493 3134 1.01889 -0.00405071 0.0105886 1 0 1 1 0 0 +EDGE2 3493 1194 1.04642 -0.0422948 -0.0356985 1 0 1 1 0 0 +EDGE2 3493 1154 0.958682 0.0695587 0.0329514 1 0 1 1 0 0 +EDGE2 3493 3133 0.0056378 0.028364 -0.00460685 1 0 1 1 0 0 +EDGE2 3493 3173 -0.0480476 0.0208962 -0.00706107 1 0 1 1 0 0 +EDGE2 3493 3093 -0.0151955 -0.0409251 0.0057567 1 0 1 1 0 0 +EDGE2 3493 3113 0.0149297 0.0413637 0.0299546 1 0 1 1 0 0 +EDGE2 3493 1193 -0.0262096 0.0414625 0.0069961 1 0 1 1 0 0 +EDGE2 3493 3092 -1.02263 -0.0713986 0.0230733 1 0 1 1 0 0 +EDGE2 3493 1153 -0.0713309 -0.00716586 -0.00254803 1 0 1 1 0 0 +EDGE2 3493 3132 -0.951526 0.00507646 0.0355931 1 0 1 1 0 0 +EDGE2 3493 3172 -0.999058 -0.0434865 -0.0091335 1 0 1 1 0 0 +EDGE2 3493 3492 -1.03565 -0.00843845 0.0229619 1 0 1 1 0 0 +EDGE2 3493 3112 -0.923331 0.0182959 0.0195 1 0 1 1 0 0 +EDGE2 3493 1152 -1.01238 -0.0505706 0.0511761 1 0 1 1 0 0 +EDGE2 3493 1172 -1.00536 -0.0100821 -0.0131431 1 0 1 1 0 0 +EDGE2 3493 1192 -0.940547 -0.0180264 -0.0028957 1 0 1 1 0 0 +EDGE2 3494 1173 -0.95405 0.0299534 0.0127047 1 0 1 1 0 0 +EDGE2 3494 1174 0.0579799 0.0242764 -0.00930391 1 0 1 1 0 0 +EDGE2 3494 3115 0.937954 -0.0284091 0.0096436 1 0 1 1 0 0 +EDGE2 3494 3175 1.04791 0.0824947 0.0108155 1 0 1 1 0 0 +EDGE2 3494 3375 1.00775 -0.0200288 -3.15728 1 0 1 1 0 0 +EDGE2 3494 3475 1.03349 -0.0173831 -3.15343 1 0 1 1 0 0 +EDGE2 3494 3135 0.894352 -0.100892 -0.00738189 1 0 1 1 0 0 +EDGE2 3494 1175 1.01159 -0.0582315 -0.00896181 1 0 1 1 0 0 +EDGE2 3494 1195 0.965052 0.0689463 0.00996515 1 0 1 1 0 0 +EDGE2 3494 3095 1.05214 -0.0641807 0.000276317 1 0 1 1 0 0 +EDGE2 3494 1155 0.93229 -0.11039 0.0081992 1 0 1 1 0 0 +EDGE2 3494 3174 -0.0637285 -0.0125245 -0.0155376 1 0 1 1 0 0 +EDGE2 3494 3094 0.0414906 0.0151204 -0.00485074 1 0 1 1 0 0 +EDGE2 3494 3114 0.0559034 0.0541731 0.0122277 1 0 1 1 0 0 +EDGE2 3494 3134 0.000169819 0.0530446 -0.0138809 1 0 1 1 0 0 +EDGE2 3494 1194 0.0191046 -0.0544769 0.0203089 1 0 1 1 0 0 +EDGE2 3494 1154 -0.0388163 -0.00471139 -0.000345474 1 0 1 1 0 0 +EDGE2 3494 3133 -0.962104 -0.0154255 0.0240848 1 0 1 1 0 0 +EDGE2 3494 3493 -0.990052 0.00459388 0.00191464 1 0 1 1 0 0 +EDGE2 3494 3173 -1.0002 -0.0621746 -0.0308553 1 0 1 1 0 0 +EDGE2 3494 3093 -0.971822 0.048332 0.0162166 1 0 1 1 0 0 +EDGE2 3494 3113 -0.922083 0.0259076 0.00173347 1 0 1 1 0 0 +EDGE2 3494 1193 -1.04462 -0.0531318 0.00185175 1 0 1 1 0 0 +EDGE2 3494 1153 -0.974098 -0.00877475 0.00649782 1 0 1 1 0 0 +EDGE2 3495 3474 0.983169 -0.0558454 -3.1456 1 0 1 1 0 0 +EDGE2 3495 3374 0.995142 -0.0386356 -3.14199 1 0 1 1 0 0 +EDGE2 3495 1196 0.0516418 0.937549 1.56696 1 0 1 1 0 0 +EDGE2 3495 3476 -0.0943746 1.07827 1.57554 1 0 1 1 0 0 +EDGE2 3495 3116 0.00963866 0.936934 1.59742 1 0 1 1 0 0 +EDGE2 3495 3136 0.141298 1.00087 1.54523 1 0 1 1 0 0 +EDGE2 3495 3376 -0.0220232 0.994632 1.59518 1 0 1 1 0 0 +EDGE2 3495 3096 -0.0655847 1.10645 1.56572 1 0 1 1 0 0 +EDGE2 3495 1156 -0.000821696 0.991454 1.59505 1 0 1 1 0 0 +EDGE2 3495 1176 0.0616934 0.996406 1.56817 1 0 1 1 0 0 +EDGE2 3495 1174 -0.992015 0.0431723 -0.0301748 1 0 1 1 0 0 +EDGE2 3495 3115 -0.0104176 0.02941 0.0186651 1 0 1 1 0 0 +EDGE2 3495 3175 -0.0169721 -0.0278773 0.0139055 1 0 1 1 0 0 +EDGE2 3495 3375 -0.0174728 0.045958 -3.1622 1 0 1 1 0 0 +EDGE2 3495 3475 0.0733321 -0.00467892 -3.13158 1 0 1 1 0 0 +EDGE2 3495 3135 -0.0366156 -0.00748948 -0.009615 1 0 1 1 0 0 +EDGE2 3495 1175 0.0591155 0.016942 0.00698946 1 0 1 1 0 0 +EDGE2 3495 1195 -0.000343946 0.0228374 0.0263083 1 0 1 1 0 0 +EDGE2 3495 3095 -0.0135106 -0.0259651 0.00556098 1 0 1 1 0 0 +EDGE2 3495 1155 -0.0603694 -0.014396 0.0153027 1 0 1 1 0 0 +EDGE2 3495 3174 -1.01541 0.0140119 -0.0309418 1 0 1 1 0 0 +EDGE2 3495 3494 -1.06857 -0.023172 0.00638284 1 0 1 1 0 0 +EDGE2 3495 3094 -0.991582 -0.000637325 0.0266263 1 0 1 1 0 0 +EDGE2 3495 3114 -0.930826 -0.00154826 -0.00109447 1 0 1 1 0 0 +EDGE2 3495 3134 -0.995297 0.00465961 0.00774239 1 0 1 1 0 0 +EDGE2 3495 1194 -1.01602 0.0141933 0.0112529 1 0 1 1 0 0 +EDGE2 3495 1154 -1.03899 -0.00879186 -0.0107639 1 0 1 1 0 0 +EDGE2 3495 3176 0.0240594 -1.02688 -1.58141 1 0 1 1 0 0 +EDGE2 3496 3495 -0.947263 0.133608 1.52085 1 0 1 1 0 0 +EDGE2 3496 3115 -1.03135 -0.0183526 1.54759 1 0 1 1 0 0 +EDGE2 3496 3175 -1.03042 -0.00388282 1.59349 1 0 1 1 0 0 +EDGE2 3496 3375 -1.00938 0.0111196 -1.56384 1 0 1 1 0 0 +EDGE2 3496 3475 -1.00062 -0.0227615 -1.57546 1 0 1 1 0 0 +EDGE2 3496 3135 -1.06325 0.00315587 1.56835 1 0 1 1 0 0 +EDGE2 3496 1175 -1.00406 0.0843665 1.57399 1 0 1 1 0 0 +EDGE2 3496 1195 -1.02325 0.000566254 1.58298 1 0 1 1 0 0 +EDGE2 3496 3095 -0.963733 -0.0576638 1.58302 1 0 1 1 0 0 +EDGE2 3496 1155 -1.00649 0.0127957 1.57445 1 0 1 1 0 0 +EDGE2 3496 3176 -0.0752026 -0.0128019 0.00275265 1 0 1 1 0 0 +EDGE2 3496 3177 0.995707 -0.0292804 -0.0016932 1 0 1 1 0 0 +EDGE2 3497 3176 -0.983355 0.0105025 -0.00924232 1 0 1 1 0 0 +EDGE2 3497 3496 -0.957508 -0.0183039 -0.00484086 1 0 1 1 0 0 +EDGE2 3497 3178 0.967234 0.0396519 0.0193957 1 0 1 1 0 0 +EDGE2 3497 3177 -0.0428741 0.00260418 0.000299127 1 0 1 1 0 0 +EDGE2 3498 3178 -0.0363779 -0.0376274 0.00423099 1 0 1 1 0 0 +EDGE2 3498 3177 -1.05595 -0.0686041 -0.0270288 1 0 1 1 0 0 +EDGE2 3498 3497 -0.988092 0.00595167 -0.00108822 1 0 1 1 0 0 +EDGE2 3498 3179 0.936602 -0.0746854 -0.0100769 1 0 1 1 0 0 +EDGE2 3499 3178 -1.02608 -0.0510748 -0.0270728 1 0 1 1 0 0 +EDGE2 3499 3498 -1.05759 -0.0583696 0.00433543 1 0 1 1 0 0 +EDGE2 3499 3179 -0.0602915 -0.0288311 -0.00165548 1 0 1 1 0 0 +EDGE2 3499 3020 0.998671 0.00996838 -3.15576 1 0 1 1 0 0 +EDGE2 3499 3180 1.00442 -0.0208545 -0.00345669 1 0 1 1 0 0 +EDGE2 3500 3179 -1.0342 0.130929 -0.0154651 1 0 1 1 0 0 +EDGE2 3500 3499 -0.981972 0.0429428 -0.0292903 1 0 1 1 0 0 +EDGE2 3500 3181 0.0391506 1.02677 1.55218 1 0 1 1 0 0 +EDGE2 3500 3020 -0.0662041 -0.00253161 -3.13013 1 0 1 1 0 0 +EDGE2 3500 3180 -0.0302762 0.0543072 0.0110623 1 0 1 1 0 0 +EDGE2 3500 3021 -0.0382184 -1.0489 -1.59434 1 0 1 1 0 0 +EDGE2 3500 3019 1.06845 0.0449819 -3.16482 1 0 1 1 0 0 +EDGE2 3501 3020 -0.917462 0.0182167 -1.57876 1 0 1 1 0 0 +EDGE2 3501 3180 -1.02637 0.0163171 1.59764 1 0 1 1 0 0 +EDGE2 3501 3500 -0.951027 0.134021 1.56043 1 0 1 1 0 0 +EDGE2 3501 3021 0.0995808 0.0092436 0.0187237 1 0 1 1 0 0 +EDGE2 3501 3022 0.973005 -0.036123 -0.00209097 1 0 1 1 0 0 +EDGE2 3502 3501 -0.860481 0.0541427 0.0419608 1 0 1 1 0 0 +EDGE2 3502 3021 -1.06943 -0.0456469 -0.0060502 1 0 1 1 0 0 +EDGE2 3502 3022 -0.0451621 0.0688981 -0.0262852 1 0 1 1 0 0 +EDGE2 3502 3023 0.96636 0.0785229 0.0171457 1 0 1 1 0 0 +EDGE2 3503 3022 -1.04304 -0.025092 -0.028177 1 0 1 1 0 0 +EDGE2 3503 3502 -0.919186 0.031409 0.0219264 1 0 1 1 0 0 +EDGE2 3503 3023 -0.0480516 -0.106483 0.055287 1 0 1 1 0 0 +EDGE2 3503 3024 0.963172 -0.021506 -0.00882602 1 0 1 1 0 0 +EDGE2 3504 3503 -0.984898 0.0200153 0.0101127 1 0 1 1 0 0 +EDGE2 3504 3023 -0.971207 0.0123122 -0.0167721 1 0 1 1 0 0 +EDGE2 3504 3024 0.0277695 -0.00464762 0.0045779 1 0 1 1 0 0 +EDGE2 3504 1145 1.0002 0.0444566 -3.13272 1 0 1 1 0 0 +EDGE2 3504 3045 1.04748 0.0138782 -3.13454 1 0 1 1 0 0 +EDGE2 3504 3025 1.00084 0.0734687 -0.0161433 1 0 1 1 0 0 +EDGE2 3504 1105 0.963354 0.0308473 -3.1396 1 0 1 1 0 0 +EDGE2 3504 1125 0.984904 0.0521265 -3.1433 1 0 1 1 0 0 +EDGE2 3505 3504 -1.00482 -0.0803029 0.00566764 1 0 1 1 0 0 +EDGE2 3505 3024 -1.0188 -0.053836 0.00536909 1 0 1 1 0 0 +EDGE2 3505 3046 -0.00200039 -1.06208 -1.54794 1 0 1 1 0 0 +EDGE2 3505 1126 0.0498737 -0.949827 -1.57228 1 0 1 1 0 0 +EDGE2 3505 1146 0.0448915 -1.11365 -1.5734 1 0 1 1 0 0 +EDGE2 3505 3026 0.0110159 -1.06268 -1.57102 1 0 1 1 0 0 +EDGE2 3505 1106 -0.112405 -1.01805 -1.59386 1 0 1 1 0 0 +EDGE2 3505 1145 -0.0395133 0.0378726 -3.15403 1 0 1 1 0 0 +EDGE2 3505 3045 -0.0501952 -0.0727086 -3.13385 1 0 1 1 0 0 +EDGE2 3505 3025 -0.0273288 0.000167345 -0.00771353 1 0 1 1 0 0 +EDGE2 3505 1105 -0.050536 0.0246224 -3.15447 1 0 1 1 0 0 +EDGE2 3505 1125 -0.0902252 -0.0083184 -3.1614 1 0 1 1 0 0 +EDGE2 3505 1124 1.03322 0.0194411 -3.13211 1 0 1 1 0 0 +EDGE2 3505 1144 1.0096 -0.0329611 -3.15051 1 0 1 1 0 0 +EDGE2 3505 3044 1.08299 -0.0320338 -3.14956 1 0 1 1 0 0 +EDGE2 3505 1104 1.02832 -0.0198847 -3.12346 1 0 1 1 0 0 +EDGE2 3506 1145 -0.989049 -0.00816758 1.55742 1 0 1 1 0 0 +EDGE2 3506 3045 -0.943412 0.0591551 1.56507 1 0 1 1 0 0 +EDGE2 3506 3505 -0.94466 -0.00308032 -1.54731 1 0 1 1 0 0 +EDGE2 3506 3025 -1.077 -0.034498 -1.60827 1 0 1 1 0 0 +EDGE2 3506 1105 -0.978239 -0.133761 1.55345 1 0 1 1 0 0 +EDGE2 3506 1125 -0.929549 0.0212284 1.55306 1 0 1 1 0 0 +EDGE2 3507 3506 -0.963599 0.104921 -0.0438242 1 0 1 1 0 0 +EDGE2 3508 3507 -0.969811 -0.019342 -0.00313859 1 0 1 1 0 0 +EDGE2 3509 3508 -1.01359 -0.0697332 0.0128905 1 0 1 1 0 0 +EDGE2 3510 3509 -1.00597 -0.0104936 -0.00536771 1 0 1 1 0 0 +EDGE2 3511 3510 -1.0395 -0.0074363 -1.5961 1 0 1 1 0 0 +EDGE2 3512 3511 -1.0425 0.00911824 0.00107585 1 0 1 1 0 0 +EDGE2 3513 3512 -1.00806 -0.0336677 0.00548401 1 0 1 1 0 0 +EDGE2 3514 2715 0.933097 0.0580507 -3.13293 1 0 1 1 0 0 +EDGE2 3514 3015 1.06656 0.0125892 -3.17349 1 0 1 1 0 0 +EDGE2 3514 3513 -1.06986 0.045522 0.00472109 1 0 1 1 0 0 +EDGE2 3515 3014 1.01437 -0.00388444 -3.12824 1 0 1 1 0 0 +EDGE2 3515 2714 1.05957 -0.0397292 -3.12033 1 0 1 1 0 0 +EDGE2 3515 3016 -0.047538 1.04899 1.58234 1 0 1 1 0 0 +EDGE2 3515 2715 -0.0307979 -0.0129525 -3.14722 1 0 1 1 0 0 +EDGE2 3515 3015 -0.0174293 -0.0132263 -3.1522 1 0 1 1 0 0 +EDGE2 3515 3514 -0.948773 0.00849337 -0.0089934 1 0 1 1 0 0 +EDGE2 3515 2716 0.0115363 -1.00985 -1.55335 1 0 1 1 0 0 +EDGE2 3516 2715 -0.999615 0.0412799 -1.54637 1 0 1 1 0 0 +EDGE2 3516 3015 -0.97818 0.0885294 -1.53699 1 0 1 1 0 0 +EDGE2 3516 3515 -0.951292 0.00600364 1.59052 1 0 1 1 0 0 +EDGE2 3516 2716 0.105166 -0.0306401 -0.00900026 1 0 1 1 0 0 +EDGE2 3516 2717 0.999995 -0.0119967 0.025461 1 0 1 1 0 0 +EDGE2 3517 3516 -1.02573 0.000808577 -0.0116553 1 0 1 1 0 0 +EDGE2 3517 2716 -0.973542 0.0306832 -0.00283933 1 0 1 1 0 0 +EDGE2 3517 2718 0.962889 0.0520964 -0.010744 1 0 1 1 0 0 +EDGE2 3517 2717 0.00513423 0.0743753 -0.0163644 1 0 1 1 0 0 +EDGE2 3518 2718 0.0243694 -0.0181997 -0.0123244 1 0 1 1 0 0 +EDGE2 3518 2717 -0.925136 0.0545601 -0.00899608 1 0 1 1 0 0 +EDGE2 3518 3517 -0.958181 -0.0542993 -0.00139671 1 0 1 1 0 0 +EDGE2 3518 2719 1.04817 0.00449935 0.0067028 1 0 1 1 0 0 +EDGE2 3519 2718 -1.08615 0.0283702 0.028262 1 0 1 1 0 0 +EDGE2 3519 3518 -1.05556 -0.0223099 -0.0215449 1 0 1 1 0 0 +EDGE2 3519 2719 0.0535596 -0.0631242 -0.0287333 1 0 1 1 0 0 +EDGE2 3519 2720 1.00133 -0.0729094 0.0177547 1 0 1 1 0 0 +EDGE2 3519 2740 1.04051 -0.120246 -3.11899 1 0 1 1 0 0 +EDGE2 3520 2741 -0.0534207 0.968379 1.56917 1 0 1 1 0 0 +EDGE2 3520 2719 -0.94325 -0.0209128 0.00494059 1 0 1 1 0 0 +EDGE2 3520 3519 -0.940266 -0.0475097 0.00777564 1 0 1 1 0 0 +EDGE2 3520 2721 -0.0659767 -0.922586 -1.55951 1 0 1 1 0 0 +EDGE2 3520 2720 0.143856 -0.0797211 0.0160082 1 0 1 1 0 0 +EDGE2 3520 2740 -0.0296271 0.0297793 -3.15162 1 0 1 1 0 0 +EDGE2 3520 2739 0.886348 0.0357825 -3.11154 1 0 1 1 0 0 +EDGE2 3521 3520 -0.961668 0.0149109 1.57875 1 0 1 1 0 0 +EDGE2 3521 2721 -0.00431323 0.0523023 0.0032559 1 0 1 1 0 0 +EDGE2 3521 2720 -0.871727 -0.026093 1.57719 1 0 1 1 0 0 +EDGE2 3521 2740 -0.995465 0.0903517 -1.52649 1 0 1 1 0 0 +EDGE2 3521 2722 0.931779 -0.00216388 -0.0114477 1 0 1 1 0 0 +EDGE2 3522 2721 -1.03267 0.0661984 -0.0148752 1 0 1 1 0 0 +EDGE2 3522 3521 -1.02835 -0.0748284 -0.0207494 1 0 1 1 0 0 +EDGE2 3522 2722 -0.0172562 -0.0420974 -0.0197416 1 0 1 1 0 0 +EDGE2 3522 2723 0.959418 0.07756 0.00100779 1 0 1 1 0 0 +EDGE2 3523 3522 -0.951044 0.00167459 0.021642 1 0 1 1 0 0 +EDGE2 3523 2722 -1.0468 0.104674 0.00555287 1 0 1 1 0 0 +EDGE2 3523 2724 0.946644 -0.0488006 -0.00256666 1 0 1 1 0 0 +EDGE2 3523 2723 0.0306851 -0.0127315 0.0375382 1 0 1 1 0 0 +EDGE2 3524 2724 -0.0232625 -0.0109333 -0.0184338 1 0 1 1 0 0 +EDGE2 3524 2723 -0.983764 0.114641 -0.00727474 1 0 1 1 0 0 +EDGE2 3524 3523 -0.967096 0.0127024 -0.0457458 1 0 1 1 0 0 +EDGE2 3524 2725 1.03632 -0.0320924 -0.0174631 1 0 1 1 0 0 +EDGE2 3525 2724 -1.01986 -0.02516 0.0232661 1 0 1 1 0 0 +EDGE2 3525 3524 -1.02015 -0.00684203 -0.0395435 1 0 1 1 0 0 +EDGE2 3525 2725 0.0110681 0.0223713 -0.00883601 1 0 1 1 0 0 +EDGE2 3525 2726 0.00300763 1.01025 1.58717 1 0 1 1 0 0 +EDGE2 3526 3525 -1.0288 -0.0635073 -1.60321 1 0 1 1 0 0 +EDGE2 3526 2725 -1.09853 0.0413539 -1.59039 1 0 1 1 0 0 +EDGE2 3526 2726 -0.0628834 0.00577784 0.0136065 1 0 1 1 0 0 +EDGE2 3526 2727 0.901185 -0.0552646 0.00927462 1 0 1 1 0 0 +EDGE2 3527 2728 0.973816 0.0937189 0.0377866 1 0 1 1 0 0 +EDGE2 3527 3526 -1.02465 -0.0132617 -0.00707618 1 0 1 1 0 0 +EDGE2 3527 2726 -1.00938 0.0624681 0.00710316 1 0 1 1 0 0 +EDGE2 3527 2727 0.0182331 -0.0409375 0.0228155 1 0 1 1 0 0 +EDGE2 3528 2728 0.0035496 0.0299341 0.00285274 1 0 1 1 0 0 +EDGE2 3528 2727 -0.949642 0.0655916 -0.0293502 1 0 1 1 0 0 +EDGE2 3528 3527 -1.05028 -0.0865334 0.0554163 1 0 1 1 0 0 +EDGE2 3528 2729 1.07848 0.0678871 0.00753668 1 0 1 1 0 0 +EDGE2 3529 2728 -1.07888 -0.074701 0.00986521 1 0 1 1 0 0 +EDGE2 3529 3528 -0.947741 -0.0528059 -0.0166314 1 0 1 1 0 0 +EDGE2 3529 2729 0.0299334 -0.082971 0.0196164 1 0 1 1 0 0 +EDGE2 3529 2730 1.0146 0.11079 0.0410943 1 0 1 1 0 0 +EDGE2 3530 2731 -0.0896013 1.06965 1.58264 1 0 1 1 0 0 +EDGE2 3530 2729 -1.01121 0.0781844 -0.0174103 1 0 1 1 0 0 +EDGE2 3530 3529 -0.879439 0.0577781 0.0115774 1 0 1 1 0 0 +EDGE2 3530 2730 0.0571959 0.0324265 0.0354826 1 0 1 1 0 0 +EDGE2 3531 2730 -0.96238 -0.017445 1.58152 1 0 1 1 0 0 +EDGE2 3531 3530 -0.964957 0.125054 1.56065 1 0 1 1 0 0 +EDGE2 3532 3531 -0.986559 0.0115632 0.0231128 1 0 1 1 0 0 +EDGE2 3533 3532 -0.990116 0.0021648 -0.0025664 1 0 1 1 0 0 +EDGE2 3534 3533 -0.993417 -0.0232174 -0.000592298 1 0 1 1 0 0 +EDGE2 3535 3534 -1.0824 0.0333581 0.0228418 1 0 1 1 0 0 +EDGE2 3536 3535 -0.998669 0.00218605 -1.57336 1 0 1 1 0 0 +EDGE2 3537 3536 -0.979675 0.0279147 -0.0135768 1 0 1 1 0 0 +EDGE2 3538 3537 -1.00113 0.0342806 -0.0366679 1 0 1 1 0 0 +EDGE2 3539 3538 -0.93913 -0.0042768 -0.0377137 1 0 1 1 0 0 +EDGE2 3540 3539 -1.05081 -0.0433081 0.0173491 1 0 1 1 0 0 +EDGE2 3541 3540 -1.02952 -0.0320495 -1.58284 1 0 1 1 0 0 +EDGE2 3542 3541 -1.14302 0.0122115 0.0126273 1 0 1 1 0 0 +EDGE2 3543 3542 -1.02998 -0.0158251 -0.0038643 1 0 1 1 0 0 +EDGE2 3544 3543 -1.12245 0.000320813 -0.00197206 1 0 1 1 0 0 +EDGE2 3545 3544 -0.991977 0.019332 0.015995 1 0 1 1 0 0 +EDGE2 3546 3545 -1.03457 0.0964991 1.58202 1 0 1 1 0 0 +EDGE2 3547 3546 -1.03275 0.040594 -0.0274157 1 0 1 1 0 0 +EDGE2 3548 3547 -1.00309 0.115239 -0.00537387 1 0 1 1 0 0 +EDGE2 3549 3548 -1.04803 0.0690886 -0.0243396 1 0 1 1 0 0 +EDGE2 3550 3549 -0.952172 0.0717824 -0.00388464 1 0 1 1 0 0 +EDGE2 3551 3550 -0.961377 0.00794283 -1.5598 1 0 1 1 0 0 +EDGE2 3552 3551 -0.969396 0.0384239 -0.00780742 1 0 1 1 0 0 +EDGE2 3553 3552 -0.992752 0.0198985 -0.00838609 1 0 1 1 0 0 +EDGE2 3554 3553 -0.983304 -0.155437 0.0275452 1 0 1 1 0 0 +EDGE2 3555 3554 -0.958546 -0.0392228 -0.0248179 1 0 1 1 0 0 +EDGE2 3556 3555 -1.07042 0.000662529 1.59281 1 0 1 1 0 0 +EDGE2 3557 3556 -1.07532 -0.0029848 0.00697898 1 0 1 1 0 0 +EDGE2 3558 3557 -1.0432 -0.00555093 -0.00883667 1 0 1 1 0 0 +EDGE2 3559 3558 -0.962305 0.0292042 -0.0233407 1 0 1 1 0 0 +EDGE2 3560 3559 -1.0234 -0.0650351 -0.0162196 1 0 1 1 0 0 +EDGE2 3561 3560 -1.07638 -0.0282083 -1.58543 1 0 1 1 0 0 +EDGE2 3562 3561 -1.02524 -0.0076558 0.0238883 1 0 1 1 0 0 +EDGE2 3563 3562 -1.06762 -0.0160881 -0.00678312 1 0 1 1 0 0 +EDGE2 3564 3563 -0.974793 0.034378 0.0570108 1 0 1 1 0 0 +EDGE2 3565 3564 -0.990885 0.0208647 -0.0115712 1 0 1 1 0 0 +EDGE2 3566 3565 -0.95472 0.0272684 -1.55403 1 0 1 1 0 0 +EDGE2 3567 3566 -0.955367 0.0418824 0.0149981 1 0 1 1 0 0 +EDGE2 3568 3567 -1.02124 -0.0323237 0.00621312 1 0 1 1 0 0 +EDGE2 3569 2910 1.01911 0.00315889 -3.14348 1 0 1 1 0 0 +EDGE2 3569 3568 -0.948932 0.0202907 0.00979098 1 0 1 1 0 0 +EDGE2 3570 2911 0.0777001 -1.04124 -1.57451 1 0 1 1 0 0 +EDGE2 3570 2909 0.952513 -0.0376873 -3.15211 1 0 1 1 0 0 +EDGE2 3570 2910 -0.00225685 -0.0322404 -3.13978 1 0 1 1 0 0 +EDGE2 3570 3569 -0.971372 0.0712304 0.00769236 1 0 1 1 0 0 +EDGE2 3571 2912 1.08492 0.0502632 -0.02506 1 0 1 1 0 0 +EDGE2 3571 2911 0.0391143 0.0633441 0.00920958 1 0 1 1 0 0 +EDGE2 3571 2910 -1.02522 0.0188788 -1.57105 1 0 1 1 0 0 +EDGE2 3571 3570 -0.963797 0.0463391 1.57295 1 0 1 1 0 0 +EDGE2 3572 3571 -0.995442 -0.0321783 0.0375562 1 0 1 1 0 0 +EDGE2 3572 2913 0.966451 0.0985201 0.00189892 1 0 1 1 0 0 +EDGE2 3572 2912 0.0675519 0.0509243 -0.00143275 1 0 1 1 0 0 +EDGE2 3572 2911 -0.989128 -0.0716816 0.0106331 1 0 1 1 0 0 +EDGE2 3573 2913 -0.0494993 0.0532077 -0.00955479 1 0 1 1 0 0 +EDGE2 3573 2914 1.01535 -0.0215595 0.011641 1 0 1 1 0 0 +EDGE2 3573 2912 -0.981565 0.00183027 -0.0116997 1 0 1 1 0 0 +EDGE2 3573 3572 -1.05533 -0.0360229 -0.0196795 1 0 1 1 0 0 +EDGE2 3574 2915 0.979075 -0.0187405 -0.00493297 1 0 1 1 0 0 +EDGE2 3574 2913 -1.0052 -0.0955978 0.0198127 1 0 1 1 0 0 +EDGE2 3574 2914 -0.0203834 0.0603758 -0.0243616 1 0 1 1 0 0 +EDGE2 3574 3573 -0.971841 -0.0274439 -0.00474852 1 0 1 1 0 0 +EDGE2 3575 2915 0.031871 -0.0516269 0.0242253 1 0 1 1 0 0 +EDGE2 3575 2916 -0.0127767 0.957237 1.59616 1 0 1 1 0 0 +EDGE2 3575 2914 -0.984122 0.00575851 -0.0144982 1 0 1 1 0 0 +EDGE2 3575 3574 -1.05294 0.0125736 -0.0021362 1 0 1 1 0 0 +EDGE2 3576 2915 -0.995283 0.0167943 -1.56739 1 0 1 1 0 0 +EDGE2 3576 2916 -0.0643713 -0.0673258 -0.0112923 1 0 1 1 0 0 +EDGE2 3576 2917 1.07593 -0.026736 0.0247868 1 0 1 1 0 0 +EDGE2 3576 3575 -1.03722 -0.0281393 -1.57615 1 0 1 1 0 0 +EDGE2 3577 2918 0.964455 -0.0205133 0.0196032 1 0 1 1 0 0 +EDGE2 3577 2916 -1.04577 0.00442923 0.0198777 1 0 1 1 0 0 +EDGE2 3577 2917 -0.0363104 -0.0520593 0.000815398 1 0 1 1 0 0 +EDGE2 3577 3576 -1.00369 0.098696 0.00942371 1 0 1 1 0 0 +EDGE2 3578 2919 0.971663 -0.00234636 0.0507929 1 0 1 1 0 0 +EDGE2 3578 3577 -0.982687 0.0451814 -0.00212148 1 0 1 1 0 0 +EDGE2 3578 2918 -0.0542581 0.00622857 -0.00390638 1 0 1 1 0 0 +EDGE2 3578 2917 -0.955297 -0.0250438 -0.0114321 1 0 1 1 0 0 +EDGE2 3579 2919 0.0435237 0.029882 -0.0350724 1 0 1 1 0 0 +EDGE2 3579 2920 1.00372 -0.0623815 -0.00812171 1 0 1 1 0 0 +EDGE2 3579 3578 -1.14112 0.0144984 0.00132829 1 0 1 1 0 0 +EDGE2 3579 2918 -1.02315 0.0385644 -0.0313726 1 0 1 1 0 0 +EDGE2 3580 2919 -1.04206 -0.0593621 -0.000305933 1 0 1 1 0 0 +EDGE2 3580 2921 0.00168201 0.978021 1.53627 1 0 1 1 0 0 +EDGE2 3580 2920 0.0365207 -0.0209304 0.00384788 1 0 1 1 0 0 +EDGE2 3580 3579 -1.06567 0.0330574 0.020355 1 0 1 1 0 0 +EDGE2 3581 2921 -0.0366985 0.00998678 0.00812765 1 0 1 1 0 0 +EDGE2 3581 2920 -0.973288 -0.0303672 -1.56073 1 0 1 1 0 0 +EDGE2 3581 3580 -1.10767 0.00769995 -1.58114 1 0 1 1 0 0 +EDGE2 3581 2922 0.971776 -0.0141026 0.0144286 1 0 1 1 0 0 +EDGE2 3582 2921 -0.925225 0.0492119 -0.00457359 1 0 1 1 0 0 +EDGE2 3582 3581 -0.94425 -0.0492033 0.0332098 1 0 1 1 0 0 +EDGE2 3582 2922 -0.00715235 -0.0854998 -0.0415441 1 0 1 1 0 0 +EDGE2 3582 2923 0.9559 -0.000452635 0.0130951 1 0 1 1 0 0 +EDGE2 3583 3582 -1.00687 0.00250129 -0.030165 1 0 1 1 0 0 +EDGE2 3583 2922 -0.982501 -0.00543484 0.0049259 1 0 1 1 0 0 +EDGE2 3583 2923 0.023543 -0.0904793 -0.007468 1 0 1 1 0 0 +EDGE2 3583 2924 1.05571 0.0763769 0.00201838 1 0 1 1 0 0 +EDGE2 3584 3583 -1.08641 0.0213004 0.0175959 1 0 1 1 0 0 +EDGE2 3584 2923 -1.03422 -0.0135618 -0.0188386 1 0 1 1 0 0 +EDGE2 3584 2924 -0.0186937 -0.0511115 0.00911622 1 0 1 1 0 0 +EDGE2 3584 2905 0.978364 -0.00999652 -3.11295 1 0 1 1 0 0 +EDGE2 3584 2925 1.03561 0.00655361 0.0109064 1 0 1 1 0 0 +EDGE2 3584 2945 1.07116 -0.0174696 -3.11667 1 0 1 1 0 0 +EDGE2 3585 2924 -0.945384 -0.0162895 0.0132784 1 0 1 1 0 0 +EDGE2 3585 3584 -1.02755 0.0913598 0.0154489 1 0 1 1 0 0 +EDGE2 3585 2904 0.991939 0.0563134 -3.1504 1 0 1 1 0 0 +EDGE2 3585 2946 0.0135426 -1.01259 -1.55985 1 0 1 1 0 0 +EDGE2 3585 2926 0.0161354 -0.886497 -1.52828 1 0 1 1 0 0 +EDGE2 3585 2905 0.0353393 0.0124805 -3.1499 1 0 1 1 0 0 +EDGE2 3585 2925 -0.0641648 0.113179 0.030011 1 0 1 1 0 0 +EDGE2 3585 2945 0.0370484 0.0434022 -3.14251 1 0 1 1 0 0 +EDGE2 3585 2944 0.872353 0.0839329 -3.11783 1 0 1 1 0 0 +EDGE2 3585 2906 -0.0833935 0.986016 1.58936 1 0 1 1 0 0 +EDGE2 3586 3585 -0.956421 0.0885157 -1.53498 1 0 1 1 0 0 +EDGE2 3586 2905 -0.929276 0.0137423 1.57946 1 0 1 1 0 0 +EDGE2 3586 2925 -0.91667 -0.0318268 -1.57294 1 0 1 1 0 0 +EDGE2 3586 2945 -0.993895 0.0725745 1.591 1 0 1 1 0 0 +EDGE2 3586 2906 0.069214 -0.0659293 0.00864318 1 0 1 1 0 0 +EDGE2 3586 2907 1.04175 -0.000547782 -0.0288872 1 0 1 1 0 0 +EDGE2 3587 2906 -0.957088 -0.0288489 -0.0296702 1 0 1 1 0 0 +EDGE2 3587 3586 -0.959601 0.00901637 0.0157659 1 0 1 1 0 0 +EDGE2 3587 2907 0.0068945 0.0252876 -0.00323452 1 0 1 1 0 0 +EDGE2 3587 2908 0.981425 -9.63793e-05 -0.0171357 1 0 1 1 0 0 +EDGE2 3588 3587 -1.03187 0.0791216 -0.0359867 1 0 1 1 0 0 +EDGE2 3588 2907 -1.0014 -0.0708218 0.0150541 1 0 1 1 0 0 +EDGE2 3588 2909 0.939918 -0.0150035 -0.0236937 1 0 1 1 0 0 +EDGE2 3588 2908 -0.0342716 -0.00740075 0.00944576 1 0 1 1 0 0 +EDGE2 3589 3588 -1.01791 -0.0184813 -0.0278683 1 0 1 1 0 0 +EDGE2 3589 2909 0.0387199 0.00898466 0.000782982 1 0 1 1 0 0 +EDGE2 3589 2908 -0.949017 0.00596122 -0.0253898 1 0 1 1 0 0 +EDGE2 3589 2910 1.00305 -0.0131385 0.0011917 1 0 1 1 0 0 +EDGE2 3589 3570 0.998507 0.00298486 -3.14189 1 0 1 1 0 0 +EDGE2 3590 3571 0.0325992 0.88769 1.53436 1 0 1 1 0 0 +EDGE2 3590 2911 0.0151588 1.00849 1.5834 1 0 1 1 0 0 +EDGE2 3590 2909 -1.02614 0.0402072 -0.00191257 1 0 1 1 0 0 +EDGE2 3590 3589 -1.01574 0.0140183 -0.0179101 1 0 1 1 0 0 +EDGE2 3590 2910 0.0383669 -0.00197992 -0.0219193 1 0 1 1 0 0 +EDGE2 3590 3570 -0.00928687 -0.0596512 -3.15921 1 0 1 1 0 0 +EDGE2 3590 3569 1.03319 0.0444559 -3.15936 1 0 1 1 0 0 +EDGE2 3591 3571 -0.0107973 0.0347988 0.0117479 1 0 1 1 0 0 +EDGE2 3591 2912 0.978651 0.127437 -0.0412822 1 0 1 1 0 0 +EDGE2 3591 3572 1.01006 -0.00274626 -0.0177974 1 0 1 1 0 0 +EDGE2 3591 2911 0.0135188 -0.00955984 -0.0405384 1 0 1 1 0 0 +EDGE2 3591 3590 -0.979419 0.0766736 -1.56194 1 0 1 1 0 0 +EDGE2 3591 2910 -0.979816 -0.0363535 -1.5319 1 0 1 1 0 0 +EDGE2 3591 3570 -1.06778 0.0428762 1.63487 1 0 1 1 0 0 +EDGE2 3592 3571 -0.967919 -0.0890833 0.00104042 1 0 1 1 0 0 +EDGE2 3592 2913 0.991527 -0.00410049 0.0228647 1 0 1 1 0 0 +EDGE2 3592 3573 0.95438 0.164679 0.020529 1 0 1 1 0 0 +EDGE2 3592 2912 -0.0129178 0.0450683 0.00292317 1 0 1 1 0 0 +EDGE2 3592 3572 -0.0074517 0.0130582 -0.0122558 1 0 1 1 0 0 +EDGE2 3592 3591 -0.950128 -0.0272273 -0.00115328 1 0 1 1 0 0 +EDGE2 3592 2911 -1.02601 -0.0169621 -0.0123573 1 0 1 1 0 0 +EDGE2 3593 2913 0.0182581 -0.0184161 0.0375666 1 0 1 1 0 0 +EDGE2 3593 2914 1.04624 0.0596473 -0.00873874 1 0 1 1 0 0 +EDGE2 3593 3574 0.968647 -0.125984 -0.00634673 1 0 1 1 0 0 +EDGE2 3593 3573 0.0209596 0.0435528 -0.0219829 1 0 1 1 0 0 +EDGE2 3593 2912 -1.01794 0.0481932 -0.0374172 1 0 1 1 0 0 +EDGE2 3593 3592 -1.00451 -0.129833 0.0336389 1 0 1 1 0 0 +EDGE2 3593 3572 -0.933026 0.0300776 -0.00776013 1 0 1 1 0 0 +EDGE2 3594 2915 0.996898 -0.0564112 0.0148417 1 0 1 1 0 0 +EDGE2 3594 3575 0.991482 -0.00907964 -0.00881068 1 0 1 1 0 0 +EDGE2 3594 2913 -0.990802 -0.0325868 -0.0152111 1 0 1 1 0 0 +EDGE2 3594 2914 0.011988 0.0388916 -0.00649595 1 0 1 1 0 0 +EDGE2 3594 3574 -0.0160596 0.00666248 0.00211474 1 0 1 1 0 0 +EDGE2 3594 3593 -1.00058 0.019715 -0.0325246 1 0 1 1 0 0 +EDGE2 3594 3573 -1.01146 0.0397535 -0.0800499 1 0 1 1 0 0 +EDGE2 3595 2915 -0.0657307 -0.116478 -0.0178591 1 0 1 1 0 0 +EDGE2 3595 2916 -0.00587725 1.06913 1.56548 1 0 1 1 0 0 +EDGE2 3595 3576 -0.117122 1.03451 1.57571 1 0 1 1 0 0 +EDGE2 3595 3575 -0.0483259 0.0125217 0.0115188 1 0 1 1 0 0 +EDGE2 3595 2914 -1.09475 0.00719182 -0.0139693 1 0 1 1 0 0 +EDGE2 3595 3594 -0.946674 -0.0424552 -0.0105207 1 0 1 1 0 0 +EDGE2 3595 3574 -1.03598 0.0190739 0.0509332 1 0 1 1 0 0 +EDGE2 3596 2915 -1.0455 0.0987611 1.60522 1 0 1 1 0 0 +EDGE2 3596 3595 -1.0845 0.0537835 1.56296 1 0 1 1 0 0 +EDGE2 3596 3575 -1.05453 -0.0142757 1.59922 1 0 1 1 0 0 +EDGE2 3597 3596 -1.03051 -0.0392412 -0.011753 1 0 1 1 0 0 +EDGE2 3598 3597 -0.918194 0.0876294 0.0233893 1 0 1 1 0 0 +EDGE2 3599 3598 -0.980574 -0.00686126 0.0160164 1 0 1 1 0 0 +EDGE2 3600 3599 -0.975176 -0.0165062 -0.0212474 1 0 1 1 0 0 +EDGE2 3601 3600 -0.943814 -0.0291512 -1.57116 1 0 1 1 0 0 +EDGE2 3602 3601 -1.02341 0.0424836 0.00429146 1 0 1 1 0 0 +EDGE2 3603 3602 -1.01646 -0.0570137 -0.0193973 1 0 1 1 0 0 +EDGE2 3604 3603 -0.969652 0.0312283 -0.0290956 1 0 1 1 0 0 +EDGE2 3605 3604 -1.02548 0.00653694 0.0114096 1 0 1 1 0 0 +EDGE2 3606 3605 -1.01592 0.0584634 1.57474 1 0 1 1 0 0 +EDGE2 3607 3606 -0.931031 -0.0546051 0.0143104 1 0 1 1 0 0 +EDGE2 3608 3607 -0.942369 0.0352036 0.00656692 1 0 1 1 0 0 +EDGE2 3609 3608 -1.0431 -0.0638784 0.0368552 1 0 1 1 0 0 +EDGE2 3610 3609 -1.04775 -0.0349576 -0.00773567 1 0 1 1 0 0 +EDGE2 3611 3610 -1.01138 0.0153274 -1.59196 1 0 1 1 0 0 +EDGE2 3612 3611 -0.976353 -0.115095 0.00911199 1 0 1 1 0 0 +EDGE2 3613 3612 -1.023 -0.0367008 0.0428617 1 0 1 1 0 0 +EDGE2 3614 3613 -0.998078 -0.111898 0.00830978 1 0 1 1 0 0 +EDGE2 3615 3614 -0.935508 -0.020724 -0.0239222 1 0 1 1 0 0 +EDGE2 3616 3615 -1.10848 0.00292889 1.63069 1 0 1 1 0 0 +EDGE2 3617 3616 -1.01279 -0.0219123 0.0313967 1 0 1 1 0 0 +EDGE2 3618 3617 -1.07452 0.0625042 0.00216186 1 0 1 1 0 0 +EDGE2 3619 3618 -0.939751 0.100159 0.0127405 1 0 1 1 0 0 +EDGE2 3620 3619 -1.02127 0.0525084 0.0123863 1 0 1 1 0 0 +EDGE2 3621 3620 -0.974246 0.0210147 1.62597 1 0 1 1 0 0 +EDGE2 3622 3621 -1.02903 0.03746 0.0309285 1 0 1 1 0 0 +EDGE2 3623 3622 -0.966804 -0.00565776 -0.00987388 1 0 1 1 0 0 +EDGE2 3624 3623 -1.03357 -0.040396 -0.025922 1 0 1 1 0 0 +EDGE2 3625 3624 -1.05831 0.0386432 -0.00959498 1 0 1 1 0 0 +EDGE2 3626 3625 -0.960349 -0.0299826 1.57874 1 0 1 1 0 0 +EDGE2 3627 3626 -1.02084 0.0528248 -0.0329606 1 0 1 1 0 0 +EDGE2 3628 3627 -0.947931 0.107528 -0.0317556 1 0 1 1 0 0 +EDGE2 3629 3610 0.970824 -0.00748793 -3.11687 1 0 1 1 0 0 +EDGE2 3629 3628 -1.09739 0.0328772 0.00980452 1 0 1 1 0 0 +EDGE2 3630 3609 0.982927 -0.046907 -3.13423 1 0 1 1 0 0 +EDGE2 3630 3611 0.102017 -0.968675 -1.56871 1 0 1 1 0 0 +EDGE2 3630 3610 -0.0330396 -0.058695 -3.09972 1 0 1 1 0 0 +EDGE2 3630 3629 -1.05624 0.0341764 -0.000254282 1 0 1 1 0 0 +EDGE2 3631 3610 -0.952568 0.0375447 1.60345 1 0 1 1 0 0 +EDGE2 3631 3630 -1.00018 0.0127167 -1.52002 1 0 1 1 0 0 +EDGE2 3632 3631 -0.996589 -0.0457907 0.0161413 1 0 1 1 0 0 +EDGE2 3633 3632 -1.04125 -0.0087923 0.0226833 1 0 1 1 0 0 +EDGE2 3634 3633 -0.965182 -0.0148887 -0.022681 1 0 1 1 0 0 +EDGE2 3635 3634 -1.04281 -0.00156852 0.0162475 1 0 1 1 0 0 +EDGE2 3636 3635 -1.07515 0.0494056 1.58185 1 0 1 1 0 0 +EDGE2 3637 3636 -0.936865 -0.0199754 0.0253948 1 0 1 1 0 0 +EDGE2 3638 3637 -1.0323 0.0059938 0.0337855 1 0 1 1 0 0 +EDGE2 3639 3600 1.06093 0.0606009 -3.12476 1 0 1 1 0 0 +EDGE2 3639 3638 -1.01737 -0.0572028 -0.00858159 1 0 1 1 0 0 +EDGE2 3640 3599 0.999358 0.0877098 -3.15165 1 0 1 1 0 0 +EDGE2 3640 3601 -0.0427969 -1.04692 -1.54828 1 0 1 1 0 0 +EDGE2 3640 3600 -0.0938801 -0.0420929 -3.14942 1 0 1 1 0 0 +EDGE2 3640 3639 -0.953004 -0.00131808 -0.00224262 1 0 1 1 0 0 +EDGE2 3641 3600 -1.01916 -0.00371992 1.58226 1 0 1 1 0 0 +EDGE2 3641 3640 -1.02003 0.0240006 -1.5587 1 0 1 1 0 0 +EDGE2 3642 3641 -1.05531 -0.11179 0.0153286 1 0 1 1 0 0 +EDGE2 3643 3642 -0.889089 -0.0657651 0.0110532 1 0 1 1 0 0 +EDGE2 3644 3643 -0.99882 0.0822448 0.00290775 1 0 1 1 0 0 +EDGE2 3644 3565 1.0454 -0.0369178 -3.15852 1 0 1 1 0 0 +EDGE2 3645 3644 -1.03058 0.0248238 0.0235179 1 0 1 1 0 0 +EDGE2 3645 3566 0.0682045 -0.989702 -1.56212 1 0 1 1 0 0 +EDGE2 3645 3564 1.08239 0.0987682 -3.16633 1 0 1 1 0 0 +EDGE2 3645 3565 0.0768728 0.0241578 -3.14258 1 0 1 1 0 0 +EDGE2 3646 3645 -1.00376 0.0152079 -1.55204 1 0 1 1 0 0 +EDGE2 3646 3565 -0.990516 -0.0252178 1.57058 1 0 1 1 0 0 +EDGE2 3647 3646 -0.952264 -0.028977 0.0272344 1 0 1 1 0 0 +EDGE2 3648 3647 -0.963526 -0.0435614 0.0032094 1 0 1 1 0 0 +EDGE2 3649 3648 -0.96126 -0.0323233 0.00665173 1 0 1 1 0 0 +EDGE2 3650 3649 -0.932565 0.0540064 0.0293103 1 0 1 1 0 0 +EDGE2 3651 3650 -0.96288 0.0228263 -1.57751 1 0 1 1 0 0 +EDGE2 3652 3651 -0.959668 -0.0791053 -0.00517596 1 0 1 1 0 0 +EDGE2 3653 3652 -0.927358 -0.106485 -0.0156827 1 0 1 1 0 0 +EDGE2 3654 3635 1.05674 -0.0425318 -3.15512 1 0 1 1 0 0 +EDGE2 3654 3653 -0.987693 0.077505 -0.0120653 1 0 1 1 0 0 +EDGE2 3655 3635 -0.0139849 -0.0599458 -3.15382 1 0 1 1 0 0 +EDGE2 3655 3636 -0.0051874 1.09877 1.57337 1 0 1 1 0 0 +EDGE2 3655 3634 1.00193 0.0123946 -3.11028 1 0 1 1 0 0 +EDGE2 3655 3654 -1.02966 -0.0816287 -0.0269701 1 0 1 1 0 0 +EDGE2 3656 3637 0.946253 -0.00121951 -0.0423478 1 0 1 1 0 0 +EDGE2 3656 3635 -0.930403 -0.107454 1.55183 1 0 1 1 0 0 +EDGE2 3656 3636 -0.0330365 0.0788001 0.00398207 1 0 1 1 0 0 +EDGE2 3656 3655 -0.98806 0.0773995 -1.58456 1 0 1 1 0 0 +EDGE2 3657 3637 -0.0277791 0.0078336 -0.00583115 1 0 1 1 0 0 +EDGE2 3657 3638 0.922611 -0.050769 -0.00938329 1 0 1 1 0 0 +EDGE2 3657 3656 -0.978517 -0.031589 -0.0334105 1 0 1 1 0 0 +EDGE2 3657 3636 -0.989168 -0.0170942 -0.0206121 1 0 1 1 0 0 +EDGE2 3658 3637 -0.983201 0.0715679 -0.0364407 1 0 1 1 0 0 +EDGE2 3658 3639 1.00749 0.0595843 0.025277 1 0 1 1 0 0 +EDGE2 3658 3638 0.0113056 0.0129908 0.00891385 1 0 1 1 0 0 +EDGE2 3658 3657 -0.984934 -0.00178717 -0.0337001 1 0 1 1 0 0 +EDGE2 3659 3600 0.975921 -0.0479629 -3.1464 1 0 1 1 0 0 +EDGE2 3659 3640 0.997486 0.055111 0.00260941 1 0 1 1 0 0 +EDGE2 3659 3639 -0.00575107 -0.003709 0.00793978 1 0 1 1 0 0 +EDGE2 3659 3638 -1.03721 0.0259274 0.00129721 1 0 1 1 0 0 +EDGE2 3659 3658 -1.00997 -0.0441272 -0.0354424 1 0 1 1 0 0 +EDGE2 3660 3599 0.977127 0.0494425 -3.15811 1 0 1 1 0 0 +EDGE2 3660 3601 0.0647704 -1.01943 -1.54339 1 0 1 1 0 0 +EDGE2 3660 3600 -0.00765131 0.031612 -3.15172 1 0 1 1 0 0 +EDGE2 3660 3640 0.00178278 0.0193116 0.0109734 1 0 1 1 0 0 +EDGE2 3660 3641 -0.0352855 1.01547 1.56125 1 0 1 1 0 0 +EDGE2 3660 3659 -0.984488 -0.0123034 -0.00218308 1 0 1 1 0 0 +EDGE2 3660 3639 -1.00101 -0.0475401 -0.00611724 1 0 1 1 0 0 +EDGE2 3661 3600 -0.938075 0.028362 1.57043 1 0 1 1 0 0 +EDGE2 3661 3640 -1.03444 -0.0867595 -1.55051 1 0 1 1 0 0 +EDGE2 3661 3660 -0.981941 0.10831 -1.57978 1 0 1 1 0 0 +EDGE2 3661 3641 0.132498 -0.116496 -0.00591795 1 0 1 1 0 0 +EDGE2 3661 3642 1.05368 0.0585675 0.00740229 1 0 1 1 0 0 +EDGE2 3662 3641 -1.00749 0.0360902 0.00964223 1 0 1 1 0 0 +EDGE2 3662 3661 -0.915994 0.0022261 0.0167955 1 0 1 1 0 0 +EDGE2 3662 3642 0.0111625 -0.00774905 0.0224375 1 0 1 1 0 0 +EDGE2 3662 3643 0.972981 -0.0183944 -0.00560114 1 0 1 1 0 0 +EDGE2 3663 3642 -0.943698 0.0107448 0.00295144 1 0 1 1 0 0 +EDGE2 3663 3662 -0.91616 -0.0285401 -0.0175616 1 0 1 1 0 0 +EDGE2 3663 3643 0.0100411 0.00800634 0.00531949 1 0 1 1 0 0 +EDGE2 3663 3644 1.07026 0.0703885 0.0210591 1 0 1 1 0 0 +EDGE2 3664 3663 -1.11136 -0.0653289 -0.00687109 1 0 1 1 0 0 +EDGE2 3664 3643 -1.09837 -0.0279865 -0.0173007 1 0 1 1 0 0 +EDGE2 3664 3644 -0.0875163 -0.0819351 -0.0172761 1 0 1 1 0 0 +EDGE2 3664 3645 0.939408 0.00640249 -0.00762899 1 0 1 1 0 0 +EDGE2 3664 3565 1.00844 -0.0775771 -3.1732 1 0 1 1 0 0 +EDGE2 3665 3664 -1.00631 -0.0184732 0.00496415 1 0 1 1 0 0 +EDGE2 3665 3644 -1.02593 0.0706589 0.0142616 1 0 1 1 0 0 +EDGE2 3665 3566 -0.00552096 -0.984424 -1.58323 1 0 1 1 0 0 +EDGE2 3665 3645 -0.007204 -0.0426157 0.00695124 1 0 1 1 0 0 +EDGE2 3665 3564 1.06468 -0.0346837 -3.12269 1 0 1 1 0 0 +EDGE2 3665 3565 -0.0178103 -0.0253895 -3.12097 1 0 1 1 0 0 +EDGE2 3665 3646 -0.108922 0.972537 1.57623 1 0 1 1 0 0 +EDGE2 3666 3645 -0.943084 0.0706368 -1.56814 1 0 1 1 0 0 +EDGE2 3666 3665 -1.02331 -0.0859053 -1.55476 1 0 1 1 0 0 +EDGE2 3666 3565 -0.984328 0.0127017 1.58074 1 0 1 1 0 0 +EDGE2 3666 3646 0.0537254 0.0103901 0.039712 1 0 1 1 0 0 +EDGE2 3666 3647 1.00951 -0.00171407 -0.00309797 1 0 1 1 0 0 +EDGE2 3667 3646 -0.949561 0.0135503 0.00201984 1 0 1 1 0 0 +EDGE2 3667 3666 -0.981165 -0.0213706 0.00393481 1 0 1 1 0 0 +EDGE2 3667 3647 0.0676738 0.063296 0.0135199 1 0 1 1 0 0 +EDGE2 3667 3648 0.98024 -0.049998 -0.0129066 1 0 1 1 0 0 +EDGE2 3668 3667 -0.998364 -0.00981187 -0.0170761 1 0 1 1 0 0 +EDGE2 3668 3647 -1.01869 -0.00368913 -0.0422763 1 0 1 1 0 0 +EDGE2 3668 3649 0.948205 0.0759912 0.0197072 1 0 1 1 0 0 +EDGE2 3668 3648 0.0488203 0.0121908 0.00279617 1 0 1 1 0 0 +EDGE2 3669 3650 1.04209 -0.0207037 -0.0383606 1 0 1 1 0 0 +EDGE2 3669 3668 -0.977446 -0.0293298 0.0289777 1 0 1 1 0 0 +EDGE2 3669 3649 0.0452115 0.0531896 0.00116409 1 0 1 1 0 0 +EDGE2 3669 3648 -0.956664 0.0237385 -0.0178563 1 0 1 1 0 0 +EDGE2 3670 3651 -0.0357377 0.950843 1.59643 1 0 1 1 0 0 +EDGE2 3670 3650 0.100417 0.0361745 -0.0197791 1 0 1 1 0 0 +EDGE2 3670 3649 -0.948639 0.0873893 0.00890398 1 0 1 1 0 0 +EDGE2 3670 3669 -1.02985 0.0125553 0.00366298 1 0 1 1 0 0 +EDGE2 3671 3651 -0.0150936 -0.0117416 0.0277266 1 0 1 1 0 0 +EDGE2 3671 3652 0.98499 -0.0545271 -0.0265683 1 0 1 1 0 0 +EDGE2 3671 3650 -1.07806 0.0258726 -1.57313 1 0 1 1 0 0 +EDGE2 3671 3670 -1.11899 0.0153734 -1.53199 1 0 1 1 0 0 +EDGE2 3672 3653 0.951161 -0.0217461 0.020157 1 0 1 1 0 0 +EDGE2 3672 3651 -0.910299 0.0352964 0.013362 1 0 1 1 0 0 +EDGE2 3672 3652 0.0279338 -0.0366807 -0.0104105 1 0 1 1 0 0 +EDGE2 3672 3671 -1.0228 0.042788 -0.0380944 1 0 1 1 0 0 +EDGE2 3673 3654 0.997887 -0.0693637 0.0108934 1 0 1 1 0 0 +EDGE2 3673 3653 -0.0369739 0.0123047 0.000493456 1 0 1 1 0 0 +EDGE2 3673 3652 -1.03428 0.0519354 0.013732 1 0 1 1 0 0 +EDGE2 3673 3672 -0.982241 -0.0466806 0.0281783 1 0 1 1 0 0 +EDGE2 3674 3635 0.952114 -0.0497773 -3.13826 1 0 1 1 0 0 +EDGE2 3674 3655 0.967674 -0.0377214 -0.0383964 1 0 1 1 0 0 +EDGE2 3674 3654 0.0577731 -0.0443818 0.0255072 1 0 1 1 0 0 +EDGE2 3674 3673 -1.01804 -0.0115073 -0.0479059 1 0 1 1 0 0 +EDGE2 3674 3653 -0.965545 -0.02143 0.0124965 1 0 1 1 0 0 +EDGE2 3675 3635 -0.084151 0.0278845 -3.15372 1 0 1 1 0 0 +EDGE2 3675 3656 -0.013326 1.04313 1.59483 1 0 1 1 0 0 +EDGE2 3675 3636 -0.115062 0.99691 1.56872 1 0 1 1 0 0 +EDGE2 3675 3634 1.02125 0.0605821 -3.13306 1 0 1 1 0 0 +EDGE2 3675 3655 -0.0057259 0.0677837 -0.0251505 1 0 1 1 0 0 +EDGE2 3675 3654 -1.06824 0.0409491 -0.0386799 1 0 1 1 0 0 +EDGE2 3675 3674 -0.984123 0.0139094 0.0348826 1 0 1 1 0 0 +EDGE2 3676 3637 0.930217 -0.0357881 -0.000879388 1 0 1 1 0 0 +EDGE2 3676 3657 1.06808 -0.0168068 -0.03122 1 0 1 1 0 0 +EDGE2 3676 3635 -0.983537 -0.00342793 1.54103 1 0 1 1 0 0 +EDGE2 3676 3656 -0.00149477 -0.118485 -0.0239329 1 0 1 1 0 0 +EDGE2 3676 3636 0.010752 -0.0730446 -0.0196542 1 0 1 1 0 0 +EDGE2 3676 3675 -1.00077 0.0491348 -1.55252 1 0 1 1 0 0 +EDGE2 3676 3655 -0.976859 0.0221275 -1.61391 1 0 1 1 0 0 +EDGE2 3677 3637 0.0667573 0.030067 -0.0282211 1 0 1 1 0 0 +EDGE2 3677 3638 0.976652 -0.0766061 0.000114748 1 0 1 1 0 0 +EDGE2 3677 3658 0.990633 -0.0472942 0.00450332 1 0 1 1 0 0 +EDGE2 3677 3657 0.0140486 -0.010937 0.0170494 1 0 1 1 0 0 +EDGE2 3677 3656 -1.11246 0.035453 -0.0040637 1 0 1 1 0 0 +EDGE2 3677 3676 -0.974803 0.0101884 0.0233516 1 0 1 1 0 0 +EDGE2 3677 3636 -1.01312 -0.0569524 0.0261928 1 0 1 1 0 0 +EDGE2 3678 3637 -0.991031 0.0839861 0.0189328 1 0 1 1 0 0 +EDGE2 3678 3677 -0.995045 -0.019296 -0.0229194 1 0 1 1 0 0 +EDGE2 3678 3659 1.04419 -0.127571 0.00769422 1 0 1 1 0 0 +EDGE2 3678 3639 0.926139 0.00933599 -0.00299818 1 0 1 1 0 0 +EDGE2 3678 3638 0.0580375 0.0193652 0.000514782 1 0 1 1 0 0 +EDGE2 3678 3658 -0.0067623 0.00179718 -0.000544135 1 0 1 1 0 0 +EDGE2 3678 3657 -0.953523 0.0127985 -0.016098 1 0 1 1 0 0 +EDGE2 3679 3600 1.03794 0.0440455 -3.11994 1 0 1 1 0 0 +EDGE2 3679 3640 1.04359 -0.0345957 -0.00946068 1 0 1 1 0 0 +EDGE2 3679 3660 0.964411 -0.133254 -0.00950161 1 0 1 1 0 0 +EDGE2 3679 3659 0.0116351 -0.0361145 -0.0172184 1 0 1 1 0 0 +EDGE2 3679 3639 0.0490091 -0.0387462 -0.0113838 1 0 1 1 0 0 +EDGE2 3679 3638 -1.06203 0.110751 -0.0332256 1 0 1 1 0 0 +EDGE2 3679 3658 -1.08232 -0.0517857 -0.0307969 1 0 1 1 0 0 +EDGE2 3679 3678 -0.960162 -0.0212995 0.0274471 1 0 1 1 0 0 +EDGE2 3680 3599 0.997737 -0.0136808 -3.15625 1 0 1 1 0 0 +EDGE2 3680 3601 0.0439874 -0.982298 -1.54585 1 0 1 1 0 0 +EDGE2 3680 3600 -0.00762638 0.0865488 -3.18283 1 0 1 1 0 0 +EDGE2 3680 3640 0.0350121 -0.036529 0.00159527 1 0 1 1 0 0 +EDGE2 3680 3660 0.0312722 0.0861353 -0.016773 1 0 1 1 0 0 +EDGE2 3680 3641 -0.0260765 0.974434 1.54965 1 0 1 1 0 0 +EDGE2 3680 3661 0.000402279 1.04772 1.5927 1 0 1 1 0 0 +EDGE2 3680 3659 -1.0527 0.0571453 0.00751585 1 0 1 1 0 0 +EDGE2 3680 3679 -1.03492 0.0718568 0.0336335 1 0 1 1 0 0 +EDGE2 3680 3639 -1.06185 -0.00356485 0.0166312 1 0 1 1 0 0 +EDGE2 3681 3680 -1.10766 0.0219706 -1.56984 1 0 1 1 0 0 +EDGE2 3681 3600 -1.07612 0.00425446 1.55557 1 0 1 1 0 0 +EDGE2 3681 3640 -0.977859 -0.0446112 -1.56507 1 0 1 1 0 0 +EDGE2 3681 3660 -1.01237 0.0582584 -1.5991 1 0 1 1 0 0 +EDGE2 3681 3641 0.00653382 -0.0196266 -0.0368064 1 0 1 1 0 0 +EDGE2 3681 3661 -0.0765555 -0.0917656 -0.00026158 1 0 1 1 0 0 +EDGE2 3681 3642 0.976167 0.0538403 0.0276125 1 0 1 1 0 0 +EDGE2 3681 3662 0.976746 0.0773708 0.0134166 1 0 1 1 0 0 +EDGE2 3682 3641 -0.97204 0.0542112 0.0296069 1 0 1 1 0 0 +EDGE2 3682 3661 -0.965536 0.0110692 0.014893 1 0 1 1 0 0 +EDGE2 3682 3681 -1.03257 0.0135241 -0.0227329 1 0 1 1 0 0 +EDGE2 3682 3642 0.0906116 -0.0674483 0.0131984 1 0 1 1 0 0 +EDGE2 3682 3662 0.0128565 0.0298224 -0.0320102 1 0 1 1 0 0 +EDGE2 3682 3663 1.09853 -0.0632372 -0.0318831 1 0 1 1 0 0 +EDGE2 3682 3643 1.01428 -0.0231802 -0.00172482 1 0 1 1 0 0 +EDGE2 3683 3642 -1.04192 -0.0390776 -0.000429629 1 0 1 1 0 0 +EDGE2 3683 3662 -0.92967 -0.0257449 -0.0235816 1 0 1 1 0 0 +EDGE2 3683 3682 -0.923021 -0.068705 0.0199505 1 0 1 1 0 0 +EDGE2 3683 3663 -0.0745543 0.0146394 -0.0152535 1 0 1 1 0 0 +EDGE2 3683 3643 0.0595209 0.0672097 0.0127603 1 0 1 1 0 0 +EDGE2 3683 3664 0.952215 0.00788984 -0.0114023 1 0 1 1 0 0 +EDGE2 3683 3644 1.04221 -0.105752 -0.0105859 1 0 1 1 0 0 +EDGE2 3684 3663 -0.92384 0.0517026 -0.0598606 1 0 1 1 0 0 +EDGE2 3684 3683 -0.989292 -0.00582925 -0.0204925 1 0 1 1 0 0 +EDGE2 3684 3643 -0.971986 -0.0313755 0.0179409 1 0 1 1 0 0 +EDGE2 3684 3664 0.0440051 0.0322047 -0.0480153 1 0 1 1 0 0 +EDGE2 3684 3644 -0.0545457 0.0607325 0.0182938 1 0 1 1 0 0 +EDGE2 3684 3645 1.00586 0.0857717 -0.0290666 1 0 1 1 0 0 +EDGE2 3684 3665 0.96626 -0.0537742 -0.0295627 1 0 1 1 0 0 +EDGE2 3684 3565 1.02527 0.0444686 -3.17116 1 0 1 1 0 0 +EDGE2 3685 3664 -0.926 0.0826938 0.00476264 1 0 1 1 0 0 +EDGE2 3685 3684 -0.975139 0.0293121 -0.0301922 1 0 1 1 0 0 +EDGE2 3685 3644 -1.01809 -0.0417626 0.00543402 1 0 1 1 0 0 +EDGE2 3685 3566 -0.0252876 -1.0449 -1.60044 1 0 1 1 0 0 +EDGE2 3685 3645 0.0189722 -0.0497022 -0.0014448 1 0 1 1 0 0 +EDGE2 3685 3665 0.0368235 -0.0399814 0.00973399 1 0 1 1 0 0 +EDGE2 3685 3564 0.921697 -0.058644 -3.12226 1 0 1 1 0 0 +EDGE2 3685 3565 0.00113986 0.105133 -3.15333 1 0 1 1 0 0 +EDGE2 3685 3646 0.00678826 1.02084 1.55874 1 0 1 1 0 0 +EDGE2 3685 3666 -0.0983271 1.08491 1.55655 1 0 1 1 0 0 +EDGE2 3686 3567 1.07158 -0.0477731 -0.00675654 1 0 1 1 0 0 +EDGE2 3686 3566 0.0191636 0.000590141 -0.0113134 1 0 1 1 0 0 +EDGE2 3686 3645 -1.06271 0.0922278 1.56139 1 0 1 1 0 0 +EDGE2 3686 3685 -0.983864 -0.0069697 1.55917 1 0 1 1 0 0 +EDGE2 3686 3665 -0.954342 -0.024931 1.57955 1 0 1 1 0 0 +EDGE2 3686 3565 -1.05304 -0.0019946 -1.6005 1 0 1 1 0 0 +EDGE2 3687 3568 1.07502 0.0585208 -0.00570134 1 0 1 1 0 0 +EDGE2 3687 3686 -0.963239 -0.0851099 0.00126872 1 0 1 1 0 0 +EDGE2 3687 3567 -0.00886377 0.0491079 0.0144418 1 0 1 1 0 0 +EDGE2 3687 3566 -1.01101 0.000425477 0.0292198 1 0 1 1 0 0 +EDGE2 3688 3687 -0.960416 0.111492 -0.0103461 1 0 1 1 0 0 +EDGE2 3688 3569 1.01307 0.102923 -0.0206168 1 0 1 1 0 0 +EDGE2 3688 3568 0.00461031 0.0393198 -0.00599874 1 0 1 1 0 0 +EDGE2 3688 3567 -0.932802 -0.00164529 0.0116706 1 0 1 1 0 0 +EDGE2 3689 3590 0.966683 -0.0180757 -3.13512 1 0 1 1 0 0 +EDGE2 3689 2910 1.03844 0.0226924 -3.14276 1 0 1 1 0 0 +EDGE2 3689 3570 1.00505 -0.0503803 -0.00634595 1 0 1 1 0 0 +EDGE2 3689 3688 -0.988131 0.0185087 -0.010635 1 0 1 1 0 0 +EDGE2 3689 3569 -0.0336354 -0.0242476 -0.0453365 1 0 1 1 0 0 +EDGE2 3689 3568 -0.924322 0.0151712 -0.0182566 1 0 1 1 0 0 +EDGE2 3690 3571 -0.0201875 -1.09619 -1.57926 1 0 1 1 0 0 +EDGE2 3690 3591 -0.00944743 -0.967829 -1.56116 1 0 1 1 0 0 +EDGE2 3690 2911 0.0341513 -1.0458 -1.5764 1 0 1 1 0 0 +EDGE2 3690 3590 0.0221697 -0.00712173 -3.17788 1 0 1 1 0 0 +EDGE2 3690 2909 1.05527 -0.0815975 -3.11641 1 0 1 1 0 0 +EDGE2 3690 3589 0.978796 0.0311157 -3.15616 1 0 1 1 0 0 +EDGE2 3690 2910 0.0751332 -0.0763199 -3.11739 1 0 1 1 0 0 +EDGE2 3690 3570 0.0818264 -0.017172 -0.0147625 1 0 1 1 0 0 +EDGE2 3690 3569 -0.889087 0.0118337 0.0323939 1 0 1 1 0 0 +EDGE2 3690 3689 -1.03455 -0.0925055 -0.0452923 1 0 1 1 0 0 +EDGE2 3691 3590 -1.0492 -0.00061644 1.57753 1 0 1 1 0 0 +EDGE2 3691 3690 -0.94311 0.0494219 -1.57079 1 0 1 1 0 0 +EDGE2 3691 2910 -1.072 0.0327878 1.60249 1 0 1 1 0 0 +EDGE2 3691 3570 -1.01682 0.00753929 -1.54981 1 0 1 1 0 0 +EDGE2 3692 3691 -1.05054 -0.0735366 -0.0459214 1 0 1 1 0 0 +EDGE2 3693 3692 -1.07857 -0.0654611 -0.0224196 1 0 1 1 0 0 +EDGE2 3694 3693 -1.04399 -0.0336481 -0.00562261 1 0 1 1 0 0 +EDGE2 3694 3555 0.997327 0.0620712 -3.17488 1 0 1 1 0 0 +EDGE2 3695 3694 -1.02209 -0.0798113 -0.0013626 1 0 1 1 0 0 +EDGE2 3695 3554 1.02197 0.0203155 -3.16927 1 0 1 1 0 0 +EDGE2 3695 3555 -0.00512229 -0.0339565 -3.14827 1 0 1 1 0 0 +EDGE2 3695 3556 -0.0171016 0.943508 1.58165 1 0 1 1 0 0 +EDGE2 3696 3695 -1.03837 0.0826626 -1.59136 1 0 1 1 0 0 +EDGE2 3696 3555 -1.02942 -0.0361722 1.58076 1 0 1 1 0 0 +EDGE2 3696 3556 -0.0138547 -0.00502966 0.0110093 1 0 1 1 0 0 +EDGE2 3696 3557 0.986324 -0.021248 0.0213896 1 0 1 1 0 0 +EDGE2 3697 3696 -1.06999 0.00313349 0.00391645 1 0 1 1 0 0 +EDGE2 3697 3556 -0.955815 0.131849 -0.0299087 1 0 1 1 0 0 +EDGE2 3697 3557 -0.0528445 -0.0303712 0.0247057 1 0 1 1 0 0 +EDGE2 3697 3558 1.01859 -0.0388206 -0.00741253 1 0 1 1 0 0 +EDGE2 3698 3559 0.97748 -0.051846 0.0184815 1 0 1 1 0 0 +EDGE2 3698 3697 -1.03551 -0.161276 0.00378656 1 0 1 1 0 0 +EDGE2 3698 3557 -0.96706 -0.0136164 -0.00914896 1 0 1 1 0 0 +EDGE2 3698 3558 -0.0143477 -0.0584842 -0.0262296 1 0 1 1 0 0 +EDGE2 3699 3559 0.0666971 -0.0687394 -0.0216509 1 0 1 1 0 0 +EDGE2 3699 3558 -0.955547 -0.0296589 -0.0264852 1 0 1 1 0 0 +EDGE2 3699 3698 -1.12951 -0.0348779 0.0069836 1 0 1 1 0 0 +EDGE2 3699 3560 1.0477 0.00227158 -0.0101667 1 0 1 1 0 0 +EDGE2 3700 3561 -0.0624941 0.973368 1.54349 1 0 1 1 0 0 +EDGE2 3700 3559 -0.986832 0.0590283 -0.00955548 1 0 1 1 0 0 +EDGE2 3700 3699 -1.00562 0.00443798 0.00432552 1 0 1 1 0 0 +EDGE2 3700 3560 -0.00733636 0.0224825 0.0371798 1 0 1 1 0 0 +EDGE2 3701 3700 -1.10096 0.0402593 1.55035 1 0 1 1 0 0 +EDGE2 3701 3560 -0.940193 -0.0167577 1.58097 1 0 1 1 0 0 +EDGE2 3702 3701 -0.979206 -0.0529738 0.0405162 1 0 1 1 0 0 +EDGE2 3703 3702 -0.92954 0.0196008 0.0147035 1 0 1 1 0 0 +EDGE2 3704 3703 -0.847431 -0.0223249 -0.0552438 1 0 1 1 0 0 +EDGE2 3705 3704 -1.07104 -0.0692379 0.0101596 1 0 1 1 0 0 +EDGE2 3706 3705 -0.995919 -0.000687854 -1.51349 1 0 1 1 0 0 +EDGE2 3707 3706 -0.989845 -0.0436232 0.0381672 1 0 1 1 0 0 +EDGE2 3708 3707 -1.00378 0.0324188 -0.00667088 1 0 1 1 0 0 +EDGE2 3709 3708 -1.02028 -0.0514557 0.0348667 1 0 1 1 0 0 +EDGE2 3710 3709 -1.07566 0.0601374 -0.0518474 1 0 1 1 0 0 +EDGE2 3711 3710 -1.03431 0.0171611 -1.56007 1 0 1 1 0 0 +EDGE2 3712 3711 -0.917795 -0.00812039 -0.000359261 1 0 1 1 0 0 +EDGE2 3713 3712 -1.04808 -0.0113265 0.00247798 1 0 1 1 0 0 +EDGE2 3714 3713 -0.884807 0.0102659 -0.0145048 1 0 1 1 0 0 +EDGE2 3715 3714 -1.05996 -0.0186261 0.00911967 1 0 1 1 0 0 +EDGE2 3716 3715 -1.0084 -0.0851085 -1.57092 1 0 1 1 0 0 +EDGE2 3717 3716 -1.02877 0.029613 -0.00173784 1 0 1 1 0 0 +EDGE2 3718 3717 -1.03971 -0.0188114 0.0161305 1 0 1 1 0 0 +EDGE2 3719 3700 1.02038 0.0247537 -3.13263 1 0 1 1 0 0 +EDGE2 3719 3560 0.894163 0.0255258 -3.14988 1 0 1 1 0 0 +EDGE2 3719 3718 -0.966496 0.0188424 -0.00469081 1 0 1 1 0 0 +EDGE2 3720 3561 -0.0124951 -1.04228 -1.5797 1 0 1 1 0 0 +EDGE2 3720 3559 1.08644 -0.0381539 -3.13702 1 0 1 1 0 0 +EDGE2 3720 3699 1.02409 -0.0153682 -3.16526 1 0 1 1 0 0 +EDGE2 3720 3700 0.0843101 -0.0490622 -3.12689 1 0 1 1 0 0 +EDGE2 3720 3560 0.0559174 0.0956471 -3.16772 1 0 1 1 0 0 +EDGE2 3720 3701 -0.0136142 0.915417 1.58023 1 0 1 1 0 0 +EDGE2 3720 3719 -0.967982 0.00290082 -0.0376776 1 0 1 1 0 0 +EDGE2 3721 3562 1.08871 0.020724 -0.0144969 1 0 1 1 0 0 +EDGE2 3721 3561 -0.00541945 -0.00105859 0.0170631 1 0 1 1 0 0 +EDGE2 3721 3700 -0.958107 -0.0387091 -1.59423 1 0 1 1 0 0 +EDGE2 3721 3720 -0.866254 0.0201263 1.55127 1 0 1 1 0 0 +EDGE2 3721 3560 -1.05666 0.048489 -1.55171 1 0 1 1 0 0 +EDGE2 3722 3563 0.920079 -0.0106007 0.0430783 1 0 1 1 0 0 +EDGE2 3722 3721 -0.963119 -0.0399708 -0.0208638 1 0 1 1 0 0 +EDGE2 3722 3562 0.0436504 -0.0601323 -0.0140224 1 0 1 1 0 0 +EDGE2 3722 3561 -1.03358 -0.0368845 0.0289276 1 0 1 1 0 0 +EDGE2 3723 3563 0.0216442 -0.0835854 0.0226765 1 0 1 1 0 0 +EDGE2 3723 3564 0.966983 -0.013598 -0.0189076 1 0 1 1 0 0 +EDGE2 3723 3562 -1.12166 -0.127084 0.00302305 1 0 1 1 0 0 +EDGE2 3723 3722 -0.998184 0.0509666 0.0147613 1 0 1 1 0 0 +EDGE2 3724 3563 -0.975947 0.0196322 -0.00270064 1 0 1 1 0 0 +EDGE2 3724 3645 1.02171 -0.0760256 -3.1525 1 0 1 1 0 0 +EDGE2 3724 3685 1.00185 -0.0463303 -3.14253 1 0 1 1 0 0 +EDGE2 3724 3665 0.986356 -0.107643 -3.13228 1 0 1 1 0 0 +EDGE2 3724 3564 0.0254974 -0.0283342 0.0188313 1 0 1 1 0 0 +EDGE2 3724 3565 0.959378 -0.00518737 -0.0267978 1 0 1 1 0 0 +EDGE2 3724 3723 -1.03619 0.0559304 -0.0106751 1 0 1 1 0 0 +EDGE2 3725 3664 0.8992 0.0013156 -3.14001 1 0 1 1 0 0 +EDGE2 3725 3684 0.972051 -0.0172114 -3.15361 1 0 1 1 0 0 +EDGE2 3725 3644 1.01774 0.0085185 -3.12311 1 0 1 1 0 0 +EDGE2 3725 3686 0.0134847 1.10547 1.56048 1 0 1 1 0 0 +EDGE2 3725 3566 -0.0205685 0.950738 1.56215 1 0 1 1 0 0 +EDGE2 3725 3645 0.0368262 -0.0334008 -3.17253 1 0 1 1 0 0 +EDGE2 3725 3685 -0.0255481 0.0228125 -3.12916 1 0 1 1 0 0 +EDGE2 3725 3665 0.00947114 0.156239 -3.11528 1 0 1 1 0 0 +EDGE2 3725 3564 -0.891158 0.0140257 -0.00796626 1 0 1 1 0 0 +EDGE2 3725 3724 -0.998243 -0.0384219 -0.0117312 1 0 1 1 0 0 +EDGE2 3725 3565 -0.0506441 -0.0628516 -0.0129557 1 0 1 1 0 0 +EDGE2 3725 3646 -0.0258718 -1.01141 -1.58438 1 0 1 1 0 0 +EDGE2 3725 3666 -0.0146648 -0.988376 -1.55126 1 0 1 1 0 0 +EDGE2 3726 3725 -0.885657 -0.0263261 -1.59923 1 0 1 1 0 0 +EDGE2 3726 3687 1.01704 -0.00743147 0.00917479 1 0 1 1 0 0 +EDGE2 3726 3686 0.0429305 -0.0663998 -0.023286 1 0 1 1 0 0 +EDGE2 3726 3567 0.875001 0.0181393 0.0127737 1 0 1 1 0 0 +EDGE2 3726 3566 0.00231435 -0.00751439 0.0274097 1 0 1 1 0 0 +EDGE2 3726 3645 -1.01804 0.0156331 1.56085 1 0 1 1 0 0 +EDGE2 3726 3685 -0.999291 0.0363754 1.56231 1 0 1 1 0 0 +EDGE2 3726 3665 -0.97573 -0.0348144 1.55281 1 0 1 1 0 0 +EDGE2 3726 3565 -1.04174 0.0173429 -1.58381 1 0 1 1 0 0 +EDGE2 3727 3687 -0.0276139 0.0757917 0.0113495 1 0 1 1 0 0 +EDGE2 3727 3688 1.00138 0.0108999 0.0220732 1 0 1 1 0 0 +EDGE2 3727 3568 1.0157 -0.0360974 0.0115205 1 0 1 1 0 0 +EDGE2 3727 3686 -1.00565 0.00871919 -0.0227309 1 0 1 1 0 0 +EDGE2 3727 3726 -1.01687 0.00154796 -0.0126792 1 0 1 1 0 0 +EDGE2 3727 3567 0.0217599 0.0537197 -0.0235968 1 0 1 1 0 0 +EDGE2 3727 3566 -1.13093 0.0370887 0.00379659 1 0 1 1 0 0 +EDGE2 3728 3727 -0.937435 -0.0472078 -0.0173583 1 0 1 1 0 0 +EDGE2 3728 3687 -1.02844 -0.0437393 -0.00122366 1 0 1 1 0 0 +EDGE2 3728 3688 -0.0578036 -0.0594301 -0.0300129 1 0 1 1 0 0 +EDGE2 3728 3569 1.00085 -0.0817566 -0.0688737 1 0 1 1 0 0 +EDGE2 3728 3689 0.982815 -0.0181713 0.0166715 1 0 1 1 0 0 +EDGE2 3728 3568 -0.0397189 -0.0264117 0.0210496 1 0 1 1 0 0 +EDGE2 3728 3567 -0.993794 -0.0883221 -0.000126605 1 0 1 1 0 0 +EDGE2 3729 3728 -0.987286 0.00808664 -0.0208916 1 0 1 1 0 0 +EDGE2 3729 3590 0.998487 0.0294831 -3.15222 1 0 1 1 0 0 +EDGE2 3729 3690 0.954547 0.0512879 -0.0510842 1 0 1 1 0 0 +EDGE2 3729 2910 0.997783 -0.0335405 -3.12775 1 0 1 1 0 0 +EDGE2 3729 3570 1.05983 0.0824144 0.0042071 1 0 1 1 0 0 +EDGE2 3729 3688 -0.929424 -0.011863 0.00855248 1 0 1 1 0 0 +EDGE2 3729 3569 -0.0646832 0.00237714 -0.00394774 1 0 1 1 0 0 +EDGE2 3729 3689 -0.0234536 0.0144128 -0.0403536 1 0 1 1 0 0 +EDGE2 3729 3568 -0.937867 0.0310721 -0.00489948 1 0 1 1 0 0 +EDGE2 3730 3571 0.00684654 -1.01265 -1.54997 1 0 1 1 0 0 +EDGE2 3730 3591 -0.104542 -1.04458 -1.62148 1 0 1 1 0 0 +EDGE2 3730 2911 0.112482 -1.01333 -1.58184 1 0 1 1 0 0 +EDGE2 3730 3729 -1.05972 -0.000981092 0.017705 1 0 1 1 0 0 +EDGE2 3730 3590 -0.0157334 0.0965967 -3.15761 1 0 1 1 0 0 +EDGE2 3730 2909 0.961741 -0.0617784 -3.14678 1 0 1 1 0 0 +EDGE2 3730 3589 0.972285 0.0684143 -3.16433 1 0 1 1 0 0 +EDGE2 3730 3690 0.0508101 -0.0260476 -0.00903697 1 0 1 1 0 0 +EDGE2 3730 3691 -0.0285941 1.0196 1.57387 1 0 1 1 0 0 +EDGE2 3730 2910 -0.0617419 0.0501058 -3.14864 1 0 1 1 0 0 +EDGE2 3730 3570 0.0344848 0.0396974 -0.0244695 1 0 1 1 0 0 +EDGE2 3730 3569 -0.941528 0.00757092 -0.0102081 1 0 1 1 0 0 +EDGE2 3730 3689 -1.00106 0.0089895 -0.00692221 1 0 1 1 0 0 +EDGE2 3731 3571 -0.0458269 0.00388193 0.00589737 1 0 1 1 0 0 +EDGE2 3731 2912 0.916675 -0.00881394 -0.00622342 1 0 1 1 0 0 +EDGE2 3731 3592 0.986442 -0.00680688 0.0150505 1 0 1 1 0 0 +EDGE2 3731 3572 1.03694 0.0721986 0.0226312 1 0 1 1 0 0 +EDGE2 3731 3591 0.0040277 0.0319724 0.00758073 1 0 1 1 0 0 +EDGE2 3731 2911 0.00904903 0.0232623 -0.0153659 1 0 1 1 0 0 +EDGE2 3731 3730 -1.03616 -0.0630649 1.55999 1 0 1 1 0 0 +EDGE2 3731 3590 -0.997233 0.00474378 -1.55023 1 0 1 1 0 0 +EDGE2 3731 3690 -0.981329 0.00621296 1.58695 1 0 1 1 0 0 +EDGE2 3731 2910 -1.0768 -0.0165555 -1.58647 1 0 1 1 0 0 +EDGE2 3731 3570 -1.01226 0.0200071 1.58371 1 0 1 1 0 0 +EDGE2 3732 3571 -0.953297 -0.0539516 -0.0276861 1 0 1 1 0 0 +EDGE2 3732 2913 1.13162 -0.0355137 0.00630385 1 0 1 1 0 0 +EDGE2 3732 3593 1.03816 -0.0361506 0.0173438 1 0 1 1 0 0 +EDGE2 3732 3573 0.953015 -0.0325373 -0.000670619 1 0 1 1 0 0 +EDGE2 3732 2912 0.0365161 0.0528243 0.0152629 1 0 1 1 0 0 +EDGE2 3732 3592 0.128345 -0.0193303 -0.0284646 1 0 1 1 0 0 +EDGE2 3732 3572 0.0302261 0.00660285 -0.0404096 1 0 1 1 0 0 +EDGE2 3732 3731 -0.947067 0.00233653 -0.00143042 1 0 1 1 0 0 +EDGE2 3732 3591 -0.978713 -0.0295576 0.0267087 1 0 1 1 0 0 +EDGE2 3732 2911 -0.965132 0.0657794 -0.0164817 1 0 1 1 0 0 +EDGE2 3733 2913 -0.0675652 0.0197383 -0.00542759 1 0 1 1 0 0 +EDGE2 3733 2914 1.01149 0.0105671 0.0101427 1 0 1 1 0 0 +EDGE2 3733 3594 0.915791 0.0416158 0.0133722 1 0 1 1 0 0 +EDGE2 3733 3574 1.04484 -0.123747 0.018484 1 0 1 1 0 0 +EDGE2 3733 3593 -0.0574501 -0.0256854 0.0349186 1 0 1 1 0 0 +EDGE2 3733 3573 -0.0604489 0.00559154 -0.0136389 1 0 1 1 0 0 +EDGE2 3733 2912 -1.02895 -0.00824867 -0.013569 1 0 1 1 0 0 +EDGE2 3733 3592 -1.06128 0.134965 4.33283e-05 1 0 1 1 0 0 +EDGE2 3733 3732 -0.984626 -0.0412267 -0.0265677 1 0 1 1 0 0 +EDGE2 3733 3572 -0.988758 0.059354 -0.0379221 1 0 1 1 0 0 +EDGE2 3734 2915 1.15382 0.0105815 0.0279729 1 0 1 1 0 0 +EDGE2 3734 3595 0.999646 0.0165099 -0.00582851 1 0 1 1 0 0 +EDGE2 3734 3575 1.085 -0.0311461 0.00990993 1 0 1 1 0 0 +EDGE2 3734 2913 -1.01541 0.0717467 0.000951837 1 0 1 1 0 0 +EDGE2 3734 2914 -0.0483076 -0.0349672 -0.0197628 1 0 1 1 0 0 +EDGE2 3734 3594 -0.0376112 0.0567632 0.0103963 1 0 1 1 0 0 +EDGE2 3734 3574 0.0159374 0.0436045 -0.00708036 1 0 1 1 0 0 +EDGE2 3734 3593 -1.01252 0.0571398 0.00777317 1 0 1 1 0 0 +EDGE2 3734 3733 -0.957907 0.0160018 -0.010906 1 0 1 1 0 0 +EDGE2 3734 3573 -0.993665 -0.00369589 -0.0201325 1 0 1 1 0 0 +EDGE2 3735 2915 -0.0135229 -0.0719582 -0.0158243 1 0 1 1 0 0 +EDGE2 3735 2916 0.0316733 1.00521 1.56464 1 0 1 1 0 0 +EDGE2 3735 3576 0.0505062 1.00011 1.5675 1 0 1 1 0 0 +EDGE2 3735 3595 -0.0287545 0.0178942 0.0112727 1 0 1 1 0 0 +EDGE2 3735 3575 -0.00730569 -0.0025278 0.0310066 1 0 1 1 0 0 +EDGE2 3735 2914 -0.974819 -0.0829327 -0.00872328 1 0 1 1 0 0 +EDGE2 3735 3594 -0.961667 0.0214221 -0.0255761 1 0 1 1 0 0 +EDGE2 3735 3734 -0.997154 0.0117407 0.0188843 1 0 1 1 0 0 +EDGE2 3735 3574 -0.946519 -0.0449226 -0.0130653 1 0 1 1 0 0 +EDGE2 3735 3596 -0.0201314 -1.12771 -1.6064 1 0 1 1 0 0 +EDGE2 3736 3577 0.931183 0.0799167 -0.00348806 1 0 1 1 0 0 +EDGE2 3736 2915 -1.01562 0.0378128 -1.55304 1 0 1 1 0 0 +EDGE2 3736 2916 0.0770878 -0.0359526 0.0108544 1 0 1 1 0 0 +EDGE2 3736 2917 0.957127 -0.0334031 -0.0143956 1 0 1 1 0 0 +EDGE2 3736 3576 -0.0321476 0.00764552 0.0275348 1 0 1 1 0 0 +EDGE2 3736 3595 -0.952072 0.00499682 -1.57539 1 0 1 1 0 0 +EDGE2 3736 3735 -0.935493 -0.0423221 -1.57611 1 0 1 1 0 0 +EDGE2 3736 3575 -1.08138 -0.0376359 -1.57462 1 0 1 1 0 0 +EDGE2 3737 3577 0.112667 -0.0428812 -0.0129527 1 0 1 1 0 0 +EDGE2 3737 3578 0.999139 -0.105544 0.0107782 1 0 1 1 0 0 +EDGE2 3737 2918 0.989839 -0.0593072 0.00659894 1 0 1 1 0 0 +EDGE2 3737 2916 -0.975922 0.0582488 0.0173833 1 0 1 1 0 0 +EDGE2 3737 3736 -1.0094 -0.000840056 -0.00460207 1 0 1 1 0 0 +EDGE2 3737 2917 -0.0382414 -0.00735409 -0.0268075 1 0 1 1 0 0 +EDGE2 3737 3576 -0.98494 -0.0154396 -0.0265514 1 0 1 1 0 0 +EDGE2 3738 2919 0.979663 0.00848351 0.013084 1 0 1 1 0 0 +EDGE2 3738 3579 1.02318 -0.0615688 -0.0137187 1 0 1 1 0 0 +EDGE2 3738 3577 -0.912944 0.025401 -0.0281398 1 0 1 1 0 0 +EDGE2 3738 3578 -0.00112156 0.0364986 -0.031403 1 0 1 1 0 0 +EDGE2 3738 2918 0.0322014 -0.0103876 0.0223782 1 0 1 1 0 0 +EDGE2 3738 3737 -0.939166 -0.0867634 -0.00680329 1 0 1 1 0 0 +EDGE2 3738 2917 -0.951952 0.00305707 0.022638 1 0 1 1 0 0 +EDGE2 3739 2919 -0.0281353 0.0838397 0.0121051 1 0 1 1 0 0 +EDGE2 3739 2920 0.999585 -0.0444115 -0.0373275 1 0 1 1 0 0 +EDGE2 3739 3580 0.997991 -0.0302725 0.013235 1 0 1 1 0 0 +EDGE2 3739 3579 -0.00942519 -0.0271423 -0.0203092 1 0 1 1 0 0 +EDGE2 3739 3578 -1.01676 -0.0239637 0.000435107 1 0 1 1 0 0 +EDGE2 3739 3738 -0.910641 0.0432691 -0.0472225 1 0 1 1 0 0 +EDGE2 3739 2918 -1.0635 0.0151767 -0.00229511 1 0 1 1 0 0 +EDGE2 3740 2919 -0.918907 0.0512571 0.0355993 1 0 1 1 0 0 +EDGE2 3740 2921 -0.0390838 1.00792 1.5778 1 0 1 1 0 0 +EDGE2 3740 2920 -0.08098 -0.00399506 0.0012401 1 0 1 1 0 0 +EDGE2 3740 3580 -0.0120268 -0.036942 0.00469555 1 0 1 1 0 0 +EDGE2 3740 3581 -0.0341832 0.93188 1.56357 1 0 1 1 0 0 +EDGE2 3740 3739 -0.995399 0.0273288 0.0325809 1 0 1 1 0 0 +EDGE2 3740 3579 -0.983751 0.0329569 -0.0168096 1 0 1 1 0 0 +EDGE2 3741 3740 -0.992819 0.11454 -1.55763 1 0 1 1 0 0 +EDGE2 3741 3582 1.02604 -0.0973208 0.0092102 1 0 1 1 0 0 +EDGE2 3741 2921 -0.000560996 -0.0194428 0.0175245 1 0 1 1 0 0 +EDGE2 3741 2920 -1.05639 0.00611136 -1.56608 1 0 1 1 0 0 +EDGE2 3741 3580 -0.920328 0.0524864 -1.54814 1 0 1 1 0 0 +EDGE2 3741 3581 -0.0956096 0.0229389 0.0259269 1 0 1 1 0 0 +EDGE2 3741 2922 0.96652 -0.017136 0.0155363 1 0 1 1 0 0 +EDGE2 3742 3582 0.0252537 -0.0235947 -0.00720996 1 0 1 1 0 0 +EDGE2 3742 2921 -1.03819 0.00196612 -0.000280846 1 0 1 1 0 0 +EDGE2 3742 3741 -0.981287 -0.0452905 0.0139879 1 0 1 1 0 0 +EDGE2 3742 3581 -1.06462 0.00877668 -0.00638036 1 0 1 1 0 0 +EDGE2 3742 3583 0.926819 -0.033067 -0.035208 1 0 1 1 0 0 +EDGE2 3742 2922 -0.0436271 0.0242232 0.0140661 1 0 1 1 0 0 +EDGE2 3742 2923 1.0294 -0.0590966 -0.0124723 1 0 1 1 0 0 +EDGE2 3743 3582 -0.964188 -0.0915538 -0.0142519 1 0 1 1 0 0 +EDGE2 3743 3742 -0.9184 0.0218074 -0.0178168 1 0 1 1 0 0 +EDGE2 3743 3583 0.000408021 -0.018053 -0.0081058 1 0 1 1 0 0 +EDGE2 3743 2922 -0.956574 0.108241 0.0165708 1 0 1 1 0 0 +EDGE2 3743 2923 0.0232343 0.0157704 -0.00332266 1 0 1 1 0 0 +EDGE2 3743 2924 1.03948 -0.0253391 -0.00224614 1 0 1 1 0 0 +EDGE2 3743 3584 1.01936 0.0433368 0.0171632 1 0 1 1 0 0 +EDGE2 3744 3583 -1.03514 -0.0426926 -0.0150359 1 0 1 1 0 0 +EDGE2 3744 3743 -1.03325 -0.017826 0.0179594 1 0 1 1 0 0 +EDGE2 3744 2923 -0.988488 -0.0142724 -0.00969368 1 0 1 1 0 0 +EDGE2 3744 2924 0.141909 -0.0161015 0.0145873 1 0 1 1 0 0 +EDGE2 3744 3584 -0.0537863 -0.0426278 0.00317473 1 0 1 1 0 0 +EDGE2 3744 3585 0.9694 0.0405274 0.0295062 1 0 1 1 0 0 +EDGE2 3744 2905 1.03396 0.0402445 -3.14716 1 0 1 1 0 0 +EDGE2 3744 2925 0.949162 -0.0465299 0.00514559 1 0 1 1 0 0 +EDGE2 3744 2945 1.01873 -0.00871802 -3.13604 1 0 1 1 0 0 +EDGE2 3745 3744 -0.973277 -0.00268447 -0.0112935 1 0 1 1 0 0 +EDGE2 3745 2924 -0.932815 -0.0531458 -0.000481099 1 0 1 1 0 0 +EDGE2 3745 3584 -0.960266 -0.00702293 0.000630538 1 0 1 1 0 0 +EDGE2 3745 2904 0.970764 0.00446654 -3.13533 1 0 1 1 0 0 +EDGE2 3745 3585 -0.0360289 -0.0233728 0.0196836 1 0 1 1 0 0 +EDGE2 3745 2946 0.0293438 -0.968913 -1.54227 1 0 1 1 0 0 +EDGE2 3745 2926 0.0211195 -1.00158 -1.58348 1 0 1 1 0 0 +EDGE2 3745 2905 -0.0429141 -0.0199135 -3.122 1 0 1 1 0 0 +EDGE2 3745 2925 -0.0823285 0.0390093 0.0385143 1 0 1 1 0 0 +EDGE2 3745 2945 -0.0347021 0.0378042 -3.16088 1 0 1 1 0 0 +EDGE2 3745 2944 1.01545 -0.034134 -3.14969 1 0 1 1 0 0 +EDGE2 3745 2906 -0.0265586 1.03833 1.58369 1 0 1 1 0 0 +EDGE2 3745 3586 -0.0341818 0.984593 1.5738 1 0 1 1 0 0 +EDGE2 3746 3745 -1.0338 0.0905889 -1.5787 1 0 1 1 0 0 +EDGE2 3746 3585 -1.02765 0.0345887 -1.5907 1 0 1 1 0 0 +EDGE2 3746 2905 -0.887075 -0.0353847 1.54986 1 0 1 1 0 0 +EDGE2 3746 2925 -0.960694 0.0229988 -1.57811 1 0 1 1 0 0 +EDGE2 3746 2945 -1.05354 -0.0185315 1.56984 1 0 1 1 0 0 +EDGE2 3746 3587 1.05094 -0.00678212 -0.00080879 1 0 1 1 0 0 +EDGE2 3746 2906 0.000888015 0.0432636 0.0459609 1 0 1 1 0 0 +EDGE2 3746 3586 0.035743 0.0436971 -0.00584461 1 0 1 1 0 0 +EDGE2 3746 2907 0.95806 -0.0485861 0.00813844 1 0 1 1 0 0 +EDGE2 3747 3746 -1.01696 -0.0461155 0.00746644 1 0 1 1 0 0 +EDGE2 3747 3588 1.06858 0.0114061 -0.0300466 1 0 1 1 0 0 +EDGE2 3747 3587 0.0469138 -0.0713213 0.0120154 1 0 1 1 0 0 +EDGE2 3747 2906 -1.01286 0.0726054 0.00866881 1 0 1 1 0 0 +EDGE2 3747 3586 -0.925988 0.0373749 0.012779 1 0 1 1 0 0 +EDGE2 3747 2907 -0.02043 -0.0637863 0.0207305 1 0 1 1 0 0 +EDGE2 3747 2908 1.02224 0.109119 -0.001619 1 0 1 1 0 0 +EDGE2 3748 3747 -1.03417 -0.0244039 -0.000195166 1 0 1 1 0 0 +EDGE2 3748 3588 0.030072 -0.0595139 0.0226325 1 0 1 1 0 0 +EDGE2 3748 3587 -0.997431 -0.00883289 0.00815174 1 0 1 1 0 0 +EDGE2 3748 2907 -1.06242 -0.0361145 0.00690347 1 0 1 1 0 0 +EDGE2 3748 2909 1.01247 -0.0158096 -0.0195571 1 0 1 1 0 0 +EDGE2 3748 3589 0.961426 0.0292636 -0.0343914 1 0 1 1 0 0 +EDGE2 3748 2908 0.0237091 -0.0505906 0.00930798 1 0 1 1 0 0 +EDGE2 3749 3748 -1.02247 0.12507 0.000553697 1 0 1 1 0 0 +EDGE2 3749 3730 0.964743 -0.0346647 -3.1436 1 0 1 1 0 0 +EDGE2 3749 3590 0.931792 0.0210837 -0.04961 1 0 1 1 0 0 +EDGE2 3749 3588 -0.981497 0.0472649 -0.0132049 1 0 1 1 0 0 +EDGE2 3749 2909 -0.0157736 0.0533849 -0.00339163 1 0 1 1 0 0 +EDGE2 3749 3589 -0.0223234 0.00871199 0.0254393 1 0 1 1 0 0 +EDGE2 3749 2908 -1.01579 -0.092575 -0.0291183 1 0 1 1 0 0 +EDGE2 3749 3690 1.02544 0.0493494 -3.12251 1 0 1 1 0 0 +EDGE2 3749 2910 0.989045 -0.0271778 0.00171249 1 0 1 1 0 0 +EDGE2 3749 3570 1.06377 0.00382811 -3.12927 1 0 1 1 0 0 +EDGE2 3750 3571 0.00172193 0.991665 1.54823 1 0 1 1 0 0 +EDGE2 3750 3749 -1.1351 0.0544389 -0.0243922 1 0 1 1 0 0 +EDGE2 3750 3731 -0.0209163 1.02586 1.58424 1 0 1 1 0 0 +EDGE2 3750 3591 -0.035826 1.058 1.56685 1 0 1 1 0 0 +EDGE2 3750 2911 0.0358965 1.11394 1.55887 1 0 1 1 0 0 +EDGE2 3750 3730 0.0206312 0.000354607 -3.1481 1 0 1 1 0 0 +EDGE2 3750 3729 0.971682 -0.112595 -3.17566 1 0 1 1 0 0 +EDGE2 3750 3590 0.108729 0.0445219 -0.0285969 1 0 1 1 0 0 +EDGE2 3750 2909 -0.997689 0.0189441 -0.014714 1 0 1 1 0 0 +EDGE2 3750 3589 -1.07949 0.113611 -0.0389967 1 0 1 1 0 0 +EDGE2 3750 3690 0.0593125 -0.0427072 -3.12951 1 0 1 1 0 0 +EDGE2 3750 3691 0.0529121 -1.00508 -1.57009 1 0 1 1 0 0 +EDGE2 3750 2910 -0.0596506 0.00162399 -0.0387088 1 0 1 1 0 0 +EDGE2 3750 3570 0.0145198 0.0358227 -3.18229 1 0 1 1 0 0 +EDGE2 3750 3569 0.982341 0.0731404 -3.16812 1 0 1 1 0 0 +EDGE2 3750 3689 1.02549 0.0545429 -3.18206 1 0 1 1 0 0 +EDGE2 3751 3571 0.0278954 0.065923 0.0133871 1 0 1 1 0 0 +EDGE2 3751 2912 0.978419 -0.00592372 0.00399583 1 0 1 1 0 0 +EDGE2 3751 3592 1.03496 -0.0276795 -0.0324602 1 0 1 1 0 0 +EDGE2 3751 3732 0.949974 0.0960554 0.0191553 1 0 1 1 0 0 +EDGE2 3751 3572 1.05613 -0.0137377 -0.00293446 1 0 1 1 0 0 +EDGE2 3751 3731 -0.0226558 0.0379395 0.0180789 1 0 1 1 0 0 +EDGE2 3751 3591 -0.0960077 -0.00142499 0.0067386 1 0 1 1 0 0 +EDGE2 3751 3750 -1.09459 -0.011267 -1.53528 1 0 1 1 0 0 +EDGE2 3751 2911 -0.00644259 -0.0476162 0.00110991 1 0 1 1 0 0 +EDGE2 3751 3730 -1.03662 -0.0339253 1.59801 1 0 1 1 0 0 +EDGE2 3751 3590 -1.07587 0.0215427 -1.60965 1 0 1 1 0 0 +EDGE2 3751 3690 -0.978005 -0.0540135 1.56801 1 0 1 1 0 0 +EDGE2 3751 2910 -0.941453 -0.0511448 -1.56017 1 0 1 1 0 0 +EDGE2 3751 3570 -1.04538 -0.0248532 1.58044 1 0 1 1 0 0 +EDGE2 3752 3571 -0.913354 0.0719005 -0.0034463 1 0 1 1 0 0 +EDGE2 3752 2913 0.940791 0.0651631 0.0175887 1 0 1 1 0 0 +EDGE2 3752 3593 1.01398 -0.0305325 -0.0165211 1 0 1 1 0 0 +EDGE2 3752 3733 1.0235 0.00310482 -0.0199581 1 0 1 1 0 0 +EDGE2 3752 3573 1.0392 -0.00232294 -0.00268911 1 0 1 1 0 0 +EDGE2 3752 2912 0.0626955 -0.0665442 0.0173768 1 0 1 1 0 0 +EDGE2 3752 3592 0.0715369 -0.0350597 -0.0456756 1 0 1 1 0 0 +EDGE2 3752 3732 -0.0297398 0.0497544 -0.0206111 1 0 1 1 0 0 +EDGE2 3752 3572 -0.00741866 -0.104909 0.0111071 1 0 1 1 0 0 +EDGE2 3752 3731 -1.00021 -0.0563549 -0.000572985 1 0 1 1 0 0 +EDGE2 3752 3751 -1.09747 0.0152063 -0.0274175 1 0 1 1 0 0 +EDGE2 3752 3591 -1.00502 0.0126902 -0.0381972 1 0 1 1 0 0 +EDGE2 3752 2911 -1.0148 -0.0106313 0.00605544 1 0 1 1 0 0 +EDGE2 3753 2913 0.0436012 -0.0157979 -0.0227974 1 0 1 1 0 0 +EDGE2 3753 2914 1.0354 -0.00557612 0.00776796 1 0 1 1 0 0 +EDGE2 3753 3594 1.00968 0.0282924 0.0199117 1 0 1 1 0 0 +EDGE2 3753 3734 1.01685 0.0576885 0.0132984 1 0 1 1 0 0 +EDGE2 3753 3574 0.904903 0.0519387 -0.0248121 1 0 1 1 0 0 +EDGE2 3753 3593 -0.0452827 0.0832086 -0.0122699 1 0 1 1 0 0 +EDGE2 3753 3733 -0.0370151 -0.00503578 0.0150335 1 0 1 1 0 0 +EDGE2 3753 3573 0.145887 -0.0260057 -0.00276473 1 0 1 1 0 0 +EDGE2 3753 2912 -0.918529 0.0169051 0.000294799 1 0 1 1 0 0 +EDGE2 3753 3592 -1.05669 -0.0526969 0.00680892 1 0 1 1 0 0 +EDGE2 3753 3732 -1.06668 -0.00545981 0.00872782 1 0 1 1 0 0 +EDGE2 3753 3752 -0.998263 0.00470086 0.0173317 1 0 1 1 0 0 +EDGE2 3753 3572 -0.952761 -0.00471632 0.00684689 1 0 1 1 0 0 +EDGE2 3754 2915 0.945481 0.0140535 0.0198179 1 0 1 1 0 0 +EDGE2 3754 3595 1.03418 0.0722437 0.0241302 1 0 1 1 0 0 +EDGE2 3754 3735 0.970908 -0.046258 -0.00333342 1 0 1 1 0 0 +EDGE2 3754 3575 0.991669 0.0184763 0.00177908 1 0 1 1 0 0 +EDGE2 3754 2913 -0.989894 -0.0464214 -0.0151576 1 0 1 1 0 0 +EDGE2 3754 2914 0.00727371 0.00468813 -0.00239024 1 0 1 1 0 0 +EDGE2 3754 3594 0.0177619 -0.0463204 0.0225994 1 0 1 1 0 0 +EDGE2 3754 3734 0.0353646 0.0362293 0.0236032 1 0 1 1 0 0 +EDGE2 3754 3574 -0.108618 -0.0100208 0.0149611 1 0 1 1 0 0 +EDGE2 3754 3593 -1.02756 -0.0191799 -0.0146212 1 0 1 1 0 0 +EDGE2 3754 3733 -0.948377 0.0346284 0.0138162 1 0 1 1 0 0 +EDGE2 3754 3753 -1.00314 0.0116864 0.00284485 1 0 1 1 0 0 +EDGE2 3754 3573 -0.961777 -0.000595466 -0.00680144 1 0 1 1 0 0 +EDGE2 3755 2915 0.0235199 -0.0279902 0.0327528 1 0 1 1 0 0 +EDGE2 3755 2916 -0.0848196 1.0955 1.55155 1 0 1 1 0 0 +EDGE2 3755 3736 0.027701 1.04378 1.55403 1 0 1 1 0 0 +EDGE2 3755 3576 -0.00224264 1.00925 1.55277 1 0 1 1 0 0 +EDGE2 3755 3595 -0.0245825 -0.0332833 0.00973616 1 0 1 1 0 0 +EDGE2 3755 3735 -0.0442619 -0.0428482 0.0209736 1 0 1 1 0 0 +EDGE2 3755 3575 0.00635199 -0.114053 -0.0291438 1 0 1 1 0 0 +EDGE2 3755 2914 -0.884182 0.0434435 -0.00299789 1 0 1 1 0 0 +EDGE2 3755 3594 -0.996798 -0.0633012 -0.0363879 1 0 1 1 0 0 +EDGE2 3755 3734 -0.902612 -0.0226327 -0.0246774 1 0 1 1 0 0 +EDGE2 3755 3754 -0.990995 -0.0382822 0.0197332 1 0 1 1 0 0 +EDGE2 3755 3574 -1.01047 -0.0805374 0.016421 1 0 1 1 0 0 +EDGE2 3755 3596 0.0151491 -0.952631 -1.58415 1 0 1 1 0 0 +EDGE2 3756 2915 -1.02701 0.00919758 1.59039 1 0 1 1 0 0 +EDGE2 3756 3595 -1.01938 -0.0295574 1.59092 1 0 1 1 0 0 +EDGE2 3756 3735 -1.00923 -0.00420296 1.59361 1 0 1 1 0 0 +EDGE2 3756 3755 -1.08383 0.00482118 1.55574 1 0 1 1 0 0 +EDGE2 3756 3575 -0.974694 0.0160291 1.57891 1 0 1 1 0 0 +EDGE2 3756 3597 0.973261 -0.036993 -0.0280561 1 0 1 1 0 0 +EDGE2 3756 3596 0.0571682 -0.0180969 0.00451732 1 0 1 1 0 0 +EDGE2 3757 3597 -0.0721304 -0.0501128 0.0245731 1 0 1 1 0 0 +EDGE2 3757 3596 -1.04136 0.0284158 -0.0209191 1 0 1 1 0 0 +EDGE2 3757 3756 -1.01827 -0.105762 0.0219001 1 0 1 1 0 0 +EDGE2 3757 3598 1.00902 0.0423872 -0.0202532 1 0 1 1 0 0 +EDGE2 3758 3597 -1.03249 -0.089125 0.0509194 1 0 1 1 0 0 +EDGE2 3758 3757 -0.979144 0.0658628 -0.0030814 1 0 1 1 0 0 +EDGE2 3758 3598 -0.0206224 -0.0700485 0.0153881 1 0 1 1 0 0 +EDGE2 3758 3599 0.901469 -0.0602366 0.0253371 1 0 1 1 0 0 +EDGE2 3759 3598 -1.00714 -0.0987977 0.00634195 1 0 1 1 0 0 +EDGE2 3759 3758 -0.937441 0.0585398 -0.0235379 1 0 1 1 0 0 +EDGE2 3759 3599 -0.109256 0.0105488 -0.0227712 1 0 1 1 0 0 +EDGE2 3759 3680 1.02778 0.0357699 -3.13492 1 0 1 1 0 0 +EDGE2 3759 3600 1.03925 -0.07672 -0.001095 1 0 1 1 0 0 +EDGE2 3759 3640 1.06279 -0.0512807 -3.16531 1 0 1 1 0 0 +EDGE2 3759 3660 0.973077 0.00420061 -3.15013 1 0 1 1 0 0 +EDGE2 3760 3599 -0.958621 -0.0178889 0.0187393 1 0 1 1 0 0 +EDGE2 3760 3759 -0.937061 0.110464 -0.0200302 1 0 1 1 0 0 +EDGE2 3760 3680 -0.0320739 -0.107309 -3.13632 1 0 1 1 0 0 +EDGE2 3760 3601 0.0197147 0.997233 1.59623 1 0 1 1 0 0 +EDGE2 3760 3600 0.00155495 -0.115807 0.0200092 1 0 1 1 0 0 +EDGE2 3760 3640 0.0253039 -0.0503484 -3.14473 1 0 1 1 0 0 +EDGE2 3760 3660 0.0258802 0.00344029 -3.14705 1 0 1 1 0 0 +EDGE2 3760 3641 -0.0192708 -0.940772 -1.58099 1 0 1 1 0 0 +EDGE2 3760 3661 -0.0349277 -1.05209 -1.59482 1 0 1 1 0 0 +EDGE2 3760 3681 0.0102391 -0.97658 -1.55671 1 0 1 1 0 0 +EDGE2 3760 3659 0.92476 -0.0114811 -3.15383 1 0 1 1 0 0 +EDGE2 3760 3679 0.936961 -0.0218046 -3.09408 1 0 1 1 0 0 +EDGE2 3760 3639 1.00702 0.030365 -3.14825 1 0 1 1 0 0 +EDGE2 3761 3680 -0.925362 0.0841578 -1.58999 1 0 1 1 0 0 +EDGE2 3761 3760 -0.994085 -0.0250984 1.56391 1 0 1 1 0 0 +EDGE2 3761 3600 -0.942702 -0.0410773 1.55653 1 0 1 1 0 0 +EDGE2 3761 3640 -1.02766 0.00416528 -1.58604 1 0 1 1 0 0 +EDGE2 3761 3660 -1.01959 -0.0345544 -1.57581 1 0 1 1 0 0 +EDGE2 3761 3641 0.00615414 0.0525522 -0.00545684 1 0 1 1 0 0 +EDGE2 3761 3661 -0.0210421 0.0719781 0.0427241 1 0 1 1 0 0 +EDGE2 3761 3681 -0.0512129 -0.00221904 -0.0142109 1 0 1 1 0 0 +EDGE2 3761 3642 0.966143 -0.0264341 -0.0125823 1 0 1 1 0 0 +EDGE2 3761 3662 0.861635 0.105654 0.0127239 1 0 1 1 0 0 +EDGE2 3761 3682 1.01514 -0.0186898 0.0194582 1 0 1 1 0 0 +EDGE2 3762 3761 -0.949237 0.0012011 -0.0145313 1 0 1 1 0 0 +EDGE2 3762 3641 -0.980964 0.00973498 -0.0244061 1 0 1 1 0 0 +EDGE2 3762 3661 -1.11569 -0.0213881 -0.012293 1 0 1 1 0 0 +EDGE2 3762 3681 -0.966408 0.00975596 -0.0216085 1 0 1 1 0 0 +EDGE2 3762 3642 -0.00476098 0.0698881 0.00784664 1 0 1 1 0 0 +EDGE2 3762 3662 -0.00675038 -0.146402 0.00526809 1 0 1 1 0 0 +EDGE2 3762 3682 -0.0435755 0.07806 0.0214844 1 0 1 1 0 0 +EDGE2 3762 3663 1.03683 0.0353454 0.00420723 1 0 1 1 0 0 +EDGE2 3762 3683 0.957426 0.049158 0.00277476 1 0 1 1 0 0 +EDGE2 3762 3643 1.02902 -0.0228384 -0.0183141 1 0 1 1 0 0 +EDGE2 3763 3762 -1.04529 -0.00865046 -0.0124415 1 0 1 1 0 0 +EDGE2 3763 3642 -1.01812 -0.0376906 -0.0178109 1 0 1 1 0 0 +EDGE2 3763 3662 -1.00175 -0.000113093 -0.0365721 1 0 1 1 0 0 +EDGE2 3763 3682 -1.08591 -0.074904 0.051802 1 0 1 1 0 0 +EDGE2 3763 3663 0.0151445 -0.0209209 -0.0260407 1 0 1 1 0 0 +EDGE2 3763 3683 0.00442927 -0.0142761 -0.0199134 1 0 1 1 0 0 +EDGE2 3763 3643 0.0349856 -0.0252495 -0.0239874 1 0 1 1 0 0 +EDGE2 3763 3664 1.04185 -0.0478352 0.0299553 1 0 1 1 0 0 +EDGE2 3763 3684 1.02244 0.0793242 -0.00720929 1 0 1 1 0 0 +EDGE2 3763 3644 1.02767 -0.0880731 -0.00798645 1 0 1 1 0 0 +EDGE2 3764 3763 -1.03407 -0.0534644 -0.00083734 1 0 1 1 0 0 +EDGE2 3764 3663 -1.00302 -0.0260354 -0.0209566 1 0 1 1 0 0 +EDGE2 3764 3683 -1.02994 -0.0118207 0.00638527 1 0 1 1 0 0 +EDGE2 3764 3643 -1.01493 0.000264789 -0.000705695 1 0 1 1 0 0 +EDGE2 3764 3664 -0.0248198 0.11529 0.0376577 1 0 1 1 0 0 +EDGE2 3764 3684 -0.0621475 0.0706172 0.0103631 1 0 1 1 0 0 +EDGE2 3764 3644 -0.112347 -0.00317053 -0.00267107 1 0 1 1 0 0 +EDGE2 3764 3725 1.03989 0.0152019 -3.12899 1 0 1 1 0 0 +EDGE2 3764 3645 0.946785 -0.104369 0.00213996 1 0 1 1 0 0 +EDGE2 3764 3685 1.07041 -0.00954956 -0.0181884 1 0 1 1 0 0 +EDGE2 3764 3665 0.967294 0.099786 -0.0222583 1 0 1 1 0 0 +EDGE2 3764 3565 1.00423 0.00503856 -3.13062 1 0 1 1 0 0 +EDGE2 3765 3664 -0.89422 0.0176712 0.0193612 1 0 1 1 0 0 +EDGE2 3765 3684 -0.890008 -0.0079357 -0.0198793 1 0 1 1 0 0 +EDGE2 3765 3764 -1.03576 -0.0485255 -0.0163619 1 0 1 1 0 0 +EDGE2 3765 3644 -0.901835 0.00339397 0.0034912 1 0 1 1 0 0 +EDGE2 3765 3725 0.0601967 -0.0573353 -3.1127 1 0 1 1 0 0 +EDGE2 3765 3686 -0.00138047 -0.942764 -1.58275 1 0 1 1 0 0 +EDGE2 3765 3726 -0.0313511 -0.993784 -1.5655 1 0 1 1 0 0 +EDGE2 3765 3566 0.0241713 -0.990546 -1.58467 1 0 1 1 0 0 +EDGE2 3765 3645 0.0592931 0.106551 0.0198864 1 0 1 1 0 0 +EDGE2 3765 3685 0.14328 -0.0536294 -0.0105087 1 0 1 1 0 0 +EDGE2 3765 3665 -0.0437279 0.0673963 -0.0197238 1 0 1 1 0 0 +EDGE2 3765 3564 0.971504 0.0406416 -3.15289 1 0 1 1 0 0 +EDGE2 3765 3724 1.00983 -0.0102701 -3.11974 1 0 1 1 0 0 +EDGE2 3765 3565 -0.0287793 0.0940618 -3.1059 1 0 1 1 0 0 +EDGE2 3765 3646 0.0945282 0.984888 1.58352 1 0 1 1 0 0 +EDGE2 3765 3666 -0.0854255 0.986066 1.59211 1 0 1 1 0 0 +EDGE2 3766 3727 1.06435 -0.0162223 0.0185899 1 0 1 1 0 0 +EDGE2 3766 3765 -0.971713 -0.00839236 1.57868 1 0 1 1 0 0 +EDGE2 3766 3725 -1.02316 0.0223046 -1.60329 1 0 1 1 0 0 +EDGE2 3766 3687 1.02372 -0.0166622 0.000134127 1 0 1 1 0 0 +EDGE2 3766 3686 -0.0629044 0.0274936 0.00384249 1 0 1 1 0 0 +EDGE2 3766 3726 0.0124671 0.0778972 0.0213059 1 0 1 1 0 0 +EDGE2 3766 3567 1.03487 0.0229879 -0.0164055 1 0 1 1 0 0 +EDGE2 3766 3566 -0.0591619 -0.0138341 0.00141505 1 0 1 1 0 0 +EDGE2 3766 3645 -0.946307 0.111135 1.60298 1 0 1 1 0 0 +EDGE2 3766 3685 -0.995754 -0.0164209 1.59209 1 0 1 1 0 0 +EDGE2 3766 3665 -1.01842 0.071795 1.57937 1 0 1 1 0 0 +EDGE2 3766 3565 -0.987807 -0.0123502 -1.58213 1 0 1 1 0 0 +EDGE2 3767 3727 -0.021617 -0.0340825 -0.0159746 1 0 1 1 0 0 +EDGE2 3767 3728 0.984591 -0.0143425 0.0126583 1 0 1 1 0 0 +EDGE2 3767 3766 -0.90371 0.0228718 0.00283868 1 0 1 1 0 0 +EDGE2 3767 3687 0.0650487 -0.00331519 0.0131619 1 0 1 1 0 0 +EDGE2 3767 3688 0.946748 0.00542634 0.0187437 1 0 1 1 0 0 +EDGE2 3767 3568 0.999562 -0.025258 0.00277128 1 0 1 1 0 0 +EDGE2 3767 3686 -0.930151 -0.0434954 -0.0036162 1 0 1 1 0 0 +EDGE2 3767 3726 -0.939437 -0.00959225 0.0106414 1 0 1 1 0 0 +EDGE2 3767 3567 -0.0758353 0.0708427 -0.011245 1 0 1 1 0 0 +EDGE2 3767 3566 -0.980786 0.024229 -0.00564439 1 0 1 1 0 0 +EDGE2 3768 3727 -0.918863 0.017309 0.00261128 1 0 1 1 0 0 +EDGE2 3768 3729 0.971552 0.0485954 0.00684409 1 0 1 1 0 0 +EDGE2 3768 3767 -1.04768 -0.045933 0.00821377 1 0 1 1 0 0 +EDGE2 3768 3728 -0.07061 0.030687 -0.0155291 1 0 1 1 0 0 +EDGE2 3768 3687 -0.915727 -0.123938 0.0164492 1 0 1 1 0 0 +EDGE2 3768 3688 -0.048822 -0.0723823 0.0174601 1 0 1 1 0 0 +EDGE2 3768 3569 0.999029 -0.00600537 0.00171686 1 0 1 1 0 0 +EDGE2 3768 3689 1.03314 -0.0648432 -0.0289225 1 0 1 1 0 0 +EDGE2 3768 3568 -0.0384246 -0.0669099 0.0126513 1 0 1 1 0 0 +EDGE2 3768 3567 -0.923374 0.106385 -0.0122121 1 0 1 1 0 0 +EDGE2 3769 3750 1.05491 -0.0407584 -3.12568 1 0 1 1 0 0 +EDGE2 3769 3730 0.958781 0.0320383 0.0109028 1 0 1 1 0 0 +EDGE2 3769 3729 0.0211816 -0.0479576 -0.0181367 1 0 1 1 0 0 +EDGE2 3769 3728 -0.980517 0.0278622 0.00054851 1 0 1 1 0 0 +EDGE2 3769 3768 -1.00542 -0.0832244 0.0162573 1 0 1 1 0 0 +EDGE2 3769 3590 1.07399 -0.0448751 -3.16422 1 0 1 1 0 0 +EDGE2 3769 3690 0.964153 0.156092 0.0190371 1 0 1 1 0 0 +EDGE2 3769 2910 1.07502 -0.09883 -3.16935 1 0 1 1 0 0 +EDGE2 3769 3570 0.955254 0.077837 -0.025531 1 0 1 1 0 0 +EDGE2 3769 3688 -1.03623 0.00543199 -0.0296179 1 0 1 1 0 0 +EDGE2 3769 3569 0.0212218 0.0486869 0.007888 1 0 1 1 0 0 +EDGE2 3769 3689 0.0366072 -0.0478319 -0.0106985 1 0 1 1 0 0 +EDGE2 3769 3568 -0.973228 0.0803346 -0.00553461 1 0 1 1 0 0 +EDGE2 3770 3571 -0.0690552 -1.01308 -1.58483 1 0 1 1 0 0 +EDGE2 3770 3749 1.08735 -0.0142412 -3.14234 1 0 1 1 0 0 +EDGE2 3770 3731 0.00471836 -1.04485 -1.54138 1 0 1 1 0 0 +EDGE2 3770 3751 -0.0232472 -0.983975 -1.53581 1 0 1 1 0 0 +EDGE2 3770 3591 -0.0903294 -1.07743 -1.53713 1 0 1 1 0 0 +EDGE2 3770 3769 -0.992523 -0.0595647 -0.0478007 1 0 1 1 0 0 +EDGE2 3770 3750 0.0846731 0.0153836 -3.13789 1 0 1 1 0 0 +EDGE2 3770 2911 -0.004733 -0.997784 -1.58403 1 0 1 1 0 0 +EDGE2 3770 3730 0.000663995 -0.079033 -0.0249558 1 0 1 1 0 0 +EDGE2 3770 3729 -0.928253 0.0309544 0.0300355 1 0 1 1 0 0 +EDGE2 3770 3590 0.0744767 0.0597479 -3.10425 1 0 1 1 0 0 +EDGE2 3770 2909 1.06338 -0.0412019 -3.17189 1 0 1 1 0 0 +EDGE2 3770 3589 1.01347 -0.0204949 -3.12929 1 0 1 1 0 0 +EDGE2 3770 3690 -0.0713652 -0.0367059 -0.00722686 1 0 1 1 0 0 +EDGE2 3770 3691 0.0081921 1.05699 1.57947 1 0 1 1 0 0 +EDGE2 3770 2910 0.0353444 -0.0441194 -3.11403 1 0 1 1 0 0 +EDGE2 3770 3570 0.0280868 -0.0288178 0.0210926 1 0 1 1 0 0 +EDGE2 3770 3569 -1.03599 -0.0704848 0.0154795 1 0 1 1 0 0 +EDGE2 3770 3689 -1.04658 0.0189887 0.0139673 1 0 1 1 0 0 +EDGE2 3771 3750 -0.989139 0.0179032 1.5927 1 0 1 1 0 0 +EDGE2 3771 3770 -1.05819 -0.15597 -1.61134 1 0 1 1 0 0 +EDGE2 3771 3730 -0.995332 -0.0652822 -1.55992 1 0 1 1 0 0 +EDGE2 3771 3590 -0.952503 -0.0416655 1.57703 1 0 1 1 0 0 +EDGE2 3771 3690 -0.976368 0.069528 -1.5471 1 0 1 1 0 0 +EDGE2 3771 3691 -0.0553561 0.0472389 -0.00330761 1 0 1 1 0 0 +EDGE2 3771 2910 -0.901074 -0.0192586 1.53898 1 0 1 1 0 0 +EDGE2 3771 3570 -1.0026 0.0401484 -1.58893 1 0 1 1 0 0 +EDGE2 3771 3692 1.06089 -0.0989115 0.00142821 1 0 1 1 0 0 +EDGE2 3772 3693 0.967424 0.082634 0.0216829 1 0 1 1 0 0 +EDGE2 3772 3691 -1.02934 -0.00423586 -0.0184896 1 0 1 1 0 0 +EDGE2 3772 3771 -1.00892 0.00157177 0.0149782 1 0 1 1 0 0 +EDGE2 3772 3692 0.030834 -0.05123 0.00506174 1 0 1 1 0 0 +EDGE2 3773 3693 0.0240802 -0.0587764 0.0332708 1 0 1 1 0 0 +EDGE2 3773 3692 -0.964533 -0.0695306 -0.00336098 1 0 1 1 0 0 +EDGE2 3773 3772 -0.99937 -0.0140582 -0.0220902 1 0 1 1 0 0 +EDGE2 3773 3694 0.955236 -0.0471745 0.0105679 1 0 1 1 0 0 +EDGE2 3774 3693 -0.94139 0.0356269 -0.006712 1 0 1 1 0 0 +EDGE2 3774 3773 -1.0092 -0.00979345 0.0228446 1 0 1 1 0 0 +EDGE2 3774 3694 -0.0111767 0.113214 -0.0346669 1 0 1 1 0 0 +EDGE2 3774 3695 1.03189 0.110126 0.0113949 1 0 1 1 0 0 +EDGE2 3774 3555 1.07258 -0.0277498 -3.11741 1 0 1 1 0 0 +EDGE2 3775 3694 -1.02306 -0.0173213 -0.00709624 1 0 1 1 0 0 +EDGE2 3775 3774 -1.00365 -0.0601123 -0.0148121 1 0 1 1 0 0 +EDGE2 3775 3696 -0.0442797 0.971279 1.56335 1 0 1 1 0 0 +EDGE2 3775 3554 0.88447 -0.0485276 -3.14738 1 0 1 1 0 0 +EDGE2 3775 3695 0.0328184 0.00136239 -0.0198623 1 0 1 1 0 0 +EDGE2 3775 3555 0.0409542 -0.0393271 -3.1192 1 0 1 1 0 0 +EDGE2 3775 3556 0.0191777 0.951451 1.56708 1 0 1 1 0 0 +EDGE2 3776 3696 -0.019801 -0.091544 0.0114599 1 0 1 1 0 0 +EDGE2 3776 3695 -1.02013 0.0387934 -1.56277 1 0 1 1 0 0 +EDGE2 3776 3775 -1.09473 -0.00406912 -1.58508 1 0 1 1 0 0 +EDGE2 3776 3555 -0.983792 -0.0133093 1.55289 1 0 1 1 0 0 +EDGE2 3776 3697 0.934077 0.00323432 0.00876951 1 0 1 1 0 0 +EDGE2 3776 3556 0.0367855 -0.0640843 -0.0332359 1 0 1 1 0 0 +EDGE2 3776 3557 0.941569 0.0421564 -0.0108218 1 0 1 1 0 0 +EDGE2 3777 3696 -1.09342 -0.00580404 -0.029614 1 0 1 1 0 0 +EDGE2 3777 3776 -0.982057 0.0134915 -0.0177653 1 0 1 1 0 0 +EDGE2 3777 3697 -0.0351935 -0.0262026 -0.00103893 1 0 1 1 0 0 +EDGE2 3777 3556 -0.957612 0.0255751 -0.0526278 1 0 1 1 0 0 +EDGE2 3777 3557 -0.0497528 -0.109939 0.00731194 1 0 1 1 0 0 +EDGE2 3777 3558 1.06189 0.0113221 -0.00760138 1 0 1 1 0 0 +EDGE2 3777 3698 1.04484 0.0225105 -0.00096938 1 0 1 1 0 0 +EDGE2 3778 3559 0.984227 -0.00114382 0.0140397 1 0 1 1 0 0 +EDGE2 3778 3697 -1.06792 -0.0207877 0.0239791 1 0 1 1 0 0 +EDGE2 3778 3777 -1.04049 -0.0891736 -0.00271807 1 0 1 1 0 0 +EDGE2 3778 3557 -0.974945 0.0163709 0.00290926 1 0 1 1 0 0 +EDGE2 3778 3558 -0.0156139 0.0536388 -0.0093651 1 0 1 1 0 0 +EDGE2 3778 3698 0.0332639 0.0222894 -0.00994669 1 0 1 1 0 0 +EDGE2 3778 3699 0.95834 -0.0647619 0.00296274 1 0 1 1 0 0 +EDGE2 3779 3559 0.026222 0.0971349 0.0135861 1 0 1 1 0 0 +EDGE2 3779 3778 -1.02367 -0.0882989 0.0143825 1 0 1 1 0 0 +EDGE2 3779 3558 -0.985157 0.0397191 -0.00707307 1 0 1 1 0 0 +EDGE2 3779 3698 -1.00229 0.027896 0.0394642 1 0 1 1 0 0 +EDGE2 3779 3699 0.0364569 -0.104801 0.0111934 1 0 1 1 0 0 +EDGE2 3779 3700 0.971777 0.0703255 0.011108 1 0 1 1 0 0 +EDGE2 3779 3720 1.07922 0.0223342 -3.16891 1 0 1 1 0 0 +EDGE2 3779 3560 0.992471 0.0185694 0.0148223 1 0 1 1 0 0 +EDGE2 3780 3721 -0.0229385 1.05294 1.61503 1 0 1 1 0 0 +EDGE2 3780 3561 0.0325856 0.86604 1.5964 1 0 1 1 0 0 +EDGE2 3780 3559 -1.00538 0.0154805 -0.0225863 1 0 1 1 0 0 +EDGE2 3780 3779 -0.977001 -0.000869608 -0.0219602 1 0 1 1 0 0 +EDGE2 3780 3699 -1.03299 -0.00901985 0.0236375 1 0 1 1 0 0 +EDGE2 3780 3700 -0.0290178 0.147279 0.0256237 1 0 1 1 0 0 +EDGE2 3780 3720 0.0313427 0.11461 -3.14095 1 0 1 1 0 0 +EDGE2 3780 3560 0.0844786 -0.0423269 -0.0215693 1 0 1 1 0 0 +EDGE2 3780 3701 0.00850086 -0.946085 -1.56604 1 0 1 1 0 0 +EDGE2 3780 3719 1.04821 0.0376881 -3.14456 1 0 1 1 0 0 +EDGE2 3781 3700 -1.04613 -0.0317306 1.57392 1 0 1 1 0 0 +EDGE2 3781 3720 -0.981552 -0.0128674 -1.55601 1 0 1 1 0 0 +EDGE2 3781 3780 -1.11653 -0.0963688 1.55193 1 0 1 1 0 0 +EDGE2 3781 3560 -1.04377 -0.0020588 1.56385 1 0 1 1 0 0 +EDGE2 3781 3701 -0.0212219 -0.0593468 -0.021194 1 0 1 1 0 0 +EDGE2 3781 3702 0.895354 0.0188902 -0.000900855 1 0 1 1 0 0 +EDGE2 3782 3781 -1.01084 -0.0187886 -0.0277146 1 0 1 1 0 0 +EDGE2 3782 3701 -0.998832 0.0442546 0.00560269 1 0 1 1 0 0 +EDGE2 3782 3702 -0.0383125 0.0425907 -0.00568291 1 0 1 1 0 0 +EDGE2 3782 3703 1.02966 -0.0362367 -0.0221154 1 0 1 1 0 0 +EDGE2 3783 3782 -0.968502 -0.0355355 0.0261475 1 0 1 1 0 0 +EDGE2 3783 3702 -0.913182 -0.0205928 0.0134201 1 0 1 1 0 0 +EDGE2 3783 3704 0.948211 0.010406 -0.014244 1 0 1 1 0 0 +EDGE2 3783 3703 0.0356125 0.0294155 -0.0133939 1 0 1 1 0 0 +EDGE2 3784 3783 -0.984191 0.0188105 -0.00803269 1 0 1 1 0 0 +EDGE2 3784 3704 -0.0467853 0.0174029 -0.0109238 1 0 1 1 0 0 +EDGE2 3784 3703 -0.97365 -0.100067 0.00227008 1 0 1 1 0 0 +EDGE2 3784 3705 0.930679 -0.0126063 -0.0164252 1 0 1 1 0 0 +EDGE2 3785 3704 -1.001 -0.0770071 -0.0139903 1 0 1 1 0 0 +EDGE2 3785 3784 -0.909442 -0.0351821 0.0207332 1 0 1 1 0 0 +EDGE2 3785 3706 0.0202041 0.955978 1.55862 1 0 1 1 0 0 +EDGE2 3785 3705 -0.0237768 0.110355 1.20291e-05 1 0 1 1 0 0 +EDGE2 3786 3785 -1.03096 0.0372955 -1.57989 1 0 1 1 0 0 +EDGE2 3786 3707 1.05895 0.0218501 -0.0407736 1 0 1 1 0 0 +EDGE2 3786 3706 -0.0359941 -0.0475601 -0.0173822 1 0 1 1 0 0 +EDGE2 3786 3705 -1.06163 0.0225162 -1.58178 1 0 1 1 0 0 +EDGE2 3787 3707 0.0351125 -0.0146956 -0.0204099 1 0 1 1 0 0 +EDGE2 3787 3706 -0.985852 -0.0178388 0.0157112 1 0 1 1 0 0 +EDGE2 3787 3786 -0.96492 -0.0210486 -0.0116369 1 0 1 1 0 0 +EDGE2 3787 3708 0.995599 0.0371665 0.0124053 1 0 1 1 0 0 +EDGE2 3788 3707 -1.07667 0.0090119 -0.000990548 1 0 1 1 0 0 +EDGE2 3788 3787 -0.856837 0.00349041 -0.0178217 1 0 1 1 0 0 +EDGE2 3788 3708 -0.00122246 0.0135471 -0.0148734 1 0 1 1 0 0 +EDGE2 3788 3709 1.00111 0.0148913 -0.0328343 1 0 1 1 0 0 +EDGE2 3789 3708 -0.915355 0.0548342 0.0201165 1 0 1 1 0 0 +EDGE2 3789 3788 -1.05957 -0.0322748 0.0122764 1 0 1 1 0 0 +EDGE2 3789 3709 -0.0534523 -0.0257515 0.0229376 1 0 1 1 0 0 +EDGE2 3789 3710 0.988013 -0.0517125 -0.0240187 1 0 1 1 0 0 +EDGE2 3790 3789 -1.00231 -0.0429175 0.00471871 1 0 1 1 0 0 +EDGE2 3790 3709 -1.01295 0.0416137 -0.0343973 1 0 1 1 0 0 +EDGE2 3790 3711 0.0345408 1.01113 1.56767 1 0 1 1 0 0 +EDGE2 3790 3710 -0.0371166 0.0300717 0.00142867 1 0 1 1 0 0 +EDGE2 3791 3712 1.01494 -0.0186483 -0.00606329 1 0 1 1 0 0 +EDGE2 3791 3790 -1.02578 0.0492658 -1.60314 1 0 1 1 0 0 +EDGE2 3791 3711 -0.031347 -0.00643175 0.018784 1 0 1 1 0 0 +EDGE2 3791 3710 -1.05336 0.0631914 -1.59014 1 0 1 1 0 0 +EDGE2 3792 3791 -0.994512 -0.00848164 0.041659 1 0 1 1 0 0 +EDGE2 3792 3713 0.897663 -0.0830261 -0.0241322 1 0 1 1 0 0 +EDGE2 3792 3712 0.0230113 0.062092 0.0385335 1 0 1 1 0 0 +EDGE2 3792 3711 -1.00219 0.050105 -0.0243273 1 0 1 1 0 0 +EDGE2 3793 3714 1.06374 0.016193 0.0199737 1 0 1 1 0 0 +EDGE2 3793 3792 -1.00733 -0.057318 0.0196731 1 0 1 1 0 0 +EDGE2 3793 3713 0.0349665 -0.072445 0.000138739 1 0 1 1 0 0 +EDGE2 3793 3712 -0.955074 -0.0658958 0.0425701 1 0 1 1 0 0 +EDGE2 3794 3715 1.01728 -0.046188 -0.0132026 1 0 1 1 0 0 +EDGE2 3794 3714 0.0401667 -0.085182 0.0306548 1 0 1 1 0 0 +EDGE2 3794 3713 -0.958365 -0.024435 -0.0262552 1 0 1 1 0 0 +EDGE2 3794 3793 -1.03101 0.0367604 0.0193584 1 0 1 1 0 0 +EDGE2 3795 3715 -0.0371036 -0.0573904 0.0088014 1 0 1 1 0 0 +EDGE2 3795 3716 -0.0357641 1.04429 1.58319 1 0 1 1 0 0 +EDGE2 3795 3714 -1.02246 -0.0245874 -0.00664078 1 0 1 1 0 0 +EDGE2 3795 3794 -1.00751 -0.0739364 0.00997247 1 0 1 1 0 0 +EDGE2 3796 3715 -0.964642 0.0317854 1.5571 1 0 1 1 0 0 +EDGE2 3796 3795 -0.860773 -0.0278518 1.54141 1 0 1 1 0 0 +EDGE2 3797 3796 -0.907844 -0.0557837 0.00682583 1 0 1 1 0 0 +EDGE2 3798 3797 -1.02886 -0.0607738 -0.00500795 1 0 1 1 0 0 +EDGE2 3799 3798 -1.03668 -0.0475531 0.00898223 1 0 1 1 0 0 +EDGE2 3800 3799 -1.00935 -0.00794822 0.0168948 1 0 1 1 0 0 +EDGE2 3801 3800 -1.08918 0.0402687 -1.58687 1 0 1 1 0 0 +EDGE2 3802 3801 -0.966602 0.0468493 -0.0303277 1 0 1 1 0 0 +EDGE2 3803 3802 -0.919686 -0.0489009 -0.0131281 1 0 1 1 0 0 +EDGE2 3804 3803 -0.912424 -0.0157017 0.0100127 1 0 1 1 0 0 +EDGE2 3805 3804 -1.0397 0.032162 -0.00405549 1 0 1 1 0 0 +EDGE2 3806 3805 -0.98994 -0.0220676 -1.56893 1 0 1 1 0 0 +EDGE2 3807 3806 -1.05862 0.0394475 -0.0568204 1 0 1 1 0 0 +EDGE2 3808 3807 -1.10311 -0.120308 -0.014605 1 0 1 1 0 0 +EDGE2 3809 3808 -0.933241 0.0792012 -0.00487086 1 0 1 1 0 0 +EDGE2 3809 3650 1.06255 -0.0386816 -3.14135 1 0 1 1 0 0 +EDGE2 3809 3670 1.12503 0.0393531 -3.1418 1 0 1 1 0 0 +EDGE2 3810 3651 0.00423372 -1.01215 -1.5468 1 0 1 1 0 0 +EDGE2 3810 3671 0.0330038 -0.977999 -1.57876 1 0 1 1 0 0 +EDGE2 3810 3809 -0.960333 -0.0132821 0.00589492 1 0 1 1 0 0 +EDGE2 3810 3650 0.0312843 -0.00701813 -3.1199 1 0 1 1 0 0 +EDGE2 3810 3649 0.921992 -0.064166 -3.13923 1 0 1 1 0 0 +EDGE2 3810 3669 0.949162 -0.0902344 -3.14281 1 0 1 1 0 0 +EDGE2 3810 3670 -0.0370959 0.0320685 -3.14802 1 0 1 1 0 0 +EDGE2 3811 3651 0.0130481 0.0415535 0.0242758 1 0 1 1 0 0 +EDGE2 3811 3652 0.952324 0.0401809 0.00822186 1 0 1 1 0 0 +EDGE2 3811 3672 1.10409 -0.0117558 -0.00716251 1 0 1 1 0 0 +EDGE2 3811 3671 0.0482546 -0.0589888 -0.013552 1 0 1 1 0 0 +EDGE2 3811 3810 -0.946077 0.0753397 1.56973 1 0 1 1 0 0 +EDGE2 3811 3650 -0.923567 0.0603087 -1.56465 1 0 1 1 0 0 +EDGE2 3811 3670 -0.997737 -0.0120413 -1.54069 1 0 1 1 0 0 +EDGE2 3812 3673 0.924646 0.0918335 0.0249804 1 0 1 1 0 0 +EDGE2 3812 3653 0.912087 0.0532318 -0.0163776 1 0 1 1 0 0 +EDGE2 3812 3651 -1.00372 0.0377044 -0.0194098 1 0 1 1 0 0 +EDGE2 3812 3811 -1.01878 -0.020464 -0.00941995 1 0 1 1 0 0 +EDGE2 3812 3652 -0.00219205 0.0728388 0.0417381 1 0 1 1 0 0 +EDGE2 3812 3672 0.0247515 -0.0594147 0.0162077 1 0 1 1 0 0 +EDGE2 3812 3671 -1.06536 -0.02482 -0.0229147 1 0 1 1 0 0 +EDGE2 3813 3812 -1.01237 -0.0486209 -0.0160555 1 0 1 1 0 0 +EDGE2 3813 3654 0.945653 -0.0502892 -0.0123721 1 0 1 1 0 0 +EDGE2 3813 3674 1.01048 0.071071 0.000615933 1 0 1 1 0 0 +EDGE2 3813 3673 -0.0398747 0.113252 0.0174715 1 0 1 1 0 0 +EDGE2 3813 3653 0.0137399 -0.0175398 -0.00185341 1 0 1 1 0 0 +EDGE2 3813 3652 -0.968124 -0.0361181 0.00576293 1 0 1 1 0 0 +EDGE2 3813 3672 -1.01415 -0.0199816 0.00638939 1 0 1 1 0 0 +EDGE2 3814 3635 1.04729 -0.00780008 -3.15174 1 0 1 1 0 0 +EDGE2 3814 3675 0.969513 0.0896135 0.0200119 1 0 1 1 0 0 +EDGE2 3814 3655 0.986558 0.0714983 -0.00964603 1 0 1 1 0 0 +EDGE2 3814 3654 -0.0261544 0.0143807 0.00322145 1 0 1 1 0 0 +EDGE2 3814 3674 -0.0230191 0.074665 0.0101032 1 0 1 1 0 0 +EDGE2 3814 3673 -0.967785 0.0604286 0.0332658 1 0 1 1 0 0 +EDGE2 3814 3813 -1.0426 -0.0305082 -0.0334485 1 0 1 1 0 0 +EDGE2 3814 3653 -0.920376 -0.0129053 -0.017962 1 0 1 1 0 0 +EDGE2 3815 3635 0.0171035 0.104649 -3.1242 1 0 1 1 0 0 +EDGE2 3815 3656 -0.0224357 1.05831 1.55145 1 0 1 1 0 0 +EDGE2 3815 3676 -0.0334858 0.948398 1.56822 1 0 1 1 0 0 +EDGE2 3815 3636 0.0358985 0.991729 1.53997 1 0 1 1 0 0 +EDGE2 3815 3675 -0.0541837 0.134503 -0.0272464 1 0 1 1 0 0 +EDGE2 3815 3634 0.963745 0.0355434 -3.15582 1 0 1 1 0 0 +EDGE2 3815 3655 0.0705327 -0.0615184 0.00660421 1 0 1 1 0 0 +EDGE2 3815 3654 -1.03796 0.0582911 0.0293077 1 0 1 1 0 0 +EDGE2 3815 3814 -1.01463 -0.0270792 0.00585219 1 0 1 1 0 0 +EDGE2 3815 3674 -1.05615 -0.014299 -0.00323795 1 0 1 1 0 0 +EDGE2 3816 3637 1.0415 0.0161868 0.00461272 1 0 1 1 0 0 +EDGE2 3816 3677 0.883947 0.0190873 0.00129441 1 0 1 1 0 0 +EDGE2 3816 3657 0.941493 0.00360163 -0.0123585 1 0 1 1 0 0 +EDGE2 3816 3635 -1.00385 0.030063 1.64359 1 0 1 1 0 0 +EDGE2 3816 3656 0.00508557 0.0361772 -0.0100647 1 0 1 1 0 0 +EDGE2 3816 3676 0.000716137 0.0992061 0.0145265 1 0 1 1 0 0 +EDGE2 3816 3636 -0.0320291 0.0596908 0.017865 1 0 1 1 0 0 +EDGE2 3816 3675 -0.961679 -0.0343481 -1.59031 1 0 1 1 0 0 +EDGE2 3816 3815 -1.12128 -0.0625168 -1.59625 1 0 1 1 0 0 +EDGE2 3816 3655 -1.04307 -0.0567772 -1.58725 1 0 1 1 0 0 +EDGE2 3817 3637 0.0405093 0.0734171 -0.00903425 1 0 1 1 0 0 +EDGE2 3817 3677 0.0723888 0.0825132 0.0125224 1 0 1 1 0 0 +EDGE2 3817 3638 0.935889 0.0556838 -0.0179495 1 0 1 1 0 0 +EDGE2 3817 3658 1.06506 0.0644967 -0.0152636 1 0 1 1 0 0 +EDGE2 3817 3678 1.01293 -0.0257892 0.00755453 1 0 1 1 0 0 +EDGE2 3817 3657 -0.0387487 -0.0176174 0.00836667 1 0 1 1 0 0 +EDGE2 3817 3656 -0.999486 0.0646814 -0.0231213 1 0 1 1 0 0 +EDGE2 3817 3676 -0.902906 -0.0247803 -0.0333053 1 0 1 1 0 0 +EDGE2 3817 3816 -1.06425 -0.0227644 -0.0126195 1 0 1 1 0 0 +EDGE2 3817 3636 -0.934183 -0.00723131 -0.00252358 1 0 1 1 0 0 +EDGE2 3818 3637 -0.996872 0.0162245 0.0102718 1 0 1 1 0 0 +EDGE2 3818 3677 -1.03951 0.00409581 0.0128965 1 0 1 1 0 0 +EDGE2 3818 3659 0.954121 0.0297799 -0.0215371 1 0 1 1 0 0 +EDGE2 3818 3679 1.05611 0.043642 -0.00250194 1 0 1 1 0 0 +EDGE2 3818 3639 1.04218 -0.0532215 -0.00322836 1 0 1 1 0 0 +EDGE2 3818 3638 0.00857368 0.0236944 -0.0117287 1 0 1 1 0 0 +EDGE2 3818 3658 0.0883998 0.133603 -0.0131584 1 0 1 1 0 0 +EDGE2 3818 3678 0.0125344 -0.00337029 0.0281068 1 0 1 1 0 0 +EDGE2 3818 3817 -0.936 0.0167184 0.0407614 1 0 1 1 0 0 +EDGE2 3818 3657 -0.967849 -0.0156483 0.0380648 1 0 1 1 0 0 +EDGE2 3819 3680 1.06454 -0.000765772 0.00195823 1 0 1 1 0 0 +EDGE2 3819 3760 1.013 0.0439722 -3.16083 1 0 1 1 0 0 +EDGE2 3819 3600 1.03951 -0.0579348 -3.13802 1 0 1 1 0 0 +EDGE2 3819 3640 1.0417 -0.0717125 0.0133378 1 0 1 1 0 0 +EDGE2 3819 3660 1.05784 -0.0341971 -0.00772021 1 0 1 1 0 0 +EDGE2 3819 3818 -1.06021 -0.0103735 0.0417873 1 0 1 1 0 0 +EDGE2 3819 3659 0.00519366 -0.0339628 -0.000693056 1 0 1 1 0 0 +EDGE2 3819 3679 -0.0536901 0.0875024 0.00522703 1 0 1 1 0 0 +EDGE2 3819 3639 -0.0210374 -0.0581977 0.00703563 1 0 1 1 0 0 +EDGE2 3819 3638 -1.01622 0.0372879 0.0352215 1 0 1 1 0 0 +EDGE2 3819 3658 -0.995194 -0.00175625 -0.0251026 1 0 1 1 0 0 +EDGE2 3819 3678 -1.00055 0.034788 0.00396788 1 0 1 1 0 0 +EDGE2 3820 3599 1.03267 -0.0262576 -3.144 1 0 1 1 0 0 +EDGE2 3820 3759 0.956734 -0.109169 -3.12855 1 0 1 1 0 0 +EDGE2 3820 3680 0.00380617 -0.103069 -0.0079759 1 0 1 1 0 0 +EDGE2 3820 3601 -0.0592402 -0.971227 -1.5731 1 0 1 1 0 0 +EDGE2 3820 3760 -0.00475745 -0.00552064 -3.14351 1 0 1 1 0 0 +EDGE2 3820 3761 -0.0896306 0.98743 1.56341 1 0 1 1 0 0 +EDGE2 3820 3600 -0.0465396 -0.0259923 -3.14975 1 0 1 1 0 0 +EDGE2 3820 3640 0.0470678 0.0451487 0.0292986 1 0 1 1 0 0 +EDGE2 3820 3660 0.00623312 -0.0134091 0.00757993 1 0 1 1 0 0 +EDGE2 3820 3641 0.03971 1.00347 1.58246 1 0 1 1 0 0 +EDGE2 3820 3661 -0.0369179 0.989651 1.54379 1 0 1 1 0 0 +EDGE2 3820 3681 -0.0383372 1.06222 1.56555 1 0 1 1 0 0 +EDGE2 3820 3659 -1.03731 -0.0131571 -0.0246346 1 0 1 1 0 0 +EDGE2 3820 3679 -1.00728 -0.0578869 0.0124157 1 0 1 1 0 0 +EDGE2 3820 3819 -0.899313 0.00173023 0.00760237 1 0 1 1 0 0 +EDGE2 3820 3639 -1.01647 -0.00247629 -0.0097074 1 0 1 1 0 0 +EDGE2 3821 3680 -0.907069 -0.0328007 -1.56007 1 0 1 1 0 0 +EDGE2 3821 3820 -1.0221 -0.0598513 -1.57989 1 0 1 1 0 0 +EDGE2 3821 3760 -0.963786 0.0503438 1.53676 1 0 1 1 0 0 +EDGE2 3821 3762 0.949755 -0.0713249 -0.00413339 1 0 1 1 0 0 +EDGE2 3821 3761 -0.0824764 -0.0414985 0.00313548 1 0 1 1 0 0 +EDGE2 3821 3600 -1.07666 0.0311692 1.52792 1 0 1 1 0 0 +EDGE2 3821 3640 -0.993624 -0.0488494 -1.59435 1 0 1 1 0 0 +EDGE2 3821 3660 -0.943398 -0.018743 -1.56986 1 0 1 1 0 0 +EDGE2 3821 3641 -0.006541 -0.0175824 -0.000241071 1 0 1 1 0 0 +EDGE2 3821 3661 -0.0469014 -0.0365402 -0.00409501 1 0 1 1 0 0 +EDGE2 3821 3681 -0.0556802 0.0538361 0.00283574 1 0 1 1 0 0 +EDGE2 3821 3642 0.998437 -0.114556 0.00898106 1 0 1 1 0 0 +EDGE2 3821 3662 1.04401 -0.00606828 -0.00171618 1 0 1 1 0 0 +EDGE2 3821 3682 1.01119 0.0370789 -0.0149826 1 0 1 1 0 0 +EDGE2 3822 3762 0.152422 -0.0164567 0.00763195 1 0 1 1 0 0 +EDGE2 3822 3761 -1.00129 -0.027142 0.0151348 1 0 1 1 0 0 +EDGE2 3822 3821 -1.09526 0.00850783 0.0160457 1 0 1 1 0 0 +EDGE2 3822 3641 -1.01414 0.0102621 0.0249901 1 0 1 1 0 0 +EDGE2 3822 3661 -1.05395 0.00212022 0.0246199 1 0 1 1 0 0 +EDGE2 3822 3681 -0.949632 -0.0563331 0.00378244 1 0 1 1 0 0 +EDGE2 3822 3763 1.07428 0.104336 -0.0306876 1 0 1 1 0 0 +EDGE2 3822 3642 0.111827 -0.115076 -0.00627196 1 0 1 1 0 0 +EDGE2 3822 3662 -0.00409457 -0.0557692 0.000772726 1 0 1 1 0 0 +EDGE2 3822 3682 0.00313722 -0.0667696 -0.0272421 1 0 1 1 0 0 +EDGE2 3822 3663 0.957992 -0.102236 0.0401462 1 0 1 1 0 0 +EDGE2 3822 3683 1.01151 0.0255878 -0.00729227 1 0 1 1 0 0 +EDGE2 3822 3643 1.02015 0.0441228 -0.0168837 1 0 1 1 0 0 +EDGE2 3823 3762 -1.08967 -0.0122304 0.0191464 1 0 1 1 0 0 +EDGE2 3823 3822 -0.949923 0.00113387 -0.0115783 1 0 1 1 0 0 +EDGE2 3823 3763 -0.00923174 -0.0015367 0.0394524 1 0 1 1 0 0 +EDGE2 3823 3642 -1.07224 -0.00444941 0.00798563 1 0 1 1 0 0 +EDGE2 3823 3662 -0.986962 0.0529148 -0.0107059 1 0 1 1 0 0 +EDGE2 3823 3682 -1.00451 -0.034097 -0.0098581 1 0 1 1 0 0 +EDGE2 3823 3663 0.0235581 0.0160294 -0.00435354 1 0 1 1 0 0 +EDGE2 3823 3683 -0.0976676 -0.0151965 -0.0204082 1 0 1 1 0 0 +EDGE2 3823 3643 0.00171323 -0.0173143 0.00408489 1 0 1 1 0 0 +EDGE2 3823 3664 0.91483 0.0237081 0.0188036 1 0 1 1 0 0 +EDGE2 3823 3684 1.04856 -0.0759413 -0.0194909 1 0 1 1 0 0 +EDGE2 3823 3764 1.07974 0.0658302 0.0188788 1 0 1 1 0 0 +EDGE2 3823 3644 0.950457 -0.026778 -0.0386397 1 0 1 1 0 0 +EDGE2 3824 3763 -0.943768 -0.0535139 0.00575941 1 0 1 1 0 0 +EDGE2 3824 3823 -1.03728 -0.017189 0.0118505 1 0 1 1 0 0 +EDGE2 3824 3663 -0.956467 0.00102764 -0.0172085 1 0 1 1 0 0 +EDGE2 3824 3683 -1.01637 -0.0449572 0.0369903 1 0 1 1 0 0 +EDGE2 3824 3643 -0.984233 0.000412239 0.0120485 1 0 1 1 0 0 +EDGE2 3824 3664 -0.0187294 -0.107116 -0.0150697 1 0 1 1 0 0 +EDGE2 3824 3684 -0.0318827 -0.022335 0.0499881 1 0 1 1 0 0 +EDGE2 3824 3764 0.033885 0.0223441 -0.0242873 1 0 1 1 0 0 +EDGE2 3824 3644 0.0170196 -0.0829362 0.0134549 1 0 1 1 0 0 +EDGE2 3824 3765 0.955813 0.0515667 0.00746456 1 0 1 1 0 0 +EDGE2 3824 3725 1.0169 -0.10863 -3.14737 1 0 1 1 0 0 +EDGE2 3824 3645 1.06056 0.03024 -0.0252974 1 0 1 1 0 0 +EDGE2 3824 3685 0.993669 -0.0145705 0.0223745 1 0 1 1 0 0 +EDGE2 3824 3665 1.02957 0.0600619 -0.0313884 1 0 1 1 0 0 +EDGE2 3824 3565 0.932102 0.0729822 -3.12771 1 0 1 1 0 0 +EDGE2 3825 3766 0.0630135 -1.00196 -1.61435 1 0 1 1 0 0 +EDGE2 3825 3824 -1.04315 0.0095672 -0.0116589 1 0 1 1 0 0 +EDGE2 3825 3664 -1.02486 0.0795824 0.00256859 1 0 1 1 0 0 +EDGE2 3825 3684 -1.01197 -0.0624611 0.0146007 1 0 1 1 0 0 +EDGE2 3825 3764 -1.003 -0.00295747 -0.00946345 1 0 1 1 0 0 +EDGE2 3825 3644 -0.991011 0.0951517 0.0180394 1 0 1 1 0 0 +EDGE2 3825 3765 0.0380029 -0.0104082 -0.00621425 1 0 1 1 0 0 +EDGE2 3825 3725 0.044368 -0.0898548 -3.15624 1 0 1 1 0 0 +EDGE2 3825 3686 -0.0805606 -1.02634 -1.57727 1 0 1 1 0 0 +EDGE2 3825 3726 0.0427497 -0.879376 -1.57406 1 0 1 1 0 0 +EDGE2 3825 3566 -0.0295787 -0.998026 -1.56878 1 0 1 1 0 0 +EDGE2 3825 3645 0.019082 -0.0162632 0.0202305 1 0 1 1 0 0 +EDGE2 3825 3685 -0.0175225 -0.000461519 -0.00764376 1 0 1 1 0 0 +EDGE2 3825 3665 0.0687743 0.0773462 0.00516243 1 0 1 1 0 0 +EDGE2 3825 3564 1.07377 0.0471468 -3.12597 1 0 1 1 0 0 +EDGE2 3825 3724 0.966642 0.0541963 -3.16039 1 0 1 1 0 0 +EDGE2 3825 3565 0.0876057 0.0834093 -3.13483 1 0 1 1 0 0 +EDGE2 3825 3646 0.00626977 1.01056 1.5536 1 0 1 1 0 0 +EDGE2 3825 3666 -0.0302349 1.00804 1.53627 1 0 1 1 0 0 +EDGE2 3826 3825 -1.04624 0.00890226 -1.56864 1 0 1 1 0 0 +EDGE2 3826 3765 -1.00951 0.0820091 -1.54075 1 0 1 1 0 0 +EDGE2 3826 3725 -1.01729 -0.111224 1.60005 1 0 1 1 0 0 +EDGE2 3826 3645 -1.04226 0.0113648 -1.56808 1 0 1 1 0 0 +EDGE2 3826 3685 -0.973326 -0.0517695 -1.54743 1 0 1 1 0 0 +EDGE2 3826 3665 -0.990381 0.075032 -1.55017 1 0 1 1 0 0 +EDGE2 3826 3565 -0.965854 -0.0058271 1.57709 1 0 1 1 0 0 +EDGE2 3826 3667 1.02234 -0.0764516 -0.00508092 1 0 1 1 0 0 +EDGE2 3826 3646 -0.00721338 0.0227896 0.0177346 1 0 1 1 0 0 +EDGE2 3826 3666 0.0856735 0.0886636 0.04442 1 0 1 1 0 0 +EDGE2 3826 3647 0.989305 0.0176898 0.043946 1 0 1 1 0 0 +EDGE2 3827 3826 -1.01265 -0.0770673 -0.013966 1 0 1 1 0 0 +EDGE2 3827 3668 1.00211 0.00473921 -0.00354805 1 0 1 1 0 0 +EDGE2 3827 3667 -0.0632489 -0.00677772 -0.0270335 1 0 1 1 0 0 +EDGE2 3827 3646 -0.995831 -0.00411064 0.0261151 1 0 1 1 0 0 +EDGE2 3827 3666 -0.989323 -0.0321912 0.00309761 1 0 1 1 0 0 +EDGE2 3827 3647 0.00799513 0.00302941 0.0258022 1 0 1 1 0 0 +EDGE2 3827 3648 1.04543 0.0627096 0.0277507 1 0 1 1 0 0 +EDGE2 3828 3827 -1.07461 0.0356456 0.0270378 1 0 1 1 0 0 +EDGE2 3828 3668 -0.0599172 -0.101753 0.0268305 1 0 1 1 0 0 +EDGE2 3828 3667 -1.03354 0.0650697 0.00956417 1 0 1 1 0 0 +EDGE2 3828 3647 -1.02441 -0.0743709 -0.017041 1 0 1 1 0 0 +EDGE2 3828 3649 1.00809 -0.104302 0.0156007 1 0 1 1 0 0 +EDGE2 3828 3669 0.904801 0.0779103 -0.00353497 1 0 1 1 0 0 +EDGE2 3828 3648 0.0738542 -0.0172428 -0.0104911 1 0 1 1 0 0 +EDGE2 3829 3828 -0.995065 0.0685169 0.0451688 1 0 1 1 0 0 +EDGE2 3829 3810 1.00566 0.0403482 -3.16306 1 0 1 1 0 0 +EDGE2 3829 3650 0.955108 0.0416949 0.0104687 1 0 1 1 0 0 +EDGE2 3829 3668 -1.05709 0.0219335 -0.00365004 1 0 1 1 0 0 +EDGE2 3829 3649 0.0136429 0.0251036 -0.0235234 1 0 1 1 0 0 +EDGE2 3829 3669 0.0584691 0.0205478 -0.0125335 1 0 1 1 0 0 +EDGE2 3829 3648 -0.992939 -0.0406249 0.0348686 1 0 1 1 0 0 +EDGE2 3829 3670 1.06665 0.0127739 0.0100169 1 0 1 1 0 0 +EDGE2 3830 3829 -0.991923 -0.0239016 -0.00349425 1 0 1 1 0 0 +EDGE2 3830 3651 -0.0124695 0.987326 1.56132 1 0 1 1 0 0 +EDGE2 3830 3811 -0.0230686 0.92294 1.58015 1 0 1 1 0 0 +EDGE2 3830 3671 -0.00666463 1.0432 1.5447 1 0 1 1 0 0 +EDGE2 3830 3809 0.880837 0.0880692 -3.13498 1 0 1 1 0 0 +EDGE2 3830 3810 -0.03654 -0.0580293 -3.15782 1 0 1 1 0 0 +EDGE2 3830 3650 -0.00641767 -0.0611362 0.0363003 1 0 1 1 0 0 +EDGE2 3830 3649 -1.08878 -0.0034116 -0.00435427 1 0 1 1 0 0 +EDGE2 3830 3669 -1.06112 0.0763917 -0.00812498 1 0 1 1 0 0 +EDGE2 3830 3670 0.0511683 -0.0112121 0.0149331 1 0 1 1 0 0 +EDGE2 3831 3810 -1.01813 0.0414606 -1.59467 1 0 1 1 0 0 +EDGE2 3831 3830 -0.981669 0.00141895 1.60708 1 0 1 1 0 0 +EDGE2 3831 3650 -0.921052 -0.00655344 1.55792 1 0 1 1 0 0 +EDGE2 3831 3670 -1.00166 -0.098493 1.53506 1 0 1 1 0 0 +EDGE2 3832 3831 -1.03138 -0.073564 -0.0168081 1 0 1 1 0 0 +EDGE2 3833 3832 -0.913977 -0.00298384 -0.0434824 1 0 1 1 0 0 +EDGE2 3834 3833 -1.1111 -0.0102374 0.01841 1 0 1 1 0 0 +EDGE2 3834 3715 1.08672 0.0192158 -3.14343 1 0 1 1 0 0 +EDGE2 3834 3795 1.05492 -0.0118464 -3.11947 1 0 1 1 0 0 +EDGE2 3835 3834 -0.971369 -0.0193979 -0.0187579 1 0 1 1 0 0 +EDGE2 3835 3715 -0.0348893 0.0853406 -3.14568 1 0 1 1 0 0 +EDGE2 3835 3716 0.044142 -1.01516 -1.55941 1 0 1 1 0 0 +EDGE2 3835 3795 -0.0135322 -0.00949839 -3.12162 1 0 1 1 0 0 +EDGE2 3835 3714 1.00208 -0.0294296 -3.13251 1 0 1 1 0 0 +EDGE2 3835 3796 -0.0616872 1 1.61349 1 0 1 1 0 0 +EDGE2 3835 3794 1.01475 0.0799424 -3.15092 1 0 1 1 0 0 +EDGE2 3836 3715 -1.02695 -0.0663632 1.56889 1 0 1 1 0 0 +EDGE2 3836 3835 -0.989185 -0.0486616 -1.55236 1 0 1 1 0 0 +EDGE2 3836 3795 -1.02442 -0.00998825 1.57931 1 0 1 1 0 0 +EDGE2 3836 3797 0.888395 0.0347023 -0.014245 1 0 1 1 0 0 +EDGE2 3836 3796 -0.0182783 0.0419495 -0.0186759 1 0 1 1 0 0 +EDGE2 3837 3797 0.0234898 -0.0516265 -0.021345 1 0 1 1 0 0 +EDGE2 3837 3796 -1.02433 0.00831916 -0.00857146 1 0 1 1 0 0 +EDGE2 3837 3836 -0.968263 -0.0479155 -0.00171215 1 0 1 1 0 0 +EDGE2 3837 3798 1.06462 -0.0360949 -0.00879375 1 0 1 1 0 0 +EDGE2 3838 3797 -0.952009 -0.0276571 0.0063009 1 0 1 1 0 0 +EDGE2 3838 3837 -1.01764 -0.00979122 0.0220019 1 0 1 1 0 0 +EDGE2 3838 3798 0.0543177 -0.121319 -0.0287212 1 0 1 1 0 0 +EDGE2 3838 3799 0.941367 0.0175075 0.0111806 1 0 1 1 0 0 +EDGE2 3839 3798 -0.999312 0.0515095 -0.0620725 1 0 1 1 0 0 +EDGE2 3839 3838 -0.974605 0.0983016 0.0164964 1 0 1 1 0 0 +EDGE2 3839 3799 0.0568886 0.00243731 -0.00938338 1 0 1 1 0 0 +EDGE2 3839 3800 1.04928 0.0195713 0.0211853 1 0 1 1 0 0 +EDGE2 3840 3839 -0.947318 -0.00524871 -0.0114846 1 0 1 1 0 0 +EDGE2 3840 3799 -0.899919 -0.00462819 -0.00997775 1 0 1 1 0 0 +EDGE2 3840 3801 -0.00653715 1.05 1.59767 1 0 1 1 0 0 +EDGE2 3840 3800 -0.061382 -0.0712226 -0.0265108 1 0 1 1 0 0 +EDGE2 3841 3840 -1.03841 -0.00140293 1.58151 1 0 1 1 0 0 +EDGE2 3841 3800 -0.968339 -0.106778 1.58679 1 0 1 1 0 0 +EDGE2 3842 3841 -1.06006 0.0169605 0.00512147 1 0 1 1 0 0 +EDGE2 3843 3842 -1.12134 0.0115876 -0.000832005 1 0 1 1 0 0 +EDGE2 3844 3843 -1.08856 -0.0124456 -0.00325574 1 0 1 1 0 0 +EDGE2 3845 3844 -1.02142 -0.00703636 -0.00642728 1 0 1 1 0 0 +EDGE2 3846 3845 -0.975053 0.0703357 -1.52224 1 0 1 1 0 0 +EDGE2 3847 3846 -1.02414 0.0696158 1.36384e-05 1 0 1 1 0 0 +EDGE2 3848 3847 -0.918077 0.0617116 -0.035867 1 0 1 1 0 0 +EDGE2 3849 3848 -1.04949 0.0187286 -0.0119755 1 0 1 1 0 0 +EDGE2 3850 3849 -0.933014 0.0306653 0.0321269 1 0 1 1 0 0 +EDGE2 3851 3850 -0.9654 0.00729662 -1.57537 1 0 1 1 0 0 +EDGE2 3852 3851 -0.978136 -0.061786 -0.0204939 1 0 1 1 0 0 +EDGE2 3853 3852 -0.992682 0.0398342 -0.0099068 1 0 1 1 0 0 +EDGE2 3854 3853 -0.986965 -0.034121 -0.00521177 1 0 1 1 0 0 +EDGE2 3855 3854 -0.899975 0.0377928 -0.0325063 1 0 1 1 0 0 +EDGE2 3856 3855 -1.14294 -0.0206868 1.58499 1 0 1 1 0 0 +EDGE2 3857 3856 -0.974188 -0.0618705 0.0140409 1 0 1 1 0 0 +EDGE2 3858 3857 -0.903404 0.0202546 -0.018858 1 0 1 1 0 0 +EDGE2 3859 3858 -0.975986 0.00167916 0.0593458 1 0 1 1 0 0 +EDGE2 3860 3859 -1.04559 0.00857098 0.00522694 1 0 1 1 0 0 +EDGE2 3861 3860 -0.979519 0.0191036 -1.54925 1 0 1 1 0 0 +EDGE2 3862 3861 -1.01905 0.0485397 -0.0520295 1 0 1 1 0 0 +EDGE2 3863 3862 -1.03826 0.0446101 -0.00755084 1 0 1 1 0 0 +EDGE2 3864 3863 -1.04692 0.0628943 -0.00272776 1 0 1 1 0 0 +EDGE2 3865 3864 -1.03393 -0.0856564 0.0255177 1 0 1 1 0 0 +EDGE2 3866 3865 -1.08146 -0.0123293 -1.57398 1 0 1 1 0 0 +EDGE2 3867 3866 -1.03827 0.0586255 0.000841667 1 0 1 1 0 0 +EDGE2 3868 3867 -0.890267 0.0533117 0.0110908 1 0 1 1 0 0 +EDGE2 3869 3868 -0.95829 0.0513142 -0.00795464 1 0 1 1 0 0 +EDGE2 3870 3869 -0.947095 -0.0471947 -0.00556152 1 0 1 1 0 0 +EDGE2 3871 3870 -1.03943 -0.0609091 -1.56822 1 0 1 1 0 0 +EDGE2 3872 3871 -1.03301 -0.113176 -0.0156633 1 0 1 1 0 0 +EDGE2 3873 3872 -1.06041 -0.0216062 0.0113574 1 0 1 1 0 0 +EDGE2 3874 3873 -0.948552 -0.00699075 0.0306944 1 0 1 1 0 0 +EDGE2 3874 3855 1.03929 -0.0322957 -3.12602 1 0 1 1 0 0 +EDGE2 3875 3856 0.0754799 1.02012 1.57847 1 0 1 1 0 0 +EDGE2 3875 3874 -1.04262 -0.0645366 0.0207897 1 0 1 1 0 0 +EDGE2 3875 3855 -0.06173 -0.0424824 -3.11373 1 0 1 1 0 0 +EDGE2 3875 3854 0.976285 -0.0212953 -3.13601 1 0 1 1 0 0 +EDGE2 3876 3856 -0.0293806 0.0488736 0.0201923 1 0 1 1 0 0 +EDGE2 3876 3855 -0.947135 0.0377059 1.57075 1 0 1 1 0 0 +EDGE2 3876 3875 -0.977523 0.0547325 -1.60469 1 0 1 1 0 0 +EDGE2 3876 3857 1.00297 -0.0566943 0.0108767 1 0 1 1 0 0 +EDGE2 3877 3856 -1.04736 0.0713256 0.00913228 1 0 1 1 0 0 +EDGE2 3877 3876 -1.01478 -0.022302 -0.025328 1 0 1 1 0 0 +EDGE2 3877 3857 0.0713903 -0.0334777 0.0224763 1 0 1 1 0 0 +EDGE2 3877 3858 1.06397 -0.0332964 -0.0165703 1 0 1 1 0 0 +EDGE2 3878 3857 -1.00529 0.0957927 -0.0297663 1 0 1 1 0 0 +EDGE2 3878 3877 -0.954834 0.0467232 0.0310579 1 0 1 1 0 0 +EDGE2 3878 3858 0.0547566 -0.00728362 0.0142985 1 0 1 1 0 0 +EDGE2 3878 3859 1.0505 -0.00541343 0.0184742 1 0 1 1 0 0 +EDGE2 3879 3878 -1.02269 -0.0268452 -0.0242671 1 0 1 1 0 0 +EDGE2 3879 3858 -0.975085 0.0293081 0.0247263 1 0 1 1 0 0 +EDGE2 3879 3859 -0.0196987 0.0126199 -0.0336489 1 0 1 1 0 0 +EDGE2 3879 3860 1.05873 -0.0162525 0.0014577 1 0 1 1 0 0 +EDGE2 3880 3859 -1.04681 0.176373 -0.0170458 1 0 1 1 0 0 +EDGE2 3880 3879 -0.990041 -0.0132503 0.00978967 1 0 1 1 0 0 +EDGE2 3880 3861 0.0826279 0.997067 1.59075 1 0 1 1 0 0 +EDGE2 3880 3860 0.0958178 0.0189624 -0.00508168 1 0 1 1 0 0 +EDGE2 3881 3860 -0.97018 0.0734679 1.54921 1 0 1 1 0 0 +EDGE2 3881 3880 -0.877681 0.121697 1.58381 1 0 1 1 0 0 +EDGE2 3882 3881 -0.962525 0.0310385 0.0303807 1 0 1 1 0 0 +EDGE2 3883 3882 -1.00077 0.0570614 0.0158379 1 0 1 1 0 0 +EDGE2 3884 3883 -1.02402 -0.0193108 -0.00951051 1 0 1 1 0 0 +EDGE2 3885 3884 -0.981206 0.00369123 0.00942413 1 0 1 1 0 0 +EDGE2 3886 3885 -0.971692 -0.089353 -1.58624 1 0 1 1 0 0 +EDGE2 3887 3886 -0.953989 -0.0567739 -0.0185566 1 0 1 1 0 0 +EDGE2 3888 3887 -0.956365 -0.00283804 -0.0155032 1 0 1 1 0 0 +EDGE2 3889 3888 -1.01331 -0.0590587 0.0151483 1 0 1 1 0 0 +EDGE2 3890 3889 -0.901323 -0.0138203 0.00908675 1 0 1 1 0 0 +EDGE2 3891 3890 -0.9215 -0.0970035 1.57302 1 0 1 1 0 0 +EDGE2 3892 3891 -1.05776 -0.0174521 0.0126408 1 0 1 1 0 0 +EDGE2 3893 3892 -0.896816 -0.0887149 0.0304549 1 0 1 1 0 0 +EDGE2 3894 3893 -0.983632 0.0336694 -0.0195337 1 0 1 1 0 0 +EDGE2 3895 3894 -0.988553 0.0342303 0.00323233 1 0 1 1 0 0 +EDGE2 3896 3895 -0.977762 0.0551075 -1.57551 1 0 1 1 0 0 +EDGE2 3897 3896 -1.09359 0.0191838 0.00618875 1 0 1 1 0 0 +EDGE2 3898 3897 -1.00293 0.0382001 -0.00136089 1 0 1 1 0 0 +EDGE2 3899 3898 -0.95394 -0.0292606 0.00201461 1 0 1 1 0 0 +EDGE2 3900 3899 -0.92964 -0.0152936 -0.0136501 1 0 1 1 0 0 +EDGE2 3901 3900 -0.97603 0.0423468 -1.58075 1 0 1 1 0 0 +EDGE2 3902 3901 -0.984396 -0.027001 0.0222496 1 0 1 1 0 0 +EDGE2 3903 3902 -0.918079 0.00378039 0.00533073 1 0 1 1 0 0 +EDGE2 3904 3903 -1.01699 0.0285773 -0.0106009 1 0 1 1 0 0 +EDGE2 3905 3904 -1.07317 -0.0381167 -0.0038992 1 0 1 1 0 0 +EDGE2 3906 3905 -1.02569 -0.0113905 1.54884 1 0 1 1 0 0 +EDGE2 3907 3906 -1.04663 0.0557236 -0.0145925 1 0 1 1 0 0 +EDGE2 3908 3907 -1.00467 -0.0591073 -0.0194362 1 0 1 1 0 0 +EDGE2 3909 3908 -0.970558 0.0576963 -0.023866 1 0 1 1 0 0 +EDGE2 3910 3909 -1.12494 0.0513159 -0.0237168 1 0 1 1 0 0 +EDGE2 3911 3910 -1.03112 0.0181604 -1.57917 1 0 1 1 0 0 +EDGE2 3912 3911 -0.992119 -0.100343 0.00979973 1 0 1 1 0 0 +EDGE2 3913 3912 -1.03994 -0.0359134 -0.0106384 1 0 1 1 0 0 +EDGE2 3914 3913 -0.999414 -0.0153049 -0.00749665 1 0 1 1 0 0 +EDGE2 3915 3914 -0.973239 0.0405177 -0.00859152 1 0 1 1 0 0 +EDGE2 3916 3915 -0.911581 0.0465664 -1.56675 1 0 1 1 0 0 +EDGE2 3917 3916 -1.03689 0.0974884 0.00889977 1 0 1 1 0 0 +EDGE2 3918 3917 -1.01676 0.0304401 -0.00376175 1 0 1 1 0 0 +EDGE2 3919 3918 -0.962073 -0.0649268 0.0264993 1 0 1 1 0 0 +EDGE2 3920 3919 -1.01434 -0.0805709 -0.0190884 1 0 1 1 0 0 +EDGE2 3921 3920 -0.987822 -0.0120973 -1.50797 1 0 1 1 0 0 +EDGE2 3922 3921 -0.950474 0.0542155 0.0259317 1 0 1 1 0 0 +EDGE2 3923 3922 -0.991529 0.0292484 0.0113761 1 0 1 1 0 0 +EDGE2 3924 3923 -0.934405 0.0453659 0.0130307 1 0 1 1 0 0 +EDGE2 3924 3905 1.02495 -0.0305329 -3.16881 1 0 1 1 0 0 +EDGE2 3925 3924 -1.05503 -0.0713289 0.00923318 1 0 1 1 0 0 +EDGE2 3925 3905 0.00759358 -0.00465692 -3.13466 1 0 1 1 0 0 +EDGE2 3925 3904 0.919601 -0.00600024 -3.12242 1 0 1 1 0 0 +EDGE2 3925 3906 0.0722175 0.956058 1.55912 1 0 1 1 0 0 +EDGE2 3926 3905 -1.008 0.0224721 1.52536 1 0 1 1 0 0 +EDGE2 3926 3925 -0.985789 -0.0427732 -1.58888 1 0 1 1 0 0 +EDGE2 3926 3907 1.003 -0.0307405 0.0134711 1 0 1 1 0 0 +EDGE2 3926 3906 0.0184411 -0.0345577 0.0185417 1 0 1 1 0 0 +EDGE2 3927 3907 -0.0298188 -0.0600376 0.0366399 1 0 1 1 0 0 +EDGE2 3927 3906 -1.02504 0.0378591 -0.0112418 1 0 1 1 0 0 +EDGE2 3927 3926 -1.06766 -0.0788098 -0.00126559 1 0 1 1 0 0 +EDGE2 3927 3908 0.990742 -0.00385412 -0.002876 1 0 1 1 0 0 +EDGE2 3928 3907 -0.973555 -0.0591126 0.00293573 1 0 1 1 0 0 +EDGE2 3928 3927 -0.985016 -0.0238586 -0.0373944 1 0 1 1 0 0 +EDGE2 3928 3908 -0.00285244 -0.0977597 -0.0348094 1 0 1 1 0 0 +EDGE2 3928 3909 1.1098 -0.0271384 -0.0074709 1 0 1 1 0 0 +EDGE2 3929 3908 -1.11616 0.0427241 0.0202109 1 0 1 1 0 0 +EDGE2 3929 3928 -0.999707 -0.0530979 0.000704284 1 0 1 1 0 0 +EDGE2 3929 3909 0.0242714 -0.043132 0.00287013 1 0 1 1 0 0 +EDGE2 3929 3910 0.99909 0.0517575 -0.0221637 1 0 1 1 0 0 +EDGE2 3930 3911 0.0257357 1.02523 1.57286 1 0 1 1 0 0 +EDGE2 3930 3929 -0.980975 0.0320052 -0.0396558 1 0 1 1 0 0 +EDGE2 3930 3909 -0.937375 -0.0342089 -0.0193364 1 0 1 1 0 0 +EDGE2 3930 3910 -0.0440142 0.0234274 -0.00011731 1 0 1 1 0 0 +EDGE2 3931 3912 0.955491 -0.0920816 -0.0199289 1 0 1 1 0 0 +EDGE2 3931 3911 -0.0463246 0.0515698 0.0574591 1 0 1 1 0 0 +EDGE2 3931 3910 -0.982038 -0.0155323 -1.54234 1 0 1 1 0 0 +EDGE2 3931 3930 -0.960902 -0.0145769 -1.57845 1 0 1 1 0 0 +EDGE2 3932 3913 0.977302 0.0719117 0.0135805 1 0 1 1 0 0 +EDGE2 3932 3912 -0.0204024 0.0467262 -0.00617341 1 0 1 1 0 0 +EDGE2 3932 3911 -1.01466 0.0165232 0.0395273 1 0 1 1 0 0 +EDGE2 3932 3931 -1.06016 0.0392835 -0.0125502 1 0 1 1 0 0 +EDGE2 3933 3913 0.0169451 0.0911068 0.0144725 1 0 1 1 0 0 +EDGE2 3933 3914 1.03485 0.0325344 -0.0163478 1 0 1 1 0 0 +EDGE2 3933 3932 -1.05553 -0.064288 0.00889699 1 0 1 1 0 0 +EDGE2 3933 3912 -1.09446 -0.0820937 -0.0275587 1 0 1 1 0 0 +EDGE2 3934 3915 0.960055 0.0234491 -0.0169289 1 0 1 1 0 0 +EDGE2 3934 3913 -0.897043 0.0824745 -0.0245618 1 0 1 1 0 0 +EDGE2 3934 3914 -0.0212442 -0.0529861 0.0126279 1 0 1 1 0 0 +EDGE2 3934 3933 -1.05636 -0.0382707 0.0146228 1 0 1 1 0 0 +EDGE2 3935 3916 0.0157197 1.02609 1.52831 1 0 1 1 0 0 +EDGE2 3935 3915 0.00398008 -0.027454 -0.0284052 1 0 1 1 0 0 +EDGE2 3935 3934 -0.954858 0.0121694 0.0118037 1 0 1 1 0 0 +EDGE2 3935 3914 -1.04272 0.0671297 -0.00266505 1 0 1 1 0 0 +EDGE2 3936 3917 0.990802 0.12192 -0.017221 1 0 1 1 0 0 +EDGE2 3936 3916 0.0156308 -0.0901733 -0.000859412 1 0 1 1 0 0 +EDGE2 3936 3935 -0.972774 -0.0308661 -1.57202 1 0 1 1 0 0 +EDGE2 3936 3915 -0.970887 -0.0232685 -1.54815 1 0 1 1 0 0 +EDGE2 3937 3918 1.04729 0.109118 -0.0282815 1 0 1 1 0 0 +EDGE2 3937 3917 0.0110989 0.0411111 0.0505792 1 0 1 1 0 0 +EDGE2 3937 3936 -0.973252 0.0239387 -0.00106782 1 0 1 1 0 0 +EDGE2 3937 3916 -0.964752 -0.00682148 -0.00886226 1 0 1 1 0 0 +EDGE2 3938 3919 0.935236 0.0756454 0.0153816 1 0 1 1 0 0 +EDGE2 3938 3918 -0.0455554 -0.0056064 0.00878275 1 0 1 1 0 0 +EDGE2 3938 3917 -0.991183 -0.0418196 -0.00155436 1 0 1 1 0 0 +EDGE2 3938 3937 -1.09002 -0.00449195 0.027887 1 0 1 1 0 0 +EDGE2 3939 3920 0.939814 -0.0492656 -0.0190914 1 0 1 1 0 0 +EDGE2 3939 3919 0.0299083 -0.0860802 0.0259366 1 0 1 1 0 0 +EDGE2 3939 3918 -1.0112 0.0242035 0.0152331 1 0 1 1 0 0 +EDGE2 3939 3938 -0.947822 0.0187086 -0.0008777 1 0 1 1 0 0 +EDGE2 3940 3920 -0.0301386 -0.0766122 -0.00727441 1 0 1 1 0 0 +EDGE2 3940 3919 -0.999042 -0.0483728 0.00817621 1 0 1 1 0 0 +EDGE2 3940 3939 -1.01786 0.0187227 0.0138533 1 0 1 1 0 0 +EDGE2 3940 3921 0.0197525 1.05223 1.56673 1 0 1 1 0 0 +EDGE2 3941 3920 -0.986999 -0.047727 -1.57154 1 0 1 1 0 0 +EDGE2 3941 3940 -0.998466 0.000419062 -1.58628 1 0 1 1 0 0 +EDGE2 3941 3921 0.0114435 -0.0349048 0.0177358 1 0 1 1 0 0 +EDGE2 3941 3922 1.13955 -0.0289301 -0.00048993 1 0 1 1 0 0 +EDGE2 3942 3921 -0.915284 -0.0773466 -0.0474731 1 0 1 1 0 0 +EDGE2 3942 3941 -1.05259 0.073056 0.000713751 1 0 1 1 0 0 +EDGE2 3942 3922 0.0168199 -0.0370553 0.0083519 1 0 1 1 0 0 +EDGE2 3942 3923 1.01979 -0.0384569 -0.0157159 1 0 1 1 0 0 +EDGE2 3943 3922 -1.02207 -0.0163128 -0.00958816 1 0 1 1 0 0 +EDGE2 3943 3942 -1.01533 0.0614749 0.00932621 1 0 1 1 0 0 +EDGE2 3943 3923 -0.0459106 -0.0201532 0.0183765 1 0 1 1 0 0 +EDGE2 3943 3924 1.06726 0.0563827 0.00456563 1 0 1 1 0 0 +EDGE2 3944 3923 -1.03125 0.0201872 -0.0379593 1 0 1 1 0 0 +EDGE2 3944 3943 -0.997107 -0.0553245 -0.0329665 1 0 1 1 0 0 +EDGE2 3944 3924 0.0217554 -0.0246538 0.0150582 1 0 1 1 0 0 +EDGE2 3944 3905 0.965519 -0.0726516 -3.15505 1 0 1 1 0 0 +EDGE2 3944 3925 1.01901 0.0780831 -0.0209593 1 0 1 1 0 0 +EDGE2 3945 3944 -0.996988 0.0290074 -0.00343808 1 0 1 1 0 0 +EDGE2 3945 3924 -1.05315 0.044913 -0.0178051 1 0 1 1 0 0 +EDGE2 3945 3905 0.0584766 0.0125898 -3.18389 1 0 1 1 0 0 +EDGE2 3945 3925 0.0266953 -0.0766206 0.0022219 1 0 1 1 0 0 +EDGE2 3945 3904 1.01244 0.0607183 -3.12718 1 0 1 1 0 0 +EDGE2 3945 3906 -0.0396637 0.988207 1.61214 1 0 1 1 0 0 +EDGE2 3945 3926 0.0372485 0.96844 1.6022 1 0 1 1 0 0 +EDGE2 3946 3905 -0.944443 0.0235196 1.56951 1 0 1 1 0 0 +EDGE2 3946 3945 -1.04062 0.00546128 -1.55495 1 0 1 1 0 0 +EDGE2 3946 3925 -1.04819 0.00515446 -1.57483 1 0 1 1 0 0 +EDGE2 3946 3907 0.997053 -0.000193128 -0.00106589 1 0 1 1 0 0 +EDGE2 3946 3906 -0.00747231 0.0548691 -0.00320364 1 0 1 1 0 0 +EDGE2 3946 3926 0.0543692 -0.157348 0.0024475 1 0 1 1 0 0 +EDGE2 3946 3927 1.05452 -0.075905 0.0142697 1 0 1 1 0 0 +EDGE2 3947 3907 -0.00153953 0.00933562 -0.0016013 1 0 1 1 0 0 +EDGE2 3947 3906 -1.07098 -0.0292647 -0.0123737 1 0 1 1 0 0 +EDGE2 3947 3946 -1.04018 0.0163899 0.0123234 1 0 1 1 0 0 +EDGE2 3947 3926 -0.955036 0.00330182 0.0226719 1 0 1 1 0 0 +EDGE2 3947 3927 0.0526602 -0.0643524 0.0112873 1 0 1 1 0 0 +EDGE2 3947 3908 1.076 -0.0488513 0.0172314 1 0 1 1 0 0 +EDGE2 3947 3928 0.952832 -0.0590619 0.0210062 1 0 1 1 0 0 +EDGE2 3948 3929 0.904645 0.0395359 -0.00925849 1 0 1 1 0 0 +EDGE2 3948 3907 -1.00182 -0.0264765 -0.00418452 1 0 1 1 0 0 +EDGE2 3948 3947 -1.05789 -0.00233179 0.00143624 1 0 1 1 0 0 +EDGE2 3948 3927 -1.04843 0.0141495 0.00811619 1 0 1 1 0 0 +EDGE2 3948 3908 0.0527842 0.0092892 -0.0389522 1 0 1 1 0 0 +EDGE2 3948 3928 0.0115994 0.0727001 -0.0426357 1 0 1 1 0 0 +EDGE2 3948 3909 0.958528 -0.0777948 0.0166825 1 0 1 1 0 0 +EDGE2 3949 3929 -0.00621143 -0.0126501 0.016701 1 0 1 1 0 0 +EDGE2 3949 3908 -0.978369 -0.0424552 0.0224362 1 0 1 1 0 0 +EDGE2 3949 3948 -0.945632 0.0102385 0.012518 1 0 1 1 0 0 +EDGE2 3949 3928 -0.977616 -0.0309899 -0.00163683 1 0 1 1 0 0 +EDGE2 3949 3909 0.0386844 0.103702 -0.0183206 1 0 1 1 0 0 +EDGE2 3949 3910 0.885718 0.0433284 0.0355569 1 0 1 1 0 0 +EDGE2 3949 3930 1.07437 -0.146406 0.0102858 1 0 1 1 0 0 +EDGE2 3950 3911 0.00979259 1.06526 1.57975 1 0 1 1 0 0 +EDGE2 3950 3931 -0.00648319 0.995451 1.60501 1 0 1 1 0 0 +EDGE2 3950 3929 -1.00147 -0.00680782 0.00356795 1 0 1 1 0 0 +EDGE2 3950 3949 -1.00036 0.0260043 -0.0151639 1 0 1 1 0 0 +EDGE2 3950 3909 -0.960941 -0.00856196 -0.00533343 1 0 1 1 0 0 +EDGE2 3950 3910 -0.0134226 0.0701394 -0.0157263 1 0 1 1 0 0 +EDGE2 3950 3930 0.0261308 0.00560371 0.0124003 1 0 1 1 0 0 +EDGE2 3951 3910 -0.971802 -0.0351151 1.58857 1 0 1 1 0 0 +EDGE2 3951 3930 -0.980358 -0.0697302 1.59074 1 0 1 1 0 0 +EDGE2 3951 3950 -0.949694 0.0284252 1.57523 1 0 1 1 0 0 +EDGE2 3952 3951 -0.95971 -0.062881 0.0125898 1 0 1 1 0 0 +EDGE2 3953 3952 -1.09334 -0.02334 -0.0135945 1 0 1 1 0 0 +EDGE2 3954 3953 -1.0382 0.0842166 0.0114412 1 0 1 1 0 0 +EDGE2 3955 3954 -0.999863 -0.0498993 -0.0251834 1 0 1 1 0 0 +EDGE2 3956 3955 -1.00196 0.0171728 -1.58399 1 0 1 1 0 0 +EDGE2 3957 3956 -0.990549 0.0308184 0.00471402 1 0 1 1 0 0 +EDGE2 3958 3957 -1.06241 -0.00239737 0.0153096 1 0 1 1 0 0 +EDGE2 3959 3958 -0.967009 -0.0802261 -0.0391654 1 0 1 1 0 0 +EDGE2 3960 3959 -1.03402 0.0124275 0.00745966 1 0 1 1 0 0 +EDGE2 3961 3960 -0.970434 0.0750717 -1.56206 1 0 1 1 0 0 +EDGE2 3962 3961 -1.00932 -0.00578213 -0.00470261 1 0 1 1 0 0 +EDGE2 3963 3962 -1.01108 -0.0147562 0.0071492 1 0 1 1 0 0 +EDGE2 3964 3963 -0.953895 0.0151128 0.00152007 1 0 1 1 0 0 +EDGE2 3965 3964 -1.06277 -0.0429947 0.0188279 1 0 1 1 0 0 +EDGE2 3966 3965 -0.916034 -0.0211437 -1.57096 1 0 1 1 0 0 +EDGE2 3967 3966 -1.01797 0.00987651 -0.0133266 1 0 1 1 0 0 +EDGE2 3968 3967 -0.986863 -0.0640326 -0.0117027 1 0 1 1 0 0 +EDGE2 3969 3910 1.03513 -0.100887 -3.17816 1 0 1 1 0 0 +EDGE2 3969 3930 1.00164 -0.0182385 -3.16117 1 0 1 1 0 0 +EDGE2 3969 3950 1.04372 -0.0736253 -3.12619 1 0 1 1 0 0 +EDGE2 3969 3968 -0.986812 -0.0510488 0.0262651 1 0 1 1 0 0 +EDGE2 3970 3911 0.0444631 -1.1243 -1.59159 1 0 1 1 0 0 +EDGE2 3970 3931 0.0715123 -1.02702 -1.59484 1 0 1 1 0 0 +EDGE2 3970 3929 1.05181 -0.0597557 -3.1399 1 0 1 1 0 0 +EDGE2 3970 3949 0.95093 0.0406906 -3.11152 1 0 1 1 0 0 +EDGE2 3970 3969 -0.952596 -0.13264 0.0108192 1 0 1 1 0 0 +EDGE2 3970 3909 1.01085 -0.0232441 -3.15708 1 0 1 1 0 0 +EDGE2 3970 3910 -0.0574641 0.0677911 -3.13988 1 0 1 1 0 0 +EDGE2 3970 3930 0.0649298 0.0122547 -3.12908 1 0 1 1 0 0 +EDGE2 3970 3950 0.038176 0.0638552 -3.13451 1 0 1 1 0 0 +EDGE2 3970 3951 0.0131745 0.99253 1.58617 1 0 1 1 0 0 +EDGE2 3971 3932 0.968869 0.0492431 -0.0188018 1 0 1 1 0 0 +EDGE2 3971 3912 0.958801 -0.0164471 -0.0263084 1 0 1 1 0 0 +EDGE2 3971 3911 0.0386739 -0.0174311 -0.0192916 1 0 1 1 0 0 +EDGE2 3971 3931 0.082298 -0.042842 0.0064814 1 0 1 1 0 0 +EDGE2 3971 3970 -0.996633 0.00358038 1.54402 1 0 1 1 0 0 +EDGE2 3971 3910 -1.00487 -0.043232 -1.56532 1 0 1 1 0 0 +EDGE2 3971 3930 -0.996433 -0.0497484 -1.58136 1 0 1 1 0 0 +EDGE2 3971 3950 -0.990804 0.0254635 -1.56214 1 0 1 1 0 0 +EDGE2 3972 3971 -1.08409 -0.0524833 0.013084 1 0 1 1 0 0 +EDGE2 3972 3913 1.03328 0.0878341 0.020849 1 0 1 1 0 0 +EDGE2 3972 3933 1.0092 -0.0545366 0.00373185 1 0 1 1 0 0 +EDGE2 3972 3932 0.00131465 -0.0515006 -0.0506972 1 0 1 1 0 0 +EDGE2 3972 3912 -0.0878919 0.0291784 0.0247677 1 0 1 1 0 0 +EDGE2 3972 3911 -0.917835 -0.00889304 -0.0238759 1 0 1 1 0 0 +EDGE2 3972 3931 -0.964628 0.134682 0.00401164 1 0 1 1 0 0 +EDGE2 3973 3913 0.0786644 0.0335015 -0.0189114 1 0 1 1 0 0 +EDGE2 3973 3934 0.951365 0.0434417 -0.0126324 1 0 1 1 0 0 +EDGE2 3973 3914 0.964273 0.0322573 -0.0217306 1 0 1 1 0 0 +EDGE2 3973 3933 0.0579518 -0.0395799 0.00376587 1 0 1 1 0 0 +EDGE2 3973 3932 -1.06709 -0.0155197 -0.0238468 1 0 1 1 0 0 +EDGE2 3973 3972 -1.01824 0.0127704 -0.0306134 1 0 1 1 0 0 +EDGE2 3973 3912 -1.09052 0.100596 0.0456727 1 0 1 1 0 0 +EDGE2 3974 3935 1.02479 -0.0450627 -0.0283511 1 0 1 1 0 0 +EDGE2 3974 3915 1.03151 -0.0112919 -0.0334844 1 0 1 1 0 0 +EDGE2 3974 3913 -1.02925 -0.0543924 -0.00523848 1 0 1 1 0 0 +EDGE2 3974 3934 0.00755197 0.0807852 -1.06975e-05 1 0 1 1 0 0 +EDGE2 3974 3914 -0.0192483 0.0181239 -0.00802741 1 0 1 1 0 0 +EDGE2 3974 3973 -0.999973 -0.0064123 -0.00841298 1 0 1 1 0 0 +EDGE2 3974 3933 -1.03385 -0.0023044 0.027361 1 0 1 1 0 0 +EDGE2 3975 3936 0.00693846 0.984496 1.60144 1 0 1 1 0 0 +EDGE2 3975 3916 -0.0272905 1.03122 1.59038 1 0 1 1 0 0 +EDGE2 3975 3935 0.0706728 -0.0234537 -0.034319 1 0 1 1 0 0 +EDGE2 3975 3915 0.016178 0.0124553 -0.0369963 1 0 1 1 0 0 +EDGE2 3975 3934 -1.01956 -0.0174279 -0.00309919 1 0 1 1 0 0 +EDGE2 3975 3974 -1.03227 -0.0483172 -0.0160358 1 0 1 1 0 0 +EDGE2 3975 3914 -1.02603 -0.0762194 -0.0203809 1 0 1 1 0 0 +EDGE2 3976 3935 -1.03765 0.0582397 1.57021 1 0 1 1 0 0 +EDGE2 3976 3975 -0.982474 0.0158827 1.54256 1 0 1 1 0 0 +EDGE2 3976 3915 -1.00831 0.0744972 1.57043 1 0 1 1 0 0 +EDGE2 3977 3976 -1.07035 -0.0997909 0.0465229 1 0 1 1 0 0 +EDGE2 3978 3977 -0.90622 0.0395775 -0.0147538 1 0 1 1 0 0 +EDGE2 3979 3978 -0.93032 0.0580046 -0.0106222 1 0 1 1 0 0 +EDGE2 3980 3979 -1.03912 0.0303219 0.0101662 1 0 1 1 0 0 +EDGE2 3981 3980 -1.1614 -0.106407 -1.55191 1 0 1 1 0 0 +EDGE2 3982 3981 -0.937661 0.0969444 -0.0122265 1 0 1 1 0 0 +EDGE2 3983 3982 -1.03195 -0.101607 -0.0189871 1 0 1 1 0 0 +EDGE2 3984 3983 -0.955031 -0.063439 -0.014379 1 0 1 1 0 0 +EDGE2 3985 3984 -1.03553 0.052987 -0.0130743 1 0 1 1 0 0 +EDGE2 3986 3985 -1.06033 0.0402089 -1.57226 1 0 1 1 0 0 +EDGE2 3987 3986 -0.958071 0.0486767 0.0186408 1 0 1 1 0 0 +EDGE2 3988 3987 -1.08821 0.0148985 0.0149148 1 0 1 1 0 0 +EDGE2 3989 3988 -0.908154 -0.0140113 0.028241 1 0 1 1 0 0 +EDGE2 3990 3989 -1.04933 0.0331141 0.0298341 1 0 1 1 0 0 +EDGE2 3991 3990 -0.853795 -0.028507 -1.54628 1 0 1 1 0 0 +EDGE2 3992 3991 -1.02045 0.0506408 -0.00799231 1 0 1 1 0 0 +EDGE2 3993 3992 -0.966169 0.0522706 -0.0284819 1 0 1 1 0 0 +EDGE2 3994 3993 -0.988849 0.0245186 -0.0237364 1 0 1 1 0 0 +EDGE2 3994 3935 1.06276 0.00152448 -3.15498 1 0 1 1 0 0 +EDGE2 3994 3975 0.937571 0.0129532 -3.10212 1 0 1 1 0 0 +EDGE2 3994 3915 1.02088 -0.0716136 -3.10513 1 0 1 1 0 0 +EDGE2 3995 3936 0.00926493 -0.981424 -1.55877 1 0 1 1 0 0 +EDGE2 3995 3916 0.0130684 -1.05768 -1.55171 1 0 1 1 0 0 +EDGE2 3995 3994 -0.97423 0.00388246 -0.0108545 1 0 1 1 0 0 +EDGE2 3995 3935 0.0767379 -0.0163454 -3.18358 1 0 1 1 0 0 +EDGE2 3995 3975 0.0529235 0.0196653 -3.11878 1 0 1 1 0 0 +EDGE2 3995 3915 -0.0914331 -0.0515895 -3.13281 1 0 1 1 0 0 +EDGE2 3995 3976 0.0793842 0.953859 1.56792 1 0 1 1 0 0 +EDGE2 3995 3934 1.0241 0.00624019 -3.11999 1 0 1 1 0 0 +EDGE2 3995 3974 1.01046 -0.0268323 -3.15985 1 0 1 1 0 0 +EDGE2 3995 3914 1.04582 0.030831 -3.16646 1 0 1 1 0 0 +EDGE2 3996 3977 1.01641 -0.0284668 -0.0152739 1 0 1 1 0 0 +EDGE2 3996 3935 -1.04588 0.0345823 1.6145 1 0 1 1 0 0 +EDGE2 3996 3975 -1.06534 -0.0397338 1.59511 1 0 1 1 0 0 +EDGE2 3996 3995 -0.939844 -0.00796382 -1.59224 1 0 1 1 0 0 +EDGE2 3996 3915 -1.07096 0.0345696 1.5961 1 0 1 1 0 0 +EDGE2 3996 3976 -0.0145956 -0.0515745 0.0303266 1 0 1 1 0 0 +EDGE2 3997 3977 0.025686 0.0105479 0.0398997 1 0 1 1 0 0 +EDGE2 3997 3976 -1.10004 0.0944381 0.02807 1 0 1 1 0 0 +EDGE2 3997 3996 -1.01544 0.0972944 -0.0358802 1 0 1 1 0 0 +EDGE2 3997 3978 1.05409 -0.00740925 0.00423157 1 0 1 1 0 0 +EDGE2 3998 3977 -0.953332 -0.0511217 0.00426294 1 0 1 1 0 0 +EDGE2 3998 3997 -1.01696 -0.048781 0.0168415 1 0 1 1 0 0 +EDGE2 3998 3978 0.0817679 -0.067804 0.00186429 1 0 1 1 0 0 +EDGE2 3998 3979 0.988736 0.0596446 -0.0287263 1 0 1 1 0 0 +EDGE2 3999 3998 -0.994827 0.0294717 0.00815113 1 0 1 1 0 0 +EDGE2 3999 3978 -0.987245 0.00799329 -0.0112637 1 0 1 1 0 0 +EDGE2 3999 3979 0.0423458 0.0407715 0.0148597 1 0 1 1 0 0 +EDGE2 3999 3980 1.07894 0.025922 -0.018046 1 0 1 1 0 0 +EDGE2 4000 3981 0.0449363 0.99433 1.59006 1 0 1 1 0 0 +EDGE2 4000 3999 -1.01882 0.0320901 0.000843137 1 0 1 1 0 0 +EDGE2 4000 3979 -0.989874 0.0182749 0.0189633 1 0 1 1 0 0 +EDGE2 4000 3980 -0.000494251 -0.0604098 -0.0409132 1 0 1 1 0 0 +EDGE2 4001 3982 0.974421 0.0933596 -0.00842304 1 0 1 1 0 0 +EDGE2 4001 3981 0.00424235 0.142219 0.00536156 1 0 1 1 0 0 +EDGE2 4001 4000 -1.0845 -0.0362491 -1.58643 1 0 1 1 0 0 +EDGE2 4001 3980 -0.976125 0.0196162 -1.58932 1 0 1 1 0 0 +EDGE2 4002 3983 0.941996 -0.00245882 0.00622596 1 0 1 1 0 0 +EDGE2 4002 4001 -0.908828 0.0341292 -0.0294848 1 0 1 1 0 0 +EDGE2 4002 3982 0.0731837 0.0510515 -0.02147 1 0 1 1 0 0 +EDGE2 4002 3981 -0.94633 -0.064486 -0.00735958 1 0 1 1 0 0 +EDGE2 4003 3983 -0.0695563 0.0586414 0.0162916 1 0 1 1 0 0 +EDGE2 4003 3984 1.04495 -0.000948157 0.00323333 1 0 1 1 0 0 +EDGE2 4003 3982 -1.01801 0.0121855 0.0144919 1 0 1 1 0 0 +EDGE2 4003 4002 -0.906636 -0.000227978 -0.0237669 1 0 1 1 0 0 +EDGE2 4004 3985 1.00245 0.0309844 -0.0037758 1 0 1 1 0 0 +EDGE2 4004 3983 -0.973757 0.0377757 -0.0124754 1 0 1 1 0 0 +EDGE2 4004 3984 0.0169983 0.0378249 0.00796035 1 0 1 1 0 0 +EDGE2 4004 4003 -1.0821 0.043369 0.0108074 1 0 1 1 0 0 +EDGE2 4005 3986 0.072014 1.06224 1.56184 1 0 1 1 0 0 +EDGE2 4005 3985 -0.0165262 -0.029118 0.0130792 1 0 1 1 0 0 +EDGE2 4005 3984 -0.978215 0.0406802 -0.000704176 1 0 1 1 0 0 +EDGE2 4005 4004 -1.00641 0.0623211 0.0208539 1 0 1 1 0 0 +EDGE2 4006 3987 0.974713 -0.00173849 0.0108086 1 0 1 1 0 0 +EDGE2 4006 4005 -1.0447 0.0769029 -1.54727 1 0 1 1 0 0 +EDGE2 4006 3986 -0.107012 -0.0851227 0.00337384 1 0 1 1 0 0 +EDGE2 4006 3985 -1.03772 0.0224761 -1.57633 1 0 1 1 0 0 +EDGE2 4007 4006 -0.99999 0.00395403 0.0281809 1 0 1 1 0 0 +EDGE2 4007 3988 0.985964 0.0371594 -0.0105052 1 0 1 1 0 0 +EDGE2 4007 3987 -0.0495683 -0.0339846 -0.0112463 1 0 1 1 0 0 +EDGE2 4007 3986 -1.01296 -0.00912437 -0.0109205 1 0 1 1 0 0 +EDGE2 4008 3989 0.994223 -0.0539417 -0.0154472 1 0 1 1 0 0 +EDGE2 4008 4007 -0.934974 0.0134691 0.00356569 1 0 1 1 0 0 +EDGE2 4008 3988 -0.120066 -0.00615467 -0.00264558 1 0 1 1 0 0 +EDGE2 4008 3987 -1.00306 0.00352838 -0.00875325 1 0 1 1 0 0 +EDGE2 4009 3989 -0.0531904 -0.0652076 0.0390614 1 0 1 1 0 0 +EDGE2 4009 3990 1.08171 0.0825465 0.00172492 1 0 1 1 0 0 +EDGE2 4009 3988 -0.978054 -0.0250194 -0.00274265 1 0 1 1 0 0 +EDGE2 4009 4008 -1.01571 0.00531535 -0.0175111 1 0 1 1 0 0 +EDGE2 4010 3989 -1.05428 -0.0413852 0.0312596 1 0 1 1 0 0 +EDGE2 4010 3990 -0.0292735 -0.0809936 0.00415125 1 0 1 1 0 0 +EDGE2 4010 4009 -1.03621 -0.0665475 0.00936737 1 0 1 1 0 0 +EDGE2 4010 3991 0.062527 1.0789 1.59322 1 0 1 1 0 0 +EDGE2 4011 3990 -1.02356 0.0166988 -1.56898 1 0 1 1 0 0 +EDGE2 4011 4010 -0.998137 -0.0502791 -1.60144 1 0 1 1 0 0 +EDGE2 4011 3991 0.0448677 -0.0343521 0.00735965 1 0 1 1 0 0 +EDGE2 4011 3992 0.997378 -0.0614224 -0.00446095 1 0 1 1 0 0 +EDGE2 4012 3991 -1.08712 0.0506498 -0.00496774 1 0 1 1 0 0 +EDGE2 4012 4011 -0.981832 -0.00758946 0.0210987 1 0 1 1 0 0 +EDGE2 4012 3992 0.0398165 0.0113989 -0.0148025 1 0 1 1 0 0 +EDGE2 4012 3993 0.937453 0.00346322 -0.0500147 1 0 1 1 0 0 +EDGE2 4013 3992 -0.993734 0.0166062 -0.0181981 1 0 1 1 0 0 +EDGE2 4013 4012 -1.02178 0.0776456 0.020614 1 0 1 1 0 0 +EDGE2 4013 3993 -0.041514 0.0558947 0.00859699 1 0 1 1 0 0 +EDGE2 4013 3994 1.01407 -0.0525147 0.00588399 1 0 1 1 0 0 +EDGE2 4014 4013 -1.00563 0.00785739 -0.0212129 1 0 1 1 0 0 +EDGE2 4014 3993 -1.01072 -0.0257498 -0.00606239 1 0 1 1 0 0 +EDGE2 4014 3994 0.0330511 0.0620249 0.00731587 1 0 1 1 0 0 +EDGE2 4014 3935 0.974154 0.0941433 -3.10167 1 0 1 1 0 0 +EDGE2 4014 3975 1.05967 0.0365069 -3.15848 1 0 1 1 0 0 +EDGE2 4014 3995 1.04077 -0.105995 0.0108651 1 0 1 1 0 0 +EDGE2 4014 3915 1.04028 0.0212543 -3.09458 1 0 1 1 0 0 +EDGE2 4015 3936 0.000277872 -1.04352 -1.54661 1 0 1 1 0 0 +EDGE2 4015 3916 0.0767657 -0.997792 -1.55366 1 0 1 1 0 0 +EDGE2 4015 4014 -1.01149 0.00388699 0.0256284 1 0 1 1 0 0 +EDGE2 4015 3994 -0.990218 0.0855245 -0.00358856 1 0 1 1 0 0 +EDGE2 4015 3935 -0.0270215 -0.0693601 -3.14056 1 0 1 1 0 0 +EDGE2 4015 3975 -0.025519 0.0254874 -3.14627 1 0 1 1 0 0 +EDGE2 4015 3995 0.0170501 0.0265776 0.000967754 1 0 1 1 0 0 +EDGE2 4015 3915 0.0604244 -0.0367459 -3.17076 1 0 1 1 0 0 +EDGE2 4015 3976 0.00788304 1.04591 1.56954 1 0 1 1 0 0 +EDGE2 4015 3996 -0.0177989 1.01569 1.55676 1 0 1 1 0 0 +EDGE2 4015 3934 1.02477 -0.00744471 -3.15809 1 0 1 1 0 0 +EDGE2 4015 3974 1.02786 -0.0709026 -3.15882 1 0 1 1 0 0 +EDGE2 4015 3914 0.925938 0.00605082 -3.15331 1 0 1 1 0 0 +EDGE2 4016 3977 0.963186 0.0314147 0.0142985 1 0 1 1 0 0 +EDGE2 4016 4015 -1.02591 0.0596763 -1.54497 1 0 1 1 0 0 +EDGE2 4016 3935 -0.983623 0.082585 1.53566 1 0 1 1 0 0 +EDGE2 4016 3975 -0.962599 -0.00925951 1.57664 1 0 1 1 0 0 +EDGE2 4016 3995 -1.01403 -0.0997539 -1.5836 1 0 1 1 0 0 +EDGE2 4016 3915 -1.03155 -0.110404 1.57988 1 0 1 1 0 0 +EDGE2 4016 3976 0.0014641 -0.0512054 0.0272914 1 0 1 1 0 0 +EDGE2 4016 3996 0.0701133 0.0350728 0.00928659 1 0 1 1 0 0 +EDGE2 4016 3997 1.00997 0.0425742 0.00947823 1 0 1 1 0 0 +EDGE2 4017 3977 0.0378632 0.0206617 0.00805449 1 0 1 1 0 0 +EDGE2 4017 4016 -0.983505 0.0673159 -0.0124727 1 0 1 1 0 0 +EDGE2 4017 3976 -1.031 0.00701482 0.025518 1 0 1 1 0 0 +EDGE2 4017 3996 -0.988852 0.111957 0.0265636 1 0 1 1 0 0 +EDGE2 4017 3997 0.0331825 0.0122699 0.0187088 1 0 1 1 0 0 +EDGE2 4017 3998 1.03035 0.0341383 -0.0213949 1 0 1 1 0 0 +EDGE2 4017 3978 1.10505 0.019095 -0.0146992 1 0 1 1 0 0 +EDGE2 4018 3977 -1.07664 -0.0410196 0.026788 1 0 1 1 0 0 +EDGE2 4018 4017 -0.940613 0.0817194 -0.00617047 1 0 1 1 0 0 +EDGE2 4018 3997 -0.867011 -0.0513418 0.0152476 1 0 1 1 0 0 +EDGE2 4018 3998 -0.0347409 0.0281853 -0.041169 1 0 1 1 0 0 +EDGE2 4018 3999 0.940834 -0.0537633 -0.0136394 1 0 1 1 0 0 +EDGE2 4018 3978 0.0701435 -0.0190943 0.0177633 1 0 1 1 0 0 +EDGE2 4018 3979 1.03848 0.0486944 -0.0115306 1 0 1 1 0 0 +EDGE2 4019 3998 -0.943057 0.119997 -0.0278866 1 0 1 1 0 0 +EDGE2 4019 4018 -1.04958 0.0485081 -0.0121006 1 0 1 1 0 0 +EDGE2 4019 3999 0.00958824 -0.0352637 -0.0176406 1 0 1 1 0 0 +EDGE2 4019 3978 -1.01432 0.0665252 -0.00790708 1 0 1 1 0 0 +EDGE2 4019 3979 -0.042681 0.0289869 -0.00358355 1 0 1 1 0 0 +EDGE2 4019 4000 0.952197 0.0843878 -0.0248328 1 0 1 1 0 0 +EDGE2 4019 3980 0.962211 -0.094058 -0.00403153 1 0 1 1 0 0 +EDGE2 4020 4001 -0.0726904 0.985112 1.56759 1 0 1 1 0 0 +EDGE2 4020 3981 -0.115244 1.00293 1.56167 1 0 1 1 0 0 +EDGE2 4020 3999 -1.06051 0.089139 -0.0159834 1 0 1 1 0 0 +EDGE2 4020 4019 -0.986547 0.0227668 0.00734384 1 0 1 1 0 0 +EDGE2 4020 3979 -0.999732 0.0755819 0.0153339 1 0 1 1 0 0 +EDGE2 4020 4000 -0.0396675 0.0962443 0.00393088 1 0 1 1 0 0 +EDGE2 4020 3980 0.0382539 -0.0608006 -0.0402671 1 0 1 1 0 0 +EDGE2 4021 4000 -0.943071 0.0961398 1.5571 1 0 1 1 0 0 +EDGE2 4021 4020 -0.937567 -0.0205232 1.59397 1 0 1 1 0 0 +EDGE2 4021 3980 -0.999047 -0.0378703 1.59537 1 0 1 1 0 0 +EDGE2 4022 4021 -0.944669 0.0830999 0.00260287 1 0 1 1 0 0 +EDGE2 4023 4022 -1.10528 0.00174373 -0.00970124 1 0 1 1 0 0 +EDGE2 4024 4023 -1.00362 -0.0192055 0.0254577 1 0 1 1 0 0 +EDGE2 4024 3965 1.10834 -0.0257793 -3.17198 1 0 1 1 0 0 +EDGE2 4025 4024 -0.948948 0.0134924 -0.0240069 1 0 1 1 0 0 +EDGE2 4025 3966 0.0457958 -1.03815 -1.56946 1 0 1 1 0 0 +EDGE2 4025 3965 0.0966231 -0.0105338 -3.11898 1 0 1 1 0 0 +EDGE2 4025 3964 1.0299 0.012309 -3.13081 1 0 1 1 0 0 +EDGE2 4026 3965 -0.947176 -0.0632 1.56341 1 0 1 1 0 0 +EDGE2 4026 4025 -0.973008 0.0019688 -1.59892 1 0 1 1 0 0 +EDGE2 4027 4026 -0.967816 0.0191693 0.0139075 1 0 1 1 0 0 +EDGE2 4028 4027 -0.972595 -0.0703494 0.0061428 1 0 1 1 0 0 +EDGE2 4029 4028 -1.03378 -0.012679 -0.0112034 1 0 1 1 0 0 +EDGE2 4030 4029 -0.953037 -0.00550354 -0.00278674 1 0 1 1 0 0 +EDGE2 4031 4030 -0.954519 -0.0629059 1.56022 1 0 1 1 0 0 +EDGE2 4032 4031 -1.00885 0.000843739 -0.0312053 1 0 1 1 0 0 +EDGE2 4033 4032 -0.990345 0.0588982 0.00163117 1 0 1 1 0 0 +EDGE2 4034 4033 -0.983136 0.00787374 -0.0138948 1 0 1 1 0 0 +EDGE2 4035 4034 -1.03266 0.0244233 0.0282075 1 0 1 1 0 0 +EDGE2 4036 4035 -1.00051 0.0258409 1.54326 1 0 1 1 0 0 +EDGE2 4037 4036 -0.998463 -0.0895462 -0.0114935 1 0 1 1 0 0 +EDGE2 4038 4037 -1.01428 -0.0488306 0.0149845 1 0 1 1 0 0 +EDGE2 4039 3960 0.978539 -0.0258281 -3.15776 1 0 1 1 0 0 +EDGE2 4039 4038 -0.923052 -0.0692094 0.00506203 1 0 1 1 0 0 +EDGE2 4040 3960 0.0184554 -0.0785404 -3.15979 1 0 1 1 0 0 +EDGE2 4040 3959 1.05169 0.0284985 -3.1666 1 0 1 1 0 0 +EDGE2 4040 3961 -0.0597764 -0.936497 -1.58132 1 0 1 1 0 0 +EDGE2 4040 4039 -0.895669 0.0404987 -0.0419637 1 0 1 1 0 0 +EDGE2 4041 3960 -0.961405 0.011121 1.536 1 0 1 1 0 0 +EDGE2 4041 4040 -1.04482 0.036684 -1.56787 1 0 1 1 0 0 +EDGE2 4042 4041 -1.02152 0.0468282 -0.0159603 1 0 1 1 0 0 +EDGE2 4043 4042 -1.07344 0.0499226 0.0217412 1 0 1 1 0 0 +EDGE2 4044 4043 -0.995265 -0.0147589 0.00984991 1 0 1 1 0 0 +EDGE2 4045 4044 -1.09847 -0.0331528 -0.0197719 1 0 1 1 0 0 +EDGE2 4046 4045 -0.985977 0.0508926 1.59604 1 0 1 1 0 0 +EDGE2 4047 4046 -0.999219 -0.0706197 0.0100908 1 0 1 1 0 0 +EDGE2 4048 4047 -1.03716 0.0378143 0.00663412 1 0 1 1 0 0 +EDGE2 4049 4048 -1.00091 -0.0891356 0.00347785 1 0 1 1 0 0 +EDGE2 4050 4049 -0.951715 -0.0984415 -0.00114586 1 0 1 1 0 0 +EDGE2 4051 4050 -1.0087 0.0055724 -1.58577 1 0 1 1 0 0 +EDGE2 4052 4051 -0.924298 0.034181 -0.0175241 1 0 1 1 0 0 +EDGE2 4053 4052 -0.912856 0.0149288 -0.0492777 1 0 1 1 0 0 +EDGE2 4054 4053 -0.980796 -0.0695152 -0.00458233 1 0 1 1 0 0 +EDGE2 4055 4054 -1.00641 -0.0549875 -0.0493418 1 0 1 1 0 0 +EDGE2 4056 4055 -0.98018 0.0682803 -1.55088 1 0 1 1 0 0 +EDGE2 4057 4056 -1.02405 0.0365275 0.00807948 1 0 1 1 0 0 +EDGE2 4058 4057 -0.973464 0.0266896 -0.0406113 1 0 1 1 0 0 +EDGE2 4059 4058 -0.968658 0.027993 -0.0359339 1 0 1 1 0 0 +EDGE2 4060 4059 -1.08639 -0.11576 -0.0122831 1 0 1 1 0 0 +EDGE2 4061 4060 -1.00013 0.0346303 -1.60502 1 0 1 1 0 0 +EDGE2 4062 4061 -1.09209 0.0990123 -0.00110964 1 0 1 1 0 0 +EDGE2 4063 4062 -1.02746 -0.0586183 -0.031227 1 0 1 1 0 0 +EDGE2 4064 4063 -1.03062 -0.0153529 -0.0142513 1 0 1 1 0 0 +EDGE2 4064 4045 1.01427 0.0446839 -3.14675 1 0 1 1 0 0 +EDGE2 4065 4046 0.00219762 0.979672 1.56697 1 0 1 1 0 0 +EDGE2 4065 4045 -0.0175805 -0.0246884 -3.16844 1 0 1 1 0 0 +EDGE2 4065 4044 0.999581 0.0497128 -3.14356 1 0 1 1 0 0 +EDGE2 4065 4064 -0.95838 -0.0381187 0.0137924 1 0 1 1 0 0 +EDGE2 4066 4047 0.947004 0.013542 0.0214027 1 0 1 1 0 0 +EDGE2 4066 4046 0.0171898 -0.120529 -0.030661 1 0 1 1 0 0 +EDGE2 4066 4045 -1.02301 -0.0530662 1.59453 1 0 1 1 0 0 +EDGE2 4066 4065 -1.03877 -0.0531598 -1.59831 1 0 1 1 0 0 +EDGE2 4067 4047 0.0023582 0.00424872 -0.0170018 1 0 1 1 0 0 +EDGE2 4067 4048 0.953334 0.00381692 0.0228027 1 0 1 1 0 0 +EDGE2 4067 4046 -1.02356 0.000638489 -0.00120048 1 0 1 1 0 0 +EDGE2 4067 4066 -1.07106 -0.0201241 0.0107965 1 0 1 1 0 0 +EDGE2 4068 4049 0.981493 0.0770439 -0.0272068 1 0 1 1 0 0 +EDGE2 4068 4047 -0.944488 0.0754092 -0.0251824 1 0 1 1 0 0 +EDGE2 4068 4048 0.0469909 -0.0290903 -0.00296566 1 0 1 1 0 0 +EDGE2 4068 4067 -1.03943 -0.0361932 -0.00436041 1 0 1 1 0 0 +EDGE2 4069 4050 0.995023 0.0396726 0.000853921 1 0 1 1 0 0 +EDGE2 4069 4049 -0.0416321 -0.015248 0.028905 1 0 1 1 0 0 +EDGE2 4069 4048 -0.948194 -0.0130082 0.0171832 1 0 1 1 0 0 +EDGE2 4069 4068 -0.944917 -0.0172062 -0.0189035 1 0 1 1 0 0 +EDGE2 4070 4050 -0.0483691 -0.016414 -0.025542 1 0 1 1 0 0 +EDGE2 4070 4051 -0.00756686 0.998828 1.5811 1 0 1 1 0 0 +EDGE2 4070 4049 -1.01776 -0.0539569 -0.0112398 1 0 1 1 0 0 +EDGE2 4070 4069 -1.01174 0.1021 0.0103674 1 0 1 1 0 0 +EDGE2 4071 4050 -1.04512 0.0130539 1.59998 1 0 1 1 0 0 +EDGE2 4071 4070 -0.972266 0.00714214 1.59466 1 0 1 1 0 0 +EDGE2 4072 4071 -1.07939 -0.0539784 0.0392938 1 0 1 1 0 0 +EDGE2 4073 4072 -0.964398 -0.0218409 -0.0119653 1 0 1 1 0 0 +EDGE2 4074 4073 -1.04194 -0.0207521 0.0143495 1 0 1 1 0 0 +EDGE2 4074 3955 0.993404 -0.0895998 -3.1394 1 0 1 1 0 0 +EDGE2 4075 3954 1.09078 0.073959 -3.15279 1 0 1 1 0 0 +EDGE2 4075 4074 -0.943007 -0.0670111 0.0137896 1 0 1 1 0 0 +EDGE2 4075 3955 -0.0403093 -0.00894896 -3.14849 1 0 1 1 0 0 +EDGE2 4075 3956 -0.0450932 -1.00719 -1.57348 1 0 1 1 0 0 +EDGE2 4076 3957 0.987344 -0.00475538 0.0431475 1 0 1 1 0 0 +EDGE2 4076 4075 -1.00427 -0.0269267 1.60345 1 0 1 1 0 0 +EDGE2 4076 3955 -1.03992 -0.0337673 -1.57359 1 0 1 1 0 0 +EDGE2 4076 3956 0.0363186 -0.0293425 0.00655942 1 0 1 1 0 0 +EDGE2 4077 3957 0.0211083 0.0470141 -0.0161686 1 0 1 1 0 0 +EDGE2 4077 3956 -0.917393 0.0975751 -0.00268867 1 0 1 1 0 0 +EDGE2 4077 4076 -1.02928 0.0427599 0.0400813 1 0 1 1 0 0 +EDGE2 4077 3958 0.938273 -0.0302525 0.00530939 1 0 1 1 0 0 +EDGE2 4078 3957 -1.1369 0.0590357 -0.00637211 1 0 1 1 0 0 +EDGE2 4078 4077 -0.884053 0.0167929 -0.0408815 1 0 1 1 0 0 +EDGE2 4078 3958 0.0102611 0.0121319 0.0165206 1 0 1 1 0 0 +EDGE2 4078 3959 1.02886 0.0341175 -0.00316504 1 0 1 1 0 0 +EDGE2 4079 3960 0.912913 0.0169507 0.00378366 1 0 1 1 0 0 +EDGE2 4079 4040 1.08653 -0.0390687 -3.1805 1 0 1 1 0 0 +EDGE2 4079 3958 -0.913363 -0.0373564 0.0131954 1 0 1 1 0 0 +EDGE2 4079 4078 -1.09011 0.0392886 -0.0406083 1 0 1 1 0 0 +EDGE2 4079 3959 0.0011328 -0.0176764 -0.0272899 1 0 1 1 0 0 +EDGE2 4080 3960 -0.0132908 -0.0154796 0.0285573 1 0 1 1 0 0 +EDGE2 4080 4040 -0.0219821 0.00464546 -3.19395 1 0 1 1 0 0 +EDGE2 4080 4079 -0.972051 -0.00331536 -0.00415645 1 0 1 1 0 0 +EDGE2 4080 3959 -1.00639 0.0665342 0.0118813 1 0 1 1 0 0 +EDGE2 4080 3961 0.0823904 0.950819 1.54452 1 0 1 1 0 0 +EDGE2 4080 4039 1.06639 -0.0160042 -3.12489 1 0 1 1 0 0 +EDGE2 4080 4041 0.0396025 -0.861265 -1.58298 1 0 1 1 0 0 +EDGE2 4081 3960 -0.965983 -0.027643 -1.5414 1 0 1 1 0 0 +EDGE2 4081 4040 -0.940747 -0.0122788 1.57914 1 0 1 1 0 0 +EDGE2 4081 3961 -0.0252193 -0.0222566 -0.0362831 1 0 1 1 0 0 +EDGE2 4081 3962 0.958645 -0.0376686 0.00683828 1 0 1 1 0 0 +EDGE2 4081 4080 -0.981571 -0.0212529 -1.56201 1 0 1 1 0 0 +EDGE2 4082 3963 1.03595 0.0819733 -0.000124844 1 0 1 1 0 0 +EDGE2 4082 3961 -0.960281 -0.0276012 -0.015784 1 0 1 1 0 0 +EDGE2 4082 4081 -0.980905 -0.0939752 -0.0352035 1 0 1 1 0 0 +EDGE2 4082 3962 -0.102558 -0.0185098 -0.00132285 1 0 1 1 0 0 +EDGE2 4083 3964 0.89281 0.0159413 -0.0152163 1 0 1 1 0 0 +EDGE2 4083 3963 -0.000922153 -0.10547 0.0256554 1 0 1 1 0 0 +EDGE2 4083 4082 -0.965605 0.0812719 -0.0125711 1 0 1 1 0 0 +EDGE2 4083 3962 -0.994548 -0.00689397 -0.0140197 1 0 1 1 0 0 +EDGE2 4084 3965 1.05065 -0.0673901 0.00868666 1 0 1 1 0 0 +EDGE2 4084 4025 1.01858 0.0703954 -3.11478 1 0 1 1 0 0 +EDGE2 4084 4083 -0.936661 -0.0508141 0.0147102 1 0 1 1 0 0 +EDGE2 4084 3964 0.0752525 -0.0440139 -0.0259894 1 0 1 1 0 0 +EDGE2 4084 3963 -1.059 -0.0426066 0.0151358 1 0 1 1 0 0 +EDGE2 4085 4024 0.962597 -0.0097802 -3.19108 1 0 1 1 0 0 +EDGE2 4085 3966 0.0474735 1.01853 1.57038 1 0 1 1 0 0 +EDGE2 4085 3965 0.0544774 0.0277547 -0.0152844 1 0 1 1 0 0 +EDGE2 4085 4025 -0.0240587 -0.0557334 -3.10675 1 0 1 1 0 0 +EDGE2 4085 4026 -0.0597713 -0.973305 -1.55386 1 0 1 1 0 0 +EDGE2 4085 3964 -0.925955 -0.115183 -0.00374486 1 0 1 1 0 0 +EDGE2 4085 4084 -1.04055 0.0394613 0.0622736 1 0 1 1 0 0 +EDGE2 4086 4085 -0.965832 -0.00933242 1.54011 1 0 1 1 0 0 +EDGE2 4086 3965 -0.95822 -0.0430844 1.58909 1 0 1 1 0 0 +EDGE2 4086 4025 -0.990917 -0.00842857 -1.5617 1 0 1 1 0 0 +EDGE2 4086 4026 0.00324202 0.0431227 0.0507998 1 0 1 1 0 0 +EDGE2 4086 4027 1.02625 -0.0418333 -0.0083718 1 0 1 1 0 0 +EDGE2 4087 4086 -0.966972 -0.00199185 -0.0209647 1 0 1 1 0 0 +EDGE2 4087 4026 -1.02362 -0.0521691 0.0294843 1 0 1 1 0 0 +EDGE2 4087 4028 1.01932 0.0343343 -0.0247512 1 0 1 1 0 0 +EDGE2 4087 4027 -0.0857523 0.0550903 -0.0259639 1 0 1 1 0 0 +EDGE2 4088 4029 1.0033 0.115957 -0.0421686 1 0 1 1 0 0 +EDGE2 4088 4087 -1.03508 0.0551787 0.00817435 1 0 1 1 0 0 +EDGE2 4088 4028 0.0530437 -0.0322673 0.000688409 1 0 1 1 0 0 +EDGE2 4088 4027 -0.937708 -0.0770651 0.0103233 1 0 1 1 0 0 +EDGE2 4089 4029 0.014253 -0.0184523 0.0191763 1 0 1 1 0 0 +EDGE2 4089 4028 -1.09281 0.0047249 -0.00277891 1 0 1 1 0 0 +EDGE2 4089 4088 -1.03067 -0.0315991 -0.000658265 1 0 1 1 0 0 +EDGE2 4089 4030 0.931522 0.0151097 -0.0110458 1 0 1 1 0 0 +EDGE2 4090 4029 -0.96618 -0.00659476 0.00400596 1 0 1 1 0 0 +EDGE2 4090 4089 -0.985377 0.00200385 0.00919744 1 0 1 1 0 0 +EDGE2 4090 4031 0.0156845 -1.02345 -1.55895 1 0 1 1 0 0 +EDGE2 4090 4030 0.0357358 -0.0291509 -0.0304199 1 0 1 1 0 0 +EDGE2 4091 4090 -0.972225 -0.0424355 -1.58329 1 0 1 1 0 0 +EDGE2 4091 4030 -1.00974 0.00971349 -1.57129 1 0 1 1 0 0 +EDGE2 4092 4091 -0.983483 0.0250525 0.0228053 1 0 1 1 0 0 +EDGE2 4093 4092 -0.983596 0.0195633 -0.0113494 1 0 1 1 0 0 +EDGE2 4094 4093 -0.909806 0.0301086 -0.00487351 1 0 1 1 0 0 +EDGE2 4095 4094 -1.02025 0.0459696 0.0102517 1 0 1 1 0 0 +EDGE2 4096 4095 -1.06913 -0.038772 -1.53137 1 0 1 1 0 0 +EDGE2 4097 4096 -0.889339 0.0545606 -0.00209169 1 0 1 1 0 0 +EDGE2 4098 4097 -1.01608 0.076577 0.00553953 1 0 1 1 0 0 +EDGE2 4099 4000 1.03398 -0.0604019 -3.12991 1 0 1 1 0 0 +EDGE2 4099 4020 1.00747 -0.00640961 -3.11512 1 0 1 1 0 0 +EDGE2 4099 3980 0.976936 0.0352646 -3.14657 1 0 1 1 0 0 +EDGE2 4099 4098 -0.9388 0.0586441 0.0138816 1 0 1 1 0 0 +EDGE2 4100 4099 -0.984432 0.0240784 -0.0268174 1 0 1 1 0 0 +EDGE2 4100 4001 -0.00667122 -0.978564 -1.55749 1 0 1 1 0 0 +EDGE2 4100 3981 -0.0166368 -0.986489 -1.55421 1 0 1 1 0 0 +EDGE2 4100 3999 1.03553 -0.0113267 -3.13348 1 0 1 1 0 0 +EDGE2 4100 4019 0.960334 -0.0509676 -3.12914 1 0 1 1 0 0 +EDGE2 4100 3979 1.03912 0.0552762 -3.15844 1 0 1 1 0 0 +EDGE2 4100 4000 0.070824 0.0361785 -3.16303 1 0 1 1 0 0 +EDGE2 4100 4020 0.0330418 -0.0293201 -3.14394 1 0 1 1 0 0 +EDGE2 4100 3980 0.0775904 -0.0152727 -3.1327 1 0 1 1 0 0 +EDGE2 4100 4021 -0.0293038 0.998594 1.55787 1 0 1 1 0 0 +EDGE2 4101 4100 -0.991087 -0.0157042 -1.56394 1 0 1 1 0 0 +EDGE2 4101 4000 -1.03576 0.0488807 1.60085 1 0 1 1 0 0 +EDGE2 4101 4020 -0.970414 -0.0396828 1.59244 1 0 1 1 0 0 +EDGE2 4101 3980 -1.05061 -0.00185481 1.59268 1 0 1 1 0 0 +EDGE2 4101 4021 0.00438144 0.0037228 -0.00989035 1 0 1 1 0 0 +EDGE2 4101 4022 1.04065 -0.0408633 0.0702087 1 0 1 1 0 0 +EDGE2 4102 4021 -0.967922 -0.00618965 -0.0150168 1 0 1 1 0 0 +EDGE2 4102 4101 -0.970328 -0.0576618 -0.0102749 1 0 1 1 0 0 +EDGE2 4102 4022 -0.0592401 -0.0146347 -0.00648604 1 0 1 1 0 0 +EDGE2 4102 4023 0.976661 -0.0160879 0.00183026 1 0 1 1 0 0 +EDGE2 4103 4102 -0.983353 0.0455855 -0.0260529 1 0 1 1 0 0 +EDGE2 4103 4022 -1.04317 0.0247899 -0.0116996 1 0 1 1 0 0 +EDGE2 4103 4023 0.0988004 -0.00776616 0.0184774 1 0 1 1 0 0 +EDGE2 4103 4024 0.927996 -0.072436 0.00268947 1 0 1 1 0 0 +EDGE2 4104 4103 -0.969952 0.0518075 -0.02363 1 0 1 1 0 0 +EDGE2 4104 4023 -1.02327 0.111318 0.000169763 1 0 1 1 0 0 +EDGE2 4104 4024 0.0139828 0.0544043 -0.00438127 1 0 1 1 0 0 +EDGE2 4104 4085 0.976492 -0.0628744 -3.12957 1 0 1 1 0 0 +EDGE2 4104 3965 1.07128 -0.032605 -3.16901 1 0 1 1 0 0 +EDGE2 4104 4025 0.984279 0.0282779 -0.038507 1 0 1 1 0 0 +EDGE2 4105 4104 -1.00275 -0.00455461 -0.00942329 1 0 1 1 0 0 +EDGE2 4105 4024 -1.06572 -0.0504295 -0.0243556 1 0 1 1 0 0 +EDGE2 4105 4085 -0.0597535 -0.0365559 -3.10802 1 0 1 1 0 0 +EDGE2 4105 3966 -0.0510192 -0.978758 -1.57178 1 0 1 1 0 0 +EDGE2 4105 4086 0.0850834 1.06246 1.58994 1 0 1 1 0 0 +EDGE2 4105 3965 0.0870967 0.0131635 -3.1319 1 0 1 1 0 0 +EDGE2 4105 4025 -0.0702688 -0.0323295 -0.0276239 1 0 1 1 0 0 +EDGE2 4105 4026 0.0259997 1.04134 1.5709 1 0 1 1 0 0 +EDGE2 4105 3964 1.00016 -0.0421257 -3.15033 1 0 1 1 0 0 +EDGE2 4105 4084 1.07272 -0.0105846 -3.13352 1 0 1 1 0 0 +EDGE2 4106 4085 -1.01884 0.067519 -1.55346 1 0 1 1 0 0 +EDGE2 4106 3966 0.0329067 0.0526656 0.0125086 1 0 1 1 0 0 +EDGE2 4106 3967 1.02041 0.0190502 -0.00106509 1 0 1 1 0 0 +EDGE2 4106 4105 -1.02871 -0.0776122 1.59885 1 0 1 1 0 0 +EDGE2 4106 3965 -0.991891 0.0219981 -1.5835 1 0 1 1 0 0 +EDGE2 4106 4025 -0.99753 0.0473806 1.58228 1 0 1 1 0 0 +EDGE2 4107 3968 1.0091 -0.00330189 0.0356119 1 0 1 1 0 0 +EDGE2 4107 3966 -1.02404 0.00849944 -0.0237384 1 0 1 1 0 0 +EDGE2 4107 4106 -0.923368 0.03802 -0.0105848 1 0 1 1 0 0 +EDGE2 4107 3967 0.00941344 0.107309 -0.0469529 1 0 1 1 0 0 +EDGE2 4108 3969 0.984949 -0.10459 0.00768438 1 0 1 1 0 0 +EDGE2 4108 4107 -0.993236 -0.101721 0.0279185 1 0 1 1 0 0 +EDGE2 4108 3968 -0.0123625 0.0924892 0.00162885 1 0 1 1 0 0 +EDGE2 4108 3967 -1.02841 -0.0236935 0.0353891 1 0 1 1 0 0 +EDGE2 4109 3969 -0.00574855 -0.0942591 -0.00126726 1 0 1 1 0 0 +EDGE2 4109 3970 1.0026 -0.00309496 0.00446333 1 0 1 1 0 0 +EDGE2 4109 3910 0.962724 0.0514748 -3.11265 1 0 1 1 0 0 +EDGE2 4109 3930 1.09214 0.00918805 -3.14454 1 0 1 1 0 0 +EDGE2 4109 3950 1.00985 -0.0282498 -3.1718 1 0 1 1 0 0 +EDGE2 4109 4108 -1.02227 -0.02976 0.00487073 1 0 1 1 0 0 +EDGE2 4109 3968 -0.982259 0.0379802 0.0479809 1 0 1 1 0 0 +EDGE2 4110 3971 0.0296514 -0.998724 -1.58282 1 0 1 1 0 0 +EDGE2 4110 3911 -0.00507971 -0.989058 -1.57 1 0 1 1 0 0 +EDGE2 4110 3931 0.0792922 -1.00475 -1.58951 1 0 1 1 0 0 +EDGE2 4110 3929 0.985261 -0.0027727 -3.16822 1 0 1 1 0 0 +EDGE2 4110 3949 1.00256 -0.0573607 -3.12463 1 0 1 1 0 0 +EDGE2 4110 3969 -1.02023 0.057272 0.00969903 1 0 1 1 0 0 +EDGE2 4110 3970 -0.0319679 -0.0307308 -0.023592 1 0 1 1 0 0 +EDGE2 4110 3909 0.938707 0.0022356 -3.13794 1 0 1 1 0 0 +EDGE2 4110 3910 0.0266798 -0.00108678 -3.13923 1 0 1 1 0 0 +EDGE2 4110 3930 -0.0531115 -0.0835295 -3.17659 1 0 1 1 0 0 +EDGE2 4110 3950 -0.0100365 0.0284922 -3.09662 1 0 1 1 0 0 +EDGE2 4110 4109 -0.95775 -0.0114668 -0.0284447 1 0 1 1 0 0 +EDGE2 4110 3951 0.00630335 0.95071 1.54133 1 0 1 1 0 0 +EDGE2 4111 3971 0.000608421 0.0470501 0.00273421 1 0 1 1 0 0 +EDGE2 4111 3932 0.971885 -0.0231275 0.00753429 1 0 1 1 0 0 +EDGE2 4111 3972 0.955658 0.0107205 -0.0348425 1 0 1 1 0 0 +EDGE2 4111 3912 0.996464 -0.0327927 -0.0150804 1 0 1 1 0 0 +EDGE2 4111 3911 -0.0415963 -0.0338686 0.0108048 1 0 1 1 0 0 +EDGE2 4111 3931 -0.0603082 0.100663 -0.00296601 1 0 1 1 0 0 +EDGE2 4111 3970 -0.983512 -0.0394408 1.59612 1 0 1 1 0 0 +EDGE2 4111 4110 -1.00537 -0.0381487 1.57941 1 0 1 1 0 0 +EDGE2 4111 3910 -1.0351 0.0615706 -1.57156 1 0 1 1 0 0 +EDGE2 4111 3930 -1.03118 0.0194787 -1.54666 1 0 1 1 0 0 +EDGE2 4111 3950 -1.03751 0.0948596 -1.60965 1 0 1 1 0 0 +EDGE2 4112 3971 -0.99609 -0.0747868 -0.0126132 1 0 1 1 0 0 +EDGE2 4112 3913 0.978596 0.0868745 -0.0108884 1 0 1 1 0 0 +EDGE2 4112 3973 0.903022 0.052151 0.0293087 1 0 1 1 0 0 +EDGE2 4112 3933 0.971569 -0.0642799 0.00831619 1 0 1 1 0 0 +EDGE2 4112 3932 -0.0641237 0.0483032 -0.00607973 1 0 1 1 0 0 +EDGE2 4112 3972 0.052638 -0.0843831 -0.00978966 1 0 1 1 0 0 +EDGE2 4112 3912 -0.0043052 0.0187674 -0.0316634 1 0 1 1 0 0 +EDGE2 4112 4111 -0.959649 0.0549708 -0.00983891 1 0 1 1 0 0 +EDGE2 4112 3911 -0.931686 0.0412097 -0.020091 1 0 1 1 0 0 +EDGE2 4112 3931 -1.02324 0.10853 -0.0337741 1 0 1 1 0 0 +EDGE2 4113 3913 0.0606689 -0.144146 -0.00251925 1 0 1 1 0 0 +EDGE2 4113 3934 0.990342 -0.0597654 -0.0125383 1 0 1 1 0 0 +EDGE2 4113 3974 0.976377 0.00404384 0.0185955 1 0 1 1 0 0 +EDGE2 4113 3914 0.958596 -0.032631 -0.0171722 1 0 1 1 0 0 +EDGE2 4113 3973 0.0515706 0.0733631 -0.00821631 1 0 1 1 0 0 +EDGE2 4113 3933 0.0588031 0.00704628 -0.0117585 1 0 1 1 0 0 +EDGE2 4113 3932 -0.962267 -0.0443333 0.0259623 1 0 1 1 0 0 +EDGE2 4113 4112 -1.06941 0.0335003 -0.0158544 1 0 1 1 0 0 +EDGE2 4113 3972 -0.982544 -0.0171219 0.00451984 1 0 1 1 0 0 +EDGE2 4113 3912 -1.01576 0.0198767 0.00219084 1 0 1 1 0 0 +EDGE2 4114 4015 0.91662 0.0249705 -3.14876 1 0 1 1 0 0 +EDGE2 4114 3935 0.919054 0.0734612 0.0268895 1 0 1 1 0 0 +EDGE2 4114 3975 1.04499 0.0295193 -0.00939126 1 0 1 1 0 0 +EDGE2 4114 3995 0.974157 -0.0178305 -3.13762 1 0 1 1 0 0 +EDGE2 4114 3915 0.937254 0.0165684 0.026444 1 0 1 1 0 0 +EDGE2 4114 3913 -1.10501 -0.067101 -0.0284082 1 0 1 1 0 0 +EDGE2 4114 3934 -0.034455 0.0722334 0.00329017 1 0 1 1 0 0 +EDGE2 4114 3974 -0.034507 -0.0423332 -0.00269114 1 0 1 1 0 0 +EDGE2 4114 3914 0.0403589 -0.0862106 -0.0258605 1 0 1 1 0 0 +EDGE2 4114 3973 -1.05423 0.0697094 -0.0103309 1 0 1 1 0 0 +EDGE2 4114 4113 -1.11303 0.0382705 0.000921137 1 0 1 1 0 0 +EDGE2 4114 3933 -0.926589 0.157273 0.0108202 1 0 1 1 0 0 +EDGE2 4115 3936 0.0291838 0.933294 1.57003 1 0 1 1 0 0 +EDGE2 4115 3916 -0.0184977 1.08984 1.5672 1 0 1 1 0 0 +EDGE2 4115 4015 -0.0246531 -0.136121 -3.13907 1 0 1 1 0 0 +EDGE2 4115 4014 0.927437 -0.00772112 -3.11609 1 0 1 1 0 0 +EDGE2 4115 3994 1.03596 0.0116371 -3.10854 1 0 1 1 0 0 +EDGE2 4115 4016 0.0482867 -0.916261 -1.57064 1 0 1 1 0 0 +EDGE2 4115 3935 0.00212112 0.0384691 -0.0352219 1 0 1 1 0 0 +EDGE2 4115 3975 -0.0272137 0.0554832 0.0222515 1 0 1 1 0 0 +EDGE2 4115 3995 0.0171891 0.0122907 -3.12943 1 0 1 1 0 0 +EDGE2 4115 3915 -0.00247101 0.0607176 -0.00212223 1 0 1 1 0 0 +EDGE2 4115 3976 0.0668832 -0.914044 -1.54402 1 0 1 1 0 0 +EDGE2 4115 3996 0.0145874 -1.03148 -1.57997 1 0 1 1 0 0 +EDGE2 4115 3934 -1.03642 -0.0366471 -0.0279592 1 0 1 1 0 0 +EDGE2 4115 3974 -1.0271 -0.00103502 -0.00584019 1 0 1 1 0 0 +EDGE2 4115 4114 -1.01343 0.0226101 -0.010135 1 0 1 1 0 0 +EDGE2 4115 3914 -0.961317 0.00257123 0.00810494 1 0 1 1 0 0 +EDGE2 4116 3917 1.0815 0.068896 -0.02981 1 0 1 1 0 0 +EDGE2 4116 3937 1.03849 0.0572929 0.0248164 1 0 1 1 0 0 +EDGE2 4116 3936 -0.061323 -0.0814939 -0.0102512 1 0 1 1 0 0 +EDGE2 4116 3916 0.0784051 -0.0558199 -0.0023268 1 0 1 1 0 0 +EDGE2 4116 4015 -0.982053 0.0294408 1.56942 1 0 1 1 0 0 +EDGE2 4116 4115 -1.0632 -0.0452747 -1.57948 1 0 1 1 0 0 +EDGE2 4116 3935 -1.01007 0.00205904 -1.54582 1 0 1 1 0 0 +EDGE2 4116 3975 -1.09368 -0.000452254 -1.54174 1 0 1 1 0 0 +EDGE2 4116 3995 -0.979497 -0.0222786 1.57463 1 0 1 1 0 0 +EDGE2 4116 3915 -1.03545 0.0215948 -1.53253 1 0 1 1 0 0 +EDGE2 4117 3918 1.00496 -0.0795566 0.0228099 1 0 1 1 0 0 +EDGE2 4117 3938 1.01302 0.027864 -0.0264671 1 0 1 1 0 0 +EDGE2 4117 3917 -0.00317869 0.078832 0.0198898 1 0 1 1 0 0 +EDGE2 4117 3937 0.0970722 0.00188354 -0.0192673 1 0 1 1 0 0 +EDGE2 4117 3936 -1.00936 0.064276 -0.00355429 1 0 1 1 0 0 +EDGE2 4117 4116 -0.937087 0.00514693 0.00772437 1 0 1 1 0 0 +EDGE2 4117 3916 -1.03564 0.0221855 0.00732457 1 0 1 1 0 0 +EDGE2 4118 3919 1.02897 -0.00496794 -0.0040421 1 0 1 1 0 0 +EDGE2 4118 3939 1.01778 -0.0726374 0.0285294 1 0 1 1 0 0 +EDGE2 4118 3918 0.065603 0.0508959 0.0277523 1 0 1 1 0 0 +EDGE2 4118 3938 -0.029186 0.00326927 -0.0333323 1 0 1 1 0 0 +EDGE2 4118 3917 -0.976832 -0.0657928 0.0153322 1 0 1 1 0 0 +EDGE2 4118 3937 -0.969646 0.039443 -0.0197021 1 0 1 1 0 0 +EDGE2 4118 4117 -1.01906 -0.0408349 -0.0158634 1 0 1 1 0 0 +EDGE2 4119 3920 1.0036 0.038742 -0.035692 1 0 1 1 0 0 +EDGE2 4119 3940 0.997092 0.00305078 -0.0235855 1 0 1 1 0 0 +EDGE2 4119 4118 -0.92784 -0.0638804 0.00417014 1 0 1 1 0 0 +EDGE2 4119 3919 0.0544408 0.0263783 0.00797729 1 0 1 1 0 0 +EDGE2 4119 3939 -0.099861 0.0183398 0.00339722 1 0 1 1 0 0 +EDGE2 4119 3918 -0.936954 -0.02134 0.00657833 1 0 1 1 0 0 +EDGE2 4119 3938 -0.994788 0.00298067 0.0277094 1 0 1 1 0 0 +EDGE2 4120 4119 -0.987602 0.148527 -0.0189412 1 0 1 1 0 0 +EDGE2 4120 3920 -0.00814967 -0.0145387 0.0228774 1 0 1 1 0 0 +EDGE2 4120 3940 0.0011901 0.0103439 -0.00137466 1 0 1 1 0 0 +EDGE2 4120 3919 -1.01724 0.0138711 0.00319011 1 0 1 1 0 0 +EDGE2 4120 3939 -0.992299 -0.0628677 -0.0253758 1 0 1 1 0 0 +EDGE2 4120 3921 -0.130629 0.990764 1.53939 1 0 1 1 0 0 +EDGE2 4120 3941 -0.00791242 0.948142 1.58671 1 0 1 1 0 0 +EDGE2 4121 4120 -0.918407 0.0829434 -1.55472 1 0 1 1 0 0 +EDGE2 4121 3920 -0.975659 -0.0356779 -1.57953 1 0 1 1 0 0 +EDGE2 4121 3940 -1.002 0.0133064 -1.54433 1 0 1 1 0 0 +EDGE2 4121 3921 -0.0682526 0.0250483 0.0211179 1 0 1 1 0 0 +EDGE2 4121 3941 0.0208161 -0.0525144 -0.0374612 1 0 1 1 0 0 +EDGE2 4121 3922 0.998747 -0.0142712 0.0120211 1 0 1 1 0 0 +EDGE2 4121 3942 0.917664 -0.0148627 -0.00620655 1 0 1 1 0 0 +EDGE2 4122 4121 -1.01515 -0.027416 -0.00638808 1 0 1 1 0 0 +EDGE2 4122 3921 -0.939742 0.115893 -0.0136388 1 0 1 1 0 0 +EDGE2 4122 3941 -0.894299 -0.0398155 0.021096 1 0 1 1 0 0 +EDGE2 4122 3922 -0.023273 0.0078043 -0.00513635 1 0 1 1 0 0 +EDGE2 4122 3942 -0.0631497 -0.0361871 0.0224033 1 0 1 1 0 0 +EDGE2 4122 3923 1.00156 -0.146696 0.00305485 1 0 1 1 0 0 +EDGE2 4122 3943 0.996375 -0.0352877 0.0165089 1 0 1 1 0 0 +EDGE2 4123 4122 -1.01431 0.0354855 -0.0134729 1 0 1 1 0 0 +EDGE2 4123 3922 -1.00708 0.046347 0.0322269 1 0 1 1 0 0 +EDGE2 4123 3942 -0.967699 -0.0484604 0.00232853 1 0 1 1 0 0 +EDGE2 4123 3923 -0.0145323 0.0258493 -0.00371711 1 0 1 1 0 0 +EDGE2 4123 3943 -0.0662434 -0.0201409 0.0173723 1 0 1 1 0 0 +EDGE2 4123 3944 1.08285 -0.115494 0.00925036 1 0 1 1 0 0 +EDGE2 4123 3924 0.985413 0.092669 0.020173 1 0 1 1 0 0 +EDGE2 4124 3923 -0.988112 0.0235406 -0.0102072 1 0 1 1 0 0 +EDGE2 4124 3943 -1.05954 0.0274898 -0.00576512 1 0 1 1 0 0 +EDGE2 4124 4123 -0.957153 -0.00121909 -0.0205244 1 0 1 1 0 0 +EDGE2 4124 3944 0.0334212 0.0858944 -0.00666952 1 0 1 1 0 0 +EDGE2 4124 3924 -0.0568327 0.0637719 -0.0124592 1 0 1 1 0 0 +EDGE2 4124 3905 0.93725 0.0267592 -3.14929 1 0 1 1 0 0 +EDGE2 4124 3945 0.990953 0.0447461 -0.036182 1 0 1 1 0 0 +EDGE2 4124 3925 0.965762 -0.0346691 0.0163248 1 0 1 1 0 0 +EDGE2 4125 3944 -0.972725 -0.00813712 -0.0268846 1 0 1 1 0 0 +EDGE2 4125 4124 -0.910232 0.019337 -0.00313798 1 0 1 1 0 0 +EDGE2 4125 3924 -0.971507 0.0270326 0.00440371 1 0 1 1 0 0 +EDGE2 4125 3905 0.000403655 0.0117402 -3.15827 1 0 1 1 0 0 +EDGE2 4125 3945 -0.0350986 0.0653662 0.00237591 1 0 1 1 0 0 +EDGE2 4125 3925 0.00244238 -0.034575 0.0378693 1 0 1 1 0 0 +EDGE2 4125 3904 1.03802 -0.0486929 -3.1591 1 0 1 1 0 0 +EDGE2 4125 3906 0.00257118 1.04602 1.58063 1 0 1 1 0 0 +EDGE2 4125 3946 0.0606902 0.906175 1.55961 1 0 1 1 0 0 +EDGE2 4125 3926 -0.0285531 0.975355 1.56063 1 0 1 1 0 0 +EDGE2 4126 3905 -1.02846 -0.00439809 -1.59585 1 0 1 1 0 0 +EDGE2 4126 3945 -1.01795 -0.0881445 1.58788 1 0 1 1 0 0 +EDGE2 4126 4125 -0.93565 -0.0195398 1.58119 1 0 1 1 0 0 +EDGE2 4126 3925 -1.14739 0.00171926 1.57812 1 0 1 1 0 0 +EDGE2 4127 4126 -0.96693 0.00394281 -0.0127933 1 0 1 1 0 0 +EDGE2 4128 4127 -0.905832 -0.0629091 -0.00980962 1 0 1 1 0 0 +EDGE2 4129 3890 1.01568 0.0532837 -3.13009 1 0 1 1 0 0 +EDGE2 4129 4128 -1.01573 -0.029943 -0.00750053 1 0 1 1 0 0 +EDGE2 4130 3889 0.963716 0.00842888 -3.12588 1 0 1 1 0 0 +EDGE2 4130 3890 0.0516153 -0.0312562 -3.14751 1 0 1 1 0 0 +EDGE2 4130 3891 0.0132783 1.0815 1.55443 1 0 1 1 0 0 +EDGE2 4130 4129 -1.02024 0.00654547 0.0316458 1 0 1 1 0 0 +EDGE2 4131 3890 -0.934034 0.0192708 1.57678 1 0 1 1 0 0 +EDGE2 4131 4130 -1.11945 0.0516254 -1.56334 1 0 1 1 0 0 +EDGE2 4131 3891 0.00498395 -0.0443542 0.0222243 1 0 1 1 0 0 +EDGE2 4131 3892 0.991239 -0.0541732 -0.0031348 1 0 1 1 0 0 +EDGE2 4132 3891 -1.04826 0.0636185 -0.00948307 1 0 1 1 0 0 +EDGE2 4132 4131 -1.03122 -0.0359121 0.0131646 1 0 1 1 0 0 +EDGE2 4132 3892 -0.00934926 -0.021881 0.0198333 1 0 1 1 0 0 +EDGE2 4132 3893 1.12298 0.0159707 0.0288301 1 0 1 1 0 0 +EDGE2 4133 4132 -1.07668 -0.0533102 -0.00601884 1 0 1 1 0 0 +EDGE2 4133 3892 -1.05325 -0.0497675 0.0153575 1 0 1 1 0 0 +EDGE2 4133 3893 0.00630469 0.0183366 0.00155196 1 0 1 1 0 0 +EDGE2 4133 3894 1.07304 -0.0224075 0.0100253 1 0 1 1 0 0 +EDGE2 4134 4133 -0.894721 0.0416176 -0.000421487 1 0 1 1 0 0 +EDGE2 4134 3893 -0.936748 -0.0853257 0.0051621 1 0 1 1 0 0 +EDGE2 4134 3895 0.950505 0.0779327 -0.0177395 1 0 1 1 0 0 +EDGE2 4134 3894 -0.00966618 0.0211246 -0.0298359 1 0 1 1 0 0 +EDGE2 4135 3895 0.0953121 0.0332539 0.00640426 1 0 1 1 0 0 +EDGE2 4135 3894 -0.927373 0.0418818 -0.000536326 1 0 1 1 0 0 +EDGE2 4135 4134 -1.02445 0.0157466 -0.0131504 1 0 1 1 0 0 +EDGE2 4135 3896 0.0101388 1.06563 1.57233 1 0 1 1 0 0 +EDGE2 4136 3895 -0.963038 -0.0581567 1.55359 1 0 1 1 0 0 +EDGE2 4136 4135 -0.983137 -0.0528055 1.53166 1 0 1 1 0 0 +EDGE2 4137 4136 -1.1101 0.0199707 -0.0069302 1 0 1 1 0 0 +EDGE2 4138 4137 -1.02007 0.0484469 0.0211341 1 0 1 1 0 0 +EDGE2 4139 4138 -1.01895 0.00402353 0.028333 1 0 1 1 0 0 +EDGE2 4140 4139 -1.05112 0.0296683 -0.0127857 1 0 1 1 0 0 +EDGE2 4141 4140 -1.05647 -0.0611069 1.55362 1 0 1 1 0 0 +EDGE2 4142 4141 -0.985053 0.0624826 -0.0156761 1 0 1 1 0 0 +EDGE2 4143 4142 -1.07925 0.0479648 -0.0147174 1 0 1 1 0 0 +EDGE2 4144 3885 0.998622 -0.0100405 -3.10475 1 0 1 1 0 0 +EDGE2 4144 4143 -1.02798 -0.00491448 -0.00515456 1 0 1 1 0 0 +EDGE2 4145 3884 0.979918 0.0504704 -3.11942 1 0 1 1 0 0 +EDGE2 4145 3885 0.0343576 -0.00746943 -3.15204 1 0 1 1 0 0 +EDGE2 4145 3886 0.0457834 -0.951028 -1.5741 1 0 1 1 0 0 +EDGE2 4145 4144 -1.06061 0.0190674 -0.00868189 1 0 1 1 0 0 +EDGE2 4146 3885 -1.05584 0.0911986 -1.52846 1 0 1 1 0 0 +EDGE2 4146 4145 -0.981751 -0.0295127 1.56282 1 0 1 1 0 0 +EDGE2 4146 3886 -0.0572313 0.082151 0.0202417 1 0 1 1 0 0 +EDGE2 4146 3887 0.929844 -0.100377 -0.0261687 1 0 1 1 0 0 +EDGE2 4147 3886 -0.986954 0.00426759 -0.00595541 1 0 1 1 0 0 +EDGE2 4147 4146 -1.0305 -0.0415707 0.0111943 1 0 1 1 0 0 +EDGE2 4147 3887 0.0873756 0.0493473 0.0215052 1 0 1 1 0 0 +EDGE2 4147 3888 1.04878 0.0221319 0.0117625 1 0 1 1 0 0 +EDGE2 4148 3887 -0.97663 -0.0210433 0.00067027 1 0 1 1 0 0 +EDGE2 4148 4147 -0.999213 -0.00611872 0.0159729 1 0 1 1 0 0 +EDGE2 4148 3888 0.0044644 0.0533128 0.0205014 1 0 1 1 0 0 +EDGE2 4148 3889 1.07288 0.00367418 -0.0218315 1 0 1 1 0 0 +EDGE2 4149 3888 -1.04308 -0.0554528 0.00379855 1 0 1 1 0 0 +EDGE2 4149 4148 -0.986065 0.00929315 -0.00773906 1 0 1 1 0 0 +EDGE2 4149 3889 0.0900561 0.0611616 -0.0186695 1 0 1 1 0 0 +EDGE2 4149 3890 0.988355 0.0496931 0.00170208 1 0 1 1 0 0 +EDGE2 4149 4130 0.909211 0.0680237 -3.13616 1 0 1 1 0 0 +EDGE2 4150 4149 -0.935118 -0.0952862 0.00104273 1 0 1 1 0 0 +EDGE2 4150 3889 -0.957433 0.0424368 0.0123642 1 0 1 1 0 0 +EDGE2 4150 3890 -0.0192604 0.0849558 -0.0080601 1 0 1 1 0 0 +EDGE2 4150 4130 -0.11031 -0.0596735 -3.15331 1 0 1 1 0 0 +EDGE2 4150 3891 0.065352 -0.986669 -1.55838 1 0 1 1 0 0 +EDGE2 4150 4131 -0.101059 -0.97538 -1.56581 1 0 1 1 0 0 +EDGE2 4150 4129 1.00205 -0.0336511 -3.10547 1 0 1 1 0 0 +EDGE2 4151 4132 0.946712 -0.0189614 0.0137091 1 0 1 1 0 0 +EDGE2 4151 3890 -1.02046 -0.00079207 1.54734 1 0 1 1 0 0 +EDGE2 4151 4150 -0.931455 -0.0240125 1.56654 1 0 1 1 0 0 +EDGE2 4151 4130 -0.976768 0.0308222 -1.57595 1 0 1 1 0 0 +EDGE2 4151 3891 0.027309 0.0560614 -0.00418258 1 0 1 1 0 0 +EDGE2 4151 4131 -0.0605256 -0.0187911 -0.0123536 1 0 1 1 0 0 +EDGE2 4151 3892 0.837898 -0.077823 0.000900901 1 0 1 1 0 0 +EDGE2 4152 4132 0.0371112 0.121828 -0.0330813 1 0 1 1 0 0 +EDGE2 4152 3891 -0.916386 -0.0639122 -0.0272544 1 0 1 1 0 0 +EDGE2 4152 4131 -1.02509 -0.0523512 0.00259402 1 0 1 1 0 0 +EDGE2 4152 4151 -1.09451 -0.0414791 -0.0276266 1 0 1 1 0 0 +EDGE2 4152 3892 -0.0648271 -0.00625308 -0.0239682 1 0 1 1 0 0 +EDGE2 4152 4133 0.9713 -0.0140933 0.0223836 1 0 1 1 0 0 +EDGE2 4152 3893 1.01049 -0.0497633 0.00591383 1 0 1 1 0 0 +EDGE2 4153 4132 -0.988657 -0.00146608 -0.0154697 1 0 1 1 0 0 +EDGE2 4153 4152 -1.03945 0.0383131 0.014829 1 0 1 1 0 0 +EDGE2 4153 3892 -0.992112 -0.0337428 0.0145901 1 0 1 1 0 0 +EDGE2 4153 4133 0.0266068 -0.0909513 0.00752628 1 0 1 1 0 0 +EDGE2 4153 3893 0.00491511 -0.0475584 0.00456904 1 0 1 1 0 0 +EDGE2 4153 3894 1.00724 0.0368992 -0.0242396 1 0 1 1 0 0 +EDGE2 4153 4134 1.02583 -0.031395 -0.0145526 1 0 1 1 0 0 +EDGE2 4154 4133 -1.07024 0.0284163 0.00162424 1 0 1 1 0 0 +EDGE2 4154 4153 -1.01615 -0.0502946 -0.0152211 1 0 1 1 0 0 +EDGE2 4154 3893 -1.05221 0.0176734 -0.00537634 1 0 1 1 0 0 +EDGE2 4154 3895 1.10454 0.0344745 0.0218122 1 0 1 1 0 0 +EDGE2 4154 3894 -0.0313335 0.049755 -0.030711 1 0 1 1 0 0 +EDGE2 4154 4134 0.0758566 0.0692609 -0.0187904 1 0 1 1 0 0 +EDGE2 4154 4135 0.950976 0.0172189 -0.000520299 1 0 1 1 0 0 +EDGE2 4155 4154 -0.986534 -0.0514038 0.00912259 1 0 1 1 0 0 +EDGE2 4155 4136 -0.0183079 -0.985803 -1.5766 1 0 1 1 0 0 +EDGE2 4155 3895 -0.0016825 -0.0546605 0.046865 1 0 1 1 0 0 +EDGE2 4155 3894 -0.918322 0.043631 -0.00447007 1 0 1 1 0 0 +EDGE2 4155 4134 -1.01608 0.0191843 0.0214576 1 0 1 1 0 0 +EDGE2 4155 4135 -0.0353296 -0.0730666 -0.0104906 1 0 1 1 0 0 +EDGE2 4155 3896 -0.000355749 1.03871 1.56505 1 0 1 1 0 0 +EDGE2 4156 3895 -1.00704 0.0437752 -1.56814 1 0 1 1 0 0 +EDGE2 4156 4155 -0.974549 0.010063 -1.57111 1 0 1 1 0 0 +EDGE2 4156 4135 -1.01424 -0.0529954 -1.56806 1 0 1 1 0 0 +EDGE2 4156 3897 1.01827 -0.0470988 -0.0261816 1 0 1 1 0 0 +EDGE2 4156 3896 -0.00512295 -1.63478e-05 -0.0217876 1 0 1 1 0 0 +EDGE2 4157 4156 -0.974402 0.0227593 0.00180288 1 0 1 1 0 0 +EDGE2 4157 3898 0.988114 -0.0101195 0.0273262 1 0 1 1 0 0 +EDGE2 4157 3897 0.0925065 -0.0136478 -0.0187657 1 0 1 1 0 0 +EDGE2 4157 3896 -0.946425 0.0293544 -0.00129635 1 0 1 1 0 0 +EDGE2 4158 3898 -0.0179206 -0.0327279 -0.0167787 1 0 1 1 0 0 +EDGE2 4158 3897 -1.06076 0.0270956 0.00422691 1 0 1 1 0 0 +EDGE2 4158 4157 -0.977343 0.000101077 0.000498585 1 0 1 1 0 0 +EDGE2 4158 3899 1.0158 -0.053217 -0.00814409 1 0 1 1 0 0 +EDGE2 4159 3898 -0.974348 -0.0525407 -0.00554611 1 0 1 1 0 0 +EDGE2 4159 4158 -1.07197 0.0311425 0.0195292 1 0 1 1 0 0 +EDGE2 4159 3899 -0.0736897 0.0105448 -0.00169651 1 0 1 1 0 0 +EDGE2 4159 3900 0.990347 -0.00482241 0.00286363 1 0 1 1 0 0 +EDGE2 4160 3901 0.0115909 0.974412 1.57704 1 0 1 1 0 0 +EDGE2 4160 3899 -0.964719 -0.0851809 0.0148842 1 0 1 1 0 0 +EDGE2 4160 4159 -0.900478 0.046336 0.00432971 1 0 1 1 0 0 +EDGE2 4160 3900 -0.0926603 0.0108901 0.0266602 1 0 1 1 0 0 +EDGE2 4161 3902 1.04411 -0.0340292 0.0310101 1 0 1 1 0 0 +EDGE2 4161 3901 0.153929 0.097424 0.0145662 1 0 1 1 0 0 +EDGE2 4161 4160 -0.929858 0.0610632 -1.58267 1 0 1 1 0 0 +EDGE2 4161 3900 -0.978478 0.0229603 -1.55459 1 0 1 1 0 0 +EDGE2 4162 3902 0.108088 0.0134195 -0.00231821 1 0 1 1 0 0 +EDGE2 4162 3903 0.991454 0.072153 -0.00820097 1 0 1 1 0 0 +EDGE2 4162 3901 -1.00429 0.0565651 0.00705976 1 0 1 1 0 0 +EDGE2 4162 4161 -1.04771 0.0462715 -5.55403e-05 1 0 1 1 0 0 +EDGE2 4163 3902 -1.12068 0.033226 -0.010488 1 0 1 1 0 0 +EDGE2 4163 4162 -1.03725 0.030614 -0.0111771 1 0 1 1 0 0 +EDGE2 4163 3904 1.0377 0.0261815 -0.00921111 1 0 1 1 0 0 +EDGE2 4163 3903 0.0231889 -0.0373836 -0.0358703 1 0 1 1 0 0 +EDGE2 4164 3905 1.01609 -0.0275783 0.00480168 1 0 1 1 0 0 +EDGE2 4164 3945 1.02935 0.016682 -3.16659 1 0 1 1 0 0 +EDGE2 4164 4125 1.09573 -0.027483 -3.14087 1 0 1 1 0 0 +EDGE2 4164 3925 0.923034 -0.0336688 -3.16259 1 0 1 1 0 0 +EDGE2 4164 4163 -1.08094 -0.0258158 0.00128102 1 0 1 1 0 0 +EDGE2 4164 3904 -0.029415 0.041023 0.0247603 1 0 1 1 0 0 +EDGE2 4164 3903 -0.988242 0.0276233 -0.0136476 1 0 1 1 0 0 +EDGE2 4165 3944 1.06254 -0.03046 -3.14028 1 0 1 1 0 0 +EDGE2 4165 4124 1.03532 0.0757624 -3.12649 1 0 1 1 0 0 +EDGE2 4165 3924 1.00605 0.0142425 -3.14865 1 0 1 1 0 0 +EDGE2 4165 4126 -0.0570626 1.0509 1.57906 1 0 1 1 0 0 +EDGE2 4165 3905 0.0397058 0.0315042 0.015222 1 0 1 1 0 0 +EDGE2 4165 3945 0.0612761 0.047106 -3.12463 1 0 1 1 0 0 +EDGE2 4165 4125 0.0619732 0.034968 -3.14746 1 0 1 1 0 0 +EDGE2 4165 3925 -0.0710425 0.0588218 -3.13446 1 0 1 1 0 0 +EDGE2 4165 3904 -0.9802 -0.0580178 0.0116761 1 0 1 1 0 0 +EDGE2 4165 4164 -1.05546 -0.048149 0.0370436 1 0 1 1 0 0 +EDGE2 4165 3906 -0.00838641 -1.05106 -1.60299 1 0 1 1 0 0 +EDGE2 4165 3946 0.114773 -0.960928 -1.58151 1 0 1 1 0 0 +EDGE2 4165 3926 -0.0311573 -1.01829 -1.62662 1 0 1 1 0 0 +EDGE2 4166 4126 -0.0700594 -0.02317 -0.015427 1 0 1 1 0 0 +EDGE2 4166 4127 1.00991 -0.0329697 -0.0155306 1 0 1 1 0 0 +EDGE2 4166 3905 -1.04143 -0.0205224 -1.58676 1 0 1 1 0 0 +EDGE2 4166 3945 -0.957499 0.0569771 1.56216 1 0 1 1 0 0 +EDGE2 4166 4125 -0.987312 0.0374876 1.57502 1 0 1 1 0 0 +EDGE2 4166 4165 -0.946576 0.0142089 -1.54821 1 0 1 1 0 0 +EDGE2 4166 3925 -0.978564 0.0153698 1.57045 1 0 1 1 0 0 +EDGE2 4167 4128 1.04308 -0.0233885 -0.0518086 1 0 1 1 0 0 +EDGE2 4167 4126 -0.952285 -0.0201368 -0.0136251 1 0 1 1 0 0 +EDGE2 4167 4166 -1.03883 -0.11086 -0.00260378 1 0 1 1 0 0 +EDGE2 4167 4127 -0.0286954 -0.0504276 0.0096339 1 0 1 1 0 0 +EDGE2 4168 4167 -1.01215 -0.00756318 -0.0253047 1 0 1 1 0 0 +EDGE2 4168 4129 0.999347 0.106215 -0.0163851 1 0 1 1 0 0 +EDGE2 4168 4128 -0.015946 -0.0452429 -0.00278872 1 0 1 1 0 0 +EDGE2 4168 4127 -0.919809 -0.0131567 0.00715404 1 0 1 1 0 0 +EDGE2 4169 3890 1.00613 0.0282217 -3.11343 1 0 1 1 0 0 +EDGE2 4169 4150 1.02054 -0.0324843 -3.14281 1 0 1 1 0 0 +EDGE2 4169 4130 1.01617 -0.0292825 0.0127447 1 0 1 1 0 0 +EDGE2 4169 4168 -0.970687 -0.0707948 0.0233302 1 0 1 1 0 0 +EDGE2 4169 4129 -0.0318545 0.0514416 -0.0166069 1 0 1 1 0 0 +EDGE2 4169 4128 -1.02903 0.0255793 -0.00558677 1 0 1 1 0 0 +EDGE2 4170 4149 1.02187 -0.0291135 -3.11639 1 0 1 1 0 0 +EDGE2 4170 3889 0.9788 0.0498501 -3.16886 1 0 1 1 0 0 +EDGE2 4170 3890 -0.0148217 0.00134228 -3.13027 1 0 1 1 0 0 +EDGE2 4170 4150 -0.00371049 0.0327081 -3.13908 1 0 1 1 0 0 +EDGE2 4170 4130 0.0574814 -0.0285286 0.0164216 1 0 1 1 0 0 +EDGE2 4170 3891 -0.0441981 0.935803 1.58437 1 0 1 1 0 0 +EDGE2 4170 4131 -0.00606858 1.02807 1.60343 1 0 1 1 0 0 +EDGE2 4170 4151 0.0804753 1.04234 1.58169 1 0 1 1 0 0 +EDGE2 4170 4129 -1.02309 -0.0605236 -0.00769308 1 0 1 1 0 0 +EDGE2 4170 4169 -1.02102 -0.0197361 0.000786066 1 0 1 1 0 0 +EDGE2 4171 3890 -1.03588 -0.0261032 -1.56018 1 0 1 1 0 0 +EDGE2 4171 4150 -0.976407 0.0434865 -1.56434 1 0 1 1 0 0 +EDGE2 4171 4170 -0.981479 0.00547536 1.56419 1 0 1 1 0 0 +EDGE2 4171 4130 -0.94306 -0.0480101 1.57297 1 0 1 1 0 0 +EDGE2 4172 4171 -1.04798 0.0679009 -0.0261505 1 0 1 1 0 0 +EDGE2 4173 4172 -1.01695 0.033099 0.0115536 1 0 1 1 0 0 +EDGE2 4174 4173 -0.948447 -0.0732368 0.0326292 1 0 1 1 0 0 +EDGE2 4175 4174 -1.00325 0.0440363 -0.0191794 1 0 1 1 0 0 +EDGE2 4176 4175 -0.95694 0.0813928 -1.58258 1 0 1 1 0 0 +EDGE2 4177 4176 -0.973556 -0.0554683 0.00190393 1 0 1 1 0 0 +EDGE2 4178 4177 -1.01576 0.00267268 0.0522009 1 0 1 1 0 0 +EDGE2 4179 3860 1.01608 -0.0426669 -3.14931 1 0 1 1 0 0 +EDGE2 4179 3880 1.05202 -0.00934161 -3.17058 1 0 1 1 0 0 +EDGE2 4179 4178 -1.0498 0.0804029 -0.0107698 1 0 1 1 0 0 +EDGE2 4180 3859 1.07285 -0.0235714 -3.12101 1 0 1 1 0 0 +EDGE2 4180 3879 1.04796 -0.0323626 -3.12581 1 0 1 1 0 0 +EDGE2 4180 3861 -0.0140491 -1.06018 -1.5564 1 0 1 1 0 0 +EDGE2 4180 3860 -0.0142061 0.0071583 -3.14962 1 0 1 1 0 0 +EDGE2 4180 3880 -0.0148525 -0.0167484 -3.14556 1 0 1 1 0 0 +EDGE2 4180 4179 -1.03573 -0.0892952 0.0299221 1 0 1 1 0 0 +EDGE2 4180 3881 0.0252949 0.976926 1.5676 1 0 1 1 0 0 +EDGE2 4181 4180 -1.10054 0.0339505 -1.5665 1 0 1 1 0 0 +EDGE2 4181 3860 -1.03731 0.0191075 1.56546 1 0 1 1 0 0 +EDGE2 4181 3880 -0.937539 -0.0185936 1.59273 1 0 1 1 0 0 +EDGE2 4181 3881 -0.0196114 0.0864509 0.0266194 1 0 1 1 0 0 +EDGE2 4181 3882 0.922487 0.0648359 0.0100647 1 0 1 1 0 0 +EDGE2 4182 4181 -1.07004 -0.0495525 -0.00202286 1 0 1 1 0 0 +EDGE2 4182 3881 -1.17152 -0.0972039 0.00610667 1 0 1 1 0 0 +EDGE2 4182 3882 -0.0191476 -0.0435167 0.00940285 1 0 1 1 0 0 +EDGE2 4182 3883 0.990423 -0.0545163 -0.00486014 1 0 1 1 0 0 +EDGE2 4183 4182 -0.924412 0.018735 -0.0223221 1 0 1 1 0 0 +EDGE2 4183 3882 -0.996326 -0.023755 -0.0241138 1 0 1 1 0 0 +EDGE2 4183 3883 0.0195308 -0.120026 -0.0197089 1 0 1 1 0 0 +EDGE2 4183 3884 0.950562 0.0217996 -0.0313454 1 0 1 1 0 0 +EDGE2 4184 4183 -0.960004 0.010322 -0.00861429 1 0 1 1 0 0 +EDGE2 4184 3883 -1.03474 -0.0262313 -0.0140669 1 0 1 1 0 0 +EDGE2 4184 3884 0.0414072 -0.0730795 -0.0140088 1 0 1 1 0 0 +EDGE2 4184 3885 1.02231 0.0722931 0.0147582 1 0 1 1 0 0 +EDGE2 4184 4145 0.950229 0.0069027 -3.11206 1 0 1 1 0 0 +EDGE2 4185 4184 -1.05701 -0.00633088 2.20966e-05 1 0 1 1 0 0 +EDGE2 4185 3884 -1.0142 -0.0429423 0.0129376 1 0 1 1 0 0 +EDGE2 4185 3885 0.0105934 0.0582916 -0.010708 1 0 1 1 0 0 +EDGE2 4185 4145 -0.0155902 0.0883267 -3.14253 1 0 1 1 0 0 +EDGE2 4185 3886 -0.0183629 0.976995 1.60246 1 0 1 1 0 0 +EDGE2 4185 4146 0.010525 0.937382 1.56943 1 0 1 1 0 0 +EDGE2 4185 4144 0.947282 0.0389514 -3.14247 1 0 1 1 0 0 +EDGE2 4186 3885 -0.987313 -0.0559894 1.55735 1 0 1 1 0 0 +EDGE2 4186 4145 -0.987998 -0.0770208 -1.5531 1 0 1 1 0 0 +EDGE2 4186 4185 -0.999878 -0.00274983 1.55046 1 0 1 1 0 0 +EDGE2 4187 4186 -0.927141 -0.0609145 -0.0172375 1 0 1 1 0 0 +EDGE2 4188 4187 -0.989158 0.00492399 0.0485584 1 0 1 1 0 0 +EDGE2 4189 3850 1.02287 -0.0390866 -3.13665 1 0 1 1 0 0 +EDGE2 4189 4188 -1.03472 0.017113 0.0102098 1 0 1 1 0 0 +EDGE2 4190 3851 -0.0246308 -0.930841 -1.57963 1 0 1 1 0 0 +EDGE2 4190 3849 1.0379 -0.00465849 -3.13714 1 0 1 1 0 0 +EDGE2 4190 3850 0.00171621 0.0167891 -3.18008 1 0 1 1 0 0 +EDGE2 4190 4189 -0.939384 0.0353109 0.0241229 1 0 1 1 0 0 +EDGE2 4191 3850 -0.976856 0.00144078 1.56256 1 0 1 1 0 0 +EDGE2 4191 4190 -1.03239 -0.0543813 -1.60506 1 0 1 1 0 0 +EDGE2 4192 4191 -1.06496 0.0377269 -0.010677 1 0 1 1 0 0 +EDGE2 4193 4192 -1.01687 0.00681068 0.0123907 1 0 1 1 0 0 +EDGE2 4194 4193 -0.980555 0.0455839 -0.0305979 1 0 1 1 0 0 +EDGE2 4195 4194 -1.02428 -0.122311 0.0190054 1 0 1 1 0 0 +EDGE2 4196 4195 -0.990109 0.0258139 -1.56135 1 0 1 1 0 0 +EDGE2 4197 4196 -1.07026 0.00597414 0.00116447 1 0 1 1 0 0 +EDGE2 4198 4197 -0.945215 -0.0321028 -0.0173787 1 0 1 1 0 0 +EDGE2 4199 4140 0.949231 0.00965717 -3.15975 1 0 1 1 0 0 +EDGE2 4199 4198 -0.977869 0.0217637 0.0308496 1 0 1 1 0 0 +EDGE2 4200 4140 -0.0212414 0.0374951 -3.14924 1 0 1 1 0 0 +EDGE2 4200 4141 0.0244608 0.987269 1.56873 1 0 1 1 0 0 +EDGE2 4200 4199 -1.03664 0.0529383 0.0195578 1 0 1 1 0 0 +EDGE2 4200 4139 1.00564 -0.0161871 -3.14403 1 0 1 1 0 0 +EDGE2 4201 4140 -1.02727 0.0704403 1.53463 1 0 1 1 0 0 +EDGE2 4201 4142 1.01376 -0.0546947 0.0135925 1 0 1 1 0 0 +EDGE2 4201 4141 0.0824355 -0.0995063 0.00382348 1 0 1 1 0 0 +EDGE2 4201 4200 -1.04984 0.007841 -1.58342 1 0 1 1 0 0 +EDGE2 4202 4143 0.963927 0.00768136 0.00684154 1 0 1 1 0 0 +EDGE2 4202 4142 0.0593405 -0.00299272 0.00847101 1 0 1 1 0 0 +EDGE2 4202 4141 -0.991941 0.115263 0.0206243 1 0 1 1 0 0 +EDGE2 4202 4201 -0.997097 0.0479488 -0.0110392 1 0 1 1 0 0 +EDGE2 4203 4144 0.975005 0.0614984 0.0113809 1 0 1 1 0 0 +EDGE2 4203 4202 -1.02808 -0.00512222 0.0158466 1 0 1 1 0 0 +EDGE2 4203 4143 0.0877901 -0.0292866 0.0146188 1 0 1 1 0 0 +EDGE2 4203 4142 -0.956198 0.0514342 0.0394289 1 0 1 1 0 0 +EDGE2 4204 3885 0.974475 -0.0644729 -3.17247 1 0 1 1 0 0 +EDGE2 4204 4145 1.04389 -0.0259069 0.000204816 1 0 1 1 0 0 +EDGE2 4204 4185 0.938631 0.0437069 -3.16254 1 0 1 1 0 0 +EDGE2 4204 4144 -0.030609 -0.0660841 -0.00266885 1 0 1 1 0 0 +EDGE2 4204 4143 -0.937921 0.102058 -0.0164822 1 0 1 1 0 0 +EDGE2 4204 4203 -1.12261 0.0772743 -0.0193501 1 0 1 1 0 0 +EDGE2 4205 4186 0.0011562 0.963244 1.57203 1 0 1 1 0 0 +EDGE2 4205 4184 1.06386 0.033671 -3.0882 1 0 1 1 0 0 +EDGE2 4205 3884 0.992665 -0.00818844 -3.19911 1 0 1 1 0 0 +EDGE2 4205 3885 0.00718043 -0.0118082 -3.1576 1 0 1 1 0 0 +EDGE2 4205 4145 -0.120901 0.0521908 0.00987938 1 0 1 1 0 0 +EDGE2 4205 4185 0.101893 -0.056265 -3.1614 1 0 1 1 0 0 +EDGE2 4205 3886 -0.0268062 -0.984805 -1.56685 1 0 1 1 0 0 +EDGE2 4205 4146 -0.0380313 -1.03725 -1.59046 1 0 1 1 0 0 +EDGE2 4205 4144 -0.973413 0.035398 -0.0190588 1 0 1 1 0 0 +EDGE2 4205 4204 -0.953093 -0.0380187 0.00572861 1 0 1 1 0 0 +EDGE2 4206 4205 -0.919937 -0.0283749 1.57664 1 0 1 1 0 0 +EDGE2 4206 3885 -0.979776 0.0112257 -1.59095 1 0 1 1 0 0 +EDGE2 4206 4145 -1.03146 0.0500503 1.56537 1 0 1 1 0 0 +EDGE2 4206 4185 -1.01146 -0.036105 -1.59474 1 0 1 1 0 0 +EDGE2 4206 3886 0.0542354 0.0953013 -0.012918 1 0 1 1 0 0 +EDGE2 4206 4146 0.0954478 -0.0583329 -0.0310819 1 0 1 1 0 0 +EDGE2 4206 3887 1.00257 -0.056055 0.0124702 1 0 1 1 0 0 +EDGE2 4206 4147 1.01251 0.0201147 0.0112617 1 0 1 1 0 0 +EDGE2 4207 3886 -0.978541 -0.0245036 -0.0170663 1 0 1 1 0 0 +EDGE2 4207 4146 -0.959006 0.0271237 0.017076 1 0 1 1 0 0 +EDGE2 4207 4206 -0.896478 0.00735268 -0.0131058 1 0 1 1 0 0 +EDGE2 4207 3887 -0.0230308 -0.075434 0.00380802 1 0 1 1 0 0 +EDGE2 4207 4147 -0.0336433 -0.013812 0.0140927 1 0 1 1 0 0 +EDGE2 4207 3888 1.0668 -0.0122276 -0.0073183 1 0 1 1 0 0 +EDGE2 4207 4148 0.929569 -0.0372867 0.0297794 1 0 1 1 0 0 +EDGE2 4208 3887 -0.976108 0.0278216 -0.0286607 1 0 1 1 0 0 +EDGE2 4208 4147 -0.897342 0.0546969 -0.00424306 1 0 1 1 0 0 +EDGE2 4208 4207 -0.956174 0.0210209 0.0152925 1 0 1 1 0 0 +EDGE2 4208 3888 -0.0782153 -0.00467886 -0.00352688 1 0 1 1 0 0 +EDGE2 4208 4148 -0.0479664 0.030812 0.0440578 1 0 1 1 0 0 +EDGE2 4208 4149 0.922458 -0.0524361 0.0306691 1 0 1 1 0 0 +EDGE2 4208 3889 1.05465 -0.020965 -0.00306649 1 0 1 1 0 0 +EDGE2 4209 3888 -0.910835 0.0128462 -0.0726852 1 0 1 1 0 0 +EDGE2 4209 4148 -0.94827 0.0446989 -0.011166 1 0 1 1 0 0 +EDGE2 4209 4208 -0.91936 0.0174483 0.026606 1 0 1 1 0 0 +EDGE2 4209 4149 -0.0845887 0.0530869 0.00157615 1 0 1 1 0 0 +EDGE2 4209 3889 -0.0628966 -0.00217699 -0.00387515 1 0 1 1 0 0 +EDGE2 4209 3890 0.920898 0.0295418 0.0203927 1 0 1 1 0 0 +EDGE2 4209 4150 1.04491 0.0458477 0.0149903 1 0 1 1 0 0 +EDGE2 4209 4170 1.00036 0.0270619 -3.14559 1 0 1 1 0 0 +EDGE2 4209 4130 0.913595 -0.0476317 -3.14927 1 0 1 1 0 0 +EDGE2 4210 4149 -0.986543 0.0557873 0.0362505 1 0 1 1 0 0 +EDGE2 4210 4209 -1.00839 -0.0167715 -0.0344522 1 0 1 1 0 0 +EDGE2 4210 3889 -0.970173 -0.0838897 -0.0207857 1 0 1 1 0 0 +EDGE2 4210 4171 0.0213239 0.999272 1.58478 1 0 1 1 0 0 +EDGE2 4210 3890 0.112195 -0.0575483 0.010306 1 0 1 1 0 0 +EDGE2 4210 4150 0.0178779 -0.0124951 0.0439095 1 0 1 1 0 0 +EDGE2 4210 4170 0.0477486 0.0148445 -3.11469 1 0 1 1 0 0 +EDGE2 4210 4130 0.0638809 0.020874 -3.13132 1 0 1 1 0 0 +EDGE2 4210 3891 0.0523875 -1.00861 -1.57452 1 0 1 1 0 0 +EDGE2 4210 4131 0.0735095 -1.05005 -1.56036 1 0 1 1 0 0 +EDGE2 4210 4151 0.00464969 -1.01265 -1.53578 1 0 1 1 0 0 +EDGE2 4210 4129 1.11625 0.029742 -3.10473 1 0 1 1 0 0 +EDGE2 4210 4169 0.988778 0.022073 -3.12541 1 0 1 1 0 0 +EDGE2 4211 4172 0.988517 0.0462896 0.00589528 1 0 1 1 0 0 +EDGE2 4211 4171 0.0260655 -0.0297972 -0.00170714 1 0 1 1 0 0 +EDGE2 4211 3890 -1.07078 -0.074861 -1.56239 1 0 1 1 0 0 +EDGE2 4211 4150 -1.06688 0.106693 -1.57397 1 0 1 1 0 0 +EDGE2 4211 4170 -1.0714 -0.0797525 1.5877 1 0 1 1 0 0 +EDGE2 4211 4210 -1.04784 -0.0164545 -1.54821 1 0 1 1 0 0 +EDGE2 4211 4130 -0.984199 0.0286425 1.55448 1 0 1 1 0 0 +EDGE2 4212 4173 0.977214 0.0116656 -0.00743663 1 0 1 1 0 0 +EDGE2 4212 4172 -0.00779749 -0.0445999 0.00385608 1 0 1 1 0 0 +EDGE2 4212 4171 -0.907455 0.00953843 0.000746989 1 0 1 1 0 0 +EDGE2 4212 4211 -1.09644 0.0243434 0.0110713 1 0 1 1 0 0 +EDGE2 4213 4173 -0.0157442 -0.072349 -0.0132405 1 0 1 1 0 0 +EDGE2 4213 4174 0.971641 0.0527023 0.00937577 1 0 1 1 0 0 +EDGE2 4213 4212 -1.01298 0.0241411 -0.0293868 1 0 1 1 0 0 +EDGE2 4213 4172 -0.949748 -0.0054966 0.0123544 1 0 1 1 0 0 +EDGE2 4214 4175 1.03955 -0.00012476 -0.00518928 1 0 1 1 0 0 +EDGE2 4214 4173 -0.990691 -0.00295728 0.0248756 1 0 1 1 0 0 +EDGE2 4214 4174 0.0220011 -0.0809451 0.00233887 1 0 1 1 0 0 +EDGE2 4214 4213 -0.9098 -0.0564386 -0.0101377 1 0 1 1 0 0 +EDGE2 4215 4176 -0.0154141 0.978309 1.6112 1 0 1 1 0 0 +EDGE2 4215 4175 0.0293817 -0.0193293 -0.010728 1 0 1 1 0 0 +EDGE2 4215 4214 -1.01039 0.00163174 0.00824664 1 0 1 1 0 0 +EDGE2 4215 4174 -0.9352 0.0159555 -0.00571072 1 0 1 1 0 0 +EDGE2 4216 4177 0.973196 -0.0314438 0.000970088 1 0 1 1 0 0 +EDGE2 4216 4176 0.0547769 -0.0234288 0.0246078 1 0 1 1 0 0 +EDGE2 4216 4175 -1.09154 0.109965 -1.50943 1 0 1 1 0 0 +EDGE2 4216 4215 -1.08651 -0.0182812 -1.52683 1 0 1 1 0 0 +EDGE2 4217 4178 1.07595 -0.00517812 -0.00315468 1 0 1 1 0 0 +EDGE2 4217 4177 -0.00727682 -0.0144062 -0.00767301 1 0 1 1 0 0 +EDGE2 4217 4176 -1.02797 -0.0164341 -0.0195224 1 0 1 1 0 0 +EDGE2 4217 4216 -1.04946 -0.0119241 -0.0322051 1 0 1 1 0 0 +EDGE2 4218 4178 0.0514249 0.0240368 -0.0072641 1 0 1 1 0 0 +EDGE2 4218 4179 1.00415 0.0341896 -0.00984132 1 0 1 1 0 0 +EDGE2 4218 4177 -1.00422 0.0335982 0.0316446 1 0 1 1 0 0 +EDGE2 4218 4217 -0.912844 -0.0821205 0.0222882 1 0 1 1 0 0 +EDGE2 4219 4180 0.975786 -0.0128571 0.00440136 1 0 1 1 0 0 +EDGE2 4219 3860 1.00057 0.0266071 -3.13243 1 0 1 1 0 0 +EDGE2 4219 3880 0.973682 -0.00580891 -3.11514 1 0 1 1 0 0 +EDGE2 4219 4178 -0.989608 0.0282399 0.0224433 1 0 1 1 0 0 +EDGE2 4219 4179 -0.027387 0.030514 -0.0107894 1 0 1 1 0 0 +EDGE2 4219 4218 -0.973122 -0.0555589 -0.0257895 1 0 1 1 0 0 +EDGE2 4220 4219 -0.990126 -0.00849747 -0.00721221 1 0 1 1 0 0 +EDGE2 4220 3859 1.03933 0.0942277 -3.10186 1 0 1 1 0 0 +EDGE2 4220 3879 1.02301 -0.0214461 -3.15652 1 0 1 1 0 0 +EDGE2 4220 3861 0.0300062 -0.987258 -1.59582 1 0 1 1 0 0 +EDGE2 4220 4180 -0.0615837 -0.0513818 -0.0306694 1 0 1 1 0 0 +EDGE2 4220 3860 0.143092 0.0206208 -3.13273 1 0 1 1 0 0 +EDGE2 4220 3880 -0.000463602 0.0694479 -3.13523 1 0 1 1 0 0 +EDGE2 4220 4179 -0.942531 -0.0183449 0.00875091 1 0 1 1 0 0 +EDGE2 4220 4181 -0.0442192 0.973532 1.56846 1 0 1 1 0 0 +EDGE2 4220 3881 0.0346369 1.00708 1.5671 1 0 1 1 0 0 +EDGE2 4221 4180 -1.04994 0.0193548 -1.56022 1 0 1 1 0 0 +EDGE2 4221 4220 -1.06707 0.0562333 -1.56962 1 0 1 1 0 0 +EDGE2 4221 3860 -0.975098 0.0103461 1.57432 1 0 1 1 0 0 +EDGE2 4221 3880 -0.938033 0.0500371 1.58812 1 0 1 1 0 0 +EDGE2 4221 4182 0.915412 0.0225161 0.0322115 1 0 1 1 0 0 +EDGE2 4221 4181 -0.000890086 0.0880657 0.0151657 1 0 1 1 0 0 +EDGE2 4221 3881 0.0563024 -0.0130507 0.00175821 1 0 1 1 0 0 +EDGE2 4221 3882 1.07593 0.0645998 -0.0125492 1 0 1 1 0 0 +EDGE2 4222 4182 -0.00164096 0.0726698 -0.023508 1 0 1 1 0 0 +EDGE2 4222 4181 -1.02069 -0.00854529 0.00778904 1 0 1 1 0 0 +EDGE2 4222 4221 -1.00895 0.00253313 0.0335438 1 0 1 1 0 0 +EDGE2 4222 3881 -1.0615 -0.0670201 0.0141077 1 0 1 1 0 0 +EDGE2 4222 4183 0.99424 0.0613945 0.0236817 1 0 1 1 0 0 +EDGE2 4222 3882 0.0584211 0.0509874 -0.0156965 1 0 1 1 0 0 +EDGE2 4222 3883 0.965648 0.0535176 -0.0096584 1 0 1 1 0 0 +EDGE2 4223 4182 -1.01064 -0.0141681 -0.0219 1 0 1 1 0 0 +EDGE2 4223 4222 -0.963674 -0.0320425 0.00376982 1 0 1 1 0 0 +EDGE2 4223 4184 1.03956 -0.010711 0.00696017 1 0 1 1 0 0 +EDGE2 4223 4183 -0.0491267 -0.0399442 -0.014115 1 0 1 1 0 0 +EDGE2 4223 3882 -0.867303 0.0131201 -0.0226307 1 0 1 1 0 0 +EDGE2 4223 3883 0.0966783 -0.0276285 -0.016927 1 0 1 1 0 0 +EDGE2 4223 3884 0.953223 -0.0368272 -0.0136247 1 0 1 1 0 0 +EDGE2 4224 4184 0.0918791 0.000857799 0.0073001 1 0 1 1 0 0 +EDGE2 4224 4183 -0.94785 -0.00334706 -0.0093804 1 0 1 1 0 0 +EDGE2 4224 4223 -1.03 -0.0584586 0.00894189 1 0 1 1 0 0 +EDGE2 4224 3883 -1.00979 -0.084941 0.0261609 1 0 1 1 0 0 +EDGE2 4224 4205 0.916607 -0.0331423 -3.15394 1 0 1 1 0 0 +EDGE2 4224 3884 0.0386558 -0.0475216 -0.0570435 1 0 1 1 0 0 +EDGE2 4224 3885 0.910048 -0.0183239 -0.00487222 1 0 1 1 0 0 +EDGE2 4224 4145 1.0832 -0.0281975 -3.13483 1 0 1 1 0 0 +EDGE2 4224 4185 0.955405 0.0550588 0.00591742 1 0 1 1 0 0 +EDGE2 4225 4186 -0.0591375 -0.966447 -1.61519 1 0 1 1 0 0 +EDGE2 4225 4184 -0.990445 0.061786 0.0147659 1 0 1 1 0 0 +EDGE2 4225 4224 -1.06182 -0.00612673 0.00752759 1 0 1 1 0 0 +EDGE2 4225 4205 0.00843055 -0.00739834 -3.16228 1 0 1 1 0 0 +EDGE2 4225 3884 -1.0018 0.0180083 -0.0228864 1 0 1 1 0 0 +EDGE2 4225 3885 -0.0389827 -0.0686374 0.0293483 1 0 1 1 0 0 +EDGE2 4225 4145 -0.0075084 0.0402034 -3.14044 1 0 1 1 0 0 +EDGE2 4225 4185 -0.0136527 0.0869017 -0.00547023 1 0 1 1 0 0 +EDGE2 4225 3886 -0.0283416 1.05931 1.56726 1 0 1 1 0 0 +EDGE2 4225 4146 -0.0112801 1.0347 1.55173 1 0 1 1 0 0 +EDGE2 4225 4206 -0.00637122 1.05095 1.6103 1 0 1 1 0 0 +EDGE2 4225 4144 0.886256 0.0783615 -3.11589 1 0 1 1 0 0 +EDGE2 4225 4204 1.08713 -0.0136419 -3.1526 1 0 1 1 0 0 +EDGE2 4226 4205 -1.04295 -0.0358691 1.56782 1 0 1 1 0 0 +EDGE2 4226 4225 -0.920133 0.0150409 -1.56333 1 0 1 1 0 0 +EDGE2 4226 3885 -1.08207 -0.0204631 -1.59716 1 0 1 1 0 0 +EDGE2 4226 4145 -1.01923 -0.0247553 1.5757 1 0 1 1 0 0 +EDGE2 4226 4185 -0.939292 0.0482859 -1.59906 1 0 1 1 0 0 +EDGE2 4226 3886 -0.0311716 -0.0606288 -0.00181121 1 0 1 1 0 0 +EDGE2 4226 4146 -0.0427943 0.016748 -0.016944 1 0 1 1 0 0 +EDGE2 4226 4206 -0.0154473 -0.0934945 0.00559746 1 0 1 1 0 0 +EDGE2 4226 3887 1.02824 0.0393045 0.0059171 1 0 1 1 0 0 +EDGE2 4226 4147 0.874843 0.115543 0.0108665 1 0 1 1 0 0 +EDGE2 4226 4207 0.912237 -0.00807944 0.000798115 1 0 1 1 0 0 +EDGE2 4227 4226 -1.11079 -0.00362371 -0.00463322 1 0 1 1 0 0 +EDGE2 4227 3886 -1.02673 0.0344165 0.024584 1 0 1 1 0 0 +EDGE2 4227 4146 -1.0678 0.00740629 -0.00288585 1 0 1 1 0 0 +EDGE2 4227 4206 -1.10514 0.0545158 -0.00630033 1 0 1 1 0 0 +EDGE2 4227 3887 -0.0488243 -0.0801839 -0.000921117 1 0 1 1 0 0 +EDGE2 4227 4147 -0.00718428 0.0525117 0.00156862 1 0 1 1 0 0 +EDGE2 4227 4207 0.0236689 -0.0627373 0.000200459 1 0 1 1 0 0 +EDGE2 4227 3888 0.942987 0.0357687 0.0075979 1 0 1 1 0 0 +EDGE2 4227 4148 0.971211 -0.0482597 0.0121092 1 0 1 1 0 0 +EDGE2 4227 4208 0.960272 -0.0632196 0.00344448 1 0 1 1 0 0 +EDGE2 4228 4227 -0.947039 -0.0119089 -0.00894061 1 0 1 1 0 0 +EDGE2 4228 3887 -1.05775 0.0312516 -0.0169465 1 0 1 1 0 0 +EDGE2 4228 4147 -0.954707 0.0221026 0.00582145 1 0 1 1 0 0 +EDGE2 4228 4207 -0.984957 -0.0377782 -0.0132679 1 0 1 1 0 0 +EDGE2 4228 3888 0.0526184 0.0758329 0.0179232 1 0 1 1 0 0 +EDGE2 4228 4148 -0.0113654 0.0263188 -0.0270453 1 0 1 1 0 0 +EDGE2 4228 4208 0.0644835 -0.0288878 0.0384895 1 0 1 1 0 0 +EDGE2 4228 4149 1.05682 0.0587177 0.0123889 1 0 1 1 0 0 +EDGE2 4228 4209 0.945121 -0.0637272 -9.23629e-05 1 0 1 1 0 0 +EDGE2 4228 3889 1.02071 -0.0195711 0.0378111 1 0 1 1 0 0 +EDGE2 4229 4228 -0.914935 -0.00775145 0.0173502 1 0 1 1 0 0 +EDGE2 4229 3888 -1.0469 0.0407293 0.0313693 1 0 1 1 0 0 +EDGE2 4229 4148 -1.0444 0.033026 0.0056718 1 0 1 1 0 0 +EDGE2 4229 4208 -1.06349 0.107895 0.000640857 1 0 1 1 0 0 +EDGE2 4229 4149 0.0277173 0.00185543 0.0162851 1 0 1 1 0 0 +EDGE2 4229 4209 0.0148521 -0.0202354 0.0139375 1 0 1 1 0 0 +EDGE2 4229 3889 0.0712484 0.0369117 0.0108168 1 0 1 1 0 0 +EDGE2 4229 3890 1.01976 0.0588983 -0.00678231 1 0 1 1 0 0 +EDGE2 4229 4150 1.00665 -0.112561 -0.010014 1 0 1 1 0 0 +EDGE2 4229 4170 1.05333 0.0154515 -3.14134 1 0 1 1 0 0 +EDGE2 4229 4210 1.01317 0.0198118 0.00181845 1 0 1 1 0 0 +EDGE2 4229 4130 1.01243 -0.0360181 -3.15045 1 0 1 1 0 0 +EDGE2 4230 4229 -0.958161 0.0516373 -0.000966222 1 0 1 1 0 0 +EDGE2 4230 4149 -1.0052 -0.0209416 0.0341839 1 0 1 1 0 0 +EDGE2 4230 4209 -0.983191 0.00788687 0.00629225 1 0 1 1 0 0 +EDGE2 4230 3889 -0.991698 4.31073e-05 0.00714835 1 0 1 1 0 0 +EDGE2 4230 4171 -0.0303023 1.00631 1.55348 1 0 1 1 0 0 +EDGE2 4230 4211 -0.0047915 0.955708 1.57923 1 0 1 1 0 0 +EDGE2 4230 3890 0.028543 0.0343418 0.00438878 1 0 1 1 0 0 +EDGE2 4230 4150 -0.0352562 0.0998699 -0.00649807 1 0 1 1 0 0 +EDGE2 4230 4170 -0.0226798 0.0555488 -3.15427 1 0 1 1 0 0 +EDGE2 4230 4210 0.0137596 0.080655 0.0383384 1 0 1 1 0 0 +EDGE2 4230 4130 0.0242587 -0.00779146 -3.1354 1 0 1 1 0 0 +EDGE2 4230 3891 0.0675323 -0.96737 -1.59013 1 0 1 1 0 0 +EDGE2 4230 4131 -0.0341828 -0.970288 -1.58781 1 0 1 1 0 0 +EDGE2 4230 4151 -0.0620211 -0.92736 -1.56643 1 0 1 1 0 0 +EDGE2 4230 4129 1.03213 0.00299861 -3.16308 1 0 1 1 0 0 +EDGE2 4230 4169 1.06274 0.0507876 -3.1225 1 0 1 1 0 0 +EDGE2 4231 4230 -1.0796 -0.0310958 -1.5689 1 0 1 1 0 0 +EDGE2 4231 4212 1.04949 -0.0207787 -0.00973521 1 0 1 1 0 0 +EDGE2 4231 4172 0.982541 0.03595 -0.0158282 1 0 1 1 0 0 +EDGE2 4231 4171 0.023711 0.0502839 -0.00291599 1 0 1 1 0 0 +EDGE2 4231 4211 -0.0957718 -0.0494049 0.002031 1 0 1 1 0 0 +EDGE2 4231 3890 -1.00436 0.0974211 -1.57216 1 0 1 1 0 0 +EDGE2 4231 4150 -0.980062 -0.00138805 -1.54524 1 0 1 1 0 0 +EDGE2 4231 4170 -0.972852 -0.00583478 1.55441 1 0 1 1 0 0 +EDGE2 4231 4210 -1.05847 0.00650571 -1.58139 1 0 1 1 0 0 +EDGE2 4231 4130 -0.975651 -0.113406 1.557 1 0 1 1 0 0 +EDGE2 4232 4173 1.04766 0.0832033 -0.0224023 1 0 1 1 0 0 +EDGE2 4232 4213 1.005 -0.0936093 0.00841476 1 0 1 1 0 0 +EDGE2 4232 4212 -0.0212687 -0.0218851 -0.0110363 1 0 1 1 0 0 +EDGE2 4232 4172 -0.0725255 -0.00711853 0.0231826 1 0 1 1 0 0 +EDGE2 4232 4171 -0.976661 -0.0771678 0.0234224 1 0 1 1 0 0 +EDGE2 4232 4211 -0.997053 -0.0551727 0.00520976 1 0 1 1 0 0 +EDGE2 4232 4231 -0.94435 -0.032671 0.0268144 1 0 1 1 0 0 +EDGE2 4233 4173 0.0141302 0.0533748 -0.0240127 1 0 1 1 0 0 +EDGE2 4233 4214 1.03425 -0.0302126 -0.00292399 1 0 1 1 0 0 +EDGE2 4233 4174 1.00956 -0.0802487 0.00700516 1 0 1 1 0 0 +EDGE2 4233 4213 -0.0242739 -0.0158914 0.052608 1 0 1 1 0 0 +EDGE2 4233 4212 -0.922409 0.00115651 -0.0172761 1 0 1 1 0 0 +EDGE2 4233 4232 -1.03031 0.0180984 0.00393415 1 0 1 1 0 0 +EDGE2 4233 4172 -1.01524 -0.0219294 -0.00370989 1 0 1 1 0 0 +EDGE2 4234 4175 1.01021 -0.0508238 -0.0273872 1 0 1 1 0 0 +EDGE2 4234 4215 0.988921 -0.143381 0.0178678 1 0 1 1 0 0 +EDGE2 4234 4173 -0.969535 0.0184371 0.0239603 1 0 1 1 0 0 +EDGE2 4234 4214 -0.0715902 0.0296457 -0.00537304 1 0 1 1 0 0 +EDGE2 4234 4174 0.0973411 -0.0113878 0.00362678 1 0 1 1 0 0 +EDGE2 4234 4213 -0.972588 -0.0217763 0.0136735 1 0 1 1 0 0 +EDGE2 4234 4233 -1.02877 -0.0276854 -0.0203394 1 0 1 1 0 0 +EDGE2 4235 4176 -0.0254112 1.06169 1.58396 1 0 1 1 0 0 +EDGE2 4235 4216 -0.00445409 0.995033 1.57732 1 0 1 1 0 0 +EDGE2 4235 4175 0.00870154 -0.0761109 0.00677979 1 0 1 1 0 0 +EDGE2 4235 4215 -0.0144472 0.00439594 0.00896976 1 0 1 1 0 0 +EDGE2 4235 4214 -1.02635 0.0983879 -0.0183181 1 0 1 1 0 0 +EDGE2 4235 4234 -0.984395 -0.0144185 -0.0200699 1 0 1 1 0 0 +EDGE2 4235 4174 -1.01014 0.0409505 0.0484067 1 0 1 1 0 0 +EDGE2 4236 4175 -1.00548 -0.0174691 1.57451 1 0 1 1 0 0 +EDGE2 4236 4215 -1.00479 -0.0212367 1.60996 1 0 1 1 0 0 +EDGE2 4236 4235 -0.974054 -0.0796152 1.55966 1 0 1 1 0 0 +EDGE2 4237 4236 -0.986463 0.0677101 -0.0237984 1 0 1 1 0 0 +EDGE2 4238 4237 -0.966834 -0.0583637 -0.0330132 1 0 1 1 0 0 +EDGE2 4239 4238 -1.09127 -0.0230386 0.00780906 1 0 1 1 0 0 +EDGE2 4239 4120 1.00497 0.024751 -3.11306 1 0 1 1 0 0 +EDGE2 4239 3920 1.04156 -0.000192203 -3.14566 1 0 1 1 0 0 +EDGE2 4239 3940 0.922209 -0.0604016 -3.09689 1 0 1 1 0 0 +EDGE2 4240 4119 0.974329 -0.125973 -3.12403 1 0 1 1 0 0 +EDGE2 4240 4120 0.0335151 0.0501805 -3.10179 1 0 1 1 0 0 +EDGE2 4240 4239 -1.02401 -0.0401997 -0.0319501 1 0 1 1 0 0 +EDGE2 4240 3920 0.0980778 0.0489414 -3.14213 1 0 1 1 0 0 +EDGE2 4240 3940 -0.035141 -0.0229202 -3.15766 1 0 1 1 0 0 +EDGE2 4240 3919 1.01677 -0.0606854 -3.13138 1 0 1 1 0 0 +EDGE2 4240 3939 0.943891 -0.0280248 -3.13675 1 0 1 1 0 0 +EDGE2 4240 4121 -0.0996223 -0.893065 -1.55587 1 0 1 1 0 0 +EDGE2 4240 3921 0.0564377 -0.912172 -1.592 1 0 1 1 0 0 +EDGE2 4240 3941 0.0187961 -0.931475 -1.56934 1 0 1 1 0 0 +EDGE2 4241 4120 -1.0115 0.0279858 -1.55664 1 0 1 1 0 0 +EDGE2 4241 4240 -0.983227 -0.0312937 1.55315 1 0 1 1 0 0 +EDGE2 4241 3920 -1.00636 0.0188688 -1.55506 1 0 1 1 0 0 +EDGE2 4241 3940 -0.955153 -0.0460612 -1.57395 1 0 1 1 0 0 +EDGE2 4241 4121 -0.0405488 -0.00985145 0.00792655 1 0 1 1 0 0 +EDGE2 4241 4122 1.03856 0.0276847 0.0390431 1 0 1 1 0 0 +EDGE2 4241 3921 -0.0504038 -0.0310791 -0.00835771 1 0 1 1 0 0 +EDGE2 4241 3941 -0.059896 0.0242667 -0.00145698 1 0 1 1 0 0 +EDGE2 4241 3922 0.965809 -0.0259233 0.00280914 1 0 1 1 0 0 +EDGE2 4241 3942 0.919746 0.0890782 0.0108334 1 0 1 1 0 0 +EDGE2 4242 4121 -1.04301 0.0846807 0.00539873 1 0 1 1 0 0 +EDGE2 4242 4241 -1.11462 -0.0333755 -0.0128484 1 0 1 1 0 0 +EDGE2 4242 4122 -0.0591882 -0.0534514 -0.00177844 1 0 1 1 0 0 +EDGE2 4242 3921 -0.975251 0.0984924 -0.00718721 1 0 1 1 0 0 +EDGE2 4242 3941 -1.01425 0.0191984 -0.00194901 1 0 1 1 0 0 +EDGE2 4242 3922 0.0517688 -0.118606 -0.00221145 1 0 1 1 0 0 +EDGE2 4242 3942 -0.0331626 0.0269088 -0.0203571 1 0 1 1 0 0 +EDGE2 4242 3923 0.998698 -0.0489709 0.0175351 1 0 1 1 0 0 +EDGE2 4242 3943 0.955226 -0.0239025 0.00947641 1 0 1 1 0 0 +EDGE2 4242 4123 0.997465 0.0702414 -0.000306614 1 0 1 1 0 0 +EDGE2 4243 4122 -0.983558 0.020601 0.0199132 1 0 1 1 0 0 +EDGE2 4243 4242 -0.965716 -0.0352242 0.000340472 1 0 1 1 0 0 +EDGE2 4243 3922 -0.946749 0.0322208 -0.00258123 1 0 1 1 0 0 +EDGE2 4243 3942 -0.991495 0.0116876 -0.00383502 1 0 1 1 0 0 +EDGE2 4243 3923 -0.0575785 -0.116441 -0.00542355 1 0 1 1 0 0 +EDGE2 4243 3943 0.0399489 -0.0763187 -0.000644173 1 0 1 1 0 0 +EDGE2 4243 4123 0.031179 -0.0349478 0.0166493 1 0 1 1 0 0 +EDGE2 4243 3944 1.09234 -0.0388112 0.00883824 1 0 1 1 0 0 +EDGE2 4243 4124 0.976303 -0.0503726 0.0106422 1 0 1 1 0 0 +EDGE2 4243 3924 1.01054 -0.00406153 0.016118 1 0 1 1 0 0 +EDGE2 4244 4243 -0.901069 -0.0120945 -0.000504979 1 0 1 1 0 0 +EDGE2 4244 3923 -1.0297 0.0258616 -0.0452401 1 0 1 1 0 0 +EDGE2 4244 3943 -0.967237 0.0141635 -0.0362177 1 0 1 1 0 0 +EDGE2 4244 4123 -0.938427 -0.0614396 -0.0213042 1 0 1 1 0 0 +EDGE2 4244 3944 -0.0496903 0.00712398 0.0270236 1 0 1 1 0 0 +EDGE2 4244 4124 0.0362614 -0.0378195 -0.0313098 1 0 1 1 0 0 +EDGE2 4244 3924 -0.0270286 0.0105644 -0.00184739 1 0 1 1 0 0 +EDGE2 4244 3905 1.02899 -0.0469 -3.13414 1 0 1 1 0 0 +EDGE2 4244 3945 1.05382 -0.0217059 0.00138603 1 0 1 1 0 0 +EDGE2 4244 4125 1.00225 0.0352139 0.00210881 1 0 1 1 0 0 +EDGE2 4244 4165 0.954933 -0.078117 -3.13138 1 0 1 1 0 0 +EDGE2 4244 3925 0.917237 -0.00772406 0.0058198 1 0 1 1 0 0 +EDGE2 4245 4244 -0.916671 0.0329139 0.000289075 1 0 1 1 0 0 +EDGE2 4245 3944 -1.04523 -0.0430981 -0.00635152 1 0 1 1 0 0 +EDGE2 4245 4124 -1.03353 -0.0438273 -0.0152712 1 0 1 1 0 0 +EDGE2 4245 3924 -1.05566 0.0841309 0.00998397 1 0 1 1 0 0 +EDGE2 4245 4126 -0.0254172 -0.961543 -1.58221 1 0 1 1 0 0 +EDGE2 4245 4166 0.0577137 -0.969906 -1.57669 1 0 1 1 0 0 +EDGE2 4245 3905 0.0297919 0.0348664 -3.1434 1 0 1 1 0 0 +EDGE2 4245 3945 0.0183287 0.0587755 0.0530124 1 0 1 1 0 0 +EDGE2 4245 4125 -0.0585091 -0.00538745 -0.00808284 1 0 1 1 0 0 +EDGE2 4245 4165 0.0718404 -0.0173348 -3.1423 1 0 1 1 0 0 +EDGE2 4245 3925 0.118302 0.0433426 -0.015434 1 0 1 1 0 0 +EDGE2 4245 3904 1.03773 0.105121 -3.14245 1 0 1 1 0 0 +EDGE2 4245 4164 0.99906 -0.0712981 -3.14406 1 0 1 1 0 0 +EDGE2 4245 3906 0.0231108 1.03735 1.58559 1 0 1 1 0 0 +EDGE2 4245 3946 0.0308229 1.01514 1.55957 1 0 1 1 0 0 +EDGE2 4245 3926 0.00201441 0.983207 1.56002 1 0 1 1 0 0 +EDGE2 4246 4245 -0.86406 -0.05628 -1.57485 1 0 1 1 0 0 +EDGE2 4246 3905 -0.989642 0.090483 1.57808 1 0 1 1 0 0 +EDGE2 4246 3945 -1.07356 0.0328384 -1.55301 1 0 1 1 0 0 +EDGE2 4246 4125 -0.989769 -0.0374255 -1.55857 1 0 1 1 0 0 +EDGE2 4246 4165 -1.05301 0.00763428 1.57898 1 0 1 1 0 0 +EDGE2 4246 3925 -1.00432 0.028676 -1.55372 1 0 1 1 0 0 +EDGE2 4246 3907 0.977559 0.119291 -0.0260652 1 0 1 1 0 0 +EDGE2 4246 3906 -0.0088112 -0.0206427 0.00535773 1 0 1 1 0 0 +EDGE2 4246 3946 -0.0304457 -0.0700372 0.00827053 1 0 1 1 0 0 +EDGE2 4246 3926 0.0470403 -0.000378432 0.0102119 1 0 1 1 0 0 +EDGE2 4246 3947 0.937831 0.111095 -0.0112588 1 0 1 1 0 0 +EDGE2 4246 3927 0.994962 -0.0763242 -0.00270074 1 0 1 1 0 0 +EDGE2 4247 3907 -0.0919173 -0.00625733 0.00514963 1 0 1 1 0 0 +EDGE2 4247 3906 -1.01307 -0.0436387 -0.00890325 1 0 1 1 0 0 +EDGE2 4247 3946 -0.975763 0.0675271 -0.0306081 1 0 1 1 0 0 +EDGE2 4247 4246 -0.946036 -0.0617216 -0.00283572 1 0 1 1 0 0 +EDGE2 4247 3926 -0.987354 -0.100824 -0.0124891 1 0 1 1 0 0 +EDGE2 4247 3947 0.0660824 -0.0711859 -0.00758499 1 0 1 1 0 0 +EDGE2 4247 3927 0.0277019 -0.0638001 -0.031149 1 0 1 1 0 0 +EDGE2 4247 3908 0.984754 -0.0219298 0.0310314 1 0 1 1 0 0 +EDGE2 4247 3948 1.02253 -0.023603 0.0186232 1 0 1 1 0 0 +EDGE2 4247 3928 0.994958 0.00293503 -0.0285642 1 0 1 1 0 0 +EDGE2 4248 3929 0.9854 -0.0543755 0.00470222 1 0 1 1 0 0 +EDGE2 4248 3907 -1.02993 -0.094078 -0.00225715 1 0 1 1 0 0 +EDGE2 4248 3947 -0.98006 0.0500232 -0.00376449 1 0 1 1 0 0 +EDGE2 4248 4247 -0.999861 -0.0398795 0.0198048 1 0 1 1 0 0 +EDGE2 4248 3927 -0.962394 0.0238052 0.0133633 1 0 1 1 0 0 +EDGE2 4248 3908 0.033904 -0.103764 0.0112165 1 0 1 1 0 0 +EDGE2 4248 3948 -0.0750186 -0.206498 0.028148 1 0 1 1 0 0 +EDGE2 4248 3928 -0.0565385 -0.0390113 -0.036484 1 0 1 1 0 0 +EDGE2 4248 3949 0.910096 0.0579502 0.0247889 1 0 1 1 0 0 +EDGE2 4248 3909 0.970318 0.038237 -0.0162776 1 0 1 1 0 0 +EDGE2 4249 3929 -0.0440983 0.131526 -0.00128348 1 0 1 1 0 0 +EDGE2 4249 3908 -0.923625 0.023974 0.0257689 1 0 1 1 0 0 +EDGE2 4249 3948 -0.804311 0.000727643 0.00774982 1 0 1 1 0 0 +EDGE2 4249 4248 -0.972353 -0.00981529 -0.00120165 1 0 1 1 0 0 +EDGE2 4249 3928 -1.02932 -0.0465066 0.00303309 1 0 1 1 0 0 +EDGE2 4249 3949 -0.0259111 0.0431847 0.026303 1 0 1 1 0 0 +EDGE2 4249 3970 0.954265 -0.0445994 -3.12458 1 0 1 1 0 0 +EDGE2 4249 3909 0.0129832 0.0228007 0.00932785 1 0 1 1 0 0 +EDGE2 4249 4110 0.982856 0.0200937 -3.15615 1 0 1 1 0 0 +EDGE2 4249 3910 0.952809 -0.0344918 0.0270882 1 0 1 1 0 0 +EDGE2 4249 3930 0.953813 -0.0498232 0.0286923 1 0 1 1 0 0 +EDGE2 4249 3950 1.01804 0.0363168 -0.00896165 1 0 1 1 0 0 +EDGE2 4250 3971 0.0341643 0.970644 1.55283 1 0 1 1 0 0 +EDGE2 4250 4111 -0.0558405 1.01819 1.5683 1 0 1 1 0 0 +EDGE2 4250 3911 0.0184587 1.03754 1.61412 1 0 1 1 0 0 +EDGE2 4250 3931 -0.0274844 0.938452 1.61341 1 0 1 1 0 0 +EDGE2 4250 3929 -0.988675 0.00576758 0.00483566 1 0 1 1 0 0 +EDGE2 4250 4249 -0.964128 0.0283508 0.0217974 1 0 1 1 0 0 +EDGE2 4250 3949 -1.00558 -0.0389253 -0.00245876 1 0 1 1 0 0 +EDGE2 4250 3969 0.975911 -0.00466094 -3.14825 1 0 1 1 0 0 +EDGE2 4250 3970 -0.00545756 0.0112092 -3.15193 1 0 1 1 0 0 +EDGE2 4250 3909 -1.06152 -0.00559662 0.0348398 1 0 1 1 0 0 +EDGE2 4250 4110 -0.00390871 0.00695184 -3.12353 1 0 1 1 0 0 +EDGE2 4250 3910 0.0450757 -0.0513103 0.0119483 1 0 1 1 0 0 +EDGE2 4250 3930 -0.0293169 -0.0284708 0.000609074 1 0 1 1 0 0 +EDGE2 4250 3950 0.00800857 -0.00195405 -0.0108429 1 0 1 1 0 0 +EDGE2 4250 4109 1.06363 -0.0624006 -3.12772 1 0 1 1 0 0 +EDGE2 4250 3951 -0.0570929 -1.04357 -1.60547 1 0 1 1 0 0 +EDGE2 4251 3971 0.0102855 -0.0427343 0.0036029 1 0 1 1 0 0 +EDGE2 4251 3932 0.985657 -0.0154686 -0.00448303 1 0 1 1 0 0 +EDGE2 4251 4112 1.01115 -0.0265736 -0.0138555 1 0 1 1 0 0 +EDGE2 4251 3972 0.967603 0.0469595 0.00192589 1 0 1 1 0 0 +EDGE2 4251 3912 1.00825 0.0187224 -0.0168567 1 0 1 1 0 0 +EDGE2 4251 4111 -0.00739929 0.0680853 0.0612968 1 0 1 1 0 0 +EDGE2 4251 3911 0.110154 -0.0156712 -0.000889058 1 0 1 1 0 0 +EDGE2 4251 3931 0.00813678 -0.0842685 0.0226122 1 0 1 1 0 0 +EDGE2 4251 3970 -0.967022 -0.0557813 1.58167 1 0 1 1 0 0 +EDGE2 4251 4250 -0.969064 0.00787773 -1.54118 1 0 1 1 0 0 +EDGE2 4251 4110 -0.941793 -0.0158256 1.55952 1 0 1 1 0 0 +EDGE2 4251 3910 -0.991321 0.0720447 -1.56291 1 0 1 1 0 0 +EDGE2 4251 3930 -0.998038 0.0111711 -1.58579 1 0 1 1 0 0 +EDGE2 4251 3950 -0.964178 0.0894637 -1.55299 1 0 1 1 0 0 +EDGE2 4252 3971 -1.06896 0.020642 -0.0485529 1 0 1 1 0 0 +EDGE2 4252 3913 1.0211 -0.0607034 -0.00313156 1 0 1 1 0 0 +EDGE2 4252 3973 0.881795 -0.0264641 -0.00354749 1 0 1 1 0 0 +EDGE2 4252 4113 1.02466 -0.0156039 -0.0164847 1 0 1 1 0 0 +EDGE2 4252 3933 1.01676 0.158963 0.000963174 1 0 1 1 0 0 +EDGE2 4252 3932 0.0210663 -0.0239373 -0.0182317 1 0 1 1 0 0 +EDGE2 4252 4112 0.0232066 0.0202514 0.00459101 1 0 1 1 0 0 +EDGE2 4252 3972 -0.0176358 0.0313402 0.027301 1 0 1 1 0 0 +EDGE2 4252 4251 -0.943612 -0.0993104 -0.0321041 1 0 1 1 0 0 +EDGE2 4252 3912 0.034208 -0.0514478 -0.030146 1 0 1 1 0 0 +EDGE2 4252 4111 -0.980549 0.0706444 -0.0059288 1 0 1 1 0 0 +EDGE2 4252 3911 -1.05801 0.0776204 0.00410919 1 0 1 1 0 0 +EDGE2 4252 3931 -0.989182 0.0602319 0.00964777 1 0 1 1 0 0 +EDGE2 4253 3913 0.0855734 0.0489907 0.00883557 1 0 1 1 0 0 +EDGE2 4253 3934 1.0132 -0.0169788 0.011813 1 0 1 1 0 0 +EDGE2 4253 3974 1.03081 -0.0998264 0.0154935 1 0 1 1 0 0 +EDGE2 4253 4114 0.911545 0.00366732 0.0207602 1 0 1 1 0 0 +EDGE2 4253 3914 0.997647 -0.0255637 0.0148109 1 0 1 1 0 0 +EDGE2 4253 3973 -0.000595981 0.0427551 0.0130739 1 0 1 1 0 0 +EDGE2 4253 4113 -0.101036 0.0432491 0.0216089 1 0 1 1 0 0 +EDGE2 4253 3933 0.0150386 0.0243745 -0.00988561 1 0 1 1 0 0 +EDGE2 4253 3932 -0.999544 0.0736198 0.0165307 1 0 1 1 0 0 +EDGE2 4253 4112 -1.09259 0.0480167 0.00511374 1 0 1 1 0 0 +EDGE2 4253 4252 -1.06794 0.0417864 -0.0261622 1 0 1 1 0 0 +EDGE2 4253 3972 -1.03239 -0.0290995 -0.0185196 1 0 1 1 0 0 +EDGE2 4253 3912 -0.939395 0.0446315 -0.01638 1 0 1 1 0 0 +EDGE2 4254 4015 1.10802 -0.0117894 -3.13362 1 0 1 1 0 0 +EDGE2 4254 4115 0.992753 -0.00396039 -0.00282437 1 0 1 1 0 0 +EDGE2 4254 3935 0.955002 -0.0145432 0.029392 1 0 1 1 0 0 +EDGE2 4254 3975 0.971328 -0.0486986 -0.00485651 1 0 1 1 0 0 +EDGE2 4254 3995 1.03272 0.049969 -3.17032 1 0 1 1 0 0 +EDGE2 4254 3915 0.932721 -0.0111753 -0.0170287 1 0 1 1 0 0 +EDGE2 4254 3913 -1.01343 0.020945 0.0546001 1 0 1 1 0 0 +EDGE2 4254 3934 0.028029 0.0621192 -0.00729877 1 0 1 1 0 0 +EDGE2 4254 3974 0.0651781 -0.0124107 -0.0408154 1 0 1 1 0 0 +EDGE2 4254 4114 0.118068 -0.0671521 -0.00998177 1 0 1 1 0 0 +EDGE2 4254 3914 0.0175138 0.0226961 0.00927474 1 0 1 1 0 0 +EDGE2 4254 3973 -1.04142 -0.0850848 -0.0336508 1 0 1 1 0 0 +EDGE2 4254 4113 -0.913853 -0.00651951 -0.0310592 1 0 1 1 0 0 +EDGE2 4254 4253 -0.949619 0.0237813 0.00545657 1 0 1 1 0 0 +EDGE2 4254 3933 -0.998615 -0.0350258 -0.000520498 1 0 1 1 0 0 +EDGE2 4255 3936 0.0294482 0.9864 1.54771 1 0 1 1 0 0 +EDGE2 4255 4116 -0.0184574 0.959934 1.56061 1 0 1 1 0 0 +EDGE2 4255 3916 -0.113886 0.959505 1.5955 1 0 1 1 0 0 +EDGE2 4255 4015 -0.0136727 0.0454076 -3.13721 1 0 1 1 0 0 +EDGE2 4255 4014 1.05189 0.0216972 -3.10382 1 0 1 1 0 0 +EDGE2 4255 3994 0.980025 0.0726579 -3.12701 1 0 1 1 0 0 +EDGE2 4255 4115 -0.00914406 -0.035153 0.00462263 1 0 1 1 0 0 +EDGE2 4255 4016 0.0244846 -1.01858 -1.55776 1 0 1 1 0 0 +EDGE2 4255 3935 0.113758 0.0531496 0.0130522 1 0 1 1 0 0 +EDGE2 4255 3975 0.0417316 0.0225581 0.0471111 1 0 1 1 0 0 +EDGE2 4255 3995 0.0679121 -0.0289697 -3.12823 1 0 1 1 0 0 +EDGE2 4255 3915 -0.0723988 -0.0632506 0.00691116 1 0 1 1 0 0 +EDGE2 4255 3976 0.0182573 -1.01474 -1.56967 1 0 1 1 0 0 +EDGE2 4255 3996 -0.04088 -0.992319 -1.55844 1 0 1 1 0 0 +EDGE2 4255 4254 -1.02797 -0.0145191 0.0270737 1 0 1 1 0 0 +EDGE2 4255 3934 -0.991401 -0.0200168 0.0107623 1 0 1 1 0 0 +EDGE2 4255 3974 -1.03786 -0.0426295 0.000817373 1 0 1 1 0 0 +EDGE2 4255 4114 -1.04303 0.00119154 0.0252607 1 0 1 1 0 0 +EDGE2 4255 3914 -1.03627 0.000503622 0.0138557 1 0 1 1 0 0 +EDGE2 4256 3917 0.990323 0.0464035 0.0122629 1 0 1 1 0 0 +EDGE2 4256 3937 0.983409 0.00595255 -0.0110679 1 0 1 1 0 0 +EDGE2 4256 4117 1.03748 0.0670878 0.0244811 1 0 1 1 0 0 +EDGE2 4256 3936 0.0116858 0.0490512 0.0234028 1 0 1 1 0 0 +EDGE2 4256 4116 -0.0978822 -0.127183 -0.0157518 1 0 1 1 0 0 +EDGE2 4256 3916 0.00526491 -0.00960401 -0.0212894 1 0 1 1 0 0 +EDGE2 4256 4015 -1.01124 -0.0400593 1.54739 1 0 1 1 0 0 +EDGE2 4256 4255 -1.04158 0.049562 -1.56704 1 0 1 1 0 0 +EDGE2 4256 4115 -0.97321 0.0084089 -1.55878 1 0 1 1 0 0 +EDGE2 4256 3935 -1.04081 -0.0302675 -1.59666 1 0 1 1 0 0 +EDGE2 4256 3975 -1.04854 -0.0784812 -1.55528 1 0 1 1 0 0 +EDGE2 4256 3995 -0.929599 0.0249161 1.56597 1 0 1 1 0 0 +EDGE2 4256 3915 -0.981243 -0.01895 -1.59328 1 0 1 1 0 0 +EDGE2 4257 4118 1.08946 -0.040521 0.0136198 1 0 1 1 0 0 +EDGE2 4257 3918 0.967422 -0.0017142 -0.00768938 1 0 1 1 0 0 +EDGE2 4257 3938 0.98437 -0.031992 0.0143334 1 0 1 1 0 0 +EDGE2 4257 4256 -0.960471 -0.0523297 -0.00118439 1 0 1 1 0 0 +EDGE2 4257 3917 0.0668885 0.0331991 0.0228589 1 0 1 1 0 0 +EDGE2 4257 3937 0.0124532 0.0100685 -0.00964179 1 0 1 1 0 0 +EDGE2 4257 4117 -0.0437529 -0.0431272 0.0137367 1 0 1 1 0 0 +EDGE2 4257 3936 -0.974242 -0.0272575 -0.00250628 1 0 1 1 0 0 +EDGE2 4257 4116 -0.991622 0.0521371 0.000783273 1 0 1 1 0 0 +EDGE2 4257 3916 -1.01263 0.00945508 0.0150486 1 0 1 1 0 0 +EDGE2 4258 4119 1.01537 0.0207098 0.00251638 1 0 1 1 0 0 +EDGE2 4258 4257 -1.05859 -0.00851431 -0.0231804 1 0 1 1 0 0 +EDGE2 4258 4118 -0.0434446 0.0864264 0.015965 1 0 1 1 0 0 +EDGE2 4258 3919 1.02204 -0.0111497 -0.0106177 1 0 1 1 0 0 +EDGE2 4258 3939 0.971729 0.0277701 0.0125016 1 0 1 1 0 0 +EDGE2 4258 3918 0.00486906 0.0489487 -0.0309663 1 0 1 1 0 0 +EDGE2 4258 3938 0.0305005 0.0476223 0.0353415 1 0 1 1 0 0 +EDGE2 4258 3917 -1.00609 -0.021658 -0.0112366 1 0 1 1 0 0 +EDGE2 4258 3937 -1.04458 0.0147705 0.0151507 1 0 1 1 0 0 +EDGE2 4258 4117 -0.940014 -0.06646 0.00101004 1 0 1 1 0 0 +EDGE2 4259 4119 0.129236 -0.037335 0.0189505 1 0 1 1 0 0 +EDGE2 4259 4120 1.02323 0.00886382 0.000777834 1 0 1 1 0 0 +EDGE2 4259 4240 0.95638 0.0144846 -3.13396 1 0 1 1 0 0 +EDGE2 4259 3920 1.00094 0.086024 0.0109329 1 0 1 1 0 0 +EDGE2 4259 3940 1.05301 0.0651662 -0.0162112 1 0 1 1 0 0 +EDGE2 4259 4118 -1.01246 -0.0339968 -0.00441399 1 0 1 1 0 0 +EDGE2 4259 3919 -0.0499106 -0.0286258 0.0257939 1 0 1 1 0 0 +EDGE2 4259 3939 0.0570678 -0.0199336 0.0303779 1 0 1 1 0 0 +EDGE2 4259 4258 -1.02012 0.00697499 -0.00338191 1 0 1 1 0 0 +EDGE2 4259 3918 -0.978191 0.00508377 -0.00972028 1 0 1 1 0 0 +EDGE2 4259 3938 -0.96761 0.0303875 -0.00975843 1 0 1 1 0 0 +EDGE2 4260 4119 -0.879795 -0.0392594 0.0235262 1 0 1 1 0 0 +EDGE2 4260 4120 0.000795933 0.0238828 0.00555928 1 0 1 1 0 0 +EDGE2 4260 4239 1.06076 0.0356211 -3.13466 1 0 1 1 0 0 +EDGE2 4260 4240 0.0561351 0.0423755 -3.16713 1 0 1 1 0 0 +EDGE2 4260 3920 -0.0369269 0.0629595 -0.0281686 1 0 1 1 0 0 +EDGE2 4260 3940 -0.0315455 0.0474666 0.0129486 1 0 1 1 0 0 +EDGE2 4260 4259 -1.00713 0.0476806 0.0025777 1 0 1 1 0 0 +EDGE2 4260 3919 -0.999185 0.071324 0.0355132 1 0 1 1 0 0 +EDGE2 4260 3939 -0.934663 -0.10957 -0.00160973 1 0 1 1 0 0 +EDGE2 4260 4121 0.0513401 1.09939 1.56666 1 0 1 1 0 0 +EDGE2 4260 4241 0.0356445 1.048 1.56533 1 0 1 1 0 0 +EDGE2 4260 3921 0.0237558 0.939763 1.59544 1 0 1 1 0 0 +EDGE2 4260 3941 -0.0481347 0.942633 1.55915 1 0 1 1 0 0 +EDGE2 4261 4120 -1.04171 -0.0135868 -1.57953 1 0 1 1 0 0 +EDGE2 4261 4260 -1.01704 0.00040067 -1.58535 1 0 1 1 0 0 +EDGE2 4261 4240 -0.906029 -0.0432978 1.57252 1 0 1 1 0 0 +EDGE2 4261 3920 -0.987998 -0.00380093 -1.55715 1 0 1 1 0 0 +EDGE2 4261 3940 -0.972286 0.0140626 -1.59687 1 0 1 1 0 0 +EDGE2 4261 4121 -0.0173055 -0.01276 0.00725014 1 0 1 1 0 0 +EDGE2 4261 4241 -0.0155906 0.0855519 0.0115844 1 0 1 1 0 0 +EDGE2 4261 4122 0.956486 0.0238314 -0.0229365 1 0 1 1 0 0 +EDGE2 4261 3921 -0.0557519 0.0282643 -0.0334559 1 0 1 1 0 0 +EDGE2 4261 3941 -0.0198509 -0.0415473 0.0330756 1 0 1 1 0 0 +EDGE2 4261 4242 1.02234 -0.0592987 0.0222403 1 0 1 1 0 0 +EDGE2 4261 3922 0.95398 -0.0611585 -0.02943 1 0 1 1 0 0 +EDGE2 4261 3942 0.96456 -0.0260308 0.015316 1 0 1 1 0 0 +EDGE2 4262 4121 -1.00911 0.0636058 0.000291735 1 0 1 1 0 0 +EDGE2 4262 4261 -0.963843 0.0367111 0.00598741 1 0 1 1 0 0 +EDGE2 4262 4241 -0.992931 0.0210673 -0.0339083 1 0 1 1 0 0 +EDGE2 4262 4243 1.01086 -0.0355239 0.000171207 1 0 1 1 0 0 +EDGE2 4262 4122 -0.00218586 -0.0466157 0.00847265 1 0 1 1 0 0 +EDGE2 4262 3921 -1.05383 -0.0199747 -0.0214124 1 0 1 1 0 0 +EDGE2 4262 3941 -0.944164 0.0427633 -0.0179784 1 0 1 1 0 0 +EDGE2 4262 4242 0.0586851 0.0854097 -0.00580099 1 0 1 1 0 0 +EDGE2 4262 3922 0.013595 -0.0282038 -0.0297843 1 0 1 1 0 0 +EDGE2 4262 3942 -0.00795321 0.0653147 0.0100789 1 0 1 1 0 0 +EDGE2 4262 3923 0.97903 -0.00492626 0.0266912 1 0 1 1 0 0 +EDGE2 4262 3943 1.11354 0.0278527 0.00485159 1 0 1 1 0 0 +EDGE2 4262 4123 1.01175 -0.0143037 -0.0108846 1 0 1 1 0 0 +EDGE2 4263 4243 0.0636032 0.042465 -0.00671982 1 0 1 1 0 0 +EDGE2 4263 4122 -1.00917 -0.0299916 -0.0235803 1 0 1 1 0 0 +EDGE2 4263 4262 -0.938565 -0.0397905 -0.0213288 1 0 1 1 0 0 +EDGE2 4263 4242 -1.03182 -0.0693896 -0.0160683 1 0 1 1 0 0 +EDGE2 4263 3922 -0.947228 0.0611755 -0.0135916 1 0 1 1 0 0 +EDGE2 4263 3942 -1.02418 0.143997 -0.033062 1 0 1 1 0 0 +EDGE2 4263 4244 0.952049 0.0218612 -0.0351248 1 0 1 1 0 0 +EDGE2 4263 3923 -0.0156234 0.122057 0.0240468 1 0 1 1 0 0 +EDGE2 4263 3943 -0.0588895 -0.0134631 -0.0114316 1 0 1 1 0 0 +EDGE2 4263 4123 -0.0287753 0.0191589 0.0348939 1 0 1 1 0 0 +EDGE2 4263 3944 1.02313 0.00226251 -0.0034472 1 0 1 1 0 0 +EDGE2 4263 4124 1.00703 -0.03088 0.034976 1 0 1 1 0 0 +EDGE2 4263 3924 1.03047 0.0419712 0.0180269 1 0 1 1 0 0 +EDGE2 4264 4243 -1.09066 -0.0128569 0.0419629 1 0 1 1 0 0 +EDGE2 4264 4263 -1.02327 -0.0475853 0.0237979 1 0 1 1 0 0 +EDGE2 4264 4244 0.0120776 -0.0377792 0.040751 1 0 1 1 0 0 +EDGE2 4264 3923 -1.07512 0.036732 -0.0207408 1 0 1 1 0 0 +EDGE2 4264 3943 -1.09672 -0.0656874 0.0179052 1 0 1 1 0 0 +EDGE2 4264 4123 -0.98749 -0.0403606 -0.0144208 1 0 1 1 0 0 +EDGE2 4264 3944 0.0107109 0.0255888 -0.00771955 1 0 1 1 0 0 +EDGE2 4264 4124 0.0265615 0.0621243 0.00459337 1 0 1 1 0 0 +EDGE2 4264 3924 -0.0320099 -0.0707647 0.00667382 1 0 1 1 0 0 +EDGE2 4264 4245 1.04174 -0.0349352 0.000774512 1 0 1 1 0 0 +EDGE2 4264 3905 1.05291 0.0417242 -3.10876 1 0 1 1 0 0 +EDGE2 4264 3945 0.969086 0.0120226 -0.00631436 1 0 1 1 0 0 +EDGE2 4264 4125 0.942122 0.0156554 0.00262202 1 0 1 1 0 0 +EDGE2 4264 4165 1.01464 -0.071185 -3.155 1 0 1 1 0 0 +EDGE2 4264 3925 0.952283 0.000712327 -0.00983929 1 0 1 1 0 0 +EDGE2 4265 4244 -1.11197 0.00580598 0.0307 1 0 1 1 0 0 +EDGE2 4265 4264 -0.88776 0.0444974 0.00218624 1 0 1 1 0 0 +EDGE2 4265 3944 -0.979583 0.0257293 -0.0154644 1 0 1 1 0 0 +EDGE2 4265 4124 -0.92942 0.00397626 -0.0063544 1 0 1 1 0 0 +EDGE2 4265 3924 -1.07862 0.0543363 -0.00523896 1 0 1 1 0 0 +EDGE2 4265 4245 -0.087949 -0.0106247 -0.0114763 1 0 1 1 0 0 +EDGE2 4265 4126 -0.0531769 -1.03003 -1.55778 1 0 1 1 0 0 +EDGE2 4265 4166 0.0232833 -1.04635 -1.5849 1 0 1 1 0 0 +EDGE2 4265 3905 0.0240299 0.00671251 -3.10876 1 0 1 1 0 0 +EDGE2 4265 3945 -0.0547567 0.0265624 0.0224292 1 0 1 1 0 0 +EDGE2 4265 4125 0.0235548 -0.0405932 -0.00378328 1 0 1 1 0 0 +EDGE2 4265 4165 0.011533 -0.131662 -3.13468 1 0 1 1 0 0 +EDGE2 4265 3925 -0.0535905 -0.0669569 -0.0115771 1 0 1 1 0 0 +EDGE2 4265 3904 0.994417 -0.0640964 -3.13528 1 0 1 1 0 0 +EDGE2 4265 4164 1.03128 -0.0246006 -3.1467 1 0 1 1 0 0 +EDGE2 4265 3906 0.0308521 0.985245 1.5732 1 0 1 1 0 0 +EDGE2 4265 3946 -0.0594448 1.00788 1.55472 1 0 1 1 0 0 +EDGE2 4265 4246 0.0380848 1.01929 1.59326 1 0 1 1 0 0 +EDGE2 4265 3926 0.131394 1.03629 1.58805 1 0 1 1 0 0 +EDGE2 4266 4245 -1.09023 -0.0777798 -1.57418 1 0 1 1 0 0 +EDGE2 4266 4265 -0.985149 -0.0668593 -1.55575 1 0 1 1 0 0 +EDGE2 4266 3905 -0.952158 0.0291659 1.57079 1 0 1 1 0 0 +EDGE2 4266 3945 -0.94239 0.000454571 -1.56344 1 0 1 1 0 0 +EDGE2 4266 4125 -1.03566 -0.0271618 -1.60084 1 0 1 1 0 0 +EDGE2 4266 4165 -0.915635 -0.0194001 1.5798 1 0 1 1 0 0 +EDGE2 4266 3925 -1.08729 0.0398309 -1.58293 1 0 1 1 0 0 +EDGE2 4266 3907 0.891117 0.00289136 -0.005035 1 0 1 1 0 0 +EDGE2 4266 3906 0.000474539 0.0329849 0.0045215 1 0 1 1 0 0 +EDGE2 4266 3946 -0.0201167 -0.0458955 0.0189756 1 0 1 1 0 0 +EDGE2 4266 4246 0.017093 -0.0200962 0.0157439 1 0 1 1 0 0 +EDGE2 4266 3926 -0.0135811 0.0202183 -0.00284898 1 0 1 1 0 0 +EDGE2 4266 3947 0.969084 -0.00684742 -0.0239324 1 0 1 1 0 0 +EDGE2 4266 4247 1.0001 -0.0231102 0.00377387 1 0 1 1 0 0 +EDGE2 4266 3927 1.08049 0.00262048 -0.0125593 1 0 1 1 0 0 +EDGE2 4267 3907 -0.045339 0.0940637 -0.0172553 1 0 1 1 0 0 +EDGE2 4267 3906 -1.00101 0.00705061 -0.0135485 1 0 1 1 0 0 +EDGE2 4267 3946 -1.05063 -0.00212917 -0.0048484 1 0 1 1 0 0 +EDGE2 4267 4246 -0.945654 -0.0628596 0.0209109 1 0 1 1 0 0 +EDGE2 4267 4266 -0.995884 -0.0304683 0.00169779 1 0 1 1 0 0 +EDGE2 4267 3926 -0.967217 0.0377805 -0.00859866 1 0 1 1 0 0 +EDGE2 4267 3947 0.00475237 -0.0405521 -0.0218181 1 0 1 1 0 0 +EDGE2 4267 4247 0.0305134 0.0235021 -0.0244193 1 0 1 1 0 0 +EDGE2 4267 3927 -0.0582813 -0.0130193 -0.00121718 1 0 1 1 0 0 +EDGE2 4267 3908 1.01753 0.006087 0.000267495 1 0 1 1 0 0 +EDGE2 4267 3948 1.01002 0.0192137 -0.00751916 1 0 1 1 0 0 +EDGE2 4267 4248 0.953603 -0.00839638 -0.0341884 1 0 1 1 0 0 +EDGE2 4267 3928 0.919038 -0.00466978 -0.0161772 1 0 1 1 0 0 +EDGE2 4268 3929 0.982765 -0.0154108 0.00799584 1 0 1 1 0 0 +EDGE2 4268 3907 -1.02772 0.0236273 0.00420237 1 0 1 1 0 0 +EDGE2 4268 3947 -0.905874 -0.0341686 0.00954868 1 0 1 1 0 0 +EDGE2 4268 4247 -1.0472 -0.030457 -0.0201331 1 0 1 1 0 0 +EDGE2 4268 4267 -0.969568 -0.042117 0.0349454 1 0 1 1 0 0 +EDGE2 4268 3927 -1.0163 0.0403324 0.0259126 1 0 1 1 0 0 +EDGE2 4268 3908 0.0587269 0.00913305 -0.0428769 1 0 1 1 0 0 +EDGE2 4268 3948 -0.0225949 -0.103886 0.0115917 1 0 1 1 0 0 +EDGE2 4268 4248 0.0240342 0.0637205 -0.00309008 1 0 1 1 0 0 +EDGE2 4268 3928 -0.0272244 -0.0046275 0.00838634 1 0 1 1 0 0 +EDGE2 4268 4249 1.01166 0.073831 -0.00969506 1 0 1 1 0 0 +EDGE2 4268 3949 1.018 0.0394502 -0.0347508 1 0 1 1 0 0 +EDGE2 4268 3909 1.0306 -0.0152755 -0.0266836 1 0 1 1 0 0 +EDGE2 4269 3929 0.0790149 0.00524581 -0.0170396 1 0 1 1 0 0 +EDGE2 4269 3908 -0.991503 -0.0436596 0.00589224 1 0 1 1 0 0 +EDGE2 4269 3948 -0.976523 0.0375386 0.0108872 1 0 1 1 0 0 +EDGE2 4269 4248 -0.976981 -0.0752399 -0.00810529 1 0 1 1 0 0 +EDGE2 4269 4268 -1.03768 -0.00495657 0.0237136 1 0 1 1 0 0 +EDGE2 4269 3928 -0.990749 0.00508287 -0.0340155 1 0 1 1 0 0 +EDGE2 4269 4249 0.0963425 0.0473621 -0.0255355 1 0 1 1 0 0 +EDGE2 4269 3949 -0.0759936 0.062054 -0.00110274 1 0 1 1 0 0 +EDGE2 4269 3970 1.02857 -0.0299554 -3.13108 1 0 1 1 0 0 +EDGE2 4269 4250 1.0606 -0.00831581 0.0143341 1 0 1 1 0 0 +EDGE2 4269 3909 0.0739775 -0.0772525 0.00309681 1 0 1 1 0 0 +EDGE2 4269 4110 0.899331 0.00740923 -3.12988 1 0 1 1 0 0 +EDGE2 4269 3910 0.970163 0.0686314 0.0304358 1 0 1 1 0 0 +EDGE2 4269 3930 1.07547 -0.0464377 0.0103649 1 0 1 1 0 0 +EDGE2 4269 3950 0.948098 0.0544418 -0.0109976 1 0 1 1 0 0 +EDGE2 4270 3971 -0.130878 1.04741 1.53404 1 0 1 1 0 0 +EDGE2 4270 4251 0.0574813 1.01099 1.56573 1 0 1 1 0 0 +EDGE2 4270 4111 -0.0382626 1.03282 1.61442 1 0 1 1 0 0 +EDGE2 4270 3911 -0.0994645 0.93109 1.55666 1 0 1 1 0 0 +EDGE2 4270 3931 0.00569031 0.996007 1.58465 1 0 1 1 0 0 +EDGE2 4270 3929 -1.00702 -0.00343243 -0.00652314 1 0 1 1 0 0 +EDGE2 4270 4249 -0.993816 0.0120776 -0.0115144 1 0 1 1 0 0 +EDGE2 4270 4269 -1.03428 -0.00310629 0.00815687 1 0 1 1 0 0 +EDGE2 4270 3949 -1.01649 0.0363781 0.0036976 1 0 1 1 0 0 +EDGE2 4270 3969 1.02666 -0.0050906 -3.14633 1 0 1 1 0 0 +EDGE2 4270 3970 0.0759817 -0.0360336 -3.16272 1 0 1 1 0 0 +EDGE2 4270 4250 -0.00632354 0.0417237 -0.012278 1 0 1 1 0 0 +EDGE2 4270 3909 -0.965173 -0.0752095 -0.00820737 1 0 1 1 0 0 +EDGE2 4270 4110 -0.0505981 0.00217524 -3.15477 1 0 1 1 0 0 +EDGE2 4270 3910 0.0182079 -0.110859 -0.00616342 1 0 1 1 0 0 +EDGE2 4270 3930 0.0352251 -0.0163693 0.00502898 1 0 1 1 0 0 +EDGE2 4270 3950 -0.0334142 -0.0218766 0.00571513 1 0 1 1 0 0 +EDGE2 4270 4109 0.881093 0.0494566 -3.15152 1 0 1 1 0 0 +EDGE2 4270 3951 0.0240754 -0.97172 -1.58438 1 0 1 1 0 0 +EDGE2 4271 3971 -0.0701471 0.0785449 -0.0114103 1 0 1 1 0 0 +EDGE2 4271 3932 1.11846 -0.0236082 -0.0276471 1 0 1 1 0 0 +EDGE2 4271 4112 0.908468 -0.00687925 -0.0169902 1 0 1 1 0 0 +EDGE2 4271 4252 1.01787 0.0149798 -0.0101557 1 0 1 1 0 0 +EDGE2 4271 3972 0.965176 0.00421947 -0.00443759 1 0 1 1 0 0 +EDGE2 4271 4251 0.0350683 0.0151042 -0.018054 1 0 1 1 0 0 +EDGE2 4271 3912 0.976901 0.0550103 0.0405886 1 0 1 1 0 0 +EDGE2 4271 4111 -0.0234839 -0.0261373 0.0150654 1 0 1 1 0 0 +EDGE2 4271 3911 0.045556 0.0075534 -0.000358006 1 0 1 1 0 0 +EDGE2 4271 3931 0.0741795 -0.0416557 -0.0147157 1 0 1 1 0 0 +EDGE2 4271 3970 -1.01407 0.0669533 1.56473 1 0 1 1 0 0 +EDGE2 4271 4250 -1.03171 0.00538858 -1.5545 1 0 1 1 0 0 +EDGE2 4271 4270 -0.900432 -0.00708732 -1.59138 1 0 1 1 0 0 +EDGE2 4271 4110 -0.927467 0.0516075 1.5737 1 0 1 1 0 0 +EDGE2 4271 3910 -1.04427 0.0288017 -1.5948 1 0 1 1 0 0 +EDGE2 4271 3930 -1.04261 -0.0153926 -1.57069 1 0 1 1 0 0 +EDGE2 4271 3950 -0.974702 0.00476821 -1.57129 1 0 1 1 0 0 +EDGE2 4272 3971 -0.983405 0.0308757 -0.0184344 1 0 1 1 0 0 +EDGE2 4272 3913 0.938637 0.0178346 0.00723475 1 0 1 1 0 0 +EDGE2 4272 3973 0.946846 -0.0117584 0.00010655 1 0 1 1 0 0 +EDGE2 4272 4113 0.945962 0.0391172 -0.0071039 1 0 1 1 0 0 +EDGE2 4272 4253 1.01603 0.0283898 0.0198276 1 0 1 1 0 0 +EDGE2 4272 3933 0.994137 0.0193799 -0.0350988 1 0 1 1 0 0 +EDGE2 4272 3932 0.0071532 -0.0462074 -0.00237413 1 0 1 1 0 0 +EDGE2 4272 4112 -0.0157064 0.0528054 -0.0123776 1 0 1 1 0 0 +EDGE2 4272 4252 0.0427561 -0.0570488 -0.00515584 1 0 1 1 0 0 +EDGE2 4272 3972 -0.0608557 -0.0797982 0.013056 1 0 1 1 0 0 +EDGE2 4272 4251 -0.989792 -0.0210087 0.0285411 1 0 1 1 0 0 +EDGE2 4272 4271 -1.004 -0.0799696 0.0227481 1 0 1 1 0 0 +EDGE2 4272 3912 0.0445188 0.00840481 -0.00162841 1 0 1 1 0 0 +EDGE2 4272 4111 -1.08937 -0.0484967 0.0250514 1 0 1 1 0 0 +EDGE2 4272 3911 -0.994516 0.0120576 0.00357439 1 0 1 1 0 0 +EDGE2 4272 3931 -1.00622 -0.0331201 0.0302632 1 0 1 1 0 0 +EDGE2 4273 4254 1.00475 -0.00025402 0.0230165 1 0 1 1 0 0 +EDGE2 4273 3913 0.0288429 0.0321211 -0.00854306 1 0 1 1 0 0 +EDGE2 4273 3934 0.952952 0.0141506 -0.0225592 1 0 1 1 0 0 +EDGE2 4273 3974 1.06301 0.0189236 -0.0195549 1 0 1 1 0 0 +EDGE2 4273 4114 0.997801 -0.144499 0.0221979 1 0 1 1 0 0 +EDGE2 4273 3914 1.04842 -0.052506 -0.0418491 1 0 1 1 0 0 +EDGE2 4273 3973 -0.0299373 -0.0153151 0.0530937 1 0 1 1 0 0 +EDGE2 4273 4113 -0.082212 -0.0319928 -0.0246167 1 0 1 1 0 0 +EDGE2 4273 4253 0.0164036 0.0149393 -0.0238919 1 0 1 1 0 0 +EDGE2 4273 3933 -0.0420234 -0.0161387 -0.0038442 1 0 1 1 0 0 +EDGE2 4273 3932 -0.973196 0.0184708 0.0315485 1 0 1 1 0 0 +EDGE2 4273 4112 -0.958496 0.0322778 -0.0043561 1 0 1 1 0 0 +EDGE2 4273 4252 -0.95539 0.012491 0.0171612 1 0 1 1 0 0 +EDGE2 4273 4272 -1.09317 0.0386646 0.0197316 1 0 1 1 0 0 +EDGE2 4273 3972 -0.962163 -0.102537 -0.00397489 1 0 1 1 0 0 +EDGE2 4273 3912 -0.963958 -0.000437169 0.0188117 1 0 1 1 0 0 +EDGE2 4274 4015 1.06295 0.0325638 -3.11783 1 0 1 1 0 0 +EDGE2 4274 4255 0.875474 -0.0445008 -0.0108866 1 0 1 1 0 0 +EDGE2 4274 4115 1.03211 0.0527073 0.00907897 1 0 1 1 0 0 +EDGE2 4274 3935 0.936452 -0.0410279 0.00410659 1 0 1 1 0 0 +EDGE2 4274 3975 0.968614 0.0800917 -0.00622444 1 0 1 1 0 0 +EDGE2 4274 3995 0.979824 -0.014991 -3.14499 1 0 1 1 0 0 +EDGE2 4274 3915 1.03813 -0.0435948 -0.0261589 1 0 1 1 0 0 +EDGE2 4274 4254 0.0718792 0.0367033 0.0268227 1 0 1 1 0 0 +EDGE2 4274 3913 -0.937742 0.0520107 -0.00361747 1 0 1 1 0 0 +EDGE2 4274 4273 -0.98912 -0.0692098 0.0371947 1 0 1 1 0 0 +EDGE2 4274 3934 0.0382537 -0.0301024 0.0202163 1 0 1 1 0 0 +EDGE2 4274 3974 -0.0805176 -0.00775005 -0.0181249 1 0 1 1 0 0 +EDGE2 4274 4114 0.0486627 0.0107704 -0.0169324 1 0 1 1 0 0 +EDGE2 4274 3914 0.071542 -0.0293836 -0.0293863 1 0 1 1 0 0 +EDGE2 4274 3973 -0.925506 -0.0931066 -0.00236299 1 0 1 1 0 0 +EDGE2 4274 4113 -1.06223 -0.0209853 -0.0241531 1 0 1 1 0 0 +EDGE2 4274 4253 -1.04882 0.0983065 0.00535951 1 0 1 1 0 0 +EDGE2 4274 3933 -1.0258 0.0198982 -0.00995426 1 0 1 1 0 0 +EDGE2 4275 4256 0.113527 1.0187 1.57898 1 0 1 1 0 0 +EDGE2 4275 3936 0.0455403 1.06537 1.61935 1 0 1 1 0 0 +EDGE2 4275 4116 0.0343888 0.98515 1.57364 1 0 1 1 0 0 +EDGE2 4275 3916 0.0399441 0.914702 1.56339 1 0 1 1 0 0 +EDGE2 4275 4015 0.0323563 -0.002017 -3.12965 1 0 1 1 0 0 +EDGE2 4275 4014 0.926293 -0.0948178 -3.13969 1 0 1 1 0 0 +EDGE2 4275 4255 -0.00557442 0.0511225 -0.0143077 1 0 1 1 0 0 +EDGE2 4275 3994 1.054 0.0591566 -3.15866 1 0 1 1 0 0 +EDGE2 4275 4115 -0.00184489 0.0198872 -0.00994365 1 0 1 1 0 0 +EDGE2 4275 4016 0.0862918 -1.02368 -1.53727 1 0 1 1 0 0 +EDGE2 4275 3935 0.0301414 -0.0017664 0.00908402 1 0 1 1 0 0 +EDGE2 4275 3975 -0.0213838 0.0695418 0.0262731 1 0 1 1 0 0 +EDGE2 4275 3995 0.0469487 0.00230547 -3.15739 1 0 1 1 0 0 +EDGE2 4275 3915 0.00809687 -0.0181111 0.0102525 1 0 1 1 0 0 +EDGE2 4275 3976 0.0105585 -1.02693 -1.58048 1 0 1 1 0 0 +EDGE2 4275 3996 -0.0634338 -0.950421 -1.57901 1 0 1 1 0 0 +EDGE2 4275 4254 -1.03112 0.0651653 0.00724748 1 0 1 1 0 0 +EDGE2 4275 4274 -0.989132 0.0352227 0.00438303 1 0 1 1 0 0 +EDGE2 4275 3934 -1.03426 0.0328938 0.00228041 1 0 1 1 0 0 +EDGE2 4275 3974 -1.00251 -0.0184763 -0.0212055 1 0 1 1 0 0 +EDGE2 4275 4114 -0.950383 -0.0267652 0.0136583 1 0 1 1 0 0 +EDGE2 4275 3914 -0.979223 -0.00147029 -0.0225452 1 0 1 1 0 0 +EDGE2 4276 4257 1.04035 0.0633541 0.00475394 1 0 1 1 0 0 +EDGE2 4276 4256 -0.0636298 -0.0126831 0.000764732 1 0 1 1 0 0 +EDGE2 4276 3917 1.10888 -0.00214695 0.00295479 1 0 1 1 0 0 +EDGE2 4276 3937 0.945511 0.00203707 0.0188234 1 0 1 1 0 0 +EDGE2 4276 4117 0.845787 0.0151636 0.00545576 1 0 1 1 0 0 +EDGE2 4276 3936 -0.00226864 -0.0315137 -0.0180731 1 0 1 1 0 0 +EDGE2 4276 4116 0.0295275 0.0219346 -0.00746986 1 0 1 1 0 0 +EDGE2 4276 3916 0.0071342 0.0207908 0.000956978 1 0 1 1 0 0 +EDGE2 4276 4015 -1.03077 0.0234716 1.56048 1 0 1 1 0 0 +EDGE2 4276 4255 -1.00787 -0.014531 -1.60188 1 0 1 1 0 0 +EDGE2 4276 4275 -1.06094 -0.0198455 -1.56121 1 0 1 1 0 0 +EDGE2 4276 4115 -0.979582 -0.0678941 -1.55851 1 0 1 1 0 0 +EDGE2 4276 3935 -0.978416 -0.0553238 -1.57068 1 0 1 1 0 0 +EDGE2 4276 3975 -0.986049 -0.0208308 -1.55607 1 0 1 1 0 0 +EDGE2 4276 3995 -1.06227 0.096723 1.58478 1 0 1 1 0 0 +EDGE2 4276 3915 -0.986191 0.0831041 -1.56473 1 0 1 1 0 0 +EDGE2 4277 4257 0.025015 -0.0482245 0.00261672 1 0 1 1 0 0 +EDGE2 4277 4118 0.978059 0.0654929 -0.00587319 1 0 1 1 0 0 +EDGE2 4277 4258 0.946541 -0.025604 0.0541308 1 0 1 1 0 0 +EDGE2 4277 3918 1.04098 0.0908207 -0.0192294 1 0 1 1 0 0 +EDGE2 4277 3938 1.02488 -0.0286237 0.00357267 1 0 1 1 0 0 +EDGE2 4277 4256 -1.014 -0.101097 -0.0158555 1 0 1 1 0 0 +EDGE2 4277 3917 0.0131721 0.00714127 0.00684154 1 0 1 1 0 0 +EDGE2 4277 3937 0.0205476 0.0119486 -0.0142243 1 0 1 1 0 0 +EDGE2 4277 4117 0.0660851 -0.0294011 -0.0147299 1 0 1 1 0 0 +EDGE2 4277 4276 -1.00709 0.0561003 0.00515862 1 0 1 1 0 0 +EDGE2 4277 3936 -1.00193 0.0827212 0.0108985 1 0 1 1 0 0 +EDGE2 4277 4116 -0.99339 0.0719138 0.0126058 1 0 1 1 0 0 +EDGE2 4277 3916 -1.01364 -0.13727 -0.0281899 1 0 1 1 0 0 +EDGE2 4278 4119 0.906241 -0.00956292 0.00147231 1 0 1 1 0 0 +EDGE2 4278 4259 0.970175 0.0606095 0.0083525 1 0 1 1 0 0 +EDGE2 4278 4257 -1.03756 0.0235602 0.0123443 1 0 1 1 0 0 +EDGE2 4278 4118 -0.0124179 0.023166 -0.000746528 1 0 1 1 0 0 +EDGE2 4278 3919 0.980037 0.0714416 0.023454 1 0 1 1 0 0 +EDGE2 4278 3939 1.05778 0.00263785 0.0250351 1 0 1 1 0 0 +EDGE2 4278 4258 0.0980308 0.0410468 -0.00442724 1 0 1 1 0 0 +EDGE2 4278 4277 -1.0027 0.00187026 0.0427472 1 0 1 1 0 0 +EDGE2 4278 3918 0.0553771 0.0139393 0.000914861 1 0 1 1 0 0 +EDGE2 4278 3938 -0.044098 -0.0284749 -0.00111895 1 0 1 1 0 0 +EDGE2 4278 3917 -0.979531 -0.0490605 0.045492 1 0 1 1 0 0 +EDGE2 4278 3937 -1.10426 0.00482909 -0.00944056 1 0 1 1 0 0 +EDGE2 4278 4117 -1.01552 0.00924446 -0.0224942 1 0 1 1 0 0 +EDGE2 4279 4119 -0.0218966 0.0595293 0.0202302 1 0 1 1 0 0 +EDGE2 4279 4120 1.00447 0.0358501 0.0081553 1 0 1 1 0 0 +EDGE2 4279 4260 0.962543 0.13733 0.0111272 1 0 1 1 0 0 +EDGE2 4279 4240 1.03882 -0.110886 -3.12707 1 0 1 1 0 0 +EDGE2 4279 3920 1.02655 -0.0379188 0.000574374 1 0 1 1 0 0 +EDGE2 4279 3940 0.921795 0.00498129 -0.0260353 1 0 1 1 0 0 +EDGE2 4279 4259 -0.0731292 -0.0359928 -0.0280589 1 0 1 1 0 0 +EDGE2 4279 4118 -1.04362 -0.06276 0.00183172 1 0 1 1 0 0 +EDGE2 4279 4278 -0.969922 -0.0595241 0.0142486 1 0 1 1 0 0 +EDGE2 4279 3919 -0.0277897 0.0428578 0.00649922 1 0 1 1 0 0 +EDGE2 4279 3939 -0.120567 0.0152419 -0.010954 1 0 1 1 0 0 +EDGE2 4279 4258 -1.02314 -0.00385081 -0.0179323 1 0 1 1 0 0 +EDGE2 4279 3918 -1.07038 -0.00685931 -0.00524065 1 0 1 1 0 0 +EDGE2 4279 3938 -0.912493 -0.120944 0.00276824 1 0 1 1 0 0 +EDGE2 4280 4119 -0.970756 -0.0917773 -0.0204914 1 0 1 1 0 0 +EDGE2 4280 4120 -0.0804489 0.00901108 0.0141102 1 0 1 1 0 0 +EDGE2 4280 4260 -0.0452451 0.00762047 -0.0171475 1 0 1 1 0 0 +EDGE2 4280 4239 0.98841 0.0990238 -3.12312 1 0 1 1 0 0 +EDGE2 4280 4240 -0.0812731 -0.0178075 -3.12344 1 0 1 1 0 0 +EDGE2 4280 4279 -0.988771 -0.026521 0.00149551 1 0 1 1 0 0 +EDGE2 4280 3920 0.0547492 0.014473 -0.0124568 1 0 1 1 0 0 +EDGE2 4280 3940 -0.0266164 0.0856284 -0.0116301 1 0 1 1 0 0 +EDGE2 4280 4259 -1.01264 -0.0255701 -0.0057571 1 0 1 1 0 0 +EDGE2 4280 3919 -0.986424 0.0286291 -0.0214022 1 0 1 1 0 0 +EDGE2 4280 3939 -1.01472 -0.016864 0.00519866 1 0 1 1 0 0 +EDGE2 4280 4121 -0.0471634 1.00065 1.56642 1 0 1 1 0 0 +EDGE2 4280 4261 0.00537346 1.15254 1.61828 1 0 1 1 0 0 +EDGE2 4280 4241 0.0548502 0.985432 1.57928 1 0 1 1 0 0 +EDGE2 4280 3921 0.0342709 0.954086 1.58755 1 0 1 1 0 0 +EDGE2 4280 3941 0.0401235 1.05823 1.59903 1 0 1 1 0 0 +EDGE2 4281 4120 -0.971103 -0.0128096 1.63111 1 0 1 1 0 0 +EDGE2 4281 4260 -1.01905 -0.0182287 1.56117 1 0 1 1 0 0 +EDGE2 4281 4280 -1.09582 -0.095568 1.55911 1 0 1 1 0 0 +EDGE2 4281 4240 -1.00758 -0.0654069 -1.58812 1 0 1 1 0 0 +EDGE2 4281 3920 -1.02493 0.110743 1.54122 1 0 1 1 0 0 +EDGE2 4281 3940 -1.00865 0.0272636 1.57365 1 0 1 1 0 0 +EDGE2 4282 4281 -0.909187 -0.107824 0.0146774 1 0 1 1 0 0 +EDGE2 4283 4282 -1.0755 0.01075 -0.00234819 1 0 1 1 0 0 +EDGE2 4284 4283 -0.965555 0.0773552 0.0288421 1 0 1 1 0 0 +EDGE2 4285 4284 -1.02434 0.0556268 0.00525276 1 0 1 1 0 0 +EDGE2 4286 4285 -0.948914 0.0629612 -1.57991 1 0 1 1 0 0 +EDGE2 4287 4286 -1.0022 0.0561617 -0.0344891 1 0 1 1 0 0 +EDGE2 4288 4287 -0.882162 0.00608715 0.0419509 1 0 1 1 0 0 +EDGE2 4289 4288 -1.0088 0.07041 0.0208553 1 0 1 1 0 0 +EDGE2 4290 4289 -1.01155 -0.0349028 -0.00143493 1 0 1 1 0 0 +EDGE2 4291 4290 -1.01533 0.0292979 -1.58421 1 0 1 1 0 0 +EDGE2 4292 4291 -1.02784 -0.0706184 -0.00223675 1 0 1 1 0 0 +EDGE2 4293 4292 -1.06808 0.0471282 0.0238189 1 0 1 1 0 0 +EDGE2 4294 4293 -1.05368 -0.122992 -0.0119829 1 0 1 1 0 0 +EDGE2 4294 4175 0.969982 0.0776945 -3.14158 1 0 1 1 0 0 +EDGE2 4294 4215 1.00378 0.0455043 -3.10647 1 0 1 1 0 0 +EDGE2 4294 4235 0.961352 -0.00554125 -3.14588 1 0 1 1 0 0 +EDGE2 4295 4294 -1.03166 -0.0336219 0.0193637 1 0 1 1 0 0 +EDGE2 4295 4176 0.00397529 -1.0069 -1.53441 1 0 1 1 0 0 +EDGE2 4295 4216 -0.0437065 -0.923648 -1.61097 1 0 1 1 0 0 +EDGE2 4295 4175 0.0265303 0.0395922 -3.12252 1 0 1 1 0 0 +EDGE2 4295 4215 0.0727505 0.0604386 -3.14387 1 0 1 1 0 0 +EDGE2 4295 4235 -0.0655774 0.0582366 -3.12188 1 0 1 1 0 0 +EDGE2 4295 4236 0.0277572 1.11249 1.57074 1 0 1 1 0 0 +EDGE2 4295 4214 0.911279 -0.0430838 -3.12581 1 0 1 1 0 0 +EDGE2 4295 4234 0.999632 0.018945 -3.11663 1 0 1 1 0 0 +EDGE2 4295 4174 0.939636 -0.0491012 -3.15591 1 0 1 1 0 0 +EDGE2 4296 4295 -0.965699 0.0497724 1.57626 1 0 1 1 0 0 +EDGE2 4296 4177 1.00259 0.0319851 -0.0133133 1 0 1 1 0 0 +EDGE2 4296 4217 0.997238 0.0464669 0.0106338 1 0 1 1 0 0 +EDGE2 4296 4176 -0.000955337 0.0625995 0.0154392 1 0 1 1 0 0 +EDGE2 4296 4216 -0.0537025 -0.0371318 0.0242847 1 0 1 1 0 0 +EDGE2 4296 4175 -0.86691 -0.0634417 -1.55903 1 0 1 1 0 0 +EDGE2 4296 4215 -0.985604 0.00978814 -1.58555 1 0 1 1 0 0 +EDGE2 4296 4235 -1.00918 -0.0926645 -1.56327 1 0 1 1 0 0 +EDGE2 4297 4178 1.04438 0.0319965 -0.0198095 1 0 1 1 0 0 +EDGE2 4297 4218 1.03474 0.0719255 0.019724 1 0 1 1 0 0 +EDGE2 4297 4296 -1.12692 0.00604215 -0.00503694 1 0 1 1 0 0 +EDGE2 4297 4177 -0.0149886 -0.0164329 -0.0143364 1 0 1 1 0 0 +EDGE2 4297 4217 -0.0475834 0.0058988 0.00121137 1 0 1 1 0 0 +EDGE2 4297 4176 -0.93569 -0.0526476 0.00494507 1 0 1 1 0 0 +EDGE2 4297 4216 -0.999097 -0.00698126 0.017294 1 0 1 1 0 0 +EDGE2 4298 4219 0.934964 0.0187518 0.0167911 1 0 1 1 0 0 +EDGE2 4298 4178 0.0768514 -0.0305988 -0.0100556 1 0 1 1 0 0 +EDGE2 4298 4179 0.97943 0.0373055 0.00526361 1 0 1 1 0 0 +EDGE2 4298 4218 -0.0456392 -0.0151265 0.0170922 1 0 1 1 0 0 +EDGE2 4298 4177 -1.02552 0.043445 0.0165876 1 0 1 1 0 0 +EDGE2 4298 4217 -1.08704 0.0283362 -0.0259767 1 0 1 1 0 0 +EDGE2 4298 4297 -1.0049 0.0505118 -0.0188835 1 0 1 1 0 0 +EDGE2 4299 4219 -0.0423873 -0.0572657 0.00932067 1 0 1 1 0 0 +EDGE2 4299 4180 1.01428 0.0646281 0.0224389 1 0 1 1 0 0 +EDGE2 4299 4220 1.00713 -0.0277819 0.037609 1 0 1 1 0 0 +EDGE2 4299 3860 1.04616 -0.0262488 -3.14523 1 0 1 1 0 0 +EDGE2 4299 3880 0.96042 0.105529 -3.15544 1 0 1 1 0 0 +EDGE2 4299 4178 -0.954528 -0.0464462 0.00264304 1 0 1 1 0 0 +EDGE2 4299 4298 -1.04592 -0.000868377 0.0159214 1 0 1 1 0 0 +EDGE2 4299 4179 -0.0327856 0.0214789 -0.0345808 1 0 1 1 0 0 +EDGE2 4299 4218 -1.15796 0.0123455 -0.00738069 1 0 1 1 0 0 +EDGE2 4300 4219 -1.0308 -0.0398382 -0.014942 1 0 1 1 0 0 +EDGE2 4300 3859 1.02964 0.00546609 -3.1318 1 0 1 1 0 0 +EDGE2 4300 3879 1.09839 0.0210022 -3.14843 1 0 1 1 0 0 +EDGE2 4300 3861 0.0288158 -0.927225 -1.54843 1 0 1 1 0 0 +EDGE2 4300 4180 -0.116884 0.0492703 0.00985168 1 0 1 1 0 0 +EDGE2 4300 4220 -0.0388042 -0.0280969 0.0121541 1 0 1 1 0 0 +EDGE2 4300 3860 0.0738383 -0.00262953 -3.11485 1 0 1 1 0 0 +EDGE2 4300 3880 0.0921499 -0.00116141 -3.13921 1 0 1 1 0 0 +EDGE2 4300 4299 -0.965762 0.0578088 -0.0144835 1 0 1 1 0 0 +EDGE2 4300 4179 -0.972468 -0.00179331 -0.00923136 1 0 1 1 0 0 +EDGE2 4300 4181 0.10822 1.15452 1.60007 1 0 1 1 0 0 +EDGE2 4300 4221 0.0566491 0.93971 1.56169 1 0 1 1 0 0 +EDGE2 4300 3881 -0.0120596 0.980178 1.56786 1 0 1 1 0 0 +EDGE2 4301 4180 -0.980137 0.0101566 -1.5759 1 0 1 1 0 0 +EDGE2 4301 4300 -0.935151 0.0288267 -1.5705 1 0 1 1 0 0 +EDGE2 4301 4220 -0.994447 -0.0312267 -1.52007 1 0 1 1 0 0 +EDGE2 4301 3860 -1.00231 -0.0211017 1.54992 1 0 1 1 0 0 +EDGE2 4301 3880 -1.05447 -0.0867539 1.57027 1 0 1 1 0 0 +EDGE2 4301 4182 0.916402 -0.0332678 -0.0293791 1 0 1 1 0 0 +EDGE2 4301 4181 -0.0335913 -0.050778 -0.0122163 1 0 1 1 0 0 +EDGE2 4301 4221 0.0594822 -0.00812799 -0.0283611 1 0 1 1 0 0 +EDGE2 4301 3881 -0.00649304 0.0219381 -0.000937134 1 0 1 1 0 0 +EDGE2 4301 4222 1.03201 -0.0114504 0.0238035 1 0 1 1 0 0 +EDGE2 4301 3882 1.01682 -0.026964 0.010437 1 0 1 1 0 0 +EDGE2 4302 4182 -0.0154037 -0.0075182 -0.0302147 1 0 1 1 0 0 +EDGE2 4302 4181 -0.990934 -0.0555723 0.0160569 1 0 1 1 0 0 +EDGE2 4302 4301 -1.00204 0.031259 -0.0247683 1 0 1 1 0 0 +EDGE2 4302 4221 -1.0236 0.078251 0.0509641 1 0 1 1 0 0 +EDGE2 4302 3881 -0.978394 -0.00237261 -0.0219282 1 0 1 1 0 0 +EDGE2 4302 4222 -0.0193404 -0.0172897 0.00584477 1 0 1 1 0 0 +EDGE2 4302 4183 0.90711 -0.00425885 0.0095085 1 0 1 1 0 0 +EDGE2 4302 3882 0.011937 0.121392 0.0122962 1 0 1 1 0 0 +EDGE2 4302 4223 1.05222 0.00152691 -0.000227264 1 0 1 1 0 0 +EDGE2 4302 3883 0.98375 -0.0507128 0.0207625 1 0 1 1 0 0 +EDGE2 4303 4182 -1.04168 -0.0201454 0.00712699 1 0 1 1 0 0 +EDGE2 4303 4302 -1.12227 -0.0026576 -0.0015715 1 0 1 1 0 0 +EDGE2 4303 4222 -1.08209 0.0719265 0.00582932 1 0 1 1 0 0 +EDGE2 4303 4184 1.08595 0.0150104 0.00156141 1 0 1 1 0 0 +EDGE2 4303 4183 -0.00967228 -0.00291249 -0.00163416 1 0 1 1 0 0 +EDGE2 4303 3882 -0.97219 -0.0790241 -0.0207069 1 0 1 1 0 0 +EDGE2 4303 4223 -0.0477576 0.000818653 0.00784621 1 0 1 1 0 0 +EDGE2 4303 3883 -0.0487126 -0.0218847 -0.0104513 1 0 1 1 0 0 +EDGE2 4303 4224 0.963495 0.0750537 -0.00932627 1 0 1 1 0 0 +EDGE2 4303 3884 0.982264 -0.00451347 0.0393214 1 0 1 1 0 0 +EDGE2 4304 4184 0.0637675 -0.00461601 0.0365437 1 0 1 1 0 0 +EDGE2 4304 4183 -1.04551 0.0297944 0.0131004 1 0 1 1 0 0 +EDGE2 4304 4303 -1.01156 0.0667044 0.0197705 1 0 1 1 0 0 +EDGE2 4304 4223 -0.961884 -0.0407365 -0.0212663 1 0 1 1 0 0 +EDGE2 4304 3883 -1.02165 -0.00309503 0.0265166 1 0 1 1 0 0 +EDGE2 4304 4224 0.0373009 0.0881351 -0.0139703 1 0 1 1 0 0 +EDGE2 4304 4205 1.02653 0.0520585 -3.15666 1 0 1 1 0 0 +EDGE2 4304 3884 -0.0102463 0.0718198 -0.0196612 1 0 1 1 0 0 +EDGE2 4304 4225 0.964912 -0.00752765 0.00247317 1 0 1 1 0 0 +EDGE2 4304 3885 0.986539 0.0454015 0.0373658 1 0 1 1 0 0 +EDGE2 4304 4145 0.985792 0.0270508 -3.14947 1 0 1 1 0 0 +EDGE2 4304 4185 0.979891 0.0307244 -0.0231772 1 0 1 1 0 0 +EDGE2 4305 4186 -0.0837141 -1.00046 -1.51475 1 0 1 1 0 0 +EDGE2 4305 4226 0.0295274 1.01485 1.56821 1 0 1 1 0 0 +EDGE2 4305 4184 -0.921783 0.00807725 0.0277184 1 0 1 1 0 0 +EDGE2 4305 4304 -0.949659 -0.000422885 0.032646 1 0 1 1 0 0 +EDGE2 4305 4224 -0.965654 -0.0277201 0.00365626 1 0 1 1 0 0 +EDGE2 4305 4205 -0.00935531 -0.0366819 -3.12124 1 0 1 1 0 0 +EDGE2 4305 3884 -0.944126 -0.0104913 0.0076806 1 0 1 1 0 0 +EDGE2 4305 4225 0.0163899 -0.0365342 0.00949926 1 0 1 1 0 0 +EDGE2 4305 3885 0.043121 -0.0710069 0.0300245 1 0 1 1 0 0 +EDGE2 4305 4145 -0.0570545 0.0295596 -3.15017 1 0 1 1 0 0 +EDGE2 4305 4185 -0.0422203 -0.00404514 0.0291051 1 0 1 1 0 0 +EDGE2 4305 3886 0.00995923 1.03198 1.59381 1 0 1 1 0 0 +EDGE2 4305 4146 0.00538772 1.0113 1.55945 1 0 1 1 0 0 +EDGE2 4305 4206 0.0500918 0.976261 1.56754 1 0 1 1 0 0 +EDGE2 4305 4144 0.957974 0.00822332 -3.1412 1 0 1 1 0 0 +EDGE2 4305 4204 1.05397 0.00262484 -3.14324 1 0 1 1 0 0 +EDGE2 4306 4226 -0.00849777 -0.0727581 0.00859292 1 0 1 1 0 0 +EDGE2 4306 4205 -1.03654 0.00497306 1.54489 1 0 1 1 0 0 +EDGE2 4306 4305 -0.937734 0.0695677 -1.57536 1 0 1 1 0 0 +EDGE2 4306 4225 -0.937172 -0.00859944 -1.59074 1 0 1 1 0 0 +EDGE2 4306 3885 -1.13659 -0.0526958 -1.54274 1 0 1 1 0 0 +EDGE2 4306 4145 -0.928129 -0.112526 1.53673 1 0 1 1 0 0 +EDGE2 4306 4185 -1.03078 -0.0755082 -1.56504 1 0 1 1 0 0 +EDGE2 4306 4227 1.05379 0.0186916 -0.0191842 1 0 1 1 0 0 +EDGE2 4306 3886 0.00965014 -0.0067475 -0.0144371 1 0 1 1 0 0 +EDGE2 4306 4146 -0.0882747 0.043264 0.00667001 1 0 1 1 0 0 +EDGE2 4306 4206 -0.00215138 -0.0330883 0.000278221 1 0 1 1 0 0 +EDGE2 4306 3887 1.03956 0.0129693 0.049067 1 0 1 1 0 0 +EDGE2 4306 4147 0.97369 0.0263164 0.0148118 1 0 1 1 0 0 +EDGE2 4306 4207 0.95173 -0.0594611 0.0258263 1 0 1 1 0 0 +EDGE2 4307 4226 -0.999863 -0.00251885 -0.0254049 1 0 1 1 0 0 +EDGE2 4307 4306 -0.982853 0.0181983 0.00890841 1 0 1 1 0 0 +EDGE2 4307 4228 1.0505 -0.0896289 0.00434809 1 0 1 1 0 0 +EDGE2 4307 4227 -0.0398292 -0.0264422 -0.0308183 1 0 1 1 0 0 +EDGE2 4307 3886 -1.01454 -0.0641819 -0.0219911 1 0 1 1 0 0 +EDGE2 4307 4146 -1.02434 -0.00205197 0.00483681 1 0 1 1 0 0 +EDGE2 4307 4206 -0.99416 0.0507246 -0.00608768 1 0 1 1 0 0 +EDGE2 4307 3887 0.0176635 -0.0414213 -0.0260322 1 0 1 1 0 0 +EDGE2 4307 4147 0.00050694 -0.0743445 -0.0150832 1 0 1 1 0 0 +EDGE2 4307 4207 -0.0494744 -0.00652933 -0.0142641 1 0 1 1 0 0 +EDGE2 4307 3888 0.995024 -0.0502294 0.00842706 1 0 1 1 0 0 +EDGE2 4307 4148 0.964906 -0.0719073 -0.0152262 1 0 1 1 0 0 +EDGE2 4307 4208 1.02286 0.0227051 -0.00802997 1 0 1 1 0 0 +EDGE2 4308 4228 -0.00692582 -0.0504772 -0.00952227 1 0 1 1 0 0 +EDGE2 4308 4227 -0.921246 0.0588532 0.00774384 1 0 1 1 0 0 +EDGE2 4308 4307 -1.00067 0.0182742 -0.0109296 1 0 1 1 0 0 +EDGE2 4308 3887 -1.03223 -0.0184476 -0.0173624 1 0 1 1 0 0 +EDGE2 4308 4147 -1.04331 0.029627 -0.00141626 1 0 1 1 0 0 +EDGE2 4308 4207 -1.00369 -0.0563534 -0.0171472 1 0 1 1 0 0 +EDGE2 4308 4229 0.989795 0.0603765 0.0363258 1 0 1 1 0 0 +EDGE2 4308 3888 0.00928614 -0.0116939 0.00609076 1 0 1 1 0 0 +EDGE2 4308 4148 -0.0157713 0.05188 -0.00112317 1 0 1 1 0 0 +EDGE2 4308 4208 0.00696496 -0.00526153 0.0330731 1 0 1 1 0 0 +EDGE2 4308 4149 0.94928 0.00598678 0.0416562 1 0 1 1 0 0 +EDGE2 4308 4209 1.02669 -0.0587617 -0.00699621 1 0 1 1 0 0 +EDGE2 4308 3889 0.980719 0.0728427 -0.0174502 1 0 1 1 0 0 +EDGE2 4309 4230 0.937216 0.0251986 -0.0495965 1 0 1 1 0 0 +EDGE2 4309 4228 -0.937401 -0.03737 0.0151537 1 0 1 1 0 0 +EDGE2 4309 4308 -0.983373 0.000230815 0.0229975 1 0 1 1 0 0 +EDGE2 4309 4229 -0.0658324 -0.0445899 0.0370273 1 0 1 1 0 0 +EDGE2 4309 3888 -0.971902 0.0637608 0.0242694 1 0 1 1 0 0 +EDGE2 4309 4148 -0.891013 0.0218253 -0.00244316 1 0 1 1 0 0 +EDGE2 4309 4208 -1.05375 -0.0511864 0.000811842 1 0 1 1 0 0 +EDGE2 4309 4149 -0.0517126 0.0444128 0.0226016 1 0 1 1 0 0 +EDGE2 4309 4209 -0.00049686 0.0324332 0.0245147 1 0 1 1 0 0 +EDGE2 4309 3889 0.000246969 -0.0429597 -0.034975 1 0 1 1 0 0 +EDGE2 4309 3890 0.990376 -0.0372863 -0.00837042 1 0 1 1 0 0 +EDGE2 4309 4150 1.03646 0.0414297 0.00546822 1 0 1 1 0 0 +EDGE2 4309 4170 1.00162 0.0116307 -3.11621 1 0 1 1 0 0 +EDGE2 4309 4210 0.904619 0.0700379 -0.0477558 1 0 1 1 0 0 +EDGE2 4309 4130 1.00125 -0.0258532 -3.13182 1 0 1 1 0 0 +EDGE2 4310 4230 -0.0504402 0.021129 -0.0132846 1 0 1 1 0 0 +EDGE2 4310 4229 -1.01048 -0.0431822 -0.00213655 1 0 1 1 0 0 +EDGE2 4310 4309 -0.976564 -0.0331765 -0.0459907 1 0 1 1 0 0 +EDGE2 4310 4149 -0.934838 -0.0750721 -0.00365015 1 0 1 1 0 0 +EDGE2 4310 4209 -0.946328 -0.0533149 0.00107084 1 0 1 1 0 0 +EDGE2 4310 3889 -1.0158 0.0210043 -0.0172158 1 0 1 1 0 0 +EDGE2 4310 4171 0.0203524 1.00133 1.59602 1 0 1 1 0 0 +EDGE2 4310 4211 0.0196066 1.05935 1.5783 1 0 1 1 0 0 +EDGE2 4310 4231 -0.0331427 0.950991 1.56374 1 0 1 1 0 0 +EDGE2 4310 3890 0.0885106 0.00824563 -0.0233032 1 0 1 1 0 0 +EDGE2 4310 4150 0.00223517 0.0360293 0.0269533 1 0 1 1 0 0 +EDGE2 4310 4170 0.0414053 -0.0648661 -3.11116 1 0 1 1 0 0 +EDGE2 4310 4210 -0.0520024 -0.0414259 0.00616436 1 0 1 1 0 0 +EDGE2 4310 4130 0.0178149 0.0234342 -3.14187 1 0 1 1 0 0 +EDGE2 4310 3891 -0.0390082 -1.03423 -1.62232 1 0 1 1 0 0 +EDGE2 4310 4131 -0.0421081 -0.98424 -1.53916 1 0 1 1 0 0 +EDGE2 4310 4151 -0.0987061 -1.03358 -1.5797 1 0 1 1 0 0 +EDGE2 4310 4129 0.933856 -0.00426414 -3.10091 1 0 1 1 0 0 +EDGE2 4310 4169 1.00865 -0.00756683 -3.16582 1 0 1 1 0 0 +EDGE2 4311 4230 -0.967787 0.0289714 -1.57478 1 0 1 1 0 0 +EDGE2 4311 4212 0.933071 -0.0252354 -0.0179768 1 0 1 1 0 0 +EDGE2 4311 4232 1.1499 0.0663287 0.0123648 1 0 1 1 0 0 +EDGE2 4311 4172 0.976635 -0.023394 0.0364205 1 0 1 1 0 0 +EDGE2 4311 4171 0.0334196 -0.0282984 -0.0227143 1 0 1 1 0 0 +EDGE2 4311 4211 0.0326225 -0.0548876 -0.00923725 1 0 1 1 0 0 +EDGE2 4311 4231 -0.082494 0.0219945 0.000481093 1 0 1 1 0 0 +EDGE2 4311 4310 -1.0667 0.0820826 -1.51656 1 0 1 1 0 0 +EDGE2 4311 3890 -1.04166 0.0448526 -1.58957 1 0 1 1 0 0 +EDGE2 4311 4150 -1.01648 0.014473 -1.53392 1 0 1 1 0 0 +EDGE2 4311 4170 -1.01729 -0.0644349 1.60674 1 0 1 1 0 0 +EDGE2 4311 4210 -1.03757 0.0673193 -1.58942 1 0 1 1 0 0 +EDGE2 4311 4130 -1.08336 0.0432495 1.54511 1 0 1 1 0 0 +EDGE2 4312 4173 1.02273 -0.0830438 -0.0193099 1 0 1 1 0 0 +EDGE2 4312 4213 0.928051 0.0134275 0.0159924 1 0 1 1 0 0 +EDGE2 4312 4233 0.95608 0.033715 0.0132216 1 0 1 1 0 0 +EDGE2 4312 4311 -1.00631 0.0676381 -0.0298442 1 0 1 1 0 0 +EDGE2 4312 4212 9.35496e-05 0.0407913 -0.0029633 1 0 1 1 0 0 +EDGE2 4312 4232 0.0238236 -0.0352501 -0.00939842 1 0 1 1 0 0 +EDGE2 4312 4172 0.0327153 -0.0628576 0.00576228 1 0 1 1 0 0 +EDGE2 4312 4171 -1.08458 0.0293291 0.0144363 1 0 1 1 0 0 +EDGE2 4312 4211 -1.10243 0.0569292 0.023499 1 0 1 1 0 0 +EDGE2 4312 4231 -1.00982 0.123856 -0.0174202 1 0 1 1 0 0 +EDGE2 4313 4173 -0.067764 0.0392718 0.0426616 1 0 1 1 0 0 +EDGE2 4313 4214 1.01646 0.00502802 -0.00433896 1 0 1 1 0 0 +EDGE2 4313 4234 1.0296 -0.0388336 0.0301109 1 0 1 1 0 0 +EDGE2 4313 4174 0.999871 -0.0061441 0.00336481 1 0 1 1 0 0 +EDGE2 4313 4213 -0.0146828 -0.0352974 0.0233731 1 0 1 1 0 0 +EDGE2 4313 4233 -0.0627272 0.0471229 0.0107995 1 0 1 1 0 0 +EDGE2 4313 4212 -0.96519 -0.0322244 0.00286927 1 0 1 1 0 0 +EDGE2 4313 4232 -1.01952 -0.0279872 -0.00559934 1 0 1 1 0 0 +EDGE2 4313 4312 -1.00177 -0.00262879 0.0201821 1 0 1 1 0 0 +EDGE2 4313 4172 -0.948372 0.0230504 0.0159915 1 0 1 1 0 0 +EDGE2 4314 4295 1.08424 -0.0406884 -3.1633 1 0 1 1 0 0 +EDGE2 4314 4175 0.921263 -0.0258104 -0.000578758 1 0 1 1 0 0 +EDGE2 4314 4215 1.06839 -0.0041245 0.00627083 1 0 1 1 0 0 +EDGE2 4314 4235 0.997252 0.0145292 -0.0249824 1 0 1 1 0 0 +EDGE2 4314 4173 -1.01033 -0.0117234 0.0388629 1 0 1 1 0 0 +EDGE2 4314 4313 -0.933669 0.0961097 0.0194333 1 0 1 1 0 0 +EDGE2 4314 4214 0.128395 -0.0327239 0.0164558 1 0 1 1 0 0 +EDGE2 4314 4234 -0.0454433 0.00487738 -0.00769379 1 0 1 1 0 0 +EDGE2 4314 4174 0.0284065 0.0658361 0.0173989 1 0 1 1 0 0 +EDGE2 4314 4213 -0.952746 -0.0964356 -0.00991249 1 0 1 1 0 0 +EDGE2 4314 4233 -0.984688 0.0273563 -0.010684 1 0 1 1 0 0 +EDGE2 4315 4295 -0.05096 -0.012435 -3.13691 1 0 1 1 0 0 +EDGE2 4315 4294 1.00797 0.0330337 -3.1308 1 0 1 1 0 0 +EDGE2 4315 4296 0.0067653 0.963354 1.5565 1 0 1 1 0 0 +EDGE2 4315 4176 -0.058782 0.909675 1.57002 1 0 1 1 0 0 +EDGE2 4315 4216 -0.0193792 1.04685 1.56818 1 0 1 1 0 0 +EDGE2 4315 4175 0.00410391 -0.00355491 -0.00498524 1 0 1 1 0 0 +EDGE2 4315 4215 -0.024682 -0.044974 -0.00241038 1 0 1 1 0 0 +EDGE2 4315 4235 0.0432021 -0.0146446 0.00704598 1 0 1 1 0 0 +EDGE2 4315 4236 -0.0314209 -1.03833 -1.60084 1 0 1 1 0 0 +EDGE2 4315 4214 -0.950981 0.0420435 0.0140434 1 0 1 1 0 0 +EDGE2 4315 4234 -1.02658 0.00669636 -0.0279263 1 0 1 1 0 0 +EDGE2 4315 4314 -0.989651 -0.0823957 0.0150584 1 0 1 1 0 0 +EDGE2 4315 4174 -1.02606 -0.0597951 0.0119355 1 0 1 1 0 0 +EDGE2 4316 4295 -1.06702 -0.040686 1.54285 1 0 1 1 0 0 +EDGE2 4316 4296 -0.0511701 0.029108 -0.00679482 1 0 1 1 0 0 +EDGE2 4316 4177 1.02175 -0.0032759 -0.0162995 1 0 1 1 0 0 +EDGE2 4316 4217 1.072 0.00123227 0.00188562 1 0 1 1 0 0 +EDGE2 4316 4297 1.05401 0.031311 -0.0174754 1 0 1 1 0 0 +EDGE2 4316 4176 0.0304479 -0.024785 -0.00637372 1 0 1 1 0 0 +EDGE2 4316 4216 -0.00864769 0.0303912 0.00305656 1 0 1 1 0 0 +EDGE2 4316 4315 -0.969585 -0.061225 -1.6075 1 0 1 1 0 0 +EDGE2 4316 4175 -0.998465 -0.0487516 -1.58453 1 0 1 1 0 0 +EDGE2 4316 4215 -1.04561 -0.00583828 -1.58201 1 0 1 1 0 0 +EDGE2 4316 4235 -1.08784 0.0788486 -1.55054 1 0 1 1 0 0 +EDGE2 4317 4178 1.09194 0.0155103 0.025117 1 0 1 1 0 0 +EDGE2 4317 4298 1.03673 0.0276761 0.000998599 1 0 1 1 0 0 +EDGE2 4317 4218 1.03238 0.0129778 -0.0143733 1 0 1 1 0 0 +EDGE2 4317 4296 -1.04601 -0.0322964 0.0190422 1 0 1 1 0 0 +EDGE2 4317 4177 0.0622149 0.0298839 0.00765782 1 0 1 1 0 0 +EDGE2 4317 4217 0.0318176 0.00656916 -0.0056712 1 0 1 1 0 0 +EDGE2 4317 4297 -0.102701 -0.0612322 0.03502 1 0 1 1 0 0 +EDGE2 4317 4316 -0.996551 -0.0303597 0.0223636 1 0 1 1 0 0 +EDGE2 4317 4176 -0.989706 -0.0510194 0.00310585 1 0 1 1 0 0 +EDGE2 4317 4216 -1.06066 0.0324353 0.0129789 1 0 1 1 0 0 +EDGE2 4318 4219 1.09305 0.0265943 -0.0208174 1 0 1 1 0 0 +EDGE2 4318 4299 1.0241 -0.0279639 0.00318225 1 0 1 1 0 0 +EDGE2 4318 4317 -1.0167 -0.0265177 0.0227047 1 0 1 1 0 0 +EDGE2 4318 4178 -0.0542279 0.0907359 -0.00546129 1 0 1 1 0 0 +EDGE2 4318 4298 -0.0460706 -0.0421857 -0.0119378 1 0 1 1 0 0 +EDGE2 4318 4179 1.01339 0.00702919 -0.0266691 1 0 1 1 0 0 +EDGE2 4318 4218 -0.00974165 0.0202548 0.0228624 1 0 1 1 0 0 +EDGE2 4318 4177 -1.0372 -0.0701553 0.00780427 1 0 1 1 0 0 +EDGE2 4318 4217 -0.947125 -0.0438929 0.0429775 1 0 1 1 0 0 +EDGE2 4318 4297 -1.03166 -0.00272734 0.00120259 1 0 1 1 0 0 +EDGE2 4319 4219 0.0239598 0.0105225 0.00940946 1 0 1 1 0 0 +EDGE2 4319 4180 0.949717 -0.0459149 0.000856512 1 0 1 1 0 0 +EDGE2 4319 4300 1.03732 0.0225171 -0.0080287 1 0 1 1 0 0 +EDGE2 4319 4220 1.0338 0.0513295 -0.0401615 1 0 1 1 0 0 +EDGE2 4319 3860 1.00798 0.0360582 -3.12304 1 0 1 1 0 0 +EDGE2 4319 3880 0.980266 -0.00702561 -3.11441 1 0 1 1 0 0 +EDGE2 4319 4299 0.015874 -0.069116 -0.00111707 1 0 1 1 0 0 +EDGE2 4319 4178 -0.96625 0.0374941 0.00711809 1 0 1 1 0 0 +EDGE2 4319 4298 -0.996618 -0.0229271 -0.0356235 1 0 1 1 0 0 +EDGE2 4319 4318 -1.02563 0.0647309 0.0168384 1 0 1 1 0 0 +EDGE2 4319 4179 -0.0082116 0.0547212 0.0070174 1 0 1 1 0 0 +EDGE2 4319 4218 -1.02966 -0.0569905 -0.0146878 1 0 1 1 0 0 +EDGE2 4320 4219 -1.01738 -0.00818924 -0.0153257 1 0 1 1 0 0 +EDGE2 4320 3859 0.990377 -0.0476781 -3.14264 1 0 1 1 0 0 +EDGE2 4320 3879 1.00693 -0.0140245 -3.11285 1 0 1 1 0 0 +EDGE2 4320 3861 -0.0215062 -1.06568 -1.57887 1 0 1 1 0 0 +EDGE2 4320 4180 -0.0115469 -0.0822309 -0.0166873 1 0 1 1 0 0 +EDGE2 4320 4300 0.0252406 -0.00863837 -0.0263255 1 0 1 1 0 0 +EDGE2 4320 4220 0.0385818 0.0178503 -0.0329664 1 0 1 1 0 0 +EDGE2 4320 4319 -1.09013 0.0202182 0.0111089 1 0 1 1 0 0 +EDGE2 4320 3860 0.06705 -0.021897 -3.1468 1 0 1 1 0 0 +EDGE2 4320 3880 -0.00228126 -0.0631604 -3.16414 1 0 1 1 0 0 +EDGE2 4320 4299 -0.95569 -0.0168973 0.0307603 1 0 1 1 0 0 +EDGE2 4320 4179 -0.942139 -0.0155553 0.0328048 1 0 1 1 0 0 +EDGE2 4320 4181 -0.0710604 1.0833 1.55989 1 0 1 1 0 0 +EDGE2 4320 4301 0.0319193 1.00283 1.56844 1 0 1 1 0 0 +EDGE2 4320 4221 0.104073 1.01061 1.55715 1 0 1 1 0 0 +EDGE2 4320 3881 -0.0921075 1.03123 1.55282 1 0 1 1 0 0 +EDGE2 4321 4180 -0.976713 0.0333252 -1.58578 1 0 1 1 0 0 +EDGE2 4321 4300 -1.02998 -0.0264386 -1.55156 1 0 1 1 0 0 +EDGE2 4321 4320 -0.930198 -0.0814558 -1.58408 1 0 1 1 0 0 +EDGE2 4321 4220 -0.999866 -0.023621 -1.58604 1 0 1 1 0 0 +EDGE2 4321 3860 -1.01556 -0.00167031 1.54905 1 0 1 1 0 0 +EDGE2 4321 3880 -0.951963 0.0296798 1.57109 1 0 1 1 0 0 +EDGE2 4321 4182 0.934713 0.0349546 -0.0218742 1 0 1 1 0 0 +EDGE2 4321 4181 -0.101277 0.12293 0.002893 1 0 1 1 0 0 +EDGE2 4321 4301 -0.00615885 0.00370456 -0.0159253 1 0 1 1 0 0 +EDGE2 4321 4221 -0.0310832 -0.0400132 -0.0243472 1 0 1 1 0 0 +EDGE2 4321 4302 1.03737 0.0342945 -0.00898372 1 0 1 1 0 0 +EDGE2 4321 3881 -0.0317877 0.0819289 0.0122189 1 0 1 1 0 0 +EDGE2 4321 4222 1.01797 -0.0675112 0.00466278 1 0 1 1 0 0 +EDGE2 4321 3882 1.01475 0.000355766 0.0214942 1 0 1 1 0 0 +EDGE2 4322 4321 -1.06166 0.000572327 -0.033578 1 0 1 1 0 0 +EDGE2 4322 4182 -0.025388 -0.0391563 0.0201701 1 0 1 1 0 0 +EDGE2 4322 4181 -1.03908 0.0439775 -0.0122079 1 0 1 1 0 0 +EDGE2 4322 4301 -0.919583 0.011373 0.025107 1 0 1 1 0 0 +EDGE2 4322 4221 -1.02678 0.0226257 0.0178062 1 0 1 1 0 0 +EDGE2 4322 4302 -0.0208008 0.0435851 -0.0140404 1 0 1 1 0 0 +EDGE2 4322 3881 -1.03109 -0.0435697 -0.0136628 1 0 1 1 0 0 +EDGE2 4322 4222 0.0810685 -0.0465187 -0.0102989 1 0 1 1 0 0 +EDGE2 4322 4183 1.04255 -0.105499 0.020956 1 0 1 1 0 0 +EDGE2 4322 4303 0.9836 0.00449177 0.0217431 1 0 1 1 0 0 +EDGE2 4322 3882 -0.0547821 0.0144467 0.0490098 1 0 1 1 0 0 +EDGE2 4322 4223 1.00163 -0.0244112 0.0187099 1 0 1 1 0 0 +EDGE2 4322 3883 0.944357 -0.0411689 -0.0024034 1 0 1 1 0 0 +EDGE2 4323 4182 -0.989375 -0.000245966 -0.0128895 1 0 1 1 0 0 +EDGE2 4323 4302 -1.08194 -0.00268534 0.00906459 1 0 1 1 0 0 +EDGE2 4323 4322 -0.980118 0.0834674 -0.0145139 1 0 1 1 0 0 +EDGE2 4323 4222 -1.00205 0.0541591 -0.0104945 1 0 1 1 0 0 +EDGE2 4323 4184 1.0273 0.0110279 -0.00328068 1 0 1 1 0 0 +EDGE2 4323 4183 -0.0146769 0.0495284 0.0043086 1 0 1 1 0 0 +EDGE2 4323 4303 0.0572653 0.059678 0.00766219 1 0 1 1 0 0 +EDGE2 4323 3882 -0.966138 0.0176952 0.0294595 1 0 1 1 0 0 +EDGE2 4323 4223 -0.0595297 -0.0352296 0.0067636 1 0 1 1 0 0 +EDGE2 4323 4304 0.976776 0.0170987 -0.000191662 1 0 1 1 0 0 +EDGE2 4323 3883 -0.0514551 0.0130138 -0.00412827 1 0 1 1 0 0 +EDGE2 4323 4224 0.925142 -0.0839525 -0.000103478 1 0 1 1 0 0 +EDGE2 4323 3884 0.977899 0.020727 -0.0177267 1 0 1 1 0 0 +EDGE2 4324 4184 0.0301987 0.0235586 0.0279053 1 0 1 1 0 0 +EDGE2 4324 4183 -1.0163 0.0508446 0.0113014 1 0 1 1 0 0 +EDGE2 4324 4303 -1.07785 -0.00651782 0.0231765 1 0 1 1 0 0 +EDGE2 4324 4323 -0.953933 -0.0169447 -0.019272 1 0 1 1 0 0 +EDGE2 4324 4223 -0.931343 -0.0170264 -0.0156082 1 0 1 1 0 0 +EDGE2 4324 4304 0.06744 0.0222655 0.00777071 1 0 1 1 0 0 +EDGE2 4324 3883 -1.00516 -0.0103758 0.017532 1 0 1 1 0 0 +EDGE2 4324 4224 0.0405842 0.0158876 -0.00414014 1 0 1 1 0 0 +EDGE2 4324 4205 1.033 0.0259657 -3.13159 1 0 1 1 0 0 +EDGE2 4324 4305 0.989767 0.013574 -0.00929597 1 0 1 1 0 0 +EDGE2 4324 3884 0.0543543 0.0295833 0.0238184 1 0 1 1 0 0 +EDGE2 4324 4225 0.972336 -0.0430092 0.0278876 1 0 1 1 0 0 +EDGE2 4324 3885 1.00142 -0.00889141 0.0572607 1 0 1 1 0 0 +EDGE2 4324 4145 0.962393 -0.0557437 -3.16534 1 0 1 1 0 0 +EDGE2 4324 4185 1.11194 -0.0620652 0.0118212 1 0 1 1 0 0 +EDGE2 4325 4186 -0.0166394 -0.9487 -1.57098 1 0 1 1 0 0 +EDGE2 4325 4226 -0.0481437 1.04125 1.57541 1 0 1 1 0 0 +EDGE2 4325 4184 -0.972389 0.0123311 -0.00142051 1 0 1 1 0 0 +EDGE2 4325 4304 -0.937871 -0.005366 0.0279671 1 0 1 1 0 0 +EDGE2 4325 4324 -0.981418 -0.0482641 0.00984738 1 0 1 1 0 0 +EDGE2 4325 4224 -0.968458 0.00773825 0.010283 1 0 1 1 0 0 +EDGE2 4325 4205 -0.029944 -0.021273 -3.12917 1 0 1 1 0 0 +EDGE2 4325 4305 -0.0244447 0.017102 0.0406751 1 0 1 1 0 0 +EDGE2 4325 3884 -0.951342 0.0265557 0.0162489 1 0 1 1 0 0 +EDGE2 4325 4225 0.064241 -0.0479276 0.035794 1 0 1 1 0 0 +EDGE2 4325 3885 -0.00182103 0.00119744 0.0152185 1 0 1 1 0 0 +EDGE2 4325 4145 -0.047907 -0.0330144 -3.15001 1 0 1 1 0 0 +EDGE2 4325 4185 -0.0619861 -0.0584858 -0.0395081 1 0 1 1 0 0 +EDGE2 4325 4306 -0.0197736 1.04085 1.55279 1 0 1 1 0 0 +EDGE2 4325 3886 -0.0369049 1.10647 1.56366 1 0 1 1 0 0 +EDGE2 4325 4146 0.0133295 0.991812 1.55735 1 0 1 1 0 0 +EDGE2 4325 4206 0.0212651 0.997436 1.57369 1 0 1 1 0 0 +EDGE2 4325 4144 0.918191 0.0242154 -3.15156 1 0 1 1 0 0 +EDGE2 4325 4204 1.00244 -0.00343978 -3.13365 1 0 1 1 0 0 +EDGE2 4326 4187 1.09206 0.0179854 0.00481145 1 0 1 1 0 0 +EDGE2 4326 4186 -0.084057 -0.0293413 -0.00150024 1 0 1 1 0 0 +EDGE2 4326 4205 -1.01383 -0.00504555 -1.54982 1 0 1 1 0 0 +EDGE2 4326 4305 -1.05624 0.0690454 1.55393 1 0 1 1 0 0 +EDGE2 4326 4325 -0.978791 -0.0467936 1.57948 1 0 1 1 0 0 +EDGE2 4326 4225 -1.02668 0.00264514 1.58163 1 0 1 1 0 0 +EDGE2 4326 3885 -1.02599 0.00122804 1.57454 1 0 1 1 0 0 +EDGE2 4326 4145 -0.943466 0.0467262 -1.56311 1 0 1 1 0 0 +EDGE2 4326 4185 -0.991164 -0.00138372 1.60302 1 0 1 1 0 0 +EDGE2 4327 4188 1.01525 0.0618342 -0.0111338 1 0 1 1 0 0 +EDGE2 4327 4326 -1.07653 0.0709698 0.0126138 1 0 1 1 0 0 +EDGE2 4327 4187 0.0130409 0.0462953 0.0174629 1 0 1 1 0 0 +EDGE2 4327 4186 -0.994176 0.0383552 -0.0173277 1 0 1 1 0 0 +EDGE2 4328 4327 -0.964354 -0.056305 0.0195831 1 0 1 1 0 0 +EDGE2 4328 4189 0.994717 0.0794291 0.00794176 1 0 1 1 0 0 +EDGE2 4328 4188 -0.0347292 -0.00662867 0.0174701 1 0 1 1 0 0 +EDGE2 4328 4187 -1.00312 0.0413334 -0.008526 1 0 1 1 0 0 +EDGE2 4329 3850 0.893871 0.11259 -3.08614 1 0 1 1 0 0 +EDGE2 4329 4190 0.989631 0.0129882 0.0218062 1 0 1 1 0 0 +EDGE2 4329 4328 -1.05928 0.00655293 0.00829332 1 0 1 1 0 0 +EDGE2 4329 4189 -0.0180126 0.0802547 0.00207397 1 0 1 1 0 0 +EDGE2 4329 4188 -1.05319 0.00657674 0.0175495 1 0 1 1 0 0 +EDGE2 4330 3851 0.0876571 -0.99016 -1.5795 1 0 1 1 0 0 +EDGE2 4330 3849 0.948393 0.0289865 -3.12578 1 0 1 1 0 0 +EDGE2 4330 3850 0.012009 0.00628055 -3.16641 1 0 1 1 0 0 +EDGE2 4330 4190 0.0409264 0.0641675 0.0141587 1 0 1 1 0 0 +EDGE2 4330 4189 -0.997541 0.0575472 0.0198313 1 0 1 1 0 0 +EDGE2 4330 4329 -1.00391 -0.00236618 0.0446129 1 0 1 1 0 0 +EDGE2 4330 4191 -0.0268149 0.919229 1.53911 1 0 1 1 0 0 +EDGE2 4331 3850 -0.992956 -0.00892552 1.56586 1 0 1 1 0 0 +EDGE2 4331 4190 -1.01088 0.00481644 -1.51513 1 0 1 1 0 0 +EDGE2 4331 4330 -1.10263 0.0637632 -1.57579 1 0 1 1 0 0 +EDGE2 4331 4192 0.95795 0.0386983 0.00389524 1 0 1 1 0 0 +EDGE2 4331 4191 -0.00632175 -0.0295014 0.0129035 1 0 1 1 0 0 +EDGE2 4332 4192 0.0317265 0.0537585 0.0371401 1 0 1 1 0 0 +EDGE2 4332 4191 -0.949146 0.0193655 0.00455963 1 0 1 1 0 0 +EDGE2 4332 4331 -1.02961 -0.0345386 -0.00796627 1 0 1 1 0 0 +EDGE2 4332 4193 1.03337 0.0464116 0.0124681 1 0 1 1 0 0 +EDGE2 4333 4192 -0.981532 0.088097 -0.0232135 1 0 1 1 0 0 +EDGE2 4333 4332 -1.01733 0.0487381 -0.0102247 1 0 1 1 0 0 +EDGE2 4333 4194 0.988002 -0.00678941 0.00157098 1 0 1 1 0 0 +EDGE2 4333 4193 0.0105493 0.0208513 0.0314739 1 0 1 1 0 0 +EDGE2 4334 4194 -0.0361809 -0.0243089 -0.00119555 1 0 1 1 0 0 +EDGE2 4334 4193 -0.962214 0.00278453 0.023823 1 0 1 1 0 0 +EDGE2 4334 4333 -1.04331 -0.0523026 -0.013831 1 0 1 1 0 0 +EDGE2 4334 4195 0.894381 0.046152 0.00643034 1 0 1 1 0 0 +EDGE2 4335 4194 -0.974744 0.0875012 -0.00653287 1 0 1 1 0 0 +EDGE2 4335 4334 -1.00362 -0.031808 0.0160225 1 0 1 1 0 0 +EDGE2 4335 4196 -0.162912 1.01394 1.58051 1 0 1 1 0 0 +EDGE2 4335 4195 0.0333801 0.00816551 0.00877512 1 0 1 1 0 0 +EDGE2 4336 4195 -0.924813 -0.0020509 1.54703 1 0 1 1 0 0 +EDGE2 4336 4335 -1.01641 -0.028549 1.57146 1 0 1 1 0 0 +EDGE2 4337 4336 -1.05793 -0.0206208 -0.00309823 1 0 1 1 0 0 +EDGE2 4338 4337 -0.927638 -0.0186665 0.00469075 1 0 1 1 0 0 +EDGE2 4339 4338 -1.03361 -0.0704482 0.0190275 1 0 1 1 0 0 +EDGE2 4340 4339 -1.07233 0.0452332 0.0161165 1 0 1 1 0 0 +EDGE2 4341 4340 -1.01343 -0.0330421 -1.5658 1 0 1 1 0 0 +EDGE2 4342 4341 -0.961779 -0.00408698 0.0276563 1 0 1 1 0 0 +EDGE2 4343 4342 -1.02553 -0.029824 -0.0276917 1 0 1 1 0 0 +EDGE2 4344 4343 -1.00562 -0.0575115 -0.0256505 1 0 1 1 0 0 +EDGE2 4345 4344 -0.966264 0.0331557 0.0155407 1 0 1 1 0 0 +EDGE2 4346 4345 -0.954129 -0.0600341 1.56962 1 0 1 1 0 0 +EDGE2 4347 4346 -1.04097 -0.00510147 0.0187716 1 0 1 1 0 0 +EDGE2 4348 4347 -0.99153 -0.0232816 0.0421321 1 0 1 1 0 0 +EDGE2 4349 4348 -1.01491 -0.031225 0.0347192 1 0 1 1 0 0 +EDGE2 4350 4349 -1.06111 0.113587 0.00776391 1 0 1 1 0 0 +EDGE2 4351 4350 -0.975314 0.0198329 -1.53916 1 0 1 1 0 0 +EDGE2 4352 4351 -0.945487 0.0116656 0.0234434 1 0 1 1 0 0 +EDGE2 4353 4352 -1.00937 -0.113525 -0.0369992 1 0 1 1 0 0 +EDGE2 4354 4353 -1.05414 -0.0321679 0.0127324 1 0 1 1 0 0 +EDGE2 4355 4354 -1.0465 -0.0147977 -0.00446619 1 0 1 1 0 0 +EDGE2 4356 4355 -1.01678 0.0685081 1.58028 1 0 1 1 0 0 +EDGE2 4357 4356 -0.996229 -0.0660808 -0.00973682 1 0 1 1 0 0 +EDGE2 4358 4357 -0.970297 -0.0768924 -0.00472861 1 0 1 1 0 0 +EDGE2 4359 4358 -1.0032 0.0238365 -0.0253574 1 0 1 1 0 0 +EDGE2 4360 4359 -0.998914 -0.0232282 0.0172108 1 0 1 1 0 0 +EDGE2 4361 4360 -1.02351 -0.119951 1.57559 1 0 1 1 0 0 +EDGE2 4362 4361 -1.00921 -0.0410872 0.0204402 1 0 1 1 0 0 +EDGE2 4363 4362 -1.06241 0.0784309 -0.00275518 1 0 1 1 0 0 +EDGE2 4364 4363 -1.04292 0.0669887 0.00783888 1 0 1 1 0 0 +EDGE2 4365 4364 -1.06377 0.0289033 -0.0175604 1 0 1 1 0 0 +EDGE2 4366 4365 -0.958462 0.0513757 -1.54794 1 0 1 1 0 0 +EDGE2 4367 4366 -0.946509 -0.0433902 -0.0236026 1 0 1 1 0 0 +EDGE2 4368 4367 -0.909685 -0.0525729 -0.0164147 1 0 1 1 0 0 +EDGE2 4369 4368 -0.990015 0.0531988 0.0173973 1 0 1 1 0 0 +EDGE2 4370 4369 -1.07861 -0.0578074 -0.00283571 1 0 1 1 0 0 +EDGE2 4371 4370 -1.04775 0.0318175 -1.57533 1 0 1 1 0 0 +EDGE2 4372 4371 -0.903758 -0.00834634 -0.00142268 1 0 1 1 0 0 +EDGE2 4373 4372 -0.956165 -0.0798055 0.0138943 1 0 1 1 0 0 +EDGE2 4374 4373 -0.981532 0.0913638 -0.0266152 1 0 1 1 0 0 +EDGE2 4375 4374 -0.95286 -0.0482391 0.000562724 1 0 1 1 0 0 +EDGE2 4376 4375 -0.928405 0.0156345 1.54504 1 0 1 1 0 0 +EDGE2 4377 4376 -1.04826 0.085493 0.0118327 1 0 1 1 0 0 +EDGE2 4378 4377 -1.0457 -0.0691623 0.0112357 1 0 1 1 0 0 +EDGE2 4379 4378 -1.01554 0.0261452 0.0277948 1 0 1 1 0 0 +EDGE2 4380 4379 -1.06856 -0.0405608 -0.0215424 1 0 1 1 0 0 +EDGE2 4381 4380 -0.999701 0.159305 1.54268 1 0 1 1 0 0 +EDGE2 4382 4381 -1.01641 -0.0231952 0.00647616 1 0 1 1 0 0 +EDGE2 4383 4382 -0.981933 0.0404394 -0.0263796 1 0 1 1 0 0 +EDGE2 4384 4383 -0.989214 -0.0025548 -0.0179164 1 0 1 1 0 0 +EDGE2 4385 4384 -0.956281 0.0720428 0.0211692 1 0 1 1 0 0 +EDGE2 4386 4385 -0.986022 0.055082 1.58458 1 0 1 1 0 0 +EDGE2 4387 4386 -0.997346 -0.060102 -0.0218017 1 0 1 1 0 0 +EDGE2 4388 4387 -0.993835 0.0201403 0.00118164 1 0 1 1 0 0 +EDGE2 4389 4388 -1.04846 -0.0319513 0.0011435 1 0 1 1 0 0 +EDGE2 4389 4370 0.990178 0.00173071 -3.16927 1 0 1 1 0 0 +EDGE2 4390 4389 -1.04712 0.0270164 -0.020397 1 0 1 1 0 0 +EDGE2 4390 4371 0.0022233 -0.960172 -1.55659 1 0 1 1 0 0 +EDGE2 4390 4370 -0.0653917 0.10569 -3.13661 1 0 1 1 0 0 +EDGE2 4390 4369 1.07102 -0.021628 -3.18177 1 0 1 1 0 0 +EDGE2 4391 4372 1.08611 -0.0820126 0.0293314 1 0 1 1 0 0 +EDGE2 4391 4390 -0.96802 0.04172 1.57348 1 0 1 1 0 0 +EDGE2 4391 4371 -0.00227271 0.0359347 0.0277614 1 0 1 1 0 0 +EDGE2 4391 4370 -0.944991 0.0444642 -1.54895 1 0 1 1 0 0 +EDGE2 4392 4372 -0.0050369 0.0670547 -0.0165023 1 0 1 1 0 0 +EDGE2 4392 4371 -1.10675 -0.0403322 -0.0095331 1 0 1 1 0 0 +EDGE2 4392 4391 -1.01364 0.0640945 0.00119945 1 0 1 1 0 0 +EDGE2 4392 4373 0.970301 -0.00714597 -0.00923849 1 0 1 1 0 0 +EDGE2 4393 4372 -0.98959 -0.0334447 -0.0289963 1 0 1 1 0 0 +EDGE2 4393 4392 -0.965221 0.0354963 -0.00279961 1 0 1 1 0 0 +EDGE2 4393 4373 0.00557198 -0.0610378 0.0159636 1 0 1 1 0 0 +EDGE2 4393 4374 1.05547 0.0767634 -0.0322442 1 0 1 1 0 0 +EDGE2 4394 4375 0.983836 0.0209696 0.0262458 1 0 1 1 0 0 +EDGE2 4394 4393 -1.07016 0.0525412 0.0107289 1 0 1 1 0 0 +EDGE2 4394 4373 -1.00694 -0.0582724 0.00221389 1 0 1 1 0 0 +EDGE2 4394 4374 -0.0870561 0.00688851 -0.00236469 1 0 1 1 0 0 +EDGE2 4395 4375 -0.0442071 -0.0773058 -0.0425206 1 0 1 1 0 0 +EDGE2 4395 4394 -1.00103 0.0479667 -0.013406 1 0 1 1 0 0 +EDGE2 4395 4374 -1.04313 -0.030397 0.0289911 1 0 1 1 0 0 +EDGE2 4395 4376 0.0438795 -1.01043 -1.58597 1 0 1 1 0 0 +EDGE2 4396 4375 -1.07523 -0.0226405 1.62116 1 0 1 1 0 0 +EDGE2 4396 4377 1.03743 -0.0497332 -0.00639323 1 0 1 1 0 0 +EDGE2 4396 4376 -0.00758092 -0.00317252 0.0175275 1 0 1 1 0 0 +EDGE2 4396 4395 -0.954002 0.00474551 1.58848 1 0 1 1 0 0 +EDGE2 4397 4378 1.01226 0.00929998 -0.0240801 1 0 1 1 0 0 +EDGE2 4397 4396 -0.991777 0.0184503 0.0114066 1 0 1 1 0 0 +EDGE2 4397 4377 -0.0199203 -0.0405812 0.0342276 1 0 1 1 0 0 +EDGE2 4397 4376 -1.04794 0.0744434 0.0168401 1 0 1 1 0 0 +EDGE2 4398 4379 0.957376 0.00585881 -0.0256446 1 0 1 1 0 0 +EDGE2 4398 4397 -0.987949 0.00418585 -0.0146776 1 0 1 1 0 0 +EDGE2 4398 4378 0.000656452 0.0284195 -0.00906511 1 0 1 1 0 0 +EDGE2 4398 4377 -1.00203 -0.0484126 -0.0264355 1 0 1 1 0 0 +EDGE2 4399 4380 1.02165 0.0334734 0.0133946 1 0 1 1 0 0 +EDGE2 4399 4379 -0.0163589 -0.00632443 0.00565929 1 0 1 1 0 0 +EDGE2 4399 4378 -0.976723 -0.0343477 0.0168167 1 0 1 1 0 0 +EDGE2 4399 4398 -0.982217 0.0350255 0.0102045 1 0 1 1 0 0 +EDGE2 4400 4381 0.0611046 -0.974154 -1.59344 1 0 1 1 0 0 +EDGE2 4400 4380 0.0350817 0.0010049 -0.0131905 1 0 1 1 0 0 +EDGE2 4400 4399 -1.09557 -0.00159903 0.0276187 1 0 1 1 0 0 +EDGE2 4400 4379 -0.964742 0.0591138 -0.00993084 1 0 1 1 0 0 +EDGE2 4401 4380 -0.983 0.0588266 -1.53988 1 0 1 1 0 0 +EDGE2 4401 4400 -1.03837 0.0898028 -1.59953 1 0 1 1 0 0 +EDGE2 4402 4401 -1.02595 -0.0378172 0.0223666 1 0 1 1 0 0 +EDGE2 4403 4402 -0.993642 -0.108955 0.0234272 1 0 1 1 0 0 +EDGE2 4404 4403 -1.00777 -0.0271981 0.0298959 1 0 1 1 0 0 +EDGE2 4405 4404 -1.00759 -0.0283338 0.00316074 1 0 1 1 0 0 +EDGE2 4406 4405 -1.08275 -0.0396562 -1.61175 1 0 1 1 0 0 +EDGE2 4407 4406 -0.983479 0.0207945 0.0181835 1 0 1 1 0 0 +EDGE2 4408 4407 -1.03293 -0.0681567 -0.0043396 1 0 1 1 0 0 +EDGE2 4409 4408 -1.0308 0.00982915 -0.00667463 1 0 1 1 0 0 +EDGE2 4410 4409 -0.923054 -0.0373294 0.0527794 1 0 1 1 0 0 +EDGE2 4411 4410 -0.976848 -0.00767205 -1.53005 1 0 1 1 0 0 +EDGE2 4412 4411 -1.00628 -0.0716824 -0.0499862 1 0 1 1 0 0 +EDGE2 4413 4412 -1.0129 -0.05458 -0.00347717 1 0 1 1 0 0 +EDGE2 4414 4375 0.966216 0.0605716 -3.16361 1 0 1 1 0 0 +EDGE2 4414 4395 1.00737 -0.0293733 -3.13612 1 0 1 1 0 0 +EDGE2 4414 4413 -0.970297 0.105204 -0.000562871 1 0 1 1 0 0 +EDGE2 4415 4375 -0.0333283 0.000690998 -3.16182 1 0 1 1 0 0 +EDGE2 4415 4394 1.03001 0.0535279 -3.15274 1 0 1 1 0 0 +EDGE2 4415 4374 0.96766 -0.0154799 -3.09951 1 0 1 1 0 0 +EDGE2 4415 4396 0.01619 1.07408 1.57826 1 0 1 1 0 0 +EDGE2 4415 4376 0.000770011 1.1154 1.57898 1 0 1 1 0 0 +EDGE2 4415 4395 0.0441134 -0.0323736 -3.1576 1 0 1 1 0 0 +EDGE2 4415 4414 -0.823751 0.0406979 -0.0699046 1 0 1 1 0 0 +EDGE2 4416 4375 -0.99265 -0.0211336 1.58608 1 0 1 1 0 0 +EDGE2 4416 4397 1.00616 0.00327034 0.00020004 1 0 1 1 0 0 +EDGE2 4416 4396 -0.0400877 0.0970481 -0.0120658 1 0 1 1 0 0 +EDGE2 4416 4377 0.96348 -0.058267 0.0183125 1 0 1 1 0 0 +EDGE2 4416 4376 0.0761521 0.0908151 0.0195736 1 0 1 1 0 0 +EDGE2 4416 4415 -0.995839 -0.0701835 -1.56646 1 0 1 1 0 0 +EDGE2 4416 4395 -1.01868 0.0163046 1.55409 1 0 1 1 0 0 +EDGE2 4417 4397 0.0714449 0.0254924 -0.00589362 1 0 1 1 0 0 +EDGE2 4417 4378 0.964203 -0.0918218 -0.0161476 1 0 1 1 0 0 +EDGE2 4417 4398 0.913912 0.0224453 0.0144251 1 0 1 1 0 0 +EDGE2 4417 4396 -1.02108 0.0335489 -0.0164011 1 0 1 1 0 0 +EDGE2 4417 4416 -0.999426 0.0305793 -0.0422697 1 0 1 1 0 0 +EDGE2 4417 4377 -0.0148887 -0.0103312 0.0127904 1 0 1 1 0 0 +EDGE2 4417 4376 -1.05664 -0.0198277 0.0252668 1 0 1 1 0 0 +EDGE2 4418 4399 1.02911 -0.0315698 -0.0268539 1 0 1 1 0 0 +EDGE2 4418 4379 1.02979 0.0274265 -0.0137195 1 0 1 1 0 0 +EDGE2 4418 4397 -0.990746 -0.00131315 -0.0131229 1 0 1 1 0 0 +EDGE2 4418 4378 0.000795532 0.00351348 -0.0125776 1 0 1 1 0 0 +EDGE2 4418 4398 0.0149832 -0.0234668 0.0285793 1 0 1 1 0 0 +EDGE2 4418 4417 -1.03297 0.0302417 -0.0479608 1 0 1 1 0 0 +EDGE2 4418 4377 -0.964443 0.0661801 -0.0273227 1 0 1 1 0 0 +EDGE2 4419 4380 0.887716 0.0337106 -0.0277263 1 0 1 1 0 0 +EDGE2 4419 4400 1.01396 -0.038693 0.00299237 1 0 1 1 0 0 +EDGE2 4419 4399 -0.0270666 -0.0398382 -0.0263989 1 0 1 1 0 0 +EDGE2 4419 4379 0.00588552 -0.00586125 0.00966185 1 0 1 1 0 0 +EDGE2 4419 4378 -0.944558 -0.0136279 -0.00910958 1 0 1 1 0 0 +EDGE2 4419 4398 -1.06078 -0.096014 -0.0455267 1 0 1 1 0 0 +EDGE2 4419 4418 -0.993107 -0.108839 0.0348007 1 0 1 1 0 0 +EDGE2 4420 4381 -0.038048 -0.961415 -1.57708 1 0 1 1 0 0 +EDGE2 4420 4380 -0.00850941 -0.110489 0.0234204 1 0 1 1 0 0 +EDGE2 4420 4400 -0.0432104 -0.0229025 0.00934987 1 0 1 1 0 0 +EDGE2 4420 4401 -0.0423969 1.00222 1.57412 1 0 1 1 0 0 +EDGE2 4420 4399 -0.9367 -0.163595 -0.0270312 1 0 1 1 0 0 +EDGE2 4420 4419 -1.06272 -0.0677209 0.00614693 1 0 1 1 0 0 +EDGE2 4420 4379 -1.05453 0.0286204 0.0262115 1 0 1 1 0 0 +EDGE2 4421 4380 -0.960086 -0.000520536 -1.57156 1 0 1 1 0 0 +EDGE2 4421 4420 -1.04554 -0.00862638 -1.57796 1 0 1 1 0 0 +EDGE2 4421 4400 -0.979407 0.0337191 -1.59932 1 0 1 1 0 0 +EDGE2 4421 4401 -0.0212919 0.0292054 0.0132089 1 0 1 1 0 0 +EDGE2 4421 4402 0.900377 -0.0250729 0.0116922 1 0 1 1 0 0 +EDGE2 4422 4401 -1.0048 0.0111635 -0.00970099 1 0 1 1 0 0 +EDGE2 4422 4421 -1.04603 -0.0451639 0.0217399 1 0 1 1 0 0 +EDGE2 4422 4402 -0.0509044 0.0533031 -0.0119538 1 0 1 1 0 0 +EDGE2 4422 4403 0.925005 0.0147373 0.0275931 1 0 1 1 0 0 +EDGE2 4423 4422 -1.05147 -0.0140831 0.00309357 1 0 1 1 0 0 +EDGE2 4423 4402 -1.00963 0.0377203 -0.0151375 1 0 1 1 0 0 +EDGE2 4423 4404 1.01658 0.0636887 -0.02089 1 0 1 1 0 0 +EDGE2 4423 4403 -0.0275423 0.0651537 0.0129632 1 0 1 1 0 0 +EDGE2 4424 4404 -0.0488915 -0.021723 -0.0113302 1 0 1 1 0 0 +EDGE2 4424 4403 -1.00197 0.0718656 0.015317 1 0 1 1 0 0 +EDGE2 4424 4423 -1.08907 -0.0676991 0.0182486 1 0 1 1 0 0 +EDGE2 4424 4405 0.90545 0.00994333 -0.0558154 1 0 1 1 0 0 +EDGE2 4425 4406 0.0554473 0.884284 1.55833 1 0 1 1 0 0 +EDGE2 4425 4404 -0.908256 -0.0108909 -0.0195408 1 0 1 1 0 0 +EDGE2 4425 4424 -0.977141 0.0307591 -0.00831808 1 0 1 1 0 0 +EDGE2 4425 4405 0.0544331 -0.0060355 0.0144221 1 0 1 1 0 0 +EDGE2 4426 4406 0.0586312 0.0140357 0.0151557 1 0 1 1 0 0 +EDGE2 4426 4405 -1.01554 0.0338126 -1.54388 1 0 1 1 0 0 +EDGE2 4426 4425 -0.997234 -0.000338181 -1.59123 1 0 1 1 0 0 +EDGE2 4426 4407 1.08061 0.0169919 -0.0042188 1 0 1 1 0 0 +EDGE2 4427 4406 -0.951508 -0.00612299 0.0231871 1 0 1 1 0 0 +EDGE2 4427 4426 -1.08233 -0.0036387 0.0108574 1 0 1 1 0 0 +EDGE2 4427 4407 -0.0614858 -0.0345596 0.00592073 1 0 1 1 0 0 +EDGE2 4427 4408 0.946145 0.0719528 0.0377149 1 0 1 1 0 0 +EDGE2 4428 4407 -0.956408 0.000946345 -0.01498 1 0 1 1 0 0 +EDGE2 4428 4427 -1.01651 0.0173166 0.039421 1 0 1 1 0 0 +EDGE2 4428 4408 0.0203117 0.0140571 -0.010447 1 0 1 1 0 0 +EDGE2 4428 4409 1.03961 0.00467706 0.0072449 1 0 1 1 0 0 +EDGE2 4429 4428 -0.943188 -0.00401911 0.0124907 1 0 1 1 0 0 +EDGE2 4429 4408 -0.999506 0.00267 0.00260157 1 0 1 1 0 0 +EDGE2 4429 4409 -0.0222006 -0.00462725 -0.00832778 1 0 1 1 0 0 +EDGE2 4429 4410 1.01611 0.0295971 0.0381036 1 0 1 1 0 0 +EDGE2 4430 4429 -1.03056 -0.0378753 -0.000312466 1 0 1 1 0 0 +EDGE2 4430 4409 -0.999541 -0.00172545 -0.0385947 1 0 1 1 0 0 +EDGE2 4430 4411 0.0494533 0.927897 1.57868 1 0 1 1 0 0 +EDGE2 4430 4410 0.000777877 -0.0181418 0.00351869 1 0 1 1 0 0 +EDGE2 4431 4412 0.930076 0.0395962 0.020315 1 0 1 1 0 0 +EDGE2 4431 4430 -0.995313 -0.0354973 -1.60414 1 0 1 1 0 0 +EDGE2 4431 4411 -0.091719 0.0317426 0.0273502 1 0 1 1 0 0 +EDGE2 4431 4410 -0.978072 -0.0520126 -1.57398 1 0 1 1 0 0 +EDGE2 4432 4412 0.0278718 0.0241752 -0.0283184 1 0 1 1 0 0 +EDGE2 4432 4413 0.966947 0.0763861 0.0034922 1 0 1 1 0 0 +EDGE2 4432 4411 -1.02123 -0.0109282 -0.0258056 1 0 1 1 0 0 +EDGE2 4432 4431 -0.933434 0.017317 -0.0166062 1 0 1 1 0 0 +EDGE2 4433 4412 -0.98313 0.0163124 -0.00307127 1 0 1 1 0 0 +EDGE2 4433 4413 -0.00304159 -0.056294 0.00958354 1 0 1 1 0 0 +EDGE2 4433 4414 1.0003 0.0371019 0.0249337 1 0 1 1 0 0 +EDGE2 4433 4432 -0.984268 -0.0444801 -0.0334524 1 0 1 1 0 0 +EDGE2 4434 4375 0.970646 -0.00180308 -3.13357 1 0 1 1 0 0 +EDGE2 4434 4415 0.997042 -0.0081325 -0.00775508 1 0 1 1 0 0 +EDGE2 4434 4395 1.06372 -0.0313462 -3.16465 1 0 1 1 0 0 +EDGE2 4434 4413 -0.953145 0.0251143 -0.0124312 1 0 1 1 0 0 +EDGE2 4434 4433 -0.977662 -0.00774124 0.00284308 1 0 1 1 0 0 +EDGE2 4434 4414 0.00265362 -0.0385916 0.0165694 1 0 1 1 0 0 +EDGE2 4435 4375 -0.012045 -0.124598 -3.12804 1 0 1 1 0 0 +EDGE2 4435 4394 1.00889 -0.0468099 -3.15789 1 0 1 1 0 0 +EDGE2 4435 4374 1.02773 -0.059858 -3.11344 1 0 1 1 0 0 +EDGE2 4435 4396 0.0633317 1.0249 1.57384 1 0 1 1 0 0 +EDGE2 4435 4416 -0.0116873 1.03409 1.54669 1 0 1 1 0 0 +EDGE2 4435 4376 0.0345875 1.02926 1.54047 1 0 1 1 0 0 +EDGE2 4435 4415 -0.0865454 0.0195311 0.00993937 1 0 1 1 0 0 +EDGE2 4435 4395 -0.0495527 -0.0366305 -3.14837 1 0 1 1 0 0 +EDGE2 4435 4434 -1.07211 -0.0330582 0.0334503 1 0 1 1 0 0 +EDGE2 4435 4414 -1.00286 -0.00756279 0.00697148 1 0 1 1 0 0 +EDGE2 4436 4375 -0.931231 -0.0667104 -1.58058 1 0 1 1 0 0 +EDGE2 4436 4435 -1.04409 0.00320678 1.57427 1 0 1 1 0 0 +EDGE2 4436 4415 -1.00175 -0.00922413 1.55903 1 0 1 1 0 0 +EDGE2 4436 4395 -0.977011 -0.032697 -1.57501 1 0 1 1 0 0 +EDGE2 4437 4436 -1.0165 -0.059277 0.0167645 1 0 1 1 0 0 +EDGE2 4438 4437 -0.936976 0.0515946 -0.021121 1 0 1 1 0 0 +EDGE2 4439 4438 -0.964951 0.0883335 -0.0128939 1 0 1 1 0 0 +EDGE2 4439 4360 0.946099 -0.0346272 -3.13246 1 0 1 1 0 0 +EDGE2 4440 4439 -0.954322 -0.0407022 0.00947365 1 0 1 1 0 0 +EDGE2 4440 4361 -0.0282928 1.01414 1.58334 1 0 1 1 0 0 +EDGE2 4440 4359 1.05704 0.00150002 -3.1515 1 0 1 1 0 0 +EDGE2 4440 4360 0.0294694 0.0231276 -3.14136 1 0 1 1 0 0 +EDGE2 4441 4440 -1.00584 -0.0539729 -1.55255 1 0 1 1 0 0 +EDGE2 4441 4362 1.00268 -0.00246939 0.0229724 1 0 1 1 0 0 +EDGE2 4441 4361 -0.0120708 0.034364 0.0315799 1 0 1 1 0 0 +EDGE2 4441 4360 -1.00322 -0.00601471 1.59117 1 0 1 1 0 0 +EDGE2 4442 4363 0.972102 0.0111887 0.00278237 1 0 1 1 0 0 +EDGE2 4442 4441 -1.00946 0.0260816 0.008767 1 0 1 1 0 0 +EDGE2 4442 4362 0.0190512 0.0812421 -0.0313351 1 0 1 1 0 0 +EDGE2 4442 4361 -0.982279 -0.0368737 0.00818475 1 0 1 1 0 0 +EDGE2 4443 4363 -0.0799443 -0.0575661 -0.00305875 1 0 1 1 0 0 +EDGE2 4443 4364 0.87812 -0.0346176 -0.00731313 1 0 1 1 0 0 +EDGE2 4443 4362 -0.959204 -0.0251158 0.00689982 1 0 1 1 0 0 +EDGE2 4443 4442 -0.888198 -0.0271229 -0.0391522 1 0 1 1 0 0 +EDGE2 4444 4363 -0.923032 0.028387 -0.00963741 1 0 1 1 0 0 +EDGE2 4444 4364 -0.0153194 -0.0704986 -0.0114067 1 0 1 1 0 0 +EDGE2 4444 4365 0.90562 0.00667492 0.00545148 1 0 1 1 0 0 +EDGE2 4444 4443 -0.995199 -0.0159808 -0.00571818 1 0 1 1 0 0 +EDGE2 4445 4366 -0.00361971 0.933796 1.57874 1 0 1 1 0 0 +EDGE2 4445 4364 -1.05841 -0.0699732 -0.00612978 1 0 1 1 0 0 +EDGE2 4445 4444 -1.0102 -0.0234464 0.00958663 1 0 1 1 0 0 +EDGE2 4445 4365 0.0580426 -0.0822161 0.0367614 1 0 1 1 0 0 +EDGE2 4446 4445 -1.01265 0.0238251 1.59358 1 0 1 1 0 0 +EDGE2 4446 4365 -1.00963 0.0348452 1.5845 1 0 1 1 0 0 +EDGE2 4447 4446 -1.04637 -0.000134086 0.0475058 1 0 1 1 0 0 +EDGE2 4448 4447 -0.956125 0.00217284 0.00832448 1 0 1 1 0 0 +EDGE2 4449 4448 -0.94926 -0.0538107 0.00998547 1 0 1 1 0 0 +EDGE2 4449 4350 1.0145 -0.00255103 -3.12027 1 0 1 1 0 0 +EDGE2 4450 4349 1.04975 -0.0753593 -3.10608 1 0 1 1 0 0 +EDGE2 4450 4449 -1.01808 -0.0817564 0.00818847 1 0 1 1 0 0 +EDGE2 4450 4351 0.0537667 -0.96224 -1.57454 1 0 1 1 0 0 +EDGE2 4450 4350 0.0382893 0.00547186 -3.10687 1 0 1 1 0 0 +EDGE2 4451 4450 -0.951536 -0.0116544 1.59117 1 0 1 1 0 0 +EDGE2 4451 4351 -0.00244937 0.0283305 -0.000493522 1 0 1 1 0 0 +EDGE2 4451 4350 -1.0363 0.0328463 -1.61284 1 0 1 1 0 0 +EDGE2 4451 4352 1.16425 -0.0637972 -0.00784369 1 0 1 1 0 0 +EDGE2 4452 4351 -1.0162 -0.0223944 -0.0386762 1 0 1 1 0 0 +EDGE2 4452 4451 -1.01724 -0.0145533 0.0137655 1 0 1 1 0 0 +EDGE2 4452 4353 1.02517 0.0888245 0.0080312 1 0 1 1 0 0 +EDGE2 4452 4352 0.101799 0.0376262 0.00246825 1 0 1 1 0 0 +EDGE2 4453 4452 -0.954828 0.050881 0.022888 1 0 1 1 0 0 +EDGE2 4453 4353 -0.113928 -0.032805 0.0366227 1 0 1 1 0 0 +EDGE2 4453 4352 -1.08358 0.021554 0.00872935 1 0 1 1 0 0 +EDGE2 4453 4354 0.97557 -0.0236115 0.00377482 1 0 1 1 0 0 +EDGE2 4454 4353 -1.04408 -0.0363178 -0.00126993 1 0 1 1 0 0 +EDGE2 4454 4453 -0.965837 -0.078155 0.0145412 1 0 1 1 0 0 +EDGE2 4454 4354 -0.0265776 -0.0151858 0.00892253 1 0 1 1 0 0 +EDGE2 4454 4355 1.02034 -0.0108455 -0.00444123 1 0 1 1 0 0 +EDGE2 4455 4356 -0.0414837 -1.01566 -1.52699 1 0 1 1 0 0 +EDGE2 4455 4354 -0.997373 0.0591692 0.0030153 1 0 1 1 0 0 +EDGE2 4455 4454 -1.05327 0.0559905 0.00432892 1 0 1 1 0 0 +EDGE2 4455 4355 -0.109432 0.0105582 0.0138084 1 0 1 1 0 0 +EDGE2 4456 4455 -1.05571 0.073643 -1.58233 1 0 1 1 0 0 +EDGE2 4456 4355 -0.989369 0.0393421 -1.53736 1 0 1 1 0 0 +EDGE2 4457 4456 -1.04543 -0.0163008 0.0133423 1 0 1 1 0 0 +EDGE2 4458 4457 -0.943771 0.046113 -0.0233985 1 0 1 1 0 0 +EDGE2 4459 4458 -1.05663 -0.00832631 -0.0046582 1 0 1 1 0 0 +EDGE2 4460 4459 -1.03398 0.0124334 0.0186751 1 0 1 1 0 0 +EDGE2 4461 4460 -0.999258 -0.0779802 -1.55695 1 0 1 1 0 0 +EDGE2 4462 4461 -0.980003 0.0891174 0.0207786 1 0 1 1 0 0 +EDGE2 4463 4462 -1.04064 -0.0199237 -0.0228535 1 0 1 1 0 0 +EDGE2 4464 4345 1.01242 -0.0258831 -3.12965 1 0 1 1 0 0 +EDGE2 4464 4463 -1.14521 0.0375552 0.0214126 1 0 1 1 0 0 +EDGE2 4465 4464 -0.977597 0.0453874 -0.00348325 1 0 1 1 0 0 +EDGE2 4465 4346 0.148268 0.959585 1.53426 1 0 1 1 0 0 +EDGE2 4465 4344 0.993233 -0.0338872 -3.09573 1 0 1 1 0 0 +EDGE2 4465 4345 0.0225913 0.0152216 -3.13375 1 0 1 1 0 0 +EDGE2 4466 4347 1.08696 -0.0440935 -0.00670443 1 0 1 1 0 0 +EDGE2 4466 4465 -1.06542 0.0342957 -1.54387 1 0 1 1 0 0 +EDGE2 4466 4346 -0.046467 0.0585465 -0.00917482 1 0 1 1 0 0 +EDGE2 4466 4345 -0.922406 0.00446377 1.56085 1 0 1 1 0 0 +EDGE2 4467 4466 -1.0855 -0.0449016 0.0142944 1 0 1 1 0 0 +EDGE2 4467 4348 1.06667 -0.0527703 0.0213769 1 0 1 1 0 0 +EDGE2 4467 4347 0.0222937 0.0448518 0.0601786 1 0 1 1 0 0 +EDGE2 4467 4346 -1.07231 0.0368931 -0.0165777 1 0 1 1 0 0 +EDGE2 4468 4349 0.967149 -0.0461899 -0.00772255 1 0 1 1 0 0 +EDGE2 4468 4467 -1.0445 0.0637093 -0.00187405 1 0 1 1 0 0 +EDGE2 4468 4348 -0.00538069 -0.102653 0.0102553 1 0 1 1 0 0 +EDGE2 4468 4347 -1.03787 -0.0553337 0.0088456 1 0 1 1 0 0 +EDGE2 4469 4349 -0.129545 0.0443907 -0.00340312 1 0 1 1 0 0 +EDGE2 4469 4450 0.995821 0.036506 -3.15071 1 0 1 1 0 0 +EDGE2 4469 4350 0.981555 -0.00883477 -0.0329231 1 0 1 1 0 0 +EDGE2 4469 4348 -1.02325 0.0714131 -0.0194995 1 0 1 1 0 0 +EDGE2 4469 4468 -1.01209 0.0272018 -0.0209489 1 0 1 1 0 0 +EDGE2 4470 4349 -1.02337 -0.02867 0.0221085 1 0 1 1 0 0 +EDGE2 4470 4450 -0.055958 0.00865045 -3.14437 1 0 1 1 0 0 +EDGE2 4470 4449 0.9536 0.0113531 -3.15194 1 0 1 1 0 0 +EDGE2 4470 4351 -0.0223176 1.14441 1.54662 1 0 1 1 0 0 +EDGE2 4470 4451 0.0389663 0.925185 1.5438 1 0 1 1 0 0 +EDGE2 4470 4350 0.00195869 -0.0639304 -0.0316808 1 0 1 1 0 0 +EDGE2 4470 4469 -0.961803 -0.00797197 -0.000190634 1 0 1 1 0 0 +EDGE2 4471 4450 -0.950546 0.0195062 -1.61997 1 0 1 1 0 0 +EDGE2 4471 4470 -1.02805 0.0436217 1.54453 1 0 1 1 0 0 +EDGE2 4471 4350 -0.953097 -0.0545732 1.60551 1 0 1 1 0 0 +EDGE2 4472 4471 -1.04002 0.0860318 -0.0101153 1 0 1 1 0 0 +EDGE2 4473 4472 -1.02525 -0.0290515 -0.0278446 1 0 1 1 0 0 +EDGE2 4474 4473 -0.975259 0.0193166 -0.0013048 1 0 1 1 0 0 +EDGE2 4475 4474 -1.01874 -0.00651044 0.00979893 1 0 1 1 0 0 +EDGE2 4476 4475 -0.928918 -0.125254 -1.57538 1 0 1 1 0 0 +EDGE2 4477 4476 -0.954174 -0.0344415 -0.0365312 1 0 1 1 0 0 +EDGE2 4478 4477 -0.974001 0.0594676 0.041037 1 0 1 1 0 0 +EDGE2 4479 4478 -0.991245 0.0401376 -0.00428872 1 0 1 1 0 0 +EDGE2 4480 4479 -0.950331 -0.0116423 0.032542 1 0 1 1 0 0 +EDGE2 4481 4480 -0.975558 -0.0657327 -1.576 1 0 1 1 0 0 +EDGE2 4482 4481 -1.03971 -0.018632 -0.00213976 1 0 1 1 0 0 +EDGE2 4483 4482 -0.916821 0.0666629 0.00162887 1 0 1 1 0 0 +EDGE2 4484 4483 -0.990526 0.0325422 0.0265837 1 0 1 1 0 0 +EDGE2 4484 4445 0.948442 0.00066724 -3.11748 1 0 1 1 0 0 +EDGE2 4484 4365 1.00485 -0.0119001 -3.09278 1 0 1 1 0 0 +EDGE2 4485 4484 -1.12414 -0.0781462 -0.00492717 1 0 1 1 0 0 +EDGE2 4485 4445 -0.0230455 -0.0501362 -3.16708 1 0 1 1 0 0 +EDGE2 4485 4366 -0.0344962 -0.966158 -1.58573 1 0 1 1 0 0 +EDGE2 4485 4364 1.07139 -0.0731297 -3.11537 1 0 1 1 0 0 +EDGE2 4485 4444 0.959397 0.0316975 -3.09466 1 0 1 1 0 0 +EDGE2 4485 4365 -0.0661715 -0.0328771 -3.12238 1 0 1 1 0 0 +EDGE2 4485 4446 0.023338 1.00175 1.59627 1 0 1 1 0 0 +EDGE2 4486 4445 -1.03299 -0.0603452 1.58461 1 0 1 1 0 0 +EDGE2 4486 4485 -0.923389 0.0402729 -1.55108 1 0 1 1 0 0 +EDGE2 4486 4365 -0.992705 0.057451 1.58708 1 0 1 1 0 0 +EDGE2 4486 4447 1.00239 0.032294 0.00724829 1 0 1 1 0 0 +EDGE2 4486 4446 -0.0240202 -0.00215866 -0.0111155 1 0 1 1 0 0 +EDGE2 4487 4448 1.06323 0.0317336 0.0279051 1 0 1 1 0 0 +EDGE2 4487 4486 -0.996227 -0.00047824 0.0292196 1 0 1 1 0 0 +EDGE2 4487 4447 -0.0229138 -0.00670363 -0.00536618 1 0 1 1 0 0 +EDGE2 4487 4446 -1.08494 0.128052 0.0108608 1 0 1 1 0 0 +EDGE2 4488 4448 -0.11439 0.105915 0.0240659 1 0 1 1 0 0 +EDGE2 4488 4447 -0.936447 -0.0513531 -0.0186104 1 0 1 1 0 0 +EDGE2 4488 4487 -1.01599 0.127014 -0.00178427 1 0 1 1 0 0 +EDGE2 4488 4449 1.08012 -0.0712714 -0.0168488 1 0 1 1 0 0 +EDGE2 4489 4448 -1.05693 -0.00549592 -0.0244429 1 0 1 1 0 0 +EDGE2 4489 4488 -0.97148 -0.085888 -0.0103295 1 0 1 1 0 0 +EDGE2 4489 4450 1.05162 0.0263215 0.0154375 1 0 1 1 0 0 +EDGE2 4489 4449 -0.051751 0.00990396 -0.0308398 1 0 1 1 0 0 +EDGE2 4489 4470 1.02416 0.0461977 -3.14662 1 0 1 1 0 0 +EDGE2 4489 4350 1.0578 -0.0228694 -3.14901 1 0 1 1 0 0 +EDGE2 4490 4471 0.0661214 1.0148 1.59245 1 0 1 1 0 0 +EDGE2 4490 4349 1.02389 -0.0799686 -3.12149 1 0 1 1 0 0 +EDGE2 4490 4450 -0.0317642 -0.0389707 0.0211622 1 0 1 1 0 0 +EDGE2 4490 4449 -1.0729 -0.0751352 -0.0222105 1 0 1 1 0 0 +EDGE2 4490 4489 -1.07554 0.0259911 -0.0288957 1 0 1 1 0 0 +EDGE2 4490 4470 -0.0161155 -0.0406744 -3.11637 1 0 1 1 0 0 +EDGE2 4490 4351 0.0336434 -0.92642 -1.57991 1 0 1 1 0 0 +EDGE2 4490 4451 -0.0260501 -0.965799 -1.57623 1 0 1 1 0 0 +EDGE2 4490 4350 -0.0324345 0.0273367 -3.11992 1 0 1 1 0 0 +EDGE2 4490 4469 0.954536 0.0382204 -3.13043 1 0 1 1 0 0 +EDGE2 4491 4471 -0.0402363 -0.0641095 0.0020574 1 0 1 1 0 0 +EDGE2 4491 4472 0.988744 0.00208459 -0.0185477 1 0 1 1 0 0 +EDGE2 4491 4450 -0.929843 0.0329627 -1.603 1 0 1 1 0 0 +EDGE2 4491 4490 -1.02013 0.00610815 -1.61223 1 0 1 1 0 0 +EDGE2 4491 4470 -1.02029 0.0279933 1.56884 1 0 1 1 0 0 +EDGE2 4491 4350 -0.904385 -0.0178738 1.5767 1 0 1 1 0 0 +EDGE2 4492 4471 -1.00909 0.00306228 -0.00354848 1 0 1 1 0 0 +EDGE2 4492 4472 -0.0583364 0.0715148 0.00738194 1 0 1 1 0 0 +EDGE2 4492 4473 0.884891 0.0534146 -0.0440848 1 0 1 1 0 0 +EDGE2 4492 4491 -1.08433 -0.130942 -0.00965165 1 0 1 1 0 0 +EDGE2 4493 4474 1.03544 0.00113571 0.0162134 1 0 1 1 0 0 +EDGE2 4493 4472 -0.854719 -0.0564973 -0.00719226 1 0 1 1 0 0 +EDGE2 4493 4492 -0.97948 0.0310608 -0.00647291 1 0 1 1 0 0 +EDGE2 4493 4473 -0.00947943 -0.0597335 0.0101253 1 0 1 1 0 0 +EDGE2 4494 4475 0.961239 -0.000925855 -0.00370431 1 0 1 1 0 0 +EDGE2 4494 4493 -0.948664 0.0173681 -0.0245148 1 0 1 1 0 0 +EDGE2 4494 4474 0.063778 0.0867247 -0.0142111 1 0 1 1 0 0 +EDGE2 4494 4473 -1.06631 -0.000391919 -0.00319042 1 0 1 1 0 0 +EDGE2 4495 4494 -1.00441 0.0875073 -0.0427147 1 0 1 1 0 0 +EDGE2 4495 4475 -0.0370028 0.0959513 0.0200435 1 0 1 1 0 0 +EDGE2 4495 4476 0.0575356 0.96908 1.58778 1 0 1 1 0 0 +EDGE2 4495 4474 -1.03905 -0.0034084 0.0104849 1 0 1 1 0 0 +EDGE2 4496 4475 -1.00726 0.0016713 1.59842 1 0 1 1 0 0 +EDGE2 4496 4495 -0.94758 0.0388824 1.59849 1 0 1 1 0 0 +EDGE2 4497 4496 -1.0028 -0.00878475 0.00556758 1 0 1 1 0 0 +EDGE2 4498 4497 -1.00826 0.0135262 -0.0115568 1 0 1 1 0 0 +EDGE2 4499 4498 -1.05442 -0.00694101 0.00609984 1 0 1 1 0 0 +EDGE2 4499 4340 1.02436 -0.039398 -3.15133 1 0 1 1 0 0 +EDGE2 4500 4499 -1.02044 0.0551708 -0.00598303 1 0 1 1 0 0 +EDGE2 4500 4339 1.04753 0.00436781 -3.13073 1 0 1 1 0 0 +EDGE2 4500 4341 -0.0407212 -1.09587 -1.63176 1 0 1 1 0 0 +EDGE2 4500 4340 0.0827363 0.069112 -3.16 1 0 1 1 0 0 +EDGE2 4501 4500 -0.99459 -0.0635453 -1.5613 1 0 1 1 0 0 +EDGE2 4501 4340 -1.08769 0.0227277 1.58092 1 0 1 1 0 0 +EDGE2 4502 4501 -1.02306 -0.0603327 0.0130901 1 0 1 1 0 0 +EDGE2 4503 4502 -0.959659 -0.0548187 -0.0123426 1 0 1 1 0 0 +EDGE2 4504 3845 0.922969 -0.0402187 -3.12157 1 0 1 1 0 0 +EDGE2 4504 4503 -0.944973 -0.00364872 0.0573695 1 0 1 1 0 0 +EDGE2 4505 3844 0.996129 0.0200259 -3.15578 1 0 1 1 0 0 +EDGE2 4505 3846 0.0396531 -0.953065 -1.5717 1 0 1 1 0 0 +EDGE2 4505 3845 0.0146568 -0.0160777 -3.14792 1 0 1 1 0 0 +EDGE2 4505 4504 -0.955504 0.0100789 0.0113862 1 0 1 1 0 0 +EDGE2 4506 4505 -0.935695 -0.0251779 1.54645 1 0 1 1 0 0 +EDGE2 4506 3847 1.01519 -0.0346173 -0.0104108 1 0 1 1 0 0 +EDGE2 4506 3846 0.0550555 -0.0252302 0.0170585 1 0 1 1 0 0 +EDGE2 4506 3845 -1.06067 0.00994295 -1.55646 1 0 1 1 0 0 +EDGE2 4507 3847 -0.0322039 0.0952189 -0.0106922 1 0 1 1 0 0 +EDGE2 4507 3846 -1.00227 0.00122396 -0.0569963 1 0 1 1 0 0 +EDGE2 4507 4506 -0.970442 0.0195484 -0.0335002 1 0 1 1 0 0 +EDGE2 4507 3848 0.927234 -0.0234202 -0.0256027 1 0 1 1 0 0 +EDGE2 4508 3847 -1.0199 0.017427 0.0038463 1 0 1 1 0 0 +EDGE2 4508 4507 -1.00577 -0.0607406 0.0227547 1 0 1 1 0 0 +EDGE2 4508 3848 0.0124088 0.00234631 -0.0113102 1 0 1 1 0 0 +EDGE2 4508 3849 1.03659 -0.00319958 -0.00226634 1 0 1 1 0 0 +EDGE2 4509 3848 -1.09226 0.0644904 0.0209914 1 0 1 1 0 0 +EDGE2 4509 4508 -1.09854 0.00615697 -0.00115548 1 0 1 1 0 0 +EDGE2 4509 3849 0.0242439 0.00712809 0.0234464 1 0 1 1 0 0 +EDGE2 4509 3850 1.00731 -0.0309891 -0.0106774 1 0 1 1 0 0 +EDGE2 4509 4190 0.983716 -0.00924934 -3.15794 1 0 1 1 0 0 +EDGE2 4509 4330 1.0028 0.0631671 -3.13432 1 0 1 1 0 0 +EDGE2 4510 3851 -0.030371 1.05998 1.57788 1 0 1 1 0 0 +EDGE2 4510 4509 -1.03028 0.0610577 0.00914757 1 0 1 1 0 0 +EDGE2 4510 3849 -0.871281 0.0875693 0.00964138 1 0 1 1 0 0 +EDGE2 4510 3850 0.0560513 -0.000520445 0.00904391 1 0 1 1 0 0 +EDGE2 4510 4190 0.0220179 -0.041076 -3.11577 1 0 1 1 0 0 +EDGE2 4510 4330 0.0232976 0.058908 -3.10288 1 0 1 1 0 0 +EDGE2 4510 4189 1.06597 0.0164536 -3.18122 1 0 1 1 0 0 +EDGE2 4510 4329 0.932555 0.0152794 -3.14723 1 0 1 1 0 0 +EDGE2 4510 4191 0.023512 -1.03126 -1.58085 1 0 1 1 0 0 +EDGE2 4510 4331 -0.0216512 -0.966218 -1.55244 1 0 1 1 0 0 +EDGE2 4511 4510 -0.961818 -0.045127 -1.58077 1 0 1 1 0 0 +EDGE2 4511 3852 0.978629 0.0331087 -0.012076 1 0 1 1 0 0 +EDGE2 4511 3851 -0.0462682 0.0237097 -0.011784 1 0 1 1 0 0 +EDGE2 4511 3850 -1.04292 -0.0172402 -1.58122 1 0 1 1 0 0 +EDGE2 4511 4190 -1.03682 -0.0476303 1.53884 1 0 1 1 0 0 +EDGE2 4511 4330 -0.976713 0.0521032 1.5348 1 0 1 1 0 0 +EDGE2 4512 3853 0.995122 0.0343843 0.0151259 1 0 1 1 0 0 +EDGE2 4512 4511 -1.00327 0.11032 -0.0198941 1 0 1 1 0 0 +EDGE2 4512 3852 -0.00494894 0.0534418 -0.00506572 1 0 1 1 0 0 +EDGE2 4512 3851 -0.947212 -0.0184942 -0.0063886 1 0 1 1 0 0 +EDGE2 4513 3854 0.972088 -0.0248506 0.0237133 1 0 1 1 0 0 +EDGE2 4513 3853 0.00315426 -0.0238633 -0.00160312 1 0 1 1 0 0 +EDGE2 4513 3852 -0.9509 -0.0183782 -0.00765924 1 0 1 1 0 0 +EDGE2 4513 4512 -1.06351 0.0428275 -0.00134319 1 0 1 1 0 0 +EDGE2 4514 3855 1.09078 0.0937869 0.017507 1 0 1 1 0 0 +EDGE2 4514 3875 1.08939 0.00719618 -3.16539 1 0 1 1 0 0 +EDGE2 4514 3854 0.00230847 0.0125792 0.00728027 1 0 1 1 0 0 +EDGE2 4514 3853 -1.02845 -0.00851217 0.0023665 1 0 1 1 0 0 +EDGE2 4514 4513 -1.01833 0.000830753 -0.00302392 1 0 1 1 0 0 +EDGE2 4515 3856 -0.0812524 -0.849205 -1.56164 1 0 1 1 0 0 +EDGE2 4515 3874 1.05247 -0.00922746 -3.1581 1 0 1 1 0 0 +EDGE2 4515 3855 0.0651731 0.00551696 -0.0220044 1 0 1 1 0 0 +EDGE2 4515 3875 -0.121928 0.0271669 -3.13695 1 0 1 1 0 0 +EDGE2 4515 3876 0.0623249 -0.971557 -1.563 1 0 1 1 0 0 +EDGE2 4515 3854 -0.992475 -0.0408658 0.016136 1 0 1 1 0 0 +EDGE2 4515 4514 -0.917404 0.098162 -0.00659058 1 0 1 1 0 0 +EDGE2 4516 3856 -0.0228086 0.0024272 0.00563246 1 0 1 1 0 0 +EDGE2 4516 4515 -0.982518 0.0303598 1.58733 1 0 1 1 0 0 +EDGE2 4516 3855 -0.969794 0.00480481 1.60307 1 0 1 1 0 0 +EDGE2 4516 3875 -0.967023 0.033183 -1.53893 1 0 1 1 0 0 +EDGE2 4516 3876 0.00483668 0.118777 -0.0151035 1 0 1 1 0 0 +EDGE2 4516 3857 0.987876 -0.0187942 -0.00180519 1 0 1 1 0 0 +EDGE2 4516 3877 1.03215 0.0467298 0.0124381 1 0 1 1 0 0 +EDGE2 4517 3856 -1.0497 0.017049 0.0202366 1 0 1 1 0 0 +EDGE2 4517 4516 -0.955342 -0.0510837 0.032351 1 0 1 1 0 0 +EDGE2 4517 3876 -1.05054 -0.0417069 -0.0204975 1 0 1 1 0 0 +EDGE2 4517 3857 0.102596 0.0133955 -0.0368581 1 0 1 1 0 0 +EDGE2 4517 3877 -0.00380042 -0.00257396 0.00383179 1 0 1 1 0 0 +EDGE2 4517 3878 1.00955 -0.0068402 -0.00541318 1 0 1 1 0 0 +EDGE2 4517 3858 0.975312 -0.00267742 -0.0281635 1 0 1 1 0 0 +EDGE2 4518 3857 -1.04838 -0.0514604 -0.00242232 1 0 1 1 0 0 +EDGE2 4518 4517 -1.03198 0.0841014 0.00607736 1 0 1 1 0 0 +EDGE2 4518 3877 -1.02077 0.0520864 -0.00121684 1 0 1 1 0 0 +EDGE2 4518 3878 0.0188962 -0.0879133 0.0471738 1 0 1 1 0 0 +EDGE2 4518 3858 0.00162934 -0.00504314 0.00628335 1 0 1 1 0 0 +EDGE2 4518 3859 1.03047 0.0378427 -0.00241213 1 0 1 1 0 0 +EDGE2 4518 3879 1.09369 -0.0045913 -0.00759342 1 0 1 1 0 0 +EDGE2 4519 3878 -0.979265 0.0312128 0.0126836 1 0 1 1 0 0 +EDGE2 4519 4518 -0.973518 0.00453025 0.0194804 1 0 1 1 0 0 +EDGE2 4519 3858 -1.0725 -0.0423655 0.0342625 1 0 1 1 0 0 +EDGE2 4519 3859 -0.000877446 0.00755582 0.022292 1 0 1 1 0 0 +EDGE2 4519 3879 -0.10561 0.00158248 -0.0361756 1 0 1 1 0 0 +EDGE2 4519 4180 1.09802 0.031351 -3.07435 1 0 1 1 0 0 +EDGE2 4519 4300 0.944617 -0.0158992 -3.14778 1 0 1 1 0 0 +EDGE2 4519 4320 1.02772 -0.0420615 -3.13985 1 0 1 1 0 0 +EDGE2 4519 4220 1.17046 0.0115164 -3.15668 1 0 1 1 0 0 +EDGE2 4519 3860 0.953439 0.0236929 0.00395209 1 0 1 1 0 0 +EDGE2 4519 3880 0.975186 -0.00290897 -0.00652566 1 0 1 1 0 0 +EDGE2 4520 4321 0.072602 -1.01485 -1.61126 1 0 1 1 0 0 +EDGE2 4520 4519 -0.989928 -0.0444082 -0.00241847 1 0 1 1 0 0 +EDGE2 4520 4219 0.943819 -0.159771 -3.18576 1 0 1 1 0 0 +EDGE2 4520 3859 -1.00911 0.0839697 0.0099561 1 0 1 1 0 0 +EDGE2 4520 3879 -1.05445 0.0190673 -0.0349381 1 0 1 1 0 0 +EDGE2 4520 3861 -0.0166357 0.920263 1.57593 1 0 1 1 0 0 +EDGE2 4520 4180 -0.0641858 -0.0876656 -3.15682 1 0 1 1 0 0 +EDGE2 4520 4300 0.00966782 -0.0853419 -3.14569 1 0 1 1 0 0 +EDGE2 4520 4320 0.0312241 -0.04441 -3.13956 1 0 1 1 0 0 +EDGE2 4520 4220 0.0474045 -0.0754664 -3.17434 1 0 1 1 0 0 +EDGE2 4520 4319 0.954084 0.00724706 -3.11863 1 0 1 1 0 0 +EDGE2 4520 3860 0.0166587 -0.0034074 0.0289598 1 0 1 1 0 0 +EDGE2 4520 3880 0.0226022 -0.0381126 0.00976404 1 0 1 1 0 0 +EDGE2 4520 4299 1.05856 0.0171816 -3.12769 1 0 1 1 0 0 +EDGE2 4520 4179 1.01381 -0.0821578 -3.1173 1 0 1 1 0 0 +EDGE2 4520 4181 -0.0160391 -1.02379 -1.53536 1 0 1 1 0 0 +EDGE2 4520 4301 -0.0736856 -1.06566 -1.59298 1 0 1 1 0 0 +EDGE2 4520 4221 -0.00368128 -0.960711 -1.59446 1 0 1 1 0 0 +EDGE2 4520 3881 -0.0141416 -0.966168 -1.53912 1 0 1 1 0 0 +EDGE2 4521 3862 1.0043 -0.0598649 -0.000640088 1 0 1 1 0 0 +EDGE2 4521 3861 0.0229248 -0.0386476 0.0310227 1 0 1 1 0 0 +EDGE2 4521 4180 -0.97683 0.0223704 1.51798 1 0 1 1 0 0 +EDGE2 4521 4300 -1.07763 0.0123242 1.54488 1 0 1 1 0 0 +EDGE2 4521 4320 -0.962571 -0.0217623 1.53923 1 0 1 1 0 0 +EDGE2 4521 4520 -0.98547 0.0277671 -1.61579 1 0 1 1 0 0 +EDGE2 4521 4220 -0.988033 -0.00203912 1.54832 1 0 1 1 0 0 +EDGE2 4521 3860 -1.13078 0.0181637 -1.56458 1 0 1 1 0 0 +EDGE2 4521 3880 -0.988384 -0.00430245 -1.57589 1 0 1 1 0 0 +EDGE2 4522 3863 0.959304 0.0139938 -0.00457456 1 0 1 1 0 0 +EDGE2 4522 4521 -1.01386 -0.115736 0.0114789 1 0 1 1 0 0 +EDGE2 4522 3862 0.00571693 -0.0177512 0.0325883 1 0 1 1 0 0 +EDGE2 4522 3861 -1.02949 -0.0413261 0.0165159 1 0 1 1 0 0 +EDGE2 4523 3863 0.022601 -0.0706263 -0.0247066 1 0 1 1 0 0 +EDGE2 4523 3864 0.94358 0.0326869 0.0228769 1 0 1 1 0 0 +EDGE2 4523 3862 -1.00907 0.00521479 0.00491378 1 0 1 1 0 0 +EDGE2 4523 4522 -1.05286 0.0251353 0.0124995 1 0 1 1 0 0 +EDGE2 4524 3865 0.981221 0.0348806 -0.00142713 1 0 1 1 0 0 +EDGE2 4524 3863 -0.971597 -0.000197048 -0.00953381 1 0 1 1 0 0 +EDGE2 4524 3864 -0.0984039 -0.0677625 -0.0318517 1 0 1 1 0 0 +EDGE2 4524 4523 -0.994494 0.0372464 0.0223467 1 0 1 1 0 0 +EDGE2 4525 3865 -0.0296179 0.0521619 0.0123721 1 0 1 1 0 0 +EDGE2 4525 3866 -0.0450109 1.03336 1.55363 1 0 1 1 0 0 +EDGE2 4525 3864 -0.992896 0.00981158 -0.00992 1 0 1 1 0 0 +EDGE2 4525 4524 -0.979678 -0.00408457 -0.0344771 1 0 1 1 0 0 +EDGE2 4526 3865 -0.989572 -0.00391786 -1.57924 1 0 1 1 0 0 +EDGE2 4526 3866 0.0350066 0.042087 -0.010819 1 0 1 1 0 0 +EDGE2 4526 3867 1.08398 -0.0455422 0.00547476 1 0 1 1 0 0 +EDGE2 4526 4525 -1.01481 0.080664 -1.55246 1 0 1 1 0 0 +EDGE2 4527 3868 1.01685 0.0191388 0.0211764 1 0 1 1 0 0 +EDGE2 4527 3866 -1.02735 0.0555207 -0.000999488 1 0 1 1 0 0 +EDGE2 4527 4526 -0.945571 0.0840335 -0.0210433 1 0 1 1 0 0 +EDGE2 4527 3867 -0.0885409 -0.0264348 -0.0133454 1 0 1 1 0 0 +EDGE2 4528 4527 -1.01542 -0.0872607 -0.0604694 1 0 1 1 0 0 +EDGE2 4528 3869 1.12941 0.0476329 -0.0116987 1 0 1 1 0 0 +EDGE2 4528 3868 -0.112608 -0.0365631 0.00863981 1 0 1 1 0 0 +EDGE2 4528 3867 -1.02049 -0.0194962 -0.00023731 1 0 1 1 0 0 +EDGE2 4529 3870 1.0815 0.0728256 0.0168181 1 0 1 1 0 0 +EDGE2 4529 4528 -0.953561 -0.0312796 -0.00500999 1 0 1 1 0 0 +EDGE2 4529 3869 0.00416691 -0.00891719 0.0224975 1 0 1 1 0 0 +EDGE2 4529 3868 -1.00299 0.0256989 -0.00860337 1 0 1 1 0 0 +EDGE2 4530 3870 0.0740579 -0.0528938 0.000160429 1 0 1 1 0 0 +EDGE2 4530 3869 -0.94316 -0.00153914 0.0271702 1 0 1 1 0 0 +EDGE2 4530 4529 -0.978614 0.0985481 -0.0496017 1 0 1 1 0 0 +EDGE2 4530 3871 -0.0411333 1.00456 1.59626 1 0 1 1 0 0 +EDGE2 4531 4530 -0.951679 6.04855e-05 -1.56027 1 0 1 1 0 0 +EDGE2 4531 3870 -1.02556 -0.0308721 -1.57012 1 0 1 1 0 0 +EDGE2 4531 3871 -0.0433184 -0.0271651 0.0132402 1 0 1 1 0 0 +EDGE2 4531 3872 0.944611 0.060467 0.00238492 1 0 1 1 0 0 +EDGE2 4532 3871 -0.934097 -0.00228215 0.000713518 1 0 1 1 0 0 +EDGE2 4532 4531 -1.02515 -0.0310174 -0.0102035 1 0 1 1 0 0 +EDGE2 4532 3872 0.133711 0.00458418 0.00545918 1 0 1 1 0 0 +EDGE2 4532 3873 1.03832 0.014375 0.00737804 1 0 1 1 0 0 +EDGE2 4533 4532 -1.01029 0.0490972 -0.0107528 1 0 1 1 0 0 +EDGE2 4533 3872 -0.969792 -0.00557545 -0.0182752 1 0 1 1 0 0 +EDGE2 4533 3874 0.934448 0.0249063 -0.0158918 1 0 1 1 0 0 +EDGE2 4533 3873 -0.0180461 0.0115917 0.035201 1 0 1 1 0 0 +EDGE2 4534 4533 -1.0836 0.00788928 -0.0023756 1 0 1 1 0 0 +EDGE2 4534 4515 1.0372 -0.0365334 -3.16156 1 0 1 1 0 0 +EDGE2 4534 3874 -0.012897 -0.0064842 0.0226615 1 0 1 1 0 0 +EDGE2 4534 3873 -0.911054 -0.0324227 -0.00895422 1 0 1 1 0 0 +EDGE2 4534 3855 0.929074 -0.0781481 -3.13927 1 0 1 1 0 0 +EDGE2 4534 3875 0.960531 0.00488299 -0.0291555 1 0 1 1 0 0 +EDGE2 4535 3856 -0.0228955 1.04803 1.53472 1 0 1 1 0 0 +EDGE2 4535 4515 -0.0393998 -0.0500833 -3.1357 1 0 1 1 0 0 +EDGE2 4535 3874 -0.945723 0.0742164 -0.028001 1 0 1 1 0 0 +EDGE2 4535 4534 -0.970158 -0.0451955 -0.0168229 1 0 1 1 0 0 +EDGE2 4535 4516 -0.0271095 0.937045 1.57705 1 0 1 1 0 0 +EDGE2 4535 3855 0.0220369 0.0518435 -3.13115 1 0 1 1 0 0 +EDGE2 4535 3875 -0.0898472 0.0190828 0.0026015 1 0 1 1 0 0 +EDGE2 4535 3876 0.0479049 1.05658 1.57142 1 0 1 1 0 0 +EDGE2 4535 3854 1.03801 0.0140617 -3.14383 1 0 1 1 0 0 +EDGE2 4535 4514 0.949327 -0.0561606 -3.15145 1 0 1 1 0 0 +EDGE2 4536 4515 -0.954974 0.0838145 -1.60002 1 0 1 1 0 0 +EDGE2 4536 4535 -1.04001 0.0176572 1.55329 1 0 1 1 0 0 +EDGE2 4536 3855 -0.998485 -0.012634 -1.54714 1 0 1 1 0 0 +EDGE2 4536 3875 -0.993938 0.00618478 1.58546 1 0 1 1 0 0 +EDGE2 4537 4536 -1.02688 -0.00289215 0.0188626 1 0 1 1 0 0 +EDGE2 4538 4537 -1.02488 -0.0301482 -0.0316326 1 0 1 1 0 0 +EDGE2 4539 3840 1.0613 0.0441773 -3.16748 1 0 1 1 0 0 +EDGE2 4539 3800 0.924407 0.0213959 -3.14121 1 0 1 1 0 0 +EDGE2 4539 4538 -0.879743 0.00825506 0.0220115 1 0 1 1 0 0 +EDGE2 4540 3839 1.04077 -0.0106115 -3.16167 1 0 1 1 0 0 +EDGE2 4540 3799 1.04502 0.0533791 -3.13907 1 0 1 1 0 0 +EDGE2 4540 3841 0.0868507 0.985678 1.56979 1 0 1 1 0 0 +EDGE2 4540 3840 -0.0765407 -0.0567569 -3.15131 1 0 1 1 0 0 +EDGE2 4540 3801 -0.00231504 -1.01226 -1.61918 1 0 1 1 0 0 +EDGE2 4540 3800 0.03947 0.0694479 -3.11624 1 0 1 1 0 0 +EDGE2 4540 4539 -0.95312 0.0237256 0.033298 1 0 1 1 0 0 +EDGE2 4541 3802 0.929573 -0.0146104 0.0195266 1 0 1 1 0 0 +EDGE2 4541 3840 -1.04503 -0.0272376 -1.59934 1 0 1 1 0 0 +EDGE2 4541 4540 -0.995095 0.00527224 1.53991 1 0 1 1 0 0 +EDGE2 4541 3801 0.0515757 0.0518786 0.00869223 1 0 1 1 0 0 +EDGE2 4541 3800 -1.10503 0.0382446 -1.59511 1 0 1 1 0 0 +EDGE2 4542 4541 -1.02321 -0.03007 -0.0168869 1 0 1 1 0 0 +EDGE2 4542 3802 0.0384768 -0.0419542 0.00357499 1 0 1 1 0 0 +EDGE2 4542 3803 1.08003 -0.0163108 -0.0499153 1 0 1 1 0 0 +EDGE2 4542 3801 -0.988444 0.0558025 0.0195234 1 0 1 1 0 0 +EDGE2 4543 3802 -0.946955 0.040307 0.00385342 1 0 1 1 0 0 +EDGE2 4543 3803 0.0233459 -0.0158541 0.00669738 1 0 1 1 0 0 +EDGE2 4543 3804 0.999307 -0.0607578 0.00678761 1 0 1 1 0 0 +EDGE2 4543 4542 -1.05253 0.0723072 -0.00699823 1 0 1 1 0 0 +EDGE2 4544 3805 0.947579 -0.100007 -0.0132613 1 0 1 1 0 0 +EDGE2 4544 3803 -1.01124 0.0287328 -0.00211321 1 0 1 1 0 0 +EDGE2 4544 4543 -0.991429 0.0246258 0.0200586 1 0 1 1 0 0 +EDGE2 4544 3804 -0.0172275 0.00730451 0.0194797 1 0 1 1 0 0 +EDGE2 4545 3805 -0.0253864 -0.0306552 0.00176055 1 0 1 1 0 0 +EDGE2 4545 3806 -0.0645627 1.07448 1.54633 1 0 1 1 0 0 +EDGE2 4545 4544 -0.968636 0.0683331 0.0415643 1 0 1 1 0 0 +EDGE2 4545 3804 -1.00587 -0.00130022 -0.00685156 1 0 1 1 0 0 +EDGE2 4546 3805 -0.92935 0.0338232 1.5527 1 0 1 1 0 0 +EDGE2 4546 4545 -0.983647 -0.0163107 1.55685 1 0 1 1 0 0 +EDGE2 4547 4546 -1.12801 -0.0493044 0.00896195 1 0 1 1 0 0 +EDGE2 4548 4547 -0.955905 0.00248035 -0.00720607 1 0 1 1 0 0 +EDGE2 4549 4548 -0.991603 -0.00671338 -0.0037873 1 0 1 1 0 0 +EDGE2 4549 4530 0.949163 -0.101707 -3.10339 1 0 1 1 0 0 +EDGE2 4549 3870 1.09858 -0.0376432 -3.15812 1 0 1 1 0 0 +EDGE2 4550 4549 -1.04188 -0.071261 0.0029021 1 0 1 1 0 0 +EDGE2 4550 4530 0.0302955 -0.0210746 -3.12831 1 0 1 1 0 0 +EDGE2 4550 3870 -0.00620473 0.0257074 -3.12358 1 0 1 1 0 0 +EDGE2 4550 3869 1.01705 0.0181814 -3.16127 1 0 1 1 0 0 +EDGE2 4550 4529 1.02444 0.0443606 -3.13128 1 0 1 1 0 0 +EDGE2 4550 3871 -0.0136497 -0.984589 -1.57299 1 0 1 1 0 0 +EDGE2 4550 4531 0.0345908 -0.984889 -1.55915 1 0 1 1 0 0 +EDGE2 4551 4530 -1.01912 -0.032376 1.56631 1 0 1 1 0 0 +EDGE2 4551 4550 -0.96635 0.026555 -1.54197 1 0 1 1 0 0 +EDGE2 4551 3870 -0.856412 0.029949 1.57862 1 0 1 1 0 0 +EDGE2 4552 4551 -0.990568 -0.00865781 0.0210247 1 0 1 1 0 0 +EDGE2 4553 4552 -1.07222 -0.0149812 0.0185241 1 0 1 1 0 0 +EDGE2 4554 4553 -0.947973 0.152086 -0.0256907 1 0 1 1 0 0 +EDGE2 4555 4554 -0.965294 -0.0990851 -0.00039397 1 0 1 1 0 0 +EDGE2 4556 4555 -0.94078 0.0631333 -1.57754 1 0 1 1 0 0 +EDGE2 4557 4556 -1.06275 -0.069187 0.00500819 1 0 1 1 0 0 +EDGE2 4558 4557 -0.956209 0.00879774 0.021716 1 0 1 1 0 0 +EDGE2 4559 4558 -1.01185 -0.00243015 0.0196383 1 0 1 1 0 0 +EDGE2 4560 4559 -0.998524 0.052508 -0.00520449 1 0 1 1 0 0 +EDGE2 4561 4560 -0.977391 0.0190176 1.57043 1 0 1 1 0 0 +EDGE2 4562 4561 -0.909385 -0.0173873 0.00125885 1 0 1 1 0 0 +EDGE2 4563 4562 -0.963394 -0.0644114 -0.0049213 1 0 1 1 0 0 +EDGE2 4564 3625 1.04698 0.0237094 -3.10953 1 0 1 1 0 0 +EDGE2 4564 4563 -1.0181 0.00218308 -0.00239068 1 0 1 1 0 0 +EDGE2 4565 3626 0.0215216 0.960938 1.60768 1 0 1 1 0 0 +EDGE2 4565 3624 1.09745 0.030973 -3.12401 1 0 1 1 0 0 +EDGE2 4565 3625 -0.0520146 -0.0412513 -3.10779 1 0 1 1 0 0 +EDGE2 4565 4564 -0.990491 0.0478058 0.0301877 1 0 1 1 0 0 +EDGE2 4566 3627 0.97236 -0.00173897 0.00155241 1 0 1 1 0 0 +EDGE2 4566 3626 0.000176343 0.00838227 -0.0213978 1 0 1 1 0 0 +EDGE2 4566 4565 -0.97515 -0.042877 -1.56911 1 0 1 1 0 0 +EDGE2 4566 3625 -0.976279 -0.010015 1.56176 1 0 1 1 0 0 +EDGE2 4567 3628 0.9815 -0.0282074 0.013941 1 0 1 1 0 0 +EDGE2 4567 4566 -0.995007 -0.048027 -0.0186493 1 0 1 1 0 0 +EDGE2 4567 3627 0.0450503 0.0047146 -0.00890789 1 0 1 1 0 0 +EDGE2 4567 3626 -1.03402 0.00447603 -0.0132957 1 0 1 1 0 0 +EDGE2 4568 3629 1.04705 -0.024711 -0.00916663 1 0 1 1 0 0 +EDGE2 4568 4567 -0.893187 -0.0368618 -0.00978632 1 0 1 1 0 0 +EDGE2 4568 3628 -0.00716776 0.0522218 -0.0337286 1 0 1 1 0 0 +EDGE2 4568 3627 -0.982527 -0.0274804 -0.00298211 1 0 1 1 0 0 +EDGE2 4569 3610 1.00902 -0.0198763 -3.16431 1 0 1 1 0 0 +EDGE2 4569 3630 1.03494 -0.0619617 -0.00484186 1 0 1 1 0 0 +EDGE2 4569 3629 0.0239713 -0.0486734 0.00966934 1 0 1 1 0 0 +EDGE2 4569 3628 -1.00005 -0.0494489 -0.026948 1 0 1 1 0 0 +EDGE2 4569 4568 -1.01637 0.109051 0.00930957 1 0 1 1 0 0 +EDGE2 4570 3609 0.982463 -0.0268964 -3.15138 1 0 1 1 0 0 +EDGE2 4570 3611 -0.0582537 -1.03102 -1.58258 1 0 1 1 0 0 +EDGE2 4570 3610 0.0430492 -0.0407992 -3.15733 1 0 1 1 0 0 +EDGE2 4570 3630 -0.0560784 0.0124317 -0.0084099 1 0 1 1 0 0 +EDGE2 4570 3631 0.00629211 0.999075 1.58214 1 0 1 1 0 0 +EDGE2 4570 3629 -0.98226 -0.0838469 0.0215598 1 0 1 1 0 0 +EDGE2 4570 4569 -0.96973 0.0260377 -0.0273677 1 0 1 1 0 0 +EDGE2 4571 3612 0.955388 0.0121013 -0.00726349 1 0 1 1 0 0 +EDGE2 4571 3611 0.0446313 -0.0614637 0.0157371 1 0 1 1 0 0 +EDGE2 4571 4570 -0.907052 -0.00213201 1.59892 1 0 1 1 0 0 +EDGE2 4571 3610 -0.986595 0.0292576 -1.56157 1 0 1 1 0 0 +EDGE2 4571 3630 -1.01095 0.0459409 1.54959 1 0 1 1 0 0 +EDGE2 4572 3613 0.982276 -0.053848 -0.0233016 1 0 1 1 0 0 +EDGE2 4572 3612 0.0828235 0.0411544 -0.000695312 1 0 1 1 0 0 +EDGE2 4572 4571 -1.0374 -0.0392446 0.0204283 1 0 1 1 0 0 +EDGE2 4572 3611 -1.04686 0.0695989 -0.0462039 1 0 1 1 0 0 +EDGE2 4573 3614 1.04175 -0.0576768 0.0609715 1 0 1 1 0 0 +EDGE2 4573 3613 -0.020148 -0.00310551 0.00428395 1 0 1 1 0 0 +EDGE2 4573 3612 -1.04815 -0.0606427 0.00335645 1 0 1 1 0 0 +EDGE2 4573 4572 -0.94546 0.0657256 -0.0229182 1 0 1 1 0 0 +EDGE2 4574 3615 0.937241 -0.0718091 0.0236519 1 0 1 1 0 0 +EDGE2 4574 3614 -0.0512511 -0.0209992 -0.0449976 1 0 1 1 0 0 +EDGE2 4574 3613 -1.00353 -0.0319979 -0.0109501 1 0 1 1 0 0 +EDGE2 4574 4573 -0.986521 0.000507196 0.0373365 1 0 1 1 0 0 +EDGE2 4575 3615 0.0271137 -0.0237596 0.0298596 1 0 1 1 0 0 +EDGE2 4575 3616 -0.0549858 -0.989697 -1.61088 1 0 1 1 0 0 +EDGE2 4575 4574 -1.01253 0.0232176 -0.0096184 1 0 1 1 0 0 +EDGE2 4575 3614 -0.99599 -0.0177809 -0.0161528 1 0 1 1 0 0 +EDGE2 4576 4575 -1.06503 0.0225511 -1.59122 1 0 1 1 0 0 +EDGE2 4576 3615 -0.987147 0.012961 -1.60336 1 0 1 1 0 0 +EDGE2 4577 4576 -0.965799 0.00216616 -0.0282829 1 0 1 1 0 0 +EDGE2 4578 4577 -1.08589 0.0267986 0.0249741 1 0 1 1 0 0 +EDGE2 4579 4578 -1.02147 0.0313111 0.0129 1 0 1 1 0 0 +EDGE2 4580 4579 -0.968607 0.0185138 0.00306273 1 0 1 1 0 0 +EDGE2 4581 4580 -1.11934 0.0337302 -1.57425 1 0 1 1 0 0 +EDGE2 4582 4581 -1.02895 0.0277117 0.0269115 1 0 1 1 0 0 +EDGE2 4583 4582 -0.984995 -0.062209 0.0259095 1 0 1 1 0 0 +EDGE2 4584 4583 -0.999363 0.0964964 -0.000489392 1 0 1 1 0 0 +EDGE2 4584 3605 1.06092 0.0445367 -3.17313 1 0 1 1 0 0 +EDGE2 4585 4584 -0.973669 0.0278611 -0.0441649 1 0 1 1 0 0 +EDGE2 4585 3605 -0.0589003 0.0811465 -3.13891 1 0 1 1 0 0 +EDGE2 4585 3606 0.0193038 1.10716 1.547 1 0 1 1 0 0 +EDGE2 4585 3604 0.981091 0.0121186 -3.12629 1 0 1 1 0 0 +EDGE2 4586 3605 -1.00881 -0.0316228 -1.57046 1 0 1 1 0 0 +EDGE2 4586 4585 -0.954929 0.109118 1.57423 1 0 1 1 0 0 +EDGE2 4587 4586 -1.12819 -0.0278642 -0.00358509 1 0 1 1 0 0 +EDGE2 4588 4587 -1.04412 0.0451689 0.00598228 1 0 1 1 0 0 +EDGE2 4589 4588 -0.949222 -0.0416876 0.0012467 1 0 1 1 0 0 +EDGE2 4590 4589 -0.938879 0.0494339 0.013277 1 0 1 1 0 0 +EDGE2 4591 4590 -1.00627 -0.00532441 -1.54458 1 0 1 1 0 0 +EDGE2 4592 4591 -0.973823 -0.0953911 -0.00095592 1 0 1 1 0 0 +EDGE2 4593 4592 -1.05293 0.0279791 -0.0203729 1 0 1 1 0 0 +EDGE2 4594 4593 -0.941494 -0.0152793 -0.0024323 1 0 1 1 0 0 +EDGE2 4594 2915 1.065 0.0293881 -3.15875 1 0 1 1 0 0 +EDGE2 4594 3595 0.952298 -0.0384419 -3.16034 1 0 1 1 0 0 +EDGE2 4594 3735 0.961311 -0.0577869 -3.16197 1 0 1 1 0 0 +EDGE2 4594 3755 1.00375 -0.0418663 -3.18215 1 0 1 1 0 0 +EDGE2 4594 3575 1.09903 -0.00273974 -3.12041 1 0 1 1 0 0 +EDGE2 4595 4594 -1.07127 0.0175559 0.0321364 1 0 1 1 0 0 +EDGE2 4595 2915 0.097003 0.00876256 -3.14709 1 0 1 1 0 0 +EDGE2 4595 2916 0.048509 -1.06388 -1.57882 1 0 1 1 0 0 +EDGE2 4595 3736 -0.0585153 -1.03063 -1.58639 1 0 1 1 0 0 +EDGE2 4595 3576 0.0521618 -0.921554 -1.55487 1 0 1 1 0 0 +EDGE2 4595 3595 0.07448 -0.0982581 -3.14724 1 0 1 1 0 0 +EDGE2 4595 3735 0.0439568 0.0338477 -3.17286 1 0 1 1 0 0 +EDGE2 4595 3755 0.0266524 0.0150204 -3.14791 1 0 1 1 0 0 +EDGE2 4595 3575 -0.000155718 0.0283326 -3.13272 1 0 1 1 0 0 +EDGE2 4595 2914 1.03644 -0.0415776 -3.1453 1 0 1 1 0 0 +EDGE2 4595 3594 0.949977 0.019186 -3.15803 1 0 1 1 0 0 +EDGE2 4595 3734 0.971431 0.0311376 -3.15298 1 0 1 1 0 0 +EDGE2 4595 3754 1.01827 0.0393724 -3.1364 1 0 1 1 0 0 +EDGE2 4595 3574 0.966921 -0.00721828 -3.14554 1 0 1 1 0 0 +EDGE2 4595 3596 -0.0155634 0.991674 1.56654 1 0 1 1 0 0 +EDGE2 4595 3756 -0.0470047 0.996408 1.57286 1 0 1 1 0 0 +EDGE2 4596 3577 0.99531 0.0703663 -0.0101752 1 0 1 1 0 0 +EDGE2 4596 3737 1.0827 -0.0460035 -0.0191882 1 0 1 1 0 0 +EDGE2 4596 2915 -0.997732 0.0015866 -1.60139 1 0 1 1 0 0 +EDGE2 4596 2916 0.00643238 0.0691486 -0.00965009 1 0 1 1 0 0 +EDGE2 4596 3736 -0.00608819 -0.0157491 0.005604 1 0 1 1 0 0 +EDGE2 4596 2917 1.00787 0.0227878 0.0175745 1 0 1 1 0 0 +EDGE2 4596 3576 0.0393458 0.0152618 0.0226348 1 0 1 1 0 0 +EDGE2 4596 4595 -1.06181 0.0697018 1.55221 1 0 1 1 0 0 +EDGE2 4596 3595 -1.09309 0.00168727 -1.59068 1 0 1 1 0 0 +EDGE2 4596 3735 -0.970346 -0.0178482 -1.5865 1 0 1 1 0 0 +EDGE2 4596 3755 -1.00923 -0.00681506 -1.56755 1 0 1 1 0 0 +EDGE2 4596 3575 -1.0013 -0.0193885 -1.56859 1 0 1 1 0 0 +EDGE2 4597 3577 -0.102147 0.0525296 0.0296488 1 0 1 1 0 0 +EDGE2 4597 3578 0.983127 -0.0436838 0.0193075 1 0 1 1 0 0 +EDGE2 4597 3738 1.01849 -0.0586257 0.00325661 1 0 1 1 0 0 +EDGE2 4597 2918 0.956561 -0.0107126 -0.0328648 1 0 1 1 0 0 +EDGE2 4597 3737 0.0135764 0.0516023 -0.0385763 1 0 1 1 0 0 +EDGE2 4597 2916 -0.969493 -0.0373676 0.0217466 1 0 1 1 0 0 +EDGE2 4597 3736 -1.0248 -0.0724007 -0.0118018 1 0 1 1 0 0 +EDGE2 4597 4596 -0.929042 -0.0442484 -0.0094419 1 0 1 1 0 0 +EDGE2 4597 2917 -0.0138373 0.0902755 0.0140221 1 0 1 1 0 0 +EDGE2 4597 3576 -1.02088 0.0382713 0.0155171 1 0 1 1 0 0 +EDGE2 4598 2919 1.00632 -0.00795554 0.0108177 1 0 1 1 0 0 +EDGE2 4598 3739 1.03731 0.0533101 -0.0054571 1 0 1 1 0 0 +EDGE2 4598 3579 0.959468 -0.0496564 -0.0166207 1 0 1 1 0 0 +EDGE2 4598 3577 -1.04938 -0.00848326 0.0208013 1 0 1 1 0 0 +EDGE2 4598 4597 -1.09147 -0.0333343 -0.00396142 1 0 1 1 0 0 +EDGE2 4598 3578 0.01773 -0.0617322 -0.0406182 1 0 1 1 0 0 +EDGE2 4598 3738 0.0152919 -0.0584197 0.0126732 1 0 1 1 0 0 +EDGE2 4598 2918 0.00855118 -0.137372 -0.0354609 1 0 1 1 0 0 +EDGE2 4598 3737 -1.0714 -0.00437968 -0.0162513 1 0 1 1 0 0 +EDGE2 4598 2917 -1.16513 -0.052126 0.0326529 1 0 1 1 0 0 +EDGE2 4599 2919 0.0209872 -0.048607 0.0209095 1 0 1 1 0 0 +EDGE2 4599 3740 1.11401 0.0624634 -0.0232589 1 0 1 1 0 0 +EDGE2 4599 2920 0.989944 -0.0163946 -0.00681462 1 0 1 1 0 0 +EDGE2 4599 3580 0.999958 0.0316101 0.0271838 1 0 1 1 0 0 +EDGE2 4599 3739 -0.0937929 0.159133 -0.00524055 1 0 1 1 0 0 +EDGE2 4599 3579 0.0250041 0.0243196 0.00282488 1 0 1 1 0 0 +EDGE2 4599 3578 -0.962671 0.0971876 0.00655261 1 0 1 1 0 0 +EDGE2 4599 3738 -1.02759 -0.00299347 -0.000371479 1 0 1 1 0 0 +EDGE2 4599 4598 -0.95984 -0.0842404 -0.0120652 1 0 1 1 0 0 +EDGE2 4599 2918 -1.03534 0.0513255 0.019667 1 0 1 1 0 0 +EDGE2 4600 2919 -0.984544 -0.0340488 -0.00233993 1 0 1 1 0 0 +EDGE2 4600 3740 -0.00652863 0.0281229 0.0222509 1 0 1 1 0 0 +EDGE2 4600 2921 -0.00768866 0.981777 1.57203 1 0 1 1 0 0 +EDGE2 4600 3741 0.0774983 1.00002 1.57731 1 0 1 1 0 0 +EDGE2 4600 2920 0.0638067 0.0784366 0.0238994 1 0 1 1 0 0 +EDGE2 4600 3580 -0.0135516 -0.0115691 0.00543969 1 0 1 1 0 0 +EDGE2 4600 3581 0.000812687 0.994325 1.58968 1 0 1 1 0 0 +EDGE2 4600 3739 -0.960432 0.0357742 -5.09759e-05 1 0 1 1 0 0 +EDGE2 4600 4599 -1.04758 0.137608 -0.00435261 1 0 1 1 0 0 +EDGE2 4600 3579 -0.877037 -0.000914275 -0.00017791 1 0 1 1 0 0 +EDGE2 4601 3740 -0.998763 -0.0509139 1.54284 1 0 1 1 0 0 +EDGE2 4601 4600 -0.98968 -0.0564743 1.56535 1 0 1 1 0 0 +EDGE2 4601 2920 -0.986285 -0.0312492 1.55401 1 0 1 1 0 0 +EDGE2 4601 3580 -0.980544 0.0430701 1.57494 1 0 1 1 0 0 +EDGE2 4602 4601 -0.998549 -0.0611343 -0.0334948 1 0 1 1 0 0 +EDGE2 4603 4602 -1.04439 -0.0607762 -0.0130735 1 0 1 1 0 0 +EDGE2 4604 4603 -0.952911 -0.00124274 0.0427627 1 0 1 1 0 0 +EDGE2 4605 4604 -1.05884 0.0199406 0.0348953 1 0 1 1 0 0 +EDGE2 4606 4605 -1.00747 0.0643916 -1.54163 1 0 1 1 0 0 +EDGE2 4607 4606 -0.985196 -0.0353032 0.0200653 1 0 1 1 0 0 +EDGE2 4608 4607 -1.00347 -0.0307025 0.0133392 1 0 1 1 0 0 +EDGE2 4609 2810 0.940628 -0.056039 -3.14857 1 0 1 1 0 0 +EDGE2 4609 2790 1.00853 0.0769727 -3.15629 1 0 1 1 0 0 +EDGE2 4609 4608 -0.941608 -0.0333894 0.0202213 1 0 1 1 0 0 +EDGE2 4610 2811 -0.00149964 -1.02704 -1.56498 1 0 1 1 0 0 +EDGE2 4610 2791 0.0217142 -0.928678 -1.57374 1 0 1 1 0 0 +EDGE2 4610 2789 1.02237 -0.0739621 -3.14203 1 0 1 1 0 0 +EDGE2 4610 2809 1.01459 -0.0802387 -3.15407 1 0 1 1 0 0 +EDGE2 4610 2810 0.0278609 0.032812 -3.15705 1 0 1 1 0 0 +EDGE2 4610 2790 -0.0841587 0.021299 -3.12509 1 0 1 1 0 0 +EDGE2 4610 4609 -1.00631 -0.0248023 -0.0352965 1 0 1 1 0 0 +EDGE2 4611 2810 -0.974936 -0.0464727 1.57475 1 0 1 1 0 0 +EDGE2 4611 4610 -0.995781 0.0875055 -1.62438 1 0 1 1 0 0 +EDGE2 4611 2790 -0.989424 -0.0274848 1.57845 1 0 1 1 0 0 +EDGE2 4612 4611 -1.0921 -0.123076 0.0311255 1 0 1 1 0 0 +EDGE2 4613 4612 -0.971249 0.000919598 0.0129252 1 0 1 1 0 0 +EDGE2 4614 4613 -1.02839 -0.0281442 -0.0494433 1 0 1 1 0 0 +EDGE2 4614 2875 0.945204 0.0248815 -3.17697 1 0 1 1 0 0 +EDGE2 4614 2955 1.09728 -0.0465563 -3.18274 1 0 1 1 0 0 +EDGE2 4614 2755 1.00024 -0.0254174 -3.15287 1 0 1 1 0 0 +EDGE2 4615 4614 -1.04974 0.0047512 -0.00254155 1 0 1 1 0 0 +EDGE2 4615 2875 0.0620849 0.0627512 -3.16183 1 0 1 1 0 0 +EDGE2 4615 2956 -0.0647001 -0.953913 -1.56806 1 0 1 1 0 0 +EDGE2 4615 2876 0.0222355 -1.0426 -1.56509 1 0 1 1 0 0 +EDGE2 4615 2756 -0.0190447 -1.02724 -1.58864 1 0 1 1 0 0 +EDGE2 4615 2955 0.0632675 0.00559481 -3.13214 1 0 1 1 0 0 +EDGE2 4615 2754 0.927946 0.0229551 -3.17234 1 0 1 1 0 0 +EDGE2 4615 2874 1.02601 -0.0832931 -3.15342 1 0 1 1 0 0 +EDGE2 4615 2954 1.12209 0.0319836 -3.12439 1 0 1 1 0 0 +EDGE2 4615 2755 0.0639201 0.0519601 -3.158 1 0 1 1 0 0 +EDGE2 4616 2875 -1.03041 0.0142208 1.55618 1 0 1 1 0 0 +EDGE2 4616 4615 -1.01721 0.0148282 -1.58249 1 0 1 1 0 0 +EDGE2 4616 2955 -1.03334 0.0495169 1.57545 1 0 1 1 0 0 +EDGE2 4616 2755 -0.998812 0.00733271 1.56121 1 0 1 1 0 0 +EDGE2 4617 4616 -1.03018 0.0298531 0.0045551 1 0 1 1 0 0 +EDGE2 4618 4617 -1.03791 -0.0928787 -0.0338413 1 0 1 1 0 0 +EDGE2 4619 3740 0.987045 0.0161445 -3.14068 1 0 1 1 0 0 +EDGE2 4619 4618 -1.01205 -0.0555942 -0.00848822 1 0 1 1 0 0 +EDGE2 4619 4600 1.02324 -0.0246485 -3.15329 1 0 1 1 0 0 +EDGE2 4619 2920 0.979001 -0.107793 -3.14772 1 0 1 1 0 0 +EDGE2 4619 3580 1.04178 -0.0497122 -3.12701 1 0 1 1 0 0 +EDGE2 4620 2919 1.0449 0.00521092 -3.13374 1 0 1 1 0 0 +EDGE2 4620 4601 0.0266037 0.988559 1.52878 1 0 1 1 0 0 +EDGE2 4620 3740 0.0411124 0.0510954 -3.16918 1 0 1 1 0 0 +EDGE2 4620 4619 -1.01469 0.106418 -0.0176879 1 0 1 1 0 0 +EDGE2 4620 4600 0.00137232 -0.0858486 -3.16509 1 0 1 1 0 0 +EDGE2 4620 2921 -0.0465907 -0.943782 -1.53787 1 0 1 1 0 0 +EDGE2 4620 3741 -0.0908194 -1.03121 -1.58648 1 0 1 1 0 0 +EDGE2 4620 2920 -0.0666847 -0.0695923 -3.15553 1 0 1 1 0 0 +EDGE2 4620 3580 -0.127157 -0.0600436 -3.1535 1 0 1 1 0 0 +EDGE2 4620 3581 -0.00259734 -0.960068 -1.55579 1 0 1 1 0 0 +EDGE2 4620 3739 1.08137 0.0433054 -3.14625 1 0 1 1 0 0 +EDGE2 4620 4599 1.08903 -0.00367764 -3.15564 1 0 1 1 0 0 +EDGE2 4620 3579 0.975997 0.0974957 -3.13647 1 0 1 1 0 0 +EDGE2 4621 4602 0.948876 -0.0196247 -0.0174904 1 0 1 1 0 0 +EDGE2 4621 4601 -0.0323803 -0.0751556 -0.0160569 1 0 1 1 0 0 +EDGE2 4621 3740 -0.957921 -0.0572483 1.57944 1 0 1 1 0 0 +EDGE2 4621 4620 -1.06869 -0.0470175 -1.55122 1 0 1 1 0 0 +EDGE2 4621 4600 -1.09153 0.0213667 1.55069 1 0 1 1 0 0 +EDGE2 4621 2920 -0.942692 0.0155049 1.5648 1 0 1 1 0 0 +EDGE2 4621 3580 -0.897053 -0.0149915 1.53617 1 0 1 1 0 0 +EDGE2 4622 4603 1.06981 -0.032459 -0.00439482 1 0 1 1 0 0 +EDGE2 4622 4621 -1.08206 -0.00941539 -0.0192251 1 0 1 1 0 0 +EDGE2 4622 4602 -0.0439681 0.00454785 -0.00298123 1 0 1 1 0 0 +EDGE2 4622 4601 -1.1477 0.132813 0.0200874 1 0 1 1 0 0 +EDGE2 4623 4604 1.03358 -0.0323869 0.0217269 1 0 1 1 0 0 +EDGE2 4623 4622 -1.01895 -0.0590984 0.0162231 1 0 1 1 0 0 +EDGE2 4623 4603 -0.053463 0.00972916 0.00380343 1 0 1 1 0 0 +EDGE2 4623 4602 -0.963414 -0.074476 0.0127238 1 0 1 1 0 0 +EDGE2 4624 4604 -0.0361333 -0.0333113 0.0322956 1 0 1 1 0 0 +EDGE2 4624 4605 0.967226 0.0553208 -0.0269241 1 0 1 1 0 0 +EDGE2 4624 4623 -1.05479 -0.000138911 0.0111683 1 0 1 1 0 0 +EDGE2 4624 4603 -1.01052 0.0288737 -0.0213873 1 0 1 1 0 0 +EDGE2 4625 4606 -0.0774281 0.905996 1.58148 1 0 1 1 0 0 +EDGE2 4625 4604 -0.958255 0.00393739 0.0345421 1 0 1 1 0 0 +EDGE2 4625 4624 -0.905264 0.00413038 -0.0192174 1 0 1 1 0 0 +EDGE2 4625 4605 0.066942 0.0360986 -0.0495752 1 0 1 1 0 0 +EDGE2 4626 4625 -0.992888 -0.0873894 1.59443 1 0 1 1 0 0 +EDGE2 4626 4605 -1.03264 0.0159102 1.57803 1 0 1 1 0 0 +EDGE2 4627 4626 -1.07206 0.0966259 -0.0208035 1 0 1 1 0 0 +EDGE2 4628 4627 -1.00215 0.0366684 -0.0515447 1 0 1 1 0 0 +EDGE2 4629 4628 -1.00619 -0.140998 -0.00530196 1 0 1 1 0 0 +EDGE2 4629 4590 1.01647 0.0330123 -3.1444 1 0 1 1 0 0 +EDGE2 4630 4629 -1.00922 -0.0124794 -0.0403856 1 0 1 1 0 0 +EDGE2 4630 4590 -0.0515502 0.0862866 -3.13271 1 0 1 1 0 0 +EDGE2 4630 4591 0.0423279 -1.05247 -1.60216 1 0 1 1 0 0 +EDGE2 4630 4589 1.02605 -0.0366979 -3.1523 1 0 1 1 0 0 +EDGE2 4631 4630 -0.853755 -0.0289504 1.5762 1 0 1 1 0 0 +EDGE2 4631 4590 -1.02345 0.0545865 -1.55168 1 0 1 1 0 0 +EDGE2 4631 4591 0.0348031 -0.00633084 0.00949972 1 0 1 1 0 0 +EDGE2 4631 4592 0.988956 0.0677374 0.0151599 1 0 1 1 0 0 +EDGE2 4632 4591 -0.864975 -0.0573092 -0.0457802 1 0 1 1 0 0 +EDGE2 4632 4631 -0.999883 -0.19122 -0.00513785 1 0 1 1 0 0 +EDGE2 4632 4592 0.0331169 0.0320229 0.0163618 1 0 1 1 0 0 +EDGE2 4632 4593 0.904159 -0.0836991 -0.0151101 1 0 1 1 0 0 +EDGE2 4633 4632 -1.10507 -0.0213475 -0.0172996 1 0 1 1 0 0 +EDGE2 4633 4592 -1.02894 -0.000433795 -0.0170066 1 0 1 1 0 0 +EDGE2 4633 4593 -0.0172948 -0.100772 -0.0319075 1 0 1 1 0 0 +EDGE2 4633 4594 1.0503 -0.0012568 -0.0511584 1 0 1 1 0 0 +EDGE2 4634 4593 -1.07084 -0.120809 -0.0158259 1 0 1 1 0 0 +EDGE2 4634 4633 -1.01966 0.00507806 -0.0100753 1 0 1 1 0 0 +EDGE2 4634 4594 0.0166588 0.0624687 -0.0305284 1 0 1 1 0 0 +EDGE2 4634 2915 1.01003 -0.00457226 -3.15837 1 0 1 1 0 0 +EDGE2 4634 4595 0.963005 -0.0193787 -0.00684997 1 0 1 1 0 0 +EDGE2 4634 3595 1.00605 -0.00018286 -3.15915 1 0 1 1 0 0 +EDGE2 4634 3735 0.986889 0.0855101 -3.15197 1 0 1 1 0 0 +EDGE2 4634 3755 0.975504 -0.012741 -3.13043 1 0 1 1 0 0 +EDGE2 4634 3575 1.03997 -0.0397658 -3.11773 1 0 1 1 0 0 +EDGE2 4635 4634 -1.05168 0.0731559 -0.0160509 1 0 1 1 0 0 +EDGE2 4635 4594 -0.99068 -0.107351 0.0176619 1 0 1 1 0 0 +EDGE2 4635 2915 -0.00180496 -0.025131 -3.14387 1 0 1 1 0 0 +EDGE2 4635 2916 -0.0456109 -1.0353 -1.58151 1 0 1 1 0 0 +EDGE2 4635 3736 0.094391 -0.934348 -1.58859 1 0 1 1 0 0 +EDGE2 4635 4596 -0.0039777 -1.03612 -1.5476 1 0 1 1 0 0 +EDGE2 4635 3576 0.0611692 -0.888092 -1.58212 1 0 1 1 0 0 +EDGE2 4635 4595 -0.0736163 0.019888 -0.000291222 1 0 1 1 0 0 +EDGE2 4635 3595 -0.050691 0.0893489 -3.13679 1 0 1 1 0 0 +EDGE2 4635 3735 -0.0564398 0.0399903 -3.14168 1 0 1 1 0 0 +EDGE2 4635 3755 -0.028803 -0.0157854 -3.11517 1 0 1 1 0 0 +EDGE2 4635 3575 -0.0391741 -0.0629345 -3.18247 1 0 1 1 0 0 +EDGE2 4635 2914 0.96253 -0.00363079 -3.13455 1 0 1 1 0 0 +EDGE2 4635 3594 1.05933 -0.0189018 -3.12801 1 0 1 1 0 0 +EDGE2 4635 3734 1.08981 -0.0562048 -3.147 1 0 1 1 0 0 +EDGE2 4635 3754 1.04144 -0.0315805 -3.1356 1 0 1 1 0 0 +EDGE2 4635 3574 0.943239 -0.0116974 -3.11942 1 0 1 1 0 0 +EDGE2 4635 3596 0.0265904 1.01431 1.55527 1 0 1 1 0 0 +EDGE2 4635 3756 -0.0129047 0.969847 1.59946 1 0 1 1 0 0 +EDGE2 4636 2915 -0.892014 0.023157 1.60247 1 0 1 1 0 0 +EDGE2 4636 4635 -1.02477 0.0378113 -1.57512 1 0 1 1 0 0 +EDGE2 4636 4595 -1.02012 -0.00946378 -1.57731 1 0 1 1 0 0 +EDGE2 4636 3595 -0.978339 0.0183207 1.54843 1 0 1 1 0 0 +EDGE2 4636 3735 -1.02508 -0.0581841 1.53746 1 0 1 1 0 0 +EDGE2 4636 3755 -0.881004 -0.0131397 1.55874 1 0 1 1 0 0 +EDGE2 4636 3575 -1.04928 0.0298049 1.56911 1 0 1 1 0 0 +EDGE2 4636 3597 1.1251 0.00606079 -0.00530884 1 0 1 1 0 0 +EDGE2 4636 3596 -0.0494148 0.0639911 0.0388236 1 0 1 1 0 0 +EDGE2 4636 3756 0.0402185 -0.0212823 0.0210914 1 0 1 1 0 0 +EDGE2 4636 3757 0.971237 0.0202842 0.0123192 1 0 1 1 0 0 +EDGE2 4637 3597 0.0283579 -0.00347692 -0.00332527 1 0 1 1 0 0 +EDGE2 4637 4636 -0.955245 0.0176307 -0.02175 1 0 1 1 0 0 +EDGE2 4637 3596 -1.02155 0.0215814 0.00395313 1 0 1 1 0 0 +EDGE2 4637 3756 -1.04905 -0.0478127 0.0111907 1 0 1 1 0 0 +EDGE2 4637 3757 0.0684657 -0.0382482 -0.040064 1 0 1 1 0 0 +EDGE2 4637 3598 0.973982 -0.033418 0.00191302 1 0 1 1 0 0 +EDGE2 4637 3758 1.0704 -0.0479616 0.0225568 1 0 1 1 0 0 +EDGE2 4638 3597 -1.04077 -0.0309028 0.0168144 1 0 1 1 0 0 +EDGE2 4638 4637 -1.08019 -0.0241597 0.00402716 1 0 1 1 0 0 +EDGE2 4638 3757 -1.0277 0.0169984 -0.00495787 1 0 1 1 0 0 +EDGE2 4638 3598 -0.0101972 0.048606 -0.0181747 1 0 1 1 0 0 +EDGE2 4638 3758 -0.0526637 -0.0489212 0.0117446 1 0 1 1 0 0 +EDGE2 4638 3599 0.958494 0.0243635 0.0163142 1 0 1 1 0 0 +EDGE2 4638 3759 0.980386 0.0201835 -0.00298051 1 0 1 1 0 0 +EDGE2 4639 4638 -1.00298 -0.0379354 0.00229249 1 0 1 1 0 0 +EDGE2 4639 3598 -1.03125 0.0514583 0.0210533 1 0 1 1 0 0 +EDGE2 4639 3758 -0.951037 -0.0581974 0.0268353 1 0 1 1 0 0 +EDGE2 4639 3599 0.0759919 -0.0501964 0.0214301 1 0 1 1 0 0 +EDGE2 4639 3759 0.0530875 -0.0383785 -0.016118 1 0 1 1 0 0 +EDGE2 4639 3680 1.02655 0.0095324 -3.11227 1 0 1 1 0 0 +EDGE2 4639 3820 1.03708 -0.142876 -3.12851 1 0 1 1 0 0 +EDGE2 4639 3760 1.02066 0.101073 -0.00685611 1 0 1 1 0 0 +EDGE2 4639 3600 1.02441 0.070465 -0.00527002 1 0 1 1 0 0 +EDGE2 4639 3640 0.99776 -0.0202114 -3.16028 1 0 1 1 0 0 +EDGE2 4639 3660 1.10293 0.0266259 -3.14238 1 0 1 1 0 0 +EDGE2 4640 4639 -1.05341 0.0295928 -0.0146857 1 0 1 1 0 0 +EDGE2 4640 3599 -1.04013 -0.0292303 0.024213 1 0 1 1 0 0 +EDGE2 4640 3759 -0.958562 -0.0272071 0.0119909 1 0 1 1 0 0 +EDGE2 4640 3680 0.0238875 -0.122546 -3.15019 1 0 1 1 0 0 +EDGE2 4640 3601 0.0188968 1.03065 1.54364 1 0 1 1 0 0 +EDGE2 4640 3820 0.0569684 -0.0199604 -3.11619 1 0 1 1 0 0 +EDGE2 4640 3760 -0.0470466 0.0164076 0.0129563 1 0 1 1 0 0 +EDGE2 4640 3761 -0.10553 -1.04332 -1.57151 1 0 1 1 0 0 +EDGE2 4640 3600 -0.0228513 0.0501364 -0.0238835 1 0 1 1 0 0 +EDGE2 4640 3640 -0.0470982 0.0928817 -3.16265 1 0 1 1 0 0 +EDGE2 4640 3660 -0.0874572 -0.0424772 -3.15468 1 0 1 1 0 0 +EDGE2 4640 3821 0.0689272 -0.993975 -1.56996 1 0 1 1 0 0 +EDGE2 4640 3641 0.0131617 -0.992453 -1.57407 1 0 1 1 0 0 +EDGE2 4640 3661 0.0233159 -1.06513 -1.5707 1 0 1 1 0 0 +EDGE2 4640 3681 0.0358284 -0.959781 -1.57639 1 0 1 1 0 0 +EDGE2 4640 3659 0.943878 0.0120663 -3.15445 1 0 1 1 0 0 +EDGE2 4640 3679 1.07129 0.0637231 -3.15314 1 0 1 1 0 0 +EDGE2 4640 3819 0.98768 -0.0308429 -3.14064 1 0 1 1 0 0 +EDGE2 4640 3639 1.00275 -0.0629238 -3.16203 1 0 1 1 0 0 +EDGE2 4641 3680 -1.03332 -0.0272266 1.60331 1 0 1 1 0 0 +EDGE2 4641 3602 1.08296 -0.0477824 -0.0274666 1 0 1 1 0 0 +EDGE2 4641 3601 -0.0137485 -0.0298588 -0.0184964 1 0 1 1 0 0 +EDGE2 4641 3820 -1.03862 0.0182635 1.5862 1 0 1 1 0 0 +EDGE2 4641 4640 -1.01516 0.0295002 -1.59124 1 0 1 1 0 0 +EDGE2 4641 3760 -1.01053 -0.0802361 -1.57007 1 0 1 1 0 0 +EDGE2 4641 3600 -0.968164 0.119397 -1.54973 1 0 1 1 0 0 +EDGE2 4641 3640 -1.04726 0.0140184 1.52745 1 0 1 1 0 0 +EDGE2 4641 3660 -1.02087 -0.0644414 1.55367 1 0 1 1 0 0 +EDGE2 4642 3603 1.02249 -0.0695818 -0.0102359 1 0 1 1 0 0 +EDGE2 4642 3602 -0.00896492 0.0286978 -0.0366767 1 0 1 1 0 0 +EDGE2 4642 3601 -1.03842 -0.0819973 0.00407241 1 0 1 1 0 0 +EDGE2 4642 4641 -0.955194 -0.024271 0.0112448 1 0 1 1 0 0 +EDGE2 4643 3604 0.97406 -0.0323225 0.00896317 1 0 1 1 0 0 +EDGE2 4643 3603 -0.0275887 0.0790153 0.0100649 1 0 1 1 0 0 +EDGE2 4643 4642 -0.952668 -0.0688123 0.0108433 1 0 1 1 0 0 +EDGE2 4643 3602 -1.05277 0.0365635 0.0046998 1 0 1 1 0 0 +EDGE2 4644 3605 1.01079 -0.0834559 -0.0254063 1 0 1 1 0 0 +EDGE2 4644 4585 1.03254 0.0437359 -3.19817 1 0 1 1 0 0 +EDGE2 4644 3604 -0.0525697 -0.0132394 -0.0460275 1 0 1 1 0 0 +EDGE2 4644 3603 -0.9256 -0.0279589 0.0304069 1 0 1 1 0 0 +EDGE2 4644 4643 -0.937542 0.0467251 0.0114196 1 0 1 1 0 0 +EDGE2 4645 4586 -0.0133798 0.973419 1.57249 1 0 1 1 0 0 +EDGE2 4645 4644 -1.01038 0.0711581 0.0120862 1 0 1 1 0 0 +EDGE2 4645 4584 1.0337 0.0994288 -3.16308 1 0 1 1 0 0 +EDGE2 4645 3605 -0.0171161 -0.0594614 -0.0223662 1 0 1 1 0 0 +EDGE2 4645 4585 -0.0092852 0.0253062 -3.11639 1 0 1 1 0 0 +EDGE2 4645 3606 0.0870258 -1.05262 -1.54992 1 0 1 1 0 0 +EDGE2 4645 3604 -1.04225 -0.0490899 -0.00381886 1 0 1 1 0 0 +EDGE2 4646 4587 1.00542 0.0165513 -0.0193927 1 0 1 1 0 0 +EDGE2 4646 4586 -0.0514693 -0.057136 0.0174059 1 0 1 1 0 0 +EDGE2 4646 3605 -0.947049 0.0064024 -1.54358 1 0 1 1 0 0 +EDGE2 4646 4645 -1.03458 0.0464458 -1.54339 1 0 1 1 0 0 +EDGE2 4646 4585 -0.929156 0.00450371 1.54676 1 0 1 1 0 0 +EDGE2 4647 4588 0.895386 0.0288508 0.0240289 1 0 1 1 0 0 +EDGE2 4647 4587 0.00702515 -0.0559483 0.0217599 1 0 1 1 0 0 +EDGE2 4647 4646 -1.00585 -0.0260321 0.00153094 1 0 1 1 0 0 +EDGE2 4647 4586 -1.02704 -0.00184118 -0.00184252 1 0 1 1 0 0 +EDGE2 4648 4589 1.00055 -0.0397674 0.00595084 1 0 1 1 0 0 +EDGE2 4648 4588 -0.048825 -0.00971149 0.0135036 1 0 1 1 0 0 +EDGE2 4648 4587 -0.996807 0.0985518 0.0185442 1 0 1 1 0 0 +EDGE2 4648 4647 -0.998268 0.0215063 -0.0113133 1 0 1 1 0 0 +EDGE2 4649 4630 0.861848 0.0117845 -3.1552 1 0 1 1 0 0 +EDGE2 4649 4590 0.974462 0.0110762 -0.0352164 1 0 1 1 0 0 +EDGE2 4649 4589 0.059096 -0.0974977 -0.00635022 1 0 1 1 0 0 +EDGE2 4649 4648 -0.930508 0.103284 -0.017358 1 0 1 1 0 0 +EDGE2 4649 4588 -1.08162 0.119474 -0.000216393 1 0 1 1 0 0 +EDGE2 4650 4629 0.975766 0.0456104 -3.12546 1 0 1 1 0 0 +EDGE2 4650 4630 0.101042 -0.0770025 -3.15651 1 0 1 1 0 0 +EDGE2 4650 4590 0.0159151 -0.00972698 0.00227581 1 0 1 1 0 0 +EDGE2 4650 4591 0.0665711 0.980796 1.5709 1 0 1 1 0 0 +EDGE2 4650 4631 0.0180344 0.994099 1.54376 1 0 1 1 0 0 +EDGE2 4650 4649 -0.969354 -0.0448005 -0.00118667 1 0 1 1 0 0 +EDGE2 4650 4589 -1.02478 -0.0211039 -0.0107182 1 0 1 1 0 0 +EDGE2 4651 4630 -0.925125 0.0542608 1.58288 1 0 1 1 0 0 +EDGE2 4651 4650 -1.01556 -0.0182911 -1.56666 1 0 1 1 0 0 +EDGE2 4651 4590 -0.977252 -0.013039 -1.55435 1 0 1 1 0 0 +EDGE2 4651 4632 1.04027 0.106223 0.0258915 1 0 1 1 0 0 +EDGE2 4651 4591 0.00252462 0.00855821 -0.0182467 1 0 1 1 0 0 +EDGE2 4651 4631 -0.0606797 0.0159801 -0.00859501 1 0 1 1 0 0 +EDGE2 4651 4592 1.03457 0.02673 -0.00580511 1 0 1 1 0 0 +EDGE2 4652 4632 0.00284918 0.0869813 0.0174153 1 0 1 1 0 0 +EDGE2 4652 4591 -0.909508 0.0227117 -0.0164718 1 0 1 1 0 0 +EDGE2 4652 4651 -1.10262 -0.0109971 -0.0141927 1 0 1 1 0 0 +EDGE2 4652 4631 -1.01573 -0.0147152 -0.0298967 1 0 1 1 0 0 +EDGE2 4652 4592 0.0978582 0.0943016 -0.0140838 1 0 1 1 0 0 +EDGE2 4652 4593 1.02325 0.00249182 -0.00127072 1 0 1 1 0 0 +EDGE2 4652 4633 1.01692 -0.0278467 0.0290677 1 0 1 1 0 0 +EDGE2 4653 4632 -0.966878 -0.0650185 -0.0168728 1 0 1 1 0 0 +EDGE2 4653 4652 -0.989404 0.0566774 -0.0371269 1 0 1 1 0 0 +EDGE2 4653 4592 -1.0315 -0.0522819 -0.0143923 1 0 1 1 0 0 +EDGE2 4653 4593 0.0906682 0.0075165 0.0106727 1 0 1 1 0 0 +EDGE2 4653 4633 -0.0232926 0.0465292 -0.00271621 1 0 1 1 0 0 +EDGE2 4653 4634 0.987158 0.0102499 0.0105474 1 0 1 1 0 0 +EDGE2 4653 4594 0.95537 -0.0719671 -0.0142134 1 0 1 1 0 0 +EDGE2 4654 4653 -0.972723 -0.0330386 -0.0101203 1 0 1 1 0 0 +EDGE2 4654 4593 -1.04079 -0.110083 -0.0255483 1 0 1 1 0 0 +EDGE2 4654 4633 -0.972992 0.0745088 -0.0227128 1 0 1 1 0 0 +EDGE2 4654 4634 -0.0503712 0.0458507 -0.0236648 1 0 1 1 0 0 +EDGE2 4654 4594 0.0176423 -0.0329798 -0.0353982 1 0 1 1 0 0 +EDGE2 4654 2915 0.958239 -0.0188159 -3.14461 1 0 1 1 0 0 +EDGE2 4654 4635 0.969139 -0.00571692 0.00648049 1 0 1 1 0 0 +EDGE2 4654 4595 0.932496 0.0922612 0.0178625 1 0 1 1 0 0 +EDGE2 4654 3595 1.00927 0.00594632 -3.14452 1 0 1 1 0 0 +EDGE2 4654 3735 1.04517 0.0140083 -3.15705 1 0 1 1 0 0 +EDGE2 4654 3755 0.937749 -0.0459182 -3.15813 1 0 1 1 0 0 +EDGE2 4654 3575 0.981968 0.0933038 -3.15839 1 0 1 1 0 0 +EDGE2 4655 4634 -1.02246 -0.028316 0.0255005 1 0 1 1 0 0 +EDGE2 4655 4654 -0.963119 0.102577 -0.0326628 1 0 1 1 0 0 +EDGE2 4655 4594 -0.991534 0.0117545 -0.033538 1 0 1 1 0 0 +EDGE2 4655 2915 -0.0441432 0.0231123 -3.1412 1 0 1 1 0 0 +EDGE2 4655 4635 0.025893 -0.0261871 -0.022978 1 0 1 1 0 0 +EDGE2 4655 2916 0.0806035 -1.06511 -1.55006 1 0 1 1 0 0 +EDGE2 4655 3736 0.0189004 -1.00648 -1.55056 1 0 1 1 0 0 +EDGE2 4655 4596 0.0680975 -1.01511 -1.57487 1 0 1 1 0 0 +EDGE2 4655 3576 -0.0196517 -0.902668 -1.54797 1 0 1 1 0 0 +EDGE2 4655 4595 -0.0471961 -0.00711248 0.0148477 1 0 1 1 0 0 +EDGE2 4655 3595 0.0948522 -0.0770973 -3.13225 1 0 1 1 0 0 +EDGE2 4655 3735 0.0484879 0.0170679 -3.15769 1 0 1 1 0 0 +EDGE2 4655 3755 -0.0854883 -0.0487742 -3.13985 1 0 1 1 0 0 +EDGE2 4655 3575 -0.00870692 -0.0216036 -3.16573 1 0 1 1 0 0 +EDGE2 4655 2914 0.996646 0.103451 -3.15235 1 0 1 1 0 0 +EDGE2 4655 3594 1.07177 -0.0455806 -3.13254 1 0 1 1 0 0 +EDGE2 4655 3734 0.929752 -0.0420534 -3.12613 1 0 1 1 0 0 +EDGE2 4655 3754 1.02241 0.0225481 -3.13364 1 0 1 1 0 0 +EDGE2 4655 3574 1.01234 -0.0374331 -3.1204 1 0 1 1 0 0 +EDGE2 4655 4636 -0.000695967 1.0492 1.56358 1 0 1 1 0 0 +EDGE2 4655 3596 0.0191099 0.963122 1.54007 1 0 1 1 0 0 +EDGE2 4655 3756 0.0363166 1.02278 1.5612 1 0 1 1 0 0 +EDGE2 4656 2915 -0.962 -0.0260339 1.57583 1 0 1 1 0 0 +EDGE2 4656 4635 -1.16984 -0.00249452 -1.56173 1 0 1 1 0 0 +EDGE2 4656 4655 -1.01236 -0.0114787 -1.55534 1 0 1 1 0 0 +EDGE2 4656 4595 -0.979353 0.0312784 -1.59727 1 0 1 1 0 0 +EDGE2 4656 3595 -1.0116 0.0533783 1.61033 1 0 1 1 0 0 +EDGE2 4656 3735 -1.09771 -0.0252588 1.60096 1 0 1 1 0 0 +EDGE2 4656 3755 -0.994405 -0.0153407 1.56454 1 0 1 1 0 0 +EDGE2 4656 3575 -1.05927 0.00317627 1.55275 1 0 1 1 0 0 +EDGE2 4656 3597 1.02145 0.00204011 -0.00123596 1 0 1 1 0 0 +EDGE2 4656 4636 -0.00768083 -0.0649218 -0.00832926 1 0 1 1 0 0 +EDGE2 4656 3596 -0.0661186 0.0152755 -0.00518506 1 0 1 1 0 0 +EDGE2 4656 3756 0.0140201 0.00616316 0.00200974 1 0 1 1 0 0 +EDGE2 4656 4637 0.958761 0.0388257 0.030338 1 0 1 1 0 0 +EDGE2 4656 3757 0.975156 -0.0311424 -0.00114849 1 0 1 1 0 0 +EDGE2 4657 3597 0.0149071 0.0285886 0.00819193 1 0 1 1 0 0 +EDGE2 4657 4636 -1.01522 0.0508749 -0.0234717 1 0 1 1 0 0 +EDGE2 4657 4656 -1.00734 -0.0671426 -0.0133293 1 0 1 1 0 0 +EDGE2 4657 3596 -0.955662 -0.0383314 0.00565175 1 0 1 1 0 0 +EDGE2 4657 3756 -1.0325 -0.0801456 0.00331254 1 0 1 1 0 0 +EDGE2 4657 4637 -0.0100283 -0.0187721 0.0264415 1 0 1 1 0 0 +EDGE2 4657 3757 0.0026029 0.0529142 0.00518336 1 0 1 1 0 0 +EDGE2 4657 4638 0.97875 -0.0641533 -0.00554536 1 0 1 1 0 0 +EDGE2 4657 3598 0.961012 -0.0257196 0.0127532 1 0 1 1 0 0 +EDGE2 4657 3758 1.00014 -0.0403112 -0.013477 1 0 1 1 0 0 +EDGE2 4658 3597 -1.05208 -0.0517667 -0.0284291 1 0 1 1 0 0 +EDGE2 4658 4637 -1.06672 -0.0209178 -0.0379802 1 0 1 1 0 0 +EDGE2 4658 4657 -1.00344 0.00303334 -0.00129388 1 0 1 1 0 0 +EDGE2 4658 3757 -1.01035 0.0495754 -0.0261623 1 0 1 1 0 0 +EDGE2 4658 4638 -0.022037 -0.00193929 -0.0181651 1 0 1 1 0 0 +EDGE2 4658 3598 -0.0452501 0.0191312 0.0154816 1 0 1 1 0 0 +EDGE2 4658 3758 -0.00670202 0.0135022 -0.00373532 1 0 1 1 0 0 +EDGE2 4658 4639 0.984522 -0.0110674 0.0170623 1 0 1 1 0 0 +EDGE2 4658 3599 1.04848 0.0891485 -0.0157689 1 0 1 1 0 0 +EDGE2 4658 3759 0.99084 0.0253534 0.000343303 1 0 1 1 0 0 +EDGE2 4659 4638 -0.96893 -0.000533945 0.00998902 1 0 1 1 0 0 +EDGE2 4659 4658 -1.01367 0.0513824 -0.0219675 1 0 1 1 0 0 +EDGE2 4659 3598 -0.955814 -0.0765802 -0.00619971 1 0 1 1 0 0 +EDGE2 4659 3758 -1.00559 -0.0212086 0.00732997 1 0 1 1 0 0 +EDGE2 4659 4639 -0.0604405 -0.0285692 0.0109693 1 0 1 1 0 0 +EDGE2 4659 3599 0.0812511 -0.0619514 0.0221572 1 0 1 1 0 0 +EDGE2 4659 3759 0.0152684 0.0402099 -0.0212574 1 0 1 1 0 0 +EDGE2 4659 3680 0.985927 -0.0750994 -3.13595 1 0 1 1 0 0 +EDGE2 4659 3820 0.967488 -0.125361 -3.12903 1 0 1 1 0 0 +EDGE2 4659 4640 0.958914 0.0491745 0.00545099 1 0 1 1 0 0 +EDGE2 4659 3760 1.03675 -0.0275715 -0.0497167 1 0 1 1 0 0 +EDGE2 4659 3600 0.931642 0.0258717 0.024032 1 0 1 1 0 0 +EDGE2 4659 3640 1.06156 -0.0237318 -3.14224 1 0 1 1 0 0 +EDGE2 4659 3660 0.994072 -0.004357 -3.13324 1 0 1 1 0 0 +EDGE2 4660 4639 -0.990567 -0.0244056 -0.0031824 1 0 1 1 0 0 +EDGE2 4660 4659 -0.987969 0.0399176 0.000619579 1 0 1 1 0 0 +EDGE2 4660 3599 -0.980557 -0.053702 -0.0235167 1 0 1 1 0 0 +EDGE2 4660 3759 -1.08145 -0.0524642 0.0167335 1 0 1 1 0 0 +EDGE2 4660 3680 -0.0578543 0.116547 -3.10044 1 0 1 1 0 0 +EDGE2 4660 3601 -0.0630176 0.945224 1.57783 1 0 1 1 0 0 +EDGE2 4660 4641 -0.0257854 0.972697 1.54593 1 0 1 1 0 0 +EDGE2 4660 3820 0.0139917 -0.000372654 -3.1488 1 0 1 1 0 0 +EDGE2 4660 4640 -0.0306407 -0.0644482 0.0128124 1 0 1 1 0 0 +EDGE2 4660 3760 0.0539505 -0.05643 -0.0192027 1 0 1 1 0 0 +EDGE2 4660 3761 -0.0180349 -1.01633 -1.57905 1 0 1 1 0 0 +EDGE2 4660 3600 -0.0271755 -0.138391 0.0327444 1 0 1 1 0 0 +EDGE2 4660 3640 -0.0511911 -0.0826109 -3.13476 1 0 1 1 0 0 +EDGE2 4660 3660 -0.00784069 -0.0224016 -3.13371 1 0 1 1 0 0 +EDGE2 4660 3821 0.0277858 -1.0151 -1.57105 1 0 1 1 0 0 +EDGE2 4660 3641 0.040355 -1.06589 -1.56842 1 0 1 1 0 0 +EDGE2 4660 3661 0.0260898 -1.08677 -1.56357 1 0 1 1 0 0 +EDGE2 4660 3681 0.04364 -0.98814 -1.54494 1 0 1 1 0 0 +EDGE2 4660 3659 0.997048 -0.0633337 -3.10924 1 0 1 1 0 0 +EDGE2 4660 3679 0.99628 0.106354 -3.1106 1 0 1 1 0 0 +EDGE2 4660 3819 1.08645 -0.0269481 -3.17421 1 0 1 1 0 0 +EDGE2 4660 3639 1.01088 0.025257 -3.14915 1 0 1 1 0 0 +EDGE2 4661 3680 -1.02668 -0.069469 1.59312 1 0 1 1 0 0 +EDGE2 4661 4642 0.988944 0.0105467 -0.0439054 1 0 1 1 0 0 +EDGE2 4661 3602 0.906891 -0.120364 0.0391157 1 0 1 1 0 0 +EDGE2 4661 3601 0.0417291 -0.0254152 -0.00730058 1 0 1 1 0 0 +EDGE2 4661 4641 -0.0562881 -0.0306232 0.0127601 1 0 1 1 0 0 +EDGE2 4661 3820 -1.01334 0.0554313 1.57377 1 0 1 1 0 0 +EDGE2 4661 4640 -1.02426 -0.0246868 -1.51781 1 0 1 1 0 0 +EDGE2 4661 4660 -0.954642 0.111006 -1.60694 1 0 1 1 0 0 +EDGE2 4661 3760 -0.895194 0.0426574 -1.55977 1 0 1 1 0 0 +EDGE2 4661 3600 -0.972314 -0.0251946 -1.55693 1 0 1 1 0 0 +EDGE2 4661 3640 -1.04806 0.0192068 1.54591 1 0 1 1 0 0 +EDGE2 4661 3660 -1.10839 0.0260414 1.58429 1 0 1 1 0 0 +EDGE2 4662 3603 1.05072 -0.0149471 0.0200316 1 0 1 1 0 0 +EDGE2 4662 4643 1.03341 -0.0422426 0.0168235 1 0 1 1 0 0 +EDGE2 4662 4661 -0.963744 -0.0357991 -0.0119135 1 0 1 1 0 0 +EDGE2 4662 4642 -0.0665607 -0.0246704 -0.0163644 1 0 1 1 0 0 +EDGE2 4662 3602 0.000445345 -0.0384819 0.00624969 1 0 1 1 0 0 +EDGE2 4662 3601 -0.978207 0.094634 -0.0160591 1 0 1 1 0 0 +EDGE2 4662 4641 -1.05676 0.0260887 -0.04188 1 0 1 1 0 0 +EDGE2 4663 4644 1.00927 -0.0403627 -0.00240081 1 0 1 1 0 0 +EDGE2 4663 3604 1.0015 0.0106406 0.0371895 1 0 1 1 0 0 +EDGE2 4663 3603 -0.0934107 0.034852 -0.00507085 1 0 1 1 0 0 +EDGE2 4663 4643 0.0587546 -0.0176915 0.00299121 1 0 1 1 0 0 +EDGE2 4663 4642 -1.02069 0.0796316 0.0347705 1 0 1 1 0 0 +EDGE2 4663 4662 -1.02021 0.0456665 0.0131842 1 0 1 1 0 0 +EDGE2 4663 3602 -1.01025 -0.00377438 0.0124058 1 0 1 1 0 0 +EDGE2 4664 4644 -0.0829876 -0.073498 -0.000569468 1 0 1 1 0 0 +EDGE2 4664 3605 0.98109 -0.0958771 0.00365125 1 0 1 1 0 0 +EDGE2 4664 4645 1.07964 0.0506285 -0.0307767 1 0 1 1 0 0 +EDGE2 4664 4585 0.951046 -0.0340408 -3.11926 1 0 1 1 0 0 +EDGE2 4664 4663 -1.03126 -0.0814367 0.000900346 1 0 1 1 0 0 +EDGE2 4664 3604 -0.039029 -0.0215556 0.031263 1 0 1 1 0 0 +EDGE2 4664 3603 -0.959785 0.0641182 -0.0161793 1 0 1 1 0 0 +EDGE2 4664 4643 -1.0887 -0.075421 -0.00545536 1 0 1 1 0 0 +EDGE2 4665 4646 -0.0342557 1.00324 1.5488 1 0 1 1 0 0 +EDGE2 4665 4586 0.00928584 1.03788 1.55902 1 0 1 1 0 0 +EDGE2 4665 4644 -0.927357 0.0129266 0.0119348 1 0 1 1 0 0 +EDGE2 4665 4584 1.07219 0.0696199 -3.18828 1 0 1 1 0 0 +EDGE2 4665 3605 0.024721 -0.034566 -0.000396297 1 0 1 1 0 0 +EDGE2 4665 4645 0.0311411 0.0110288 0.0131542 1 0 1 1 0 0 +EDGE2 4665 4585 0.0191633 -0.080765 -3.14821 1 0 1 1 0 0 +EDGE2 4665 4664 -0.892408 0.028605 -0.0418035 1 0 1 1 0 0 +EDGE2 4665 3606 -0.083349 -1.00395 -1.54044 1 0 1 1 0 0 +EDGE2 4665 3604 -0.940024 -0.0400466 -0.00899283 1 0 1 1 0 0 +EDGE2 4666 3605 -0.999895 0.0520991 1.55885 1 0 1 1 0 0 +EDGE2 4666 4645 -0.881465 0.0105096 1.57562 1 0 1 1 0 0 +EDGE2 4666 4665 -0.973606 -0.00268324 1.55786 1 0 1 1 0 0 +EDGE2 4666 4585 -1.06829 0.0143759 -1.56881 1 0 1 1 0 0 +EDGE2 4666 3607 0.966702 0.0468591 0.00626834 1 0 1 1 0 0 +EDGE2 4666 3606 0.0672666 0.0310709 -0.0332078 1 0 1 1 0 0 +EDGE2 4667 3607 -0.0325639 0.0665069 -0.0084488 1 0 1 1 0 0 +EDGE2 4667 3606 -0.988632 -0.00347093 0.0101812 1 0 1 1 0 0 +EDGE2 4667 4666 -1.0077 0.0238012 -0.0203415 1 0 1 1 0 0 +EDGE2 4667 3608 0.995882 -0.043266 -0.015121 1 0 1 1 0 0 +EDGE2 4668 3607 -0.995741 -0.0550594 0.0106432 1 0 1 1 0 0 +EDGE2 4668 4667 -1.06154 0.0105485 -0.0028829 1 0 1 1 0 0 +EDGE2 4668 3608 -0.0416746 -0.0452643 -0.0520472 1 0 1 1 0 0 +EDGE2 4668 3609 1.00958 -5.75826e-05 -0.00769182 1 0 1 1 0 0 +EDGE2 4669 3608 -0.983541 -0.02742 -0.0401129 1 0 1 1 0 0 +EDGE2 4669 4668 -0.935336 -0.00175483 0.0172225 1 0 1 1 0 0 +EDGE2 4669 3609 0.00967239 0.0844282 -0.00293299 1 0 1 1 0 0 +EDGE2 4669 4570 0.958803 -0.0280334 -3.1176 1 0 1 1 0 0 +EDGE2 4669 3610 1.01029 0.00675 -0.050597 1 0 1 1 0 0 +EDGE2 4669 3630 1.04846 0.00944227 -3.14516 1 0 1 1 0 0 +EDGE2 4670 3609 -0.955182 -0.125095 -0.0173934 1 0 1 1 0 0 +EDGE2 4670 4669 -1.0074 0.0392975 0.0243369 1 0 1 1 0 0 +EDGE2 4670 4571 -0.00064009 1.00845 1.58041 1 0 1 1 0 0 +EDGE2 4670 3611 -0.064804 0.971878 1.58017 1 0 1 1 0 0 +EDGE2 4670 4570 0.0234693 0.012238 -3.10615 1 0 1 1 0 0 +EDGE2 4670 3610 0.0155283 -0.0813253 -0.0250708 1 0 1 1 0 0 +EDGE2 4670 3630 0.0277384 0.0138513 -3.13764 1 0 1 1 0 0 +EDGE2 4670 3631 0.021879 -1.02074 -1.60846 1 0 1 1 0 0 +EDGE2 4670 3629 0.959427 0.0047708 -3.17214 1 0 1 1 0 0 +EDGE2 4670 4569 1.03011 -0.0815687 -3.11922 1 0 1 1 0 0 +EDGE2 4671 3612 1.00933 0.0364697 0.00463797 1 0 1 1 0 0 +EDGE2 4671 4572 0.986971 -0.0471048 -0.00692615 1 0 1 1 0 0 +EDGE2 4671 4571 -0.0197752 -0.0509384 0.0228897 1 0 1 1 0 0 +EDGE2 4671 3611 -0.0858485 0.0240697 0.0276821 1 0 1 1 0 0 +EDGE2 4671 4570 -1.02619 -0.00471719 1.59024 1 0 1 1 0 0 +EDGE2 4671 4670 -1.00889 -0.00235468 -1.58483 1 0 1 1 0 0 +EDGE2 4671 3610 -1.03114 0.0107938 -1.56447 1 0 1 1 0 0 +EDGE2 4671 3630 -0.979859 0.0584919 1.62172 1 0 1 1 0 0 +EDGE2 4672 3613 0.985761 0.0463532 -0.0368563 1 0 1 1 0 0 +EDGE2 4672 4573 1.03172 -0.0555549 0.00971701 1 0 1 1 0 0 +EDGE2 4672 3612 -0.0577261 0.118708 -0.0106823 1 0 1 1 0 0 +EDGE2 4672 4572 0.0884725 -0.0347454 -0.0102268 1 0 1 1 0 0 +EDGE2 4672 4571 -0.951236 0.0260335 -0.00742091 1 0 1 1 0 0 +EDGE2 4672 4671 -1.06781 -0.0109508 0.00570012 1 0 1 1 0 0 +EDGE2 4672 3611 -1.05174 -0.0640215 0.0216005 1 0 1 1 0 0 +EDGE2 4673 4574 0.901419 0.039538 -0.000571135 1 0 1 1 0 0 +EDGE2 4673 3614 1.00121 0.0728322 0.00314501 1 0 1 1 0 0 +EDGE2 4673 4672 -0.938835 -0.0774788 -0.0182372 1 0 1 1 0 0 +EDGE2 4673 3613 -0.0399399 -0.0660875 0.00193309 1 0 1 1 0 0 +EDGE2 4673 4573 0.0111907 0.113621 -0.00624421 1 0 1 1 0 0 +EDGE2 4673 3612 -0.943947 -0.0521374 0.00939023 1 0 1 1 0 0 +EDGE2 4673 4572 -1.08971 0.0387781 0.0194643 1 0 1 1 0 0 +EDGE2 4674 4575 1.0779 -0.00365461 -0.0096018 1 0 1 1 0 0 +EDGE2 4674 3615 1.02185 0.0040312 -0.0422429 1 0 1 1 0 0 +EDGE2 4674 4574 0.0650128 0.0241284 0.0216868 1 0 1 1 0 0 +EDGE2 4674 3614 0.0123248 -0.060918 -0.0238706 1 0 1 1 0 0 +EDGE2 4674 4673 -0.951599 -0.0836682 0.0024786 1 0 1 1 0 0 +EDGE2 4674 3613 -1.08349 -0.00827281 0.0206292 1 0 1 1 0 0 +EDGE2 4674 4573 -1.05435 0.000290214 0.0113243 1 0 1 1 0 0 +EDGE2 4675 4576 -0.0414826 1.01536 1.54632 1 0 1 1 0 0 +EDGE2 4675 4575 -0.0105266 0.0249225 -0.0037272 1 0 1 1 0 0 +EDGE2 4675 3615 -0.0274559 0.113384 0.0266641 1 0 1 1 0 0 +EDGE2 4675 3616 0.0339578 -0.966749 -1.57967 1 0 1 1 0 0 +EDGE2 4675 4574 -1.00943 -0.0116001 0.0246307 1 0 1 1 0 0 +EDGE2 4675 4674 -0.924291 -0.0725411 0.0040217 1 0 1 1 0 0 +EDGE2 4675 3614 -1.06615 -0.0127121 0.0420329 1 0 1 1 0 0 +EDGE2 4676 4577 0.997711 0.00256851 0.00637948 1 0 1 1 0 0 +EDGE2 4676 4576 0.0323768 0.0157401 -0.0359822 1 0 1 1 0 0 +EDGE2 4676 4575 -1.0099 -0.00686036 -1.59284 1 0 1 1 0 0 +EDGE2 4676 4675 -1.02222 -0.0120698 -1.55731 1 0 1 1 0 0 +EDGE2 4676 3615 -1.0488 0.0337093 -1.54785 1 0 1 1 0 0 +EDGE2 4677 4578 1.08961 -0.0653601 0.00488515 1 0 1 1 0 0 +EDGE2 4677 4577 0.0270926 -0.0855646 -0.0452985 1 0 1 1 0 0 +EDGE2 4677 4676 -0.961431 0.00235482 -0.0207927 1 0 1 1 0 0 +EDGE2 4677 4576 -0.959143 0.0642211 0.0152568 1 0 1 1 0 0 +EDGE2 4678 4579 1.05996 0.000364156 -0.0156251 1 0 1 1 0 0 +EDGE2 4678 4578 -0.0689868 0.0812656 -0.0108603 1 0 1 1 0 0 +EDGE2 4678 4577 -1.06544 0.0294601 0.0191238 1 0 1 1 0 0 +EDGE2 4678 4677 -0.968499 0.0260437 -0.0101329 1 0 1 1 0 0 +EDGE2 4679 4580 0.951997 0.05045 -0.02791 1 0 1 1 0 0 +EDGE2 4679 4579 -0.00860605 0.0451822 -0.00768769 1 0 1 1 0 0 +EDGE2 4679 4678 -1.0771 0.00170605 0.0318566 1 0 1 1 0 0 +EDGE2 4679 4578 -1.02272 0.0621696 -0.0167182 1 0 1 1 0 0 +EDGE2 4680 4580 -0.0208919 -0.0363691 0.00958485 1 0 1 1 0 0 +EDGE2 4680 4581 -0.00650206 0.96774 1.57253 1 0 1 1 0 0 +EDGE2 4680 4679 -1.11264 -0.0906509 -0.00237549 1 0 1 1 0 0 +EDGE2 4680 4579 -1.03255 0.0455492 -0.00257912 1 0 1 1 0 0 +EDGE2 4681 4580 -1.07844 -0.0598566 -1.54277 1 0 1 1 0 0 +EDGE2 4681 4680 -0.971079 0.127663 -1.57232 1 0 1 1 0 0 +EDGE2 4681 4581 -0.0682021 -0.0429469 -0.0102945 1 0 1 1 0 0 +EDGE2 4681 4582 0.934635 0.0306541 -0.0157696 1 0 1 1 0 0 +EDGE2 4682 4681 -1.00705 0.0720015 0.000137275 1 0 1 1 0 0 +EDGE2 4682 4581 -0.997084 -0.0624643 -0.000158272 1 0 1 1 0 0 +EDGE2 4682 4583 0.953426 0.0933419 0.00441303 1 0 1 1 0 0 +EDGE2 4682 4582 -0.0170983 -0.0174047 0.0166705 1 0 1 1 0 0 +EDGE2 4683 4583 0.00499497 0.0203485 0.0214532 1 0 1 1 0 0 +EDGE2 4683 4582 -0.987238 -0.0423273 -0.0170299 1 0 1 1 0 0 +EDGE2 4683 4682 -0.937551 -0.0809787 0.0529856 1 0 1 1 0 0 +EDGE2 4683 4584 0.992319 -0.015177 -0.0064253 1 0 1 1 0 0 +EDGE2 4684 4583 -0.967894 0.0174072 -0.0036677 1 0 1 1 0 0 +EDGE2 4684 4683 -1.00243 -0.0181026 0.00309114 1 0 1 1 0 0 +EDGE2 4684 4584 0.0625214 0.0245596 0.00240742 1 0 1 1 0 0 +EDGE2 4684 3605 1.09171 -0.0100076 -3.13885 1 0 1 1 0 0 +EDGE2 4684 4645 0.952578 -0.0295674 -3.13009 1 0 1 1 0 0 +EDGE2 4684 4665 0.982378 0.0724851 -3.15862 1 0 1 1 0 0 +EDGE2 4684 4585 0.979201 -0.0141077 0.0102084 1 0 1 1 0 0 +EDGE2 4685 4646 -0.0728589 -1.01155 -1.54159 1 0 1 1 0 0 +EDGE2 4685 4586 0.0190182 -0.930127 -1.54358 1 0 1 1 0 0 +EDGE2 4685 4644 1.02584 0.0507587 -3.16815 1 0 1 1 0 0 +EDGE2 4685 4684 -0.935125 -0.0552696 0.00647822 1 0 1 1 0 0 +EDGE2 4685 4584 -0.995988 -0.0365968 -0.00842871 1 0 1 1 0 0 +EDGE2 4685 3605 -0.0166613 0.00503566 -3.11941 1 0 1 1 0 0 +EDGE2 4685 4645 -0.0515566 0.000216447 -3.15973 1 0 1 1 0 0 +EDGE2 4685 4665 0.0170037 0.054063 -3.15088 1 0 1 1 0 0 +EDGE2 4685 4585 0.072519 0.0498128 0.0432161 1 0 1 1 0 0 +EDGE2 4685 4664 0.952152 0.109547 -3.14561 1 0 1 1 0 0 +EDGE2 4685 3606 -0.0161596 0.940163 1.58133 1 0 1 1 0 0 +EDGE2 4685 4666 0.0256151 0.987867 1.56254 1 0 1 1 0 0 +EDGE2 4685 3604 0.974586 0.0234028 -3.11642 1 0 1 1 0 0 +EDGE2 4686 3605 -1.06723 -0.00562 1.56726 1 0 1 1 0 0 +EDGE2 4686 4645 -1.02845 0.048742 1.62952 1 0 1 1 0 0 +EDGE2 4686 4665 -0.997546 -0.0671842 1.60218 1 0 1 1 0 0 +EDGE2 4686 4685 -0.944942 0.0783668 -1.56256 1 0 1 1 0 0 +EDGE2 4686 4585 -1.03524 0.0598813 -1.53688 1 0 1 1 0 0 +EDGE2 4686 3607 0.961212 0.0191288 0.00924514 1 0 1 1 0 0 +EDGE2 4686 3606 0.0348957 0.0737505 -0.0344621 1 0 1 1 0 0 +EDGE2 4686 4666 0.00714886 0.0409018 0.00610471 1 0 1 1 0 0 +EDGE2 4686 4667 0.945055 0.0106328 -0.00782305 1 0 1 1 0 0 +EDGE2 4687 3607 -0.0434387 0.0149561 0.0211074 1 0 1 1 0 0 +EDGE2 4687 3606 -0.999519 0.0124409 0.0429052 1 0 1 1 0 0 +EDGE2 4687 4686 -1.02426 -0.077774 -0.0173113 1 0 1 1 0 0 +EDGE2 4687 4666 -1.00667 -0.0625951 -0.00586217 1 0 1 1 0 0 +EDGE2 4687 4667 0.0455529 0.00568036 0.00883469 1 0 1 1 0 0 +EDGE2 4687 3608 0.909498 -0.0669308 -0.00955654 1 0 1 1 0 0 +EDGE2 4687 4668 0.992911 -0.0568333 -0.00992356 1 0 1 1 0 0 +EDGE2 4688 3607 -1.02599 0.0497123 0.00647737 1 0 1 1 0 0 +EDGE2 4688 4687 -1.0091 0.0527918 0.00951738 1 0 1 1 0 0 +EDGE2 4688 4667 -1.03836 0.0830301 -0.020234 1 0 1 1 0 0 +EDGE2 4688 3608 -0.0539294 -0.0584423 0.00859993 1 0 1 1 0 0 +EDGE2 4688 4668 -0.109177 -0.0367917 0.0113403 1 0 1 1 0 0 +EDGE2 4688 3609 0.951788 -0.0527618 0.045564 1 0 1 1 0 0 +EDGE2 4688 4669 1.04818 -0.0623477 0.00236516 1 0 1 1 0 0 +EDGE2 4689 3608 -1.06173 -0.0423895 -0.0285839 1 0 1 1 0 0 +EDGE2 4689 4668 -0.928297 -0.0235661 -0.00191694 1 0 1 1 0 0 +EDGE2 4689 4688 -0.9659 0.0772317 -0.0178809 1 0 1 1 0 0 +EDGE2 4689 3609 -0.0496938 -0.00599952 0.0193542 1 0 1 1 0 0 +EDGE2 4689 4669 0.0150039 -0.0250647 -0.000382058 1 0 1 1 0 0 +EDGE2 4689 4570 0.949207 -0.0160969 -3.12587 1 0 1 1 0 0 +EDGE2 4689 4670 1.04941 0.0460997 -0.00927947 1 0 1 1 0 0 +EDGE2 4689 3610 1.02153 -0.0983745 0.00014481 1 0 1 1 0 0 +EDGE2 4689 3630 0.989387 -0.015729 -3.18162 1 0 1 1 0 0 +EDGE2 4690 3609 -0.928345 -0.0775912 -0.0115965 1 0 1 1 0 0 +EDGE2 4690 4669 -0.906741 0.0387846 -0.0425588 1 0 1 1 0 0 +EDGE2 4690 4689 -0.91572 -0.0225054 0.0208537 1 0 1 1 0 0 +EDGE2 4690 4571 0.021448 0.969412 1.56021 1 0 1 1 0 0 +EDGE2 4690 4671 -0.0717072 1.03253 1.53047 1 0 1 1 0 0 +EDGE2 4690 3611 -0.00828953 1.01161 1.56588 1 0 1 1 0 0 +EDGE2 4690 4570 0.0483613 -0.0247307 -3.10779 1 0 1 1 0 0 +EDGE2 4690 4670 0.0299202 0.0355868 -0.00737851 1 0 1 1 0 0 +EDGE2 4690 3610 0.0120631 0.0299009 0.00480281 1 0 1 1 0 0 +EDGE2 4690 3630 0.0628494 0.066678 -3.14471 1 0 1 1 0 0 +EDGE2 4690 3631 0.0599929 -0.977322 -1.56536 1 0 1 1 0 0 +EDGE2 4690 3629 0.984774 -0.012548 -3.13429 1 0 1 1 0 0 +EDGE2 4690 4569 1.03838 0.0431346 -3.13929 1 0 1 1 0 0 +EDGE2 4691 4672 1.03486 0.0185708 0.0231647 1 0 1 1 0 0 +EDGE2 4691 3612 1.01819 -0.0516624 -0.000902858 1 0 1 1 0 0 +EDGE2 4691 4572 0.965401 -0.0163959 -0.0191327 1 0 1 1 0 0 +EDGE2 4691 4571 0.0334627 0.0175197 -0.014701 1 0 1 1 0 0 +EDGE2 4691 4671 -0.0065484 0.00985057 -0.0114088 1 0 1 1 0 0 +EDGE2 4691 3611 -0.0823215 0.0179061 -0.01837 1 0 1 1 0 0 +EDGE2 4691 4570 -1.05969 -0.0953516 1.54493 1 0 1 1 0 0 +EDGE2 4691 4690 -1.04889 -0.0340094 -1.54173 1 0 1 1 0 0 +EDGE2 4691 4670 -1.02827 0.0205711 -1.55868 1 0 1 1 0 0 +EDGE2 4691 3610 -1.03248 -0.0265534 -1.57467 1 0 1 1 0 0 +EDGE2 4691 3630 -1.09155 0.0086906 1.61112 1 0 1 1 0 0 +EDGE2 4692 4672 0.036927 0.0603429 -0.0113544 1 0 1 1 0 0 +EDGE2 4692 4673 1.06822 -0.118811 0.0149654 1 0 1 1 0 0 +EDGE2 4692 3613 0.995013 0.0438964 0.0056499 1 0 1 1 0 0 +EDGE2 4692 4573 1.02524 -0.0888765 0.00610924 1 0 1 1 0 0 +EDGE2 4692 3612 -0.0443718 0.0500057 0.0242237 1 0 1 1 0 0 +EDGE2 4692 4572 -0.0477357 -0.0383155 0.0296909 1 0 1 1 0 0 +EDGE2 4692 4571 -1.09575 0.108441 -0.00144598 1 0 1 1 0 0 +EDGE2 4692 4671 -1.02145 -0.0117559 0.000356382 1 0 1 1 0 0 +EDGE2 4692 4691 -1.04169 0.0545329 -0.0124468 1 0 1 1 0 0 +EDGE2 4692 3611 -0.992518 -0.00415565 0.0164162 1 0 1 1 0 0 +EDGE2 4693 4574 0.976203 0.0922202 -0.0179571 1 0 1 1 0 0 +EDGE2 4693 4674 1.05274 0.0618714 0.0111323 1 0 1 1 0 0 +EDGE2 4693 3614 1.00092 0.0228352 0.0269973 1 0 1 1 0 0 +EDGE2 4693 4672 -1.00872 0.115372 -0.00688662 1 0 1 1 0 0 +EDGE2 4693 4673 0.032864 0.0392821 -0.0290357 1 0 1 1 0 0 +EDGE2 4693 3613 0.00664697 -0.0248983 0.000986834 1 0 1 1 0 0 +EDGE2 4693 4573 -0.0371313 -0.0536406 -0.0132289 1 0 1 1 0 0 +EDGE2 4693 4692 -1.03184 -0.0476215 0.0271228 1 0 1 1 0 0 +EDGE2 4693 3612 -1.00774 -0.0538842 0.0383942 1 0 1 1 0 0 +EDGE2 4693 4572 -1.08279 -0.0334295 -0.00549897 1 0 1 1 0 0 +EDGE2 4694 4575 1.05067 -0.019154 -0.00908728 1 0 1 1 0 0 +EDGE2 4694 4675 0.929746 0.0298457 -0.0387638 1 0 1 1 0 0 +EDGE2 4694 3615 0.987001 0.103376 -0.0168317 1 0 1 1 0 0 +EDGE2 4694 4574 -0.0736671 -0.0308008 0.0144725 1 0 1 1 0 0 +EDGE2 4694 4674 0.0100484 -0.0527527 -0.00952755 1 0 1 1 0 0 +EDGE2 4694 3614 -0.0765047 0.0109751 0.0107304 1 0 1 1 0 0 +EDGE2 4694 4673 -0.900308 -0.0186582 0.0364068 1 0 1 1 0 0 +EDGE2 4694 4693 -0.938709 -0.0768503 0.00482104 1 0 1 1 0 0 +EDGE2 4694 3613 -1.05696 0.112242 0.00282239 1 0 1 1 0 0 +EDGE2 4694 4573 -0.948062 0.0922302 0.013168 1 0 1 1 0 0 +EDGE2 4695 4676 -0.0106688 0.962666 1.56484 1 0 1 1 0 0 +EDGE2 4695 4576 0.0091083 1.02929 1.56006 1 0 1 1 0 0 +EDGE2 4695 4575 0.0618516 -0.0597098 0.0143762 1 0 1 1 0 0 +EDGE2 4695 4675 -0.0241462 -0.0195442 0.00983652 1 0 1 1 0 0 +EDGE2 4695 3615 -0.0340163 -0.0215388 0.0133462 1 0 1 1 0 0 +EDGE2 4695 3616 -0.0428866 -1.05849 -1.55001 1 0 1 1 0 0 +EDGE2 4695 4574 -0.883429 -0.0442134 -0.000180642 1 0 1 1 0 0 +EDGE2 4695 4674 -0.988356 0.111787 0.00798343 1 0 1 1 0 0 +EDGE2 4695 4694 -0.977984 -0.0325661 0.0226765 1 0 1 1 0 0 +EDGE2 4695 3614 -0.976599 -0.0371206 -0.0289943 1 0 1 1 0 0 +EDGE2 4696 4577 1.02383 -0.0508447 0.00030924 1 0 1 1 0 0 +EDGE2 4696 4677 1.07469 -0.0849881 -0.00585038 1 0 1 1 0 0 +EDGE2 4696 4676 -0.031423 0.0620098 -0.0239806 1 0 1 1 0 0 +EDGE2 4696 4576 -0.107826 0.0543446 0.0152996 1 0 1 1 0 0 +EDGE2 4696 4575 -1.09484 0.0223026 -1.59329 1 0 1 1 0 0 +EDGE2 4696 4695 -0.916474 0.0626429 -1.58991 1 0 1 1 0 0 +EDGE2 4696 4675 -1.02302 -0.0160495 -1.56432 1 0 1 1 0 0 +EDGE2 4696 3615 -0.968319 0.0440534 -1.56581 1 0 1 1 0 0 +EDGE2 4697 4678 0.947342 0.0361772 -0.0166831 1 0 1 1 0 0 +EDGE2 4697 4578 0.973537 -0.0265297 -0.00299312 1 0 1 1 0 0 +EDGE2 4697 4577 -0.00122869 0.033556 0.0435766 1 0 1 1 0 0 +EDGE2 4697 4677 -0.0467371 0.0454601 0.000951082 1 0 1 1 0 0 +EDGE2 4697 4676 -0.973569 -0.0313703 -0.00910151 1 0 1 1 0 0 +EDGE2 4697 4696 -0.97912 0.00481393 -0.000922379 1 0 1 1 0 0 +EDGE2 4697 4576 -0.96882 0.1018 0.0243909 1 0 1 1 0 0 +EDGE2 4698 4679 1.06774 0.0375226 -0.00260199 1 0 1 1 0 0 +EDGE2 4698 4579 1.02853 -0.0526434 0.0014952 1 0 1 1 0 0 +EDGE2 4698 4678 -0.0238889 -0.0825166 0.0191043 1 0 1 1 0 0 +EDGE2 4698 4578 -0.044421 -0.0528705 0.0129444 1 0 1 1 0 0 +EDGE2 4698 4577 -0.971923 -0.0275937 -0.0131798 1 0 1 1 0 0 +EDGE2 4698 4677 -0.897574 0.0212324 0.030812 1 0 1 1 0 0 +EDGE2 4698 4697 -1.05683 -0.0173142 -0.020333 1 0 1 1 0 0 +EDGE2 4699 4580 0.992169 -0.031593 0.0174837 1 0 1 1 0 0 +EDGE2 4699 4680 1.08711 -0.0287742 -0.0154602 1 0 1 1 0 0 +EDGE2 4699 4679 0.0319311 -0.0501288 -0.0124788 1 0 1 1 0 0 +EDGE2 4699 4579 0.0121231 0.0350084 -0.0352106 1 0 1 1 0 0 +EDGE2 4699 4678 -0.986012 0.0240108 -0.00291291 1 0 1 1 0 0 +EDGE2 4699 4698 -1.07847 -0.000319891 0.0117739 1 0 1 1 0 0 +EDGE2 4699 4578 -0.930812 -0.00846535 0.0026047 1 0 1 1 0 0 +EDGE2 4700 4580 0.00980082 -0.126309 -0.0334518 1 0 1 1 0 0 +EDGE2 4700 4680 -0.0373147 -0.0490976 -0.0118352 1 0 1 1 0 0 +EDGE2 4700 4681 0.0375917 1.00269 1.57922 1 0 1 1 0 0 +EDGE2 4700 4581 -0.037964 1.01917 1.59043 1 0 1 1 0 0 +EDGE2 4700 4679 -0.992479 0.0466739 0.025771 1 0 1 1 0 0 +EDGE2 4700 4699 -0.996014 -0.0676938 -0.0302516 1 0 1 1 0 0 +EDGE2 4700 4579 -1.04703 0.0655306 -0.0281562 1 0 1 1 0 0 +EDGE2 4701 4580 -1.07 -0.000315498 -1.57443 1 0 1 1 0 0 +EDGE2 4701 4680 -0.950697 -0.0102523 -1.56636 1 0 1 1 0 0 +EDGE2 4701 4700 -0.984003 -0.016127 -1.55792 1 0 1 1 0 0 +EDGE2 4701 4681 -0.0194853 -0.0470174 0.0437186 1 0 1 1 0 0 +EDGE2 4701 4581 -0.0579147 0.114852 -0.0146889 1 0 1 1 0 0 +EDGE2 4701 4582 1.02505 0.0993313 -0.0280589 1 0 1 1 0 0 +EDGE2 4701 4682 1.01535 -0.0112013 0.001175 1 0 1 1 0 0 +EDGE2 4702 4681 -1.04359 0.10351 0.0130971 1 0 1 1 0 0 +EDGE2 4702 4701 -0.99448 0.0116747 -0.0280954 1 0 1 1 0 0 +EDGE2 4702 4581 -1.06718 0.0652953 0.0015356 1 0 1 1 0 0 +EDGE2 4702 4583 0.978159 -0.00936247 0.00760063 1 0 1 1 0 0 +EDGE2 4702 4582 -0.0202021 -0.0620463 -0.0204057 1 0 1 1 0 0 +EDGE2 4702 4682 -0.040062 0.0762443 0.0229161 1 0 1 1 0 0 +EDGE2 4702 4683 0.953307 -0.0138739 0.00187163 1 0 1 1 0 0 +EDGE2 4703 4583 0.023373 -0.05472 -0.0460642 1 0 1 1 0 0 +EDGE2 4703 4582 -0.988397 -0.062172 -0.0128637 1 0 1 1 0 0 +EDGE2 4703 4702 -1.04458 0.00278668 0.0232077 1 0 1 1 0 0 +EDGE2 4703 4682 -1.0169 0.095374 -0.0214272 1 0 1 1 0 0 +EDGE2 4703 4683 0.0558334 0.082337 -0.0271432 1 0 1 1 0 0 +EDGE2 4703 4684 1.02553 0.00618837 0.0101707 1 0 1 1 0 0 +EDGE2 4703 4584 0.954934 -0.000673972 0.021604 1 0 1 1 0 0 +EDGE2 4704 4583 -1.00524 0.117873 -0.0474705 1 0 1 1 0 0 +EDGE2 4704 4703 -1.0034 0.157505 0.00664467 1 0 1 1 0 0 +EDGE2 4704 4683 -0.941615 0.0463948 -0.00923963 1 0 1 1 0 0 +EDGE2 4704 4684 -0.0655938 -0.0834801 0.00289965 1 0 1 1 0 0 +EDGE2 4704 4584 0.000973968 -0.0490303 0.000526618 1 0 1 1 0 0 +EDGE2 4704 3605 1.05702 -0.00309615 -3.12317 1 0 1 1 0 0 +EDGE2 4704 4645 0.89417 0.000533926 -3.15303 1 0 1 1 0 0 +EDGE2 4704 4665 0.93998 0.0263976 -3.14628 1 0 1 1 0 0 +EDGE2 4704 4685 0.96437 0.0453101 0.0115741 1 0 1 1 0 0 +EDGE2 4704 4585 1.1094 0.0287506 0.0447043 1 0 1 1 0 0 +EDGE2 4705 4646 0.0520205 -1.07908 -1.56423 1 0 1 1 0 0 +EDGE2 4705 4586 0.0384938 -1.00287 -1.54105 1 0 1 1 0 0 +EDGE2 4705 4644 0.940372 0.0934495 -3.12745 1 0 1 1 0 0 +EDGE2 4705 4684 -0.979494 0.0193882 -0.00802395 1 0 1 1 0 0 +EDGE2 4705 4704 -0.883833 -0.00899715 -0.0100888 1 0 1 1 0 0 +EDGE2 4705 4584 -0.9965 0.0474375 -0.0125195 1 0 1 1 0 0 +EDGE2 4705 3605 0.0286747 -0.0730211 -3.17592 1 0 1 1 0 0 +EDGE2 4705 4645 0.0386142 0.00662623 -3.15596 1 0 1 1 0 0 +EDGE2 4705 4665 -0.0100283 0.0971925 -3.1424 1 0 1 1 0 0 +EDGE2 4705 4685 -0.0536077 0.0444658 -0.0225505 1 0 1 1 0 0 +EDGE2 4705 4585 0.0112806 -0.00364417 0.00702426 1 0 1 1 0 0 +EDGE2 4705 4664 1.02539 0.0450145 -3.1424 1 0 1 1 0 0 +EDGE2 4705 3606 0.058688 0.975958 1.56708 1 0 1 1 0 0 +EDGE2 4705 4686 0.0699766 0.94788 1.58166 1 0 1 1 0 0 +EDGE2 4705 4666 0.0837005 0.992191 1.58723 1 0 1 1 0 0 +EDGE2 4705 3604 1.04984 -0.00355919 -3.13437 1 0 1 1 0 0 +EDGE2 4706 4587 0.966055 0.0752155 -0.0180708 1 0 1 1 0 0 +EDGE2 4706 4647 0.988308 -0.00372618 0.0246719 1 0 1 1 0 0 +EDGE2 4706 4646 -0.0330166 0.00070329 -0.0172378 1 0 1 1 0 0 +EDGE2 4706 4586 -0.0159048 -0.000132161 0.0362173 1 0 1 1 0 0 +EDGE2 4706 4705 -0.905419 0.00804991 1.5873 1 0 1 1 0 0 +EDGE2 4706 3605 -0.981667 -0.0326347 -1.56968 1 0 1 1 0 0 +EDGE2 4706 4645 -0.936356 0.13854 -1.57677 1 0 1 1 0 0 +EDGE2 4706 4665 -1.01583 -0.0236728 -1.55452 1 0 1 1 0 0 +EDGE2 4706 4685 -0.996316 0.0235532 1.56621 1 0 1 1 0 0 +EDGE2 4706 4585 -1.09885 -0.0777919 1.57616 1 0 1 1 0 0 +EDGE2 4707 4648 1.03546 -0.086037 0.0100832 1 0 1 1 0 0 +EDGE2 4707 4588 0.988786 0.037098 -0.0572406 1 0 1 1 0 0 +EDGE2 4707 4587 -0.0579958 0.0550194 -0.0450576 1 0 1 1 0 0 +EDGE2 4707 4647 -0.0499758 -0.0132189 0.0127005 1 0 1 1 0 0 +EDGE2 4707 4646 -1.0644 0.00789441 0.00834997 1 0 1 1 0 0 +EDGE2 4707 4706 -0.987338 0.0191929 0.00962858 1 0 1 1 0 0 +EDGE2 4707 4586 -1.009 -0.0406221 0.00554351 1 0 1 1 0 0 +EDGE2 4708 4707 -0.986137 0.060028 -0.0287114 1 0 1 1 0 0 +EDGE2 4708 4649 0.967932 -0.068213 0.0125141 1 0 1 1 0 0 +EDGE2 4708 4589 0.98224 0.0932896 -0.00464817 1 0 1 1 0 0 +EDGE2 4708 4648 0.0428524 0.0100724 0.0166444 1 0 1 1 0 0 +EDGE2 4708 4588 -0.031768 -0.0104104 0.000921624 1 0 1 1 0 0 +EDGE2 4708 4587 -1.12711 0.0685514 0.0144629 1 0 1 1 0 0 +EDGE2 4708 4647 -1.01505 -0.0514664 -0.0195285 1 0 1 1 0 0 +EDGE2 4709 4630 0.972917 -0.0346767 -3.13671 1 0 1 1 0 0 +EDGE2 4709 4650 1.0099 -0.00157526 -0.0341171 1 0 1 1 0 0 +EDGE2 4709 4590 1.10871 0.0531643 0.0361053 1 0 1 1 0 0 +EDGE2 4709 4708 -1.08723 -0.00611853 0.0250018 1 0 1 1 0 0 +EDGE2 4709 4649 0.0366189 -0.0369751 0.0171524 1 0 1 1 0 0 +EDGE2 4709 4589 -0.0681754 -0.107258 0.0287901 1 0 1 1 0 0 +EDGE2 4709 4648 -1.06617 0.0126241 -0.0111428 1 0 1 1 0 0 +EDGE2 4709 4588 -1.05698 0.0136898 -0.0140225 1 0 1 1 0 0 +EDGE2 4710 4629 1.01227 0.0433944 -3.13642 1 0 1 1 0 0 +EDGE2 4710 4630 0.0386839 0.0155165 -3.18248 1 0 1 1 0 0 +EDGE2 4710 4650 -0.00133836 -0.0464786 -0.0250061 1 0 1 1 0 0 +EDGE2 4710 4590 0.0357445 -0.0774507 -0.00590793 1 0 1 1 0 0 +EDGE2 4710 4591 0.0324335 1.01589 1.57996 1 0 1 1 0 0 +EDGE2 4710 4651 -0.0458996 0.897005 1.59607 1 0 1 1 0 0 +EDGE2 4710 4631 0.0372219 0.961757 1.57652 1 0 1 1 0 0 +EDGE2 4710 4649 -0.886182 -0.010619 0.0205519 1 0 1 1 0 0 +EDGE2 4710 4709 -1.02645 -0.0172987 -0.0392437 1 0 1 1 0 0 +EDGE2 4710 4589 -1.06334 0.0287501 -0.0367851 1 0 1 1 0 0 +EDGE2 4711 4710 -1.00929 0.0807109 1.55358 1 0 1 1 0 0 +EDGE2 4711 4630 -1.05272 -0.00137438 -1.56009 1 0 1 1 0 0 +EDGE2 4711 4650 -0.913682 -0.0402145 1.56915 1 0 1 1 0 0 +EDGE2 4711 4590 -0.957905 -0.000763464 1.54748 1 0 1 1 0 0 +EDGE2 4712 4711 -1.07532 0.0132972 -0.0323855 1 0 1 1 0 0 +EDGE2 4713 4712 -0.981769 0.0125824 -0.00990674 1 0 1 1 0 0 +EDGE2 4714 4713 -0.957535 0.0211642 0.000997017 1 0 1 1 0 0 +EDGE2 4715 4714 -1.10484 0.0177242 0.0030737 1 0 1 1 0 0 +EDGE2 4716 4715 -0.925677 0.0490432 -1.55935 1 0 1 1 0 0 +EDGE2 4717 4716 -0.942281 0.0109949 -0.0215728 1 0 1 1 0 0 +EDGE2 4718 4717 -1.01968 0.0518172 -0.0436428 1 0 1 1 0 0 +EDGE2 4719 4718 -0.994304 -0.0713052 0.00861329 1 0 1 1 0 0 +EDGE2 4720 4719 -0.938709 0.0299456 -0.00662047 1 0 1 1 0 0 +EDGE2 4721 4720 -1.06819 0.0133619 1.56939 1 0 1 1 0 0 +EDGE2 4722 4721 -0.945559 -0.0152287 0.0277063 1 0 1 1 0 0 +EDGE2 4723 4722 -0.955231 0.0310916 -0.00645568 1 0 1 1 0 0 +EDGE2 4724 4723 -0.977637 0.0278494 0.0131724 1 0 1 1 0 0 +EDGE2 4725 4724 -0.943423 -0.108226 0.0462374 1 0 1 1 0 0 +EDGE2 4726 4725 -1.09811 0.12685 -1.57863 1 0 1 1 0 0 +EDGE2 4727 4726 -1.00807 -0.00086702 -0.0132755 1 0 1 1 0 0 +EDGE2 4728 4727 -0.998376 -0.0486175 0.0124935 1 0 1 1 0 0 +EDGE2 4729 1610 1.06504 0.000922701 -3.1264 1 0 1 1 0 0 +EDGE2 4729 1630 1.01087 -0.00685931 -3.1673 1 0 1 1 0 0 +EDGE2 4729 1310 1.02308 -0.0419753 -3.12739 1 0 1 1 0 0 +EDGE2 4729 4728 -1.0461 -0.0244722 -0.0127439 1 0 1 1 0 0 +EDGE2 4730 1609 1.01102 0.0536333 -3.09146 1 0 1 1 0 0 +EDGE2 4730 1629 0.995677 -0.0242554 -3.13379 1 0 1 1 0 0 +EDGE2 4730 1309 1.01466 0.00418342 -3.13439 1 0 1 1 0 0 +EDGE2 4730 1611 -0.000787569 -0.971667 -1.56077 1 0 1 1 0 0 +EDGE2 4730 1631 -0.00433884 -1.00352 -1.58083 1 0 1 1 0 0 +EDGE2 4730 1311 0.0404036 -0.978781 -1.56391 1 0 1 1 0 0 +EDGE2 4730 1610 -0.0133985 -0.0716504 -3.12287 1 0 1 1 0 0 +EDGE2 4730 1630 0.0833203 -0.073425 -3.15624 1 0 1 1 0 0 +EDGE2 4730 1310 -0.00766904 -0.0577104 -3.14317 1 0 1 1 0 0 +EDGE2 4730 4729 -1.00704 0.0474658 -0.0220881 1 0 1 1 0 0 +EDGE2 4731 1610 -0.971326 0.0514681 1.57244 1 0 1 1 0 0 +EDGE2 4731 1630 -0.990239 -0.00265591 1.54285 1 0 1 1 0 0 +EDGE2 4731 4730 -1.03953 0.0539255 -1.58067 1 0 1 1 0 0 +EDGE2 4731 1310 -1.0313 -0.0108869 1.57389 1 0 1 1 0 0 +EDGE2 4732 4731 -1.03018 -0.00920329 -0.0077509 1 0 1 1 0 0 +EDGE2 4733 4732 -1.05272 0.103131 -0.019173 1 0 1 1 0 0 +EDGE2 4734 2815 0.964052 -0.0791446 -3.13529 1 0 1 1 0 0 +EDGE2 4734 4733 -1.02958 -0.0761716 -0.00276349 1 0 1 1 0 0 +EDGE2 4734 2795 1.04609 -0.0812229 -3.12879 1 0 1 1 0 0 +EDGE2 4735 2816 0.00886624 -0.99043 -1.5858 1 0 1 1 0 0 +EDGE2 4735 2796 -0.0420124 -0.985351 -1.56544 1 0 1 1 0 0 +EDGE2 4735 2815 0.0351442 -0.0213539 -3.13618 1 0 1 1 0 0 +EDGE2 4735 4734 -0.967305 -0.018671 0.00726098 1 0 1 1 0 0 +EDGE2 4735 2814 0.932149 -0.00267338 -3.15144 1 0 1 1 0 0 +EDGE2 4735 2795 0.0147919 -0.0203454 -3.1358 1 0 1 1 0 0 +EDGE2 4735 2794 1.00834 -0.0477672 -3.11285 1 0 1 1 0 0 +EDGE2 4736 2817 0.938557 0.0393466 -0.0296243 1 0 1 1 0 0 +EDGE2 4736 2797 1.02359 0.00114921 0.000268166 1 0 1 1 0 0 +EDGE2 4736 2816 0.0245809 -0.0821597 0.0171928 1 0 1 1 0 0 +EDGE2 4736 2796 -0.0077159 -0.000255971 -0.0253776 1 0 1 1 0 0 +EDGE2 4736 2815 -0.968146 -0.0511475 -1.54064 1 0 1 1 0 0 +EDGE2 4736 4735 -1.0222 0.0305299 1.58201 1 0 1 1 0 0 +EDGE2 4736 2795 -0.939172 -0.0219147 -1.60396 1 0 1 1 0 0 +EDGE2 4737 2818 1.117 0.0531138 0.00832794 1 0 1 1 0 0 +EDGE2 4737 2798 1.01992 0.0600675 0.0302229 1 0 1 1 0 0 +EDGE2 4737 2817 0.0762861 0.0337762 0.0157403 1 0 1 1 0 0 +EDGE2 4737 2797 0.0523281 -0.0581206 -0.00106817 1 0 1 1 0 0 +EDGE2 4737 2816 -0.98831 0.0290256 0.0325361 1 0 1 1 0 0 +EDGE2 4737 4736 -0.993258 -0.0299495 -0.00785458 1 0 1 1 0 0 +EDGE2 4737 2796 -0.913807 0.0379256 0.0204302 1 0 1 1 0 0 +EDGE2 4738 2819 0.86835 0.0261805 -0.00732369 1 0 1 1 0 0 +EDGE2 4738 2799 1.09518 0.0626395 -0.0126704 1 0 1 1 0 0 +EDGE2 4738 2818 0.0260497 0.0346611 -0.0370262 1 0 1 1 0 0 +EDGE2 4738 2798 0.0374555 -0.0123069 0.00237819 1 0 1 1 0 0 +EDGE2 4738 2817 -0.98932 -0.0254429 -0.0124223 1 0 1 1 0 0 +EDGE2 4738 4737 -1.04323 0.0298492 -0.0213413 1 0 1 1 0 0 +EDGE2 4738 2797 -1.0744 0.0571081 -0.0084358 1 0 1 1 0 0 +EDGE2 4739 2840 1.0146 0.0266767 -3.13777 1 0 1 1 0 0 +EDGE2 4739 1300 1.09327 0.00290839 -3.13919 1 0 1 1 0 0 +EDGE2 4739 2800 0.935904 0.0476779 0.00278762 1 0 1 1 0 0 +EDGE2 4739 2820 1.01863 -0.00665899 -0.0206278 1 0 1 1 0 0 +EDGE2 4739 1280 1.0426 -0.0121396 -3.14171 1 0 1 1 0 0 +EDGE2 4739 2819 -0.0337399 0.0541364 0.00847401 1 0 1 1 0 0 +EDGE2 4739 2799 0.0247107 0.0317358 -0.0239414 1 0 1 1 0 0 +EDGE2 4739 2818 -0.960151 0.046083 0.0352687 1 0 1 1 0 0 +EDGE2 4739 4738 -1.00077 -0.022257 0.0111505 1 0 1 1 0 0 +EDGE2 4739 2798 -0.989037 0.0093271 0.00960275 1 0 1 1 0 0 +EDGE2 4740 1299 1.02403 -0.00552058 -3.1081 1 0 1 1 0 0 +EDGE2 4740 2839 0.918931 -0.0166843 -3.14064 1 0 1 1 0 0 +EDGE2 4740 1279 1.02306 -0.00901801 -3.12465 1 0 1 1 0 0 +EDGE2 4740 2840 -0.00233385 -0.0305931 -3.16106 1 0 1 1 0 0 +EDGE2 4740 2821 0.0243434 -0.920566 -1.56436 1 0 1 1 0 0 +EDGE2 4740 1281 0.0312826 -1.02514 -1.59717 1 0 1 1 0 0 +EDGE2 4740 1301 -0.0769665 -0.96497 -1.57397 1 0 1 1 0 0 +EDGE2 4740 1300 -0.0380582 -0.0374467 -3.16873 1 0 1 1 0 0 +EDGE2 4740 2800 0.0260539 -0.00206074 0.0170497 1 0 1 1 0 0 +EDGE2 4740 2820 -0.0954238 0.0550285 -0.0165836 1 0 1 1 0 0 +EDGE2 4740 1280 -0.0222547 -0.0136634 -3.14008 1 0 1 1 0 0 +EDGE2 4740 2801 0.0190933 0.988659 1.58068 1 0 1 1 0 0 +EDGE2 4740 2841 0.0488125 0.978956 1.55137 1 0 1 1 0 0 +EDGE2 4740 4739 -0.991832 0.0578004 0.0121421 1 0 1 1 0 0 +EDGE2 4740 2819 -0.983108 0.0256378 -0.0194001 1 0 1 1 0 0 +EDGE2 4740 2799 -1.00463 -0.0788679 0.0191027 1 0 1 1 0 0 +EDGE2 4741 2840 -1.01735 -0.0217749 1.57863 1 0 1 1 0 0 +EDGE2 4741 4740 -0.984506 -0.108313 -1.58389 1 0 1 1 0 0 +EDGE2 4741 1300 -0.962241 0.022589 1.57724 1 0 1 1 0 0 +EDGE2 4741 2800 -1.0236 -0.0394686 -1.5709 1 0 1 1 0 0 +EDGE2 4741 2820 -1.05194 -0.0578381 -1.57462 1 0 1 1 0 0 +EDGE2 4741 1280 -0.980002 -0.0290061 1.58724 1 0 1 1 0 0 +EDGE2 4741 2801 -0.0249042 -0.00839507 -0.00234567 1 0 1 1 0 0 +EDGE2 4741 2841 0.0110323 0.0377808 -0.0193465 1 0 1 1 0 0 +EDGE2 4741 2802 1.00869 0.00441653 -0.00117055 1 0 1 1 0 0 +EDGE2 4741 2842 1.04253 0.0821043 0.0273456 1 0 1 1 0 0 +EDGE2 4742 2801 -1.03585 0.00978797 0.0507541 1 0 1 1 0 0 +EDGE2 4742 2841 -1.04354 -0.0556423 0.0270993 1 0 1 1 0 0 +EDGE2 4742 4741 -1.04094 -0.00200374 0.0439931 1 0 1 1 0 0 +EDGE2 4742 2802 0.0151151 -0.0479285 -0.0143792 1 0 1 1 0 0 +EDGE2 4742 2842 -0.0558862 -0.00484661 -0.00979394 1 0 1 1 0 0 +EDGE2 4742 2843 0.941412 -0.119588 0.00397266 1 0 1 1 0 0 +EDGE2 4742 2803 0.984196 -0.121854 0.0346344 1 0 1 1 0 0 +EDGE2 4743 4742 -0.950024 0.0153151 -0.0221551 1 0 1 1 0 0 +EDGE2 4743 2802 -1.00737 0.0165425 -0.00436399 1 0 1 1 0 0 +EDGE2 4743 2842 -0.962495 0.106435 -0.00781002 1 0 1 1 0 0 +EDGE2 4743 2843 -0.0015831 -0.0260061 -0.00516845 1 0 1 1 0 0 +EDGE2 4743 2803 0.0587687 0.0252765 -0.0301074 1 0 1 1 0 0 +EDGE2 4743 2804 1.05836 -0.0228748 0.0332635 1 0 1 1 0 0 +EDGE2 4743 2844 0.950749 0.0379794 0.00892439 1 0 1 1 0 0 +EDGE2 4744 2843 -0.984619 -0.0335394 -0.00645522 1 0 1 1 0 0 +EDGE2 4744 4743 -1.02952 -0.0336585 0.0300547 1 0 1 1 0 0 +EDGE2 4744 2803 -0.974285 -0.00509739 0.0169294 1 0 1 1 0 0 +EDGE2 4744 2804 -0.0588305 0.0234207 0.0225839 1 0 1 1 0 0 +EDGE2 4744 2844 0.111785 0.0115563 0.0285466 1 0 1 1 0 0 +EDGE2 4744 2685 1.0029 -0.028448 -3.12119 1 0 1 1 0 0 +EDGE2 4744 2785 0.983407 -0.0846009 -3.13787 1 0 1 1 0 0 +EDGE2 4744 2805 1.01358 -0.054335 -0.0220064 1 0 1 1 0 0 +EDGE2 4744 2845 0.976033 0.0519659 0.00189798 1 0 1 1 0 0 +EDGE2 4744 2765 1.00001 -0.000821621 -3.12785 1 0 1 1 0 0 +EDGE2 4744 2625 0.994378 -0.0234601 -3.12456 1 0 1 1 0 0 +EDGE2 4745 2766 0.0542934 -0.896828 -1.55088 1 0 1 1 0 0 +EDGE2 4745 2846 0.0206545 -0.961753 -1.58741 1 0 1 1 0 0 +EDGE2 4745 2686 -0.0288301 -0.998548 -1.5344 1 0 1 1 0 0 +EDGE2 4745 2626 0.0357417 -0.957117 -1.54971 1 0 1 1 0 0 +EDGE2 4745 2786 -0.0591331 0.99672 1.61683 1 0 1 1 0 0 +EDGE2 4745 2624 1.00124 -0.0199911 -3.1492 1 0 1 1 0 0 +EDGE2 4745 2804 -0.993749 0.0219351 0.00121874 1 0 1 1 0 0 +EDGE2 4745 2844 -0.93688 -0.0847401 -0.0126979 1 0 1 1 0 0 +EDGE2 4745 4744 -1.01089 0.0192811 -0.0233119 1 0 1 1 0 0 +EDGE2 4745 2685 -0.0255358 0.054086 -3.088 1 0 1 1 0 0 +EDGE2 4745 2785 -0.00377176 -0.064194 -3.15261 1 0 1 1 0 0 +EDGE2 4745 2805 0.0424715 0.0799353 -0.0131431 1 0 1 1 0 0 +EDGE2 4745 2845 0.0261413 0.0712549 0.00388074 1 0 1 1 0 0 +EDGE2 4745 2765 0.0364766 -0.125116 -3.12923 1 0 1 1 0 0 +EDGE2 4745 2764 1.00285 -0.0082058 -3.1222 1 0 1 1 0 0 +EDGE2 4745 2784 0.962492 -0.0606569 -3.15679 1 0 1 1 0 0 +EDGE2 4745 2625 -0.0145077 -0.0347561 -3.1409 1 0 1 1 0 0 +EDGE2 4745 2684 1.02402 0.0491773 -3.13125 1 0 1 1 0 0 +EDGE2 4745 2806 0.0243371 0.96939 1.54519 1 0 1 1 0 0 +EDGE2 4746 2786 -0.0210714 -0.164802 0.00155905 1 0 1 1 0 0 +EDGE2 4746 4745 -1.04618 -0.0241458 -1.58591 1 0 1 1 0 0 +EDGE2 4746 2685 -1.01501 0.035829 1.58695 1 0 1 1 0 0 +EDGE2 4746 2785 -0.96375 0.0542822 1.60602 1 0 1 1 0 0 +EDGE2 4746 2805 -0.988627 0.0339958 -1.57846 1 0 1 1 0 0 +EDGE2 4746 2845 -1.01784 -0.0611293 -1.579 1 0 1 1 0 0 +EDGE2 4746 2765 -0.978203 0.0221427 1.54541 1 0 1 1 0 0 +EDGE2 4746 2625 -0.985926 0.0791042 1.56681 1 0 1 1 0 0 +EDGE2 4746 2806 0.0255948 0.0430005 -0.00154703 1 0 1 1 0 0 +EDGE2 4746 2787 0.982635 0.0172172 -0.0108158 1 0 1 1 0 0 +EDGE2 4746 2807 1.04621 -0.0207747 -0.0138168 1 0 1 1 0 0 +EDGE2 4747 2786 -1.02964 -0.00923121 0.0476942 1 0 1 1 0 0 +EDGE2 4747 4746 -1.00164 -0.0138149 -0.00394932 1 0 1 1 0 0 +EDGE2 4747 2806 -1.02288 0.0440169 0.0194879 1 0 1 1 0 0 +EDGE2 4747 2787 0.0336904 -0.0637528 -0.0126061 1 0 1 1 0 0 +EDGE2 4747 2807 0.0855655 0.0142514 0.0112574 1 0 1 1 0 0 +EDGE2 4747 2788 1.00562 0.00016632 -0.0236702 1 0 1 1 0 0 +EDGE2 4747 2808 1.02909 0.00186854 -0.00947226 1 0 1 1 0 0 +EDGE2 4748 2787 -0.971404 -0.00555867 -0.0169318 1 0 1 1 0 0 +EDGE2 4748 2807 -1.04805 -0.0605911 -0.0232198 1 0 1 1 0 0 +EDGE2 4748 4747 -1.05321 0.0595459 -0.0371958 1 0 1 1 0 0 +EDGE2 4748 2789 1.00613 0.00551892 0.0450286 1 0 1 1 0 0 +EDGE2 4748 2788 0.0199022 0.00165368 0.0135476 1 0 1 1 0 0 +EDGE2 4748 2808 0.015154 0.0628839 -0.00774669 1 0 1 1 0 0 +EDGE2 4748 2809 0.990902 -0.0553872 -0.00197697 1 0 1 1 0 0 +EDGE2 4749 4748 -0.967606 -0.00531119 0.0346491 1 0 1 1 0 0 +EDGE2 4749 2789 -0.0651075 0.00883964 0.00159251 1 0 1 1 0 0 +EDGE2 4749 2788 -1.04696 0.0322091 -0.00484836 1 0 1 1 0 0 +EDGE2 4749 2808 -1.03461 -0.00192702 -0.00690582 1 0 1 1 0 0 +EDGE2 4749 2809 -0.0212824 -0.0168054 -0.011538 1 0 1 1 0 0 +EDGE2 4749 2810 1.08692 -0.035975 -0.00216168 1 0 1 1 0 0 +EDGE2 4749 4610 1.07321 -0.0436852 -3.15783 1 0 1 1 0 0 +EDGE2 4749 2790 0.972859 0.0294439 -0.0235575 1 0 1 1 0 0 +EDGE2 4750 4611 -0.0307019 -1.01078 -1.56668 1 0 1 1 0 0 +EDGE2 4750 2811 0.00408919 1.02989 1.57099 1 0 1 1 0 0 +EDGE2 4750 2791 -0.0201916 1.00604 1.59852 1 0 1 1 0 0 +EDGE2 4750 2789 -1.02923 0.0841886 0.0288638 1 0 1 1 0 0 +EDGE2 4750 4749 -0.965575 -0.0827572 0.00482723 1 0 1 1 0 0 +EDGE2 4750 2809 -0.994254 0.0399892 -0.00874731 1 0 1 1 0 0 +EDGE2 4750 2810 -0.0219461 0.00810911 -0.0289281 1 0 1 1 0 0 +EDGE2 4750 4610 -0.0632774 0.0102946 -3.12113 1 0 1 1 0 0 +EDGE2 4750 2790 -0.00223632 0.0104846 -0.00282056 1 0 1 1 0 0 +EDGE2 4750 4609 1.08354 -0.0231711 -3.15511 1 0 1 1 0 0 +EDGE2 4751 2812 0.952989 -0.0499675 -0.0106558 1 0 1 1 0 0 +EDGE2 4751 2811 0.0476442 0.0958167 0.0622529 1 0 1 1 0 0 +EDGE2 4751 2792 0.918257 -0.0178426 -0.0270544 1 0 1 1 0 0 +EDGE2 4751 2791 -0.0231806 -0.00130509 -0.00138053 1 0 1 1 0 0 +EDGE2 4751 2810 -0.976764 -0.0318482 -1.58054 1 0 1 1 0 0 +EDGE2 4751 4610 -0.991198 0.156851 1.56353 1 0 1 1 0 0 +EDGE2 4751 4750 -0.890525 0.0636407 -1.56124 1 0 1 1 0 0 +EDGE2 4751 2790 -1.01435 0.0103206 -1.57978 1 0 1 1 0 0 +EDGE2 4752 2793 1.07893 0.0755587 -0.0275873 1 0 1 1 0 0 +EDGE2 4752 2813 1.01761 -0.0574921 0.0174528 1 0 1 1 0 0 +EDGE2 4752 2812 -0.00644702 0.00383239 -0.0130155 1 0 1 1 0 0 +EDGE2 4752 2811 -1.02792 0.0685592 0.0391268 1 0 1 1 0 0 +EDGE2 4752 4751 -0.953327 -0.00913831 -0.00834341 1 0 1 1 0 0 +EDGE2 4752 2792 0.0461685 -0.0382289 0.00250592 1 0 1 1 0 0 +EDGE2 4752 2791 -0.945715 -0.014804 -0.0230943 1 0 1 1 0 0 +EDGE2 4753 2793 -0.0345302 -0.0315978 -0.00300779 1 0 1 1 0 0 +EDGE2 4753 2814 0.95639 0.0297807 -0.0152693 1 0 1 1 0 0 +EDGE2 4753 2794 1.03332 0.0710578 0.0241346 1 0 1 1 0 0 +EDGE2 4753 2813 -0.0132897 0.0089111 0.024719 1 0 1 1 0 0 +EDGE2 4753 2812 -1.03083 -0.0473783 0.000405104 1 0 1 1 0 0 +EDGE2 4753 4752 -0.90365 0.0307704 0.0191437 1 0 1 1 0 0 +EDGE2 4753 2792 -0.955221 0.012061 -0.0105238 1 0 1 1 0 0 +EDGE2 4754 2793 -0.988179 0.0225864 -0.0185111 1 0 1 1 0 0 +EDGE2 4754 2815 0.995034 -0.00912162 0.0101312 1 0 1 1 0 0 +EDGE2 4754 4735 0.919972 0.00227739 -3.1216 1 0 1 1 0 0 +EDGE2 4754 4753 -1.02944 0.033644 -0.024641 1 0 1 1 0 0 +EDGE2 4754 2814 -0.0460489 0.0359365 0.000818871 1 0 1 1 0 0 +EDGE2 4754 2795 0.966805 0.064645 0.0126896 1 0 1 1 0 0 +EDGE2 4754 2794 -0.00727461 -0.0215875 0.0263624 1 0 1 1 0 0 +EDGE2 4754 2813 -0.994206 -0.0035006 -0.00781067 1 0 1 1 0 0 +EDGE2 4755 2816 -0.0666734 1.0117 1.56529 1 0 1 1 0 0 +EDGE2 4755 4736 0.0684644 0.950846 1.60441 1 0 1 1 0 0 +EDGE2 4755 2796 0.0275893 1.05512 1.572 1 0 1 1 0 0 +EDGE2 4755 2815 0.0473488 0.0036378 -0.0822518 1 0 1 1 0 0 +EDGE2 4755 4734 0.970803 -0.00153134 -3.14298 1 0 1 1 0 0 +EDGE2 4755 4735 -0.0391399 0.0282578 -3.1787 1 0 1 1 0 0 +EDGE2 4755 2814 -1.07312 0.0388881 0.0102303 1 0 1 1 0 0 +EDGE2 4755 4754 -0.955025 -0.0411956 -0.024942 1 0 1 1 0 0 +EDGE2 4755 2795 0.0327694 -0.00792565 0.00655568 1 0 1 1 0 0 +EDGE2 4755 2794 -1.0183 0.164604 -0.00989244 1 0 1 1 0 0 +EDGE2 4756 2815 -1.03655 0.0101715 1.5809 1 0 1 1 0 0 +EDGE2 4756 4755 -0.995109 -0.0152337 1.58211 1 0 1 1 0 0 +EDGE2 4756 4735 -0.995694 -0.00311379 -1.55578 1 0 1 1 0 0 +EDGE2 4756 2795 -1.01023 0.0153454 1.54514 1 0 1 1 0 0 +EDGE2 4757 4756 -1.06072 -0.0869042 0.0134746 1 0 1 1 0 0 +EDGE2 4758 4757 -0.996945 -0.0153838 -0.0390399 1 0 1 1 0 0 +EDGE2 4759 4758 -0.956274 0.045861 0.0312121 1 0 1 1 0 0 +EDGE2 4759 4720 0.945569 -0.0866452 -3.10016 1 0 1 1 0 0 +EDGE2 4760 4759 -1.03238 0.0393893 0.00376034 1 0 1 1 0 0 +EDGE2 4760 4721 0.0145228 0.985132 1.60651 1 0 1 1 0 0 +EDGE2 4760 4719 0.990343 0.064878 -3.15236 1 0 1 1 0 0 +EDGE2 4760 4720 -0.0696625 -0.0479747 -3.12445 1 0 1 1 0 0 +EDGE2 4761 4760 -1.04185 0.0167553 -1.58255 1 0 1 1 0 0 +EDGE2 4761 4722 0.990683 0.0612141 0.00465781 1 0 1 1 0 0 +EDGE2 4761 4721 -0.0781306 0.0133327 -0.0192123 1 0 1 1 0 0 +EDGE2 4761 4720 -1.08339 0.000613247 1.61449 1 0 1 1 0 0 +EDGE2 4762 4723 0.952914 0.0510717 -0.0153669 1 0 1 1 0 0 +EDGE2 4762 4761 -1.02763 0.0259027 -0.00786347 1 0 1 1 0 0 +EDGE2 4762 4722 0.0172564 0.0928684 -0.029585 1 0 1 1 0 0 +EDGE2 4762 4721 -0.978642 -0.00643982 0.0183538 1 0 1 1 0 0 +EDGE2 4763 4762 -1.06082 -0.0552047 -0.0484894 1 0 1 1 0 0 +EDGE2 4763 4724 1.02553 0.00694293 -0.00894308 1 0 1 1 0 0 +EDGE2 4763 4723 0.00466624 0.0655384 -0.0155615 1 0 1 1 0 0 +EDGE2 4763 4722 -0.934516 0.07715 -0.00419006 1 0 1 1 0 0 +EDGE2 4764 4763 -1.02013 -0.0510956 -0.0132866 1 0 1 1 0 0 +EDGE2 4764 4725 0.98883 0.0260662 -0.0249667 1 0 1 1 0 0 +EDGE2 4764 4724 0.00120228 0.0115556 0.00646122 1 0 1 1 0 0 +EDGE2 4764 4723 -0.968022 -0.0431891 -0.0235711 1 0 1 1 0 0 +EDGE2 4765 4726 0.0284508 1.04076 1.58216 1 0 1 1 0 0 +EDGE2 4765 4764 -0.961013 0.00316331 0.0122634 1 0 1 1 0 0 +EDGE2 4765 4725 -0.0347213 0.0123119 -0.0136922 1 0 1 1 0 0 +EDGE2 4765 4724 -0.943969 -0.0508823 -0.015621 1 0 1 1 0 0 +EDGE2 4766 4725 -0.964706 -0.0441262 1.57183 1 0 1 1 0 0 +EDGE2 4766 4765 -0.983502 0.0479679 1.58481 1 0 1 1 0 0 +EDGE2 4767 4766 -0.941453 -0.0278655 0.015155 1 0 1 1 0 0 +EDGE2 4768 4767 -1.01112 -0.138285 -0.0239056 1 0 1 1 0 0 +EDGE2 4769 4768 -1.06608 0.00303465 -0.000237177 1 0 1 1 0 0 +EDGE2 4770 4769 -0.955992 0.0762802 0.0435343 1 0 1 1 0 0 +EDGE2 4771 4770 -0.984936 0.0653147 -1.56861 1 0 1 1 0 0 +EDGE2 4772 4771 -1.01529 0.0600565 0.0351106 1 0 1 1 0 0 +EDGE2 4773 4772 -0.967545 -0.0516033 -0.0233 1 0 1 1 0 0 +EDGE2 4774 4773 -0.975056 -0.0283773 -0.0309008 1 0 1 1 0 0 +EDGE2 4775 4774 -1.03141 0.0872595 0.00297127 1 0 1 1 0 0 +EDGE2 4776 4775 -0.941392 -0.0385002 1.55044 1 0 1 1 0 0 +EDGE2 4777 4776 -0.953914 -0.0108542 -0.0114877 1 0 1 1 0 0 +EDGE2 4778 4777 -0.919675 0.0937519 -0.00614963 1 0 1 1 0 0 +EDGE2 4779 4778 -0.978176 -0.047611 -0.00813231 1 0 1 1 0 0 +EDGE2 4780 4779 -1.01248 -0.040308 0.0273901 1 0 1 1 0 0 +EDGE2 4781 4780 -0.94813 0.0297826 1.57926 1 0 1 1 0 0 +EDGE2 4782 4781 -1.00632 0.000325003 0.0124988 1 0 1 1 0 0 +EDGE2 4783 4782 -0.953516 -0.039145 -0.00490413 1 0 1 1 0 0 +EDGE2 4784 4783 -0.963991 -0.0499456 0.00221887 1 0 1 1 0 0 +EDGE2 4785 4784 -0.977076 0.00249232 -0.0232782 1 0 1 1 0 0 +EDGE2 4786 4785 -1.04565 -0.0455247 -1.56662 1 0 1 1 0 0 +EDGE2 4787 4786 -0.964601 0.0705552 -0.0189978 1 0 1 1 0 0 +EDGE2 4788 4787 -1.00361 -0.0633724 -0.00649734 1 0 1 1 0 0 +EDGE2 4789 4788 -1.0355 0.0109435 -0.0229172 1 0 1 1 0 0 +EDGE2 4790 4789 -0.931909 0.00366545 0.00403783 1 0 1 1 0 0 +EDGE2 4791 4790 -1.0522 0.0961548 -1.5946 1 0 1 1 0 0 +EDGE2 4792 4791 -1.03266 0.017409 0.0201339 1 0 1 1 0 0 +EDGE2 4793 4792 -1.03391 -0.00629051 0.0224378 1 0 1 1 0 0 +EDGE2 4794 4793 -1.0678 -0.0120851 -0.00813277 1 0 1 1 0 0 +EDGE2 4795 4794 -0.976347 -0.059102 0.0161671 1 0 1 1 0 0 +EDGE2 4796 4795 -0.92561 0.0282241 -1.55116 1 0 1 1 0 0 +EDGE2 4797 4796 -1.009 0.0222392 0.0164535 1 0 1 1 0 0 +EDGE2 4798 4797 -0.968214 0.0754007 -0.000245714 1 0 1 1 0 0 +EDGE2 4799 4780 1.02297 0.0256665 -3.15271 1 0 1 1 0 0 +EDGE2 4799 4798 -0.988451 0.0598454 0.000713912 1 0 1 1 0 0 +EDGE2 4800 4779 0.979179 0.0537555 -3.17173 1 0 1 1 0 0 +EDGE2 4800 4780 0.0671195 0.0694896 -3.14487 1 0 1 1 0 0 +EDGE2 4800 4781 0.00576276 1.02429 1.5252 1 0 1 1 0 0 +EDGE2 4800 4799 -1.03295 -0.0206227 -0.0214471 1 0 1 1 0 0 +EDGE2 4801 4782 1.04081 -0.0212484 0.0192373 1 0 1 1 0 0 +EDGE2 4801 4780 -1.00832 -0.0434012 1.60447 1 0 1 1 0 0 +EDGE2 4801 4800 -0.937209 0.0131751 -1.59293 1 0 1 1 0 0 +EDGE2 4801 4781 -0.0588177 0.0873199 -0.00524967 1 0 1 1 0 0 +EDGE2 4802 4782 -0.0115319 -0.000112056 0.00376296 1 0 1 1 0 0 +EDGE2 4802 4781 -0.927345 0.0191584 0.0198414 1 0 1 1 0 0 +EDGE2 4802 4801 -1.01442 -0.029537 -0.0243436 1 0 1 1 0 0 +EDGE2 4802 4783 0.926281 0.0223162 0.0136934 1 0 1 1 0 0 +EDGE2 4803 4782 -0.976384 0.0631276 -0.00135979 1 0 1 1 0 0 +EDGE2 4803 4802 -1.03786 0.0271888 -0.0131067 1 0 1 1 0 0 +EDGE2 4803 4784 1.01033 -0.0048823 -0.0313772 1 0 1 1 0 0 +EDGE2 4803 4783 -0.0306497 0.0236093 0.00961738 1 0 1 1 0 0 +EDGE2 4804 4784 -0.0813811 -0.0881727 -0.0210297 1 0 1 1 0 0 +EDGE2 4804 4783 -0.994064 -0.035983 -0.0074045 1 0 1 1 0 0 +EDGE2 4804 4803 -0.970701 0.126587 0.0126791 1 0 1 1 0 0 +EDGE2 4804 4785 0.910596 -0.0229425 0.00302129 1 0 1 1 0 0 +EDGE2 4805 4784 -0.968798 0.0476182 -0.0376063 1 0 1 1 0 0 +EDGE2 4805 4804 -0.986522 0.0432658 0.0277017 1 0 1 1 0 0 +EDGE2 4805 4785 0.0268951 8.64607e-05 -0.00151838 1 0 1 1 0 0 +EDGE2 4805 4786 -0.0970028 1.0142 1.58084 1 0 1 1 0 0 +EDGE2 4806 4785 -0.938906 -0.0458814 1.5672 1 0 1 1 0 0 +EDGE2 4806 4805 -1.03277 -0.00539183 1.55437 1 0 1 1 0 0 +EDGE2 4807 4806 -1.03807 -0.0240593 0.00931313 1 0 1 1 0 0 +EDGE2 4808 4807 -0.945708 -0.0154473 -0.00687948 1 0 1 1 0 0 +EDGE2 4809 4770 0.890902 -0.0475144 -3.15031 1 0 1 1 0 0 +EDGE2 4809 4808 -1.03088 -0.04092 0.0275315 1 0 1 1 0 0 +EDGE2 4810 4771 0.00666191 -1.01519 -1.59751 1 0 1 1 0 0 +EDGE2 4810 4769 1.01496 0.071669 -3.14007 1 0 1 1 0 0 +EDGE2 4810 4770 -0.0403108 -0.0394289 -3.14955 1 0 1 1 0 0 +EDGE2 4810 4809 -1.08515 -0.0336519 -0.0124545 1 0 1 1 0 0 +EDGE2 4811 4770 -1.03125 0.0219984 1.58119 1 0 1 1 0 0 +EDGE2 4811 4810 -0.94968 -0.0685877 -1.53453 1 0 1 1 0 0 +EDGE2 4812 4811 -1.0353 0.0480167 0.00820244 1 0 1 1 0 0 +EDGE2 4813 4812 -0.835487 0.048545 0.0125487 1 0 1 1 0 0 +EDGE2 4814 4715 0.911988 -0.0151897 -3.14704 1 0 1 1 0 0 +EDGE2 4814 4813 -1.08605 -0.0173169 -0.00276311 1 0 1 1 0 0 +EDGE2 4815 4715 -0.00728604 -0.104032 -3.14803 1 0 1 1 0 0 +EDGE2 4815 4716 -0.107724 -0.988602 -1.58446 1 0 1 1 0 0 +EDGE2 4815 4814 -0.95952 -0.045708 -0.0224014 1 0 1 1 0 0 +EDGE2 4815 4714 0.979824 -0.0122398 -3.12889 1 0 1 1 0 0 +EDGE2 4816 4715 -1.11297 -0.0551872 1.56466 1 0 1 1 0 0 +EDGE2 4816 4815 -1.00376 0.041408 -1.54737 1 0 1 1 0 0 +EDGE2 4817 4816 -0.986919 -0.0315221 0.0318333 1 0 1 1 0 0 +EDGE2 4818 4817 -1.0531 0.055833 -0.0387682 1 0 1 1 0 0 +EDGE2 4819 4818 -0.990382 0.0362104 0.0138063 1 0 1 1 0 0 +EDGE2 4819 4580 1.11082 0.0183641 -3.13875 1 0 1 1 0 0 +EDGE2 4819 4680 1.0642 0.0612104 -3.1561 1 0 1 1 0 0 +EDGE2 4819 4700 1.08189 -0.0078321 -3.1129 1 0 1 1 0 0 +EDGE2 4820 4819 -0.973478 -0.00522768 0.0298117 1 0 1 1 0 0 +EDGE2 4820 4580 -0.0397963 0.0742657 -3.15713 1 0 1 1 0 0 +EDGE2 4820 4680 -0.0300774 0.00620375 -3.12333 1 0 1 1 0 0 +EDGE2 4820 4700 -0.0255596 -0.0135292 -3.15796 1 0 1 1 0 0 +EDGE2 4820 4681 0.0598137 -1.02505 -1.58449 1 0 1 1 0 0 +EDGE2 4820 4701 -0.0413185 -0.997888 -1.59791 1 0 1 1 0 0 +EDGE2 4820 4581 -0.125662 -1.00891 -1.50365 1 0 1 1 0 0 +EDGE2 4820 4679 0.996446 -0.0544459 -3.13115 1 0 1 1 0 0 +EDGE2 4820 4699 1.03274 -0.0553048 -3.12266 1 0 1 1 0 0 +EDGE2 4820 4579 1.01363 -0.0371324 -3.14246 1 0 1 1 0 0 +EDGE2 4821 4820 -0.966967 -0.053884 -1.54977 1 0 1 1 0 0 +EDGE2 4821 4580 -0.987232 0.105109 1.55559 1 0 1 1 0 0 +EDGE2 4821 4680 -1.01731 -0.0618153 1.53936 1 0 1 1 0 0 +EDGE2 4821 4700 -0.994027 -0.0171758 1.54979 1 0 1 1 0 0 +EDGE2 4822 4821 -0.958633 0.0458486 -0.00707511 1 0 1 1 0 0 +EDGE2 4823 4822 -1.02847 0.00332667 -0.0259391 1 0 1 1 0 0 +EDGE2 4824 4785 1.02184 0.0634503 -3.13814 1 0 1 1 0 0 +EDGE2 4824 4805 0.90828 -0.0143287 -3.12801 1 0 1 1 0 0 +EDGE2 4824 4823 -1.08484 -0.0741041 0.00150441 1 0 1 1 0 0 +EDGE2 4825 4806 0.0266758 1.02603 1.57213 1 0 1 1 0 0 +EDGE2 4825 4784 0.913848 0.0464874 -3.16437 1 0 1 1 0 0 +EDGE2 4825 4804 1.04966 0.047151 -3.16277 1 0 1 1 0 0 +EDGE2 4825 4785 0.050288 -0.032415 -3.15348 1 0 1 1 0 0 +EDGE2 4825 4805 -0.0441692 -0.0270706 -3.12567 1 0 1 1 0 0 +EDGE2 4825 4824 -0.99697 -0.0249955 0.0283253 1 0 1 1 0 0 +EDGE2 4825 4786 -0.0152061 -1.06343 -1.591 1 0 1 1 0 0 +EDGE2 4826 4807 1.05187 -0.0260952 -0.0200413 1 0 1 1 0 0 +EDGE2 4826 4806 0.01708 -0.00344103 0.00172289 1 0 1 1 0 0 +EDGE2 4826 4825 -0.975813 -0.0222034 -1.6037 1 0 1 1 0 0 +EDGE2 4826 4785 -0.916367 0.0213421 1.57222 1 0 1 1 0 0 +EDGE2 4826 4805 -0.944519 0.0305595 1.5862 1 0 1 1 0 0 +EDGE2 4827 4808 1.01418 0.0633069 -0.0364 1 0 1 1 0 0 +EDGE2 4827 4826 -1.00897 -0.0456552 0.0335982 1 0 1 1 0 0 +EDGE2 4827 4807 -0.0736935 -0.0311162 -0.0173884 1 0 1 1 0 0 +EDGE2 4827 4806 -1.0504 0.0158999 -0.0298592 1 0 1 1 0 0 +EDGE2 4828 4827 -1.0021 0.119702 0.0111826 1 0 1 1 0 0 +EDGE2 4828 4809 0.947561 -0.0341404 -0.00448816 1 0 1 1 0 0 +EDGE2 4828 4808 -0.00561534 0.0165157 -0.00202942 1 0 1 1 0 0 +EDGE2 4828 4807 -0.942526 -0.0224257 0.00925676 1 0 1 1 0 0 +EDGE2 4829 4770 0.940086 -0.0174152 -3.12359 1 0 1 1 0 0 +EDGE2 4829 4810 0.976985 -0.0315431 -0.000196202 1 0 1 1 0 0 +EDGE2 4829 4828 -0.953995 0.0484382 -0.0155747 1 0 1 1 0 0 +EDGE2 4829 4809 -0.0624329 -0.094859 -0.0475828 1 0 1 1 0 0 +EDGE2 4829 4808 -1.01187 0.000391584 -0.0108824 1 0 1 1 0 0 +EDGE2 4830 4811 -0.0196851 1.03169 1.60602 1 0 1 1 0 0 +EDGE2 4830 4771 0.0192312 -0.925503 -1.57113 1 0 1 1 0 0 +EDGE2 4830 4769 1.0712 -0.100811 -3.13053 1 0 1 1 0 0 +EDGE2 4830 4770 -0.00742698 -0.0133506 -3.14207 1 0 1 1 0 0 +EDGE2 4830 4810 -0.0315468 -0.0114631 -0.0303076 1 0 1 1 0 0 +EDGE2 4830 4809 -0.955649 -0.0252485 -0.0258518 1 0 1 1 0 0 +EDGE2 4830 4829 -1.06236 0.0540492 0.00914489 1 0 1 1 0 0 +EDGE2 4831 4811 0.0440076 -0.0065263 0.00462327 1 0 1 1 0 0 +EDGE2 4831 4770 -1.04034 -0.0592079 1.56286 1 0 1 1 0 0 +EDGE2 4831 4810 -1.03642 -0.0205062 -1.56871 1 0 1 1 0 0 +EDGE2 4831 4830 -1.06645 0.0166257 -1.57698 1 0 1 1 0 0 +EDGE2 4831 4812 0.959908 -0.035828 -0.00559715 1 0 1 1 0 0 +EDGE2 4832 4811 -1.0483 0.0669329 0.000551026 1 0 1 1 0 0 +EDGE2 4832 4831 -1.04247 -0.126056 -0.00902948 1 0 1 1 0 0 +EDGE2 4832 4813 1.00322 0.0849638 0.00882843 1 0 1 1 0 0 +EDGE2 4832 4812 -0.0339807 0.0952686 -0.0229848 1 0 1 1 0 0 +EDGE2 4833 4813 -0.0793722 0.0254817 -0.024674 1 0 1 1 0 0 +EDGE2 4833 4812 -1.0543 -0.122843 0.0621493 1 0 1 1 0 0 +EDGE2 4833 4832 -0.999001 -0.000209365 -0.0158098 1 0 1 1 0 0 +EDGE2 4833 4814 0.931754 -0.0422992 -0.0165092 1 0 1 1 0 0 +EDGE2 4834 4715 0.988147 0.0770503 -3.14397 1 0 1 1 0 0 +EDGE2 4834 4813 -1.0193 -0.0193272 0.0157639 1 0 1 1 0 0 +EDGE2 4834 4833 -0.991292 0.00480408 0.0296028 1 0 1 1 0 0 +EDGE2 4834 4814 -0.0479001 0.00818999 0.00579362 1 0 1 1 0 0 +EDGE2 4834 4815 0.988004 0.021319 0.0422351 1 0 1 1 0 0 +EDGE2 4835 4715 -0.042281 0.0844725 -3.09862 1 0 1 1 0 0 +EDGE2 4835 4716 -0.0419745 -1.06765 -1.55846 1 0 1 1 0 0 +EDGE2 4835 4814 -0.902272 -0.0165237 0.0167222 1 0 1 1 0 0 +EDGE2 4835 4834 -1.0204 0.00407417 -0.0278672 1 0 1 1 0 0 +EDGE2 4835 4815 -0.0553599 0.083691 -2.552e-05 1 0 1 1 0 0 +EDGE2 4835 4714 1.06146 0.0258898 -3.16514 1 0 1 1 0 0 +EDGE2 4835 4816 0.0450161 1.0688 1.56519 1 0 1 1 0 0 +EDGE2 4836 4715 -0.934382 0.00880755 1.57331 1 0 1 1 0 0 +EDGE2 4836 4835 -1.00414 0.0150921 -1.59291 1 0 1 1 0 0 +EDGE2 4836 4815 -0.981746 -0.00753119 -1.54433 1 0 1 1 0 0 +EDGE2 4836 4816 0.0693359 0.0476431 0.0224862 1 0 1 1 0 0 +EDGE2 4836 4817 0.993281 -0.0524843 0.00173968 1 0 1 1 0 0 +EDGE2 4837 4836 -0.958529 -0.00608958 0.023718 1 0 1 1 0 0 +EDGE2 4837 4816 -1.08087 -0.0734452 0.01353 1 0 1 1 0 0 +EDGE2 4837 4817 -0.0156388 0.0116343 0.0303356 1 0 1 1 0 0 +EDGE2 4837 4818 0.999332 0.109403 0.0136696 1 0 1 1 0 0 +EDGE2 4838 4837 -0.972979 -0.00902997 -0.0150446 1 0 1 1 0 0 +EDGE2 4838 4817 -0.95207 0.0241528 -0.00283428 1 0 1 1 0 0 +EDGE2 4838 4818 -0.122636 -0.0500826 -0.00539672 1 0 1 1 0 0 +EDGE2 4838 4819 0.960749 0.0336356 0.0130578 1 0 1 1 0 0 +EDGE2 4839 4838 -1.09421 -0.00980912 -0.00907104 1 0 1 1 0 0 +EDGE2 4839 4818 -1.02204 -0.00379099 -0.0134674 1 0 1 1 0 0 +EDGE2 4839 4819 -0.0404331 -0.0482008 -0.0226945 1 0 1 1 0 0 +EDGE2 4839 4820 0.95048 -0.00895433 -0.00845786 1 0 1 1 0 0 +EDGE2 4839 4580 0.989458 -0.041413 -3.15292 1 0 1 1 0 0 +EDGE2 4839 4680 0.980212 0.0801743 -3.14158 1 0 1 1 0 0 +EDGE2 4839 4700 1.07075 -0.045078 -3.14958 1 0 1 1 0 0 +EDGE2 4840 4839 -1.00292 -0.0357882 -0.0167101 1 0 1 1 0 0 +EDGE2 4840 4819 -1.06758 -0.0162548 -0.0079294 1 0 1 1 0 0 +EDGE2 4840 4820 0.0265173 -0.0518635 -0.0344956 1 0 1 1 0 0 +EDGE2 4840 4821 -0.0372244 1.02658 1.55238 1 0 1 1 0 0 +EDGE2 4840 4580 0.0432794 -0.0873644 -3.13241 1 0 1 1 0 0 +EDGE2 4840 4680 0.0278679 0.0345975 -3.12513 1 0 1 1 0 0 +EDGE2 4840 4700 -0.0818493 -0.0217618 -3.12202 1 0 1 1 0 0 +EDGE2 4840 4681 0.0525878 -0.98183 -1.57132 1 0 1 1 0 0 +EDGE2 4840 4701 -0.0360432 -1.00397 -1.54618 1 0 1 1 0 0 +EDGE2 4840 4581 -0.0256847 -0.908281 -1.59926 1 0 1 1 0 0 +EDGE2 4840 4679 1.08038 -0.00402877 -3.13788 1 0 1 1 0 0 +EDGE2 4840 4699 1.01018 0.0302453 -3.17084 1 0 1 1 0 0 +EDGE2 4840 4579 1.00571 -0.00931216 -3.12964 1 0 1 1 0 0 +EDGE2 4841 4820 -1.00737 -0.0499251 -1.53163 1 0 1 1 0 0 +EDGE2 4841 4821 -0.00809944 0.0376606 0.0176982 1 0 1 1 0 0 +EDGE2 4841 4822 0.991174 0.0301223 -0.019014 1 0 1 1 0 0 +EDGE2 4841 4840 -1.00104 0.0395865 -1.58692 1 0 1 1 0 0 +EDGE2 4841 4580 -0.941932 -0.0571815 1.57527 1 0 1 1 0 0 +EDGE2 4841 4680 -1.03123 0.019848 1.53228 1 0 1 1 0 0 +EDGE2 4841 4700 -0.889644 -0.0630937 1.58331 1 0 1 1 0 0 +EDGE2 4842 4821 -1.08712 0.0289358 -0.0377921 1 0 1 1 0 0 +EDGE2 4842 4822 0.0441435 0.0182405 0.00835233 1 0 1 1 0 0 +EDGE2 4842 4823 0.956401 0.0612306 0.000733124 1 0 1 1 0 0 +EDGE2 4842 4841 -0.977449 -0.0128732 -0.00776616 1 0 1 1 0 0 +EDGE2 4843 4824 1.01143 -0.0184359 -0.0116652 1 0 1 1 0 0 +EDGE2 4843 4822 -0.962108 -0.0107334 -0.0002493 1 0 1 1 0 0 +EDGE2 4843 4842 -1.00112 -0.0213579 -0.00580577 1 0 1 1 0 0 +EDGE2 4843 4823 -0.0279513 -0.0209895 -0.00977023 1 0 1 1 0 0 +EDGE2 4844 4843 -0.953027 0.0977701 -0.0242942 1 0 1 1 0 0 +EDGE2 4844 4825 0.912137 0.0241935 -0.0140995 1 0 1 1 0 0 +EDGE2 4844 4785 0.938731 0.0327692 -3.10885 1 0 1 1 0 0 +EDGE2 4844 4805 1.00236 -0.00790924 -3.12174 1 0 1 1 0 0 +EDGE2 4844 4824 -0.0528872 0.0365693 -0.00481337 1 0 1 1 0 0 +EDGE2 4844 4823 -0.974171 -0.0356631 0.0190814 1 0 1 1 0 0 +EDGE2 4845 4826 -0.00830254 1.06358 1.54641 1 0 1 1 0 0 +EDGE2 4845 4806 -0.0457704 1.06066 1.5769 1 0 1 1 0 0 +EDGE2 4845 4784 1.00754 0.0533456 -3.12946 1 0 1 1 0 0 +EDGE2 4845 4804 0.883931 -0.0651014 -3.11683 1 0 1 1 0 0 +EDGE2 4845 4825 0.030634 -0.0285949 -0.0183671 1 0 1 1 0 0 +EDGE2 4845 4844 -1.07491 -0.0526622 -0.0135838 1 0 1 1 0 0 +EDGE2 4845 4785 -0.0673223 0.0531581 -3.13596 1 0 1 1 0 0 +EDGE2 4845 4805 -0.00774607 -0.0115658 -3.16842 1 0 1 1 0 0 +EDGE2 4845 4824 -0.914233 -0.0820142 0.0170956 1 0 1 1 0 0 +EDGE2 4845 4786 -0.0148537 -0.971389 -1.58355 1 0 1 1 0 0 +EDGE2 4846 4825 -0.975002 0.072855 1.55968 1 0 1 1 0 0 +EDGE2 4846 4845 -0.94176 -0.0224938 1.59395 1 0 1 1 0 0 +EDGE2 4846 4785 -0.974749 0.0499406 -1.54886 1 0 1 1 0 0 +EDGE2 4846 4805 -0.938016 -0.0106298 -1.53843 1 0 1 1 0 0 +EDGE2 4846 4786 0.0503156 0.0468111 0.0101136 1 0 1 1 0 0 +EDGE2 4846 4787 0.892189 -0.067269 0.0238972 1 0 1 1 0 0 +EDGE2 4847 4786 -1.04681 -0.0779597 -0.0337127 1 0 1 1 0 0 +EDGE2 4847 4846 -1.02131 0.0393341 0.00416933 1 0 1 1 0 0 +EDGE2 4847 4787 -0.0389143 0.0756968 0.00788527 1 0 1 1 0 0 +EDGE2 4847 4788 0.973823 0.0401588 -0.0135432 1 0 1 1 0 0 +EDGE2 4848 4787 -0.885693 0.0313828 -0.0104871 1 0 1 1 0 0 +EDGE2 4848 4847 -1.01861 0.0390711 0.00543855 1 0 1 1 0 0 +EDGE2 4848 4788 -0.0420017 0.0616804 -0.00170414 1 0 1 1 0 0 +EDGE2 4848 4789 1.05137 -0.00145097 -0.0163257 1 0 1 1 0 0 +EDGE2 4849 4788 -1.0777 0.00592655 0.00689215 1 0 1 1 0 0 +EDGE2 4849 4848 -0.939188 -0.00105137 0.00236803 1 0 1 1 0 0 +EDGE2 4849 4789 -0.0748179 -0.0629188 -0.00729117 1 0 1 1 0 0 +EDGE2 4849 4790 1.08398 0.0482519 -0.0476765 1 0 1 1 0 0 +EDGE2 4850 4849 -0.961128 0.0102318 0.0161879 1 0 1 1 0 0 +EDGE2 4850 4789 -1.06127 0.0978025 -0.00329751 1 0 1 1 0 0 +EDGE2 4850 4791 -0.0422347 0.991937 1.6002 1 0 1 1 0 0 +EDGE2 4850 4790 0.0388854 -0.0411574 0.0201345 1 0 1 1 0 0 +EDGE2 4851 4792 0.995991 -0.0190056 -0.0211822 1 0 1 1 0 0 +EDGE2 4851 4791 0.0992489 0.0710028 0.000669173 1 0 1 1 0 0 +EDGE2 4851 4850 -0.946108 0.0062466 -1.59999 1 0 1 1 0 0 +EDGE2 4851 4790 -0.980606 -0.0101034 -1.54131 1 0 1 1 0 0 +EDGE2 4852 4793 1.05637 0.0312219 0.00609153 1 0 1 1 0 0 +EDGE2 4852 4792 -0.0369079 -0.0180085 0.0171421 1 0 1 1 0 0 +EDGE2 4852 4791 -1.01337 0.0722942 -0.025308 1 0 1 1 0 0 +EDGE2 4852 4851 -1.02903 -0.00954938 0.0163472 1 0 1 1 0 0 +EDGE2 4853 4794 0.983817 -0.0606697 0.0238254 1 0 1 1 0 0 +EDGE2 4853 4793 -0.0272316 0.0215859 -0.0135483 1 0 1 1 0 0 +EDGE2 4853 4792 -0.976851 0.0100934 -0.018909 1 0 1 1 0 0 +EDGE2 4853 4852 -0.936741 0.0707816 0.0411367 1 0 1 1 0 0 +EDGE2 4854 4795 0.992267 0.00558051 0.0392086 1 0 1 1 0 0 +EDGE2 4854 4794 -0.124316 -0.067968 -0.014001 1 0 1 1 0 0 +EDGE2 4854 4793 -0.998776 0.0165714 0.00654276 1 0 1 1 0 0 +EDGE2 4854 4853 -0.98951 0.0726859 -0.0333392 1 0 1 1 0 0 +EDGE2 4855 4796 -0.0696234 1.0514 1.55828 1 0 1 1 0 0 +EDGE2 4855 4795 -0.00840806 0.0298555 0.0232067 1 0 1 1 0 0 +EDGE2 4855 4794 -1.00979 -0.0195533 0.00113997 1 0 1 1 0 0 +EDGE2 4855 4854 -1.06032 -0.0184649 -0.0171907 1 0 1 1 0 0 +EDGE2 4856 4797 1.02521 -0.0534272 0.00512886 1 0 1 1 0 0 +EDGE2 4856 4796 -0.0361261 -0.0135703 -0.0309073 1 0 1 1 0 0 +EDGE2 4856 4795 -0.971801 -0.00998847 -1.615 1 0 1 1 0 0 +EDGE2 4856 4855 -1.0373 0.026389 -1.578 1 0 1 1 0 0 +EDGE2 4857 4798 0.99647 0.0258374 0.00391853 1 0 1 1 0 0 +EDGE2 4857 4797 -0.0365941 -0.0255422 0.00408907 1 0 1 1 0 0 +EDGE2 4857 4856 -0.985536 0.0178807 0.0277257 1 0 1 1 0 0 +EDGE2 4857 4796 -0.994047 -0.0260841 -0.00882975 1 0 1 1 0 0 +EDGE2 4858 4799 1.06835 -0.0192733 -0.0230623 1 0 1 1 0 0 +EDGE2 4858 4857 -0.953372 -0.0529151 0.0188172 1 0 1 1 0 0 +EDGE2 4858 4798 0.0939036 0.0240434 0.00012926 1 0 1 1 0 0 +EDGE2 4858 4797 -1.04106 0.114747 -0.0116169 1 0 1 1 0 0 +EDGE2 4859 4780 0.986704 -0.0263215 -3.13903 1 0 1 1 0 0 +EDGE2 4859 4800 1.02996 0.0203668 0.0385829 1 0 1 1 0 0 +EDGE2 4859 4799 -0.011312 0.045454 -0.0141149 1 0 1 1 0 0 +EDGE2 4859 4798 -1.01211 0.0409331 0.0156088 1 0 1 1 0 0 +EDGE2 4859 4858 -1.01254 -0.0125029 -0.0171593 1 0 1 1 0 0 +EDGE2 4860 4779 0.984596 -0.089236 -3.11514 1 0 1 1 0 0 +EDGE2 4860 4780 -0.0128388 -0.0523945 -3.12198 1 0 1 1 0 0 +EDGE2 4860 4800 -0.155172 -0.0658744 -0.00251521 1 0 1 1 0 0 +EDGE2 4860 4859 -0.985495 0.00687715 -0.0254638 1 0 1 1 0 0 +EDGE2 4860 4781 -0.11806 1.0594 1.5634 1 0 1 1 0 0 +EDGE2 4860 4801 0.072087 1.01718 1.54317 1 0 1 1 0 0 +EDGE2 4860 4799 -0.941382 -0.0787219 -0.0251837 1 0 1 1 0 0 +EDGE2 4861 4782 0.966531 0.0040054 0.0373967 1 0 1 1 0 0 +EDGE2 4861 4780 -0.971202 -0.0383251 1.5718 1 0 1 1 0 0 +EDGE2 4861 4800 -1.02585 -0.0290888 -1.55536 1 0 1 1 0 0 +EDGE2 4861 4860 -1.02054 0.0769137 -1.56744 1 0 1 1 0 0 +EDGE2 4861 4781 -0.0129406 0.0547837 0.0163938 1 0 1 1 0 0 +EDGE2 4861 4801 0.0545999 0.0409169 -0.00332109 1 0 1 1 0 0 +EDGE2 4861 4802 1.04178 0.00206281 0.00441367 1 0 1 1 0 0 +EDGE2 4862 4782 -0.126548 -0.00885488 0.0147189 1 0 1 1 0 0 +EDGE2 4862 4781 -0.987395 -0.0547525 -0.00474906 1 0 1 1 0 0 +EDGE2 4862 4801 -0.999206 -0.0231882 -0.0269439 1 0 1 1 0 0 +EDGE2 4862 4861 -0.961372 -0.0452852 0.000360261 1 0 1 1 0 0 +EDGE2 4862 4802 0.0175722 0.0202052 0.0148709 1 0 1 1 0 0 +EDGE2 4862 4783 0.942224 0.0275355 -0.0213744 1 0 1 1 0 0 +EDGE2 4862 4803 0.964839 0.00860359 -0.0065363 1 0 1 1 0 0 +EDGE2 4863 4782 -1.00849 -0.0301304 0.00846377 1 0 1 1 0 0 +EDGE2 4863 4802 -1.01888 0.00702162 0.00755918 1 0 1 1 0 0 +EDGE2 4863 4862 -0.942614 -0.0209856 -0.0240404 1 0 1 1 0 0 +EDGE2 4863 4784 0.997761 -0.00128463 -0.0174225 1 0 1 1 0 0 +EDGE2 4863 4783 -0.0287355 0.00773795 -0.0509424 1 0 1 1 0 0 +EDGE2 4863 4803 0.0244807 -0.0755325 0.00625424 1 0 1 1 0 0 +EDGE2 4863 4804 1.07258 0.0614374 0.0108784 1 0 1 1 0 0 +EDGE2 4864 4784 0.0646808 0.0898976 0.023006 1 0 1 1 0 0 +EDGE2 4864 4783 -0.956606 -0.0546391 -0.0321814 1 0 1 1 0 0 +EDGE2 4864 4863 -0.948629 0.061933 0.00589899 1 0 1 1 0 0 +EDGE2 4864 4803 -1.09173 0.0795408 -0.00300291 1 0 1 1 0 0 +EDGE2 4864 4804 0.0419262 -0.0361025 -0.00050001 1 0 1 1 0 0 +EDGE2 4864 4825 0.936895 -0.0100967 -3.11133 1 0 1 1 0 0 +EDGE2 4864 4845 1.05172 0.0139632 -3.16786 1 0 1 1 0 0 +EDGE2 4864 4785 1.00831 0.112496 -0.00251492 1 0 1 1 0 0 +EDGE2 4864 4805 1.06463 0.0430468 -0.0264361 1 0 1 1 0 0 +EDGE2 4865 4826 -0.0905947 -1.07596 -1.55096 1 0 1 1 0 0 +EDGE2 4865 4806 -0.0165443 -0.949508 -1.56994 1 0 1 1 0 0 +EDGE2 4865 4784 -1.03078 0.0417791 0.00660046 1 0 1 1 0 0 +EDGE2 4865 4864 -0.955537 0.00705796 0.00388818 1 0 1 1 0 0 +EDGE2 4865 4804 -1.05617 -0.0667259 -0.0292309 1 0 1 1 0 0 +EDGE2 4865 4825 0.00396771 -0.0301459 -3.15438 1 0 1 1 0 0 +EDGE2 4865 4845 -0.0754472 0.00937646 -3.15089 1 0 1 1 0 0 +EDGE2 4865 4844 0.915927 -0.0181885 -3.14567 1 0 1 1 0 0 +EDGE2 4865 4785 0.00164913 0.0854283 0.0162301 1 0 1 1 0 0 +EDGE2 4865 4805 -0.0548085 0.0185215 0.0284487 1 0 1 1 0 0 +EDGE2 4865 4824 1.01373 0.0488683 -3.11853 1 0 1 1 0 0 +EDGE2 4865 4786 -0.00118066 1.0119 1.58007 1 0 1 1 0 0 +EDGE2 4865 4846 -0.0450044 0.927649 1.59447 1 0 1 1 0 0 +EDGE2 4866 4825 -1.01652 0.00393997 1.56218 1 0 1 1 0 0 +EDGE2 4866 4865 -0.97815 0.045367 -1.5502 1 0 1 1 0 0 +EDGE2 4866 4845 -1.05825 -0.0255617 1.55949 1 0 1 1 0 0 +EDGE2 4866 4785 -0.939653 0.0333605 -1.57728 1 0 1 1 0 0 +EDGE2 4866 4805 -1.01975 -0.00725177 -1.55532 1 0 1 1 0 0 +EDGE2 4866 4786 -0.0348697 0.0368943 -0.044117 1 0 1 1 0 0 +EDGE2 4866 4846 -0.00279768 0.046152 0.0133105 1 0 1 1 0 0 +EDGE2 4866 4787 0.990362 -0.02793 0.00788127 1 0 1 1 0 0 +EDGE2 4866 4847 0.934573 0.017379 -0.0247892 1 0 1 1 0 0 +EDGE2 4867 4786 -1.03175 -0.0913665 -0.0180732 1 0 1 1 0 0 +EDGE2 4867 4846 -0.924968 0.0220099 0.0138254 1 0 1 1 0 0 +EDGE2 4867 4866 -0.882684 -0.0689603 0.00472745 1 0 1 1 0 0 +EDGE2 4867 4787 0.0219842 0.0626007 0.0178654 1 0 1 1 0 0 +EDGE2 4867 4847 0.0564966 0.0826471 -0.018646 1 0 1 1 0 0 +EDGE2 4867 4788 0.921824 0.0101704 0.00317703 1 0 1 1 0 0 +EDGE2 4867 4848 1.00846 0.00707416 -0.0329114 1 0 1 1 0 0 +EDGE2 4868 4787 -1.01129 0.0160181 0.0289916 1 0 1 1 0 0 +EDGE2 4868 4847 -0.964924 -0.0309283 0.00379487 1 0 1 1 0 0 +EDGE2 4868 4867 -1.0348 0.0124831 0.0214832 1 0 1 1 0 0 +EDGE2 4868 4788 -0.0390324 -0.00703954 0.0322528 1 0 1 1 0 0 +EDGE2 4868 4848 -0.00954867 0.0754511 0.0245682 1 0 1 1 0 0 +EDGE2 4868 4849 0.96949 -0.0665226 0.000262697 1 0 1 1 0 0 +EDGE2 4868 4789 1.01126 0.0076513 -0.000729712 1 0 1 1 0 0 +EDGE2 4869 4788 -0.935624 0.0788576 -0.0257981 1 0 1 1 0 0 +EDGE2 4869 4848 -0.986201 -0.0430085 0.00520675 1 0 1 1 0 0 +EDGE2 4869 4868 -1.05677 -0.0496425 0.0149989 1 0 1 1 0 0 +EDGE2 4869 4849 0.0512305 -0.0652354 -0.00424147 1 0 1 1 0 0 +EDGE2 4869 4789 0.0892608 0.0547198 -0.0180509 1 0 1 1 0 0 +EDGE2 4869 4850 0.943508 0.0131447 0.00788314 1 0 1 1 0 0 +EDGE2 4869 4790 1.03668 -0.0664234 -0.0310282 1 0 1 1 0 0 +EDGE2 4870 4849 -0.927404 0.00544809 -0.00610406 1 0 1 1 0 0 +EDGE2 4870 4869 -1.00293 0.0076652 -0.0515979 1 0 1 1 0 0 +EDGE2 4870 4789 -1.05698 -0.0101642 -0.00515127 1 0 1 1 0 0 +EDGE2 4870 4791 -0.0199642 1.03965 1.59096 1 0 1 1 0 0 +EDGE2 4870 4851 -0.0197589 1.04617 1.59991 1 0 1 1 0 0 +EDGE2 4870 4850 0.0176976 0.0728037 -0.0239758 1 0 1 1 0 0 +EDGE2 4870 4790 0.0243323 -0.00413326 -0.0136454 1 0 1 1 0 0 +EDGE2 4871 4850 -0.989137 0.0291333 1.57275 1 0 1 1 0 0 +EDGE2 4871 4870 -0.940709 -0.0795417 1.53745 1 0 1 1 0 0 +EDGE2 4871 4790 -0.957908 -0.0155952 1.56565 1 0 1 1 0 0 +EDGE2 4872 4871 -0.996159 -0.000707799 -0.027264 1 0 1 1 0 0 +EDGE2 4873 4872 -1.02464 0.024297 -0.00590268 1 0 1 1 0 0 +EDGE2 4874 4873 -1.03527 -0.00294663 -0.0171106 1 0 1 1 0 0 +EDGE2 4874 4575 1.08945 -0.0375697 -3.17222 1 0 1 1 0 0 +EDGE2 4874 4695 1.03042 -0.0520132 -3.13369 1 0 1 1 0 0 +EDGE2 4874 4675 0.928969 0.0289548 -3.14055 1 0 1 1 0 0 +EDGE2 4874 3615 0.98049 -0.0468039 -3.12675 1 0 1 1 0 0 +EDGE2 4875 4676 -0.0469903 -0.992324 -1.55195 1 0 1 1 0 0 +EDGE2 4875 4696 0.0392304 -1.00866 -1.54988 1 0 1 1 0 0 +EDGE2 4875 4576 0.0254609 -0.986158 -1.57904 1 0 1 1 0 0 +EDGE2 4875 4874 -1.07791 -0.00301117 -0.0052514 1 0 1 1 0 0 +EDGE2 4875 4575 0.0369254 0.028362 -3.12292 1 0 1 1 0 0 +EDGE2 4875 4695 0.00519425 0.088447 -3.15504 1 0 1 1 0 0 +EDGE2 4875 4675 -0.0117984 -0.0887923 -3.17733 1 0 1 1 0 0 +EDGE2 4875 3615 0.029255 -0.040363 -3.15829 1 0 1 1 0 0 +EDGE2 4875 3616 0.0409731 0.958338 1.56166 1 0 1 1 0 0 +EDGE2 4875 4574 1.11292 0.0977237 -3.13646 1 0 1 1 0 0 +EDGE2 4875 4674 1.02762 0.0298384 -3.16208 1 0 1 1 0 0 +EDGE2 4875 4694 0.937131 -0.00520084 -3.16811 1 0 1 1 0 0 +EDGE2 4875 3614 1.08427 0.00823227 -3.09366 1 0 1 1 0 0 +EDGE2 4876 4575 -0.977006 -0.0145153 1.53617 1 0 1 1 0 0 +EDGE2 4876 4695 -1.03411 0.0902265 1.58514 1 0 1 1 0 0 +EDGE2 4876 4875 -1.05089 -0.0844494 -1.55283 1 0 1 1 0 0 +EDGE2 4876 4675 -1.01296 0.0998319 1.5862 1 0 1 1 0 0 +EDGE2 4876 3615 -0.965644 -0.0349022 1.58161 1 0 1 1 0 0 +EDGE2 4876 3617 1.00873 0.00348507 0.00287061 1 0 1 1 0 0 +EDGE2 4876 3616 0.0515475 -0.00342458 0.0219138 1 0 1 1 0 0 +EDGE2 4877 3617 -0.0912084 -0.00993319 0.0164859 1 0 1 1 0 0 +EDGE2 4877 4876 -0.972897 -0.042493 -0.0249579 1 0 1 1 0 0 +EDGE2 4877 3616 -0.950991 0.0859822 0.0104202 1 0 1 1 0 0 +EDGE2 4877 3618 0.967954 -0.0470018 -0.00501666 1 0 1 1 0 0 +EDGE2 4878 3619 1.00727 -0.0572363 0.00331063 1 0 1 1 0 0 +EDGE2 4878 3617 -0.931459 0.0148726 -0.0349499 1 0 1 1 0 0 +EDGE2 4878 4877 -1.0126 -0.0293355 0.00927647 1 0 1 1 0 0 +EDGE2 4878 3618 -0.0659359 -0.0307386 0.0106913 1 0 1 1 0 0 +EDGE2 4879 3619 0.00356828 -0.0293754 -0.0214934 1 0 1 1 0 0 +EDGE2 4879 3618 -1.06816 -0.050028 0.00997931 1 0 1 1 0 0 +EDGE2 4879 4878 -0.904017 -0.105559 -0.0311391 1 0 1 1 0 0 +EDGE2 4879 3620 1.00967 0.0201929 -0.0268491 1 0 1 1 0 0 +EDGE2 4880 3619 -1.00761 0.00928431 0.017161 1 0 1 1 0 0 +EDGE2 4880 4879 -0.915062 0.0727884 0.00900361 1 0 1 1 0 0 +EDGE2 4880 3620 -0.0422813 -0.0171991 -0.00970716 1 0 1 1 0 0 +EDGE2 4880 3621 -0.0194194 -0.948504 -1.60892 1 0 1 1 0 0 +EDGE2 4881 4880 -1.01434 -0.0105773 1.56419 1 0 1 1 0 0 +EDGE2 4881 3620 -0.847488 0.0859189 1.59595 1 0 1 1 0 0 +EDGE2 4881 3621 0.10786 -0.0363934 -0.00436561 1 0 1 1 0 0 +EDGE2 4881 3622 0.998204 0.0104206 -0.000896103 1 0 1 1 0 0 +EDGE2 4882 3621 -1.05124 -0.134777 -0.0168847 1 0 1 1 0 0 +EDGE2 4882 4881 -1.02912 -0.0326982 -0.0221849 1 0 1 1 0 0 +EDGE2 4882 3622 0.00682184 0.019732 -0.021455 1 0 1 1 0 0 +EDGE2 4882 3623 1.09389 0.0106979 -0.014351 1 0 1 1 0 0 +EDGE2 4883 3622 -0.959326 -0.0154551 -0.0314369 1 0 1 1 0 0 +EDGE2 4883 4882 -1.02425 -0.0242316 0.0237607 1 0 1 1 0 0 +EDGE2 4883 3623 -0.00899701 -0.00953845 -0.0161476 1 0 1 1 0 0 +EDGE2 4883 3624 0.92762 -0.0475369 0.0145929 1 0 1 1 0 0 +EDGE2 4884 3623 -0.965284 -0.00069975 -0.00391641 1 0 1 1 0 0 +EDGE2 4884 4883 -0.92012 -0.00410548 -0.000579553 1 0 1 1 0 0 +EDGE2 4884 4565 1.08295 -0.00132695 -3.13784 1 0 1 1 0 0 +EDGE2 4884 3624 0.0171366 0.0262363 0.0234932 1 0 1 1 0 0 +EDGE2 4884 3625 1.04611 0.0319046 0.0201315 1 0 1 1 0 0 +EDGE2 4885 4884 -1.00152 -0.0222688 -0.0193923 1 0 1 1 0 0 +EDGE2 4885 4566 0.0440104 -1.02253 -1.55118 1 0 1 1 0 0 +EDGE2 4885 3626 0.0314093 -0.932508 -1.54879 1 0 1 1 0 0 +EDGE2 4885 4565 0.011112 -0.0409054 -3.16647 1 0 1 1 0 0 +EDGE2 4885 3624 -1.02901 -0.00689787 0.0348659 1 0 1 1 0 0 +EDGE2 4885 3625 -0.0291785 -0.00292385 0.00837152 1 0 1 1 0 0 +EDGE2 4885 4564 0.976644 -0.0432105 -3.09776 1 0 1 1 0 0 +EDGE2 4886 4565 -0.963168 -0.0210427 1.5603 1 0 1 1 0 0 +EDGE2 4886 4885 -0.981907 0.0126551 -1.58307 1 0 1 1 0 0 +EDGE2 4886 3625 -0.952853 -0.0349591 -1.59331 1 0 1 1 0 0 +EDGE2 4887 4886 -0.998731 -0.0235357 0.00897544 1 0 1 1 0 0 +EDGE2 4888 4887 -0.957308 -0.0876089 -0.00917566 1 0 1 1 0 0 +EDGE2 4889 4888 -0.988939 0.0625046 0.0332408 1 0 1 1 0 0 +EDGE2 4890 4889 -1.04273 0.0073775 0.000262254 1 0 1 1 0 0 +EDGE2 4891 4890 -1.02979 0.00116041 1.57908 1 0 1 1 0 0 +EDGE2 4892 4891 -0.916225 -0.0416047 0.0142445 1 0 1 1 0 0 +EDGE2 4893 4892 -0.954229 -0.0582862 -0.0101994 1 0 1 1 0 0 +EDGE2 4894 4893 -1.05177 0.0103947 0.0115461 1 0 1 1 0 0 +EDGE2 4894 4555 0.990348 -0.0192581 -3.14005 1 0 1 1 0 0 +EDGE2 4895 4894 -0.975915 0.0268458 -0.0109191 1 0 1 1 0 0 +EDGE2 4895 4556 -0.00360804 -1.02672 -1.57927 1 0 1 1 0 0 +EDGE2 4895 4555 0.0243822 0.0418387 -3.17491 1 0 1 1 0 0 +EDGE2 4895 4554 0.963955 0.0651406 -3.15983 1 0 1 1 0 0 +EDGE2 4896 4555 -1.03378 -0.0010137 1.57472 1 0 1 1 0 0 +EDGE2 4896 4895 -0.944692 0.0271018 -1.5903 1 0 1 1 0 0 +EDGE2 4897 4896 -0.989186 0.0647733 -0.0233122 1 0 1 1 0 0 +EDGE2 4898 4897 -0.950636 0.0268783 -0.0149027 1 0 1 1 0 0 +EDGE2 4899 4898 -0.935644 -0.0180743 -0.0276457 1 0 1 1 0 0 +EDGE2 4900 4899 -1.10619 -0.00251985 0.0177924 1 0 1 1 0 0 +EDGE2 4901 4900 -0.9853 0.0210439 -1.56273 1 0 1 1 0 0 +EDGE2 4902 4901 -1.04338 0.0259953 -0.00140139 1 0 1 1 0 0 +EDGE2 4903 4902 -1.0759 0.0683426 -0.00466869 1 0 1 1 0 0 +EDGE2 4904 4903 -1.00944 0.0657576 0.0110058 1 0 1 1 0 0 +EDGE2 4905 4904 -1.04402 -0.00785137 0.0121855 1 0 1 1 0 0 +EDGE2 4906 4905 -0.945481 0.0257388 -1.54922 1 0 1 1 0 0 +EDGE2 4907 4906 -0.994115 0.0189974 0.0145326 1 0 1 1 0 0 +EDGE2 4908 4907 -0.999693 -0.0347176 0.000880472 1 0 1 1 0 0 +EDGE2 4909 4890 0.995453 0.0481009 -3.12563 1 0 1 1 0 0 +EDGE2 4909 4908 -0.98048 0.108991 0.0121049 1 0 1 1 0 0 +EDGE2 4910 4890 -0.0259889 0.07496 -3.10667 1 0 1 1 0 0 +EDGE2 4910 4889 0.970094 -0.0764392 -3.15579 1 0 1 1 0 0 +EDGE2 4910 4891 0.0256398 0.980084 1.59529 1 0 1 1 0 0 +EDGE2 4910 4909 -1.029 -0.0121341 0.0142128 1 0 1 1 0 0 +EDGE2 4911 4890 -1.0277 -0.00562561 1.55181 1 0 1 1 0 0 +EDGE2 4911 4910 -1.05235 -0.090139 -1.57337 1 0 1 1 0 0 +EDGE2 4911 4891 -0.0511638 -0.00862764 -0.0314871 1 0 1 1 0 0 +EDGE2 4911 4892 1.10581 -0.0478088 -0.0273708 1 0 1 1 0 0 +EDGE2 4912 4891 -1.04082 0.0201281 0.0238432 1 0 1 1 0 0 +EDGE2 4912 4911 -1.04621 0.0387973 -0.0168529 1 0 1 1 0 0 +EDGE2 4912 4892 0.0183243 -0.0934188 -0.0087272 1 0 1 1 0 0 +EDGE2 4912 4893 1.04195 -0.00748562 -0.021828 1 0 1 1 0 0 +EDGE2 4913 4912 -1.04201 -0.0549614 -0.00640704 1 0 1 1 0 0 +EDGE2 4913 4892 -0.970617 -0.0519523 -0.0511672 1 0 1 1 0 0 +EDGE2 4913 4893 0.0315645 0.0461897 -0.00274475 1 0 1 1 0 0 +EDGE2 4913 4894 1.02636 0.0582869 -0.00730158 1 0 1 1 0 0 +EDGE2 4914 4913 -0.976499 0.033214 -0.016381 1 0 1 1 0 0 +EDGE2 4914 4893 -0.968606 0.027835 2.08709e-05 1 0 1 1 0 0 +EDGE2 4914 4894 0.0451882 0.0636954 -0.00140563 1 0 1 1 0 0 +EDGE2 4914 4555 0.962296 0.00355747 -3.1562 1 0 1 1 0 0 +EDGE2 4914 4895 0.990668 0.0760514 -0.024187 1 0 1 1 0 0 +EDGE2 4915 4894 -0.939833 -0.0114895 -0.0086798 1 0 1 1 0 0 +EDGE2 4915 4914 -0.990833 0.0390216 0.0091572 1 0 1 1 0 0 +EDGE2 4915 4556 0.0283249 -1.07231 -1.57583 1 0 1 1 0 0 +EDGE2 4915 4555 0.0216206 -0.0236572 -3.14276 1 0 1 1 0 0 +EDGE2 4915 4895 -0.0656702 0.063889 0.0187654 1 0 1 1 0 0 +EDGE2 4915 4554 0.975905 -0.0505796 -3.14164 1 0 1 1 0 0 +EDGE2 4915 4896 -0.0421125 0.983125 1.61534 1 0 1 1 0 0 +EDGE2 4916 4555 -1.06427 0.0202875 1.60407 1 0 1 1 0 0 +EDGE2 4916 4895 -0.932544 0.0365887 -1.56645 1 0 1 1 0 0 +EDGE2 4916 4915 -1.0459 -0.100204 -1.56465 1 0 1 1 0 0 +EDGE2 4916 4897 0.980437 -0.0477197 0.00100831 1 0 1 1 0 0 +EDGE2 4916 4896 -0.03035 0.0785098 -0.0262095 1 0 1 1 0 0 +EDGE2 4917 4916 -1.01379 -0.0555295 -0.00804339 1 0 1 1 0 0 +EDGE2 4917 4898 0.967206 0.0531132 -0.0238237 1 0 1 1 0 0 +EDGE2 4917 4897 -0.0630293 -0.0186192 0.0123317 1 0 1 1 0 0 +EDGE2 4917 4896 -0.980204 -0.0234558 -0.010184 1 0 1 1 0 0 +EDGE2 4918 4898 -0.0232793 0.034651 0.0123846 1 0 1 1 0 0 +EDGE2 4918 4897 -1.02384 0.0004221 0.01043 1 0 1 1 0 0 +EDGE2 4918 4917 -0.942406 0.0290234 0.036269 1 0 1 1 0 0 +EDGE2 4918 4899 0.965091 -0.0267643 -0.0163342 1 0 1 1 0 0 +EDGE2 4919 4900 0.998394 -0.0324589 -0.00679614 1 0 1 1 0 0 +EDGE2 4919 4898 -1.05552 -0.0943106 -0.00526199 1 0 1 1 0 0 +EDGE2 4919 4918 -1.00731 0.0490386 -0.00717311 1 0 1 1 0 0 +EDGE2 4919 4899 -0.0031265 0.0216801 0.00455951 1 0 1 1 0 0 +EDGE2 4920 4900 -0.013384 0.0425835 0.018065 1 0 1 1 0 0 +EDGE2 4920 4901 -0.0380975 1.04868 1.51556 1 0 1 1 0 0 +EDGE2 4920 4899 -0.992935 0.11475 0.0170714 1 0 1 1 0 0 +EDGE2 4920 4919 -0.986352 0.046314 0.00300555 1 0 1 1 0 0 +EDGE2 4921 4902 0.871598 0.0475606 0.0265032 1 0 1 1 0 0 +EDGE2 4921 4900 -1.03326 -0.0388793 -1.57011 1 0 1 1 0 0 +EDGE2 4921 4901 0.0319723 0.0106748 -0.0285079 1 0 1 1 0 0 +EDGE2 4921 4920 -1.04968 -0.00117042 -1.57568 1 0 1 1 0 0 +EDGE2 4922 4921 -1.01294 -0.0530598 -0.00769694 1 0 1 1 0 0 +EDGE2 4922 4903 1.02155 0.0296009 0.00110549 1 0 1 1 0 0 +EDGE2 4922 4902 -0.032096 -0.0664845 -0.0286681 1 0 1 1 0 0 +EDGE2 4922 4901 -1.00958 0.0440906 -0.0432563 1 0 1 1 0 0 +EDGE2 4923 4904 0.962897 0.064234 -0.0180418 1 0 1 1 0 0 +EDGE2 4923 4922 -0.988501 -0.0249542 0.0126752 1 0 1 1 0 0 +EDGE2 4923 4903 -0.00701409 0.0298546 -0.0017018 1 0 1 1 0 0 +EDGE2 4923 4902 -0.986711 -0.0032851 0.00119841 1 0 1 1 0 0 +EDGE2 4924 4905 0.96475 -0.0578739 -0.00140791 1 0 1 1 0 0 +EDGE2 4924 4923 -1.02268 0.0929153 -0.0447334 1 0 1 1 0 0 +EDGE2 4924 4904 -0.0432513 -0.0274535 -0.00890581 1 0 1 1 0 0 +EDGE2 4924 4903 -0.901791 -0.0194677 0.025792 1 0 1 1 0 0 +EDGE2 4925 4905 -0.001167 0.0134993 -0.0025823 1 0 1 1 0 0 +EDGE2 4925 4906 -0.0859248 1.02545 1.56595 1 0 1 1 0 0 +EDGE2 4925 4924 -0.962986 0.0149328 -0.0158077 1 0 1 1 0 0 +EDGE2 4925 4904 -0.999155 -0.0256048 -0.0145533 1 0 1 1 0 0 +EDGE2 4926 4905 -0.938264 -0.00374208 -1.5706 1 0 1 1 0 0 +EDGE2 4926 4906 -0.0480859 0.0534533 -0.00996016 1 0 1 1 0 0 +EDGE2 4926 4907 0.960709 0.0124028 -0.00701107 1 0 1 1 0 0 +EDGE2 4926 4925 -0.935031 0.00287409 -1.56956 1 0 1 1 0 0 +EDGE2 4927 4908 1.01282 0.00447689 0.0318499 1 0 1 1 0 0 +EDGE2 4927 4906 -1.01316 -0.0615721 -0.00334158 1 0 1 1 0 0 +EDGE2 4927 4926 -0.964769 0.00551491 -0.00704712 1 0 1 1 0 0 +EDGE2 4927 4907 0.0957515 0.0777898 -0.0168723 1 0 1 1 0 0 +EDGE2 4928 4927 -0.989396 0.00665783 0.0194166 1 0 1 1 0 0 +EDGE2 4928 4909 1.08663 -0.0107533 -0.0242994 1 0 1 1 0 0 +EDGE2 4928 4908 0.00576815 0.00780445 0.00407627 1 0 1 1 0 0 +EDGE2 4928 4907 -0.955503 -0.0564906 0.0327027 1 0 1 1 0 0 +EDGE2 4929 4890 0.979245 0.0957527 -3.13067 1 0 1 1 0 0 +EDGE2 4929 4910 0.929287 -0.0134155 -0.0232163 1 0 1 1 0 0 +EDGE2 4929 4928 -0.989978 0.00842105 0.018315 1 0 1 1 0 0 +EDGE2 4929 4909 -0.02056 -0.0691853 -0.00448916 1 0 1 1 0 0 +EDGE2 4929 4908 -0.962833 -0.0520534 0.0297619 1 0 1 1 0 0 +EDGE2 4930 4890 -0.0704783 -0.0603969 -3.1243 1 0 1 1 0 0 +EDGE2 4930 4889 1.02705 -0.0453281 -3.12271 1 0 1 1 0 0 +EDGE2 4930 4910 0.0452123 0.0443753 -0.0206082 1 0 1 1 0 0 +EDGE2 4930 4891 -0.0278023 1.03397 1.57058 1 0 1 1 0 0 +EDGE2 4930 4911 -0.0634297 1.03221 1.57317 1 0 1 1 0 0 +EDGE2 4930 4909 -0.941835 -0.00719328 -0.0109516 1 0 1 1 0 0 +EDGE2 4930 4929 -0.969315 -0.0371629 -0.0110744 1 0 1 1 0 0 +EDGE2 4931 4890 -0.970254 -0.0174333 1.54461 1 0 1 1 0 0 +EDGE2 4931 4930 -1.0014 -0.0340014 -1.6021 1 0 1 1 0 0 +EDGE2 4931 4910 -0.976972 -0.0319758 -1.58211 1 0 1 1 0 0 +EDGE2 4931 4912 1.05337 -0.00488674 -0.0159999 1 0 1 1 0 0 +EDGE2 4931 4891 0.010568 0.000947398 0.0210015 1 0 1 1 0 0 +EDGE2 4931 4911 0.0157991 -0.0695712 -0.0145224 1 0 1 1 0 0 +EDGE2 4931 4892 0.985002 -0.0196298 -0.0583345 1 0 1 1 0 0 +EDGE2 4932 4912 -0.0757775 -0.131178 -0.0250583 1 0 1 1 0 0 +EDGE2 4932 4891 -0.991784 0.00865865 -0.0346964 1 0 1 1 0 0 +EDGE2 4932 4911 -1.01452 0.00416996 -0.0131032 1 0 1 1 0 0 +EDGE2 4932 4931 -1.0382 0.0319623 0.028227 1 0 1 1 0 0 +EDGE2 4932 4913 0.94793 -0.0490686 0.0144052 1 0 1 1 0 0 +EDGE2 4932 4892 0.0286656 0.0518962 0.00704044 1 0 1 1 0 0 +EDGE2 4932 4893 0.993773 0.08216 -0.0100992 1 0 1 1 0 0 +EDGE2 4933 4912 -0.899155 0.0476444 0.0243363 1 0 1 1 0 0 +EDGE2 4933 4932 -1.00873 -0.0311881 0.0075686 1 0 1 1 0 0 +EDGE2 4933 4913 0.0231222 0.0221665 0.0151605 1 0 1 1 0 0 +EDGE2 4933 4892 -0.95156 0.0374932 0.0241807 1 0 1 1 0 0 +EDGE2 4933 4893 -0.0421525 -0.041663 0.00540472 1 0 1 1 0 0 +EDGE2 4933 4894 1.0448 0.0480917 -0.00582346 1 0 1 1 0 0 +EDGE2 4933 4914 0.92792 -0.048553 -0.00702735 1 0 1 1 0 0 +EDGE2 4934 4913 -1.048 -0.0438417 0.00572277 1 0 1 1 0 0 +EDGE2 4934 4933 -1.06742 0.0170368 -0.0334274 1 0 1 1 0 0 +EDGE2 4934 4893 -0.994318 -0.00742265 0.0162364 1 0 1 1 0 0 +EDGE2 4934 4894 0.099659 -0.0128144 0.0215272 1 0 1 1 0 0 +EDGE2 4934 4914 -0.0256765 0.00430689 0.0149173 1 0 1 1 0 0 +EDGE2 4934 4555 0.878088 0.047502 -3.13584 1 0 1 1 0 0 +EDGE2 4934 4895 1.07871 0.0298365 0.0210887 1 0 1 1 0 0 +EDGE2 4934 4915 1.0503 0.0152655 -0.00964921 1 0 1 1 0 0 +EDGE2 4935 4934 -1.05832 0.0573384 -0.0094049 1 0 1 1 0 0 +EDGE2 4935 4894 -0.995814 0.00345221 0.00670598 1 0 1 1 0 0 +EDGE2 4935 4914 -1.0011 -0.0123164 0.000384626 1 0 1 1 0 0 +EDGE2 4935 4916 -0.0588644 0.965843 1.60442 1 0 1 1 0 0 +EDGE2 4935 4556 0.00809691 -1.14465 -1.58097 1 0 1 1 0 0 +EDGE2 4935 4555 -0.0196404 0.0261547 -3.14705 1 0 1 1 0 0 +EDGE2 4935 4895 0.0444928 -0.142195 0.00767506 1 0 1 1 0 0 +EDGE2 4935 4915 0.044636 -0.0599657 0.00689297 1 0 1 1 0 0 +EDGE2 4935 4554 1.04136 0.00312835 -3.13942 1 0 1 1 0 0 +EDGE2 4935 4896 -0.00161261 1.0546 1.56436 1 0 1 1 0 0 +EDGE2 4936 4935 -0.986699 -0.100905 1.56544 1 0 1 1 0 0 +EDGE2 4936 4557 1.00242 -0.0840634 0.0130418 1 0 1 1 0 0 +EDGE2 4936 4556 -0.101102 0.008597 -0.0160813 1 0 1 1 0 0 +EDGE2 4936 4555 -0.978184 0.0329181 -1.57266 1 0 1 1 0 0 +EDGE2 4936 4895 -1.01735 0.0127073 1.58903 1 0 1 1 0 0 +EDGE2 4936 4915 -1.06531 -0.0380199 1.59576 1 0 1 1 0 0 +EDGE2 4937 4558 1.07197 -0.0302853 -0.0087892 1 0 1 1 0 0 +EDGE2 4937 4936 -0.997438 0.0163433 -0.022917 1 0 1 1 0 0 +EDGE2 4937 4557 -0.0229875 0.0867822 0.0245102 1 0 1 1 0 0 +EDGE2 4937 4556 -1.01611 -0.0724675 0.00177188 1 0 1 1 0 0 +EDGE2 4938 4558 0.0371203 0.0185732 -0.0243275 1 0 1 1 0 0 +EDGE2 4938 4559 0.9802 0.00873703 0.000787298 1 0 1 1 0 0 +EDGE2 4938 4557 -1.0091 -0.0347334 0.00791238 1 0 1 1 0 0 +EDGE2 4938 4937 -0.9221 -0.0638293 0.0146851 1 0 1 1 0 0 +EDGE2 4939 4558 -1.01765 0.075501 -0.0128911 1 0 1 1 0 0 +EDGE2 4939 4559 0.0254892 -0.0255316 0.0356061 1 0 1 1 0 0 +EDGE2 4939 4560 0.960312 0.0333551 -0.0241172 1 0 1 1 0 0 +EDGE2 4939 4938 -1.08137 -0.11586 0.026344 1 0 1 1 0 0 +EDGE2 4940 4561 -0.0466448 -1.03606 -1.58096 1 0 1 1 0 0 +EDGE2 4940 4559 -1.05181 -0.0913266 -0.00611614 1 0 1 1 0 0 +EDGE2 4940 4939 -1.09872 0.00808491 -0.00783045 1 0 1 1 0 0 +EDGE2 4940 4560 0.0249319 -0.0153653 -0.0106074 1 0 1 1 0 0 +EDGE2 4941 4562 1.02785 0.0121903 0.00449124 1 0 1 1 0 0 +EDGE2 4941 4561 0.0910258 0.0217297 -0.0108173 1 0 1 1 0 0 +EDGE2 4941 4940 -1.0488 0.0483932 1.55925 1 0 1 1 0 0 +EDGE2 4941 4560 -1.10734 0.0241599 1.57589 1 0 1 1 0 0 +EDGE2 4942 4563 1.03465 0.0951563 0.0116267 1 0 1 1 0 0 +EDGE2 4942 4941 -0.951288 -0.070997 0.037646 1 0 1 1 0 0 +EDGE2 4942 4562 0.0226841 0.0725917 0.0352876 1 0 1 1 0 0 +EDGE2 4942 4561 -0.991927 -0.00407685 -0.00645249 1 0 1 1 0 0 +EDGE2 4943 4942 -1.02894 0.0630756 0.0330689 1 0 1 1 0 0 +EDGE2 4943 4564 1.02747 -0.0543602 -0.0332049 1 0 1 1 0 0 +EDGE2 4943 4563 -0.104547 0.00198976 -0.0204268 1 0 1 1 0 0 +EDGE2 4943 4562 -1.00562 -0.00584494 0.0266781 1 0 1 1 0 0 +EDGE2 4944 4565 0.964835 0.0410308 0.0274371 1 0 1 1 0 0 +EDGE2 4944 4885 1.09901 0.0232252 -3.15472 1 0 1 1 0 0 +EDGE2 4944 3625 0.99725 0.0531286 -3.13751 1 0 1 1 0 0 +EDGE2 4944 4943 -1.06551 -0.037016 0.0123385 1 0 1 1 0 0 +EDGE2 4944 4564 -0.0448491 -0.0535159 -0.0207503 1 0 1 1 0 0 +EDGE2 4944 4563 -0.921859 -0.032461 0.0140025 1 0 1 1 0 0 +EDGE2 4945 4884 1.06152 -0.033448 -3.13343 1 0 1 1 0 0 +EDGE2 4945 4566 0.0505926 1.01116 1.57783 1 0 1 1 0 0 +EDGE2 4945 3626 -0.0108255 0.99433 1.57591 1 0 1 1 0 0 +EDGE2 4945 4565 0.0139653 0.0104956 -0.0165513 1 0 1 1 0 0 +EDGE2 4945 3624 1.03559 -0.000312513 -3.13538 1 0 1 1 0 0 +EDGE2 4945 4885 -0.0318149 -0.0675342 -3.16608 1 0 1 1 0 0 +EDGE2 4945 4886 0.0335504 -0.994672 -1.56427 1 0 1 1 0 0 +EDGE2 4945 3625 0.038372 -0.0601595 -3.15097 1 0 1 1 0 0 +EDGE2 4945 4564 -0.957578 -0.0748739 -0.00358567 1 0 1 1 0 0 +EDGE2 4945 4944 -0.912472 -0.0139178 0.00523538 1 0 1 1 0 0 +EDGE2 4946 4887 1.01107 -0.0129253 0.0214932 1 0 1 1 0 0 +EDGE2 4946 4565 -1.03782 -0.00705571 1.61164 1 0 1 1 0 0 +EDGE2 4946 4945 -1.02327 0.0284616 1.57405 1 0 1 1 0 0 +EDGE2 4946 4885 -1.02286 0.057866 -1.56318 1 0 1 1 0 0 +EDGE2 4946 4886 0.00405625 0.0654426 0.0177188 1 0 1 1 0 0 +EDGE2 4946 3625 -0.995209 -0.0648075 -1.56536 1 0 1 1 0 0 +EDGE2 4947 4887 0.0409766 0.0398049 0.00796646 1 0 1 1 0 0 +EDGE2 4947 4886 -0.953194 -0.0385339 -0.0135412 1 0 1 1 0 0 +EDGE2 4947 4946 -1.05257 0.0153947 -0.0134536 1 0 1 1 0 0 +EDGE2 4947 4888 1.0121 0.0321186 -0.00187047 1 0 1 1 0 0 +EDGE2 4948 4887 -0.964829 -0.0230072 0.0239044 1 0 1 1 0 0 +EDGE2 4948 4947 -0.93857 -0.0142781 0.0260118 1 0 1 1 0 0 +EDGE2 4948 4889 0.974585 -0.00470302 -0.0104512 1 0 1 1 0 0 +EDGE2 4948 4888 -0.0125873 -0.00826713 -0.0277097 1 0 1 1 0 0 +EDGE2 4949 4948 -1.00433 0.107262 -0.00138026 1 0 1 1 0 0 +EDGE2 4949 4890 1.03687 0.0116863 -0.0118515 1 0 1 1 0 0 +EDGE2 4949 4889 0.0381299 0.0232477 -0.0291844 1 0 1 1 0 0 +EDGE2 4949 4888 -0.950366 0.00257688 -0.0134011 1 0 1 1 0 0 +EDGE2 4949 4930 1.01339 -0.0457417 -3.14357 1 0 1 1 0 0 +EDGE2 4949 4910 1.0695 0.0261264 -3.14367 1 0 1 1 0 0 +EDGE2 4950 4890 0.0176293 -0.0455783 0.0530608 1 0 1 1 0 0 +EDGE2 4950 4889 -1.02722 0.0359081 -0.0115681 1 0 1 1 0 0 +EDGE2 4950 4949 -1.00459 -0.0266109 0.0183106 1 0 1 1 0 0 +EDGE2 4950 4930 0.0305035 0.0191562 -3.14183 1 0 1 1 0 0 +EDGE2 4950 4910 -0.116996 -0.0146739 -3.13233 1 0 1 1 0 0 +EDGE2 4950 4891 0.107159 -1.10754 -1.60153 1 0 1 1 0 0 +EDGE2 4950 4911 0.0200855 -0.91341 -1.55627 1 0 1 1 0 0 +EDGE2 4950 4931 -0.149568 -0.957846 -1.57254 1 0 1 1 0 0 +EDGE2 4950 4909 1.02933 0.0176294 -3.16349 1 0 1 1 0 0 +EDGE2 4950 4929 0.999901 -0.0377165 -3.157 1 0 1 1 0 0 +EDGE2 4951 4890 -0.945465 -0.025053 -1.55974 1 0 1 1 0 0 +EDGE2 4951 4930 -0.996648 0.0482117 1.57025 1 0 1 1 0 0 +EDGE2 4951 4950 -1.07368 0.0114948 -1.57613 1 0 1 1 0 0 +EDGE2 4951 4910 -0.949924 -0.0331387 1.59369 1 0 1 1 0 0 +EDGE2 4952 4951 -0.978047 0.0031698 -0.0275855 1 0 1 1 0 0 +EDGE2 4953 4952 -0.990612 0.0638387 0.00714578 1 0 1 1 0 0 +EDGE2 4954 4953 -1.0061 -0.0181476 0.0126886 1 0 1 1 0 0 +EDGE2 4955 4954 -0.998945 -0.00351732 -0.0284709 1 0 1 1 0 0 +EDGE2 4956 4955 -1.03022 0.0381692 -1.60659 1 0 1 1 0 0 +EDGE2 4957 4956 -0.954693 -0.0628401 0.0261163 1 0 1 1 0 0 +EDGE2 4958 4957 -1.11177 0.0444216 -0.00974177 1 0 1 1 0 0 +EDGE2 4959 4880 0.999061 0.0897915 -3.126 1 0 1 1 0 0 +EDGE2 4959 3620 1.00302 0.017552 -3.13946 1 0 1 1 0 0 +EDGE2 4959 4958 -0.956124 -0.00733337 -0.00288018 1 0 1 1 0 0 +EDGE2 4960 3619 1.05495 -0.0358626 -3.14407 1 0 1 1 0 0 +EDGE2 4960 4879 0.904618 -0.0519703 -3.11173 1 0 1 1 0 0 +EDGE2 4960 4959 -0.978192 0.0547148 -0.0406945 1 0 1 1 0 0 +EDGE2 4960 4880 0.0477961 0.064351 -3.17538 1 0 1 1 0 0 +EDGE2 4960 3620 0.038257 0.0248913 -3.15244 1 0 1 1 0 0 +EDGE2 4960 3621 0.0977789 0.957478 1.56443 1 0 1 1 0 0 +EDGE2 4960 4881 0.0844455 0.956527 1.58615 1 0 1 1 0 0 +EDGE2 4961 4880 -1.07256 0.00974833 1.58122 1 0 1 1 0 0 +EDGE2 4961 4960 -1.05418 -0.0636587 -1.57876 1 0 1 1 0 0 +EDGE2 4961 3620 -0.965342 0.0176225 1.55258 1 0 1 1 0 0 +EDGE2 4961 3621 -0.0520457 0.0423909 0.00541907 1 0 1 1 0 0 +EDGE2 4961 4881 -0.0693021 0.0446904 0.000132831 1 0 1 1 0 0 +EDGE2 4961 3622 1.02918 0.0415242 -0.0122082 1 0 1 1 0 0 +EDGE2 4961 4882 1.02261 -0.037447 0.00108042 1 0 1 1 0 0 +EDGE2 4962 3621 -1.02815 0.0303277 -0.00617718 1 0 1 1 0 0 +EDGE2 4962 4881 -1.05994 -0.053491 0.00164906 1 0 1 1 0 0 +EDGE2 4962 4961 -0.996367 -0.0917863 0.00869174 1 0 1 1 0 0 +EDGE2 4962 3622 0.0209103 -0.0802031 0.0054928 1 0 1 1 0 0 +EDGE2 4962 4882 -0.00607043 0.0564104 -0.00679997 1 0 1 1 0 0 +EDGE2 4962 3623 0.984457 0.0410419 -0.0331345 1 0 1 1 0 0 +EDGE2 4962 4883 1.03554 -0.0633127 0.00240581 1 0 1 1 0 0 +EDGE2 4963 4884 0.943909 -0.0881536 0.0144303 1 0 1 1 0 0 +EDGE2 4963 3622 -1.00527 0.0936917 0.0160921 1 0 1 1 0 0 +EDGE2 4963 4962 -0.969974 0.00821494 -0.0106762 1 0 1 1 0 0 +EDGE2 4963 4882 -0.899453 -0.100312 -0.0163309 1 0 1 1 0 0 +EDGE2 4963 3623 -0.0478214 0.0253749 0.00256096 1 0 1 1 0 0 +EDGE2 4963 4883 0.126224 0.0204772 0.0124428 1 0 1 1 0 0 +EDGE2 4963 3624 0.970445 -0.0085342 -0.0073161 1 0 1 1 0 0 +EDGE2 4964 4884 0.0272372 -0.11778 0.0174377 1 0 1 1 0 0 +EDGE2 4964 3623 -1.00679 0.0323506 -0.0250089 1 0 1 1 0 0 +EDGE2 4964 4883 -0.967654 0.0580225 -0.00282534 1 0 1 1 0 0 +EDGE2 4964 4963 -1.0377 -0.111019 0.011296 1 0 1 1 0 0 +EDGE2 4964 4565 1.01164 0.00303659 -3.17389 1 0 1 1 0 0 +EDGE2 4964 4945 1.08426 -0.0342625 -3.15858 1 0 1 1 0 0 +EDGE2 4964 3624 -0.0316881 0.0424338 0.00152664 1 0 1 1 0 0 +EDGE2 4964 4885 0.942325 -0.0307793 -0.038808 1 0 1 1 0 0 +EDGE2 4964 3625 1.05845 -0.0589893 0.00926174 1 0 1 1 0 0 +EDGE2 4965 4884 -0.983029 0.0642963 -0.00433267 1 0 1 1 0 0 +EDGE2 4965 4964 -1.08192 0.0148857 0.00268528 1 0 1 1 0 0 +EDGE2 4965 4566 0.0299275 -0.994963 -1.54073 1 0 1 1 0 0 +EDGE2 4965 3626 -0.0534923 -0.980265 -1.5785 1 0 1 1 0 0 +EDGE2 4965 4565 -0.0122689 0.0380116 -3.16755 1 0 1 1 0 0 +EDGE2 4965 4945 -0.0719678 -0.0502081 -3.13458 1 0 1 1 0 0 +EDGE2 4965 3624 -0.994403 -0.0140112 0.0111096 1 0 1 1 0 0 +EDGE2 4965 4885 0.0879728 -0.0469558 0.0161493 1 0 1 1 0 0 +EDGE2 4965 4886 0.100059 1.05401 1.54422 1 0 1 1 0 0 +EDGE2 4965 4946 0.0304824 1.02999 1.5369 1 0 1 1 0 0 +EDGE2 4965 3625 -0.0292133 0.0841425 0.00331287 1 0 1 1 0 0 +EDGE2 4965 4564 1.01898 -0.0113783 -3.17117 1 0 1 1 0 0 +EDGE2 4965 4944 0.958736 0.0303029 -3.12998 1 0 1 1 0 0 +EDGE2 4966 4567 1.02566 -0.0674518 -0.0154406 1 0 1 1 0 0 +EDGE2 4966 4566 -0.0013169 -0.0280206 0.00050735 1 0 1 1 0 0 +EDGE2 4966 3627 0.989167 -0.0167482 0.00854894 1 0 1 1 0 0 +EDGE2 4966 3626 -0.022451 -0.0545988 0.00312372 1 0 1 1 0 0 +EDGE2 4966 4565 -1.03507 0.0236098 -1.57299 1 0 1 1 0 0 +EDGE2 4966 4945 -1.00088 0.0165619 -1.56063 1 0 1 1 0 0 +EDGE2 4966 4965 -1.01535 -0.0225578 1.57047 1 0 1 1 0 0 +EDGE2 4966 4885 -1.02178 -0.011063 1.60369 1 0 1 1 0 0 +EDGE2 4966 3625 -1.07324 0.0779789 1.56446 1 0 1 1 0 0 +EDGE2 4967 4567 -0.0389593 0.0373782 -0.0140704 1 0 1 1 0 0 +EDGE2 4967 3628 1.13991 0.0592436 0.00473888 1 0 1 1 0 0 +EDGE2 4967 4568 0.925791 0.0199542 0.0108224 1 0 1 1 0 0 +EDGE2 4967 4566 -1.01251 0.0106211 -0.0028052 1 0 1 1 0 0 +EDGE2 4967 4966 -1.02433 -0.0720275 -0.0137794 1 0 1 1 0 0 +EDGE2 4967 3627 -0.0319646 0.0673114 -0.0111377 1 0 1 1 0 0 +EDGE2 4967 3626 -1.00302 0.0597078 -0.0222271 1 0 1 1 0 0 +EDGE2 4968 3629 0.974563 0.0373408 -0.00907147 1 0 1 1 0 0 +EDGE2 4968 4569 0.937778 0.00199868 -0.000343259 1 0 1 1 0 0 +EDGE2 4968 4567 -0.984208 0.0130808 0.0085706 1 0 1 1 0 0 +EDGE2 4968 3628 0.00931623 0.00199209 -0.00111007 1 0 1 1 0 0 +EDGE2 4968 4568 0.041401 0.0368097 0.0198051 1 0 1 1 0 0 +EDGE2 4968 4967 -1.08119 0.0743409 0.0015572 1 0 1 1 0 0 +EDGE2 4968 3627 -0.919284 -0.0804011 -0.0127234 1 0 1 1 0 0 +EDGE2 4969 4570 1.01482 0.153406 0.0070328 1 0 1 1 0 0 +EDGE2 4969 4690 0.963119 -0.062454 -3.12916 1 0 1 1 0 0 +EDGE2 4969 4670 1.04878 0.0492314 -3.18156 1 0 1 1 0 0 +EDGE2 4969 3610 0.900862 0.0160838 -3.13398 1 0 1 1 0 0 +EDGE2 4969 3630 0.966276 -0.0246134 -0.00209935 1 0 1 1 0 0 +EDGE2 4969 3629 -0.0601316 -0.034073 -0.0140381 1 0 1 1 0 0 +EDGE2 4969 4569 0.0913168 0.0153503 -0.00328504 1 0 1 1 0 0 +EDGE2 4969 3628 -1.01101 -0.0257416 0.0260899 1 0 1 1 0 0 +EDGE2 4969 4568 -0.963179 -0.0183047 -0.0121224 1 0 1 1 0 0 +EDGE2 4969 4968 -1.05891 0.0869456 0.0147289 1 0 1 1 0 0 +EDGE2 4970 3609 0.99229 -0.0395596 -3.14589 1 0 1 1 0 0 +EDGE2 4970 4669 1.00167 0.0940858 -3.10918 1 0 1 1 0 0 +EDGE2 4970 4689 0.959921 0.0139998 -3.16838 1 0 1 1 0 0 +EDGE2 4970 4571 -0.0874348 -0.927422 -1.58771 1 0 1 1 0 0 +EDGE2 4970 4671 0.0370443 -1.03875 -1.54323 1 0 1 1 0 0 +EDGE2 4970 4691 -0.0387265 -1.00739 -1.56888 1 0 1 1 0 0 +EDGE2 4970 3611 -0.0680085 -1.04192 -1.5449 1 0 1 1 0 0 +EDGE2 4970 4570 0.0293429 0.071881 -0.0133637 1 0 1 1 0 0 +EDGE2 4970 4690 0.0640439 -0.0744113 -3.12755 1 0 1 1 0 0 +EDGE2 4970 4670 0.0921353 -0.000687506 -3.14161 1 0 1 1 0 0 +EDGE2 4970 3610 -0.0428572 0.00530935 -3.16471 1 0 1 1 0 0 +EDGE2 4970 3630 0.000746537 -0.131063 0.0138724 1 0 1 1 0 0 +EDGE2 4970 3631 -0.00589152 0.998109 1.53617 1 0 1 1 0 0 +EDGE2 4970 3629 -1.06532 0.016295 0.00735301 1 0 1 1 0 0 +EDGE2 4970 4569 -0.96004 -0.0670864 -0.0167456 1 0 1 1 0 0 +EDGE2 4970 4969 -0.959847 0.0626944 0.0124404 1 0 1 1 0 0 +EDGE2 4971 4672 0.953308 -0.0635566 -0.0107789 1 0 1 1 0 0 +EDGE2 4971 4692 0.949121 -0.0194685 -0.0115649 1 0 1 1 0 0 +EDGE2 4971 3612 1.09042 0.0573054 0.0105854 1 0 1 1 0 0 +EDGE2 4971 4572 0.954707 -0.0130885 -0.0287737 1 0 1 1 0 0 +EDGE2 4971 4571 -0.0103412 -0.0188086 0.023129 1 0 1 1 0 0 +EDGE2 4971 4671 0.0332772 0.046273 0.0207075 1 0 1 1 0 0 +EDGE2 4971 4691 -0.000819833 0.0143989 0.0286417 1 0 1 1 0 0 +EDGE2 4971 3611 0.0587337 -0.0333304 0.0248506 1 0 1 1 0 0 +EDGE2 4971 4570 -1.02569 0.0224766 1.59358 1 0 1 1 0 0 +EDGE2 4971 4690 -0.999535 -0.0369307 -1.56919 1 0 1 1 0 0 +EDGE2 4971 4970 -1.03267 0.028732 1.60651 1 0 1 1 0 0 +EDGE2 4971 4670 -1.03921 -0.0302783 -1.58699 1 0 1 1 0 0 +EDGE2 4971 3610 -0.95804 -0.0274187 -1.52567 1 0 1 1 0 0 +EDGE2 4971 3630 -1.03249 0.0389939 1.58007 1 0 1 1 0 0 +EDGE2 4972 4672 -0.0400247 -0.00472694 0.00155041 1 0 1 1 0 0 +EDGE2 4972 4673 1.02778 0.0286643 1.41265e-05 1 0 1 1 0 0 +EDGE2 4972 4693 1.04074 -0.0276562 0.0147416 1 0 1 1 0 0 +EDGE2 4972 3613 1.02626 -0.0478122 0.0323932 1 0 1 1 0 0 +EDGE2 4972 4573 0.981983 -0.117056 0.011765 1 0 1 1 0 0 +EDGE2 4972 4692 -0.0250029 0.0226584 0.00894305 1 0 1 1 0 0 +EDGE2 4972 4971 -0.989935 -0.0283938 -0.0238243 1 0 1 1 0 0 +EDGE2 4972 3612 -0.0345176 -0.0164658 -0.000134351 1 0 1 1 0 0 +EDGE2 4972 4572 0.0258783 0.084078 0.032973 1 0 1 1 0 0 +EDGE2 4972 4571 -1.05018 0.022948 -0.0186511 1 0 1 1 0 0 +EDGE2 4972 4671 -0.896451 -0.00756493 -0.00971285 1 0 1 1 0 0 +EDGE2 4972 4691 -1.02107 -0.0667377 -0.0125123 1 0 1 1 0 0 +EDGE2 4972 3611 -0.986669 -0.00681525 0.0155376 1 0 1 1 0 0 +EDGE2 4973 4574 0.996271 0.0202364 0.0085786 1 0 1 1 0 0 +EDGE2 4973 4674 1.01721 -0.0642928 -0.0152634 1 0 1 1 0 0 +EDGE2 4973 4694 1.02942 -0.0342806 -0.0123198 1 0 1 1 0 0 +EDGE2 4973 3614 1.06209 -0.0162477 0.0214658 1 0 1 1 0 0 +EDGE2 4973 4672 -1.07552 0.0181814 -0.0035381 1 0 1 1 0 0 +EDGE2 4973 4972 -1.06785 -0.065913 0.0217416 1 0 1 1 0 0 +EDGE2 4973 4673 -0.0691576 -0.0708306 -0.00840798 1 0 1 1 0 0 +EDGE2 4973 4693 -0.0191323 -0.00967235 -0.0286743 1 0 1 1 0 0 +EDGE2 4973 3613 0.017299 0.0295186 0.0147909 1 0 1 1 0 0 +EDGE2 4973 4573 0.003593 0.053235 0.0105437 1 0 1 1 0 0 +EDGE2 4973 4692 -0.959854 0.0822103 -0.00912081 1 0 1 1 0 0 +EDGE2 4973 3612 -0.866442 0.00301158 0.0125307 1 0 1 1 0 0 +EDGE2 4973 4572 -0.999192 -0.00892554 0.0207997 1 0 1 1 0 0 +EDGE2 4974 4575 0.965188 -0.0003794 -0.0295798 1 0 1 1 0 0 +EDGE2 4974 4695 1.00815 -0.0181936 -0.0191059 1 0 1 1 0 0 +EDGE2 4974 4875 1.02909 0.110008 -3.10855 1 0 1 1 0 0 +EDGE2 4974 4675 0.982908 0.0278132 0.0289434 1 0 1 1 0 0 +EDGE2 4974 3615 0.993851 0.000793431 0.00101418 1 0 1 1 0 0 +EDGE2 4974 4574 0.0601535 0.00328796 -0.00365862 1 0 1 1 0 0 +EDGE2 4974 4674 -0.0012885 -0.052815 0.0258841 1 0 1 1 0 0 +EDGE2 4974 4694 0.0139365 0.0317674 0.0138222 1 0 1 1 0 0 +EDGE2 4974 3614 -0.0144071 -0.0199819 0.00274351 1 0 1 1 0 0 +EDGE2 4974 4673 -1.02485 -0.023569 0.0221273 1 0 1 1 0 0 +EDGE2 4974 4973 -1.0269 -0.03701 -0.00664205 1 0 1 1 0 0 +EDGE2 4974 4693 -0.986631 0.0839764 -0.000950115 1 0 1 1 0 0 +EDGE2 4974 3613 -0.946558 -0.0583331 0.00754365 1 0 1 1 0 0 +EDGE2 4974 4573 -0.928217 -0.0234815 -0.00804969 1 0 1 1 0 0 +EDGE2 4975 4676 0.0334034 0.969004 1.58389 1 0 1 1 0 0 +EDGE2 4975 4696 -0.00108562 0.893217 1.56968 1 0 1 1 0 0 +EDGE2 4975 4576 0.0639383 0.961243 1.5355 1 0 1 1 0 0 +EDGE2 4975 4974 -0.959035 0.0135839 -0.00169515 1 0 1 1 0 0 +EDGE2 4975 4874 0.943439 0.0288717 -3.10804 1 0 1 1 0 0 +EDGE2 4975 4575 -0.0179165 -0.0109902 -0.0128804 1 0 1 1 0 0 +EDGE2 4975 4695 -0.0846553 0.0010406 0.000492163 1 0 1 1 0 0 +EDGE2 4975 4875 -0.0143471 -0.0322361 -3.13054 1 0 1 1 0 0 +EDGE2 4975 4675 0.00436557 -0.0527107 -0.00602893 1 0 1 1 0 0 +EDGE2 4975 3615 -0.0598366 0.0046097 0.0088412 1 0 1 1 0 0 +EDGE2 4975 4876 0.0676229 -1.00895 -1.60332 1 0 1 1 0 0 +EDGE2 4975 3616 0.0042146 -0.975375 -1.53673 1 0 1 1 0 0 +EDGE2 4975 4574 -0.949765 -0.00240485 -0.0227194 1 0 1 1 0 0 +EDGE2 4975 4674 -0.997818 -0.0229463 -0.0121448 1 0 1 1 0 0 +EDGE2 4975 4694 -0.980963 0.0341888 0.0128745 1 0 1 1 0 0 +EDGE2 4975 3614 -1.04389 -0.0626323 0.0236609 1 0 1 1 0 0 +EDGE2 4976 4577 1.03807 0.0432048 0.00588976 1 0 1 1 0 0 +EDGE2 4976 4677 0.992298 -0.0708306 -0.0138183 1 0 1 1 0 0 +EDGE2 4976 4697 0.927163 0.0562285 -0.0323279 1 0 1 1 0 0 +EDGE2 4976 4676 0.170824 0.00790814 0.000871054 1 0 1 1 0 0 +EDGE2 4976 4696 -0.0214553 -0.0339638 0.0346107 1 0 1 1 0 0 +EDGE2 4976 4576 -0.00186481 -0.029139 -0.0131291 1 0 1 1 0 0 +EDGE2 4976 4575 -1.01625 -0.0585654 -1.59425 1 0 1 1 0 0 +EDGE2 4976 4695 -1.00724 0.0579552 -1.52896 1 0 1 1 0 0 +EDGE2 4976 4875 -1.00696 0.0312516 1.55196 1 0 1 1 0 0 +EDGE2 4976 4975 -0.975979 -0.00121401 -1.5764 1 0 1 1 0 0 +EDGE2 4976 4675 -0.97804 -0.00337566 -1.58644 1 0 1 1 0 0 +EDGE2 4976 3615 -0.98162 -0.0633076 -1.57399 1 0 1 1 0 0 +EDGE2 4977 4678 1.08912 -0.0163924 0.00935904 1 0 1 1 0 0 +EDGE2 4977 4698 0.919421 0.0418677 0.0360207 1 0 1 1 0 0 +EDGE2 4977 4578 0.99348 0.0138223 0.00129621 1 0 1 1 0 0 +EDGE2 4977 4976 -1.1402 -0.0553233 0.0408255 1 0 1 1 0 0 +EDGE2 4977 4577 -0.0181278 -0.102854 0.0450813 1 0 1 1 0 0 +EDGE2 4977 4677 -0.040818 -0.0519769 -0.022307 1 0 1 1 0 0 +EDGE2 4977 4697 -0.00825037 0.0150652 -0.0216502 1 0 1 1 0 0 +EDGE2 4977 4676 -1.00909 0.0317062 -0.0138058 1 0 1 1 0 0 +EDGE2 4977 4696 -0.957354 -0.0348587 0.00713764 1 0 1 1 0 0 +EDGE2 4977 4576 -1.00012 0.00942345 -0.000761402 1 0 1 1 0 0 +EDGE2 4978 4679 1.00701 0.0050226 0.0186121 1 0 1 1 0 0 +EDGE2 4978 4699 1.04227 0.0481039 0.0220701 1 0 1 1 0 0 +EDGE2 4978 4579 1.03725 0.0043957 -0.0349674 1 0 1 1 0 0 +EDGE2 4978 4678 0.0299688 0.0133061 0.0395519 1 0 1 1 0 0 +EDGE2 4978 4698 0.021471 -0.0268768 -0.0136325 1 0 1 1 0 0 +EDGE2 4978 4578 -0.128732 -0.0317848 0.0305929 1 0 1 1 0 0 +EDGE2 4978 4977 -0.996505 -0.00144983 0.0228816 1 0 1 1 0 0 +EDGE2 4978 4577 -0.992888 0.00577023 -0.00816895 1 0 1 1 0 0 +EDGE2 4978 4677 -1.00758 0.00350203 -0.0100481 1 0 1 1 0 0 +EDGE2 4978 4697 -1.00762 -0.00222737 -0.0141485 1 0 1 1 0 0 +EDGE2 4979 4820 1.01591 0.10655 -3.11445 1 0 1 1 0 0 +EDGE2 4979 4840 0.95675 0.0173729 -3.18409 1 0 1 1 0 0 +EDGE2 4979 4580 0.961849 -0.0547658 -0.013741 1 0 1 1 0 0 +EDGE2 4979 4680 0.99416 0.0118866 0.00862068 1 0 1 1 0 0 +EDGE2 4979 4700 0.979521 0.00961149 -0.0506819 1 0 1 1 0 0 +EDGE2 4979 4679 0.00850677 0.0333407 0.0128593 1 0 1 1 0 0 +EDGE2 4979 4699 0.0106291 -0.0593651 -0.0156243 1 0 1 1 0 0 +EDGE2 4979 4579 0.031526 0.0401908 -0.0082867 1 0 1 1 0 0 +EDGE2 4979 4678 -1.13341 0.0485667 0.0206762 1 0 1 1 0 0 +EDGE2 4979 4698 -0.930649 -0.0180867 0.00467754 1 0 1 1 0 0 +EDGE2 4979 4978 -1.06827 -0.0837101 0.0262004 1 0 1 1 0 0 +EDGE2 4979 4578 -1.05991 -0.0860573 -0.0314609 1 0 1 1 0 0 +EDGE2 4980 4839 1.03687 -0.0353112 -3.14241 1 0 1 1 0 0 +EDGE2 4980 4819 0.920505 0.0358924 -3.16882 1 0 1 1 0 0 +EDGE2 4980 4820 0.0372394 -0.0305687 -3.15232 1 0 1 1 0 0 +EDGE2 4980 4821 -0.0309913 -0.992945 -1.58209 1 0 1 1 0 0 +EDGE2 4980 4841 0.0382881 -0.989175 -1.60116 1 0 1 1 0 0 +EDGE2 4980 4840 -0.0806871 0.00739266 -3.18956 1 0 1 1 0 0 +EDGE2 4980 4580 -0.00713215 -0.010086 -0.05186 1 0 1 1 0 0 +EDGE2 4980 4680 -0.00151514 0.0438719 0.00927572 1 0 1 1 0 0 +EDGE2 4980 4700 0.0329065 0.0955712 0.0347364 1 0 1 1 0 0 +EDGE2 4980 4681 0.074655 1.0124 1.57679 1 0 1 1 0 0 +EDGE2 4980 4701 0.00810814 1.02298 1.56567 1 0 1 1 0 0 +EDGE2 4980 4581 0.0497688 0.990499 1.58039 1 0 1 1 0 0 +EDGE2 4980 4679 -0.916584 0.0293173 -0.0188641 1 0 1 1 0 0 +EDGE2 4980 4699 -0.946729 -0.0575824 -0.0491222 1 0 1 1 0 0 +EDGE2 4980 4979 -1.03701 0.0235889 -0.00425726 1 0 1 1 0 0 +EDGE2 4980 4579 -0.953378 -0.0598571 -0.00202553 1 0 1 1 0 0 +EDGE2 4981 4820 -0.970459 0.0556788 1.56922 1 0 1 1 0 0 +EDGE2 4981 4840 -0.998721 -0.0528144 1.54844 1 0 1 1 0 0 +EDGE2 4981 4980 -1.05835 0.0355243 -1.52861 1 0 1 1 0 0 +EDGE2 4981 4580 -1.00697 0.0530773 -1.56056 1 0 1 1 0 0 +EDGE2 4981 4680 -0.994818 -0.0494347 -1.56481 1 0 1 1 0 0 +EDGE2 4981 4700 -0.989251 -0.0874014 -1.59824 1 0 1 1 0 0 +EDGE2 4981 4681 -0.038982 -0.0141713 0.0320499 1 0 1 1 0 0 +EDGE2 4981 4701 0.00465137 -0.0701784 -0.0162931 1 0 1 1 0 0 +EDGE2 4981 4581 -0.0498158 -0.00715912 0.0145819 1 0 1 1 0 0 +EDGE2 4981 4582 0.986338 0.0185203 0.00116288 1 0 1 1 0 0 +EDGE2 4981 4702 1.04153 -0.079207 0.00681822 1 0 1 1 0 0 +EDGE2 4981 4682 1.11484 -0.0569197 -0.000698628 1 0 1 1 0 0 +EDGE2 4982 4981 -1.0338 0.0204248 -0.0334497 1 0 1 1 0 0 +EDGE2 4982 4681 -0.986637 -0.0108084 -0.0106245 1 0 1 1 0 0 +EDGE2 4982 4701 -0.985885 -0.0581175 -0.00995694 1 0 1 1 0 0 +EDGE2 4982 4581 -0.99962 -0.0023796 -0.043688 1 0 1 1 0 0 +EDGE2 4982 4583 1.03282 0.0628853 0.033563 1 0 1 1 0 0 +EDGE2 4982 4582 0.0070544 -0.00699593 -0.0328758 1 0 1 1 0 0 +EDGE2 4982 4702 -0.0987542 -0.078731 -0.011898 1 0 1 1 0 0 +EDGE2 4982 4682 -0.0333678 -0.0306529 -0.0363816 1 0 1 1 0 0 +EDGE2 4982 4703 0.919187 -0.0318481 -0.0134836 1 0 1 1 0 0 +EDGE2 4982 4683 1.01256 0.0448739 -0.0322795 1 0 1 1 0 0 +EDGE2 4983 4583 -0.0277415 0.0550911 0.00772669 1 0 1 1 0 0 +EDGE2 4983 4582 -1.0275 -0.0239046 -0.00770386 1 0 1 1 0 0 +EDGE2 4983 4702 -0.974146 0.0999032 0.00197053 1 0 1 1 0 0 +EDGE2 4983 4982 -1.01848 -0.0695043 -0.0181274 1 0 1 1 0 0 +EDGE2 4983 4682 -0.992156 0.0417427 0.0169664 1 0 1 1 0 0 +EDGE2 4983 4703 -0.0280694 0.0367891 -0.0424263 1 0 1 1 0 0 +EDGE2 4983 4683 -0.0131622 0.0730965 0.0124622 1 0 1 1 0 0 +EDGE2 4983 4684 0.937667 0.0377986 0.00680379 1 0 1 1 0 0 +EDGE2 4983 4704 1.08411 -0.0539723 -0.00543 1 0 1 1 0 0 +EDGE2 4983 4584 1.03735 -0.0752582 -0.029352 1 0 1 1 0 0 +EDGE2 4984 4583 -1.00966 -0.0321569 -0.034919 1 0 1 1 0 0 +EDGE2 4984 4703 -0.950178 0.10319 0.00207083 1 0 1 1 0 0 +EDGE2 4984 4983 -1.09344 -0.0316506 0.0135544 1 0 1 1 0 0 +EDGE2 4984 4683 -1.02716 -0.0581547 -0.00449781 1 0 1 1 0 0 +EDGE2 4984 4705 1.0298 -0.0632125 -0.00651185 1 0 1 1 0 0 +EDGE2 4984 4684 -0.0685868 -0.0698935 0.0113018 1 0 1 1 0 0 +EDGE2 4984 4704 -0.0999132 0.0891281 0.00835608 1 0 1 1 0 0 +EDGE2 4984 4584 0.106233 0.0819946 -0.006512 1 0 1 1 0 0 +EDGE2 4984 3605 1.03359 -0.0954392 -3.17371 1 0 1 1 0 0 +EDGE2 4984 4645 1.00645 -0.0155223 -3.14675 1 0 1 1 0 0 +EDGE2 4984 4665 1.06591 -0.0828447 -3.14021 1 0 1 1 0 0 +EDGE2 4984 4685 1.00862 -0.0176695 -0.00245546 1 0 1 1 0 0 +EDGE2 4984 4585 0.947856 -0.0676708 0.0254566 1 0 1 1 0 0 +EDGE2 4985 4646 0.0720222 -0.971678 -1.59344 1 0 1 1 0 0 +EDGE2 4985 4706 -0.082351 -0.976359 -1.55698 1 0 1 1 0 0 +EDGE2 4985 4586 -0.0518866 -0.87903 -1.53624 1 0 1 1 0 0 +EDGE2 4985 4644 1.05876 -0.0481702 -3.16337 1 0 1 1 0 0 +EDGE2 4985 4705 0.0171245 -0.0648654 0.00487685 1 0 1 1 0 0 +EDGE2 4985 4684 -1.01731 -0.00992037 0.0233709 1 0 1 1 0 0 +EDGE2 4985 4704 -0.991741 0.0173133 0.0374329 1 0 1 1 0 0 +EDGE2 4985 4984 -0.969686 0.0236302 -0.00165462 1 0 1 1 0 0 +EDGE2 4985 4584 -1.00282 0.0315895 0.0111388 1 0 1 1 0 0 +EDGE2 4985 3605 0.0507776 0.0224066 -3.1467 1 0 1 1 0 0 +EDGE2 4985 4645 0.00549795 0.0540544 -3.13393 1 0 1 1 0 0 +EDGE2 4985 4665 0.111962 -0.0241835 -3.11966 1 0 1 1 0 0 +EDGE2 4985 4685 -0.0570039 -0.0324802 0.0242032 1 0 1 1 0 0 +EDGE2 4985 4585 0.0354477 0.00398726 0.0390011 1 0 1 1 0 0 +EDGE2 4985 4664 0.966433 0.066721 -3.15216 1 0 1 1 0 0 +EDGE2 4985 3606 0.0635645 0.992349 1.54744 1 0 1 1 0 0 +EDGE2 4985 4686 0.00371124 0.998892 1.5647 1 0 1 1 0 0 +EDGE2 4985 4666 0.0488077 0.956091 1.55408 1 0 1 1 0 0 +EDGE2 4985 3604 0.994494 -0.00535277 -3.13663 1 0 1 1 0 0 +EDGE2 4986 4707 1.05234 0.0256465 0.0269284 1 0 1 1 0 0 +EDGE2 4986 4587 1.01717 -0.0505965 -0.0224463 1 0 1 1 0 0 +EDGE2 4986 4647 1.03797 -0.0282561 0.00962305 1 0 1 1 0 0 +EDGE2 4986 4646 0.0290554 0.0189345 0.0384395 1 0 1 1 0 0 +EDGE2 4986 4706 -0.0605269 0.0334007 -0.00757094 1 0 1 1 0 0 +EDGE2 4986 4586 -0.0295052 0.0706586 0.00147897 1 0 1 1 0 0 +EDGE2 4986 4705 -0.989238 0.0150563 1.56859 1 0 1 1 0 0 +EDGE2 4986 4985 -0.956617 -0.0571187 1.56634 1 0 1 1 0 0 +EDGE2 4986 3605 -0.997997 0.0394122 -1.56743 1 0 1 1 0 0 +EDGE2 4986 4645 -0.943954 0.0369758 -1.5561 1 0 1 1 0 0 +EDGE2 4986 4665 -0.976712 0.0245466 -1.62692 1 0 1 1 0 0 +EDGE2 4986 4685 -1.02219 -0.0599476 1.59762 1 0 1 1 0 0 +EDGE2 4986 4585 -1.02351 -0.00278265 1.55647 1 0 1 1 0 0 +EDGE2 4987 4707 0.061576 0.019511 0.0266206 1 0 1 1 0 0 +EDGE2 4987 4708 0.971315 0.0712691 0.00910586 1 0 1 1 0 0 +EDGE2 4987 4648 1.02375 0.009822 0.00596081 1 0 1 1 0 0 +EDGE2 4987 4588 1.05792 0.0704288 0.00901015 1 0 1 1 0 0 +EDGE2 4987 4986 -1.09526 -0.0449908 0.0269313 1 0 1 1 0 0 +EDGE2 4987 4587 0.0186132 0.0355484 -0.00672651 1 0 1 1 0 0 +EDGE2 4987 4647 -0.0190014 -0.0211908 0.0370911 1 0 1 1 0 0 +EDGE2 4987 4646 -1.0267 -0.0853012 0.0266897 1 0 1 1 0 0 +EDGE2 4987 4706 -1.04418 -0.0490444 -0.00209183 1 0 1 1 0 0 +EDGE2 4987 4586 -0.987192 0.0210198 -0.000968682 1 0 1 1 0 0 +EDGE2 4988 4707 -1.03318 -0.00524571 -0.00920808 1 0 1 1 0 0 +EDGE2 4988 4708 -0.0179255 -0.0190816 -0.0101512 1 0 1 1 0 0 +EDGE2 4988 4649 1.04008 0.0378109 0.0119571 1 0 1 1 0 0 +EDGE2 4988 4709 0.992108 -0.0521376 0.0336918 1 0 1 1 0 0 +EDGE2 4988 4589 0.96965 -0.0207807 -0.027678 1 0 1 1 0 0 +EDGE2 4988 4648 -0.0437612 -0.0284637 -0.00133792 1 0 1 1 0 0 +EDGE2 4988 4588 0.0746068 0.0263004 0.0190475 1 0 1 1 0 0 +EDGE2 4988 4987 -0.999241 0.0497471 -0.0254823 1 0 1 1 0 0 +EDGE2 4988 4587 -1.02539 -0.0938768 -0.0395779 1 0 1 1 0 0 +EDGE2 4988 4647 -1.0232 -0.025084 0.00943149 1 0 1 1 0 0 +EDGE2 4989 4710 0.985536 0.0282569 0.015006 1 0 1 1 0 0 +EDGE2 4989 4630 0.959229 -0.0575196 -3.14582 1 0 1 1 0 0 +EDGE2 4989 4650 1.02103 -0.0300354 0.0319084 1 0 1 1 0 0 +EDGE2 4989 4590 0.939649 0.0342257 0.0106068 1 0 1 1 0 0 +EDGE2 4989 4708 -1.02121 0.00419878 0.00444584 1 0 1 1 0 0 +EDGE2 4989 4649 0.0211867 -0.0533671 -0.0251073 1 0 1 1 0 0 +EDGE2 4989 4709 0.0486073 0.0883247 0.0163719 1 0 1 1 0 0 +EDGE2 4989 4589 0.0528394 -0.10258 0.010078 1 0 1 1 0 0 +EDGE2 4989 4988 -0.980853 0.0232497 0.00831091 1 0 1 1 0 0 +EDGE2 4989 4648 -0.961828 0.0444725 -0.000699415 1 0 1 1 0 0 +EDGE2 4989 4588 -1.01593 0.00931823 -0.0107863 1 0 1 1 0 0 +EDGE2 4990 4710 -0.131513 -0.00456236 0.0230922 1 0 1 1 0 0 +EDGE2 4990 4629 1.04071 -0.0450077 -3.14343 1 0 1 1 0 0 +EDGE2 4990 4711 0.0743458 -0.966357 -1.57789 1 0 1 1 0 0 +EDGE2 4990 4630 0.0718181 0.0387723 -3.18381 1 0 1 1 0 0 +EDGE2 4990 4650 0.0828875 -0.0684995 -0.000515203 1 0 1 1 0 0 +EDGE2 4990 4590 0.00730001 0.0796985 -0.00617258 1 0 1 1 0 0 +EDGE2 4990 4591 0.032812 1.00534 1.58273 1 0 1 1 0 0 +EDGE2 4990 4651 0.0100075 1.03286 1.54781 1 0 1 1 0 0 +EDGE2 4990 4631 0.0392314 0.97714 1.58264 1 0 1 1 0 0 +EDGE2 4990 4649 -1.06272 -0.084921 0.0267649 1 0 1 1 0 0 +EDGE2 4990 4989 -1.11343 0.0704253 -0.00686472 1 0 1 1 0 0 +EDGE2 4990 4709 -0.926261 0.0146665 -0.00516572 1 0 1 1 0 0 +EDGE2 4990 4589 -1.01106 -0.00768327 0.0185291 1 0 1 1 0 0 +EDGE2 4991 4710 -0.923965 -0.0382186 -1.5655 1 0 1 1 0 0 +EDGE2 4991 4990 -1.00692 -0.069277 -1.55202 1 0 1 1 0 0 +EDGE2 4991 4630 -1.02936 0.020985 1.63001 1 0 1 1 0 0 +EDGE2 4991 4650 -1.08419 0.0955197 -1.53946 1 0 1 1 0 0 +EDGE2 4991 4590 -1.07847 -0.0360335 -1.5469 1 0 1 1 0 0 +EDGE2 4991 4632 0.947306 -0.0622063 0.0273782 1 0 1 1 0 0 +EDGE2 4991 4591 0.0425918 0.0274826 -0.0456082 1 0 1 1 0 0 +EDGE2 4991 4651 0.0600099 0.0375823 0.0134358 1 0 1 1 0 0 +EDGE2 4991 4631 0.0503269 0.00239124 0.0237605 1 0 1 1 0 0 +EDGE2 4991 4652 1.01089 -0.0662232 0.0286152 1 0 1 1 0 0 +EDGE2 4991 4592 0.965267 -0.0453685 0.0462239 1 0 1 1 0 0 +EDGE2 4992 4632 0.0221765 -0.0628341 -0.0111597 1 0 1 1 0 0 +EDGE2 4992 4591 -0.952528 0.0357623 0.00570467 1 0 1 1 0 0 +EDGE2 4992 4651 -0.980279 -0.00506177 -0.0139963 1 0 1 1 0 0 +EDGE2 4992 4991 -0.939364 -0.0322875 -0.000526282 1 0 1 1 0 0 +EDGE2 4992 4631 -1.00149 0.0287596 -0.0213031 1 0 1 1 0 0 +EDGE2 4992 4652 0.0175384 0.0168964 0.0165896 1 0 1 1 0 0 +EDGE2 4992 4653 0.947955 0.0149349 -0.0125869 1 0 1 1 0 0 +EDGE2 4992 4592 -0.010666 -0.0501854 -0.0120076 1 0 1 1 0 0 +EDGE2 4992 4593 0.959936 0.0778519 -0.0112486 1 0 1 1 0 0 +EDGE2 4992 4633 1.0583 -0.118661 0.00421977 1 0 1 1 0 0 +EDGE2 4993 4632 -1.03603 -0.0390831 -0.053216 1 0 1 1 0 0 +EDGE2 4993 4992 -0.994488 -0.0642779 -0.00445791 1 0 1 1 0 0 +EDGE2 4993 4652 -0.962143 0.0446925 0.0051158 1 0 1 1 0 0 +EDGE2 4993 4653 0.0503135 0.108215 0.000341456 1 0 1 1 0 0 +EDGE2 4993 4592 -1.01376 0.0144699 0.00906796 1 0 1 1 0 0 +EDGE2 4993 4593 0.0311562 0.00156052 -0.0191698 1 0 1 1 0 0 +EDGE2 4993 4633 0.11269 -0.0541552 0.00567547 1 0 1 1 0 0 +EDGE2 4993 4634 0.98682 -0.0549099 -0.0048354 1 0 1 1 0 0 +EDGE2 4993 4654 1.06935 0.0148444 0.00367712 1 0 1 1 0 0 +EDGE2 4993 4594 1.08577 -0.00242746 0.0144186 1 0 1 1 0 0 +EDGE2 4994 4653 -1.03607 0.0290864 -0.0296126 1 0 1 1 0 0 +EDGE2 4994 4993 -1.00234 0.0301412 0.00511415 1 0 1 1 0 0 +EDGE2 4994 4593 -1.09056 0.00554831 -0.0116128 1 0 1 1 0 0 +EDGE2 4994 4633 -0.950646 0.000809852 -0.0111899 1 0 1 1 0 0 +EDGE2 4994 4634 0.0112949 0.0193282 0.0126923 1 0 1 1 0 0 +EDGE2 4994 4654 0.0482863 -0.0352142 -0.0186472 1 0 1 1 0 0 +EDGE2 4994 4594 0.00317751 -0.0144098 -0.0343393 1 0 1 1 0 0 +EDGE2 4994 2915 1.10823 -0.0338097 -3.12991 1 0 1 1 0 0 +EDGE2 4994 4635 0.931303 -0.0265657 -0.0148235 1 0 1 1 0 0 +EDGE2 4994 4655 0.965883 0.027078 0.0370928 1 0 1 1 0 0 +EDGE2 4994 4595 0.924167 -0.0158118 0.0200409 1 0 1 1 0 0 +EDGE2 4994 3595 1.04408 -0.0248412 -3.15652 1 0 1 1 0 0 +EDGE2 4994 3735 0.965426 -0.00971233 -3.13259 1 0 1 1 0 0 +EDGE2 4994 3755 0.96171 0.0237219 -3.12596 1 0 1 1 0 0 +EDGE2 4994 3575 1.06757 -0.00740124 -3.14995 1 0 1 1 0 0 +EDGE2 4995 4634 -0.961519 -0.064866 -0.0462318 1 0 1 1 0 0 +EDGE2 4995 4654 -1.03443 0.065014 0.0108443 1 0 1 1 0 0 +EDGE2 4995 4994 -0.956721 0.0826159 0.0264603 1 0 1 1 0 0 +EDGE2 4995 4594 -1.01953 -0.0432939 0.00219374 1 0 1 1 0 0 +EDGE2 4995 2915 0.0762246 0.0356365 -3.12709 1 0 1 1 0 0 +EDGE2 4995 4635 -0.0139569 0.0788762 0.00817856 1 0 1 1 0 0 +EDGE2 4995 2916 -0.0273187 -0.96146 -1.57854 1 0 1 1 0 0 +EDGE2 4995 3736 -0.0212922 -0.937829 -1.56817 1 0 1 1 0 0 +EDGE2 4995 4596 -0.0425084 -0.960679 -1.59924 1 0 1 1 0 0 +EDGE2 4995 3576 0.0393755 -0.985332 -1.58432 1 0 1 1 0 0 +EDGE2 4995 4655 -0.0144234 -0.0155829 -0.00673758 1 0 1 1 0 0 +EDGE2 4995 4595 -0.0401222 0.0162865 0.0300317 1 0 1 1 0 0 +EDGE2 4995 3595 0.123429 0.0295622 -3.15854 1 0 1 1 0 0 +EDGE2 4995 3735 -0.0422606 0.0966813 -3.21375 1 0 1 1 0 0 +EDGE2 4995 3755 0.0676595 0.122995 -3.10886 1 0 1 1 0 0 +EDGE2 4995 3575 0.0556813 -0.0154994 -3.13731 1 0 1 1 0 0 +EDGE2 4995 2914 0.92143 0.00341842 -3.15777 1 0 1 1 0 0 +EDGE2 4995 3594 0.985286 0.0138732 -3.11415 1 0 1 1 0 0 +EDGE2 4995 3734 1.02331 0.023993 -3.15402 1 0 1 1 0 0 +EDGE2 4995 3754 1.09155 0.0650785 -3.12719 1 0 1 1 0 0 +EDGE2 4995 3574 0.974034 -0.0177171 -3.15208 1 0 1 1 0 0 +EDGE2 4995 4636 0.110046 0.899848 1.562 1 0 1 1 0 0 +EDGE2 4995 4656 0.00685987 0.987491 1.5844 1 0 1 1 0 0 +EDGE2 4995 3596 -0.0471409 1.01377 1.57069 1 0 1 1 0 0 +EDGE2 4995 3756 -0.0318802 0.953184 1.57835 1 0 1 1 0 0 +EDGE2 4996 2915 -0.962502 0.077105 1.54796 1 0 1 1 0 0 +EDGE2 4996 4635 -0.925339 0.0227639 -1.55743 1 0 1 1 0 0 +EDGE2 4996 4995 -1.0289 -0.012711 -1.54649 1 0 1 1 0 0 +EDGE2 4996 4655 -0.917222 0.0646398 -1.57918 1 0 1 1 0 0 +EDGE2 4996 4595 -1.02401 0.0737692 -1.57642 1 0 1 1 0 0 +EDGE2 4996 3595 -1.00748 0.10961 1.56334 1 0 1 1 0 0 +EDGE2 4996 3735 -0.961961 -0.0300007 1.58248 1 0 1 1 0 0 +EDGE2 4996 3755 -0.986048 0.00778313 1.58504 1 0 1 1 0 0 +EDGE2 4996 3575 -0.93754 0.00616374 1.52886 1 0 1 1 0 0 +EDGE2 4996 3597 0.986519 -0.00691823 0.0209664 1 0 1 1 0 0 +EDGE2 4996 4636 -0.0319177 0.0154481 0.0276171 1 0 1 1 0 0 +EDGE2 4996 4656 -0.0202134 -0.0109061 -0.00360186 1 0 1 1 0 0 +EDGE2 4996 3596 -0.0110983 0.088566 -0.0338264 1 0 1 1 0 0 +EDGE2 4996 3756 0.0528266 -0.0196099 -0.0363263 1 0 1 1 0 0 +EDGE2 4996 4637 1.08743 -0.0451873 0.000537108 1 0 1 1 0 0 +EDGE2 4996 4657 1.07808 -0.028103 0.0154034 1 0 1 1 0 0 +EDGE2 4996 3757 1.00343 0.0488807 0.0414383 1 0 1 1 0 0 +EDGE2 4997 3597 -0.105254 0.0555519 -0.0230483 1 0 1 1 0 0 +EDGE2 4997 4636 -1.00748 -0.0769368 -0.000714514 1 0 1 1 0 0 +EDGE2 4997 4996 -0.966987 0.0499207 -0.0150273 1 0 1 1 0 0 +EDGE2 4997 4656 -0.985542 0.113745 0.0228676 1 0 1 1 0 0 +EDGE2 4997 3596 -0.874204 -0.0310677 0.0252859 1 0 1 1 0 0 +EDGE2 4997 3756 -1.01145 0.0449947 0.037801 1 0 1 1 0 0 +EDGE2 4997 4637 0.0110448 0.0230571 0.00954454 1 0 1 1 0 0 +EDGE2 4997 4657 -0.0126036 -0.080253 0.0165464 1 0 1 1 0 0 +EDGE2 4997 3757 -0.0729346 0.00566398 0.0209366 1 0 1 1 0 0 +EDGE2 4997 4638 0.929186 0.0125167 0.0238371 1 0 1 1 0 0 +EDGE2 4997 4658 1.00367 0.000467171 0.0132125 1 0 1 1 0 0 +EDGE2 4997 3598 0.881703 0.00993972 -0.0254925 1 0 1 1 0 0 +EDGE2 4997 3758 0.934822 -0.0235748 -0.0406054 1 0 1 1 0 0 +EDGE2 4998 3597 -0.998764 -0.0297188 -0.0119105 1 0 1 1 0 0 +EDGE2 4998 4997 -0.996598 -0.0441652 -0.00157648 1 0 1 1 0 0 +EDGE2 4998 4637 -1.03449 -0.0379164 0.018836 1 0 1 1 0 0 +EDGE2 4998 4657 -0.959051 0.0292547 -0.00262306 1 0 1 1 0 0 +EDGE2 4998 3757 -0.952443 -0.0107488 -0.0314358 1 0 1 1 0 0 +EDGE2 4998 4638 0.0150142 0.0503345 -0.0126537 1 0 1 1 0 0 +EDGE2 4998 4658 0.0996033 0.0250554 -0.00803076 1 0 1 1 0 0 +EDGE2 4998 3598 0.0198787 -0.0964836 -0.0140065 1 0 1 1 0 0 +EDGE2 4998 3758 0.0339935 -0.0234201 0.00955914 1 0 1 1 0 0 +EDGE2 4998 4639 1.00957 0.0423338 -0.0169103 1 0 1 1 0 0 +EDGE2 4998 4659 0.945288 -0.0701601 -0.0195436 1 0 1 1 0 0 +EDGE2 4998 3599 1.0089 -0.00896759 -0.0164396 1 0 1 1 0 0 +EDGE2 4998 3759 1.05272 -0.00875037 0.00571615 1 0 1 1 0 0 +EDGE2 4999 4638 -1.04957 -0.0439059 -0.00750296 1 0 1 1 0 0 +EDGE2 4999 4998 -0.984589 -0.108622 0.0203522 1 0 1 1 0 0 +EDGE2 4999 4658 -0.965986 -0.0350197 0.0467252 1 0 1 1 0 0 +EDGE2 4999 3598 -0.93451 0.0341331 0.00637611 1 0 1 1 0 0 +EDGE2 4999 3758 -1.01168 0.042404 0.0366208 1 0 1 1 0 0 +EDGE2 4999 4639 -0.00894232 0.0197159 0.00847412 1 0 1 1 0 0 +EDGE2 4999 4659 0.11123 -0.0105896 -0.0197236 1 0 1 1 0 0 +EDGE2 4999 3599 0.0430199 0.0416162 0.0141019 1 0 1 1 0 0 +EDGE2 4999 3759 0.024534 -0.0965399 0.0353215 1 0 1 1 0 0 +EDGE2 4999 3680 0.95366 0.00986323 -3.15733 1 0 1 1 0 0 +EDGE2 4999 3820 0.978244 0.0254498 -3.16113 1 0 1 1 0 0 +EDGE2 4999 4640 1.01072 -0.0181773 -0.00617767 1 0 1 1 0 0 +EDGE2 4999 4660 1.0222 0.0579668 0.0238988 1 0 1 1 0 0 +EDGE2 4999 3760 1.0318 -0.0394235 0.0353613 1 0 1 1 0 0 +EDGE2 4999 3600 0.947504 -0.0370475 0.0122516 1 0 1 1 0 0 +EDGE2 4999 3640 1.0485 0.0623504 -3.12519 1 0 1 1 0 0 +EDGE2 4999 3660 1.02834 -0.0420579 -3.16022 1 0 1 1 0 0 +EDGE2 5000 4999 -0.965051 0.0820334 -0.00448935 1 0 1 1 0 0 +EDGE2 5000 4639 -0.968193 0.0954812 0.0373153 1 0 1 1 0 0 +EDGE2 5000 4659 -1.002 -0.054797 -0.0302248 1 0 1 1 0 0 +EDGE2 5000 3599 -0.958826 0.00284047 -0.0364439 1 0 1 1 0 0 +EDGE2 5000 3759 -0.976736 0.00470795 -0.00228236 1 0 1 1 0 0 +EDGE2 5000 3680 0.0122013 -0.0205142 -3.12524 1 0 1 1 0 0 +EDGE2 5000 4661 0.0455897 1.02277 1.55911 1 0 1 1 0 0 +EDGE2 5000 3601 0.000800765 1.03059 1.55866 1 0 1 1 0 0 +EDGE2 5000 4641 -0.1147 0.986945 1.58842 1 0 1 1 0 0 +EDGE2 5000 3820 0.00903463 -0.0765831 -3.12422 1 0 1 1 0 0 +EDGE2 5000 4640 -0.0976163 0.00814115 0.000547697 1 0 1 1 0 0 +EDGE2 5000 4660 0.0861355 -0.010112 0.0179159 1 0 1 1 0 0 +EDGE2 5000 3760 0.0184862 -0.0264088 -0.00737003 1 0 1 1 0 0 +EDGE2 5000 3761 0.0229483 -0.968344 -1.5938 1 0 1 1 0 0 +EDGE2 5000 3600 -0.0409178 0.0222681 0.0267245 1 0 1 1 0 0 +EDGE2 5000 3640 -0.0533456 -0.0668135 -3.10521 1 0 1 1 0 0 +EDGE2 5000 3660 -0.00306205 0.00500628 -3.13608 1 0 1 1 0 0 +EDGE2 5000 3821 0.00981371 -0.944371 -1.57862 1 0 1 1 0 0 +EDGE2 5000 3641 0.0040339 -1.0302 -1.5374 1 0 1 1 0 0 +EDGE2 5000 3661 -0.0611794 -0.974674 -1.58233 1 0 1 1 0 0 +EDGE2 5000 3681 -0.0630304 -0.946092 -1.56137 1 0 1 1 0 0 +EDGE2 5000 3659 1.00609 0.0567217 -3.16974 1 0 1 1 0 0 +EDGE2 5000 3679 1.00619 0.0193184 -3.16019 1 0 1 1 0 0 +EDGE2 5000 3819 0.971167 0.00962218 -3.11827 1 0 1 1 0 0 +EDGE2 5000 3639 1.00986 -0.00754501 -3.12099 1 0 1 1 0 0 +EDGE2 5001 3680 -0.987365 0.0244901 1.58768 1 0 1 1 0 0 +EDGE2 5001 4661 0.0108355 -0.064613 0.0474834 1 0 1 1 0 0 +EDGE2 5001 4642 0.954225 -0.0110864 0.00804114 1 0 1 1 0 0 +EDGE2 5001 4662 0.961348 -0.0785878 -0.0368093 1 0 1 1 0 0 +EDGE2 5001 3602 0.965905 0.0597253 0.0214139 1 0 1 1 0 0 +EDGE2 5001 5000 -1.00536 -0.0170553 -1.58561 1 0 1 1 0 0 +EDGE2 5001 3601 -0.00232574 0.00649151 -0.011941 1 0 1 1 0 0 +EDGE2 5001 4641 -0.0359284 0.0305705 0.0264889 1 0 1 1 0 0 +EDGE2 5001 3820 -1.01049 0.0161833 1.59548 1 0 1 1 0 0 +EDGE2 5001 4640 -1.01461 0.0759801 -1.51405 1 0 1 1 0 0 +EDGE2 5001 4660 -1.04558 -0.061034 -1.58476 1 0 1 1 0 0 +EDGE2 5001 3760 -1.05225 0.0331168 -1.56966 1 0 1 1 0 0 +EDGE2 5001 3600 -1.02045 0.0393887 -1.57212 1 0 1 1 0 0 +EDGE2 5001 3640 -1.01941 -0.02612 1.50601 1 0 1 1 0 0 +EDGE2 5001 3660 -1.04597 0.00792698 1.54971 1 0 1 1 0 0 +EDGE2 5002 4663 1.00137 -0.0272035 0.00717409 1 0 1 1 0 0 +EDGE2 5002 3603 1.10668 -0.0401421 -0.017358 1 0 1 1 0 0 +EDGE2 5002 4643 0.89912 -0.0306818 -0.000842706 1 0 1 1 0 0 +EDGE2 5002 4661 -0.988476 0.104882 -0.000729867 1 0 1 1 0 0 +EDGE2 5002 4642 -0.0133206 0.0147669 -0.0333562 1 0 1 1 0 0 +EDGE2 5002 4662 -0.0479603 0.0086964 -0.00698888 1 0 1 1 0 0 +EDGE2 5002 3602 -0.137783 0.00925852 0.0102274 1 0 1 1 0 0 +EDGE2 5002 5001 -1.00412 0.0368521 0.0462565 1 0 1 1 0 0 +EDGE2 5002 3601 -1.05879 -0.0840496 6.72237e-05 1 0 1 1 0 0 +EDGE2 5002 4641 -1.01629 -0.086918 0.028287 1 0 1 1 0 0 +EDGE2 5003 4644 0.953684 -0.0251702 -1.34539e-05 1 0 1 1 0 0 +EDGE2 5003 4664 0.931873 0.0275304 -0.00328799 1 0 1 1 0 0 +EDGE2 5003 4663 -0.00809683 0.0763131 0.0073845 1 0 1 1 0 0 +EDGE2 5003 3604 1.04033 0.0119605 -0.00592278 1 0 1 1 0 0 +EDGE2 5003 3603 -0.0700117 0.0921954 0.0155191 1 0 1 1 0 0 +EDGE2 5003 4643 0.0527426 0.0462652 0.00785481 1 0 1 1 0 0 +EDGE2 5003 4642 -0.987362 0.0549116 0.00545283 1 0 1 1 0 0 +EDGE2 5003 5002 -1.01252 -0.0361771 0.0169926 1 0 1 1 0 0 +EDGE2 5003 4662 -1.0375 -0.0369913 0.000902179 1 0 1 1 0 0 +EDGE2 5003 3602 -1.04509 -0.0494439 -0.010672 1 0 1 1 0 0 +EDGE2 5004 4644 -0.0334125 -0.0734333 0.000600022 1 0 1 1 0 0 +EDGE2 5004 4705 0.969991 0.0358902 -3.12379 1 0 1 1 0 0 +EDGE2 5004 4985 0.967973 -0.0261614 -3.16894 1 0 1 1 0 0 +EDGE2 5004 3605 1.01402 0.0370034 -0.0295458 1 0 1 1 0 0 +EDGE2 5004 4645 0.961008 -0.00818509 -0.0118809 1 0 1 1 0 0 +EDGE2 5004 4665 0.954101 0.00481892 -0.0426646 1 0 1 1 0 0 +EDGE2 5004 4685 1.03235 -0.0110783 -3.14144 1 0 1 1 0 0 +EDGE2 5004 4585 0.996018 -0.0444533 -3.13563 1 0 1 1 0 0 +EDGE2 5004 4664 0.0264907 0.03197 0.0332663 1 0 1 1 0 0 +EDGE2 5004 4663 -1.02745 0.0182922 -0.0273105 1 0 1 1 0 0 +EDGE2 5004 3604 0.0561032 -0.0679324 0.0137863 1 0 1 1 0 0 +EDGE2 5004 5003 -0.979686 -0.0196333 0.00493398 1 0 1 1 0 0 +EDGE2 5004 3603 -1.04754 0.0408567 -0.000663749 1 0 1 1 0 0 +EDGE2 5004 4643 -0.972816 -0.0363013 -0.023106 1 0 1 1 0 0 +EDGE2 5005 4986 0.016728 1.08652 1.57218 1 0 1 1 0 0 +EDGE2 5005 4646 -0.0259138 0.983627 1.56979 1 0 1 1 0 0 +EDGE2 5005 4706 0.0142161 1.00366 1.54648 1 0 1 1 0 0 +EDGE2 5005 4586 -0.0230866 0.96699 1.57756 1 0 1 1 0 0 +EDGE2 5005 4644 -1.01349 0.0506597 -0.0221343 1 0 1 1 0 0 +EDGE2 5005 4705 0.0369287 0.061497 -3.12545 1 0 1 1 0 0 +EDGE2 5005 4684 1.15823 -0.0211421 -3.16858 1 0 1 1 0 0 +EDGE2 5005 4704 1.04932 -0.0203801 -3.13999 1 0 1 1 0 0 +EDGE2 5005 4984 0.953075 0.0601714 -3.11689 1 0 1 1 0 0 +EDGE2 5005 4584 1.06811 -0.0773838 -3.15858 1 0 1 1 0 0 +EDGE2 5005 4985 0.0559235 0.0217872 -3.10959 1 0 1 1 0 0 +EDGE2 5005 3605 0.0456002 0.00136975 -0.0288999 1 0 1 1 0 0 +EDGE2 5005 4645 0.0406353 0.0935816 -0.0103188 1 0 1 1 0 0 +EDGE2 5005 4665 -0.00825706 0.0245332 0.0318501 1 0 1 1 0 0 +EDGE2 5005 4685 0.0194422 -0.0184959 -3.15603 1 0 1 1 0 0 +EDGE2 5005 4585 0.0647887 0.0981835 -3.12852 1 0 1 1 0 0 +EDGE2 5005 5004 -1.03461 0.0355842 -0.0122518 1 0 1 1 0 0 +EDGE2 5005 4664 -1.03404 -0.0483107 -0.0305981 1 0 1 1 0 0 +EDGE2 5005 3606 0.0707046 -0.986315 -1.58888 1 0 1 1 0 0 +EDGE2 5005 4686 0.0548074 -1.03453 -1.57796 1 0 1 1 0 0 +EDGE2 5005 4666 -0.000775463 -0.965646 -1.5949 1 0 1 1 0 0 +EDGE2 5005 3604 -0.974087 -0.0287926 0.0107711 1 0 1 1 0 0 +EDGE2 5006 4705 -1.07964 0.0848247 -1.58274 1 0 1 1 0 0 +EDGE2 5006 5005 -0.976352 0.0768783 1.58941 1 0 1 1 0 0 +EDGE2 5006 4985 -1.00373 -0.0408383 -1.56929 1 0 1 1 0 0 +EDGE2 5006 3605 -0.913564 -0.00779005 1.53299 1 0 1 1 0 0 +EDGE2 5006 4645 -0.929551 0.0332846 1.58066 1 0 1 1 0 0 +EDGE2 5006 4665 -0.955593 0.0355037 1.62952 1 0 1 1 0 0 +EDGE2 5006 4685 -0.995859 0.067911 -1.56316 1 0 1 1 0 0 +EDGE2 5006 4585 -0.968571 0.0471166 -1.58442 1 0 1 1 0 0 +EDGE2 5006 3607 1.03372 -0.00445663 -0.0150819 1 0 1 1 0 0 +EDGE2 5006 3606 -0.0825777 0.0828641 -0.000628799 1 0 1 1 0 0 +EDGE2 5006 4686 -0.0156624 -0.018462 -0.028542 1 0 1 1 0 0 +EDGE2 5006 4666 -0.0175118 -0.070168 0.00512109 1 0 1 1 0 0 +EDGE2 5006 4687 1.00654 -0.00676027 0.0191922 1 0 1 1 0 0 +EDGE2 5006 4667 0.91818 0.0654762 -0.0153649 1 0 1 1 0 0 +EDGE2 5007 3607 0.0572138 0.0511148 0.0159083 1 0 1 1 0 0 +EDGE2 5007 3606 -0.961939 -0.0188729 -0.0195072 1 0 1 1 0 0 +EDGE2 5007 4686 -1.06967 0.0371935 -0.0140209 1 0 1 1 0 0 +EDGE2 5007 5006 -0.970725 0.00330048 0.00425446 1 0 1 1 0 0 +EDGE2 5007 4666 -1.03961 -0.111231 -0.0004452 1 0 1 1 0 0 +EDGE2 5007 4687 -0.0618009 -0.0257289 -0.0203014 1 0 1 1 0 0 +EDGE2 5007 4667 0.0550024 0.0142171 -0.00377476 1 0 1 1 0 0 +EDGE2 5007 3608 1.0218 0.0368386 -0.0253844 1 0 1 1 0 0 +EDGE2 5007 4668 1.00971 -0.0379312 -0.0162484 1 0 1 1 0 0 +EDGE2 5007 4688 1.00656 0.0308658 0.0256417 1 0 1 1 0 0 +EDGE2 5008 3607 -1.05445 -0.0262471 -0.024867 1 0 1 1 0 0 +EDGE2 5008 4687 -0.988205 0.00160016 0.00243292 1 0 1 1 0 0 +EDGE2 5008 5007 -0.947371 -0.0492556 -0.0102861 1 0 1 1 0 0 +EDGE2 5008 4667 -1.07814 0.024782 -0.00982544 1 0 1 1 0 0 +EDGE2 5008 3608 -0.0206577 0.00147908 -0.0196462 1 0 1 1 0 0 +EDGE2 5008 4668 0.0727211 -0.00906917 -0.0154987 1 0 1 1 0 0 +EDGE2 5008 4688 0.00854836 0.112335 0.0136168 1 0 1 1 0 0 +EDGE2 5008 3609 0.990162 -0.00418343 0.0160453 1 0 1 1 0 0 +EDGE2 5008 4669 1.01928 0.0266221 -0.01749 1 0 1 1 0 0 +EDGE2 5008 4689 1.05843 -0.0181201 0.0170064 1 0 1 1 0 0 +EDGE2 5009 5008 -0.964346 0.0418123 -0.000476476 1 0 1 1 0 0 +EDGE2 5009 3608 -1.01494 0.112358 0.0124742 1 0 1 1 0 0 +EDGE2 5009 4668 -1.0351 0.0690471 0.00934334 1 0 1 1 0 0 +EDGE2 5009 4688 -0.980763 0.019129 -0.0141442 1 0 1 1 0 0 +EDGE2 5009 3609 -0.0083851 -0.0209336 0.0356987 1 0 1 1 0 0 +EDGE2 5009 4669 0.0316534 -0.0119883 -0.0340445 1 0 1 1 0 0 +EDGE2 5009 4689 -0.00475448 0.0296374 0.0232311 1 0 1 1 0 0 +EDGE2 5009 4570 0.993917 0.0188175 -3.16527 1 0 1 1 0 0 +EDGE2 5009 4690 0.993619 0.0655434 -0.00796422 1 0 1 1 0 0 +EDGE2 5009 4970 0.979463 -0.0362911 -3.14523 1 0 1 1 0 0 +EDGE2 5009 4670 0.95602 -0.0709329 -0.00587261 1 0 1 1 0 0 +EDGE2 5009 3610 1.00274 -0.0201018 0.0160033 1 0 1 1 0 0 +EDGE2 5009 3630 1.13261 0.0245565 -3.12887 1 0 1 1 0 0 +EDGE2 5010 5009 -1.0413 0.025107 -0.0171717 1 0 1 1 0 0 +EDGE2 5010 3609 -1.00141 -0.0176991 -0.0108212 1 0 1 1 0 0 +EDGE2 5010 4669 -0.953686 0.038666 -0.0249778 1 0 1 1 0 0 +EDGE2 5010 4689 -1.08957 0.0660857 -0.0121286 1 0 1 1 0 0 +EDGE2 5010 4971 -0.0233809 0.961183 1.56546 1 0 1 1 0 0 +EDGE2 5010 4571 0.0228379 0.964765 1.57659 1 0 1 1 0 0 +EDGE2 5010 4671 0.018716 0.970213 1.5977 1 0 1 1 0 0 +EDGE2 5010 4691 -0.0126957 0.943505 1.6031 1 0 1 1 0 0 +EDGE2 5010 3611 -0.101743 1.10797 1.53758 1 0 1 1 0 0 +EDGE2 5010 4570 -0.0394641 0.0613753 -3.12481 1 0 1 1 0 0 +EDGE2 5010 4690 -0.0331494 0.0379614 0.00890143 1 0 1 1 0 0 +EDGE2 5010 4970 0.00888122 -0.0452849 -3.14993 1 0 1 1 0 0 +EDGE2 5010 4670 -0.0193407 0.0369098 0.00279954 1 0 1 1 0 0 +EDGE2 5010 3610 -0.036198 -0.053474 -0.00915768 1 0 1 1 0 0 +EDGE2 5010 3630 -0.0126201 0.0179552 -3.1598 1 0 1 1 0 0 +EDGE2 5010 3631 -0.0490402 -1.00884 -1.57464 1 0 1 1 0 0 +EDGE2 5010 3629 0.877519 0.0183478 -3.11823 1 0 1 1 0 0 +EDGE2 5010 4569 1.02902 0.0092559 -3.14891 1 0 1 1 0 0 +EDGE2 5010 4969 1.04491 -0.0345164 -3.10419 1 0 1 1 0 0 +EDGE2 5011 4672 0.973255 -0.046633 -0.0199873 1 0 1 1 0 0 +EDGE2 5011 4972 1.06857 0.0143598 -0.00487972 1 0 1 1 0 0 +EDGE2 5011 4692 0.99272 -0.02141 -0.0389061 1 0 1 1 0 0 +EDGE2 5011 4971 0.0587642 -0.034762 0.00541733 1 0 1 1 0 0 +EDGE2 5011 3612 0.972637 -0.0303687 0.0217221 1 0 1 1 0 0 +EDGE2 5011 4572 0.99456 0.0136846 0.0214349 1 0 1 1 0 0 +EDGE2 5011 4571 -0.0273718 0.00449504 0.00142204 1 0 1 1 0 0 +EDGE2 5011 4671 0.0974603 -0.0352104 -0.00370875 1 0 1 1 0 0 +EDGE2 5011 4691 -0.07703 0.0481766 -0.00339093 1 0 1 1 0 0 +EDGE2 5011 3611 -0.029972 -0.0559491 0.00544089 1 0 1 1 0 0 +EDGE2 5011 4570 -1.03324 -0.0275868 1.5916 1 0 1 1 0 0 +EDGE2 5011 4690 -0.946714 0.0809624 -1.55502 1 0 1 1 0 0 +EDGE2 5011 4970 -0.947879 -0.0295713 1.55441 1 0 1 1 0 0 +EDGE2 5011 5010 -1.02882 -0.0148151 -1.55344 1 0 1 1 0 0 +EDGE2 5011 4670 -0.998399 -0.06626 -1.5302 1 0 1 1 0 0 +EDGE2 5011 3610 -0.919764 -0.0426467 -1.53782 1 0 1 1 0 0 +EDGE2 5011 3630 -1.08758 0.00357428 1.56332 1 0 1 1 0 0 +EDGE2 5012 4672 -0.0393052 0.0365043 0.000572724 1 0 1 1 0 0 +EDGE2 5012 4972 0.0201861 -0.00244454 0.0161945 1 0 1 1 0 0 +EDGE2 5012 4673 1.05785 -0.000648804 -0.0257201 1 0 1 1 0 0 +EDGE2 5012 4973 0.932668 0.00700541 -0.0243368 1 0 1 1 0 0 +EDGE2 5012 4693 1.0072 0.0922846 0.0216211 1 0 1 1 0 0 +EDGE2 5012 3613 1.02463 0.00290077 -0.0123017 1 0 1 1 0 0 +EDGE2 5012 4573 1.01619 0.0927994 -0.0264232 1 0 1 1 0 0 +EDGE2 5012 4692 -0.00795014 -0.01159 0.00914927 1 0 1 1 0 0 +EDGE2 5012 4971 -1.08291 -0.0943441 -0.0151582 1 0 1 1 0 0 +EDGE2 5012 3612 0.00203271 0.0178037 0.0012204 1 0 1 1 0 0 +EDGE2 5012 4572 -0.0129049 0.174876 0.0118041 1 0 1 1 0 0 +EDGE2 5012 5011 -1.011 0.00556097 0.0126277 1 0 1 1 0 0 +EDGE2 5012 4571 -1.02722 0.111695 0.0116267 1 0 1 1 0 0 +EDGE2 5012 4671 -0.978983 0.0475271 0.0249778 1 0 1 1 0 0 +EDGE2 5012 4691 -0.990152 0.0200388 0.000164516 1 0 1 1 0 0 +EDGE2 5012 3611 -0.941669 -0.00960933 -0.00527302 1 0 1 1 0 0 +EDGE2 5013 4974 0.923906 -0.0703126 0.0127648 1 0 1 1 0 0 +EDGE2 5013 4574 0.938206 0.0858639 0.000680958 1 0 1 1 0 0 +EDGE2 5013 4674 1.01476 -0.0774879 0.0229475 1 0 1 1 0 0 +EDGE2 5013 4694 0.954837 -0.0652615 0.0275633 1 0 1 1 0 0 +EDGE2 5013 3614 0.950963 -0.0286705 0.00884659 1 0 1 1 0 0 +EDGE2 5013 4672 -1.02373 -0.0813059 -0.00810412 1 0 1 1 0 0 +EDGE2 5013 4972 -0.991571 0.0496593 0.0169176 1 0 1 1 0 0 +EDGE2 5013 4673 0.00639961 -0.0117697 -0.00221968 1 0 1 1 0 0 +EDGE2 5013 4973 -0.00451803 0.030444 0.015251 1 0 1 1 0 0 +EDGE2 5013 4693 -0.0200277 0.0316633 -0.00164665 1 0 1 1 0 0 +EDGE2 5013 3613 -0.0849719 -0.0172366 -0.0310375 1 0 1 1 0 0 +EDGE2 5013 4573 -0.0569286 -0.044479 0.0141374 1 0 1 1 0 0 +EDGE2 5013 5012 -0.926727 0.0448764 -0.0447619 1 0 1 1 0 0 +EDGE2 5013 4692 -1.04384 0.0671178 0.00632464 1 0 1 1 0 0 +EDGE2 5013 3612 -0.923208 0.0723132 -0.0102484 1 0 1 1 0 0 +EDGE2 5013 4572 -1.04435 -0.0339515 0.0109447 1 0 1 1 0 0 +EDGE2 5014 4974 -0.0847947 0.0443246 -0.0085039 1 0 1 1 0 0 +EDGE2 5014 4575 1.03128 0.0356825 -0.0118194 1 0 1 1 0 0 +EDGE2 5014 4695 0.89215 -0.0123947 0.00270151 1 0 1 1 0 0 +EDGE2 5014 4875 0.955198 0.0770394 -3.14234 1 0 1 1 0 0 +EDGE2 5014 4975 0.924693 0.0201844 0.00880085 1 0 1 1 0 0 +EDGE2 5014 4675 0.988573 0.0584238 0.000450019 1 0 1 1 0 0 +EDGE2 5014 3615 0.968056 -0.0467901 0.025897 1 0 1 1 0 0 +EDGE2 5014 4574 -0.0235731 -0.0207041 -0.000920674 1 0 1 1 0 0 +EDGE2 5014 4674 0.0251359 0.0784847 0.00668785 1 0 1 1 0 0 +EDGE2 5014 4694 -0.00735047 0.0670773 -0.0224952 1 0 1 1 0 0 +EDGE2 5014 3614 0.0124624 -0.0531967 0.0474735 1 0 1 1 0 0 +EDGE2 5014 4673 -1.05809 -0.0460341 -0.00394128 1 0 1 1 0 0 +EDGE2 5014 4973 -1.01764 -0.061679 -0.000872697 1 0 1 1 0 0 +EDGE2 5014 5013 -0.923858 -0.115541 -0.0395559 1 0 1 1 0 0 +EDGE2 5014 4693 -1.02832 -0.0488413 -0.009745 1 0 1 1 0 0 +EDGE2 5014 3613 -0.89116 0.000217289 -0.0124593 1 0 1 1 0 0 +EDGE2 5014 4573 -1.06531 -0.0106872 0.0173777 1 0 1 1 0 0 +EDGE2 5015 4976 0.0604762 0.990576 1.58718 1 0 1 1 0 0 +EDGE2 5015 4676 0.0504479 0.906646 1.54575 1 0 1 1 0 0 +EDGE2 5015 4696 0.0491691 1.05775 1.56454 1 0 1 1 0 0 +EDGE2 5015 4576 0.0163118 0.988644 1.57544 1 0 1 1 0 0 +EDGE2 5015 4974 -1.04701 0.0882888 0.021194 1 0 1 1 0 0 +EDGE2 5015 4874 0.944132 0.00270777 -3.14885 1 0 1 1 0 0 +EDGE2 5015 4575 0.0836398 0.0169207 -0.0398062 1 0 1 1 0 0 +EDGE2 5015 4695 0.0342962 0.0350335 0.00675047 1 0 1 1 0 0 +EDGE2 5015 4875 0.0703068 0.0221664 -3.18306 1 0 1 1 0 0 +EDGE2 5015 4975 0.0155845 0.014513 0.00721768 1 0 1 1 0 0 +EDGE2 5015 4675 0.0409182 0.0540994 -0.0084308 1 0 1 1 0 0 +EDGE2 5015 3615 0.0964709 0.040718 0.0122122 1 0 1 1 0 0 +EDGE2 5015 5014 -1.08915 -0.0633513 -0.0129897 1 0 1 1 0 0 +EDGE2 5015 4876 0.0117353 -1.03905 -1.5551 1 0 1 1 0 0 +EDGE2 5015 3616 0.0252534 -1.01107 -1.5459 1 0 1 1 0 0 +EDGE2 5015 4574 -1.08081 0.0153225 0.0231993 1 0 1 1 0 0 +EDGE2 5015 4674 -0.940299 -0.0296786 -0.0065442 1 0 1 1 0 0 +EDGE2 5015 4694 -1.00373 -0.0140367 -0.0291192 1 0 1 1 0 0 +EDGE2 5015 3614 -1.03844 -0.00866176 -0.00915928 1 0 1 1 0 0 +EDGE2 5016 4977 1.11347 -0.0666437 0.000893582 1 0 1 1 0 0 +EDGE2 5016 4976 -0.00635579 -0.0362484 0.0042497 1 0 1 1 0 0 +EDGE2 5016 4577 0.913646 -0.0613174 0.00596375 1 0 1 1 0 0 +EDGE2 5016 4677 1.01457 -0.0482407 -9.27671e-05 1 0 1 1 0 0 +EDGE2 5016 4697 0.937656 -0.0529526 -0.0211407 1 0 1 1 0 0 +EDGE2 5016 4676 0.0565992 0.0319568 -0.0038078 1 0 1 1 0 0 +EDGE2 5016 4696 0.00760148 -0.0457023 -0.0119066 1 0 1 1 0 0 +EDGE2 5016 4576 -0.0775986 0.0888881 0.00606736 1 0 1 1 0 0 +EDGE2 5016 5015 -1.05099 -0.048723 -1.61356 1 0 1 1 0 0 +EDGE2 5016 4575 -1.01415 -0.0840806 -1.58227 1 0 1 1 0 0 +EDGE2 5016 4695 -1.08697 -0.0355476 -1.59386 1 0 1 1 0 0 +EDGE2 5016 4875 -1.01812 0.0364696 1.5888 1 0 1 1 0 0 +EDGE2 5016 4975 -1.00784 0.0246531 -1.55585 1 0 1 1 0 0 +EDGE2 5016 4675 -0.997604 0.0567214 -1.58602 1 0 1 1 0 0 +EDGE2 5016 3615 -1.07822 -0.0309972 -1.57882 1 0 1 1 0 0 +EDGE2 5017 4678 0.991813 -0.0209346 0.0033953 1 0 1 1 0 0 +EDGE2 5017 4698 1.03548 0.0547208 0.0163631 1 0 1 1 0 0 +EDGE2 5017 4978 0.922736 0.0612939 0.00199473 1 0 1 1 0 0 +EDGE2 5017 4578 1.06966 0.00769302 0.017341 1 0 1 1 0 0 +EDGE2 5017 4977 -0.0849673 0.0283315 -0.0523456 1 0 1 1 0 0 +EDGE2 5017 4976 -0.970907 0.0215853 0.0256244 1 0 1 1 0 0 +EDGE2 5017 4577 0.0266257 0.0146029 0.00780342 1 0 1 1 0 0 +EDGE2 5017 4677 0.092753 0.017801 0.0202751 1 0 1 1 0 0 +EDGE2 5017 4697 0.0266546 -0.0201612 0.0399442 1 0 1 1 0 0 +EDGE2 5017 5016 -0.950937 0.0775026 0.0209772 1 0 1 1 0 0 +EDGE2 5017 4676 -0.927133 -0.00308717 0.0114226 1 0 1 1 0 0 +EDGE2 5017 4696 -0.98622 -0.0187658 0.0263487 1 0 1 1 0 0 +EDGE2 5017 4576 -1.00805 -0.0399664 0.0215859 1 0 1 1 0 0 +EDGE2 5018 4679 0.904312 -0.0434833 0.0181285 1 0 1 1 0 0 +EDGE2 5018 4699 1.02398 -0.122933 0.0301843 1 0 1 1 0 0 +EDGE2 5018 4979 0.972176 0.0128825 0.0156873 1 0 1 1 0 0 +EDGE2 5018 4579 1.05749 -0.0583208 -0.0321959 1 0 1 1 0 0 +EDGE2 5018 4678 0.010535 -0.0231635 0.00828949 1 0 1 1 0 0 +EDGE2 5018 4698 -0.0587419 -0.00992318 0.0182433 1 0 1 1 0 0 +EDGE2 5018 4978 0.0181149 0.0664347 -0.00989014 1 0 1 1 0 0 +EDGE2 5018 4578 -0.0626814 0.0582904 -0.0245054 1 0 1 1 0 0 +EDGE2 5018 4977 -0.94873 -0.0484652 0.0135882 1 0 1 1 0 0 +EDGE2 5018 5017 -0.983388 0.0190099 -0.0113524 1 0 1 1 0 0 +EDGE2 5018 4577 -1.01854 0.070659 0.0178845 1 0 1 1 0 0 +EDGE2 5018 4677 -1.10891 -0.0584589 -0.000753514 1 0 1 1 0 0 +EDGE2 5018 4697 -1.11322 -0.0781366 -0.00124593 1 0 1 1 0 0 +EDGE2 5019 4820 0.956194 -0.0495253 -3.16325 1 0 1 1 0 0 +EDGE2 5019 4840 0.931157 0.069456 -3.1375 1 0 1 1 0 0 +EDGE2 5019 4980 1.03951 -0.0188265 0.0349459 1 0 1 1 0 0 +EDGE2 5019 4580 1.03777 0.00783418 -0.000586635 1 0 1 1 0 0 +EDGE2 5019 4680 0.997713 -0.0377277 0.00846154 1 0 1 1 0 0 +EDGE2 5019 4700 0.945469 0.0647998 0.00681837 1 0 1 1 0 0 +EDGE2 5019 5018 -0.992341 0.0963235 -0.0558121 1 0 1 1 0 0 +EDGE2 5019 4679 0.0833477 -0.0331798 -0.0185832 1 0 1 1 0 0 +EDGE2 5019 4699 -0.0296977 0.0514733 0.00212734 1 0 1 1 0 0 +EDGE2 5019 4979 0.0440066 -0.00327084 0.0178718 1 0 1 1 0 0 +EDGE2 5019 4579 0.0106486 0.0562858 -0.024684 1 0 1 1 0 0 +EDGE2 5019 4678 -1.04902 0.0446701 0.00558795 1 0 1 1 0 0 +EDGE2 5019 4698 -1.06056 0.0154179 0.0123657 1 0 1 1 0 0 +EDGE2 5019 4978 -1.02984 -0.0268891 0.0155665 1 0 1 1 0 0 +EDGE2 5019 4578 -0.998235 0.112651 0.00570647 1 0 1 1 0 0 +EDGE2 5020 4839 1.02798 0.0966291 -3.15257 1 0 1 1 0 0 +EDGE2 5020 4819 0.939333 -0.0368848 -3.15566 1 0 1 1 0 0 +EDGE2 5020 4820 -0.0650891 0.00656252 -3.13967 1 0 1 1 0 0 +EDGE2 5020 4821 0.00504033 -0.962956 -1.55111 1 0 1 1 0 0 +EDGE2 5020 4841 -0.00893712 -0.892211 -1.52364 1 0 1 1 0 0 +EDGE2 5020 4840 0.0218243 -0.00162098 -3.16204 1 0 1 1 0 0 +EDGE2 5020 4980 0.0199475 -0.0707164 -0.0272383 1 0 1 1 0 0 +EDGE2 5020 4981 -0.0627481 1.01968 1.56451 1 0 1 1 0 0 +EDGE2 5020 4580 -0.0848465 -0.0708189 -0.025737 1 0 1 1 0 0 +EDGE2 5020 4680 -0.0139512 0.0804525 -0.032561 1 0 1 1 0 0 +EDGE2 5020 4700 -0.0173299 0.0365013 -0.0313553 1 0 1 1 0 0 +EDGE2 5020 4681 0.044074 0.992428 1.57363 1 0 1 1 0 0 +EDGE2 5020 4701 0.0572531 0.945496 1.59767 1 0 1 1 0 0 +EDGE2 5020 4581 0.0363362 0.986613 1.56758 1 0 1 1 0 0 +EDGE2 5020 5019 -0.941833 -0.00498453 0.0186777 1 0 1 1 0 0 +EDGE2 5020 4679 -0.950999 -0.0372364 0.0108235 1 0 1 1 0 0 +EDGE2 5020 4699 -1.10918 -0.0137953 -0.0150133 1 0 1 1 0 0 +EDGE2 5020 4979 -0.994846 0.030101 0.0258787 1 0 1 1 0 0 +EDGE2 5020 4579 -0.974387 0.0467648 -0.0101247 1 0 1 1 0 0 +EDGE2 5021 4820 -0.914289 -0.0260044 1.55864 1 0 1 1 0 0 +EDGE2 5021 4840 -1.0344 0.0406146 1.58654 1 0 1 1 0 0 +EDGE2 5021 4980 -1.05402 0.0252428 -1.53716 1 0 1 1 0 0 +EDGE2 5021 5020 -0.986729 0.0350923 -1.567 1 0 1 1 0 0 +EDGE2 5021 4981 -0.0847542 -0.0628252 -0.00452424 1 0 1 1 0 0 +EDGE2 5021 4580 -0.92632 -0.0420179 -1.57206 1 0 1 1 0 0 +EDGE2 5021 4680 -0.947598 0.00761828 -1.59243 1 0 1 1 0 0 +EDGE2 5021 4700 -1.0199 -0.0446126 -1.56572 1 0 1 1 0 0 +EDGE2 5021 4681 -0.00879418 0.0522169 -0.00312473 1 0 1 1 0 0 +EDGE2 5021 4701 0.042807 -0.0360757 0.0142646 1 0 1 1 0 0 +EDGE2 5021 4581 0.0238488 0.00438248 -0.0105458 1 0 1 1 0 0 +EDGE2 5021 4582 1.00662 0.0455024 -0.0214179 1 0 1 1 0 0 +EDGE2 5021 4702 1.06737 0.0215165 0.00772723 1 0 1 1 0 0 +EDGE2 5021 4982 0.975202 0.156861 0.026398 1 0 1 1 0 0 +EDGE2 5021 4682 0.996812 -0.0160368 -0.00547452 1 0 1 1 0 0 +EDGE2 5022 4981 -0.940655 0.0332662 0.0286528 1 0 1 1 0 0 +EDGE2 5022 5021 -1.02795 -0.0185135 -0.0170049 1 0 1 1 0 0 +EDGE2 5022 4681 -0.943704 0.0554824 0.0193763 1 0 1 1 0 0 +EDGE2 5022 4701 -1.00284 -0.107916 -0.00455826 1 0 1 1 0 0 +EDGE2 5022 4581 -0.978393 0.0734106 -0.00293053 1 0 1 1 0 0 +EDGE2 5022 4583 0.984753 -0.0066355 -0.00801196 1 0 1 1 0 0 +EDGE2 5022 4582 0.12368 0.00272709 -0.0203299 1 0 1 1 0 0 +EDGE2 5022 4702 0.00242717 -0.0469257 -0.00900835 1 0 1 1 0 0 +EDGE2 5022 4982 -0.0309406 0.0213594 0.00116283 1 0 1 1 0 0 +EDGE2 5022 4682 0.0740208 0.0301458 0.00571188 1 0 1 1 0 0 +EDGE2 5022 4703 0.982829 0.0032147 0.0268439 1 0 1 1 0 0 +EDGE2 5022 4983 1.00433 -0.0423332 -0.0266019 1 0 1 1 0 0 +EDGE2 5022 4683 0.904494 -0.0342507 -0.00170292 1 0 1 1 0 0 +EDGE2 5023 4583 0.0182219 -0.0549334 -0.0334811 1 0 1 1 0 0 +EDGE2 5023 4582 -1.02217 0.0445118 0.0171198 1 0 1 1 0 0 +EDGE2 5023 4702 -1.04563 -0.0234925 0.00559461 1 0 1 1 0 0 +EDGE2 5023 4982 -1.05663 -0.0425114 0.0308014 1 0 1 1 0 0 +EDGE2 5023 5022 -0.903835 -0.0517525 0.00521181 1 0 1 1 0 0 +EDGE2 5023 4682 -1.00453 0.0174141 0.00644743 1 0 1 1 0 0 +EDGE2 5023 4703 -0.0334766 -0.0394295 0.0046432 1 0 1 1 0 0 +EDGE2 5023 4983 0.0340334 0.0883471 0.031088 1 0 1 1 0 0 +EDGE2 5023 4683 0.0268879 -0.0342384 -0.00198388 1 0 1 1 0 0 +EDGE2 5023 4684 1.07392 0.0317801 0.0106778 1 0 1 1 0 0 +EDGE2 5023 4704 0.978918 -0.0442322 0.0295945 1 0 1 1 0 0 +EDGE2 5023 4984 0.968599 0.0586081 -0.0400856 1 0 1 1 0 0 +EDGE2 5023 4584 0.956798 -0.0465914 0.00276556 1 0 1 1 0 0 +EDGE2 5024 4583 -1.04473 -0.00271832 -0.040784 1 0 1 1 0 0 +EDGE2 5024 4703 -0.994653 0.0680014 -0.0114394 1 0 1 1 0 0 +EDGE2 5024 4983 -1.07056 -0.0589781 0.0119748 1 0 1 1 0 0 +EDGE2 5024 5023 -0.952387 0.0343527 -0.0122446 1 0 1 1 0 0 +EDGE2 5024 4683 -1.01606 0.0140569 0.0235451 1 0 1 1 0 0 +EDGE2 5024 4705 0.975516 -0.0470149 0.0422912 1 0 1 1 0 0 +EDGE2 5024 4684 -0.0438712 -0.023182 -0.0226962 1 0 1 1 0 0 +EDGE2 5024 4704 -0.00607266 0.041375 0.0137435 1 0 1 1 0 0 +EDGE2 5024 4984 -0.00229854 -0.0582 0.0357324 1 0 1 1 0 0 +EDGE2 5024 4584 -0.0499603 -0.0148026 -0.0109243 1 0 1 1 0 0 +EDGE2 5024 5005 0.949219 0.00741739 -3.16886 1 0 1 1 0 0 +EDGE2 5024 4985 0.996319 -0.0296041 -0.0420117 1 0 1 1 0 0 +EDGE2 5024 3605 0.947727 0.00859675 -3.14725 1 0 1 1 0 0 +EDGE2 5024 4645 1.03775 -0.00956318 -3.12037 1 0 1 1 0 0 +EDGE2 5024 4665 0.936346 0.057823 -3.1094 1 0 1 1 0 0 +EDGE2 5024 4685 1.0263 0.0252946 -0.0457997 1 0 1 1 0 0 +EDGE2 5024 4585 0.987859 0.0280095 0.00140606 1 0 1 1 0 0 +EDGE2 5025 5024 -1.07987 -0.134453 -0.0148449 1 0 1 1 0 0 +EDGE2 5025 4986 -0.0594592 -1.02812 -1.57734 1 0 1 1 0 0 +EDGE2 5025 4646 -0.0134253 -1.08262 -1.55781 1 0 1 1 0 0 +EDGE2 5025 4706 -0.0519919 -0.93849 -1.60154 1 0 1 1 0 0 +EDGE2 5025 4586 -0.0181928 -1.03256 -1.5573 1 0 1 1 0 0 +EDGE2 5025 4644 1.03067 0.0363566 -3.1054 1 0 1 1 0 0 +EDGE2 5025 4705 0.0273045 -0.0196696 -0.0197525 1 0 1 1 0 0 +EDGE2 5025 4684 -0.935014 0.0153502 0.0120068 1 0 1 1 0 0 +EDGE2 5025 4704 -1.06502 -0.0419374 0.0232907 1 0 1 1 0 0 +EDGE2 5025 4984 -0.990568 0.0918279 0.0188783 1 0 1 1 0 0 +EDGE2 5025 4584 -1.0684 0.0237718 0.0430057 1 0 1 1 0 0 +EDGE2 5025 5005 -0.0422422 -0.00259233 -3.14113 1 0 1 1 0 0 +EDGE2 5025 4985 -0.121299 -0.0205431 0.0127232 1 0 1 1 0 0 +EDGE2 5025 3605 -0.0897427 0.0456206 -3.14445 1 0 1 1 0 0 +EDGE2 5025 4645 0.033922 -0.031719 -3.13074 1 0 1 1 0 0 +EDGE2 5025 4665 0.000433646 -0.00718647 -3.11975 1 0 1 1 0 0 +EDGE2 5025 4685 0.0573112 -0.0340561 0.0297315 1 0 1 1 0 0 +EDGE2 5025 4585 -0.0463417 0.044091 -0.0182402 1 0 1 1 0 0 +EDGE2 5025 5004 1.03559 -0.0677591 -3.1344 1 0 1 1 0 0 +EDGE2 5025 4664 0.906241 -0.010492 -3.15948 1 0 1 1 0 0 +EDGE2 5025 3606 0.0185251 0.980406 1.56454 1 0 1 1 0 0 +EDGE2 5025 4686 0.0665997 0.897408 1.54129 1 0 1 1 0 0 +EDGE2 5025 5006 0.0014147 1.05484 1.54844 1 0 1 1 0 0 +EDGE2 5025 4666 0.0570637 0.970237 1.53852 1 0 1 1 0 0 +EDGE2 5025 3604 0.971726 0.0764986 -3.13392 1 0 1 1 0 0 +EDGE2 5026 4707 1.06132 -0.0286245 0.0370596 1 0 1 1 0 0 +EDGE2 5026 4987 0.929114 0.0538748 0.0190609 1 0 1 1 0 0 +EDGE2 5026 4986 -0.0836232 -0.0472302 -0.0099875 1 0 1 1 0 0 +EDGE2 5026 4587 0.958226 0.00562681 -0.020782 1 0 1 1 0 0 +EDGE2 5026 4647 1.0196 0.0180231 0.0310293 1 0 1 1 0 0 +EDGE2 5026 4646 0.00105591 0.0244483 -0.0294247 1 0 1 1 0 0 +EDGE2 5026 4706 0.0367259 -0.0709114 -0.0326125 1 0 1 1 0 0 +EDGE2 5026 4586 0.0250412 -0.0194639 -0.0142116 1 0 1 1 0 0 +EDGE2 5026 4705 -1.10304 0.00799474 1.5515 1 0 1 1 0 0 +EDGE2 5026 5005 -1.07415 0.0185577 -1.56504 1 0 1 1 0 0 +EDGE2 5026 5025 -1.01737 0.0319106 1.53721 1 0 1 1 0 0 +EDGE2 5026 4985 -0.934759 -0.0259344 1.58346 1 0 1 1 0 0 +EDGE2 5026 3605 -0.935942 -0.0936441 -1.56234 1 0 1 1 0 0 +EDGE2 5026 4645 -0.990621 0.0354097 -1.59916 1 0 1 1 0 0 +EDGE2 5026 4665 -1.0003 -0.0600227 -1.59014 1 0 1 1 0 0 +EDGE2 5026 4685 -1.0212 -0.00936726 1.58171 1 0 1 1 0 0 +EDGE2 5026 4585 -0.957417 -0.0530844 1.57086 1 0 1 1 0 0 +EDGE2 5027 4707 0.126749 -0.0333949 -0.0212203 1 0 1 1 0 0 +EDGE2 5027 4708 0.992874 -0.0857001 0.036597 1 0 1 1 0 0 +EDGE2 5027 4988 0.9591 0.0165344 0.01782 1 0 1 1 0 0 +EDGE2 5027 4648 1.05823 0.0146314 0.0400771 1 0 1 1 0 0 +EDGE2 5027 4588 1.04319 -0.0494004 0.0366822 1 0 1 1 0 0 +EDGE2 5027 4987 0.0618851 -0.00811951 -0.0122866 1 0 1 1 0 0 +EDGE2 5027 4986 -0.956757 -0.172533 -0.00158838 1 0 1 1 0 0 +EDGE2 5027 4587 -0.0391728 0.0555396 -0.0226276 1 0 1 1 0 0 +EDGE2 5027 4647 0.0206295 0.0222582 0.0305136 1 0 1 1 0 0 +EDGE2 5027 5026 -1.00631 -0.0282245 0.0221767 1 0 1 1 0 0 +EDGE2 5027 4646 -1.0321 0.0730589 -0.0059829 1 0 1 1 0 0 +EDGE2 5027 4706 -1.06519 -0.00454142 0.0213985 1 0 1 1 0 0 +EDGE2 5027 4586 -0.988839 -0.0454069 -0.02312 1 0 1 1 0 0 +EDGE2 5028 4707 -1.03618 -0.138627 -0.00546379 1 0 1 1 0 0 +EDGE2 5028 4708 -0.000547632 0.0781116 0.0163455 1 0 1 1 0 0 +EDGE2 5028 4649 0.951624 0.0343018 0.0362724 1 0 1 1 0 0 +EDGE2 5028 4989 1.05775 -0.0598407 0.0365102 1 0 1 1 0 0 +EDGE2 5028 4709 0.987264 0.0928733 -0.011748 1 0 1 1 0 0 +EDGE2 5028 4589 0.9389 -0.0247168 -0.0150564 1 0 1 1 0 0 +EDGE2 5028 4988 0.0173107 -0.0346444 0.024067 1 0 1 1 0 0 +EDGE2 5028 4648 0.0195004 -0.00139152 0.00141543 1 0 1 1 0 0 +EDGE2 5028 5027 -0.987463 -0.119858 -0.0452125 1 0 1 1 0 0 +EDGE2 5028 4588 -0.016667 0.0190724 -0.0241243 1 0 1 1 0 0 +EDGE2 5028 4987 -1.04346 0.0437383 0.00541575 1 0 1 1 0 0 +EDGE2 5028 4587 -1.09404 0.0166872 0.0163556 1 0 1 1 0 0 +EDGE2 5028 4647 -0.96837 0.0790074 0.00722673 1 0 1 1 0 0 +EDGE2 5029 4710 0.963304 -0.0702726 -0.00827532 1 0 1 1 0 0 +EDGE2 5029 4990 1.05202 -0.0408348 -0.00930554 1 0 1 1 0 0 +EDGE2 5029 4630 1.00541 -0.0528389 -3.1121 1 0 1 1 0 0 +EDGE2 5029 4650 0.990349 0.0515033 0.0164231 1 0 1 1 0 0 +EDGE2 5029 4590 0.973944 -0.0268286 0.00105798 1 0 1 1 0 0 +EDGE2 5029 4708 -1.0483 -0.00763023 -0.0302798 1 0 1 1 0 0 +EDGE2 5029 4649 0.0246351 0.00952662 -0.0331144 1 0 1 1 0 0 +EDGE2 5029 4989 0.0524928 -0.107482 0.0251885 1 0 1 1 0 0 +EDGE2 5029 4709 -0.0048524 -0.0155593 0.0223423 1 0 1 1 0 0 +EDGE2 5029 5028 -1.04351 -0.0117407 0.0166097 1 0 1 1 0 0 +EDGE2 5029 4589 0.0372137 0.0207298 0.01642 1 0 1 1 0 0 +EDGE2 5029 4988 -0.931489 0.125915 0.0226164 1 0 1 1 0 0 +EDGE2 5029 4648 -1.02688 0.0348159 0.0226541 1 0 1 1 0 0 +EDGE2 5029 4588 -0.983388 0.0360729 0.0157437 1 0 1 1 0 0 +EDGE2 5030 4710 0.0175227 0.130351 0.00350533 1 0 1 1 0 0 +EDGE2 5030 4629 1.01986 0.0897939 -3.10681 1 0 1 1 0 0 +EDGE2 5030 4711 -0.0583961 -1.01789 -1.55467 1 0 1 1 0 0 +EDGE2 5030 4990 -0.0551178 0.0355147 0.0134288 1 0 1 1 0 0 +EDGE2 5030 4630 0.00350209 -0.0202036 -3.13378 1 0 1 1 0 0 +EDGE2 5030 4650 -0.00913627 -0.0334997 -0.0153033 1 0 1 1 0 0 +EDGE2 5030 4590 0.021309 -0.0120204 0.0140951 1 0 1 1 0 0 +EDGE2 5030 4591 -0.0346655 1.01562 1.57656 1 0 1 1 0 0 +EDGE2 5030 4651 0.0104318 0.996778 1.58782 1 0 1 1 0 0 +EDGE2 5030 4991 0.00629501 1.07291 1.56466 1 0 1 1 0 0 +EDGE2 5030 4631 -0.000738067 0.985859 1.59321 1 0 1 1 0 0 +EDGE2 5030 4649 -1.02082 -0.0146427 0.0235738 1 0 1 1 0 0 +EDGE2 5030 4989 -0.971017 0.0123913 -0.0201894 1 0 1 1 0 0 +EDGE2 5030 5029 -0.920257 0.0179367 0.0154938 1 0 1 1 0 0 +EDGE2 5030 4709 -1.07028 -0.131512 -0.0230097 1 0 1 1 0 0 +EDGE2 5030 4589 -1.03936 -0.0428498 0.000536541 1 0 1 1 0 0 +EDGE2 5031 4710 -1.01455 -0.0589789 -1.55269 1 0 1 1 0 0 +EDGE2 5031 5030 -0.96988 0.0396391 -1.59648 1 0 1 1 0 0 +EDGE2 5031 4990 -0.985819 0.0248178 -1.59001 1 0 1 1 0 0 +EDGE2 5031 4630 -0.96697 0.0166895 1.55528 1 0 1 1 0 0 +EDGE2 5031 4650 -1.00904 0.101074 -1.57482 1 0 1 1 0 0 +EDGE2 5031 4590 -0.981698 -0.0482896 -1.578 1 0 1 1 0 0 +EDGE2 5031 4632 1.07363 -0.00675927 0.00665634 1 0 1 1 0 0 +EDGE2 5031 4591 -0.0151122 -0.0130845 0.0166589 1 0 1 1 0 0 +EDGE2 5031 4651 0.044398 -0.0614678 -0.0156994 1 0 1 1 0 0 +EDGE2 5031 4991 0.0370828 0.086027 -0.0219931 1 0 1 1 0 0 +EDGE2 5031 4631 0.0269424 0.0890016 -0.00615818 1 0 1 1 0 0 +EDGE2 5031 4992 0.992448 0.0048125 -0.0214794 1 0 1 1 0 0 +EDGE2 5031 4652 0.981904 0.0590417 0.0111338 1 0 1 1 0 0 +EDGE2 5031 4592 1.02293 0.00755269 0.0132465 1 0 1 1 0 0 +EDGE2 5032 4632 -0.0527513 0.114611 0.0159059 1 0 1 1 0 0 +EDGE2 5032 4591 -1.11742 -0.00708688 -0.0180698 1 0 1 1 0 0 +EDGE2 5032 4651 -0.998192 -0.0613822 0.00288568 1 0 1 1 0 0 +EDGE2 5032 4991 -1.08812 -0.071325 0.0121159 1 0 1 1 0 0 +EDGE2 5032 5031 -1.04756 -0.122363 -0.010314 1 0 1 1 0 0 +EDGE2 5032 4631 -0.923534 0.0023212 0.0408687 1 0 1 1 0 0 +EDGE2 5032 4992 -0.10599 0.120927 0.00786858 1 0 1 1 0 0 +EDGE2 5032 4652 -0.0993324 -0.146769 -0.00260302 1 0 1 1 0 0 +EDGE2 5032 4653 0.908477 -0.0207717 -0.00674078 1 0 1 1 0 0 +EDGE2 5032 4592 -0.0197069 -0.0784441 -0.0054972 1 0 1 1 0 0 +EDGE2 5032 4993 1.03988 -0.014596 0.0163626 1 0 1 1 0 0 +EDGE2 5032 4593 1.02397 0.0140821 0.0128691 1 0 1 1 0 0 +EDGE2 5032 4633 1.00253 0.030169 0.0553498 1 0 1 1 0 0 +EDGE2 5033 4632 -0.955153 -0.0975599 0.0170233 1 0 1 1 0 0 +EDGE2 5033 4992 -1.02328 -0.0255784 -0.0178037 1 0 1 1 0 0 +EDGE2 5033 5032 -0.919986 0.0296859 0.00945031 1 0 1 1 0 0 +EDGE2 5033 4652 -0.95808 0.0968413 0.0101965 1 0 1 1 0 0 +EDGE2 5033 4653 0.0160203 0.0706046 0.0078146 1 0 1 1 0 0 +EDGE2 5033 4592 -1.03759 0.072121 -0.00306813 1 0 1 1 0 0 +EDGE2 5033 4993 0.0222511 0.0250608 0.00195846 1 0 1 1 0 0 +EDGE2 5033 4593 0.0218792 0.0489486 0.00814482 1 0 1 1 0 0 +EDGE2 5033 4633 0.017279 -0.0184385 0.0298591 1 0 1 1 0 0 +EDGE2 5033 4634 0.952219 0.0215165 -0.0248919 1 0 1 1 0 0 +EDGE2 5033 4654 0.935521 0.0129768 0.0225107 1 0 1 1 0 0 +EDGE2 5033 4994 1.01151 0.0719069 0.0198487 1 0 1 1 0 0 +EDGE2 5033 4594 1.03898 0.0238055 -0.0338684 1 0 1 1 0 0 +EDGE2 5034 4653 -1.06632 0.0420278 0.0108644 1 0 1 1 0 0 +EDGE2 5034 5033 -1.0545 0.00341014 0.0123244 1 0 1 1 0 0 +EDGE2 5034 4993 -0.975988 -0.0423344 -0.00674519 1 0 1 1 0 0 +EDGE2 5034 4593 -1.01209 0.0891473 -0.0163158 1 0 1 1 0 0 +EDGE2 5034 4633 -1.03724 -0.0116869 -0.0153503 1 0 1 1 0 0 +EDGE2 5034 4634 -0.0172229 -0.00863416 0.0233865 1 0 1 1 0 0 +EDGE2 5034 4654 0.00941161 -0.0158641 0.0144398 1 0 1 1 0 0 +EDGE2 5034 4994 -0.0412856 -0.044761 -0.0274603 1 0 1 1 0 0 +EDGE2 5034 4594 0.0496961 -0.0288767 -0.0371004 1 0 1 1 0 0 +EDGE2 5034 2915 0.984242 -0.00526276 -3.18085 1 0 1 1 0 0 +EDGE2 5034 4635 0.984798 -0.0215071 0.0175664 1 0 1 1 0 0 +EDGE2 5034 4995 0.904809 -0.0366026 -0.0139332 1 0 1 1 0 0 +EDGE2 5034 4655 1.00714 -0.014692 -0.0517553 1 0 1 1 0 0 +EDGE2 5034 4595 0.997578 0.0207986 -0.0293903 1 0 1 1 0 0 +EDGE2 5034 3595 1.02259 -0.110417 -3.16761 1 0 1 1 0 0 +EDGE2 5034 3735 0.984071 0.0731787 -3.15931 1 0 1 1 0 0 +EDGE2 5034 3755 1.02535 -0.0296067 -3.15559 1 0 1 1 0 0 +EDGE2 5034 3575 1.01391 0.0363573 -3.15447 1 0 1 1 0 0 +EDGE2 5035 5034 -0.966187 -0.0473154 -0.0323658 1 0 1 1 0 0 +EDGE2 5035 4634 -1.01693 -0.0808175 0.0137002 1 0 1 1 0 0 +EDGE2 5035 4654 -1.02644 -0.127636 -0.00238796 1 0 1 1 0 0 +EDGE2 5035 4994 -1.0059 -0.0741366 0.0400013 1 0 1 1 0 0 +EDGE2 5035 4594 -1.02159 -0.0578141 -0.0182984 1 0 1 1 0 0 +EDGE2 5035 2915 0.0268386 -0.0169837 -3.17851 1 0 1 1 0 0 +EDGE2 5035 4635 -0.0609352 -0.136516 -0.022973 1 0 1 1 0 0 +EDGE2 5035 2916 -0.0416787 -0.881412 -1.5827 1 0 1 1 0 0 +EDGE2 5035 3736 0.0329049 -0.991881 -1.58406 1 0 1 1 0 0 +EDGE2 5035 4596 0.0367747 -0.987968 -1.57524 1 0 1 1 0 0 +EDGE2 5035 3576 -0.0750511 -1.03317 -1.59384 1 0 1 1 0 0 +EDGE2 5035 4995 0.0709031 -0.0504286 0.00313921 1 0 1 1 0 0 +EDGE2 5035 4655 0.0412287 -0.0492454 0.000600552 1 0 1 1 0 0 +EDGE2 5035 4595 -0.0366377 -0.110825 0.0240166 1 0 1 1 0 0 +EDGE2 5035 3595 0.0101207 -0.0443795 -3.12599 1 0 1 1 0 0 +EDGE2 5035 3735 -0.0280392 -0.0168199 -3.13962 1 0 1 1 0 0 +EDGE2 5035 3755 -0.0164059 -0.0637807 -3.10045 1 0 1 1 0 0 +EDGE2 5035 3575 0.0159217 0.0658876 -3.14061 1 0 1 1 0 0 +EDGE2 5035 2914 0.931114 0.0454031 -3.15373 1 0 1 1 0 0 +EDGE2 5035 3594 0.986399 -0.052948 -3.17592 1 0 1 1 0 0 +EDGE2 5035 3734 1.00513 -0.0768337 -3.17655 1 0 1 1 0 0 +EDGE2 5035 3754 0.961118 0.0230493 -3.14773 1 0 1 1 0 0 +EDGE2 5035 3574 1.00827 0.00873383 -3.14592 1 0 1 1 0 0 +EDGE2 5035 4636 0.0508992 1.06877 1.58439 1 0 1 1 0 0 +EDGE2 5035 4996 0.00644394 1.00304 1.56565 1 0 1 1 0 0 +EDGE2 5035 4656 -0.00565895 1.04817 1.56973 1 0 1 1 0 0 +EDGE2 5035 3596 -0.00341286 1.03062 1.55674 1 0 1 1 0 0 +EDGE2 5035 3756 0.0317607 0.997927 1.58061 1 0 1 1 0 0 +EDGE2 5036 2915 -0.961347 -0.0214895 1.60312 1 0 1 1 0 0 +EDGE2 5036 4635 -0.985759 0.0592077 -1.56028 1 0 1 1 0 0 +EDGE2 5036 4995 -0.96618 -0.0015643 -1.57142 1 0 1 1 0 0 +EDGE2 5036 5035 -1.00698 -0.0258679 -1.56398 1 0 1 1 0 0 +EDGE2 5036 4655 -0.993737 -0.0407157 -1.58239 1 0 1 1 0 0 +EDGE2 5036 4595 -1.02577 -0.0105677 -1.56592 1 0 1 1 0 0 +EDGE2 5036 3595 -1.06514 0.00121495 1.54216 1 0 1 1 0 0 +EDGE2 5036 3735 -0.953254 0.0800439 1.57673 1 0 1 1 0 0 +EDGE2 5036 3755 -0.971061 0.00228637 1.60402 1 0 1 1 0 0 +EDGE2 5036 3575 -1.01855 -0.000172448 1.56101 1 0 1 1 0 0 +EDGE2 5036 3597 1.06189 0.0816262 -0.0184905 1 0 1 1 0 0 +EDGE2 5036 4997 1.09046 0.0241183 0.0100763 1 0 1 1 0 0 +EDGE2 5036 4636 0.113252 0.0339535 0.019704 1 0 1 1 0 0 +EDGE2 5036 4996 0.0175238 0.0448915 -0.0215329 1 0 1 1 0 0 +EDGE2 5036 4656 0.0396335 -0.0188562 0.0120135 1 0 1 1 0 0 +EDGE2 5036 3596 0.0289347 -0.0144058 -0.00200503 1 0 1 1 0 0 +EDGE2 5036 3756 0.0905479 -0.0113134 -0.0155915 1 0 1 1 0 0 +EDGE2 5036 4637 0.985618 -0.0901154 -0.0137369 1 0 1 1 0 0 +EDGE2 5036 4657 0.984338 -0.0167907 -0.00882042 1 0 1 1 0 0 +EDGE2 5036 3757 0.968213 0.0591717 -0.0378262 1 0 1 1 0 0 +EDGE2 5037 3597 -0.00594744 -0.0425448 -0.00315677 1 0 1 1 0 0 +EDGE2 5037 4997 0.0349978 -0.0527305 -0.00718011 1 0 1 1 0 0 +EDGE2 5037 4636 -0.99847 0.0423291 -0.0169539 1 0 1 1 0 0 +EDGE2 5037 4996 -0.961884 -0.0562013 0.0257961 1 0 1 1 0 0 +EDGE2 5037 5036 -1.04026 -0.0916554 -0.0364912 1 0 1 1 0 0 +EDGE2 5037 4656 -1.01591 0.00223502 -0.00663157 1 0 1 1 0 0 +EDGE2 5037 3596 -1.04151 0.0490868 -0.00300117 1 0 1 1 0 0 +EDGE2 5037 3756 -1.08467 -0.0403227 -0.00095216 1 0 1 1 0 0 +EDGE2 5037 4637 0.0451498 -0.0297096 -0.000825006 1 0 1 1 0 0 +EDGE2 5037 4657 0.00868618 0.0150602 -0.0135565 1 0 1 1 0 0 +EDGE2 5037 3757 0.000242621 -0.0688768 0.0183969 1 0 1 1 0 0 +EDGE2 5037 4638 0.946936 0.0898739 0.0174233 1 0 1 1 0 0 +EDGE2 5037 4998 0.902729 0.0669105 -0.0164992 1 0 1 1 0 0 +EDGE2 5037 4658 1.01853 -0.0865596 0.0391665 1 0 1 1 0 0 +EDGE2 5037 3598 0.957468 0.0947058 -0.0166381 1 0 1 1 0 0 +EDGE2 5037 3758 0.940781 -0.0429639 -0.0226641 1 0 1 1 0 0 +EDGE2 5038 3597 -0.994274 -0.000330134 -0.0234745 1 0 1 1 0 0 +EDGE2 5038 4997 -1.00249 0.021936 0.0226852 1 0 1 1 0 0 +EDGE2 5038 5037 -1.01109 0.0617373 -0.0282422 1 0 1 1 0 0 +EDGE2 5038 4637 -1.02997 0.0269414 0.00415753 1 0 1 1 0 0 +EDGE2 5038 4657 -0.941584 0.0545719 0.00637859 1 0 1 1 0 0 +EDGE2 5038 3757 -1.03861 -0.048799 -0.00661605 1 0 1 1 0 0 +EDGE2 5038 4999 0.977976 0.0173551 -0.0122725 1 0 1 1 0 0 +EDGE2 5038 4638 0.0133983 0.0817425 0.0107212 1 0 1 1 0 0 +EDGE2 5038 4998 -0.00440798 -0.0593506 0.0298707 1 0 1 1 0 0 +EDGE2 5038 4658 0.00342862 0.0214243 -0.029538 1 0 1 1 0 0 +EDGE2 5038 3598 0.0104962 -0.075427 0.00605781 1 0 1 1 0 0 +EDGE2 5038 3758 -0.0129716 0.04552 0.0214745 1 0 1 1 0 0 +EDGE2 5038 4639 0.925206 -0.0134682 -0.0161666 1 0 1 1 0 0 +EDGE2 5038 4659 0.975419 0.0468074 -0.0265725 1 0 1 1 0 0 +EDGE2 5038 3599 0.944181 0.0751799 -0.00529949 1 0 1 1 0 0 +EDGE2 5038 3759 0.992252 -0.013942 0.00354052 1 0 1 1 0 0 +EDGE2 5039 4999 0.00731507 -0.0364759 0.0142918 1 0 1 1 0 0 +EDGE2 5039 4638 -1.07041 -0.0417061 0.00792656 1 0 1 1 0 0 +EDGE2 5039 4998 -1.03875 0.000322388 -0.0155692 1 0 1 1 0 0 +EDGE2 5039 5038 -1.03503 -0.041748 0.00482075 1 0 1 1 0 0 +EDGE2 5039 4658 -1.02251 0.0385676 0.00238763 1 0 1 1 0 0 +EDGE2 5039 3598 -0.94546 0.015419 -0.0017396 1 0 1 1 0 0 +EDGE2 5039 3758 -1.00002 0.0314938 -0.020267 1 0 1 1 0 0 +EDGE2 5039 4639 0.00785242 -0.0588705 0.0119352 1 0 1 1 0 0 +EDGE2 5039 4659 -0.0202768 -0.0562973 0.0266317 1 0 1 1 0 0 +EDGE2 5039 3599 -0.0387956 -0.0639658 -0.00870723 1 0 1 1 0 0 +EDGE2 5039 3759 -0.0631057 -0.0447818 0.0307542 1 0 1 1 0 0 +EDGE2 5039 3680 1.03803 0.0277166 -3.15397 1 0 1 1 0 0 +EDGE2 5039 5000 1.02302 0.0344102 -0.0242247 1 0 1 1 0 0 +EDGE2 5039 3820 1.00963 0.00563277 -3.14638 1 0 1 1 0 0 +EDGE2 5039 4640 0.973718 0.00943684 -0.0190289 1 0 1 1 0 0 +EDGE2 5039 4660 1.03115 0.0670592 0.0374929 1 0 1 1 0 0 +EDGE2 5039 3760 0.948204 0.007807 -0.00968677 1 0 1 1 0 0 +EDGE2 5039 3600 1.05489 0.0984233 -0.0211127 1 0 1 1 0 0 +EDGE2 5039 3640 0.963376 0.0497337 -3.11592 1 0 1 1 0 0 +EDGE2 5039 3660 1.01568 -0.00999631 -3.12181 1 0 1 1 0 0 +EDGE2 5040 4999 -1.04989 -0.0502683 -0.0200844 1 0 1 1 0 0 +EDGE2 5040 5039 -0.989475 0.0773278 0.00591319 1 0 1 1 0 0 +EDGE2 5040 4639 -0.986333 0.0292054 -0.0188508 1 0 1 1 0 0 +EDGE2 5040 4659 -0.940746 0.00914481 0.00476495 1 0 1 1 0 0 +EDGE2 5040 3599 -0.984543 0.0614654 -0.00955922 1 0 1 1 0 0 +EDGE2 5040 3759 -0.981808 -0.0135962 -0.0139239 1 0 1 1 0 0 +EDGE2 5040 3680 0.11695 0.0418259 -3.11881 1 0 1 1 0 0 +EDGE2 5040 4661 -0.00720721 1.11916 1.57875 1 0 1 1 0 0 +EDGE2 5040 5001 -0.0462268 0.979115 1.53615 1 0 1 1 0 0 +EDGE2 5040 5000 -0.0517104 -0.0335069 -0.0166593 1 0 1 1 0 0 +EDGE2 5040 3601 0.0052534 1.00672 1.57885 1 0 1 1 0 0 +EDGE2 5040 4641 -0.0949968 0.93287 1.58322 1 0 1 1 0 0 +EDGE2 5040 3820 0.0540461 -0.0428697 -3.15748 1 0 1 1 0 0 +EDGE2 5040 4640 0.0338742 0.0616923 -0.00995573 1 0 1 1 0 0 +EDGE2 5040 4660 -0.0078461 0.0180698 -0.0270025 1 0 1 1 0 0 +EDGE2 5040 3760 -0.0692752 0.075124 0.0175375 1 0 1 1 0 0 +EDGE2 5040 3761 0.0497336 -0.968537 -1.60801 1 0 1 1 0 0 +EDGE2 5040 3600 -0.0675942 -0.0360516 -0.00929776 1 0 1 1 0 0 +EDGE2 5040 3640 0.0194305 -0.0453574 -3.11909 1 0 1 1 0 0 +EDGE2 5040 3660 0.00349347 -0.0468189 -3.14678 1 0 1 1 0 0 +EDGE2 5040 3821 0.0626565 -1.05993 -1.60174 1 0 1 1 0 0 +EDGE2 5040 3641 0.028695 -1.03351 -1.58578 1 0 1 1 0 0 +EDGE2 5040 3661 -0.0866296 -1.013 -1.56223 1 0 1 1 0 0 +EDGE2 5040 3681 0.0129605 -0.996653 -1.57193 1 0 1 1 0 0 +EDGE2 5040 3659 0.956971 -0.00795601 -3.12455 1 0 1 1 0 0 +EDGE2 5040 3679 0.881338 0.0521983 -3.13437 1 0 1 1 0 0 +EDGE2 5040 3819 1.05556 0.0965861 -3.13347 1 0 1 1 0 0 +EDGE2 5040 3639 1.02481 0.00391314 -3.21947 1 0 1 1 0 0 +EDGE2 5041 3680 -0.989764 -0.108328 1.5831 1 0 1 1 0 0 +EDGE2 5041 4661 0.0692258 -0.124532 0.00767925 1 0 1 1 0 0 +EDGE2 5041 4642 0.907637 0.0270029 0.00699207 1 0 1 1 0 0 +EDGE2 5041 5002 0.956772 -0.0442713 0.0202029 1 0 1 1 0 0 +EDGE2 5041 4662 0.998054 -0.019304 -0.00170715 1 0 1 1 0 0 +EDGE2 5041 3602 1.15167 0.102148 -0.0189471 1 0 1 1 0 0 +EDGE2 5041 5001 -0.0634577 0.0299945 -0.0190435 1 0 1 1 0 0 +EDGE2 5041 5000 -1.02636 0.0655095 -1.60007 1 0 1 1 0 0 +EDGE2 5041 3601 0.0512613 0.0130829 0.0269673 1 0 1 1 0 0 +EDGE2 5041 4641 -0.0375964 -0.0294475 0.0160653 1 0 1 1 0 0 +EDGE2 5041 5040 -1.02398 0.0328546 -1.52758 1 0 1 1 0 0 +EDGE2 5041 3820 -1.07005 -0.0153797 1.62804 1 0 1 1 0 0 +EDGE2 5041 4640 -1.03173 -0.0586205 -1.59578 1 0 1 1 0 0 +EDGE2 5041 4660 -1.01617 0.000817618 -1.5623 1 0 1 1 0 0 +EDGE2 5041 3760 -1.01617 0.00433596 -1.58412 1 0 1 1 0 0 +EDGE2 5041 3600 -0.963276 0.0698089 -1.56462 1 0 1 1 0 0 +EDGE2 5041 3640 -1.00419 -0.0989822 1.56011 1 0 1 1 0 0 +EDGE2 5041 3660 -0.968282 0.053521 1.59072 1 0 1 1 0 0 +EDGE2 5042 4663 1.01144 0.0626552 -0.00397763 1 0 1 1 0 0 +EDGE2 5042 5003 0.947731 -0.00374974 -0.0275184 1 0 1 1 0 0 +EDGE2 5042 3603 1.05502 0.0391454 -0.037121 1 0 1 1 0 0 +EDGE2 5042 4643 0.984312 0.0316942 0.0340623 1 0 1 1 0 0 +EDGE2 5042 4661 -1.07917 0.0426411 -0.00258841 1 0 1 1 0 0 +EDGE2 5042 4642 0.0124572 0.0155143 -0.0525939 1 0 1 1 0 0 +EDGE2 5042 5002 0.0632263 -0.0327208 -0.0393037 1 0 1 1 0 0 +EDGE2 5042 4662 0.0359107 -0.151259 0.0063595 1 0 1 1 0 0 +EDGE2 5042 5041 -1.02297 0.0389921 0.0122073 1 0 1 1 0 0 +EDGE2 5042 3602 -0.0421545 -0.0414542 0.0141319 1 0 1 1 0 0 +EDGE2 5042 5001 -1.17172 -0.0205799 0.000194546 1 0 1 1 0 0 +EDGE2 5042 3601 -0.922675 -0.0726811 0.0135306 1 0 1 1 0 0 +EDGE2 5042 4641 -0.971055 0.0382807 -0.000492185 1 0 1 1 0 0 +EDGE2 5043 4644 1.01096 0.0612014 0.00642542 1 0 1 1 0 0 +EDGE2 5043 5004 1.07554 0.11899 0.0245749 1 0 1 1 0 0 +EDGE2 5043 4664 1.06496 -0.034956 -0.0352489 1 0 1 1 0 0 +EDGE2 5043 4663 -0.0707701 0.0420882 -0.0232443 1 0 1 1 0 0 +EDGE2 5043 3604 1.01315 -0.0525479 0.0210334 1 0 1 1 0 0 +EDGE2 5043 5003 0.0980617 0.0127022 0.00461163 1 0 1 1 0 0 +EDGE2 5043 3603 -0.00127275 0.0377328 -0.0116912 1 0 1 1 0 0 +EDGE2 5043 4643 0.00689266 0.035351 0.0175369 1 0 1 1 0 0 +EDGE2 5043 4642 -0.985512 -0.148825 -0.0302969 1 0 1 1 0 0 +EDGE2 5043 5002 -0.992813 -0.0572672 -0.0131856 1 0 1 1 0 0 +EDGE2 5043 5042 -0.96154 0.00960408 0.0115024 1 0 1 1 0 0 +EDGE2 5043 4662 -0.964862 -0.00901462 0.00166034 1 0 1 1 0 0 +EDGE2 5043 3602 -0.909516 -0.070885 -0.0175541 1 0 1 1 0 0 +EDGE2 5044 4644 -0.0172753 -0.00528634 -0.00538123 1 0 1 1 0 0 +EDGE2 5044 4705 1.11468 0.0390118 -3.15265 1 0 1 1 0 0 +EDGE2 5044 5005 0.98721 0.0341809 0.0209196 1 0 1 1 0 0 +EDGE2 5044 5025 1.04699 0.00331851 -3.18354 1 0 1 1 0 0 +EDGE2 5044 4985 0.923353 0.0013007 -3.14579 1 0 1 1 0 0 +EDGE2 5044 3605 0.980749 -0.0507619 0.00389324 1 0 1 1 0 0 +EDGE2 5044 4645 0.993137 0.0358132 0.000823456 1 0 1 1 0 0 +EDGE2 5044 4665 0.955129 0.0123823 0.00500487 1 0 1 1 0 0 +EDGE2 5044 4685 0.95775 0.0867266 -3.15524 1 0 1 1 0 0 +EDGE2 5044 4585 1.02476 -0.031749 -3.12248 1 0 1 1 0 0 +EDGE2 5044 5004 0.0398209 -0.013917 -0.00314998 1 0 1 1 0 0 +EDGE2 5044 4664 -0.00216172 -0.0340505 -0.0333969 1 0 1 1 0 0 +EDGE2 5044 4663 -0.986155 -0.021533 -0.0348836 1 0 1 1 0 0 +EDGE2 5044 5043 -1.11697 0.0147619 -0.00236819 1 0 1 1 0 0 +EDGE2 5044 3604 -0.0759931 -0.000652854 -0.00631024 1 0 1 1 0 0 +EDGE2 5044 5003 -1.02419 0.0605792 -0.0420805 1 0 1 1 0 0 +EDGE2 5044 3603 -1.03252 0.0657685 -0.00254371 1 0 1 1 0 0 +EDGE2 5044 4643 -1.04843 0.00847905 0.00194886 1 0 1 1 0 0 +EDGE2 5045 5024 1.0055 0.0765973 -3.14138 1 0 1 1 0 0 +EDGE2 5045 4986 0.0132602 1.01444 1.55826 1 0 1 1 0 0 +EDGE2 5045 5026 0.0123694 0.98823 1.59189 1 0 1 1 0 0 +EDGE2 5045 4646 0.0425327 1.055 1.52253 1 0 1 1 0 0 +EDGE2 5045 4706 0.0177051 0.997124 1.54367 1 0 1 1 0 0 +EDGE2 5045 4586 -0.0199487 1.00527 1.58669 1 0 1 1 0 0 +EDGE2 5045 4644 -1.00018 -0.00622894 -0.0171144 1 0 1 1 0 0 +EDGE2 5045 4705 -0.0714168 -0.0233498 -3.13596 1 0 1 1 0 0 +EDGE2 5045 4684 1.07561 0.068867 -3.13857 1 0 1 1 0 0 +EDGE2 5045 4704 1.06315 0.0161542 -3.15818 1 0 1 1 0 0 +EDGE2 5045 4984 1.02683 0.0887102 -3.14381 1 0 1 1 0 0 +EDGE2 5045 4584 0.988566 0.00191895 -3.1243 1 0 1 1 0 0 +EDGE2 5045 5005 0.0140213 0.0785228 -0.00631356 1 0 1 1 0 0 +EDGE2 5045 5025 -0.0774779 -0.0323995 -3.17034 1 0 1 1 0 0 +EDGE2 5045 4985 0.0154403 0.0975019 -3.16149 1 0 1 1 0 0 +EDGE2 5045 3605 -0.0116444 -0.0177501 0.0142295 1 0 1 1 0 0 +EDGE2 5045 4645 -0.0266746 0.0680683 -6.78222e-05 1 0 1 1 0 0 +EDGE2 5045 4665 -0.00321455 -0.0426306 0.00533746 1 0 1 1 0 0 +EDGE2 5045 4685 0.00289761 -0.0966255 -3.16842 1 0 1 1 0 0 +EDGE2 5045 4585 0.0794438 0.00800277 -3.13541 1 0 1 1 0 0 +EDGE2 5045 5004 -1.06522 -0.0476811 0.0157646 1 0 1 1 0 0 +EDGE2 5045 5044 -0.961159 0.0949544 -0.0426687 1 0 1 1 0 0 +EDGE2 5045 4664 -0.993005 0.0313604 -0.0180657 1 0 1 1 0 0 +EDGE2 5045 3606 0.0398868 -1.03044 -1.53312 1 0 1 1 0 0 +EDGE2 5045 4686 -0.0074096 -1.0371 -1.57087 1 0 1 1 0 0 +EDGE2 5045 5006 0.00757825 -1.00967 -1.57685 1 0 1 1 0 0 +EDGE2 5045 4666 0.0248443 -0.993074 -1.55691 1 0 1 1 0 0 +EDGE2 5045 3604 -0.955495 -0.0445563 0.010926 1 0 1 1 0 0 +EDGE2 5046 4707 1.0201 0.0089893 -0.0203241 1 0 1 1 0 0 +EDGE2 5046 5027 0.95912 -0.000963205 -0.0340704 1 0 1 1 0 0 +EDGE2 5046 4987 0.890755 0.0625454 -0.0165486 1 0 1 1 0 0 +EDGE2 5046 4986 0.092634 -0.0240241 0.0154682 1 0 1 1 0 0 +EDGE2 5046 4587 0.956972 -0.0677491 0.0262787 1 0 1 1 0 0 +EDGE2 5046 4647 0.973177 0.0233677 -0.022797 1 0 1 1 0 0 +EDGE2 5046 5026 0.0203562 -0.0947668 -0.0132069 1 0 1 1 0 0 +EDGE2 5046 4646 0.0696344 0.015268 0.0113976 1 0 1 1 0 0 +EDGE2 5046 4706 -0.0204452 0.0211607 -0.00323715 1 0 1 1 0 0 +EDGE2 5046 4586 -0.0233578 -0.0861795 -0.0277544 1 0 1 1 0 0 +EDGE2 5046 4705 -1.0466 -0.0266065 1.6045 1 0 1 1 0 0 +EDGE2 5046 5005 -1.0236 0.00230424 -1.57097 1 0 1 1 0 0 +EDGE2 5046 5025 -0.97577 -0.0401979 1.57798 1 0 1 1 0 0 +EDGE2 5046 5045 -0.982301 -0.0625449 -1.56948 1 0 1 1 0 0 +EDGE2 5046 4985 -0.940753 0.0322454 1.557 1 0 1 1 0 0 +EDGE2 5046 3605 -1.04749 -0.0530858 -1.58402 1 0 1 1 0 0 +EDGE2 5046 4645 -1.0804 -0.0685887 -1.57527 1 0 1 1 0 0 +EDGE2 5046 4665 -1.05273 0.0426478 -1.57232 1 0 1 1 0 0 +EDGE2 5046 4685 -1.03318 0.0449556 1.60568 1 0 1 1 0 0 +EDGE2 5046 4585 -0.99111 0.053012 1.57158 1 0 1 1 0 0 +EDGE2 5047 4707 0.035242 0.0141148 0.0182281 1 0 1 1 0 0 +EDGE2 5047 4708 1.06499 -0.103649 0.00647444 1 0 1 1 0 0 +EDGE2 5047 5028 1.01865 -0.00792765 0.0155553 1 0 1 1 0 0 +EDGE2 5047 4988 1.12128 0.0243808 0.00737292 1 0 1 1 0 0 +EDGE2 5047 4648 0.969467 -0.0180775 -0.0221849 1 0 1 1 0 0 +EDGE2 5047 5027 -0.0305999 0.0206871 0.0094186 1 0 1 1 0 0 +EDGE2 5047 4588 0.98116 -0.00728043 0.0120294 1 0 1 1 0 0 +EDGE2 5047 4987 -0.045455 -0.0297311 -0.00214525 1 0 1 1 0 0 +EDGE2 5047 4986 -1.00539 0.0127596 -0.0166976 1 0 1 1 0 0 +EDGE2 5047 5046 -1.04773 0.0732778 -0.0183794 1 0 1 1 0 0 +EDGE2 5047 4587 0.0032409 0.0665799 -0.0306841 1 0 1 1 0 0 +EDGE2 5047 4647 -0.00253618 0.000784338 0.00975287 1 0 1 1 0 0 +EDGE2 5047 5026 -0.951287 -0.0677493 0.025435 1 0 1 1 0 0 +EDGE2 5047 4646 -1.04702 0.00244045 -0.0110539 1 0 1 1 0 0 +EDGE2 5047 4706 -0.973954 0.0722479 -0.00976514 1 0 1 1 0 0 +EDGE2 5047 4586 -1.02051 -0.0690647 -0.00888409 1 0 1 1 0 0 +EDGE2 5048 4707 -1.0258 0.00627672 0.0134438 1 0 1 1 0 0 +EDGE2 5048 4708 -0.0235526 -0.0240445 0.025708 1 0 1 1 0 0 +EDGE2 5048 4649 0.991796 0.018616 -0.00225481 1 0 1 1 0 0 +EDGE2 5048 4989 0.91309 -0.0676196 -0.0114777 1 0 1 1 0 0 +EDGE2 5048 5029 0.999334 -0.0121884 -0.00775048 1 0 1 1 0 0 +EDGE2 5048 4709 0.886428 -0.0467956 -0.0116729 1 0 1 1 0 0 +EDGE2 5048 5028 0.0536796 -0.0199807 -0.00979154 1 0 1 1 0 0 +EDGE2 5048 4589 0.966641 0.0174082 0.00176985 1 0 1 1 0 0 +EDGE2 5048 4988 0.0783708 0.0168838 0.0258702 1 0 1 1 0 0 +EDGE2 5048 4648 -0.0498627 0.0599339 -0.0114448 1 0 1 1 0 0 +EDGE2 5048 5027 -0.916519 0.0473622 -0.0165482 1 0 1 1 0 0 +EDGE2 5048 5047 -1.0412 -0.109238 0.00685898 1 0 1 1 0 0 +EDGE2 5048 4588 -0.0474974 0.0581858 -0.0116032 1 0 1 1 0 0 +EDGE2 5048 4987 -1.08516 0.0475397 -0.0111028 1 0 1 1 0 0 +EDGE2 5048 4587 -0.973439 -0.00717315 0.00394468 1 0 1 1 0 0 +EDGE2 5048 4647 -0.969445 -0.0352619 0.000409471 1 0 1 1 0 0 +EDGE2 5049 4710 0.917226 0.103237 0.00260875 1 0 1 1 0 0 +EDGE2 5049 5030 0.974327 -0.00858961 0.0173049 1 0 1 1 0 0 +EDGE2 5049 4990 0.97533 -0.004932 0.00859239 1 0 1 1 0 0 +EDGE2 5049 4630 0.955393 -0.0682447 -3.14427 1 0 1 1 0 0 +EDGE2 5049 4650 0.948069 -0.0670716 -0.0264492 1 0 1 1 0 0 +EDGE2 5049 4590 1.02226 0.0457484 -0.0109181 1 0 1 1 0 0 +EDGE2 5049 4708 -1.06733 -0.032883 -0.0211321 1 0 1 1 0 0 +EDGE2 5049 4649 -0.0354676 0.00718463 0.0478525 1 0 1 1 0 0 +EDGE2 5049 4989 0.0193216 -0.0133072 0.00294344 1 0 1 1 0 0 +EDGE2 5049 5029 0.0377458 0.00623718 -0.00409523 1 0 1 1 0 0 +EDGE2 5049 4709 -0.0599791 0.00973148 0.0106868 1 0 1 1 0 0 +EDGE2 5049 5028 -1.0139 0.0626469 0.011699 1 0 1 1 0 0 +EDGE2 5049 5048 -0.911347 0.00348692 -0.00754022 1 0 1 1 0 0 +EDGE2 5049 4589 0.0217537 0.0534923 -0.0237696 1 0 1 1 0 0 +EDGE2 5049 4988 -0.960416 -0.0223813 -0.00156329 1 0 1 1 0 0 +EDGE2 5049 4648 -0.943298 0.0419444 -0.0140945 1 0 1 1 0 0 +EDGE2 5049 4588 -0.966643 0.0608425 0.0216724 1 0 1 1 0 0 +EDGE2 5050 4710 0.0598834 -0.00248284 0.0121172 1 0 1 1 0 0 +EDGE2 5050 4629 1.04672 -0.0157465 -3.12333 1 0 1 1 0 0 +EDGE2 5050 5030 0.0616342 -0.0898295 -0.0043937 1 0 1 1 0 0 +EDGE2 5050 4711 -0.0217928 -1.0268 -1.57777 1 0 1 1 0 0 +EDGE2 5050 4990 0.00703801 -0.0164563 -0.0225425 1 0 1 1 0 0 +EDGE2 5050 4630 0.0419865 -0.101417 -3.14859 1 0 1 1 0 0 +EDGE2 5050 4650 0.0132265 0.0372399 -0.00407399 1 0 1 1 0 0 +EDGE2 5050 4590 -0.0367737 0.0818708 0.0104138 1 0 1 1 0 0 +EDGE2 5050 4591 -0.112369 0.970204 1.62649 1 0 1 1 0 0 +EDGE2 5050 4651 -0.0547418 1.12408 1.56312 1 0 1 1 0 0 +EDGE2 5050 4991 0.112058 0.958261 1.59404 1 0 1 1 0 0 +EDGE2 5050 5031 0.0448419 1.09716 1.5473 1 0 1 1 0 0 +EDGE2 5050 4631 -0.0279505 1.03402 1.6265 1 0 1 1 0 0 +EDGE2 5050 4649 -0.957667 -0.0664208 -0.0246921 1 0 1 1 0 0 +EDGE2 5050 4989 -1.05602 0.0499355 0.000508693 1 0 1 1 0 0 +EDGE2 5050 5029 -0.92699 0.0595255 0.0204363 1 0 1 1 0 0 +EDGE2 5050 5049 -0.933245 -0.0487457 0.0282935 1 0 1 1 0 0 +EDGE2 5050 4709 -0.95839 0.0136223 0.000374329 1 0 1 1 0 0 +EDGE2 5050 4589 -1.094 -0.0293951 0.00155091 1 0 1 1 0 0 +EDGE2 5051 4710 -1.01079 0.0471663 -1.57629 1 0 1 1 0 0 +EDGE2 5051 5030 -1.0358 0.0221656 -1.5648 1 0 1 1 0 0 +EDGE2 5051 5050 -0.99385 0.0160135 -1.57065 1 0 1 1 0 0 +EDGE2 5051 4990 -1.21512 -0.0118959 -1.55226 1 0 1 1 0 0 +EDGE2 5051 4630 -0.9808 0.0416443 1.55186 1 0 1 1 0 0 +EDGE2 5051 4650 -1.0518 -0.0312626 -1.56828 1 0 1 1 0 0 +EDGE2 5051 4590 -1.01688 -0.0238503 -1.56791 1 0 1 1 0 0 +EDGE2 5051 4632 1.07397 -0.0740409 -0.0242833 1 0 1 1 0 0 +EDGE2 5051 4591 0.0928933 0.0589165 0.00960414 1 0 1 1 0 0 +EDGE2 5051 4651 0.0249158 -0.0603287 -0.0301938 1 0 1 1 0 0 +EDGE2 5051 4991 0.0378568 -0.0432963 0.0338061 1 0 1 1 0 0 +EDGE2 5051 5031 -0.0245969 0.0497474 0.0270418 1 0 1 1 0 0 +EDGE2 5051 4631 -0.0171789 0.0638717 0.00313944 1 0 1 1 0 0 +EDGE2 5051 4992 1.02458 -0.00719812 -0.019307 1 0 1 1 0 0 +EDGE2 5051 5032 0.933175 0.015774 -0.0442127 1 0 1 1 0 0 +EDGE2 5051 4652 0.999219 -0.0601721 0.0174182 1 0 1 1 0 0 +EDGE2 5051 4592 1.00397 -0.0455964 0.0221705 1 0 1 1 0 0 +EDGE2 5052 5051 -1.02039 -0.041237 0.0111735 1 0 1 1 0 0 +EDGE2 5052 4632 -0.0514124 -0.0829173 0.0251783 1 0 1 1 0 0 +EDGE2 5052 4591 -1.04579 0.0231222 0.0338579 1 0 1 1 0 0 +EDGE2 5052 4651 -1.01313 -0.0598757 0.0287494 1 0 1 1 0 0 +EDGE2 5052 4991 -0.989995 -0.05706 -0.015772 1 0 1 1 0 0 +EDGE2 5052 5031 -0.94674 0.0282309 0.00298089 1 0 1 1 0 0 +EDGE2 5052 4631 -1.01881 0.146003 -0.00579078 1 0 1 1 0 0 +EDGE2 5052 4992 -0.139161 -0.0199842 -0.00281953 1 0 1 1 0 0 +EDGE2 5052 5032 -0.0625304 0.0301854 -0.0105131 1 0 1 1 0 0 +EDGE2 5052 4652 -0.0103602 0.0143174 -0.0181869 1 0 1 1 0 0 +EDGE2 5052 4653 0.934095 -0.0239523 -0.00123241 1 0 1 1 0 0 +EDGE2 5052 5033 1.02924 0.0294147 0.0121268 1 0 1 1 0 0 +EDGE2 5052 4592 0.117712 -0.0290853 -0.0208022 1 0 1 1 0 0 +EDGE2 5052 4993 1.10892 0.0552496 -0.0273213 1 0 1 1 0 0 +EDGE2 5052 4593 0.953722 -0.0522751 0.0367959 1 0 1 1 0 0 +EDGE2 5052 4633 1.03525 0.0487326 -0.012022 1 0 1 1 0 0 +EDGE2 5053 5034 0.995829 0.0253628 0.0256806 1 0 1 1 0 0 +EDGE2 5053 4632 -0.973704 -0.0147296 0.030463 1 0 1 1 0 0 +EDGE2 5053 4992 -0.960659 -0.0382452 0.0452802 1 0 1 1 0 0 +EDGE2 5053 5032 -1.09149 -0.0130081 -0.0173321 1 0 1 1 0 0 +EDGE2 5053 5052 -1.03132 -0.0435697 0.00589453 1 0 1 1 0 0 +EDGE2 5053 4652 -1.00696 0.0276155 0.00324872 1 0 1 1 0 0 +EDGE2 5053 4653 0.0714171 0.0370252 -0.0134579 1 0 1 1 0 0 +EDGE2 5053 5033 -0.0365175 -0.00809591 0.0126018 1 0 1 1 0 0 +EDGE2 5053 4592 -0.962222 -0.00253079 -0.00808945 1 0 1 1 0 0 +EDGE2 5053 4993 -0.0215363 0.00606585 -0.0243342 1 0 1 1 0 0 +EDGE2 5053 4593 0.0822924 0.10946 0.00844973 1 0 1 1 0 0 +EDGE2 5053 4633 0.0649917 -0.0414503 0.0193376 1 0 1 1 0 0 +EDGE2 5053 4634 1.10177 -0.0440768 -0.0191973 1 0 1 1 0 0 +EDGE2 5053 4654 0.949435 0.0545654 -0.0239024 1 0 1 1 0 0 +EDGE2 5053 4994 0.995011 0.0237992 0.0113055 1 0 1 1 0 0 +EDGE2 5053 4594 0.9554 -0.0116776 0.0158444 1 0 1 1 0 0 +EDGE2 5054 5034 -0.0412374 0.0315882 0.0196787 1 0 1 1 0 0 +EDGE2 5054 4653 -0.958002 -0.0183726 -0.00381045 1 0 1 1 0 0 +EDGE2 5054 5033 -1.02165 -0.0707644 0.0164746 1 0 1 1 0 0 +EDGE2 5054 5053 -1.00302 -0.000316737 -0.0124898 1 0 1 1 0 0 +EDGE2 5054 4993 -1.00031 0.115576 0.0128377 1 0 1 1 0 0 +EDGE2 5054 4593 -0.984643 0.0348494 0.0251871 1 0 1 1 0 0 +EDGE2 5054 4633 -1.04181 0.0606661 -0.00440588 1 0 1 1 0 0 +EDGE2 5054 4634 0.0358939 0.0226228 -0.00720211 1 0 1 1 0 0 +EDGE2 5054 4654 0.0724374 0.0428595 -0.0177298 1 0 1 1 0 0 +EDGE2 5054 4994 -0.0314647 -0.0181489 0.0279295 1 0 1 1 0 0 +EDGE2 5054 4594 0.0159975 0.045413 0.00655281 1 0 1 1 0 0 +EDGE2 5054 2915 1.06936 -0.0369952 -3.17631 1 0 1 1 0 0 +EDGE2 5054 4635 0.988844 0.00880145 0.00735074 1 0 1 1 0 0 +EDGE2 5054 4995 0.974758 -0.00077888 -0.0110812 1 0 1 1 0 0 +EDGE2 5054 5035 1.10772 -0.0984504 0.0349249 1 0 1 1 0 0 +EDGE2 5054 4655 0.900104 0.0366692 0.00174105 1 0 1 1 0 0 +EDGE2 5054 4595 0.905469 0.0675708 0.00120005 1 0 1 1 0 0 +EDGE2 5054 3595 0.96672 -0.0469281 -3.15009 1 0 1 1 0 0 +EDGE2 5054 3735 1.08235 -0.062289 -3.13442 1 0 1 1 0 0 +EDGE2 5054 3755 1.0362 -0.010603 -3.14358 1 0 1 1 0 0 +EDGE2 5054 3575 1.00036 0.0345306 -3.15719 1 0 1 1 0 0 +EDGE2 5055 5034 -0.923709 0.0117646 0.0147178 1 0 1 1 0 0 +EDGE2 5055 5054 -1.05227 -0.0270452 0.00115716 1 0 1 1 0 0 +EDGE2 5055 4634 -0.912833 0.0107748 0.00399984 1 0 1 1 0 0 +EDGE2 5055 4654 -1.12603 -0.0162195 0.0368692 1 0 1 1 0 0 +EDGE2 5055 4994 -0.956947 -0.0661409 -0.0103616 1 0 1 1 0 0 +EDGE2 5055 4594 -1.01042 -0.0368793 -0.0251292 1 0 1 1 0 0 +EDGE2 5055 2915 0.0516125 0.0612583 -3.14127 1 0 1 1 0 0 +EDGE2 5055 4635 -0.0319951 -0.0394609 -0.00080981 1 0 1 1 0 0 +EDGE2 5055 2916 -0.0845433 -1.11035 -1.60492 1 0 1 1 0 0 +EDGE2 5055 3736 -0.00631345 -1.00218 -1.60087 1 0 1 1 0 0 +EDGE2 5055 4596 -0.0303071 -0.982592 -1.57 1 0 1 1 0 0 +EDGE2 5055 3576 0.031883 -0.973678 -1.58355 1 0 1 1 0 0 +EDGE2 5055 4995 -0.0500363 0.00109638 -0.0139127 1 0 1 1 0 0 +EDGE2 5055 5035 0.00380068 0.0928962 0.00375756 1 0 1 1 0 0 +EDGE2 5055 4655 -0.0024126 -0.0284437 -0.0241185 1 0 1 1 0 0 +EDGE2 5055 4595 0.0929423 -0.0923544 0.00054748 1 0 1 1 0 0 +EDGE2 5055 3595 -0.0320705 0.0270017 -3.14242 1 0 1 1 0 0 +EDGE2 5055 3735 -0.0825454 -0.032966 -3.10868 1 0 1 1 0 0 +EDGE2 5055 3755 0.00625061 0.0117677 -3.12107 1 0 1 1 0 0 +EDGE2 5055 3575 0.0348893 0.044345 -3.09662 1 0 1 1 0 0 +EDGE2 5055 2914 0.928981 0.0558205 -3.16857 1 0 1 1 0 0 +EDGE2 5055 3594 0.939678 -0.0161139 -3.11185 1 0 1 1 0 0 +EDGE2 5055 3734 1.0013 -0.0197111 -3.15647 1 0 1 1 0 0 +EDGE2 5055 3754 1.02905 0.0165454 -3.11419 1 0 1 1 0 0 +EDGE2 5055 3574 0.976493 -0.0640395 -3.09751 1 0 1 1 0 0 +EDGE2 5055 4636 0.0224489 1.02322 1.57559 1 0 1 1 0 0 +EDGE2 5055 4996 -0.0586711 0.976546 1.56478 1 0 1 1 0 0 +EDGE2 5055 5036 0.082006 1.03494 1.57074 1 0 1 1 0 0 +EDGE2 5055 4656 -0.00337176 0.932917 1.54867 1 0 1 1 0 0 +EDGE2 5055 3596 0.0294381 0.912995 1.58489 1 0 1 1 0 0 +EDGE2 5055 3756 0.110048 1.07786 1.55505 1 0 1 1 0 0 +EDGE2 5056 2915 -1.06436 0.00245677 1.56775 1 0 1 1 0 0 +EDGE2 5056 4635 -1.00504 0.0512874 -1.56835 1 0 1 1 0 0 +EDGE2 5056 4995 -0.935317 0.00818829 -1.55738 1 0 1 1 0 0 +EDGE2 5056 5035 -1.00689 0.0886826 -1.58972 1 0 1 1 0 0 +EDGE2 5056 5055 -1.00352 0.00534951 -1.58322 1 0 1 1 0 0 +EDGE2 5056 4655 -1.0089 -0.102547 -1.557 1 0 1 1 0 0 +EDGE2 5056 4595 -1.05144 0.000826286 -1.58627 1 0 1 1 0 0 +EDGE2 5056 3595 -0.917973 0.0634443 1.57229 1 0 1 1 0 0 +EDGE2 5056 3735 -1.05516 0.0211722 1.57129 1 0 1 1 0 0 +EDGE2 5056 3755 -1.0061 0.0998649 1.5655 1 0 1 1 0 0 +EDGE2 5056 3575 -1.05166 -0.00393004 1.55942 1 0 1 1 0 0 +EDGE2 5056 3597 0.949727 0.0739602 0.00388486 1 0 1 1 0 0 +EDGE2 5056 4997 1.08423 -0.0435521 -0.0248493 1 0 1 1 0 0 +EDGE2 5056 4636 0.0693485 0.0199339 -0.0156014 1 0 1 1 0 0 +EDGE2 5056 4996 0.000774231 0.00366262 0.00948994 1 0 1 1 0 0 +EDGE2 5056 5036 0.0708754 -0.0627063 -0.00225791 1 0 1 1 0 0 +EDGE2 5056 4656 0.0674146 -0.0140351 -0.00826199 1 0 1 1 0 0 +EDGE2 5056 3596 -0.063244 -0.0863884 -0.0322998 1 0 1 1 0 0 +EDGE2 5056 3756 -0.0994079 0.03167 0.00448151 1 0 1 1 0 0 +EDGE2 5056 5037 0.925845 -0.028869 -0.0340146 1 0 1 1 0 0 +EDGE2 5056 4637 1.02506 0.0277648 0.00474749 1 0 1 1 0 0 +EDGE2 5056 4657 1.05602 -0.0633459 0.0218001 1 0 1 1 0 0 +EDGE2 5056 3757 1.01472 0.0229588 -0.019351 1 0 1 1 0 0 +EDGE2 5057 3597 -0.00254731 0.102999 -0.027068 1 0 1 1 0 0 +EDGE2 5057 4997 0.0168664 0.0226796 0.0401441 1 0 1 1 0 0 +EDGE2 5057 4636 -1.02893 0.00465038 -0.0120345 1 0 1 1 0 0 +EDGE2 5057 4996 -0.962822 0.00558387 0.0195577 1 0 1 1 0 0 +EDGE2 5057 5036 -0.941938 -0.033638 0.00898758 1 0 1 1 0 0 +EDGE2 5057 5056 -0.973173 0.0122149 -0.0151303 1 0 1 1 0 0 +EDGE2 5057 4656 -1.03489 0.0649192 -0.0040707 1 0 1 1 0 0 +EDGE2 5057 3596 -1.03491 0.0184328 0.00846042 1 0 1 1 0 0 +EDGE2 5057 3756 -1.03928 0.0276173 0.024079 1 0 1 1 0 0 +EDGE2 5057 5037 -0.121072 -0.0492043 -0.0109242 1 0 1 1 0 0 +EDGE2 5057 4637 -0.0138499 -0.0194543 0.0165755 1 0 1 1 0 0 +EDGE2 5057 4657 0.0339574 0.0414377 0.0155516 1 0 1 1 0 0 +EDGE2 5057 3757 0.0104412 -0.0382814 -0.0137248 1 0 1 1 0 0 +EDGE2 5057 4638 0.950416 0.000230788 0.0107493 1 0 1 1 0 0 +EDGE2 5057 4998 1.09278 0.0245749 0.0123777 1 0 1 1 0 0 +EDGE2 5057 5038 0.992895 -0.0301196 -0.00842146 1 0 1 1 0 0 +EDGE2 5057 4658 0.962926 0.038988 -0.0110981 1 0 1 1 0 0 +EDGE2 5057 3598 0.959658 -0.0602566 -0.01306 1 0 1 1 0 0 +EDGE2 5057 3758 0.934746 0.00405528 -0.0144675 1 0 1 1 0 0 +EDGE2 5058 3597 -1.04297 -0.0718256 -0.00108137 1 0 1 1 0 0 +EDGE2 5058 4997 -0.995611 0.0321846 0.00673658 1 0 1 1 0 0 +EDGE2 5058 5057 -0.903743 -0.0431165 0.0187393 1 0 1 1 0 0 +EDGE2 5058 5037 -1.0869 -0.0144594 -0.00427296 1 0 1 1 0 0 +EDGE2 5058 4637 -1.01677 0.000111846 -0.00316368 1 0 1 1 0 0 +EDGE2 5058 4657 -0.986097 -0.0692458 -0.0031666 1 0 1 1 0 0 +EDGE2 5058 3757 -1.0318 0.0461683 0.00148697 1 0 1 1 0 0 +EDGE2 5058 4999 0.9979 -0.0972281 -0.0180603 1 0 1 1 0 0 +EDGE2 5058 4638 -0.00353847 -0.0130824 0.0143975 1 0 1 1 0 0 +EDGE2 5058 4998 0.0989716 -0.0121493 0.0244892 1 0 1 1 0 0 +EDGE2 5058 5038 0.00573601 -0.0704037 -0.00537682 1 0 1 1 0 0 +EDGE2 5058 4658 0.00830164 -0.0456681 0.000674579 1 0 1 1 0 0 +EDGE2 5058 3598 0.05317 0.0258405 -0.015783 1 0 1 1 0 0 +EDGE2 5058 3758 -0.0269734 0.0155742 -0.0294837 1 0 1 1 0 0 +EDGE2 5058 5039 1.08068 0.0799215 -0.0105505 1 0 1 1 0 0 +EDGE2 5058 4639 1.01995 -0.0238864 0.0163159 1 0 1 1 0 0 +EDGE2 5058 4659 1.05012 0.0257992 -0.00200816 1 0 1 1 0 0 +EDGE2 5058 3599 0.930363 -0.0188842 0.0143553 1 0 1 1 0 0 +EDGE2 5058 3759 0.966926 0.000802271 -0.0284501 1 0 1 1 0 0 +EDGE2 5059 4999 0.0897379 0.0226401 0.00229506 1 0 1 1 0 0 +EDGE2 5059 4638 -1.05583 -0.0173789 0.0277315 1 0 1 1 0 0 +EDGE2 5059 4998 -1.07525 0.00239883 0.051584 1 0 1 1 0 0 +EDGE2 5059 5038 -1.07519 0.00541595 -0.00896252 1 0 1 1 0 0 +EDGE2 5059 5058 -1.01599 -0.0984571 -0.010333 1 0 1 1 0 0 +EDGE2 5059 4658 -1.01019 0.0149912 0.00435058 1 0 1 1 0 0 +EDGE2 5059 3598 -0.986325 0.0344853 -0.0151246 1 0 1 1 0 0 +EDGE2 5059 3758 -1.01402 0.00147956 -0.00160369 1 0 1 1 0 0 +EDGE2 5059 5039 0.0188358 -0.0309874 -0.0135645 1 0 1 1 0 0 +EDGE2 5059 4639 -0.0351029 0.0537471 -0.0147688 1 0 1 1 0 0 +EDGE2 5059 4659 -0.0454158 0.077736 0.00248426 1 0 1 1 0 0 +EDGE2 5059 3599 0.0343515 -0.033086 0.0048615 1 0 1 1 0 0 +EDGE2 5059 3759 0.0774875 -0.00656218 0.0343164 1 0 1 1 0 0 +EDGE2 5059 3680 1.0287 -0.0490106 -3.13542 1 0 1 1 0 0 +EDGE2 5059 5000 0.944117 0.0142274 0.00704943 1 0 1 1 0 0 +EDGE2 5059 5040 0.951448 0.0343009 -0.0300031 1 0 1 1 0 0 +EDGE2 5059 3820 1.01749 0.0210715 -3.12061 1 0 1 1 0 0 +EDGE2 5059 4640 1.03009 -0.105112 -0.00421869 1 0 1 1 0 0 +EDGE2 5059 4660 1.04668 -0.00704662 0.003729 1 0 1 1 0 0 +EDGE2 5059 3760 1.01125 0.0440081 0.0257173 1 0 1 1 0 0 +EDGE2 5059 3600 0.956363 -0.0481855 -0.00457638 1 0 1 1 0 0 +EDGE2 5059 3640 0.968181 -0.0669705 -3.13824 1 0 1 1 0 0 +EDGE2 5059 3660 1.01457 -0.0058024 -3.18833 1 0 1 1 0 0 +EDGE2 5060 4999 -1.10263 0.0102043 -0.0162668 1 0 1 1 0 0 +EDGE2 5060 5059 -0.925618 0.0578644 0.0136073 1 0 1 1 0 0 +EDGE2 5060 5039 -0.998407 -0.0428239 0.0156652 1 0 1 1 0 0 +EDGE2 5060 4639 -0.948065 -0.0868165 0.0308161 1 0 1 1 0 0 +EDGE2 5060 4659 -0.976249 -0.0327512 0.0334176 1 0 1 1 0 0 +EDGE2 5060 3599 -1.02894 0.077922 -0.022911 1 0 1 1 0 0 +EDGE2 5060 3759 -0.883391 -0.145841 -0.0189173 1 0 1 1 0 0 +EDGE2 5060 3680 0.00211085 0.0351261 -3.15367 1 0 1 1 0 0 +EDGE2 5060 4661 -0.0580097 0.998826 1.55581 1 0 1 1 0 0 +EDGE2 5060 5041 0.00058222 1.00929 1.55712 1 0 1 1 0 0 +EDGE2 5060 5001 -0.0822421 1.08303 1.56195 1 0 1 1 0 0 +EDGE2 5060 5000 -0.0230458 0.0123599 -0.0247786 1 0 1 1 0 0 +EDGE2 5060 3601 0.0381943 0.962639 1.61873 1 0 1 1 0 0 +EDGE2 5060 4641 -0.0463159 0.907863 1.57481 1 0 1 1 0 0 +EDGE2 5060 5040 -0.0549543 0.0426663 0.00960444 1 0 1 1 0 0 +EDGE2 5060 3820 0.070428 0.0163446 -3.16935 1 0 1 1 0 0 +EDGE2 5060 4640 -0.0291761 0.00615654 -0.00111899 1 0 1 1 0 0 +EDGE2 5060 4660 -0.0165851 -0.00288271 -0.0257734 1 0 1 1 0 0 +EDGE2 5060 3760 -0.0013137 -0.0405831 0.00283651 1 0 1 1 0 0 +EDGE2 5060 3761 0.0436717 -1.01988 -1.55785 1 0 1 1 0 0 +EDGE2 5060 3600 0.0371694 -0.0147573 -0.0314186 1 0 1 1 0 0 +EDGE2 5060 3640 0.0136182 -0.00644056 -3.15586 1 0 1 1 0 0 +EDGE2 5060 3660 -0.0240323 -0.00704753 -3.14013 1 0 1 1 0 0 +EDGE2 5060 3821 0.00908441 -0.992398 -1.54976 1 0 1 1 0 0 +EDGE2 5060 3641 -0.0358345 -1.03254 -1.5671 1 0 1 1 0 0 +EDGE2 5060 3661 -0.0201966 -1.02088 -1.5491 1 0 1 1 0 0 +EDGE2 5060 3681 0.0591425 -0.984817 -1.57186 1 0 1 1 0 0 +EDGE2 5060 3659 1.04218 0.0805304 -3.15554 1 0 1 1 0 0 +EDGE2 5060 3679 0.982989 0.103706 -3.13897 1 0 1 1 0 0 +EDGE2 5060 3819 1.0187 0.0830388 -3.14801 1 0 1 1 0 0 +EDGE2 5060 3639 0.970005 0.0481787 -3.12196 1 0 1 1 0 0 +EDGE2 5061 3680 -0.982377 -0.0106682 1.59436 1 0 1 1 0 0 +EDGE2 5061 4661 0.000448847 -0.0166864 0.0211138 1 0 1 1 0 0 +EDGE2 5061 4642 0.909486 -0.0257122 -0.00291876 1 0 1 1 0 0 +EDGE2 5061 5002 0.977414 -0.0337731 -0.0168766 1 0 1 1 0 0 +EDGE2 5061 5042 1.11329 -0.0229715 0.00113461 1 0 1 1 0 0 +EDGE2 5061 4662 1.06606 0.00982476 -0.0123124 1 0 1 1 0 0 +EDGE2 5061 5041 0.0059222 0.00428273 -0.0445129 1 0 1 1 0 0 +EDGE2 5061 3602 1.03639 0.00185404 0.0108958 1 0 1 1 0 0 +EDGE2 5061 5001 -0.0385116 -0.0531401 0.0280711 1 0 1 1 0 0 +EDGE2 5061 5000 -1.04874 0.0999823 -1.54891 1 0 1 1 0 0 +EDGE2 5061 5060 -0.884546 0.0252206 -1.5779 1 0 1 1 0 0 +EDGE2 5061 3601 0.0142676 0.044021 -0.0253083 1 0 1 1 0 0 +EDGE2 5061 4641 0.0732571 0.0879019 0.0131459 1 0 1 1 0 0 +EDGE2 5061 5040 -1.06045 0.0102112 -1.5609 1 0 1 1 0 0 +EDGE2 5061 3820 -0.929959 0.0324345 1.55511 1 0 1 1 0 0 +EDGE2 5061 4640 -0.978848 -0.0291714 -1.55536 1 0 1 1 0 0 +EDGE2 5061 4660 -1.03675 0.00304862 -1.53158 1 0 1 1 0 0 +EDGE2 5061 3760 -0.951319 0.0384459 -1.58427 1 0 1 1 0 0 +EDGE2 5061 3600 -1.01488 -0.0588594 -1.57952 1 0 1 1 0 0 +EDGE2 5061 3640 -1.01942 0.019048 1.54508 1 0 1 1 0 0 +EDGE2 5061 3660 -1.03044 -0.0166455 1.58178 1 0 1 1 0 0 +EDGE2 5062 4663 0.990757 0.0654511 -0.0186993 1 0 1 1 0 0 +EDGE2 5062 5043 0.991223 0.0497005 -0.0220287 1 0 1 1 0 0 +EDGE2 5062 5003 0.945022 0.0276347 0.0080639 1 0 1 1 0 0 +EDGE2 5062 3603 1.02102 0.0252261 -0.0184538 1 0 1 1 0 0 +EDGE2 5062 4643 1.03372 -0.0399929 0.00259828 1 0 1 1 0 0 +EDGE2 5062 4661 -0.996142 -0.0405581 -0.00599818 1 0 1 1 0 0 +EDGE2 5062 4642 0.0418065 0.012741 0.0137347 1 0 1 1 0 0 +EDGE2 5062 5002 0.0132315 -0.000606627 -0.017717 1 0 1 1 0 0 +EDGE2 5062 5042 -0.0785936 0.0196429 -0.00134823 1 0 1 1 0 0 +EDGE2 5062 4662 -0.0648339 0.0839268 -0.00727963 1 0 1 1 0 0 +EDGE2 5062 5041 -1.02214 -0.0888408 0.026393 1 0 1 1 0 0 +EDGE2 5062 5061 -0.982025 0.0211939 -0.0174774 1 0 1 1 0 0 +EDGE2 5062 3602 0.0139119 -0.00924632 0.0134075 1 0 1 1 0 0 +EDGE2 5062 5001 -0.97996 -0.0188207 0.0039139 1 0 1 1 0 0 +EDGE2 5062 3601 -1.03587 -0.00875396 0.0452624 1 0 1 1 0 0 +EDGE2 5062 4641 -1.00407 0.0169524 0.015442 1 0 1 1 0 0 +EDGE2 5063 4644 0.982123 -0.0578859 -0.0203052 1 0 1 1 0 0 +EDGE2 5063 5004 0.994867 -0.0387406 0.040726 1 0 1 1 0 0 +EDGE2 5063 5044 0.952295 0.046722 0.00377953 1 0 1 1 0 0 +EDGE2 5063 4664 1.01403 -0.00846237 -0.0108917 1 0 1 1 0 0 +EDGE2 5063 4663 0.0715004 -0.0570035 -0.0158143 1 0 1 1 0 0 +EDGE2 5063 5043 0.0487302 0.0189916 0.0246939 1 0 1 1 0 0 +EDGE2 5063 3604 0.998635 0.00279118 0.017522 1 0 1 1 0 0 +EDGE2 5063 5003 0.0110432 0.0120616 -0.00713148 1 0 1 1 0 0 +EDGE2 5063 3603 0.00114592 0.0549516 0.0169068 1 0 1 1 0 0 +EDGE2 5063 4643 0.0268348 0.0192412 -0.00855982 1 0 1 1 0 0 +EDGE2 5063 4642 -0.979304 -0.0403012 0.00169875 1 0 1 1 0 0 +EDGE2 5063 5002 -0.954474 0.0244179 -0.0117644 1 0 1 1 0 0 +EDGE2 5063 5042 -0.927346 0.0333642 0.0267086 1 0 1 1 0 0 +EDGE2 5063 5062 -1.00018 -0.0464415 0.0349824 1 0 1 1 0 0 +EDGE2 5063 4662 -1.09419 -0.0632233 -0.000811393 1 0 1 1 0 0 +EDGE2 5063 3602 -0.998292 -0.0462973 -0.0106662 1 0 1 1 0 0 +EDGE2 5064 4644 0.0719279 0.0610589 0.0340589 1 0 1 1 0 0 +EDGE2 5064 4705 0.964328 -0.113819 -3.12503 1 0 1 1 0 0 +EDGE2 5064 5005 0.987172 -0.050879 -0.0159278 1 0 1 1 0 0 +EDGE2 5064 5025 0.998489 0.0697399 -3.14152 1 0 1 1 0 0 +EDGE2 5064 5045 1.01885 -0.0597198 0.0160519 1 0 1 1 0 0 +EDGE2 5064 4985 0.890178 -0.0183531 -3.15611 1 0 1 1 0 0 +EDGE2 5064 3605 1.07246 0.0325932 -0.00544938 1 0 1 1 0 0 +EDGE2 5064 4645 0.988053 0.0443939 0.0253755 1 0 1 1 0 0 +EDGE2 5064 4665 0.99388 -0.0130577 -0.00395888 1 0 1 1 0 0 +EDGE2 5064 4685 1.06538 -0.0432601 -3.16374 1 0 1 1 0 0 +EDGE2 5064 4585 0.948976 0.0371598 -3.14318 1 0 1 1 0 0 +EDGE2 5064 5004 0.00582195 0.00103148 0.0125741 1 0 1 1 0 0 +EDGE2 5064 5044 0.0401872 0.0488571 0.0042059 1 0 1 1 0 0 +EDGE2 5064 4664 -0.0220053 0.0405942 0.0110901 1 0 1 1 0 0 +EDGE2 5064 4663 -0.995752 -0.022891 -0.000500692 1 0 1 1 0 0 +EDGE2 5064 5043 -1.07505 -0.0224924 0.00322583 1 0 1 1 0 0 +EDGE2 5064 5063 -1.0871 -0.0547689 -0.00122369 1 0 1 1 0 0 +EDGE2 5064 3604 0.0124744 0.0342859 -0.00149015 1 0 1 1 0 0 +EDGE2 5064 5003 -1.0239 -0.00527492 0.00228581 1 0 1 1 0 0 +EDGE2 5064 3603 -0.879261 -0.0659991 0.0240152 1 0 1 1 0 0 +EDGE2 5064 4643 -1.03034 0.0793964 0.0168733 1 0 1 1 0 0 +EDGE2 5065 5024 0.903218 -0.00229353 -3.13062 1 0 1 1 0 0 +EDGE2 5065 4986 -0.0209962 0.947034 1.57121 1 0 1 1 0 0 +EDGE2 5065 5046 -0.0386125 0.96767 1.5847 1 0 1 1 0 0 +EDGE2 5065 5026 -0.00413724 1.01163 1.53557 1 0 1 1 0 0 +EDGE2 5065 4646 -0.0489579 0.940405 1.56359 1 0 1 1 0 0 +EDGE2 5065 4706 -0.0507511 0.951084 1.575 1 0 1 1 0 0 +EDGE2 5065 4586 0.0743285 0.998786 1.60507 1 0 1 1 0 0 +EDGE2 5065 4644 -0.967321 -0.0491938 0.00551955 1 0 1 1 0 0 +EDGE2 5065 4705 -0.0981316 -0.0639689 -3.1534 1 0 1 1 0 0 +EDGE2 5065 4684 0.970456 0.098026 -3.12285 1 0 1 1 0 0 +EDGE2 5065 4704 1.01031 -0.0249177 -3.11893 1 0 1 1 0 0 +EDGE2 5065 4984 0.968776 -0.134135 -3.14376 1 0 1 1 0 0 +EDGE2 5065 4584 1.03106 0.0100445 -3.16249 1 0 1 1 0 0 +EDGE2 5065 5005 -0.0280399 -0.0729718 -0.024486 1 0 1 1 0 0 +EDGE2 5065 5025 0.0216904 0.0609248 -3.14129 1 0 1 1 0 0 +EDGE2 5065 5045 0.0402366 -0.112347 0.00663399 1 0 1 1 0 0 +EDGE2 5065 4985 -0.00655456 -0.0790277 -3.16772 1 0 1 1 0 0 +EDGE2 5065 3605 -0.0167038 -0.0106567 0.0190272 1 0 1 1 0 0 +EDGE2 5065 4645 -0.0898012 -0.0366632 -0.020047 1 0 1 1 0 0 +EDGE2 5065 4665 -0.0197275 -0.014386 0.00833261 1 0 1 1 0 0 +EDGE2 5065 4685 -0.0809167 -0.0303601 -3.15451 1 0 1 1 0 0 +EDGE2 5065 4585 -0.0171413 -0.00834873 -3.13659 1 0 1 1 0 0 +EDGE2 5065 5004 -0.958689 0.0219935 -0.00958224 1 0 1 1 0 0 +EDGE2 5065 5044 -0.990981 -0.0623261 -0.0180187 1 0 1 1 0 0 +EDGE2 5065 5064 -1.02603 0.0218648 -0.0157452 1 0 1 1 0 0 +EDGE2 5065 4664 -0.917642 -0.000354084 -0.00650321 1 0 1 1 0 0 +EDGE2 5065 3606 -0.00301563 -0.975335 -1.55764 1 0 1 1 0 0 +EDGE2 5065 4686 -0.0297599 -1.04438 -1.50416 1 0 1 1 0 0 +EDGE2 5065 5006 -0.0329615 -0.99423 -1.54373 1 0 1 1 0 0 +EDGE2 5065 4666 0.0256889 -0.988892 -1.58806 1 0 1 1 0 0 +EDGE2 5065 3604 -0.999719 -0.0591315 -0.013992 1 0 1 1 0 0 +EDGE2 5066 4705 -1.04575 0.0337159 -1.54447 1 0 1 1 0 0 +EDGE2 5066 5065 -0.964158 -0.0390089 1.56738 1 0 1 1 0 0 +EDGE2 5066 5005 -1.00365 0.0212078 1.58746 1 0 1 1 0 0 +EDGE2 5066 5025 -1.02501 -0.0582051 -1.55793 1 0 1 1 0 0 +EDGE2 5066 5045 -0.990896 -0.0378061 1.58654 1 0 1 1 0 0 +EDGE2 5066 4985 -0.97403 -0.0459661 -1.57131 1 0 1 1 0 0 +EDGE2 5066 3605 -1.07235 0.0467699 1.54752 1 0 1 1 0 0 +EDGE2 5066 4645 -1.01328 0.0107115 1.57924 1 0 1 1 0 0 +EDGE2 5066 4665 -0.975669 0.0115657 1.58553 1 0 1 1 0 0 +EDGE2 5066 4685 -1.05217 -0.0401692 -1.58728 1 0 1 1 0 0 +EDGE2 5066 4585 -0.926385 -0.00454037 -1.57579 1 0 1 1 0 0 +EDGE2 5066 3607 1.01856 0.0952527 0.00425691 1 0 1 1 0 0 +EDGE2 5066 3606 0.0798198 -0.0184485 -0.0091519 1 0 1 1 0 0 +EDGE2 5066 4686 0.070969 -0.0869073 0.00437502 1 0 1 1 0 0 +EDGE2 5066 5006 0.0968828 -0.0672326 0.0078867 1 0 1 1 0 0 +EDGE2 5066 4666 0.0995269 0.019584 0.000533421 1 0 1 1 0 0 +EDGE2 5066 4687 1.02834 0.0688046 0.0079462 1 0 1 1 0 0 +EDGE2 5066 5007 0.950164 -0.0329032 0.0155148 1 0 1 1 0 0 +EDGE2 5066 4667 1.01137 0.0844401 0.000826668 1 0 1 1 0 0 +EDGE2 5067 5008 1.00058 -0.0864335 0.0439761 1 0 1 1 0 0 +EDGE2 5067 3607 0.007772 0.055803 -0.00234039 1 0 1 1 0 0 +EDGE2 5067 3606 -0.93693 0.0279515 0.0153357 1 0 1 1 0 0 +EDGE2 5067 4686 -1.13456 0.0229998 -0.00760339 1 0 1 1 0 0 +EDGE2 5067 5006 -1.04297 0.0647687 0.0159409 1 0 1 1 0 0 +EDGE2 5067 5066 -0.99529 0.0347406 0.0176415 1 0 1 1 0 0 +EDGE2 5067 4666 -1.0316 -0.0212434 -0.00428031 1 0 1 1 0 0 +EDGE2 5067 4687 -0.0216456 -0.030826 0.00174276 1 0 1 1 0 0 +EDGE2 5067 5007 0.0167312 -0.045686 0.00982519 1 0 1 1 0 0 +EDGE2 5067 4667 -0.0131091 -0.0312945 0.0107237 1 0 1 1 0 0 +EDGE2 5067 3608 0.960275 -0.00440492 0.00305776 1 0 1 1 0 0 +EDGE2 5067 4668 1.02129 0.0773856 -0.00475004 1 0 1 1 0 0 +EDGE2 5067 4688 1.00591 -0.0676705 0.0238929 1 0 1 1 0 0 +EDGE2 5068 5008 -0.0987131 -0.0121895 -0.0292411 1 0 1 1 0 0 +EDGE2 5068 3607 -1.01149 -0.0155271 0.0185084 1 0 1 1 0 0 +EDGE2 5068 4687 -0.923025 0.0379412 0.0287678 1 0 1 1 0 0 +EDGE2 5068 5007 -0.984045 0.0452686 0.0167946 1 0 1 1 0 0 +EDGE2 5068 5067 -0.991695 0.00108088 0.00159458 1 0 1 1 0 0 +EDGE2 5068 4667 -0.923479 -0.0487742 0.0128708 1 0 1 1 0 0 +EDGE2 5068 5009 0.957272 0.0792742 -0.0169351 1 0 1 1 0 0 +EDGE2 5068 3608 -0.000750723 0.00642202 0.00486138 1 0 1 1 0 0 +EDGE2 5068 4668 0.00354818 0.0533274 -0.00118167 1 0 1 1 0 0 +EDGE2 5068 4688 -0.0717662 -0.0512735 -0.0166293 1 0 1 1 0 0 +EDGE2 5068 3609 0.948935 -0.0155974 -0.0251295 1 0 1 1 0 0 +EDGE2 5068 4669 0.988223 -0.017422 -0.00758819 1 0 1 1 0 0 +EDGE2 5068 4689 1.03257 -0.0896541 -0.00381906 1 0 1 1 0 0 +EDGE2 5069 5008 -0.987483 0.0371178 0.00384953 1 0 1 1 0 0 +EDGE2 5069 5068 -0.985491 -0.118795 -0.00483182 1 0 1 1 0 0 +EDGE2 5069 5009 -0.0597974 -0.00445239 -0.00658463 1 0 1 1 0 0 +EDGE2 5069 3608 -0.998314 -0.0275457 0.0203278 1 0 1 1 0 0 +EDGE2 5069 4668 -1.04698 0.0199079 -0.00542591 1 0 1 1 0 0 +EDGE2 5069 4688 -1.00276 -0.0117854 0.00314786 1 0 1 1 0 0 +EDGE2 5069 3609 0.0444323 0.0766222 -0.00459311 1 0 1 1 0 0 +EDGE2 5069 4669 0.0573795 -0.0832844 0.00285811 1 0 1 1 0 0 +EDGE2 5069 4689 0.05513 0.00645256 -0.0117137 1 0 1 1 0 0 +EDGE2 5069 4570 1.13256 -0.0860884 -3.11486 1 0 1 1 0 0 +EDGE2 5069 4690 1.03675 -0.0182531 0.0147651 1 0 1 1 0 0 +EDGE2 5069 4970 1.02196 0.00761666 -3.12994 1 0 1 1 0 0 +EDGE2 5069 5010 1.00196 0.0247026 0.0112353 1 0 1 1 0 0 +EDGE2 5069 4670 1.05056 -0.0805822 0.0266268 1 0 1 1 0 0 +EDGE2 5069 3610 0.995101 -0.0890575 -0.0327113 1 0 1 1 0 0 +EDGE2 5069 3630 0.958462 0.0488734 -3.14875 1 0 1 1 0 0 +EDGE2 5070 5009 -0.962606 -0.0026326 0.0336542 1 0 1 1 0 0 +EDGE2 5070 5069 -1.03632 0.0862453 -0.00616074 1 0 1 1 0 0 +EDGE2 5070 3609 -0.948325 0.010516 -0.016011 1 0 1 1 0 0 +EDGE2 5070 4669 -1.03508 -0.0824752 -0.0157039 1 0 1 1 0 0 +EDGE2 5070 4689 -1.0805 0.0111032 -0.0121104 1 0 1 1 0 0 +EDGE2 5070 4971 -0.00402761 1.08073 1.56139 1 0 1 1 0 0 +EDGE2 5070 5011 0.0957491 1.06607 1.55294 1 0 1 1 0 0 +EDGE2 5070 4571 0.00585226 1.02476 1.56029 1 0 1 1 0 0 +EDGE2 5070 4671 0.0321573 0.989378 1.56225 1 0 1 1 0 0 +EDGE2 5070 4691 0.0244146 1.03399 1.54884 1 0 1 1 0 0 +EDGE2 5070 3611 0.0425733 0.930434 1.57913 1 0 1 1 0 0 +EDGE2 5070 4570 0.0243227 0.0646486 -3.16262 1 0 1 1 0 0 +EDGE2 5070 4690 0.00108112 0.097298 -0.0198209 1 0 1 1 0 0 +EDGE2 5070 4970 0.0667021 0.0984146 -3.13614 1 0 1 1 0 0 +EDGE2 5070 5010 0.034286 0.00822742 -0.0063754 1 0 1 1 0 0 +EDGE2 5070 4670 -0.0340025 0.0345706 -0.0103124 1 0 1 1 0 0 +EDGE2 5070 3610 -0.0105902 0.0502603 -0.00159923 1 0 1 1 0 0 +EDGE2 5070 3630 -0.0210279 0.0218468 -3.10134 1 0 1 1 0 0 +EDGE2 5070 3631 -0.0343667 -1.00014 -1.59855 1 0 1 1 0 0 +EDGE2 5070 3629 0.962876 -0.00057642 -3.10543 1 0 1 1 0 0 +EDGE2 5070 4569 0.98975 0.0532073 -3.13617 1 0 1 1 0 0 +EDGE2 5070 4969 0.995955 -0.0399466 -3.16499 1 0 1 1 0 0 +EDGE2 5071 4672 1.01939 -0.011997 0.0152797 1 0 1 1 0 0 +EDGE2 5071 4972 0.93166 0.00286418 -0.0133248 1 0 1 1 0 0 +EDGE2 5071 5012 0.988556 0.011983 -0.017024 1 0 1 1 0 0 +EDGE2 5071 4692 0.960538 0.028324 0.00338114 1 0 1 1 0 0 +EDGE2 5071 5070 -1.00421 -0.083716 -1.5493 1 0 1 1 0 0 +EDGE2 5071 4971 -0.0121131 0.012766 0.00248126 1 0 1 1 0 0 +EDGE2 5071 3612 0.970086 0.00266181 0.0154128 1 0 1 1 0 0 +EDGE2 5071 4572 1.06484 -0.0264665 -0.0138741 1 0 1 1 0 0 +EDGE2 5071 5011 0.0130391 0.0815019 0.0104324 1 0 1 1 0 0 +EDGE2 5071 4571 -0.0818276 0.0613862 0.0399935 1 0 1 1 0 0 +EDGE2 5071 4671 0.0190851 -0.025445 -0.0186475 1 0 1 1 0 0 +EDGE2 5071 4691 0.0564169 0.0553373 0.0210496 1 0 1 1 0 0 +EDGE2 5071 3611 -0.0238327 -0.026038 -0.0319076 1 0 1 1 0 0 +EDGE2 5071 4570 -1.03386 0.0739319 1.60585 1 0 1 1 0 0 +EDGE2 5071 4690 -0.933804 0.00591365 -1.57069 1 0 1 1 0 0 +EDGE2 5071 4970 -0.986263 -0.097264 1.60673 1 0 1 1 0 0 +EDGE2 5071 5010 -0.999585 -0.00695791 -1.58695 1 0 1 1 0 0 +EDGE2 5071 4670 -0.989359 -0.0446243 -1.56533 1 0 1 1 0 0 +EDGE2 5071 3610 -1.05929 -0.0135448 -1.56964 1 0 1 1 0 0 +EDGE2 5071 3630 -1.00118 0.060453 1.58784 1 0 1 1 0 0 +EDGE2 5072 4672 0.0362179 -0.0346271 -0.00132156 1 0 1 1 0 0 +EDGE2 5072 4972 -0.0240124 -0.00579273 0.00906517 1 0 1 1 0 0 +EDGE2 5072 4673 0.903921 0.0417026 -0.00370632 1 0 1 1 0 0 +EDGE2 5072 4973 0.939274 0.0570143 0.0315163 1 0 1 1 0 0 +EDGE2 5072 5013 0.942454 0.0591524 0.0215464 1 0 1 1 0 0 +EDGE2 5072 4693 1.06047 -0.0468546 -0.00399703 1 0 1 1 0 0 +EDGE2 5072 3613 0.992503 -0.0402811 -0.0041622 1 0 1 1 0 0 +EDGE2 5072 4573 1.08139 0.000562471 -0.0162856 1 0 1 1 0 0 +EDGE2 5072 5012 0.0232636 -0.0207198 -0.0116183 1 0 1 1 0 0 +EDGE2 5072 4692 -0.00873936 0.0824309 -0.0140049 1 0 1 1 0 0 +EDGE2 5072 4971 -1.03224 0.0502536 0.00631719 1 0 1 1 0 0 +EDGE2 5072 5071 -0.922599 -0.0589794 -0.004707 1 0 1 1 0 0 +EDGE2 5072 3612 -0.0187808 -0.0604588 0.033302 1 0 1 1 0 0 +EDGE2 5072 4572 -0.0643438 0.0265033 0.0127777 1 0 1 1 0 0 +EDGE2 5072 5011 -0.981941 0.0306193 0.0288722 1 0 1 1 0 0 +EDGE2 5072 4571 -0.97063 -0.0361981 -0.000515337 1 0 1 1 0 0 +EDGE2 5072 4671 -0.931774 -0.0151408 -0.0247233 1 0 1 1 0 0 +EDGE2 5072 4691 -1.00267 0.020791 -0.0396552 1 0 1 1 0 0 +EDGE2 5072 3611 -1.02538 0.00719156 0.0240383 1 0 1 1 0 0 +EDGE2 5073 4974 0.999571 0.0120922 -0.00330108 1 0 1 1 0 0 +EDGE2 5073 5014 1.06499 0.00664687 -0.0693855 1 0 1 1 0 0 +EDGE2 5073 4574 0.993836 -0.0290673 0.00859591 1 0 1 1 0 0 +EDGE2 5073 4674 1.01531 0.026951 0.0462205 1 0 1 1 0 0 +EDGE2 5073 4694 1.00916 -0.0747068 0.0149935 1 0 1 1 0 0 +EDGE2 5073 3614 1.02524 0.0483587 -0.00424983 1 0 1 1 0 0 +EDGE2 5073 4672 -0.986998 0.0349464 0.0128555 1 0 1 1 0 0 +EDGE2 5073 4972 -0.981508 0.0194852 0.00838957 1 0 1 1 0 0 +EDGE2 5073 4673 -0.0346598 0.00886221 -0.0332424 1 0 1 1 0 0 +EDGE2 5073 4973 0.0163157 0.030419 -0.0232819 1 0 1 1 0 0 +EDGE2 5073 5013 0.0196735 0.00446838 -0.015774 1 0 1 1 0 0 +EDGE2 5073 4693 0.0591552 -0.0744352 0.0150557 1 0 1 1 0 0 +EDGE2 5073 5072 -1.00827 0.134717 -0.00359982 1 0 1 1 0 0 +EDGE2 5073 3613 0.0430927 0.098028 -0.0076963 1 0 1 1 0 0 +EDGE2 5073 4573 0.0398623 -0.0062895 -0.0290743 1 0 1 1 0 0 +EDGE2 5073 5012 -1.05659 -0.05884 -0.0343559 1 0 1 1 0 0 +EDGE2 5073 4692 -1.03883 -0.0134646 0.0045517 1 0 1 1 0 0 +EDGE2 5073 3612 -0.952707 -0.0174586 -0.00544838 1 0 1 1 0 0 +EDGE2 5073 4572 -1.07684 0.0109191 0.0286221 1 0 1 1 0 0 +EDGE2 5074 4974 -0.0114785 0.00127231 -0.0152196 1 0 1 1 0 0 +EDGE2 5074 5015 0.955919 0.0353409 -0.0266062 1 0 1 1 0 0 +EDGE2 5074 4575 1.0408 -0.0021494 0.0278335 1 0 1 1 0 0 +EDGE2 5074 4695 1.01882 -0.0211926 0.00703567 1 0 1 1 0 0 +EDGE2 5074 4875 0.953298 0.00452162 -3.11397 1 0 1 1 0 0 +EDGE2 5074 4975 0.964935 -0.042459 -0.00429511 1 0 1 1 0 0 +EDGE2 5074 4675 0.947036 -0.143183 -0.00593398 1 0 1 1 0 0 +EDGE2 5074 3615 1.08239 0.0481645 -0.00573107 1 0 1 1 0 0 +EDGE2 5074 5014 0.0488051 -0.0128971 0.00628356 1 0 1 1 0 0 +EDGE2 5074 4574 0.00598547 0.0548133 -0.00474834 1 0 1 1 0 0 +EDGE2 5074 4674 -0.0777556 -0.0586008 -0.0161279 1 0 1 1 0 0 +EDGE2 5074 4694 0.0552888 -0.0470628 0.034126 1 0 1 1 0 0 +EDGE2 5074 3614 -0.0216316 0.00529816 -0.0251646 1 0 1 1 0 0 +EDGE2 5074 4673 -0.955135 0.0197409 0.0168041 1 0 1 1 0 0 +EDGE2 5074 4973 -1.04308 0.00269022 -0.0142814 1 0 1 1 0 0 +EDGE2 5074 5013 -1.00625 0.0490508 -0.0548476 1 0 1 1 0 0 +EDGE2 5074 5073 -0.98624 -0.0519908 0.00170811 1 0 1 1 0 0 +EDGE2 5074 4693 -0.971437 -0.00277889 0.0101318 1 0 1 1 0 0 +EDGE2 5074 3613 -1.01905 0.0403877 -0.0168769 1 0 1 1 0 0 +EDGE2 5074 4573 -1.03737 -0.0594188 -0.00376197 1 0 1 1 0 0 +EDGE2 5075 4976 -0.0494731 0.956183 1.55387 1 0 1 1 0 0 +EDGE2 5075 5016 0.0175176 0.949038 1.57294 1 0 1 1 0 0 +EDGE2 5075 4676 -0.0249972 1.02964 1.57912 1 0 1 1 0 0 +EDGE2 5075 4696 0.0398664 0.94977 1.59533 1 0 1 1 0 0 +EDGE2 5075 4576 0.162922 0.973338 1.57088 1 0 1 1 0 0 +EDGE2 5075 4974 -1.06676 -0.0274546 0.00596816 1 0 1 1 0 0 +EDGE2 5075 5015 -0.00530796 0.0225387 -5.84689e-05 1 0 1 1 0 0 +EDGE2 5075 4874 1.05518 -0.027853 -3.10362 1 0 1 1 0 0 +EDGE2 5075 4575 -0.0346408 -0.059148 0.000137707 1 0 1 1 0 0 +EDGE2 5075 4695 -0.0741521 0.0665366 0.0195962 1 0 1 1 0 0 +EDGE2 5075 4875 0.010288 -0.0257508 -3.1445 1 0 1 1 0 0 +EDGE2 5075 4975 -0.0477121 0.0518827 0.00278809 1 0 1 1 0 0 +EDGE2 5075 4675 -0.00260061 -0.0414594 0.0102032 1 0 1 1 0 0 +EDGE2 5075 5074 -1.0853 -0.0105229 -0.0265278 1 0 1 1 0 0 +EDGE2 5075 3615 -0.0604382 0.0184512 -0.0352939 1 0 1 1 0 0 +EDGE2 5075 5014 -1.02486 -0.0585899 -0.0276606 1 0 1 1 0 0 +EDGE2 5075 4876 0.0389945 -0.984735 -1.59727 1 0 1 1 0 0 +EDGE2 5075 3616 0.0239243 -1.0098 -1.56406 1 0 1 1 0 0 +EDGE2 5075 4574 -0.934286 0.0257443 0.00350053 1 0 1 1 0 0 +EDGE2 5075 4674 -1.00152 0.00753589 -0.0122832 1 0 1 1 0 0 +EDGE2 5075 4694 -0.997458 -0.0370973 0.000532506 1 0 1 1 0 0 +EDGE2 5075 3614 -0.918897 -0.0294032 0.0032517 1 0 1 1 0 0 +EDGE2 5076 5015 -0.943299 -0.082319 1.55056 1 0 1 1 0 0 +EDGE2 5076 5075 -0.997467 0.0598193 1.555 1 0 1 1 0 0 +EDGE2 5076 4575 -0.96646 0.0608487 1.57729 1 0 1 1 0 0 +EDGE2 5076 4695 -1.07497 0.0210766 1.57127 1 0 1 1 0 0 +EDGE2 5076 4875 -0.925135 0.101136 -1.55422 1 0 1 1 0 0 +EDGE2 5076 4975 -0.941259 0.0532038 1.5808 1 0 1 1 0 0 +EDGE2 5076 4675 -1.03031 0.0355022 1.56019 1 0 1 1 0 0 +EDGE2 5076 3615 -0.993437 -0.0177359 1.57477 1 0 1 1 0 0 +EDGE2 5076 3617 0.883618 0.0153414 -0.0256432 1 0 1 1 0 0 +EDGE2 5076 4876 0.0193651 -0.0196083 -0.0296264 1 0 1 1 0 0 +EDGE2 5076 3616 -0.0198616 -0.0851356 0.00298571 1 0 1 1 0 0 +EDGE2 5076 4877 1.02838 0.0348561 0.00826527 1 0 1 1 0 0 +EDGE2 5077 3617 0.0191489 0.0181577 0.00351161 1 0 1 1 0 0 +EDGE2 5077 4876 -1.02605 0.0111 0.00123285 1 0 1 1 0 0 +EDGE2 5077 5076 -1.03472 -0.0569839 -0.000883323 1 0 1 1 0 0 +EDGE2 5077 3616 -1.02176 -0.0375961 -0.0172443 1 0 1 1 0 0 +EDGE2 5077 4877 -0.0320195 -0.0304124 0.0232043 1 0 1 1 0 0 +EDGE2 5077 3618 1.00999 -0.0046649 0.0286449 1 0 1 1 0 0 +EDGE2 5077 4878 1.12668 0.147636 0.00357688 1 0 1 1 0 0 +EDGE2 5078 3619 0.886233 -0.0126143 -0.0146582 1 0 1 1 0 0 +EDGE2 5078 3617 -0.962476 -0.0454257 0.0284255 1 0 1 1 0 0 +EDGE2 5078 4877 -1.00139 0.0552009 0.0205394 1 0 1 1 0 0 +EDGE2 5078 5077 -0.860796 0.0459389 -0.00825844 1 0 1 1 0 0 +EDGE2 5078 3618 -0.104506 0.124709 0.0076298 1 0 1 1 0 0 +EDGE2 5078 4878 -0.0465881 -0.0880919 -0.0072535 1 0 1 1 0 0 +EDGE2 5078 4879 1.00611 0.00519253 0.00894314 1 0 1 1 0 0 +EDGE2 5079 3619 0.020187 0.0279892 -0.00286638 1 0 1 1 0 0 +EDGE2 5079 5078 -1.09658 -0.0311184 0.00384337 1 0 1 1 0 0 +EDGE2 5079 3618 -1.06282 0.0716558 -0.0376422 1 0 1 1 0 0 +EDGE2 5079 4878 -1.03836 0.0208878 0.00454147 1 0 1 1 0 0 +EDGE2 5079 4879 0.070835 0.0277475 0.0121057 1 0 1 1 0 0 +EDGE2 5079 4880 0.956137 0.00589889 -0.0217957 1 0 1 1 0 0 +EDGE2 5079 4960 0.931872 0.00446109 -3.20635 1 0 1 1 0 0 +EDGE2 5079 3620 1.00633 0.052317 -0.0327701 1 0 1 1 0 0 +EDGE2 5080 3619 -1.05398 -0.0154365 0.00677204 1 0 1 1 0 0 +EDGE2 5080 5079 -1.04768 0.0295708 0.00800209 1 0 1 1 0 0 +EDGE2 5080 4879 -0.998816 -0.0348491 0.0283579 1 0 1 1 0 0 +EDGE2 5080 4959 1.08452 0.064967 -3.14401 1 0 1 1 0 0 +EDGE2 5080 4880 0.0124916 -0.0455461 -0.00275246 1 0 1 1 0 0 +EDGE2 5080 4960 -0.0461605 -0.0233689 -3.12847 1 0 1 1 0 0 +EDGE2 5080 3620 0.00988258 -0.0115084 0.0147559 1 0 1 1 0 0 +EDGE2 5080 3621 0.0481879 -0.98571 -1.51547 1 0 1 1 0 0 +EDGE2 5080 4881 0.0468405 -0.918393 -1.5298 1 0 1 1 0 0 +EDGE2 5080 4961 -0.0164934 -0.973422 -1.59433 1 0 1 1 0 0 +EDGE2 5081 4880 -1.04018 0.0498881 -1.61402 1 0 1 1 0 0 +EDGE2 5081 4960 -1.06696 0.0703814 1.59521 1 0 1 1 0 0 +EDGE2 5081 5080 -1.0713 0.0385423 -1.59322 1 0 1 1 0 0 +EDGE2 5081 3620 -1.04747 -0.0284573 -1.56688 1 0 1 1 0 0 +EDGE2 5082 5081 -1.01285 0.0769025 -0.00143011 1 0 1 1 0 0 +EDGE2 5083 5082 -0.951767 -0.0672934 0.0388266 1 0 1 1 0 0 +EDGE2 5084 5083 -1.00126 -0.013087 0.00228864 1 0 1 1 0 0 +EDGE2 5085 5084 -1.12292 -0.068519 -0.0187594 1 0 1 1 0 0 +EDGE2 5086 5085 -0.996801 -0.0572378 -1.58906 1 0 1 1 0 0 +EDGE2 5087 5086 -0.971062 0.0189059 0.0112809 1 0 1 1 0 0 +EDGE2 5088 5087 -0.962156 0.0339883 -0.00694796 1 0 1 1 0 0 +EDGE2 5089 4850 0.981689 -0.0185699 -3.11508 1 0 1 1 0 0 +EDGE2 5089 4870 0.985785 0.0358087 -3.14046 1 0 1 1 0 0 +EDGE2 5089 4790 0.93365 -0.000419611 -3.15507 1 0 1 1 0 0 +EDGE2 5089 5088 -0.995787 0.0914648 0.0365657 1 0 1 1 0 0 +EDGE2 5090 4849 1.04929 -0.0266032 -3.12023 1 0 1 1 0 0 +EDGE2 5090 4869 0.915116 0.0689192 -3.14357 1 0 1 1 0 0 +EDGE2 5090 4789 1.00579 -0.0718262 -3.13408 1 0 1 1 0 0 +EDGE2 5090 4791 0.0421217 -0.975289 -1.57455 1 0 1 1 0 0 +EDGE2 5090 4851 0.050343 -1.06017 -1.57246 1 0 1 1 0 0 +EDGE2 5090 4871 -0.023316 0.915497 1.56489 1 0 1 1 0 0 +EDGE2 5090 4850 0.0432195 -0.0851474 -3.15491 1 0 1 1 0 0 +EDGE2 5090 4870 -0.0417357 -0.00953995 -3.14874 1 0 1 1 0 0 +EDGE2 5090 4790 -0.0449872 -0.0653598 -3.14906 1 0 1 1 0 0 +EDGE2 5090 5089 -0.981896 -0.0391482 -0.0202447 1 0 1 1 0 0 +EDGE2 5091 4792 0.985363 -0.00824757 -0.0131395 1 0 1 1 0 0 +EDGE2 5091 4852 1.02492 0.00913547 -0.0182761 1 0 1 1 0 0 +EDGE2 5091 4791 -0.00850809 -0.0546809 -0.0166626 1 0 1 1 0 0 +EDGE2 5091 4851 0.0751999 -0.00303219 -0.0339519 1 0 1 1 0 0 +EDGE2 5091 4850 -1.05523 0.0473534 -1.56171 1 0 1 1 0 0 +EDGE2 5091 4870 -1.05922 0.0396073 -1.62201 1 0 1 1 0 0 +EDGE2 5091 5090 -1.06212 0.0479186 1.55239 1 0 1 1 0 0 +EDGE2 5091 4790 -0.987376 0.0192557 -1.59935 1 0 1 1 0 0 +EDGE2 5092 4793 1.03066 0.00663669 -0.0073198 1 0 1 1 0 0 +EDGE2 5092 4853 0.922095 0.16826 0.0122784 1 0 1 1 0 0 +EDGE2 5092 4792 0.0332877 0.0846837 0.0141119 1 0 1 1 0 0 +EDGE2 5092 4852 0.0422055 0.0682492 0.0060087 1 0 1 1 0 0 +EDGE2 5092 4791 -1.04544 -0.0112938 0.0464839 1 0 1 1 0 0 +EDGE2 5092 4851 -0.958198 -0.000227053 0.00284403 1 0 1 1 0 0 +EDGE2 5092 5091 -1.05224 -0.136512 0.00739512 1 0 1 1 0 0 +EDGE2 5093 4794 1.03932 0.0382119 -0.0177888 1 0 1 1 0 0 +EDGE2 5093 4854 0.923312 -0.101876 -0.0339507 1 0 1 1 0 0 +EDGE2 5093 4793 0.0171876 0.0265286 -0.0306772 1 0 1 1 0 0 +EDGE2 5093 4853 -0.0397997 0.0195443 -0.0240895 1 0 1 1 0 0 +EDGE2 5093 4792 -0.983178 -0.0185516 -0.00260093 1 0 1 1 0 0 +EDGE2 5093 4852 -1.04186 0.132854 -0.0366364 1 0 1 1 0 0 +EDGE2 5093 5092 -1.03106 -0.0395069 -0.0060903 1 0 1 1 0 0 +EDGE2 5094 4795 0.972997 -0.101245 0.000123791 1 0 1 1 0 0 +EDGE2 5094 4855 1.05118 0.0315247 0.0170209 1 0 1 1 0 0 +EDGE2 5094 4794 -0.0684065 0.105039 0.00358436 1 0 1 1 0 0 +EDGE2 5094 4854 0.0209056 -0.0204042 0.00785847 1 0 1 1 0 0 +EDGE2 5094 4793 -0.992366 -0.0276418 -0.00337861 1 0 1 1 0 0 +EDGE2 5094 4853 -1.02773 -0.0732226 0.00385171 1 0 1 1 0 0 +EDGE2 5094 5093 -0.991786 0.0129296 0.02279 1 0 1 1 0 0 +EDGE2 5095 4856 0.0199373 1.04507 1.60686 1 0 1 1 0 0 +EDGE2 5095 4796 0.114038 0.989003 1.62288 1 0 1 1 0 0 +EDGE2 5095 4795 -0.00718334 0.0388742 -0.00820965 1 0 1 1 0 0 +EDGE2 5095 4855 -0.00344415 0.0236945 -0.0213622 1 0 1 1 0 0 +EDGE2 5095 4794 -1.00421 -0.0316415 -0.00509248 1 0 1 1 0 0 +EDGE2 5095 4854 -1.02853 -0.0405068 0.000438764 1 0 1 1 0 0 +EDGE2 5095 5094 -0.996837 0.0600948 0.00301671 1 0 1 1 0 0 +EDGE2 5096 4857 1.00858 -0.0550778 -0.0351227 1 0 1 1 0 0 +EDGE2 5096 4797 1.01812 0.00665578 -0.0337702 1 0 1 1 0 0 +EDGE2 5096 4856 0.0918369 -0.0627229 0.0290405 1 0 1 1 0 0 +EDGE2 5096 4796 0.00325199 0.016484 0.00766634 1 0 1 1 0 0 +EDGE2 5096 5095 -0.984571 0.0509086 -1.57328 1 0 1 1 0 0 +EDGE2 5096 4795 -1.05501 0.0490276 -1.56483 1 0 1 1 0 0 +EDGE2 5096 4855 -0.977213 -0.00196722 -1.589 1 0 1 1 0 0 +EDGE2 5097 4857 0.0508523 -0.00727556 0.0193649 1 0 1 1 0 0 +EDGE2 5097 4798 0.923773 -0.0255125 -0.0148392 1 0 1 1 0 0 +EDGE2 5097 4858 1.01368 0.0634591 -0.000235844 1 0 1 1 0 0 +EDGE2 5097 4797 0.00986499 0.0354062 -0.0219831 1 0 1 1 0 0 +EDGE2 5097 4856 -1.03197 0.0368105 0.0332049 1 0 1 1 0 0 +EDGE2 5097 5096 -1.0721 -0.0800805 0.00507625 1 0 1 1 0 0 +EDGE2 5097 4796 -1.02333 -0.0194362 0.0136672 1 0 1 1 0 0 +EDGE2 5098 4859 1.00011 -0.0368192 0.0158715 1 0 1 1 0 0 +EDGE2 5098 4799 0.997284 0.034415 0.0313719 1 0 1 1 0 0 +EDGE2 5098 4857 -0.924429 0.0550628 -0.0291449 1 0 1 1 0 0 +EDGE2 5098 4798 -0.0514216 0.0540901 0.0111864 1 0 1 1 0 0 +EDGE2 5098 4858 0.0633671 -0.0194991 0.0160063 1 0 1 1 0 0 +EDGE2 5098 5097 -1.00221 0.015754 -0.00632375 1 0 1 1 0 0 +EDGE2 5098 4797 -0.965011 0.0578979 -0.00039704 1 0 1 1 0 0 +EDGE2 5099 4780 0.973225 -0.0154353 -3.13022 1 0 1 1 0 0 +EDGE2 5099 4800 0.93023 -0.0318415 -0.001563 1 0 1 1 0 0 +EDGE2 5099 4860 1.06839 0.055766 0.00590956 1 0 1 1 0 0 +EDGE2 5099 4859 -0.02326 -0.00900507 0.0132145 1 0 1 1 0 0 +EDGE2 5099 4799 -0.0445642 -0.021096 -0.000740616 1 0 1 1 0 0 +EDGE2 5099 4798 -1.01514 -0.023189 -0.016518 1 0 1 1 0 0 +EDGE2 5099 5098 -0.966293 0.0286942 0.0388446 1 0 1 1 0 0 +EDGE2 5099 4858 -1.07263 0.14325 0.0290218 1 0 1 1 0 0 +EDGE2 5100 4779 1.0813 -0.0455095 -3.13409 1 0 1 1 0 0 +EDGE2 5100 4780 -0.0311693 -0.0625884 -3.12966 1 0 1 1 0 0 +EDGE2 5100 4800 -0.0281462 0.0411505 0.0155084 1 0 1 1 0 0 +EDGE2 5100 4860 -0.00430106 -0.0239613 -0.0288317 1 0 1 1 0 0 +EDGE2 5100 4859 -0.944348 0.0426775 -0.00677328 1 0 1 1 0 0 +EDGE2 5100 5099 -0.947451 0.00508247 0.0290442 1 0 1 1 0 0 +EDGE2 5100 4781 0.0651362 1.02929 1.57036 1 0 1 1 0 0 +EDGE2 5100 4801 0.00201947 0.955161 1.59509 1 0 1 1 0 0 +EDGE2 5100 4861 0.00643123 0.915925 1.58452 1 0 1 1 0 0 +EDGE2 5100 4799 -1.05809 -0.0112426 0.00105009 1 0 1 1 0 0 +EDGE2 5101 4782 0.998391 0.0406579 0.0540762 1 0 1 1 0 0 +EDGE2 5101 5100 -0.993598 -0.0545009 -1.58077 1 0 1 1 0 0 +EDGE2 5101 4780 -0.991023 -0.00203975 1.56767 1 0 1 1 0 0 +EDGE2 5101 4800 -0.974604 0.0827369 -1.60503 1 0 1 1 0 0 +EDGE2 5101 4860 -1.01155 0.0686694 -1.54405 1 0 1 1 0 0 +EDGE2 5101 4781 -0.012725 -0.0377722 -0.0058548 1 0 1 1 0 0 +EDGE2 5101 4801 -0.0189082 -0.0113249 -0.0223067 1 0 1 1 0 0 +EDGE2 5101 4861 0.0769738 0.0114136 0.0184981 1 0 1 1 0 0 +EDGE2 5101 4802 0.963028 -0.00292451 0.0291122 1 0 1 1 0 0 +EDGE2 5101 4862 0.952884 0.0238075 -0.0383043 1 0 1 1 0 0 +EDGE2 5102 4782 -0.00835386 -0.0321008 -0.0125717 1 0 1 1 0 0 +EDGE2 5102 5101 -0.967141 0.068024 0.0173749 1 0 1 1 0 0 +EDGE2 5102 4781 -0.960576 0.0526737 -0.0406457 1 0 1 1 0 0 +EDGE2 5102 4801 -0.995937 -0.0179052 -0.0371255 1 0 1 1 0 0 +EDGE2 5102 4861 -0.977938 0.0669454 0.0132222 1 0 1 1 0 0 +EDGE2 5102 4802 0.0134885 0.0622746 0.0180804 1 0 1 1 0 0 +EDGE2 5102 4862 0.0289196 -0.0204036 -0.0150296 1 0 1 1 0 0 +EDGE2 5102 4783 0.981049 0.0225208 -0.0299149 1 0 1 1 0 0 +EDGE2 5102 4863 0.913412 -0.0992486 0.00657339 1 0 1 1 0 0 +EDGE2 5102 4803 0.971373 0.0487653 0.00583457 1 0 1 1 0 0 +EDGE2 5103 4782 -0.961147 0.0386367 0.0195071 1 0 1 1 0 0 +EDGE2 5103 5102 -1.0275 -0.0607567 -0.00639729 1 0 1 1 0 0 +EDGE2 5103 4802 -0.986936 0.0166125 -0.00267096 1 0 1 1 0 0 +EDGE2 5103 4862 -0.97398 -0.0204491 -0.0281761 1 0 1 1 0 0 +EDGE2 5103 4784 1.05043 0.0495235 0.00729304 1 0 1 1 0 0 +EDGE2 5103 4783 -0.0201441 -0.00562383 0.0107184 1 0 1 1 0 0 +EDGE2 5103 4863 -0.0695538 0.06689 0.0273963 1 0 1 1 0 0 +EDGE2 5103 4803 -0.0300361 0.0525787 -0.00479185 1 0 1 1 0 0 +EDGE2 5103 4864 1.05084 0.0114822 0.0127068 1 0 1 1 0 0 +EDGE2 5103 4804 0.996047 -0.0171536 -0.00461129 1 0 1 1 0 0 +EDGE2 5104 4784 0.081662 0.0193923 -0.000477655 1 0 1 1 0 0 +EDGE2 5104 4783 -0.89305 -0.00110922 -0.0107217 1 0 1 1 0 0 +EDGE2 5104 4863 -1.01734 0.002367 -0.0504782 1 0 1 1 0 0 +EDGE2 5104 5103 -1.012 -0.0622694 -0.00340119 1 0 1 1 0 0 +EDGE2 5104 4803 -1.01517 -0.0689465 -0.00700633 1 0 1 1 0 0 +EDGE2 5104 4864 -0.118782 -0.0593243 -0.0279567 1 0 1 1 0 0 +EDGE2 5104 4804 -0.0602658 0.0985096 0.0311721 1 0 1 1 0 0 +EDGE2 5104 4825 0.968139 0.0263338 -3.14742 1 0 1 1 0 0 +EDGE2 5104 4865 0.905917 0.0219242 0.0228151 1 0 1 1 0 0 +EDGE2 5104 4845 1.01124 -0.0183807 -3.16026 1 0 1 1 0 0 +EDGE2 5104 4785 1.0106 0.0285329 0.00459956 1 0 1 1 0 0 +EDGE2 5104 4805 0.99269 -0.0880266 0.00928514 1 0 1 1 0 0 +EDGE2 5105 4826 -0.00641207 -1.05525 -1.54825 1 0 1 1 0 0 +EDGE2 5105 4806 0.0351328 -0.885592 -1.57385 1 0 1 1 0 0 +EDGE2 5105 4784 -0.964452 0.0552777 -0.0173594 1 0 1 1 0 0 +EDGE2 5105 4864 -0.990906 0.0129779 0.0206458 1 0 1 1 0 0 +EDGE2 5105 5104 -0.989965 0.0479115 -0.012981 1 0 1 1 0 0 +EDGE2 5105 4804 -1.06456 0.0681943 -0.00430972 1 0 1 1 0 0 +EDGE2 5105 4825 0.0183921 0.05582 -3.10624 1 0 1 1 0 0 +EDGE2 5105 4865 0.011825 -0.0588472 0.00910066 1 0 1 1 0 0 +EDGE2 5105 4845 0.0126891 0.0778546 -3.16879 1 0 1 1 0 0 +EDGE2 5105 4844 1.11065 0.0645744 -3.10945 1 0 1 1 0 0 +EDGE2 5105 4785 0.00894623 0.0139845 0.0266443 1 0 1 1 0 0 +EDGE2 5105 4805 -0.0593175 -0.112451 -0.0188746 1 0 1 1 0 0 +EDGE2 5105 4824 1.057 0.0964981 -3.11777 1 0 1 1 0 0 +EDGE2 5105 4786 -0.0414453 0.985842 1.57141 1 0 1 1 0 0 +EDGE2 5105 4846 -0.055146 1.0993 1.58924 1 0 1 1 0 0 +EDGE2 5105 4866 -0.0197879 0.899695 1.58457 1 0 1 1 0 0 +EDGE2 5106 4825 -1.03322 -0.0201314 1.56675 1 0 1 1 0 0 +EDGE2 5106 4865 -0.965573 0.0657279 -1.55849 1 0 1 1 0 0 +EDGE2 5106 5105 -1.04418 0.0030446 -1.61133 1 0 1 1 0 0 +EDGE2 5106 4845 -0.940546 0.0566658 1.57039 1 0 1 1 0 0 +EDGE2 5106 4785 -0.899072 -0.0112445 -1.59699 1 0 1 1 0 0 +EDGE2 5106 4805 -1.02367 0.0620837 -1.58088 1 0 1 1 0 0 +EDGE2 5106 4786 0.0287943 0.029459 -0.00160695 1 0 1 1 0 0 +EDGE2 5106 4846 0.0232512 0.0201209 -0.00231067 1 0 1 1 0 0 +EDGE2 5106 4866 0.0604642 0.0581414 -0.0305227 1 0 1 1 0 0 +EDGE2 5106 4787 0.982558 0.0272936 -0.00287471 1 0 1 1 0 0 +EDGE2 5106 4847 1.02037 -0.00454818 0.00396677 1 0 1 1 0 0 +EDGE2 5106 4867 1.13139 -0.00479566 0.00460245 1 0 1 1 0 0 +EDGE2 5107 5106 -0.87566 -0.0449035 -0.00805639 1 0 1 1 0 0 +EDGE2 5107 4786 -1.05058 0.0560126 0.0120517 1 0 1 1 0 0 +EDGE2 5107 4846 -0.972157 -0.00659179 -0.0352812 1 0 1 1 0 0 +EDGE2 5107 4866 -1.0391 0.0229947 0.000169661 1 0 1 1 0 0 +EDGE2 5107 4787 0.0852593 0.0715267 0.0359375 1 0 1 1 0 0 +EDGE2 5107 4847 -0.072059 0.00360064 -0.0244518 1 0 1 1 0 0 +EDGE2 5107 4867 -0.0293714 0.0893012 0.00510342 1 0 1 1 0 0 +EDGE2 5107 4788 0.96208 0.0612707 -0.0053381 1 0 1 1 0 0 +EDGE2 5107 4848 0.967005 0.0793844 -0.0213243 1 0 1 1 0 0 +EDGE2 5107 4868 1.0721 0.04959 -0.034707 1 0 1 1 0 0 +EDGE2 5108 5107 -0.989777 -0.0140931 -0.00317671 1 0 1 1 0 0 +EDGE2 5108 4787 -0.95917 -0.0552519 -0.00559243 1 0 1 1 0 0 +EDGE2 5108 4847 -1.08754 0.0264413 0.00715269 1 0 1 1 0 0 +EDGE2 5108 4867 -0.992969 0.0293363 0.00351317 1 0 1 1 0 0 +EDGE2 5108 4788 0.0537132 0.0972329 0.0209938 1 0 1 1 0 0 +EDGE2 5108 4848 0.0162314 -0.0191253 -0.0378556 1 0 1 1 0 0 +EDGE2 5108 4868 -0.0750274 -0.0545548 0.00478239 1 0 1 1 0 0 +EDGE2 5108 4849 1.05559 -0.0784972 -0.00425193 1 0 1 1 0 0 +EDGE2 5108 4869 0.967083 -0.0216718 0.00179122 1 0 1 1 0 0 +EDGE2 5108 4789 1.05292 0.0261396 -0.0129852 1 0 1 1 0 0 +EDGE2 5109 5108 -0.983272 0.0105389 -0.0304048 1 0 1 1 0 0 +EDGE2 5109 4788 -1.04204 0.0878912 -0.0336401 1 0 1 1 0 0 +EDGE2 5109 4848 -1.12587 0.0460037 -0.0260083 1 0 1 1 0 0 +EDGE2 5109 4868 -1.06069 0.0504452 0.015594 1 0 1 1 0 0 +EDGE2 5109 4849 -0.0067035 -0.033233 -0.00468352 1 0 1 1 0 0 +EDGE2 5109 4869 0.0879102 0.00954006 -0.0211345 1 0 1 1 0 0 +EDGE2 5109 4789 -0.0551885 0.02937 -0.00640071 1 0 1 1 0 0 +EDGE2 5109 4850 0.920265 -0.000484249 0.00871558 1 0 1 1 0 0 +EDGE2 5109 4870 0.933661 -0.0044661 0.00251328 1 0 1 1 0 0 +EDGE2 5109 5090 0.966967 -0.0173285 -3.16129 1 0 1 1 0 0 +EDGE2 5109 4790 1.09653 0.000700537 0.0294941 1 0 1 1 0 0 +EDGE2 5110 4849 -1.09392 0.0489797 0.0227108 1 0 1 1 0 0 +EDGE2 5110 4869 -1.03592 -0.0276659 0.0164892 1 0 1 1 0 0 +EDGE2 5110 5109 -0.983788 0.0430889 -0.0227856 1 0 1 1 0 0 +EDGE2 5110 4789 -1.04026 -0.0921473 0.0308046 1 0 1 1 0 0 +EDGE2 5110 4791 0.0345431 1.01412 1.56958 1 0 1 1 0 0 +EDGE2 5110 4851 -0.00496524 1.0167 1.55586 1 0 1 1 0 0 +EDGE2 5110 5091 0.0414717 0.967915 1.62873 1 0 1 1 0 0 +EDGE2 5110 4871 -0.0428198 -1.03934 -1.55905 1 0 1 1 0 0 +EDGE2 5110 4850 -0.0335762 -0.028262 -0.0147887 1 0 1 1 0 0 +EDGE2 5110 4870 -0.0320501 -0.0189743 0.0238103 1 0 1 1 0 0 +EDGE2 5110 5090 0.0382417 -0.013922 -3.13653 1 0 1 1 0 0 +EDGE2 5110 4790 -0.0321884 -0.0157463 0.0142782 1 0 1 1 0 0 +EDGE2 5110 5089 1.00076 -0.0483283 -3.14242 1 0 1 1 0 0 +EDGE2 5111 5110 -0.979915 -0.0497075 -1.57005 1 0 1 1 0 0 +EDGE2 5111 4792 1.04179 -0.0353187 0.0184799 1 0 1 1 0 0 +EDGE2 5111 4852 1.02877 0.00783631 -0.0123696 1 0 1 1 0 0 +EDGE2 5111 5092 1.11088 -0.0391253 0.00618908 1 0 1 1 0 0 +EDGE2 5111 4791 0.0279998 -0.00435177 0.000872709 1 0 1 1 0 0 +EDGE2 5111 4851 -0.102906 -0.0437406 0.0269386 1 0 1 1 0 0 +EDGE2 5111 5091 -0.0370226 0.0144707 0.0292909 1 0 1 1 0 0 +EDGE2 5111 4850 -1.03627 0.00182587 -1.59357 1 0 1 1 0 0 +EDGE2 5111 4870 -0.892771 -0.0256021 -1.56125 1 0 1 1 0 0 +EDGE2 5111 5090 -1.0667 -0.0141876 1.59198 1 0 1 1 0 0 +EDGE2 5111 4790 -1.03186 0.073717 -1.60364 1 0 1 1 0 0 +EDGE2 5112 4793 1.00364 -0.0605508 0.00567346 1 0 1 1 0 0 +EDGE2 5112 4853 1.03036 -0.0168079 0.00764522 1 0 1 1 0 0 +EDGE2 5112 5093 0.966151 0.0564518 0.0194294 1 0 1 1 0 0 +EDGE2 5112 5111 -1.04675 -0.0818453 0.011395 1 0 1 1 0 0 +EDGE2 5112 4792 0.0886152 -0.0979257 0.0313209 1 0 1 1 0 0 +EDGE2 5112 4852 0.0782579 0.0470475 0.00754058 1 0 1 1 0 0 +EDGE2 5112 5092 -0.0257003 0.00754309 -0.000950412 1 0 1 1 0 0 +EDGE2 5112 4791 -0.996188 0.0550252 -0.0360772 1 0 1 1 0 0 +EDGE2 5112 4851 -1.02114 -0.0193536 0.0215239 1 0 1 1 0 0 +EDGE2 5112 5091 -1.08211 -0.0225503 -0.000795815 1 0 1 1 0 0 +EDGE2 5113 5112 -1.00856 0.0247686 0.0146173 1 0 1 1 0 0 +EDGE2 5113 4794 0.94586 -0.00713634 0.0121157 1 0 1 1 0 0 +EDGE2 5113 4854 0.963851 -0.0726498 -0.0131838 1 0 1 1 0 0 +EDGE2 5113 5094 0.993592 -0.0214351 -0.0250272 1 0 1 1 0 0 +EDGE2 5113 4793 -0.0118057 0.0894539 0.000227068 1 0 1 1 0 0 +EDGE2 5113 4853 -0.0775354 0.00558839 0.00754223 1 0 1 1 0 0 +EDGE2 5113 5093 -0.0581862 0.0120224 -0.0192521 1 0 1 1 0 0 +EDGE2 5113 4792 -0.979075 -0.0297232 0.00302853 1 0 1 1 0 0 +EDGE2 5113 4852 -0.990821 0.0448268 -0.0293974 1 0 1 1 0 0 +EDGE2 5113 5092 -1.03433 0.0243945 0.0455312 1 0 1 1 0 0 +EDGE2 5114 5095 1.02672 -0.0238344 -0.0224447 1 0 1 1 0 0 +EDGE2 5114 4795 1.00432 -0.0535463 0.000467153 1 0 1 1 0 0 +EDGE2 5114 4855 0.98372 0.045971 -0.0174567 1 0 1 1 0 0 +EDGE2 5114 5113 -0.973689 0.0494145 0.0130079 1 0 1 1 0 0 +EDGE2 5114 4794 0.0385996 0.00333842 -0.00338688 1 0 1 1 0 0 +EDGE2 5114 4854 0.0235652 0.0388109 -0.0420134 1 0 1 1 0 0 +EDGE2 5114 5094 -0.0348109 -0.0242652 -0.00590818 1 0 1 1 0 0 +EDGE2 5114 4793 -0.987408 0.0312689 -0.00992146 1 0 1 1 0 0 +EDGE2 5114 4853 -1.02291 0.000838742 0.0333511 1 0 1 1 0 0 +EDGE2 5114 5093 -1.05492 -0.0195548 -0.0134984 1 0 1 1 0 0 +EDGE2 5115 4856 -0.0602127 0.941066 1.56977 1 0 1 1 0 0 +EDGE2 5115 5096 0.0275416 1.03745 1.58314 1 0 1 1 0 0 +EDGE2 5115 4796 -0.0538722 1.04178 1.54824 1 0 1 1 0 0 +EDGE2 5115 5114 -0.993463 0.014805 -0.0170228 1 0 1 1 0 0 +EDGE2 5115 5095 0.0147094 -0.0161395 0.0189306 1 0 1 1 0 0 +EDGE2 5115 4795 0.0262188 0.0254532 0.0308664 1 0 1 1 0 0 +EDGE2 5115 4855 -0.0322895 -0.0624876 -0.0152205 1 0 1 1 0 0 +EDGE2 5115 4794 -1.06814 0.00332546 -0.00897167 1 0 1 1 0 0 +EDGE2 5115 4854 -1.03816 -0.00402146 -0.0180252 1 0 1 1 0 0 +EDGE2 5115 5094 -1.03312 0.0546025 0.0206793 1 0 1 1 0 0 +EDGE2 5116 5095 -0.979815 0.0155251 1.59748 1 0 1 1 0 0 +EDGE2 5116 5115 -0.970472 -0.0193217 1.58276 1 0 1 1 0 0 +EDGE2 5116 4795 -1.07599 -0.0141249 1.56333 1 0 1 1 0 0 +EDGE2 5116 4855 -0.957293 0.0592995 1.61281 1 0 1 1 0 0 +EDGE2 5117 5116 -0.985206 0.0832272 0.0439953 1 0 1 1 0 0 +EDGE2 5118 5117 -1.07606 0.015744 0.00233453 1 0 1 1 0 0 +EDGE2 5119 5118 -1.00279 0.01734 -0.0171405 1 0 1 1 0 0 +EDGE2 5120 5119 -0.963452 0.0116946 -0.00704836 1 0 1 1 0 0 +EDGE2 5121 5120 -1.01525 0.0208596 -1.6107 1 0 1 1 0 0 +EDGE2 5122 5121 -0.981246 0.0322562 -0.00589133 1 0 1 1 0 0 +EDGE2 5123 5122 -1.01439 -0.0610991 0.000942069 1 0 1 1 0 0 +EDGE2 5124 5123 -1.02661 -0.00562351 0.0177793 1 0 1 1 0 0 +EDGE2 5125 5124 -1.01669 -0.00902802 0.00814672 1 0 1 1 0 0 +EDGE2 5126 5125 -0.955318 -0.0110123 -1.59846 1 0 1 1 0 0 +EDGE2 5127 5126 -1.0885 0.00376557 0.0104333 1 0 1 1 0 0 +EDGE2 5128 5127 -1.00111 -0.00601395 -0.00825092 1 0 1 1 0 0 +EDGE2 5129 5128 -0.976094 -0.0781228 0.019034 1 0 1 1 0 0 +EDGE2 5130 5129 -0.905807 0.0154941 0.0203687 1 0 1 1 0 0 +EDGE2 5131 5130 -1.00736 0.0110251 -1.55459 1 0 1 1 0 0 +EDGE2 5132 5131 -0.956957 -0.0966069 -0.02018 1 0 1 1 0 0 +EDGE2 5133 5132 -0.983419 -0.00797199 -0.0210965 1 0 1 1 0 0 +EDGE2 5134 5133 -0.96201 0.0716216 -0.0196526 1 0 1 1 0 0 +EDGE2 5134 5095 0.972963 -0.0839366 -3.13094 1 0 1 1 0 0 +EDGE2 5134 5115 0.974741 -0.0920333 -3.16658 1 0 1 1 0 0 +EDGE2 5134 4795 0.965461 -0.0257393 -3.15647 1 0 1 1 0 0 +EDGE2 5134 4855 1.0426 -0.0250405 -3.16226 1 0 1 1 0 0 +EDGE2 5135 4856 -0.0164664 -1.02525 -1.58814 1 0 1 1 0 0 +EDGE2 5135 5096 0.00784359 -0.990382 -1.55056 1 0 1 1 0 0 +EDGE2 5135 4796 0.0161922 -0.987134 -1.57449 1 0 1 1 0 0 +EDGE2 5135 5114 1.0553 0.00170493 -3.16313 1 0 1 1 0 0 +EDGE2 5135 5095 0.0232569 -0.0519634 -3.16826 1 0 1 1 0 0 +EDGE2 5135 5134 -1.08726 -0.0559885 0.0137937 1 0 1 1 0 0 +EDGE2 5135 5115 -0.0210945 -0.0112381 -3.12171 1 0 1 1 0 0 +EDGE2 5135 4795 -0.0700317 -0.00297196 -3.1325 1 0 1 1 0 0 +EDGE2 5135 4855 -0.0194244 0.0459208 -3.14077 1 0 1 1 0 0 +EDGE2 5135 5116 0.0530608 1.06084 1.57827 1 0 1 1 0 0 +EDGE2 5135 4794 1.01423 -0.070658 -3.15649 1 0 1 1 0 0 +EDGE2 5135 4854 0.972319 0.0310007 -3.14808 1 0 1 1 0 0 +EDGE2 5135 5094 1.05515 0.0213965 -3.13942 1 0 1 1 0 0 +EDGE2 5136 4857 1.04644 0.0194254 -0.00872517 1 0 1 1 0 0 +EDGE2 5136 5097 0.982045 0.0277489 -0.0137816 1 0 1 1 0 0 +EDGE2 5136 4797 0.968442 -0.0356538 -0.00476146 1 0 1 1 0 0 +EDGE2 5136 4856 -0.0715632 -0.0870664 0.0200957 1 0 1 1 0 0 +EDGE2 5136 5096 -0.0137166 0.105505 -0.0223755 1 0 1 1 0 0 +EDGE2 5136 4796 0.00625594 -0.0135132 0.0128156 1 0 1 1 0 0 +EDGE2 5136 5095 -1.06504 -0.0802119 -1.55568 1 0 1 1 0 0 +EDGE2 5136 5135 -0.948613 -0.0822038 1.56135 1 0 1 1 0 0 +EDGE2 5136 5115 -0.956162 -0.000643481 -1.55603 1 0 1 1 0 0 +EDGE2 5136 4795 -0.996317 -0.03224 -1.55982 1 0 1 1 0 0 +EDGE2 5136 4855 -1.00299 0.012357 -1.57789 1 0 1 1 0 0 +EDGE2 5137 4857 0.0500439 -0.0315565 0.0219129 1 0 1 1 0 0 +EDGE2 5137 4798 0.971459 -0.0883768 0.00683633 1 0 1 1 0 0 +EDGE2 5137 5098 1.09653 0.0802138 0.0101888 1 0 1 1 0 0 +EDGE2 5137 4858 1.0776 -0.033387 -0.00267561 1 0 1 1 0 0 +EDGE2 5137 5097 0.0201812 -0.0419341 0.0275642 1 0 1 1 0 0 +EDGE2 5137 5136 -0.980787 0.0623873 -0.00198723 1 0 1 1 0 0 +EDGE2 5137 4797 0.0215735 0.0530234 -0.0310483 1 0 1 1 0 0 +EDGE2 5137 4856 -1.01089 0.0464127 0.00590881 1 0 1 1 0 0 +EDGE2 5137 5096 -0.884497 -0.0466382 0.00159993 1 0 1 1 0 0 +EDGE2 5137 4796 -0.92326 -0.0170535 -0.00338053 1 0 1 1 0 0 +EDGE2 5138 4859 1.07118 0.0423636 0.0490674 1 0 1 1 0 0 +EDGE2 5138 5099 1.02006 0.00875551 0.0353758 1 0 1 1 0 0 +EDGE2 5138 4799 0.975514 -0.0842439 0.00386423 1 0 1 1 0 0 +EDGE2 5138 4857 -0.989203 0.112739 0.00562437 1 0 1 1 0 0 +EDGE2 5138 4798 -0.0111801 -0.0119747 0.00996322 1 0 1 1 0 0 +EDGE2 5138 5098 -0.0278732 -0.0213584 0.00134181 1 0 1 1 0 0 +EDGE2 5138 4858 0.0133863 -0.0982971 -0.00439395 1 0 1 1 0 0 +EDGE2 5138 5137 -1.05232 -0.0218903 0.00254262 1 0 1 1 0 0 +EDGE2 5138 5097 -0.985559 -0.0201703 0.0241048 1 0 1 1 0 0 +EDGE2 5138 4797 -0.967663 -0.102299 0.0151425 1 0 1 1 0 0 +EDGE2 5139 5100 0.970025 0.0158211 -0.0210612 1 0 1 1 0 0 +EDGE2 5139 4780 1.04864 -0.019367 -3.12988 1 0 1 1 0 0 +EDGE2 5139 4800 1.00376 -0.0316787 -0.00740888 1 0 1 1 0 0 +EDGE2 5139 4860 1.00364 -0.00996042 -0.0175133 1 0 1 1 0 0 +EDGE2 5139 4859 -0.0461118 0.0166044 0.0132022 1 0 1 1 0 0 +EDGE2 5139 5099 -0.0918853 0.00942815 -0.0369318 1 0 1 1 0 0 +EDGE2 5139 4799 0.0216043 0.0172613 -0.0261499 1 0 1 1 0 0 +EDGE2 5139 4798 -0.982894 -0.046582 0.0297174 1 0 1 1 0 0 +EDGE2 5139 5098 -1.00816 0.0332462 -0.0139441 1 0 1 1 0 0 +EDGE2 5139 5138 -1.00195 -0.0174371 -0.0119301 1 0 1 1 0 0 +EDGE2 5139 4858 -0.964072 0.0276249 0.0109841 1 0 1 1 0 0 +EDGE2 5140 4779 1.02246 -0.0818469 -3.10547 1 0 1 1 0 0 +EDGE2 5140 5101 0.0194153 1.03294 1.56763 1 0 1 1 0 0 +EDGE2 5140 5100 0.0158694 0.116587 0.0134789 1 0 1 1 0 0 +EDGE2 5140 4780 0.0418803 0.0510185 -3.13709 1 0 1 1 0 0 +EDGE2 5140 4800 -0.0116178 0.046674 0.0224471 1 0 1 1 0 0 +EDGE2 5140 4860 0.07221 -0.00734657 0.0171234 1 0 1 1 0 0 +EDGE2 5140 4859 -1.0011 0.0250026 0.0141511 1 0 1 1 0 0 +EDGE2 5140 5139 -1.04771 0.0859986 -0.0117675 1 0 1 1 0 0 +EDGE2 5140 5099 -1.00881 -0.0164571 -0.0181546 1 0 1 1 0 0 +EDGE2 5140 4781 0.11791 0.92886 1.56697 1 0 1 1 0 0 +EDGE2 5140 4801 0.0615735 1.02597 1.56496 1 0 1 1 0 0 +EDGE2 5140 4861 0.0823823 1.01363 1.53181 1 0 1 1 0 0 +EDGE2 5140 4799 -1.05948 0.0847802 0.00407866 1 0 1 1 0 0 +EDGE2 5141 4782 1.01602 0.0226507 -0.0420393 1 0 1 1 0 0 +EDGE2 5141 5101 0.0907465 0.0647979 -0.024318 1 0 1 1 0 0 +EDGE2 5141 5100 -0.995665 0.0661923 -1.55051 1 0 1 1 0 0 +EDGE2 5141 5140 -1.02578 -0.00929197 -1.61349 1 0 1 1 0 0 +EDGE2 5141 4780 -1.11379 -0.054185 1.58129 1 0 1 1 0 0 +EDGE2 5141 4800 -1.10902 -0.0547707 -1.51951 1 0 1 1 0 0 +EDGE2 5141 4860 -0.999982 -0.150632 -1.56275 1 0 1 1 0 0 +EDGE2 5141 5102 1.01775 0.0538776 -0.0366529 1 0 1 1 0 0 +EDGE2 5141 4781 -0.0123279 -0.0140232 -0.00783448 1 0 1 1 0 0 +EDGE2 5141 4801 0.00444096 0.0135861 -0.010732 1 0 1 1 0 0 +EDGE2 5141 4861 0.0525323 -0.00236417 0.011982 1 0 1 1 0 0 +EDGE2 5141 4802 0.910469 -0.00371437 0.00359356 1 0 1 1 0 0 +EDGE2 5141 4862 1.06337 0.0178287 -0.0384222 1 0 1 1 0 0 +EDGE2 5142 4782 -0.0171321 0.0357513 0.0219037 1 0 1 1 0 0 +EDGE2 5142 5101 -1.02753 -0.125992 0.0109138 1 0 1 1 0 0 +EDGE2 5142 5141 -0.923144 -0.0603785 0.0150106 1 0 1 1 0 0 +EDGE2 5142 5102 -0.0176655 -0.0776017 0.0139473 1 0 1 1 0 0 +EDGE2 5142 4781 -0.97716 0.026569 0.0304203 1 0 1 1 0 0 +EDGE2 5142 4801 -1.04356 -0.0134228 -0.0155787 1 0 1 1 0 0 +EDGE2 5142 4861 -0.89661 0.0488107 -0.00550484 1 0 1 1 0 0 +EDGE2 5142 4802 -0.0163127 0.0594078 -0.0405765 1 0 1 1 0 0 +EDGE2 5142 4862 -0.0643193 0.011006 0.0132029 1 0 1 1 0 0 +EDGE2 5142 4783 1.07949 0.0552693 -0.0110014 1 0 1 1 0 0 +EDGE2 5142 4863 0.985777 0.0186539 0.000696294 1 0 1 1 0 0 +EDGE2 5142 5103 0.956325 -0.0658452 0.0139303 1 0 1 1 0 0 +EDGE2 5142 4803 1.06823 -0.0108851 0.0101468 1 0 1 1 0 0 +EDGE2 5143 4782 -0.977753 -0.044975 -0.0131826 1 0 1 1 0 0 +EDGE2 5143 5102 -0.925196 -0.0482695 -0.016096 1 0 1 1 0 0 +EDGE2 5143 5142 -1.02296 -0.0313425 -0.0426936 1 0 1 1 0 0 +EDGE2 5143 4802 -0.979489 0.0247971 0.0199354 1 0 1 1 0 0 +EDGE2 5143 4862 -0.966806 -0.0359432 -0.00323509 1 0 1 1 0 0 +EDGE2 5143 4784 1.1095 -0.0154861 -0.000240414 1 0 1 1 0 0 +EDGE2 5143 4783 0.0203303 0.0400659 -0.0287377 1 0 1 1 0 0 +EDGE2 5143 4863 0.0591092 -0.0103552 0.00982705 1 0 1 1 0 0 +EDGE2 5143 5103 0.0319992 0.0226315 -0.0100855 1 0 1 1 0 0 +EDGE2 5143 4803 -0.124534 0.0334427 -0.0132048 1 0 1 1 0 0 +EDGE2 5143 4864 0.995637 -0.00613659 0.039864 1 0 1 1 0 0 +EDGE2 5143 5104 1.05508 -0.00968773 0.000724872 1 0 1 1 0 0 +EDGE2 5143 4804 1.03049 -0.0213311 0.00780787 1 0 1 1 0 0 +EDGE2 5144 4784 -0.0297458 -0.0201654 0.0201819 1 0 1 1 0 0 +EDGE2 5144 4783 -0.993859 -0.0318803 -0.0210187 1 0 1 1 0 0 +EDGE2 5144 4863 -1.01178 -0.0927893 0.00227251 1 0 1 1 0 0 +EDGE2 5144 5103 -1.04072 0.0362469 -0.00250167 1 0 1 1 0 0 +EDGE2 5144 5143 -0.937491 0.00207912 -0.00915364 1 0 1 1 0 0 +EDGE2 5144 4803 -0.925908 0.00666821 -0.00918661 1 0 1 1 0 0 +EDGE2 5144 4864 -0.034738 -0.0307079 0.00163503 1 0 1 1 0 0 +EDGE2 5144 5104 -0.0250094 -0.0376485 0.00308804 1 0 1 1 0 0 +EDGE2 5144 4804 0.0519571 -0.0585728 -0.0156177 1 0 1 1 0 0 +EDGE2 5144 4825 1.02291 0.062989 -3.13253 1 0 1 1 0 0 +EDGE2 5144 4865 1.05788 -0.0653461 -0.00431246 1 0 1 1 0 0 +EDGE2 5144 5105 0.995218 0.0832468 -0.0140234 1 0 1 1 0 0 +EDGE2 5144 4845 0.993592 0.00307413 -3.14986 1 0 1 1 0 0 +EDGE2 5144 4785 1.01695 -0.0633965 -0.0128789 1 0 1 1 0 0 +EDGE2 5144 4805 0.993687 -0.0804067 0.0262792 1 0 1 1 0 0 +EDGE2 5145 4826 0.0465105 -1.01779 -1.53603 1 0 1 1 0 0 +EDGE2 5145 4806 0.0812792 -1.04387 -1.56716 1 0 1 1 0 0 +EDGE2 5145 5106 0.0129097 0.934418 1.55698 1 0 1 1 0 0 +EDGE2 5145 4784 -1.10457 0.134178 0.0181114 1 0 1 1 0 0 +EDGE2 5145 4864 -1.12765 -0.00508602 0.026728 1 0 1 1 0 0 +EDGE2 5145 5104 -1.07074 0.0745963 -0.0234326 1 0 1 1 0 0 +EDGE2 5145 5144 -0.974862 0.0418517 -0.0324512 1 0 1 1 0 0 +EDGE2 5145 4804 -1.02992 0.0412489 -0.00725033 1 0 1 1 0 0 +EDGE2 5145 4825 0.0147158 -0.00027726 -3.1668 1 0 1 1 0 0 +EDGE2 5145 4865 -0.0397493 0.0316797 0.00399134 1 0 1 1 0 0 +EDGE2 5145 5105 -0.0502988 -0.0318523 0.0312029 1 0 1 1 0 0 +EDGE2 5145 4845 -0.0159568 -0.000898036 -3.16558 1 0 1 1 0 0 +EDGE2 5145 4844 0.916483 0.000653906 -3.14727 1 0 1 1 0 0 +EDGE2 5145 4785 0.0516487 0.0544455 -0.0092108 1 0 1 1 0 0 +EDGE2 5145 4805 -0.0439807 0.0377423 0.0181571 1 0 1 1 0 0 +EDGE2 5145 4824 1.01034 0.0840437 -3.13316 1 0 1 1 0 0 +EDGE2 5145 4786 0.0363262 0.996228 1.56366 1 0 1 1 0 0 +EDGE2 5145 4846 -0.103202 0.97399 1.56393 1 0 1 1 0 0 +EDGE2 5145 4866 -0.00306438 1.02902 1.55695 1 0 1 1 0 0 +EDGE2 5146 5106 -0.056674 -0.0374473 -0.0247983 1 0 1 1 0 0 +EDGE2 5146 4825 -0.987722 0.0254433 1.56766 1 0 1 1 0 0 +EDGE2 5146 4865 -0.968373 -0.0463154 -1.58418 1 0 1 1 0 0 +EDGE2 5146 5105 -1.00191 -0.00362265 -1.56804 1 0 1 1 0 0 +EDGE2 5146 5145 -1.02599 0.0132353 -1.61178 1 0 1 1 0 0 +EDGE2 5146 4845 -1.03408 -0.125183 1.61277 1 0 1 1 0 0 +EDGE2 5146 4785 -0.928892 -0.00606083 -1.56153 1 0 1 1 0 0 +EDGE2 5146 4805 -0.974365 0.0717912 -1.61339 1 0 1 1 0 0 +EDGE2 5146 5107 0.957153 -0.0577707 -0.0267645 1 0 1 1 0 0 +EDGE2 5146 4786 0.0529561 -0.101534 -0.00329726 1 0 1 1 0 0 +EDGE2 5146 4846 0.0893396 0.13014 -0.0259828 1 0 1 1 0 0 +EDGE2 5146 4866 -0.0876506 -0.0380026 0.0163595 1 0 1 1 0 0 +EDGE2 5146 4787 1.10219 0.0454458 0.0130899 1 0 1 1 0 0 +EDGE2 5146 4847 0.94252 -0.0428923 -0.00138003 1 0 1 1 0 0 +EDGE2 5146 4867 1.03085 -0.0575595 0.0253796 1 0 1 1 0 0 +EDGE2 5147 5106 -0.947314 0.0340899 0.00894692 1 0 1 1 0 0 +EDGE2 5147 5146 -1.00373 -0.0687107 -0.00370562 1 0 1 1 0 0 +EDGE2 5147 5108 1.00983 0.0165129 0.00230819 1 0 1 1 0 0 +EDGE2 5147 5107 -0.112989 0.126848 0.00270087 1 0 1 1 0 0 +EDGE2 5147 4786 -0.99011 -0.0311101 0.00958907 1 0 1 1 0 0 +EDGE2 5147 4846 -1.03834 -0.0454333 -0.0420249 1 0 1 1 0 0 +EDGE2 5147 4866 -1.03156 0.0360431 -0.0295663 1 0 1 1 0 0 +EDGE2 5147 4787 -0.00856217 -0.0684105 0.0259896 1 0 1 1 0 0 +EDGE2 5147 4847 -0.0514079 0.0138309 0.0143855 1 0 1 1 0 0 +EDGE2 5147 4867 0.107347 -0.0280844 0.00491188 1 0 1 1 0 0 +EDGE2 5147 4788 0.953044 -0.00862421 0.0158056 1 0 1 1 0 0 +EDGE2 5147 4848 0.891456 -0.0225067 -0.00332287 1 0 1 1 0 0 +EDGE2 5147 4868 1.03289 0.0578653 0.0326794 1 0 1 1 0 0 +EDGE2 5148 5108 0.0685157 0.00450094 0.00239668 1 0 1 1 0 0 +EDGE2 5148 5107 -1.07902 0.0180077 -0.028825 1 0 1 1 0 0 +EDGE2 5148 5147 -0.970525 -0.0543466 -0.014134 1 0 1 1 0 0 +EDGE2 5148 4787 -1.07543 0.0140607 -0.00726481 1 0 1 1 0 0 +EDGE2 5148 4847 -0.934161 0.0571064 0.00811515 1 0 1 1 0 0 +EDGE2 5148 4867 -1.05888 -0.024367 -0.0329698 1 0 1 1 0 0 +EDGE2 5148 4788 0.00547813 -0.0581314 -0.010236 1 0 1 1 0 0 +EDGE2 5148 4848 -0.0270095 -0.0109086 0.00399842 1 0 1 1 0 0 +EDGE2 5148 4868 -0.0321202 0.00628644 -0.0143647 1 0 1 1 0 0 +EDGE2 5148 4849 1.09393 0.0358967 -0.0254888 1 0 1 1 0 0 +EDGE2 5148 4869 1.02679 -0.0728393 0.00581471 1 0 1 1 0 0 +EDGE2 5148 5109 0.986784 -0.0327906 0.000126889 1 0 1 1 0 0 +EDGE2 5148 4789 0.944681 0.124013 0.013868 1 0 1 1 0 0 +EDGE2 5149 5108 -0.956413 0.00585674 0.00735886 1 0 1 1 0 0 +EDGE2 5149 5148 -1.01209 0.000637731 0.00842725 1 0 1 1 0 0 +EDGE2 5149 4788 -1.02656 -0.0249744 0.00809639 1 0 1 1 0 0 +EDGE2 5149 4848 -0.923122 -0.0639967 0.000142625 1 0 1 1 0 0 +EDGE2 5149 4868 -0.982107 0.0493912 0.0176263 1 0 1 1 0 0 +EDGE2 5149 4849 0.0164382 0.0643566 0.00760911 1 0 1 1 0 0 +EDGE2 5149 4869 -0.0131518 -0.135746 0.00214348 1 0 1 1 0 0 +EDGE2 5149 5109 -0.0116901 0.104107 0.0212496 1 0 1 1 0 0 +EDGE2 5149 4789 -0.0190221 -0.0127596 0.0208864 1 0 1 1 0 0 +EDGE2 5149 5110 0.930302 -0.0439594 -0.00785589 1 0 1 1 0 0 +EDGE2 5149 4850 1.0037 0.0383216 0.00259897 1 0 1 1 0 0 +EDGE2 5149 4870 1.00995 -0.0428098 0.0217752 1 0 1 1 0 0 +EDGE2 5149 5090 0.974797 -0.0384483 -3.16137 1 0 1 1 0 0 +EDGE2 5149 4790 1.01954 -0.0227178 -0.0376444 1 0 1 1 0 0 +EDGE2 5150 5149 -0.982921 -0.0528356 0.0389166 1 0 1 1 0 0 +EDGE2 5150 4849 -0.985906 0.0371191 -0.000909633 1 0 1 1 0 0 +EDGE2 5150 4869 -0.984895 0.0395322 0.018321 1 0 1 1 0 0 +EDGE2 5150 5109 -0.913909 -0.0458769 0.0164613 1 0 1 1 0 0 +EDGE2 5150 4789 -1.00809 0.0395314 -0.0191427 1 0 1 1 0 0 +EDGE2 5150 5110 -0.00788935 0.0737357 -0.00874108 1 0 1 1 0 0 +EDGE2 5150 5111 -0.0380214 1.07835 1.55332 1 0 1 1 0 0 +EDGE2 5150 4791 0.0744185 1.01759 1.59187 1 0 1 1 0 0 +EDGE2 5150 4851 0.0297287 0.967108 1.54812 1 0 1 1 0 0 +EDGE2 5150 5091 -0.069976 0.959626 1.59277 1 0 1 1 0 0 +EDGE2 5150 4871 0.0230581 -1.00288 -1.5759 1 0 1 1 0 0 +EDGE2 5150 4850 -0.0137274 0.0780896 0.00413888 1 0 1 1 0 0 +EDGE2 5150 4870 0.0368642 0.00997131 0.0155288 1 0 1 1 0 0 +EDGE2 5150 5090 0.0589911 0.0717896 -3.13052 1 0 1 1 0 0 +EDGE2 5150 4790 0.00599647 0.0145482 0.0344822 1 0 1 1 0 0 +EDGE2 5150 5089 1.02091 0.00517219 -3.12393 1 0 1 1 0 0 +EDGE2 5151 5110 -0.998954 0.00919641 -1.57806 1 0 1 1 0 0 +EDGE2 5151 5112 1.04016 -0.0901972 -0.0313998 1 0 1 1 0 0 +EDGE2 5151 5111 0.0424825 0.0137095 0.0113288 1 0 1 1 0 0 +EDGE2 5151 4792 0.966792 0.0518223 -0.0177522 1 0 1 1 0 0 +EDGE2 5151 4852 0.958533 0.0897199 0.016221 1 0 1 1 0 0 +EDGE2 5151 5092 1.08176 -0.0353292 0.000346366 1 0 1 1 0 0 +EDGE2 5151 4791 -0.00997359 -0.0124627 0.0557281 1 0 1 1 0 0 +EDGE2 5151 4851 0.00373871 0.0410769 0.0190441 1 0 1 1 0 0 +EDGE2 5151 5091 0.0361605 0.0144952 -0.00499842 1 0 1 1 0 0 +EDGE2 5151 5150 -0.944018 0.0450118 -1.57718 1 0 1 1 0 0 +EDGE2 5151 4850 -1.00269 -0.025111 -1.58082 1 0 1 1 0 0 +EDGE2 5151 4870 -0.891717 -0.00984827 -1.58258 1 0 1 1 0 0 +EDGE2 5151 5090 -0.949784 -0.0296436 1.53925 1 0 1 1 0 0 +EDGE2 5151 4790 -0.974317 -0.0412577 -1.54716 1 0 1 1 0 0 +EDGE2 5152 5112 0.0632264 0.0215064 0.00386534 1 0 1 1 0 0 +EDGE2 5152 5113 1.04648 -0.0237654 0.0132896 1 0 1 1 0 0 +EDGE2 5152 4793 0.956831 0.00215833 -0.00805869 1 0 1 1 0 0 +EDGE2 5152 4853 0.993049 0.0279007 -0.00528204 1 0 1 1 0 0 +EDGE2 5152 5093 0.976421 0.0649727 -0.0477514 1 0 1 1 0 0 +EDGE2 5152 5111 -0.960565 0.0238041 -0.0149352 1 0 1 1 0 0 +EDGE2 5152 4792 -0.0516401 -0.00211849 0.0326103 1 0 1 1 0 0 +EDGE2 5152 4852 -0.0180832 0.0130309 -0.0161604 1 0 1 1 0 0 +EDGE2 5152 5092 -0.0230995 -0.0481537 0.020885 1 0 1 1 0 0 +EDGE2 5152 5151 -0.982018 -0.0489039 -0.00913317 1 0 1 1 0 0 +EDGE2 5152 4791 -0.980009 0.00877736 -0.00436764 1 0 1 1 0 0 +EDGE2 5152 4851 -0.984122 0.0426081 -0.0372575 1 0 1 1 0 0 +EDGE2 5152 5091 -1.06443 -0.0107037 0.0146195 1 0 1 1 0 0 +EDGE2 5153 5114 1.05869 0.0338434 0.010324 1 0 1 1 0 0 +EDGE2 5153 5112 -1.07448 -0.0440584 -0.0137871 1 0 1 1 0 0 +EDGE2 5153 5113 0.0140927 -0.0270486 -0.0115857 1 0 1 1 0 0 +EDGE2 5153 4794 0.958316 -0.00505013 0.0302329 1 0 1 1 0 0 +EDGE2 5153 4854 1.04813 -0.037633 -0.0419667 1 0 1 1 0 0 +EDGE2 5153 5094 1.01966 0.0447574 -0.0260098 1 0 1 1 0 0 +EDGE2 5153 4793 -0.0333295 0.0109627 -0.018181 1 0 1 1 0 0 +EDGE2 5153 4853 -0.0195425 -0.0346261 -0.0061582 1 0 1 1 0 0 +EDGE2 5153 5093 -0.0210634 0.00056569 -0.00710566 1 0 1 1 0 0 +EDGE2 5153 5152 -1.08752 0.000183968 -0.00981601 1 0 1 1 0 0 +EDGE2 5153 4792 -0.968397 -0.101303 0.0222741 1 0 1 1 0 0 +EDGE2 5153 4852 -0.951763 0.0517174 -0.010048 1 0 1 1 0 0 +EDGE2 5153 5092 -1.05842 0.00616308 -0.0116984 1 0 1 1 0 0 +EDGE2 5154 5114 -0.0341401 0.0521068 -0.00822376 1 0 1 1 0 0 +EDGE2 5154 5095 1.10395 -0.0239288 -0.0277329 1 0 1 1 0 0 +EDGE2 5154 5135 1.03645 -0.00867161 -3.13583 1 0 1 1 0 0 +EDGE2 5154 5115 1.0474 -0.00105215 -0.0196883 1 0 1 1 0 0 +EDGE2 5154 4795 0.940975 0.0147392 0.0269488 1 0 1 1 0 0 +EDGE2 5154 4855 1.0537 -0.0176392 0.00302876 1 0 1 1 0 0 +EDGE2 5154 5113 -0.968802 -0.00173617 0.00185768 1 0 1 1 0 0 +EDGE2 5154 4794 -0.0500493 -0.0361588 -0.0452675 1 0 1 1 0 0 +EDGE2 5154 4854 0.0722265 -0.116035 0.016427 1 0 1 1 0 0 +EDGE2 5154 5094 -0.00359139 0.0553391 0.0259682 1 0 1 1 0 0 +EDGE2 5154 5153 -0.939095 -0.0361003 -6.6895e-05 1 0 1 1 0 0 +EDGE2 5154 4793 -0.942734 -0.053032 -0.00178111 1 0 1 1 0 0 +EDGE2 5154 4853 -0.986719 0.0438188 0.0127895 1 0 1 1 0 0 +EDGE2 5154 5093 -1.02384 -0.0938845 0.0179857 1 0 1 1 0 0 +EDGE2 5155 5136 -0.0238031 1.00623 1.57188 1 0 1 1 0 0 +EDGE2 5155 4856 -0.00966262 1.03692 1.57486 1 0 1 1 0 0 +EDGE2 5155 5096 0.0339045 1.07558 1.60115 1 0 1 1 0 0 +EDGE2 5155 4796 0.0834677 0.952215 1.5577 1 0 1 1 0 0 +EDGE2 5155 5114 -1.01811 0.0775553 -0.043845 1 0 1 1 0 0 +EDGE2 5155 5095 -0.03115 0.0970877 0.0209923 1 0 1 1 0 0 +EDGE2 5155 5135 0.0282368 -0.0700353 -3.14207 1 0 1 1 0 0 +EDGE2 5155 5134 0.927697 -0.00322797 -3.1774 1 0 1 1 0 0 +EDGE2 5155 5115 0.0114517 -0.0500251 -0.015961 1 0 1 1 0 0 +EDGE2 5155 4795 -0.0611743 -0.00507096 0.0214028 1 0 1 1 0 0 +EDGE2 5155 4855 -0.0169225 0.0619003 0.00274308 1 0 1 1 0 0 +EDGE2 5155 5154 -1.07105 0.0738518 -0.0064793 1 0 1 1 0 0 +EDGE2 5155 5116 -0.0048789 -1.11243 -1.57036 1 0 1 1 0 0 +EDGE2 5155 4794 -0.951856 0.0393576 -0.0316529 1 0 1 1 0 0 +EDGE2 5155 4854 -0.989987 0.0348104 -0.0110429 1 0 1 1 0 0 +EDGE2 5155 5094 -1.03716 -0.00909011 0.0072276 1 0 1 1 0 0 +EDGE2 5156 4857 1.0268 -0.0252909 -0.00758362 1 0 1 1 0 0 +EDGE2 5156 5137 0.987804 -0.0065555 0.0256999 1 0 1 1 0 0 +EDGE2 5156 5097 0.94413 -0.0426508 0.0152464 1 0 1 1 0 0 +EDGE2 5156 5136 -0.0455088 0.0557167 -0.0122417 1 0 1 1 0 0 +EDGE2 5156 4797 0.98569 -0.0597774 0.00185144 1 0 1 1 0 0 +EDGE2 5156 4856 -0.0574224 -0.0418785 0.00223782 1 0 1 1 0 0 +EDGE2 5156 5096 0.0387702 0.00898392 0.00657743 1 0 1 1 0 0 +EDGE2 5156 4796 -0.0493461 0.0257322 0.0150889 1 0 1 1 0 0 +EDGE2 5156 5095 -0.956793 0.0797623 -1.56976 1 0 1 1 0 0 +EDGE2 5156 5135 -1.0793 0.0101222 1.56001 1 0 1 1 0 0 +EDGE2 5156 5155 -1.1128 -0.0380205 -1.57099 1 0 1 1 0 0 +EDGE2 5156 5115 -0.991304 0.0486105 -1.56532 1 0 1 1 0 0 +EDGE2 5156 4795 -1.03733 0.052999 -1.53869 1 0 1 1 0 0 +EDGE2 5156 4855 -1.06717 0.0141695 -1.56973 1 0 1 1 0 0 +EDGE2 5157 4857 -0.117212 -0.063067 0.00217624 1 0 1 1 0 0 +EDGE2 5157 4798 1.03458 -0.0163631 -0.00758214 1 0 1 1 0 0 +EDGE2 5157 5098 1.0132 -0.0954679 0.0190316 1 0 1 1 0 0 +EDGE2 5157 5138 1.01678 0.0561272 0.0310775 1 0 1 1 0 0 +EDGE2 5157 4858 1.01353 0.092895 -0.00655051 1 0 1 1 0 0 +EDGE2 5157 5137 -0.0376417 0.0215507 0.0102109 1 0 1 1 0 0 +EDGE2 5157 5097 0.0103021 0.0459837 0.0506028 1 0 1 1 0 0 +EDGE2 5157 5136 -0.983279 -0.0103345 0.0185926 1 0 1 1 0 0 +EDGE2 5157 4797 -0.0186858 -0.0614858 0.00629242 1 0 1 1 0 0 +EDGE2 5157 5156 -0.965557 0.0707569 -0.0289356 1 0 1 1 0 0 +EDGE2 5157 4856 -1.04265 -0.0128876 -0.0112608 1 0 1 1 0 0 +EDGE2 5157 5096 -1.00318 -0.0341354 0.0326153 1 0 1 1 0 0 +EDGE2 5157 4796 -0.951424 0.127957 0.0342717 1 0 1 1 0 0 +EDGE2 5158 4859 0.987186 -0.00355664 0.00404445 1 0 1 1 0 0 +EDGE2 5158 5139 1.02677 -0.0147776 0.00233037 1 0 1 1 0 0 +EDGE2 5158 5099 1.04182 0.0422344 -0.0381996 1 0 1 1 0 0 +EDGE2 5158 4799 1.06664 0.0105501 0.0144236 1 0 1 1 0 0 +EDGE2 5158 4857 -0.973867 -0.0153074 0.0176855 1 0 1 1 0 0 +EDGE2 5158 4798 0.0498597 -0.00124147 -0.0483504 1 0 1 1 0 0 +EDGE2 5158 5098 -0.036955 -0.0998173 -0.000862014 1 0 1 1 0 0 +EDGE2 5158 5138 0.0867563 -0.0924645 0.00585881 1 0 1 1 0 0 +EDGE2 5158 4858 -0.0359866 -0.032261 0.00603656 1 0 1 1 0 0 +EDGE2 5158 5137 -0.975687 -0.0783278 -0.0123075 1 0 1 1 0 0 +EDGE2 5158 5157 -1.00198 0.0434876 -0.0060216 1 0 1 1 0 0 +EDGE2 5158 5097 -0.941783 -0.000746886 -0.0111379 1 0 1 1 0 0 +EDGE2 5158 4797 -0.996101 -0.044463 -0.000997747 1 0 1 1 0 0 +EDGE2 5159 5100 0.976448 -0.0476362 -0.019171 1 0 1 1 0 0 +EDGE2 5159 5140 0.941973 0.0460953 0.00109545 1 0 1 1 0 0 +EDGE2 5159 4780 0.898581 -0.0327983 -3.07378 1 0 1 1 0 0 +EDGE2 5159 4800 0.974154 0.0422845 0.0334321 1 0 1 1 0 0 +EDGE2 5159 4860 1.03995 -0.128516 0.0088966 1 0 1 1 0 0 +EDGE2 5159 4859 -0.0614894 0.0192761 0.00618234 1 0 1 1 0 0 +EDGE2 5159 5139 -0.0217313 -0.0211774 -0.0172372 1 0 1 1 0 0 +EDGE2 5159 5099 0.0544038 0.0307158 0.00617455 1 0 1 1 0 0 +EDGE2 5159 4799 0.00155592 0.0457973 0.0173195 1 0 1 1 0 0 +EDGE2 5159 4798 -0.8776 -0.025198 0.0106483 1 0 1 1 0 0 +EDGE2 5159 5098 -0.949573 0.0700438 0.0332312 1 0 1 1 0 0 +EDGE2 5159 5138 -1.02231 -0.0504274 -0.0189984 1 0 1 1 0 0 +EDGE2 5159 5158 -1.02794 -0.0210393 -0.0245214 1 0 1 1 0 0 +EDGE2 5159 4858 -0.993647 0.0275884 -0.0391455 1 0 1 1 0 0 +EDGE2 5160 4779 1.1315 0.0146525 -3.13456 1 0 1 1 0 0 +EDGE2 5160 5101 0.00447284 0.991395 1.58806 1 0 1 1 0 0 +EDGE2 5160 5100 0.154637 -0.0856909 -0.0396199 1 0 1 1 0 0 +EDGE2 5160 5140 0.047372 -0.079135 -0.0200684 1 0 1 1 0 0 +EDGE2 5160 4780 0.0500467 0.0220249 -3.11343 1 0 1 1 0 0 +EDGE2 5160 4800 7.74459e-05 -0.0265373 0.0202768 1 0 1 1 0 0 +EDGE2 5160 4860 -0.00196744 0.0917498 0.0315821 1 0 1 1 0 0 +EDGE2 5160 5141 0.00579528 0.94811 1.61854 1 0 1 1 0 0 +EDGE2 5160 4859 -1.0338 -0.0742542 -0.00343552 1 0 1 1 0 0 +EDGE2 5160 5139 -1.0566 -0.0453592 0.00277394 1 0 1 1 0 0 +EDGE2 5160 5159 -0.921431 -0.0478433 0.00659998 1 0 1 1 0 0 +EDGE2 5160 5099 -1.03913 0.0283118 0.000886137 1 0 1 1 0 0 +EDGE2 5160 4781 -0.118043 0.949672 1.59141 1 0 1 1 0 0 +EDGE2 5160 4801 -0.0536561 1.01301 1.53968 1 0 1 1 0 0 +EDGE2 5160 4861 0.00703187 1.06771 1.56515 1 0 1 1 0 0 +EDGE2 5160 4799 -1.00054 0.00612884 -0.0495224 1 0 1 1 0 0 +EDGE2 5161 5100 -1.00884 -0.131098 1.57541 1 0 1 1 0 0 +EDGE2 5161 5160 -1.00778 -0.0227267 1.54411 1 0 1 1 0 0 +EDGE2 5161 5140 -0.965288 -0.00970978 1.56661 1 0 1 1 0 0 +EDGE2 5161 4780 -0.875877 -0.0443896 -1.60096 1 0 1 1 0 0 +EDGE2 5161 4800 -0.958366 -0.017483 1.53152 1 0 1 1 0 0 +EDGE2 5161 4860 -0.96983 0.0508969 1.57813 1 0 1 1 0 0 +EDGE2 5162 5161 -1.04215 -0.0480071 -0.000129416 1 0 1 1 0 0 +EDGE2 5163 5162 -1.07407 0.0242422 -0.0146226 1 0 1 1 0 0 +EDGE2 5164 5163 -0.928426 0.0386234 -9.72824e-05 1 0 1 1 0 0 +EDGE2 5165 5164 -1.02683 0.0110506 0.0282599 1 0 1 1 0 0 +EDGE2 5166 5165 -1.00518 -0.0517767 1.56864 1 0 1 1 0 0 +EDGE2 5167 5166 -0.974583 -0.0172774 0.00157344 1 0 1 1 0 0 +EDGE2 5168 5167 -0.916429 0.079277 0.0171981 1 0 1 1 0 0 +EDGE2 5169 5168 -1.03737 -0.134899 -0.00607159 1 0 1 1 0 0 +EDGE2 5169 5130 0.961145 -0.00275312 -3.15074 1 0 1 1 0 0 +EDGE2 5170 5169 -0.975366 0.0919874 -0.0212499 1 0 1 1 0 0 +EDGE2 5170 5131 0.0606166 -0.952008 -1.57224 1 0 1 1 0 0 +EDGE2 5170 5130 0.0153932 -0.0428595 -3.16298 1 0 1 1 0 0 +EDGE2 5170 5129 1.07412 -0.046988 -3.11844 1 0 1 1 0 0 +EDGE2 5171 5170 -1.03723 0.0189489 -1.57487 1 0 1 1 0 0 +EDGE2 5171 5130 -1.07524 0.0819259 1.54267 1 0 1 1 0 0 +EDGE2 5172 5171 -1.0244 0.0814761 -0.0142727 1 0 1 1 0 0 +EDGE2 5173 5172 -1.02223 -0.0937396 0.0202301 1 0 1 1 0 0 +EDGE2 5174 5173 -0.861735 0.0494403 0.0152819 1 0 1 1 0 0 +EDGE2 5175 5174 -1.02363 -0.0085307 -0.0336715 1 0 1 1 0 0 +EDGE2 5176 5175 -1.06407 -0.0398364 1.59019 1 0 1 1 0 0 +EDGE2 5177 5176 -1.0061 0.0169038 0.0228449 1 0 1 1 0 0 +EDGE2 5178 5177 -1.00417 0.0986417 -0.00413573 1 0 1 1 0 0 +EDGE2 5179 5178 -0.95293 0.0686691 -0.00848323 1 0 1 1 0 0 +EDGE2 5180 5179 -1.04147 -0.101672 -0.0287542 1 0 1 1 0 0 +EDGE2 5181 5180 -1.10188 -0.0212185 -1.53057 1 0 1 1 0 0 +EDGE2 5182 5181 -0.945918 -0.0416141 0.025342 1 0 1 1 0 0 +EDGE2 5183 5182 -0.967173 0.00389321 0.0174562 1 0 1 1 0 0 +EDGE2 5184 5183 -1.09026 0.0288715 -0.00271052 1 0 1 1 0 0 +EDGE2 5185 5184 -1.00452 -0.0298633 -0.00513144 1 0 1 1 0 0 +EDGE2 5186 5185 -0.911083 0.0510197 -1.55406 1 0 1 1 0 0 +EDGE2 5187 5186 -0.911645 0.0429263 0.0197593 1 0 1 1 0 0 +EDGE2 5188 5187 -1.0625 -0.0549862 0.0161829 1 0 1 1 0 0 +EDGE2 5189 5188 -1.04375 0.0228701 0.0204694 1 0 1 1 0 0 +EDGE2 5190 5189 -0.854254 -0.0539164 -0.0255377 1 0 1 1 0 0 +EDGE2 5191 5190 -1.02076 -0.00948899 -1.56718 1 0 1 1 0 0 +EDGE2 5192 5191 -1.00362 0.0248421 -0.00524435 1 0 1 1 0 0 +EDGE2 5193 5192 -1.02378 0.0570592 -0.0011759 1 0 1 1 0 0 +EDGE2 5194 5193 -0.946311 0.0508309 0.0308019 1 0 1 1 0 0 +EDGE2 5194 5175 1.03206 0.0538954 -3.16201 1 0 1 1 0 0 +EDGE2 5195 5176 -0.00662581 0.988001 1.5483 1 0 1 1 0 0 +EDGE2 5195 5194 -0.981223 0.037443 0.00491859 1 0 1 1 0 0 +EDGE2 5195 5175 0.0266691 -0.0257843 -3.17859 1 0 1 1 0 0 +EDGE2 5195 5174 0.96616 0.0502055 -3.12972 1 0 1 1 0 0 +EDGE2 5196 5176 0.0366671 -0.0372995 0.00393877 1 0 1 1 0 0 +EDGE2 5196 5175 -1.03522 0.00753056 1.56489 1 0 1 1 0 0 +EDGE2 5196 5195 -1.0914 0.043043 -1.56281 1 0 1 1 0 0 +EDGE2 5196 5177 0.971441 0.134174 -0.00457284 1 0 1 1 0 0 +EDGE2 5197 5176 -0.966286 -0.0524098 0.014562 1 0 1 1 0 0 +EDGE2 5197 5196 -1.01158 -0.0265456 -0.0180505 1 0 1 1 0 0 +EDGE2 5197 5178 1.06251 0.0423037 -0.00173158 1 0 1 1 0 0 +EDGE2 5197 5177 0.0131077 -0.0502417 -0.0174664 1 0 1 1 0 0 +EDGE2 5198 5178 -0.00292016 -0.0765866 -0.0398593 1 0 1 1 0 0 +EDGE2 5198 5197 -1.02111 0.0477337 0.0163785 1 0 1 1 0 0 +EDGE2 5198 5177 -1.08787 -0.000229515 0.00460695 1 0 1 1 0 0 +EDGE2 5198 5179 0.93633 0.0359893 0.0156631 1 0 1 1 0 0 +EDGE2 5199 5178 -1.06184 0.0147183 0.00594309 1 0 1 1 0 0 +EDGE2 5199 5198 -1.04022 -0.0716559 -0.00326138 1 0 1 1 0 0 +EDGE2 5199 5179 0.0669607 0.0723308 -0.0198309 1 0 1 1 0 0 +EDGE2 5199 5180 1.13004 -0.0575824 -0.00798029 1 0 1 1 0 0 +EDGE2 5200 5179 -1.02882 -0.0626379 -0.000808032 1 0 1 1 0 0 +EDGE2 5200 5199 -0.964004 -0.0204286 -0.0143679 1 0 1 1 0 0 +EDGE2 5200 5181 0.0192488 1.0569 1.56255 1 0 1 1 0 0 +EDGE2 5200 5180 0.0275052 -0.0950865 -0.0295569 1 0 1 1 0 0 +EDGE2 5201 5181 0.0542938 0.0543862 0.0238917 1 0 1 1 0 0 +EDGE2 5201 5182 1.03579 0.0966671 0.018992 1 0 1 1 0 0 +EDGE2 5201 5180 -1.02623 -0.0650128 -1.5602 1 0 1 1 0 0 +EDGE2 5201 5200 -0.971722 -0.0279358 -1.57865 1 0 1 1 0 0 +EDGE2 5202 5181 -0.97078 -0.00875243 0.0155076 1 0 1 1 0 0 +EDGE2 5202 5182 0.0614017 0.00684165 0.0232545 1 0 1 1 0 0 +EDGE2 5202 5183 1.04971 -0.048803 -0.000450596 1 0 1 1 0 0 +EDGE2 5202 5201 -0.966994 -0.0114732 -0.0079644 1 0 1 1 0 0 +EDGE2 5203 5184 0.94475 -0.00357253 0.020876 1 0 1 1 0 0 +EDGE2 5203 5182 -1.09019 -0.0330181 -0.0157916 1 0 1 1 0 0 +EDGE2 5203 5202 -1.02346 -0.0441566 0.00100821 1 0 1 1 0 0 +EDGE2 5203 5183 -0.0205423 0.147759 0.0111516 1 0 1 1 0 0 +EDGE2 5204 5203 -1.06797 -0.0173812 -0.025988 1 0 1 1 0 0 +EDGE2 5204 5185 1.02297 0.018154 0.00443968 1 0 1 1 0 0 +EDGE2 5204 5184 -0.0932533 0.0210788 0.0217514 1 0 1 1 0 0 +EDGE2 5204 5183 -1.01509 -0.018365 -0.0189706 1 0 1 1 0 0 +EDGE2 5205 5186 -0.0606331 1.00671 1.55706 1 0 1 1 0 0 +EDGE2 5205 5204 -0.985908 -0.0539917 -0.0117193 1 0 1 1 0 0 +EDGE2 5205 5185 0.00975375 -0.0394506 -0.0171568 1 0 1 1 0 0 +EDGE2 5205 5184 -1.13234 0.0147146 -0.00767392 1 0 1 1 0 0 +EDGE2 5206 5187 1.02153 0.0347331 -0.0238151 1 0 1 1 0 0 +EDGE2 5206 5186 0.0493015 0.0169097 0.00578141 1 0 1 1 0 0 +EDGE2 5206 5185 -1.01866 -0.011712 -1.57615 1 0 1 1 0 0 +EDGE2 5206 5205 -0.982737 -0.00709881 -1.58361 1 0 1 1 0 0 +EDGE2 5207 5188 0.948886 -0.0528504 -0.0103704 1 0 1 1 0 0 +EDGE2 5207 5206 -0.96335 0.0174428 -0.00989838 1 0 1 1 0 0 +EDGE2 5207 5187 0.0850454 -0.0213852 0.0136245 1 0 1 1 0 0 +EDGE2 5207 5186 -1.10689 -0.00980235 -0.00795848 1 0 1 1 0 0 +EDGE2 5208 5189 0.898559 0.0415744 0.0169884 1 0 1 1 0 0 +EDGE2 5208 5207 -0.96773 0.00882251 0.0190586 1 0 1 1 0 0 +EDGE2 5208 5188 -0.0643111 -0.118352 -0.00680511 1 0 1 1 0 0 +EDGE2 5208 5187 -0.955008 0.0251501 0.003069 1 0 1 1 0 0 +EDGE2 5209 5190 1.00333 0.0875946 -0.0110707 1 0 1 1 0 0 +EDGE2 5209 5189 0.0174851 -0.0520437 -0.0193361 1 0 1 1 0 0 +EDGE2 5209 5188 -1.01818 -0.0599184 0.0188875 1 0 1 1 0 0 +EDGE2 5209 5208 -0.927969 -0.0677239 -0.00981993 1 0 1 1 0 0 +EDGE2 5210 5190 -0.0235461 -0.0249156 0.00478828 1 0 1 1 0 0 +EDGE2 5210 5191 0.0284555 1.05158 1.57339 1 0 1 1 0 0 +EDGE2 5210 5189 -0.963174 -0.0311129 -0.0231805 1 0 1 1 0 0 +EDGE2 5210 5209 -1.01449 0.0991325 0.00867611 1 0 1 1 0 0 +EDGE2 5211 5190 -0.987139 -0.0156539 -1.5787 1 0 1 1 0 0 +EDGE2 5211 5210 -0.957038 -0.0591214 -1.58923 1 0 1 1 0 0 +EDGE2 5211 5191 0.0131381 0.05787 -0.0118572 1 0 1 1 0 0 +EDGE2 5211 5192 1.00525 0.0111879 0.00563854 1 0 1 1 0 0 +EDGE2 5212 5191 -1.07283 0.0160471 -0.00702741 1 0 1 1 0 0 +EDGE2 5212 5211 -1.00634 -0.0337876 0.00389108 1 0 1 1 0 0 +EDGE2 5212 5192 -0.0071507 -0.0559381 -0.000307697 1 0 1 1 0 0 +EDGE2 5212 5193 0.997195 -0.0268362 0.0524064 1 0 1 1 0 0 +EDGE2 5213 5212 -0.958821 -0.00395347 -0.00178355 1 0 1 1 0 0 +EDGE2 5213 5192 -0.938712 -0.00163511 -0.00671896 1 0 1 1 0 0 +EDGE2 5213 5194 0.927321 0.0441977 -0.0333898 1 0 1 1 0 0 +EDGE2 5213 5193 -0.00740432 -0.0938302 -0.0325346 1 0 1 1 0 0 +EDGE2 5214 5213 -1.0044 0.0815967 -0.0128382 1 0 1 1 0 0 +EDGE2 5214 5194 -0.0826063 0.0816467 0.0242701 1 0 1 1 0 0 +EDGE2 5214 5193 -0.949494 -0.0152967 -0.0272402 1 0 1 1 0 0 +EDGE2 5214 5175 1.01178 -0.00666231 -3.13291 1 0 1 1 0 0 +EDGE2 5214 5195 1.10678 -0.014781 -0.0141799 1 0 1 1 0 0 +EDGE2 5215 5176 0.0122359 0.97068 1.59249 1 0 1 1 0 0 +EDGE2 5215 5194 -0.977878 0.0583002 0.0252796 1 0 1 1 0 0 +EDGE2 5215 5214 -0.914882 -0.0728527 0.0201886 1 0 1 1 0 0 +EDGE2 5215 5175 -0.0067703 -3.90254e-05 -3.1614 1 0 1 1 0 0 +EDGE2 5215 5195 -0.0271788 -0.0516972 0.0106338 1 0 1 1 0 0 +EDGE2 5215 5174 0.953892 -0.038791 -3.15347 1 0 1 1 0 0 +EDGE2 5215 5196 -0.0863497 0.993538 1.59458 1 0 1 1 0 0 +EDGE2 5216 5175 -0.981079 0.0668892 -1.55722 1 0 1 1 0 0 +EDGE2 5216 5195 -0.906928 -0.0344114 1.51506 1 0 1 1 0 0 +EDGE2 5216 5215 -1.07356 -0.0912102 1.57067 1 0 1 1 0 0 +EDGE2 5217 5216 -0.98483 0.0302648 0.0247222 1 0 1 1 0 0 +EDGE2 5218 5217 -1.00747 0.0242603 0.00171085 1 0 1 1 0 0 +EDGE2 5219 5218 -1.0296 0.0595912 -0.0222985 1 0 1 1 0 0 +EDGE2 5220 5219 -1.10199 0.0172813 0.0225013 1 0 1 1 0 0 +EDGE2 5221 5220 -0.955384 -0.111965 -1.58277 1 0 1 1 0 0 +EDGE2 5222 5221 -0.935984 0.0619862 -0.00333844 1 0 1 1 0 0 +EDGE2 5223 5222 -0.944456 -0.058335 -0.0237955 1 0 1 1 0 0 +EDGE2 5224 5223 -0.960416 -0.0442617 -0.026446 1 0 1 1 0 0 +EDGE2 5224 5165 0.931391 -0.0291368 -3.11217 1 0 1 1 0 0 +EDGE2 5225 5224 -0.991433 0.00105435 0.0196626 1 0 1 1 0 0 +EDGE2 5225 5165 -0.0761482 0.0310403 -3.15613 1 0 1 1 0 0 +EDGE2 5225 5164 1.13126 -0.0375956 -3.12362 1 0 1 1 0 0 +EDGE2 5225 5166 0.0419758 0.909795 1.57547 1 0 1 1 0 0 +EDGE2 5226 5165 -0.93563 -0.0058674 -1.55403 1 0 1 1 0 0 +EDGE2 5226 5225 -1.10264 0.0470529 1.55844 1 0 1 1 0 0 +EDGE2 5227 5226 -1.0152 0.103698 -0.024142 1 0 1 1 0 0 +EDGE2 5228 5227 -1.02409 -0.0198583 -0.00191175 1 0 1 1 0 0 +EDGE2 5229 5228 -0.974655 -0.0205378 0.00530741 1 0 1 1 0 0 +EDGE2 5230 5229 -0.948951 0.0186542 0.00437797 1 0 1 1 0 0 +EDGE2 5231 5230 -0.932884 0.0180792 1.57195 1 0 1 1 0 0 +EDGE2 5232 5231 -1.03917 -0.0349972 0.0386043 1 0 1 1 0 0 +EDGE2 5233 5232 -0.990357 0.108004 0.0165197 1 0 1 1 0 0 +EDGE2 5234 5233 -0.966326 0.0186996 -0.0196059 1 0 1 1 0 0 +EDGE2 5235 5234 -1.01935 -0.0150866 -0.020038 1 0 1 1 0 0 +EDGE2 5236 5235 -1.00019 -0.00253026 -1.57617 1 0 1 1 0 0 +EDGE2 5237 5236 -0.994849 -0.00720543 -0.0102224 1 0 1 1 0 0 +EDGE2 5238 5237 -0.914445 0.0271757 0.0174408 1 0 1 1 0 0 +EDGE2 5239 5238 -1.03674 -0.0108946 0.0291422 1 0 1 1 0 0 +EDGE2 5240 5239 -0.921666 -0.03391 -0.0233741 1 0 1 1 0 0 +EDGE2 5241 5240 -1.0963 -0.101712 -1.58152 1 0 1 1 0 0 +EDGE2 5242 5241 -0.996901 -0.073956 0.00972675 1 0 1 1 0 0 +EDGE2 5243 5242 -0.944476 0.00289278 0.027347 1 0 1 1 0 0 +EDGE2 5244 5243 -1.11712 0.0386012 0.00154242 1 0 1 1 0 0 +EDGE2 5245 5244 -0.937568 0.0302108 -0.00388681 1 0 1 1 0 0 +EDGE2 5246 5245 -0.999885 -0.0143379 -1.57737 1 0 1 1 0 0 +EDGE2 5247 5246 -0.967797 -0.0985091 0.00895939 1 0 1 1 0 0 +EDGE2 5248 5247 -1.05457 -0.0154038 0.0329648 1 0 1 1 0 0 +EDGE2 5249 5248 -1.06804 0.0305139 0.000514745 1 0 1 1 0 0 +EDGE2 5249 5230 1.0095 -0.0128368 -3.16548 1 0 1 1 0 0 +EDGE2 5250 5249 -0.978756 -0.0601845 0.00355165 1 0 1 1 0 0 +EDGE2 5250 5229 1.00319 0.0202074 -3.14726 1 0 1 1 0 0 +EDGE2 5250 5230 0.0192818 -0.0423735 -3.1614 1 0 1 1 0 0 +EDGE2 5250 5231 -0.0778879 1.06823 1.5796 1 0 1 1 0 0 +EDGE2 5251 5232 0.977934 0.0869688 0.0338511 1 0 1 1 0 0 +EDGE2 5251 5230 -0.882684 -0.0587845 1.59361 1 0 1 1 0 0 +EDGE2 5251 5250 -1.00689 0.0442253 -1.59296 1 0 1 1 0 0 +EDGE2 5251 5231 -0.0275158 -0.0546864 -0.00957425 1 0 1 1 0 0 +EDGE2 5252 5251 -0.972976 -0.0186851 0.00826426 1 0 1 1 0 0 +EDGE2 5252 5232 0.0324094 -0.0502086 0.00115557 1 0 1 1 0 0 +EDGE2 5252 5233 1.00601 -0.0135867 0.0240597 1 0 1 1 0 0 +EDGE2 5252 5231 -0.961337 0.0514721 -0.0186299 1 0 1 1 0 0 +EDGE2 5253 5234 1.04077 0.00672366 -0.0320702 1 0 1 1 0 0 +EDGE2 5253 5232 -1.06852 0.0172604 0.0025737 1 0 1 1 0 0 +EDGE2 5253 5252 -0.923921 0.0505254 -0.00203058 1 0 1 1 0 0 +EDGE2 5253 5233 0.00708121 0.0318095 -0.0244288 1 0 1 1 0 0 +EDGE2 5254 5253 -1.09224 -0.0251384 -0.0154445 1 0 1 1 0 0 +EDGE2 5254 5235 0.874589 -0.0248458 -0.00889735 1 0 1 1 0 0 +EDGE2 5254 5234 -0.0167774 0.0702159 0.00328586 1 0 1 1 0 0 +EDGE2 5254 5233 -1.03648 0.0487891 0.00549811 1 0 1 1 0 0 +EDGE2 5255 5236 -0.00312236 1.03512 1.58972 1 0 1 1 0 0 +EDGE2 5255 5254 -1.00917 0.064233 -0.0188666 1 0 1 1 0 0 +EDGE2 5255 5235 -0.0811603 0.0242282 -0.00747322 1 0 1 1 0 0 +EDGE2 5255 5234 -0.949695 0.153038 -0.0091953 1 0 1 1 0 0 +EDGE2 5256 5255 -0.97419 0.00633744 1.52272 1 0 1 1 0 0 +EDGE2 5256 5235 -1.06632 -0.0397918 1.55923 1 0 1 1 0 0 +EDGE2 5257 5256 -1.03741 -0.0523688 0.00224676 1 0 1 1 0 0 +EDGE2 5258 5257 -1.01443 0.0545497 0.0171517 1 0 1 1 0 0 +EDGE2 5259 5258 -0.953189 -0.130717 -0.00287124 1 0 1 1 0 0 +EDGE2 5259 5220 1.11032 -0.0453435 -3.13965 1 0 1 1 0 0 +EDGE2 5260 5220 0.0436817 0.0586473 -3.15145 1 0 1 1 0 0 +EDGE2 5260 5259 -0.96796 -0.0737621 0.0514834 1 0 1 1 0 0 +EDGE2 5260 5221 -0.019361 -0.916571 -1.52575 1 0 1 1 0 0 +EDGE2 5260 5219 1.01255 -0.00885836 -3.14541 1 0 1 1 0 0 +EDGE2 5261 5220 -0.999867 0.0568148 -1.59404 1 0 1 1 0 0 +EDGE2 5261 5260 -1.07767 0.128375 1.6035 1 0 1 1 0 0 +EDGE2 5261 5221 -0.00162504 -0.0239701 0.00648769 1 0 1 1 0 0 +EDGE2 5261 5222 0.984658 0.0420337 -0.012616 1 0 1 1 0 0 +EDGE2 5262 5261 -0.995339 0.0622321 -0.0519242 1 0 1 1 0 0 +EDGE2 5262 5221 -1.05114 -0.0118675 -0.0426434 1 0 1 1 0 0 +EDGE2 5262 5222 -0.0162129 0.0493094 -0.0244359 1 0 1 1 0 0 +EDGE2 5262 5223 0.952608 0.0372079 -0.034842 1 0 1 1 0 0 +EDGE2 5263 5222 -1.02807 0.0310602 0.03641 1 0 1 1 0 0 +EDGE2 5263 5262 -0.930828 0.0474441 -0.0189019 1 0 1 1 0 0 +EDGE2 5263 5223 -0.0372303 0.0188325 0.0240755 1 0 1 1 0 0 +EDGE2 5263 5224 1.09198 -0.0819277 -0.0146395 1 0 1 1 0 0 +EDGE2 5264 5263 -1.03621 0.0421873 -0.0196007 1 0 1 1 0 0 +EDGE2 5264 5223 -1.07751 0.0159748 -0.0308295 1 0 1 1 0 0 +EDGE2 5264 5224 0.0297242 -0.0195517 -0.00129233 1 0 1 1 0 0 +EDGE2 5264 5165 1.0135 0.00965875 -3.14704 1 0 1 1 0 0 +EDGE2 5264 5225 0.935684 -0.0300547 -0.00974231 1 0 1 1 0 0 +EDGE2 5265 5226 -0.0482757 -1.03091 -1.55816 1 0 1 1 0 0 +EDGE2 5265 5264 -1.01787 0.0460838 0.0157839 1 0 1 1 0 0 +EDGE2 5265 5224 -1.09166 -0.01108 -0.0173269 1 0 1 1 0 0 +EDGE2 5265 5165 0.0370984 -0.053744 -3.16794 1 0 1 1 0 0 +EDGE2 5265 5225 0.0493168 0.0071806 -0.0107188 1 0 1 1 0 0 +EDGE2 5265 5164 0.956496 -0.0736247 -3.12539 1 0 1 1 0 0 +EDGE2 5265 5166 -0.0441564 0.90879 1.56822 1 0 1 1 0 0 +EDGE2 5266 5165 -1.06536 -0.0583413 1.55476 1 0 1 1 0 0 +EDGE2 5266 5225 -0.974727 0.0172342 -1.55587 1 0 1 1 0 0 +EDGE2 5266 5265 -1.02725 -0.0179078 -1.56564 1 0 1 1 0 0 +EDGE2 5266 5166 -0.0616791 0.0132129 -0.0433674 1 0 1 1 0 0 +EDGE2 5266 5167 0.870122 -0.0332239 0.0113917 1 0 1 1 0 0 +EDGE2 5267 5266 -1.05539 0.0383005 0.00301418 1 0 1 1 0 0 +EDGE2 5267 5166 -1.0444 -0.000306598 -0.00624789 1 0 1 1 0 0 +EDGE2 5267 5167 -0.0487688 0.0149578 -0.0215563 1 0 1 1 0 0 +EDGE2 5267 5168 0.96105 0.0405306 -0.00915463 1 0 1 1 0 0 +EDGE2 5268 5167 -1.04181 0.00930512 0.0207373 1 0 1 1 0 0 +EDGE2 5268 5267 -0.998381 0.0138871 -0.00163632 1 0 1 1 0 0 +EDGE2 5268 5168 0.0589348 -0.0250914 0.000963451 1 0 1 1 0 0 +EDGE2 5268 5169 0.89773 -0.0603219 -0.0114304 1 0 1 1 0 0 +EDGE2 5269 5268 -0.962799 -0.0947609 -0.00806636 1 0 1 1 0 0 +EDGE2 5269 5168 -1.01213 -0.0396488 -0.0534084 1 0 1 1 0 0 +EDGE2 5269 5169 0.0701621 -0.0130195 -0.00464114 1 0 1 1 0 0 +EDGE2 5269 5170 0.955834 0.0877518 -0.0150559 1 0 1 1 0 0 +EDGE2 5269 5130 1.09329 -0.0123659 -3.16469 1 0 1 1 0 0 +EDGE2 5270 5169 -0.976428 0.0237889 0.0181044 1 0 1 1 0 0 +EDGE2 5270 5269 -1.06669 -0.0557434 -0.000302434 1 0 1 1 0 0 +EDGE2 5270 5171 0.0236562 0.988914 1.55031 1 0 1 1 0 0 +EDGE2 5270 5131 -0.0843132 -1.06555 -1.53148 1 0 1 1 0 0 +EDGE2 5270 5170 -0.0483094 -0.00767997 0.0201337 1 0 1 1 0 0 +EDGE2 5270 5130 -0.0446787 0.010847 -3.11885 1 0 1 1 0 0 +EDGE2 5270 5129 0.918002 0.0382848 -3.09864 1 0 1 1 0 0 +EDGE2 5271 5171 -0.0523116 0.0612967 -0.00159425 1 0 1 1 0 0 +EDGE2 5271 5172 0.970623 0.126215 -0.0158151 1 0 1 1 0 0 +EDGE2 5271 5170 -0.956958 -0.0721949 -1.58806 1 0 1 1 0 0 +EDGE2 5271 5270 -0.910023 0.0173067 -1.56549 1 0 1 1 0 0 +EDGE2 5271 5130 -1.02064 -0.016658 1.60007 1 0 1 1 0 0 +EDGE2 5272 5171 -1.01125 -0.00608422 -0.00615324 1 0 1 1 0 0 +EDGE2 5272 5173 1.06039 -0.0342135 -0.00987567 1 0 1 1 0 0 +EDGE2 5272 5172 0.074874 -0.0492731 -0.0227235 1 0 1 1 0 0 +EDGE2 5272 5271 -1.04853 0.0827397 0.0307174 1 0 1 1 0 0 +EDGE2 5273 5174 0.969564 0.0510397 0.00102064 1 0 1 1 0 0 +EDGE2 5273 5173 0.0460285 0.0325059 -0.00480363 1 0 1 1 0 0 +EDGE2 5273 5172 -0.974565 0.000174281 0.0294272 1 0 1 1 0 0 +EDGE2 5273 5272 -1.08616 0.034157 0.00602666 1 0 1 1 0 0 +EDGE2 5274 5175 1.00439 -0.0886061 0.00681784 1 0 1 1 0 0 +EDGE2 5274 5195 1.01287 0.0185412 -3.1539 1 0 1 1 0 0 +EDGE2 5274 5215 0.993245 -0.119419 -3.1338 1 0 1 1 0 0 +EDGE2 5274 5273 -1.02056 -0.0264768 -0.016599 1 0 1 1 0 0 +EDGE2 5274 5174 0.0573336 -0.0179891 0.0297371 1 0 1 1 0 0 +EDGE2 5274 5173 -1.04126 -0.0350605 0.0312748 1 0 1 1 0 0 +EDGE2 5275 5216 -0.0835364 0.923032 1.59184 1 0 1 1 0 0 +EDGE2 5275 5176 0.0244819 -0.974585 -1.60001 1 0 1 1 0 0 +EDGE2 5275 5274 -0.976682 -0.0180059 -0.00909595 1 0 1 1 0 0 +EDGE2 5275 5194 1.07112 -0.00758279 -3.1348 1 0 1 1 0 0 +EDGE2 5275 5214 0.952563 0.028487 -3.12354 1 0 1 1 0 0 +EDGE2 5275 5175 0.0108303 -0.0163266 -0.0214319 1 0 1 1 0 0 +EDGE2 5275 5195 -0.0832148 0.0148979 -3.16384 1 0 1 1 0 0 +EDGE2 5275 5215 0.0971453 -0.0157045 -3.14954 1 0 1 1 0 0 +EDGE2 5275 5174 -0.959438 -0.0654266 -0.016263 1 0 1 1 0 0 +EDGE2 5275 5196 0.0048923 -0.975609 -1.57446 1 0 1 1 0 0 +EDGE2 5276 5217 0.994944 0.0870754 -0.0399542 1 0 1 1 0 0 +EDGE2 5276 5216 -0.00634293 0.137015 -0.0185917 1 0 1 1 0 0 +EDGE2 5276 5275 -0.999718 0.029051 -1.57399 1 0 1 1 0 0 +EDGE2 5276 5175 -1.00064 0.000973754 -1.57677 1 0 1 1 0 0 +EDGE2 5276 5195 -0.947528 -0.0652914 1.57992 1 0 1 1 0 0 +EDGE2 5276 5215 -1.06973 -0.0225852 1.56966 1 0 1 1 0 0 +EDGE2 5277 5218 1.03834 -0.00448509 0.0171063 1 0 1 1 0 0 +EDGE2 5277 5217 0.0363476 0.0192764 -0.0289605 1 0 1 1 0 0 +EDGE2 5277 5216 -1.03306 0.00699196 0.0248509 1 0 1 1 0 0 +EDGE2 5277 5276 -1.00887 0.00347833 0.0171831 1 0 1 1 0 0 +EDGE2 5278 5219 0.925676 -0.00408402 -0.0153546 1 0 1 1 0 0 +EDGE2 5278 5218 -0.0314081 0.021074 0.026605 1 0 1 1 0 0 +EDGE2 5278 5217 -1.07465 -0.0184719 -0.00308941 1 0 1 1 0 0 +EDGE2 5278 5277 -0.962797 -0.0166595 0.0172564 1 0 1 1 0 0 +EDGE2 5279 5220 1.20702 -0.0149067 0.00702275 1 0 1 1 0 0 +EDGE2 5279 5260 1.03767 0.0169071 -3.15915 1 0 1 1 0 0 +EDGE2 5279 5219 -0.022588 -0.00934807 0.00588211 1 0 1 1 0 0 +EDGE2 5279 5218 -1.08902 0.149875 -0.00775319 1 0 1 1 0 0 +EDGE2 5279 5278 -1.02762 0.0382329 -0.0284359 1 0 1 1 0 0 +EDGE2 5280 5220 0.0837293 -0.0308631 -0.00522486 1 0 1 1 0 0 +EDGE2 5280 5259 1.02704 0.000282687 -3.14583 1 0 1 1 0 0 +EDGE2 5280 5260 -0.0248512 0.00756492 -3.116 1 0 1 1 0 0 +EDGE2 5280 5261 0.0190713 0.973867 1.58048 1 0 1 1 0 0 +EDGE2 5280 5221 -0.0129371 0.970316 1.58753 1 0 1 1 0 0 +EDGE2 5280 5219 -1.08638 -0.0245012 0.00953126 1 0 1 1 0 0 +EDGE2 5280 5279 -0.972892 0.0330508 -0.0102304 1 0 1 1 0 0 +EDGE2 5281 5220 -0.993238 -0.00401917 -1.56656 1 0 1 1 0 0 +EDGE2 5281 5280 -1.11079 0.0134405 -1.54725 1 0 1 1 0 0 +EDGE2 5281 5260 -1.0288 -0.0071675 1.50096 1 0 1 1 0 0 +EDGE2 5281 5261 -0.0163213 0.0147077 -0.0108381 1 0 1 1 0 0 +EDGE2 5281 5221 -0.052989 0.0584767 0.0237362 1 0 1 1 0 0 +EDGE2 5281 5222 0.956563 0.00462349 -0.0136076 1 0 1 1 0 0 +EDGE2 5281 5262 0.906748 -0.0757325 -0.00156525 1 0 1 1 0 0 +EDGE2 5282 5263 1.03491 -0.0389339 0.0141854 1 0 1 1 0 0 +EDGE2 5282 5261 -0.896334 0.0176 0.00501709 1 0 1 1 0 0 +EDGE2 5282 5281 -0.991893 -0.0197961 0.0318406 1 0 1 1 0 0 +EDGE2 5282 5221 -0.968239 -0.0562816 0.0123911 1 0 1 1 0 0 +EDGE2 5282 5222 -0.0386999 0.0286716 0.00979355 1 0 1 1 0 0 +EDGE2 5282 5262 0.00442173 0.0392464 0.00196058 1 0 1 1 0 0 +EDGE2 5282 5223 1.00347 -0.071979 0.0228008 1 0 1 1 0 0 +EDGE2 5283 5263 -0.0156642 -0.0215719 0.019829 1 0 1 1 0 0 +EDGE2 5283 5282 -0.942406 -0.0875394 -0.0100938 1 0 1 1 0 0 +EDGE2 5283 5222 -1.04356 0.0912952 6.30635e-05 1 0 1 1 0 0 +EDGE2 5283 5262 -1.01828 0.0798299 0.00899754 1 0 1 1 0 0 +EDGE2 5283 5264 0.960922 -0.00375242 0.00580197 1 0 1 1 0 0 +EDGE2 5283 5223 -0.0553515 -0.0475609 -0.0146218 1 0 1 1 0 0 +EDGE2 5283 5224 0.93014 -0.0545948 -0.0221283 1 0 1 1 0 0 +EDGE2 5284 5263 -0.941615 0.00594896 -0.0295433 1 0 1 1 0 0 +EDGE2 5284 5283 -0.934318 0.0917844 -0.00507376 1 0 1 1 0 0 +EDGE2 5284 5264 -0.0418843 0.0930527 0.00440672 1 0 1 1 0 0 +EDGE2 5284 5223 -0.967758 0.0907141 -0.0254474 1 0 1 1 0 0 +EDGE2 5284 5224 0.0120795 -0.00471147 0.01048 1 0 1 1 0 0 +EDGE2 5284 5165 0.973669 -0.0183494 -3.16897 1 0 1 1 0 0 +EDGE2 5284 5225 0.934061 0.028335 0.0114501 1 0 1 1 0 0 +EDGE2 5284 5265 0.987078 0.00901437 -0.0520362 1 0 1 1 0 0 +EDGE2 5285 5226 -0.0324754 -1.02941 -1.57205 1 0 1 1 0 0 +EDGE2 5285 5264 -0.998613 -0.01036 0.0131137 1 0 1 1 0 0 +EDGE2 5285 5284 -1.03751 -0.00146734 -0.00829745 1 0 1 1 0 0 +EDGE2 5285 5224 -0.957569 0.0158794 0.0222437 1 0 1 1 0 0 +EDGE2 5285 5165 -0.0154935 0.0229327 -3.17357 1 0 1 1 0 0 +EDGE2 5285 5225 0.014764 0.0936308 0.0227322 1 0 1 1 0 0 +EDGE2 5285 5265 0.0124336 -0.00169602 -0.0128935 1 0 1 1 0 0 +EDGE2 5285 5164 1.03167 0.00981277 -3.1196 1 0 1 1 0 0 +EDGE2 5285 5266 0.0230961 0.976169 1.5811 1 0 1 1 0 0 +EDGE2 5285 5166 0.0250901 0.928558 1.60619 1 0 1 1 0 0 +EDGE2 5286 5285 -0.946208 0.0869951 -1.58288 1 0 1 1 0 0 +EDGE2 5286 5165 -0.951367 -0.0720927 1.5663 1 0 1 1 0 0 +EDGE2 5286 5225 -1.07331 -0.00783602 -1.55329 1 0 1 1 0 0 +EDGE2 5286 5265 -1.01001 0.0479768 -1.57031 1 0 1 1 0 0 +EDGE2 5286 5266 -0.00463405 -0.0535579 -0.00784849 1 0 1 1 0 0 +EDGE2 5286 5166 -0.00482095 -0.0672182 0.0127381 1 0 1 1 0 0 +EDGE2 5286 5167 0.933708 0.0418191 -0.00633177 1 0 1 1 0 0 +EDGE2 5286 5267 0.934823 0.015716 -0.008712 1 0 1 1 0 0 +EDGE2 5287 5266 -0.967388 0.0264471 0.0499241 1 0 1 1 0 0 +EDGE2 5287 5286 -1.02037 -0.00497862 -0.00771676 1 0 1 1 0 0 +EDGE2 5287 5166 -1.00872 -0.0180399 -0.0130955 1 0 1 1 0 0 +EDGE2 5287 5268 0.929144 -0.0867676 -0.0148661 1 0 1 1 0 0 +EDGE2 5287 5167 -0.0351356 0.0437639 -0.0101371 1 0 1 1 0 0 +EDGE2 5287 5267 -0.0184141 0.114157 0.0181815 1 0 1 1 0 0 +EDGE2 5287 5168 0.975009 -0.0422323 -0.0125027 1 0 1 1 0 0 +EDGE2 5288 5268 -0.0579479 -0.0379741 -0.0215644 1 0 1 1 0 0 +EDGE2 5288 5167 -1.06453 0.00663123 -0.00637823 1 0 1 1 0 0 +EDGE2 5288 5287 -0.96099 0.0422807 -0.011935 1 0 1 1 0 0 +EDGE2 5288 5267 -1.00492 -0.0594187 0.0189809 1 0 1 1 0 0 +EDGE2 5288 5168 -0.192537 0.112706 -0.00238694 1 0 1 1 0 0 +EDGE2 5288 5169 1.06871 0.0514954 0.0363875 1 0 1 1 0 0 +EDGE2 5288 5269 1.00999 -0.0359508 0.0470504 1 0 1 1 0 0 +EDGE2 5289 5268 -1.01838 -0.0833903 -0.00532567 1 0 1 1 0 0 +EDGE2 5289 5288 -1.09449 -0.0155047 -0.0171105 1 0 1 1 0 0 +EDGE2 5289 5168 -0.980468 -0.0302187 -0.0144216 1 0 1 1 0 0 +EDGE2 5289 5169 0.0502144 0.00106465 0.0219247 1 0 1 1 0 0 +EDGE2 5289 5269 -0.0251716 0.0247587 0.00572637 1 0 1 1 0 0 +EDGE2 5289 5170 1.04533 0.0341853 0.00169837 1 0 1 1 0 0 +EDGE2 5289 5270 0.955066 0.0777918 -0.0217774 1 0 1 1 0 0 +EDGE2 5289 5130 1.02813 0.0117849 -3.12853 1 0 1 1 0 0 +EDGE2 5290 5289 -1.04795 0.00384439 0.020853 1 0 1 1 0 0 +EDGE2 5290 5169 -1.01455 -0.013152 -0.00703142 1 0 1 1 0 0 +EDGE2 5290 5269 -0.981139 -0.0595979 0.0351794 1 0 1 1 0 0 +EDGE2 5290 5171 0.0002603 1.02014 1.57092 1 0 1 1 0 0 +EDGE2 5290 5271 -0.00128367 1.01965 1.56585 1 0 1 1 0 0 +EDGE2 5290 5131 0.0506013 -1.07126 -1.55997 1 0 1 1 0 0 +EDGE2 5290 5170 -0.029201 0.0354688 -0.00734281 1 0 1 1 0 0 +EDGE2 5290 5270 -0.0433179 0.040409 -0.0188361 1 0 1 1 0 0 +EDGE2 5290 5130 0.031132 0.0556405 -3.13211 1 0 1 1 0 0 +EDGE2 5290 5129 0.994178 0.00661647 -3.13869 1 0 1 1 0 0 +EDGE2 5291 5171 -0.04482 0.0126678 -0.0148141 1 0 1 1 0 0 +EDGE2 5291 5172 1.01347 0.0706796 -0.0201139 1 0 1 1 0 0 +EDGE2 5291 5272 0.963343 -0.00324246 0.0141349 1 0 1 1 0 0 +EDGE2 5291 5271 -0.032489 -0.0305785 0.00412675 1 0 1 1 0 0 +EDGE2 5291 5170 -0.947625 0.0400577 -1.5674 1 0 1 1 0 0 +EDGE2 5291 5270 -1.00927 -0.00591751 -1.56334 1 0 1 1 0 0 +EDGE2 5291 5290 -0.986962 -0.0931349 -1.53378 1 0 1 1 0 0 +EDGE2 5291 5130 -1.00425 0.0794753 1.56815 1 0 1 1 0 0 +EDGE2 5292 5171 -1.05544 -0.0110502 -0.0104543 1 0 1 1 0 0 +EDGE2 5292 5273 0.983061 0.00443468 -0.0086214 1 0 1 1 0 0 +EDGE2 5292 5173 1.02475 -0.0151293 0.020037 1 0 1 1 0 0 +EDGE2 5292 5291 -0.943079 0.0742874 -0.0185924 1 0 1 1 0 0 +EDGE2 5292 5172 -0.0681249 -0.0352345 -0.0350438 1 0 1 1 0 0 +EDGE2 5292 5272 0.0145029 -0.0434153 0.0231095 1 0 1 1 0 0 +EDGE2 5292 5271 -1.08834 -0.0179437 0.021635 1 0 1 1 0 0 +EDGE2 5293 5274 1.04639 0.124943 0.0157935 1 0 1 1 0 0 +EDGE2 5293 5292 -1.03401 -0.0436092 -0.0111232 1 0 1 1 0 0 +EDGE2 5293 5273 -0.0485782 -0.0269797 -0.0338919 1 0 1 1 0 0 +EDGE2 5293 5174 1.02039 -0.0727471 0.00381499 1 0 1 1 0 0 +EDGE2 5293 5173 -0.0748908 -0.000643224 0.0138314 1 0 1 1 0 0 +EDGE2 5293 5172 -0.986684 -0.0975214 -0.00310348 1 0 1 1 0 0 +EDGE2 5293 5272 -0.957103 -0.0559769 -0.00639172 1 0 1 1 0 0 +EDGE2 5294 5274 -0.0138599 0.0122823 -0.00549892 1 0 1 1 0 0 +EDGE2 5294 5275 0.990153 -0.00338779 0.0271387 1 0 1 1 0 0 +EDGE2 5294 5175 1.00177 0.0174884 -0.00173733 1 0 1 1 0 0 +EDGE2 5294 5195 0.935899 0.0231774 -3.15125 1 0 1 1 0 0 +EDGE2 5294 5215 0.946079 -0.0603096 -3.14109 1 0 1 1 0 0 +EDGE2 5294 5273 -1.00392 -0.0344652 -0.00621775 1 0 1 1 0 0 +EDGE2 5294 5293 -1.01261 -0.0734278 -0.0155144 1 0 1 1 0 0 +EDGE2 5294 5174 0.0253978 -0.0812525 0.00809766 1 0 1 1 0 0 +EDGE2 5294 5173 -0.976667 -0.0930385 0.00661363 1 0 1 1 0 0 +EDGE2 5295 5216 0.052537 1.04156 1.54577 1 0 1 1 0 0 +EDGE2 5295 5276 0.00266308 1.06101 1.57798 1 0 1 1 0 0 +EDGE2 5295 5176 -0.0430091 -0.881269 -1.60538 1 0 1 1 0 0 +EDGE2 5295 5274 -1.04408 0.00854891 0.00996136 1 0 1 1 0 0 +EDGE2 5295 5275 0.000416704 -0.0352035 -0.00283134 1 0 1 1 0 0 +EDGE2 5295 5194 1.007 0.00828869 -3.13969 1 0 1 1 0 0 +EDGE2 5295 5214 0.929543 -0.121502 -3.16154 1 0 1 1 0 0 +EDGE2 5295 5175 -0.0447413 -0.106901 0.000229589 1 0 1 1 0 0 +EDGE2 5295 5195 -0.0155267 -0.0426131 -3.14783 1 0 1 1 0 0 +EDGE2 5295 5215 -0.0747928 0.0124793 -3.12329 1 0 1 1 0 0 +EDGE2 5295 5294 -1.04028 -0.0380039 -0.00416697 1 0 1 1 0 0 +EDGE2 5295 5174 -1.05722 0.0403389 0.0220277 1 0 1 1 0 0 +EDGE2 5295 5196 0.0466087 -0.922206 -1.60988 1 0 1 1 0 0 +EDGE2 5296 5217 0.897547 0.0814138 0.0229903 1 0 1 1 0 0 +EDGE2 5296 5277 1.0077 -0.0777914 -0.0152586 1 0 1 1 0 0 +EDGE2 5296 5216 0.0660189 -0.0177427 -0.0103862 1 0 1 1 0 0 +EDGE2 5296 5276 -0.0602193 0.0162932 0.00372514 1 0 1 1 0 0 +EDGE2 5296 5275 -1.00778 -0.0373502 -1.58607 1 0 1 1 0 0 +EDGE2 5296 5295 -1.02703 0.0409659 -1.60112 1 0 1 1 0 0 +EDGE2 5296 5175 -1.02614 0.134322 -1.58906 1 0 1 1 0 0 +EDGE2 5296 5195 -0.965328 0.00833199 1.59748 1 0 1 1 0 0 +EDGE2 5296 5215 -1.05657 -0.0302012 1.5437 1 0 1 1 0 0 +EDGE2 5297 5218 0.958955 0.0287936 0.0118859 1 0 1 1 0 0 +EDGE2 5297 5278 0.997478 0.0154309 -0.0115558 1 0 1 1 0 0 +EDGE2 5297 5217 0.0221513 -0.0672715 0.00342814 1 0 1 1 0 0 +EDGE2 5297 5277 0.0294225 -0.0427065 -0.0156915 1 0 1 1 0 0 +EDGE2 5297 5216 -1.03528 -3.40414e-05 -0.0123458 1 0 1 1 0 0 +EDGE2 5297 5276 -1.05457 -0.0580576 -0.00993886 1 0 1 1 0 0 +EDGE2 5297 5296 -1.04724 -0.0469315 0.00635838 1 0 1 1 0 0 +EDGE2 5298 5219 0.986359 0.0231643 -0.0172092 1 0 1 1 0 0 +EDGE2 5298 5279 1.07224 0.0268974 -0.0295497 1 0 1 1 0 0 +EDGE2 5298 5218 0.014509 -0.0652895 0.0211649 1 0 1 1 0 0 +EDGE2 5298 5278 0.0174009 -0.0628808 0.0252625 1 0 1 1 0 0 +EDGE2 5298 5217 -0.98215 0.0616274 -0.0100462 1 0 1 1 0 0 +EDGE2 5298 5277 -0.949789 -0.0133599 0.011692 1 0 1 1 0 0 +EDGE2 5298 5297 -0.974797 0.0458182 0.00980108 1 0 1 1 0 0 +EDGE2 5299 5220 0.956338 -0.00337008 -0.0298346 1 0 1 1 0 0 +EDGE2 5299 5280 1.06859 0.0431163 -0.0135999 1 0 1 1 0 0 +EDGE2 5299 5260 1.02579 0.00147723 -3.11928 1 0 1 1 0 0 +EDGE2 5299 5298 -1.05583 0.035942 0.0182898 1 0 1 1 0 0 +EDGE2 5299 5219 0.0746721 0.00443314 0.00845145 1 0 1 1 0 0 +EDGE2 5299 5279 -0.00866502 0.00131107 0.000649231 1 0 1 1 0 0 +EDGE2 5299 5218 -0.912234 0.0659722 -0.0170015 1 0 1 1 0 0 +EDGE2 5299 5278 -0.96088 -0.0860769 0.0029009 1 0 1 1 0 0 +EDGE2 5300 5220 -0.0132146 -0.00167555 0.0212818 1 0 1 1 0 0 +EDGE2 5300 5259 1.00642 -0.0218646 -3.17492 1 0 1 1 0 0 +EDGE2 5300 5280 -0.00107753 0.00831562 0.00905191 1 0 1 1 0 0 +EDGE2 5300 5260 0.0442849 -0.000674288 -3.11947 1 0 1 1 0 0 +EDGE2 5300 5261 0.0175626 0.995146 1.5434 1 0 1 1 0 0 +EDGE2 5300 5281 -0.0407454 0.978064 1.5691 1 0 1 1 0 0 +EDGE2 5300 5221 -0.0989003 1.00963 1.57908 1 0 1 1 0 0 +EDGE2 5300 5219 -1.03908 -0.00707621 0.0137937 1 0 1 1 0 0 +EDGE2 5300 5279 -0.951099 0.0652219 0.00156437 1 0 1 1 0 0 +EDGE2 5300 5299 -1.01891 0.0245933 0.012854 1 0 1 1 0 0 +EDGE2 5301 5220 -0.969259 0.000230363 1.58675 1 0 1 1 0 0 +EDGE2 5301 5280 -1.00685 -0.0182223 1.584 1 0 1 1 0 0 +EDGE2 5301 5300 -1.00154 0.0339899 1.57318 1 0 1 1 0 0 +EDGE2 5301 5260 -1.07899 0.106621 -1.55384 1 0 1 1 0 0 +EDGE2 5302 5301 -1.08826 -0.0497139 -0.00862183 1 0 1 1 0 0 +EDGE2 5303 5302 -1.04643 -0.0408984 -0.0377279 1 0 1 1 0 0 +EDGE2 5304 5303 -0.95925 0.0271785 -0.0136847 1 0 1 1 0 0 +EDGE2 5305 5304 -1.0047 0.00365805 0.0175622 1 0 1 1 0 0 +EDGE2 5306 5305 -1.00085 0.00972585 -1.5817 1 0 1 1 0 0 +EDGE2 5307 5306 -1.03316 0.00355143 -0.00808913 1 0 1 1 0 0 +EDGE2 5308 5307 -0.98276 0.00358443 0.0238656 1 0 1 1 0 0 +EDGE2 5309 5308 -0.901166 0.0117655 -0.044529 1 0 1 1 0 0 +EDGE2 5310 5309 -1.01307 0.0894427 0.00909529 1 0 1 1 0 0 +EDGE2 5311 5310 -0.941743 0.065672 -1.56327 1 0 1 1 0 0 +EDGE2 5312 5311 -0.916795 -0.0207715 0.00633645 1 0 1 1 0 0 +EDGE2 5313 5312 -0.960575 0.0163333 0.00361385 1 0 1 1 0 0 +EDGE2 5314 5313 -1.02207 0.00295707 -0.0198707 1 0 1 1 0 0 +EDGE2 5314 5255 1.02904 -0.0478483 -3.13166 1 0 1 1 0 0 +EDGE2 5314 5235 0.958063 -0.0699168 -3.15048 1 0 1 1 0 0 +EDGE2 5315 5236 -0.0334773 -1.00333 -1.59187 1 0 1 1 0 0 +EDGE2 5315 5314 -0.98921 0.11217 0.0237346 1 0 1 1 0 0 +EDGE2 5315 5255 0.00765215 0.0795573 -3.15736 1 0 1 1 0 0 +EDGE2 5315 5254 1.013 0.00462199 -3.13148 1 0 1 1 0 0 +EDGE2 5315 5235 -0.0128917 -0.00471703 -3.17383 1 0 1 1 0 0 +EDGE2 5315 5234 1.05685 0.00923175 -3.18686 1 0 1 1 0 0 +EDGE2 5315 5256 -0.0253961 1.05931 1.49752 1 0 1 1 0 0 +EDGE2 5316 5236 -0.0762093 0.013318 -0.0154867 1 0 1 1 0 0 +EDGE2 5316 5237 1.04259 0.0100835 -0.00776577 1 0 1 1 0 0 +EDGE2 5316 5255 -0.954302 0.0512556 -1.5699 1 0 1 1 0 0 +EDGE2 5316 5315 -1.05671 0.0220923 1.56921 1 0 1 1 0 0 +EDGE2 5316 5235 -1.07951 0.0266402 -1.57945 1 0 1 1 0 0 +EDGE2 5317 5236 -0.941548 -0.0839545 0.0534792 1 0 1 1 0 0 +EDGE2 5317 5237 -0.0860831 -0.0357087 -0.0322797 1 0 1 1 0 0 +EDGE2 5317 5238 0.915367 0.043896 0.00194299 1 0 1 1 0 0 +EDGE2 5317 5316 -1.00145 -0.0112875 0.0329506 1 0 1 1 0 0 +EDGE2 5318 5239 1.06294 0.0405817 0.0368701 1 0 1 1 0 0 +EDGE2 5318 5237 -0.984239 -0.0705397 -0.0145437 1 0 1 1 0 0 +EDGE2 5318 5317 -0.974912 0.0118217 -0.0228733 1 0 1 1 0 0 +EDGE2 5318 5238 -0.0166649 -0.0279513 -0.00041243 1 0 1 1 0 0 +EDGE2 5319 5318 -0.946272 0.0761549 -0.0226261 1 0 1 1 0 0 +EDGE2 5319 5240 0.904357 -0.0198238 -0.0178528 1 0 1 1 0 0 +EDGE2 5319 5239 0.0613887 -0.0113521 0.00821927 1 0 1 1 0 0 +EDGE2 5319 5238 -1.02369 -0.0806609 0.0109208 1 0 1 1 0 0 +EDGE2 5320 5240 -0.0204051 0.0546917 -0.0105482 1 0 1 1 0 0 +EDGE2 5320 5241 -0.0422343 0.930916 1.60331 1 0 1 1 0 0 +EDGE2 5320 5319 -1.01087 -0.0319532 -0.0174899 1 0 1 1 0 0 +EDGE2 5320 5239 -1.01651 0.0142361 -0.0517989 1 0 1 1 0 0 +EDGE2 5321 5240 -1.005 -0.0179295 -1.5536 1 0 1 1 0 0 +EDGE2 5321 5320 -1.0328 0.132203 -1.59889 1 0 1 1 0 0 +EDGE2 5321 5241 0.023602 -0.00828274 0.000644092 1 0 1 1 0 0 +EDGE2 5321 5242 0.931881 -0.0440284 0.00279564 1 0 1 1 0 0 +EDGE2 5322 5243 1.00573 -0.0554428 -0.00591267 1 0 1 1 0 0 +EDGE2 5322 5321 -0.9729 0.0103311 0.0496861 1 0 1 1 0 0 +EDGE2 5322 5241 -0.999313 -0.0506019 0.0255908 1 0 1 1 0 0 +EDGE2 5322 5242 -0.0160215 0.0756934 -0.00335335 1 0 1 1 0 0 +EDGE2 5323 5243 0.0372108 -0.0238561 0.00996751 1 0 1 1 0 0 +EDGE2 5323 5322 -0.905069 -0.0280504 -0.0016148 1 0 1 1 0 0 +EDGE2 5323 5242 -0.924014 0.107455 -0.00186156 1 0 1 1 0 0 +EDGE2 5323 5244 1.00668 0.0258123 -0.00462616 1 0 1 1 0 0 +EDGE2 5324 5243 -1.04135 -0.0574657 -0.014049 1 0 1 1 0 0 +EDGE2 5324 5323 -1.01794 0.091577 -0.0254457 1 0 1 1 0 0 +EDGE2 5324 5245 1.02729 0.026756 0.000279341 1 0 1 1 0 0 +EDGE2 5324 5244 0.0424123 0.0239222 0.00323396 1 0 1 1 0 0 +EDGE2 5325 5324 -1.0184 0.0911367 -0.0137709 1 0 1 1 0 0 +EDGE2 5325 5245 0.034348 0.0269639 0.00869601 1 0 1 1 0 0 +EDGE2 5325 5244 -0.997746 -0.0381603 0.00970609 1 0 1 1 0 0 +EDGE2 5325 5246 0.0135052 0.9946 1.53372 1 0 1 1 0 0 +EDGE2 5326 5245 -0.986984 -0.0218368 1.5408 1 0 1 1 0 0 +EDGE2 5326 5325 -1.06348 0.133387 1.59619 1 0 1 1 0 0 +EDGE2 5327 5326 -1.01516 0.037274 -0.0408232 1 0 1 1 0 0 +EDGE2 5328 5327 -0.990448 -0.0275639 0.00474961 1 0 1 1 0 0 +EDGE2 5329 1910 0.999308 0.0431642 -3.13903 1 0 1 1 0 0 +EDGE2 5329 1330 1.07127 -0.0153202 -3.16669 1 0 1 1 0 0 +EDGE2 5329 1350 0.994245 0.0610553 -3.16007 1 0 1 1 0 0 +EDGE2 5329 1490 1.01311 0.0384672 -3.14311 1 0 1 1 0 0 +EDGE2 5329 5328 -0.980368 0.0371505 -0.0160677 1 0 1 1 0 0 +EDGE2 5330 1349 0.997537 -0.0026712 -3.13306 1 0 1 1 0 0 +EDGE2 5330 1489 0.956211 0.00828127 -3.10258 1 0 1 1 0 0 +EDGE2 5330 1909 1.0531 0.0740382 -3.1344 1 0 1 1 0 0 +EDGE2 5330 1329 0.903457 0.0318104 -3.13543 1 0 1 1 0 0 +EDGE2 5330 1910 0.00448625 -0.00445013 -3.12924 1 0 1 1 0 0 +EDGE2 5330 1911 0.113369 -1.03901 -1.54444 1 0 1 1 0 0 +EDGE2 5330 1331 0.0864798 -0.995531 -1.57349 1 0 1 1 0 0 +EDGE2 5330 1351 -0.00955358 -1.0248 -1.54384 1 0 1 1 0 0 +EDGE2 5330 1491 0.0510907 -1.04268 -1.55011 1 0 1 1 0 0 +EDGE2 5330 1330 -0.0252774 0.039617 -3.15416 1 0 1 1 0 0 +EDGE2 5330 1350 0.00164225 -0.0260647 -3.16094 1 0 1 1 0 0 +EDGE2 5330 1490 -0.0621053 -0.0880664 -3.14335 1 0 1 1 0 0 +EDGE2 5330 5329 -1.04057 0.0174281 -0.00928409 1 0 1 1 0 0 +EDGE2 5331 1910 -1.02616 -0.00182263 1.56247 1 0 1 1 0 0 +EDGE2 5331 5330 -1.08991 -0.0256593 -1.57573 1 0 1 1 0 0 +EDGE2 5331 1330 -1.05857 0.0844348 1.52405 1 0 1 1 0 0 +EDGE2 5331 1350 -1.01481 -0.00234021 1.5565 1 0 1 1 0 0 +EDGE2 5331 1490 -1.02023 -0.0109444 1.57674 1 0 1 1 0 0 +EDGE2 5332 5331 -0.93148 -0.0358083 -0.0159841 1 0 1 1 0 0 +EDGE2 5333 5332 -1.06039 -0.0186277 -7.00056e-05 1 0 1 1 0 0 +EDGE2 5334 1635 1.05415 0.00369216 -3.15072 1 0 1 1 0 0 +EDGE2 5334 5333 -0.943348 0.05508 0.026144 1 0 1 1 0 0 +EDGE2 5334 1315 1.0738 0.0161018 -3.15251 1 0 1 1 0 0 +EDGE2 5334 1615 1.06284 -0.024835 -3.14622 1 0 1 1 0 0 +EDGE2 5335 1635 -0.0683872 -0.0204839 -3.113 1 0 1 1 0 0 +EDGE2 5335 1316 0.0692671 -0.966159 -1.56588 1 0 1 1 0 0 +EDGE2 5335 1616 -0.000201982 -1.05134 -1.58147 1 0 1 1 0 0 +EDGE2 5335 1636 -0.112021 -1.01152 -1.54477 1 0 1 1 0 0 +EDGE2 5335 5334 -1.06017 0.053949 -0.0441173 1 0 1 1 0 0 +EDGE2 5335 1314 0.950391 -0.0335586 -3.15485 1 0 1 1 0 0 +EDGE2 5335 1634 1.02023 -0.0318021 -3.13112 1 0 1 1 0 0 +EDGE2 5335 1315 -0.00372276 0.0206586 -3.14892 1 0 1 1 0 0 +EDGE2 5335 1615 -0.000596462 -0.0140074 -3.15424 1 0 1 1 0 0 +EDGE2 5335 1614 0.950453 0.0248798 -3.15463 1 0 1 1 0 0 +EDGE2 5336 1635 -0.989259 -0.000187726 -1.57349 1 0 1 1 0 0 +EDGE2 5336 1617 0.946983 -0.0101413 -0.00966061 1 0 1 1 0 0 +EDGE2 5336 1637 0.985402 -0.0439561 0.00941268 1 0 1 1 0 0 +EDGE2 5336 1317 0.982917 0.0446724 -0.0235493 1 0 1 1 0 0 +EDGE2 5336 1316 0.0615275 0.0317691 0.00765151 1 0 1 1 0 0 +EDGE2 5336 1616 0.0600927 -0.00185432 -0.012832 1 0 1 1 0 0 +EDGE2 5336 1636 0.00632973 -0.0404423 -0.0181195 1 0 1 1 0 0 +EDGE2 5336 5335 -0.978387 0.0463665 1.59415 1 0 1 1 0 0 +EDGE2 5336 1315 -1.00171 -0.0332163 -1.59847 1 0 1 1 0 0 +EDGE2 5336 1615 -1.01173 -0.0658039 -1.57477 1 0 1 1 0 0 +EDGE2 5337 1618 0.948119 0.0319055 0.00851161 1 0 1 1 0 0 +EDGE2 5337 1638 0.983868 0.0329978 -0.0125589 1 0 1 1 0 0 +EDGE2 5337 1318 1.05149 -0.0665652 -0.00932536 1 0 1 1 0 0 +EDGE2 5337 1617 0.0609896 -0.033293 -0.0133172 1 0 1 1 0 0 +EDGE2 5337 1637 0.0787266 -0.0181946 0.0140834 1 0 1 1 0 0 +EDGE2 5337 1317 -0.0174376 0.0184843 0.0156772 1 0 1 1 0 0 +EDGE2 5337 5336 -1.03358 0.0351136 -0.029907 1 0 1 1 0 0 +EDGE2 5337 1316 -1.03974 0.0777453 0.018749 1 0 1 1 0 0 +EDGE2 5337 1616 -0.983087 -0.0129673 0.00748904 1 0 1 1 0 0 +EDGE2 5337 1636 -0.947593 0.0320075 -0.0306655 1 0 1 1 0 0 +EDGE2 5338 1619 0.933327 0.0608781 0.00930178 1 0 1 1 0 0 +EDGE2 5338 1639 1.00217 -0.020605 -0.0125485 1 0 1 1 0 0 +EDGE2 5338 1319 1.02876 -0.0350389 -0.00210598 1 0 1 1 0 0 +EDGE2 5338 1618 0.105714 0.0267335 0.00537998 1 0 1 1 0 0 +EDGE2 5338 1638 -0.045821 -0.043719 0.0110256 1 0 1 1 0 0 +EDGE2 5338 1318 -0.00942368 -0.0242603 0.00566078 1 0 1 1 0 0 +EDGE2 5338 1617 -0.906343 0.0725028 -0.00489901 1 0 1 1 0 0 +EDGE2 5338 1637 -0.944318 -0.0185206 0.00211668 1 0 1 1 0 0 +EDGE2 5338 5337 -0.978624 -0.0594487 0.0337743 1 0 1 1 0 0 +EDGE2 5338 1317 -1.00065 -0.0272361 -0.010576 1 0 1 1 0 0 +EDGE2 5339 2340 0.940999 0.0410667 -3.12058 1 0 1 1 0 0 +EDGE2 5339 2360 0.951599 -0.0199321 -3.1381 1 0 1 1 0 0 +EDGE2 5339 1520 0.926282 0.0776664 -3.11688 1 0 1 1 0 0 +EDGE2 5339 1620 1.00297 0.0562076 -0.019565 1 0 1 1 0 0 +EDGE2 5339 1640 1.01507 -0.01313 -0.0359506 1 0 1 1 0 0 +EDGE2 5339 2320 0.955126 0.053019 -3.1487 1 0 1 1 0 0 +EDGE2 5339 1600 1.00368 0.0258379 -3.09218 1 0 1 1 0 0 +EDGE2 5339 1320 0.98253 0.0292435 0.0190933 1 0 1 1 0 0 +EDGE2 5339 1619 0.077586 0.010446 0.0206588 1 0 1 1 0 0 +EDGE2 5339 1639 -0.0205739 0.112226 -0.00244244 1 0 1 1 0 0 +EDGE2 5339 1319 0.00169921 0.00923866 0.0150853 1 0 1 1 0 0 +EDGE2 5339 1618 -0.878832 0.0736381 0.00863004 1 0 1 1 0 0 +EDGE2 5339 1638 -1.00919 0.0319821 0.00363212 1 0 1 1 0 0 +EDGE2 5339 5338 -1.07384 -0.015466 -0.0198445 1 0 1 1 0 0 +EDGE2 5339 1318 -0.948293 0.000178252 0.00520227 1 0 1 1 0 0 +EDGE2 5340 2359 0.906171 0.0559809 -3.14122 1 0 1 1 0 0 +EDGE2 5340 1599 0.961922 -0.125694 -3.12662 1 0 1 1 0 0 +EDGE2 5340 2319 1.06448 -0.110075 -3.14098 1 0 1 1 0 0 +EDGE2 5340 2339 1.02617 0.0582192 -3.15119 1 0 1 1 0 0 +EDGE2 5340 1519 0.99577 0.0270785 -3.14453 1 0 1 1 0 0 +EDGE2 5340 2340 -0.0367935 0.0541471 -3.1807 1 0 1 1 0 0 +EDGE2 5340 2341 0.0992528 -1.02961 -1.5301 1 0 1 1 0 0 +EDGE2 5340 2361 -0.101226 -0.938184 -1.55388 1 0 1 1 0 0 +EDGE2 5340 1521 0.058816 -1.05358 -1.56927 1 0 1 1 0 0 +EDGE2 5340 1641 -0.0708558 -1.02643 -1.55403 1 0 1 1 0 0 +EDGE2 5340 2321 -0.0103887 -1.04659 -1.58407 1 0 1 1 0 0 +EDGE2 5340 1321 -0.025564 -1.01885 -1.53983 1 0 1 1 0 0 +EDGE2 5340 2360 -0.0190544 -0.0453565 -3.1272 1 0 1 1 0 0 +EDGE2 5340 1520 0.0315701 0.14851 -3.13314 1 0 1 1 0 0 +EDGE2 5340 1620 -0.00180584 -0.0599919 0.00672848 1 0 1 1 0 0 +EDGE2 5340 1640 -0.0986096 -0.00068567 -0.0211537 1 0 1 1 0 0 +EDGE2 5340 2320 0.0567941 -0.161244 -3.15938 1 0 1 1 0 0 +EDGE2 5340 1600 -0.0296552 -0.0125017 -3.12398 1 0 1 1 0 0 +EDGE2 5340 1621 0.00568386 1.0521 1.5749 1 0 1 1 0 0 +EDGE2 5340 1320 0.00251894 0.0239085 0.0240101 1 0 1 1 0 0 +EDGE2 5340 1601 0.0542676 1.11057 1.59741 1 0 1 1 0 0 +EDGE2 5340 1619 -1.06185 0.0795233 -0.0143135 1 0 1 1 0 0 +EDGE2 5340 5339 -1.04481 0.0209291 -0.0076609 1 0 1 1 0 0 +EDGE2 5340 1639 -1.018 -0.110545 -0.00163888 1 0 1 1 0 0 +EDGE2 5340 1319 -1.03088 0.00907229 -0.00136296 1 0 1 1 0 0 +EDGE2 5341 2362 0.987578 -0.0454786 -0.00944701 1 0 1 1 0 0 +EDGE2 5341 2340 -1.03309 -0.066947 -1.60947 1 0 1 1 0 0 +EDGE2 5341 2341 -0.0147936 -0.127116 -0.00921999 1 0 1 1 0 0 +EDGE2 5341 1322 1.13821 -0.0118569 -0.0104805 1 0 1 1 0 0 +EDGE2 5341 1642 1.01406 -0.0875098 -0.0224062 1 0 1 1 0 0 +EDGE2 5341 2322 1.11722 -0.038095 0.0112679 1 0 1 1 0 0 +EDGE2 5341 2342 0.962257 0.0486639 -0.00593142 1 0 1 1 0 0 +EDGE2 5341 1522 0.995135 0.0136479 0.00328339 1 0 1 1 0 0 +EDGE2 5341 2361 -0.0194279 0.024644 -0.0130818 1 0 1 1 0 0 +EDGE2 5341 1521 0.0530905 -0.0240871 -0.0205718 1 0 1 1 0 0 +EDGE2 5341 1641 -0.0110198 -0.0367139 -0.0633876 1 0 1 1 0 0 +EDGE2 5341 2321 -0.0793917 0.027674 -0.0111529 1 0 1 1 0 0 +EDGE2 5341 1321 0.00719555 0.107234 -0.00749037 1 0 1 1 0 0 +EDGE2 5341 5340 -0.888797 -0.0198337 1.56928 1 0 1 1 0 0 +EDGE2 5341 2360 -1.06284 0.032981 -1.60837 1 0 1 1 0 0 +EDGE2 5341 1520 -1.06563 -0.0689958 -1.57428 1 0 1 1 0 0 +EDGE2 5341 1620 -0.97151 -0.0143282 1.59205 1 0 1 1 0 0 +EDGE2 5341 1640 -0.992442 0.0157714 1.57227 1 0 1 1 0 0 +EDGE2 5341 2320 -1.07753 0.0550579 -1.57747 1 0 1 1 0 0 +EDGE2 5341 1600 -1.05886 -0.0548133 -1.55981 1 0 1 1 0 0 +EDGE2 5341 1320 -1.07441 -0.032068 1.60609 1 0 1 1 0 0 +EDGE2 5342 2362 0.0141857 -0.0595715 0.024172 1 0 1 1 0 0 +EDGE2 5342 2363 1.02907 0.00931225 0.0208843 1 0 1 1 0 0 +EDGE2 5342 1323 0.934426 -0.11701 -0.00195852 1 0 1 1 0 0 +EDGE2 5342 1643 1.02708 0.0145013 0.00057096 1 0 1 1 0 0 +EDGE2 5342 2323 0.985806 0.111647 0.0342974 1 0 1 1 0 0 +EDGE2 5342 2343 1.01823 0.0485512 -0.0143758 1 0 1 1 0 0 +EDGE2 5342 1523 1.06251 0.0474959 0.00474575 1 0 1 1 0 0 +EDGE2 5342 2341 -1.07621 -0.0819812 -0.0154776 1 0 1 1 0 0 +EDGE2 5342 1322 0.00642197 0.0278959 0.00426127 1 0 1 1 0 0 +EDGE2 5342 1642 0.0297632 -0.037256 0.020891 1 0 1 1 0 0 +EDGE2 5342 2322 0.00179289 -0.0519775 -0.0167605 1 0 1 1 0 0 +EDGE2 5342 2342 -0.100017 0.00236207 0.00546745 1 0 1 1 0 0 +EDGE2 5342 1522 -0.0769912 -0.0906358 0.00258361 1 0 1 1 0 0 +EDGE2 5342 5341 -1.02333 0.0323287 0.0230573 1 0 1 1 0 0 +EDGE2 5342 2361 -1.08793 0.0952296 0.0148541 1 0 1 1 0 0 +EDGE2 5342 1521 -1.00526 -0.0151958 -0.0313 1 0 1 1 0 0 +EDGE2 5342 1641 -0.932805 0.0573751 -0.0122824 1 0 1 1 0 0 +EDGE2 5342 2321 -0.968089 0.00125336 -0.0177832 1 0 1 1 0 0 +EDGE2 5342 1321 -1.07598 0.00285998 -0.0129843 1 0 1 1 0 0 +EDGE2 5343 2362 -1.01219 0.0246088 -0.0209587 1 0 1 1 0 0 +EDGE2 5343 2363 0.0282555 -0.0460555 0.00860596 1 0 1 1 0 0 +EDGE2 5343 1524 1.05054 0.0553433 0.00149609 1 0 1 1 0 0 +EDGE2 5343 2324 1.0611 0.0177312 -0.00271073 1 0 1 1 0 0 +EDGE2 5343 2344 1.08628 0.00664767 -0.00170968 1 0 1 1 0 0 +EDGE2 5343 2364 1.04885 0.00241636 0.00239626 1 0 1 1 0 0 +EDGE2 5343 1644 0.967876 0.00604973 0.00188438 1 0 1 1 0 0 +EDGE2 5343 1324 0.982848 0.0438551 0.00790804 1 0 1 1 0 0 +EDGE2 5343 1323 0.0579612 -0.0227443 -0.0146953 1 0 1 1 0 0 +EDGE2 5343 1643 -0.0330159 -0.10686 0.0533842 1 0 1 1 0 0 +EDGE2 5343 2323 0.051468 0.073603 0.039928 1 0 1 1 0 0 +EDGE2 5343 2343 -0.0320997 -0.0195002 0.0103468 1 0 1 1 0 0 +EDGE2 5343 1523 0.114663 0.0635683 0.0403164 1 0 1 1 0 0 +EDGE2 5343 5342 -0.992118 0.016811 -0.0223895 1 0 1 1 0 0 +EDGE2 5343 1322 -0.995092 -0.0139263 -0.0214539 1 0 1 1 0 0 +EDGE2 5343 1642 -0.968655 -0.00744247 -0.00251694 1 0 1 1 0 0 +EDGE2 5343 2322 -0.918164 0.0550387 0.00138847 1 0 1 1 0 0 +EDGE2 5343 2342 -0.993131 0.0261473 -0.0136855 1 0 1 1 0 0 +EDGE2 5343 1522 -0.987624 -0.00957612 -0.0568123 1 0 1 1 0 0 +EDGE2 5344 1345 0.992775 0.0466344 -3.13993 1 0 1 1 0 0 +EDGE2 5344 2345 1.05168 0.0153125 -0.0219869 1 0 1 1 0 0 +EDGE2 5344 2365 1.04782 0.0112173 0.0145147 1 0 1 1 0 0 +EDGE2 5344 1525 1.04937 -0.0142192 -0.00789369 1 0 1 1 0 0 +EDGE2 5344 1905 0.978128 0.0262744 -3.17073 1 0 1 1 0 0 +EDGE2 5344 1925 0.950254 0.0392869 -3.17233 1 0 1 1 0 0 +EDGE2 5344 2325 1.00737 0.0180946 -0.00381697 1 0 1 1 0 0 +EDGE2 5344 1645 1.04611 -0.0569278 0.000363449 1 0 1 1 0 0 +EDGE2 5344 1485 1.04202 0.0248001 -3.16886 1 0 1 1 0 0 +EDGE2 5344 1505 1.06715 0.0334549 -3.15249 1 0 1 1 0 0 +EDGE2 5344 1365 0.9791 -0.0281882 -3.14582 1 0 1 1 0 0 +EDGE2 5344 1325 0.916178 -0.0290229 -0.0208715 1 0 1 1 0 0 +EDGE2 5344 2363 -0.95635 0.0268275 0.0254181 1 0 1 1 0 0 +EDGE2 5344 1524 -0.0311519 0.01376 -0.028934 1 0 1 1 0 0 +EDGE2 5344 2324 -0.00251364 -0.0478653 0.0109133 1 0 1 1 0 0 +EDGE2 5344 2344 0.0238424 -0.018 0.00656615 1 0 1 1 0 0 +EDGE2 5344 2364 0.0544403 0.0295259 -0.00873594 1 0 1 1 0 0 +EDGE2 5344 1644 0.107065 -0.0127884 0.00550418 1 0 1 1 0 0 +EDGE2 5344 1324 -0.00378716 0.0141814 0.00433729 1 0 1 1 0 0 +EDGE2 5344 5343 -1.05272 -0.045277 0.0467688 1 0 1 1 0 0 +EDGE2 5344 1323 -1.00719 -0.00155544 -0.0131522 1 0 1 1 0 0 +EDGE2 5344 1643 -0.943303 -0.0424207 0.0181605 1 0 1 1 0 0 +EDGE2 5344 2323 -0.943223 -0.0036703 -0.0146775 1 0 1 1 0 0 +EDGE2 5344 2343 -0.979779 0.0103962 -0.0235449 1 0 1 1 0 0 +EDGE2 5344 1523 -1.07757 -0.026156 0.00794222 1 0 1 1 0 0 +EDGE2 5345 1345 0.0659254 0.0120842 -3.15092 1 0 1 1 0 0 +EDGE2 5345 1526 0.0257915 1.00389 1.57001 1 0 1 1 0 0 +EDGE2 5345 2366 -0.0143894 1.04486 1.57773 1 0 1 1 0 0 +EDGE2 5345 1926 -0.0581065 0.879967 1.56826 1 0 1 1 0 0 +EDGE2 5345 2326 -0.00484454 1.05859 1.55742 1 0 1 1 0 0 +EDGE2 5345 2346 -0.0304352 1.02845 1.55069 1 0 1 1 0 0 +EDGE2 5345 1646 0.0468909 1.05788 1.59519 1 0 1 1 0 0 +EDGE2 5345 1366 0.0175777 1.10195 1.59351 1 0 1 1 0 0 +EDGE2 5345 1506 -0.105649 0.903397 1.55605 1 0 1 1 0 0 +EDGE2 5345 1924 0.969107 0.0839727 -3.13026 1 0 1 1 0 0 +EDGE2 5345 2345 -0.00925094 -0.0143569 0.0143765 1 0 1 1 0 0 +EDGE2 5345 1344 0.943641 0.0582663 -3.13909 1 0 1 1 0 0 +EDGE2 5345 1484 0.969571 -0.0332095 -3.15096 1 0 1 1 0 0 +EDGE2 5345 1504 0.976832 0.0596299 -3.10606 1 0 1 1 0 0 +EDGE2 5345 1904 0.961275 0.0443593 -3.16121 1 0 1 1 0 0 +EDGE2 5345 1364 1.00754 0.0451479 -3.14721 1 0 1 1 0 0 +EDGE2 5345 2365 -0.00337845 0.0521401 0.00609223 1 0 1 1 0 0 +EDGE2 5345 1525 0.0672548 -0.0788658 0.00166969 1 0 1 1 0 0 +EDGE2 5345 1905 -0.0195564 -0.0879045 -3.16578 1 0 1 1 0 0 +EDGE2 5345 1925 0.0712672 0.0310532 -3.10829 1 0 1 1 0 0 +EDGE2 5345 2325 0.00146801 -0.00158023 -0.0198053 1 0 1 1 0 0 +EDGE2 5345 1645 -0.0399603 -0.00661796 -0.00423871 1 0 1 1 0 0 +EDGE2 5345 1485 0.0875396 -0.0288665 -3.15041 1 0 1 1 0 0 +EDGE2 5345 1505 -0.00828201 0.0507524 -3.11752 1 0 1 1 0 0 +EDGE2 5345 1365 0.000512196 0.00564371 -3.13596 1 0 1 1 0 0 +EDGE2 5345 5344 -1.03 0.0187134 0.00316106 1 0 1 1 0 0 +EDGE2 5345 1325 0.0341571 0.0614088 0.00853963 1 0 1 1 0 0 +EDGE2 5345 1524 -0.971036 0.0178963 0.00192315 1 0 1 1 0 0 +EDGE2 5345 2324 -0.974273 -0.0578793 0.00762314 1 0 1 1 0 0 +EDGE2 5345 2344 -1.01196 -0.0491421 -0.0325954 1 0 1 1 0 0 +EDGE2 5345 2364 -1.00699 0.046277 -0.0116981 1 0 1 1 0 0 +EDGE2 5345 1644 -1.09359 -0.0838635 -0.00952295 1 0 1 1 0 0 +EDGE2 5345 1324 -1.07335 0.000360487 -0.0199289 1 0 1 1 0 0 +EDGE2 5345 1486 0.0231005 -1.02272 -1.58043 1 0 1 1 0 0 +EDGE2 5345 1906 -0.0512856 -1.01439 -1.58772 1 0 1 1 0 0 +EDGE2 5345 1326 -0.021957 -1.07573 -1.5677 1 0 1 1 0 0 +EDGE2 5345 1346 0.0242794 -1.01129 -1.56691 1 0 1 1 0 0 +EDGE2 5346 2327 0.987077 0.00465089 -0.00545204 1 0 1 1 0 0 +EDGE2 5346 2367 1.06014 0.0506328 -0.000794322 1 0 1 1 0 0 +EDGE2 5346 2347 1.07315 0.0307064 0.00662462 1 0 1 1 0 0 +EDGE2 5346 1345 -0.970738 -0.0249508 1.56776 1 0 1 1 0 0 +EDGE2 5346 1526 0.000614996 -0.0632528 -0.0251656 1 0 1 1 0 0 +EDGE2 5346 1507 0.935955 0.0214172 0.000418744 1 0 1 1 0 0 +EDGE2 5346 1527 1.00203 -0.00871269 -0.018263 1 0 1 1 0 0 +EDGE2 5346 1647 1.04235 0.0217112 -0.0131313 1 0 1 1 0 0 +EDGE2 5346 1927 1.05839 -0.0826604 -0.031189 1 0 1 1 0 0 +EDGE2 5346 2366 0.0438427 0.0077328 0.0431101 1 0 1 1 0 0 +EDGE2 5346 1367 0.992019 -0.0134008 6.77159e-06 1 0 1 1 0 0 +EDGE2 5346 1926 -0.0760783 -0.0748817 0.011869 1 0 1 1 0 0 +EDGE2 5346 2326 -0.0486688 0.0201264 -0.0193632 1 0 1 1 0 0 +EDGE2 5346 2346 -0.0843576 -0.0233479 0.00871814 1 0 1 1 0 0 +EDGE2 5346 1646 -0.0181519 -0.0130233 0.0148276 1 0 1 1 0 0 +EDGE2 5346 1366 0.102737 0.0171588 -0.0133913 1 0 1 1 0 0 +EDGE2 5346 1506 0.00722424 -0.045495 -0.00870768 1 0 1 1 0 0 +EDGE2 5346 2345 -0.958456 -0.144308 -1.59877 1 0 1 1 0 0 +EDGE2 5346 5345 -1.02433 -0.023926 -1.59403 1 0 1 1 0 0 +EDGE2 5346 2365 -0.964917 0.00151301 -1.58314 1 0 1 1 0 0 +EDGE2 5346 1525 -0.928877 0.0050548 -1.59629 1 0 1 1 0 0 +EDGE2 5346 1905 -0.969261 -0.0196975 1.58184 1 0 1 1 0 0 +EDGE2 5346 1925 -0.949453 -0.0121058 1.54636 1 0 1 1 0 0 +EDGE2 5346 2325 -0.970983 0.0269719 -1.57622 1 0 1 1 0 0 +EDGE2 5346 1645 -0.980867 -0.0173868 -1.59079 1 0 1 1 0 0 +EDGE2 5346 1485 -1.0045 -0.020191 1.56885 1 0 1 1 0 0 +EDGE2 5346 1505 -1.04158 -0.0108953 1.60923 1 0 1 1 0 0 +EDGE2 5346 1365 -1.02571 0.0527722 1.58675 1 0 1 1 0 0 +EDGE2 5346 1325 -1.01383 -0.0239853 -1.59104 1 0 1 1 0 0 +EDGE2 5347 2327 -0.0589005 -0.0060329 0.00446219 1 0 1 1 0 0 +EDGE2 5347 2368 0.898581 -0.0263299 0.0299366 1 0 1 1 0 0 +EDGE2 5347 1648 0.985381 -0.0551437 0.0149067 1 0 1 1 0 0 +EDGE2 5347 1928 1.02838 -0.0482214 0.0154405 1 0 1 1 0 0 +EDGE2 5347 2328 1.05588 0.0136169 0.0128831 1 0 1 1 0 0 +EDGE2 5347 2348 1.02793 0.0131865 -0.0274809 1 0 1 1 0 0 +EDGE2 5347 1368 1.01168 -0.0964873 -0.0124205 1 0 1 1 0 0 +EDGE2 5347 1508 1.00019 0.0249347 -0.0285404 1 0 1 1 0 0 +EDGE2 5347 1528 0.966691 0.0517012 -0.0156032 1 0 1 1 0 0 +EDGE2 5347 2367 -0.144527 0.0237413 0.0179675 1 0 1 1 0 0 +EDGE2 5347 2347 0.0693492 -0.00399877 -0.0101175 1 0 1 1 0 0 +EDGE2 5347 1526 -0.964186 0.0148674 0.00532172 1 0 1 1 0 0 +EDGE2 5347 1507 0.022503 0.103787 -0.00501662 1 0 1 1 0 0 +EDGE2 5347 1527 0.0313463 0.0996614 -0.0118606 1 0 1 1 0 0 +EDGE2 5347 1647 -0.0340741 -0.0624505 0.027128 1 0 1 1 0 0 +EDGE2 5347 1927 0.0520577 -0.0208171 -0.0113058 1 0 1 1 0 0 +EDGE2 5347 2366 -0.984222 0.000290289 0.00429459 1 0 1 1 0 0 +EDGE2 5347 1367 -0.0419615 0.0160533 0.000645457 1 0 1 1 0 0 +EDGE2 5347 5346 -1.13909 -0.00477725 -0.0184405 1 0 1 1 0 0 +EDGE2 5347 1926 -1.01435 0.0341116 0.0150361 1 0 1 1 0 0 +EDGE2 5347 2326 -0.990339 0.0561674 0.0141984 1 0 1 1 0 0 +EDGE2 5347 2346 -0.978737 0.0275732 0.00255321 1 0 1 1 0 0 +EDGE2 5347 1646 -0.964855 0.0489241 0.0155506 1 0 1 1 0 0 +EDGE2 5347 1366 -1.00044 0.0276115 0.0578307 1 0 1 1 0 0 +EDGE2 5347 1506 -0.970353 0.00682943 -0.0104188 1 0 1 1 0 0 +EDGE2 5348 2327 -0.94195 -0.0195321 -0.0127928 1 0 1 1 0 0 +EDGE2 5348 2368 0.00175568 -0.0651025 0.0314987 1 0 1 1 0 0 +EDGE2 5348 2349 0.916894 0.055578 0.0180127 1 0 1 1 0 0 +EDGE2 5348 2369 1.07121 0.0447968 -0.016142 1 0 1 1 0 0 +EDGE2 5348 1509 1.00998 0.0457366 -0.0115475 1 0 1 1 0 0 +EDGE2 5348 1649 0.979312 0.0123879 -0.0320334 1 0 1 1 0 0 +EDGE2 5348 1929 0.97295 -0.0495176 0.031339 1 0 1 1 0 0 +EDGE2 5348 2329 1.08323 0.0952059 0.00994186 1 0 1 1 0 0 +EDGE2 5348 1529 0.918036 -0.0557158 -0.00556883 1 0 1 1 0 0 +EDGE2 5348 1369 1.01589 -0.0691155 -0.0184028 1 0 1 1 0 0 +EDGE2 5348 1648 0.103496 -0.0430921 -0.0230196 1 0 1 1 0 0 +EDGE2 5348 1928 -0.0356873 0.0990627 0.0114833 1 0 1 1 0 0 +EDGE2 5348 2328 0.0183956 -0.102934 0.0427845 1 0 1 1 0 0 +EDGE2 5348 2348 0.0452516 0.0791065 -0.0238078 1 0 1 1 0 0 +EDGE2 5348 1368 -0.0258179 -0.0809366 -0.0218998 1 0 1 1 0 0 +EDGE2 5348 1508 0.0329318 0.0256216 -0.00953219 1 0 1 1 0 0 +EDGE2 5348 1528 -0.0406315 -0.0163898 -0.0241639 1 0 1 1 0 0 +EDGE2 5348 2367 -0.982487 0.0685867 -0.019891 1 0 1 1 0 0 +EDGE2 5348 5347 -0.984307 -0.0657208 -0.0402059 1 0 1 1 0 0 +EDGE2 5348 2347 -1.06285 0.0836287 0.0143817 1 0 1 1 0 0 +EDGE2 5348 1507 -0.959703 0.0252651 -0.0255055 1 0 1 1 0 0 +EDGE2 5348 1527 -1.0262 0.0679893 0.00680473 1 0 1 1 0 0 +EDGE2 5348 1647 -0.92331 -0.0313487 -0.000170505 1 0 1 1 0 0 +EDGE2 5348 1927 -0.93567 0.0136182 0.0123708 1 0 1 1 0 0 +EDGE2 5348 1367 -0.949313 -0.0567674 0.00687783 1 0 1 1 0 0 +EDGE2 5349 2330 1.00235 0.0468489 0.0317208 1 0 1 1 0 0 +EDGE2 5349 2370 0.997547 -0.00823313 -0.0142323 1 0 1 1 0 0 +EDGE2 5349 2350 0.911949 0.0284603 0.0546999 1 0 1 1 0 0 +EDGE2 5349 1650 0.941163 -0.10468 -0.0163541 1 0 1 1 0 0 +EDGE2 5349 1710 1.03527 0.0799346 -3.1441 1 0 1 1 0 0 +EDGE2 5349 1870 1.06573 0.0759414 -3.12961 1 0 1 1 0 0 +EDGE2 5349 1930 0.977529 0.030332 -0.0259069 1 0 1 1 0 0 +EDGE2 5349 1670 0.936185 0.00339426 -3.14665 1 0 1 1 0 0 +EDGE2 5349 1470 1.01011 0.0338053 -3.1469 1 0 1 1 0 0 +EDGE2 5349 1510 0.989509 -0.0241593 0.00339591 1 0 1 1 0 0 +EDGE2 5349 1530 0.968505 -0.0714552 0.0119822 1 0 1 1 0 0 +EDGE2 5349 1370 0.978914 0.0621572 0.00111779 1 0 1 1 0 0 +EDGE2 5349 2368 -1.00284 -0.0227893 -0.0299201 1 0 1 1 0 0 +EDGE2 5349 2349 -0.0996155 -0.094676 0.00934858 1 0 1 1 0 0 +EDGE2 5349 2369 -0.107579 -0.00888295 -0.00196084 1 0 1 1 0 0 +EDGE2 5349 1509 0.0966261 -0.000766594 -0.0156209 1 0 1 1 0 0 +EDGE2 5349 1649 -0.0184443 -0.0840826 0.0252559 1 0 1 1 0 0 +EDGE2 5349 1929 0.0750346 0.0263489 -0.0182969 1 0 1 1 0 0 +EDGE2 5349 2329 0.0911528 -0.0701304 -0.00531533 1 0 1 1 0 0 +EDGE2 5349 1529 -0.154832 0.0378447 -0.00141765 1 0 1 1 0 0 +EDGE2 5349 1369 -0.0105236 0.0463538 0.0465133 1 0 1 1 0 0 +EDGE2 5349 5348 -0.954779 0.0689471 0.0176764 1 0 1 1 0 0 +EDGE2 5349 1648 -1.05288 0.0540488 0.0156586 1 0 1 1 0 0 +EDGE2 5349 1928 -0.952782 -0.0561596 -0.0267917 1 0 1 1 0 0 +EDGE2 5349 2328 -0.958347 0.0371245 0.0310815 1 0 1 1 0 0 +EDGE2 5349 2348 -1.01661 0.0483153 0.00556328 1 0 1 1 0 0 +EDGE2 5349 1368 -0.973304 -0.0260871 -0.0086127 1 0 1 1 0 0 +EDGE2 5349 1508 -0.998036 0.00860459 0.00867477 1 0 1 1 0 0 +EDGE2 5349 1528 -1.06752 0.0355804 -0.0275924 1 0 1 1 0 0 +EDGE2 5350 1931 0.110211 -1.02325 -1.58048 1 0 1 1 0 0 +EDGE2 5350 1669 0.996248 -0.00408482 -3.15911 1 0 1 1 0 0 +EDGE2 5350 1709 1.01441 0.0576939 -3.14178 1 0 1 1 0 0 +EDGE2 5350 1869 0.975139 0.00818902 -3.15012 1 0 1 1 0 0 +EDGE2 5350 1469 0.99696 0.0291796 -3.13466 1 0 1 1 0 0 +EDGE2 5350 2330 -0.0382966 0.0397972 -0.00653408 1 0 1 1 0 0 +EDGE2 5350 1671 0.00905654 -0.931518 -1.53569 1 0 1 1 0 0 +EDGE2 5350 1711 0.0481766 -1.04563 -1.5526 1 0 1 1 0 0 +EDGE2 5350 1871 0.0535415 -1.022 -1.58411 1 0 1 1 0 0 +EDGE2 5350 1471 -0.0223018 -1.03335 -1.56868 1 0 1 1 0 0 +EDGE2 5350 2370 -0.0653109 -0.0509523 -0.00972812 1 0 1 1 0 0 +EDGE2 5350 2350 0.02461 -0.00972012 -0.00591721 1 0 1 1 0 0 +EDGE2 5350 1650 0.0708891 0.0182202 0.0225285 1 0 1 1 0 0 +EDGE2 5350 1710 -0.0404502 0.0428808 -3.14967 1 0 1 1 0 0 +EDGE2 5350 1870 0.0621851 -0.0467958 -3.13904 1 0 1 1 0 0 +EDGE2 5350 1930 -0.053641 0.0389956 -0.0217983 1 0 1 1 0 0 +EDGE2 5350 1670 -0.00148002 -0.0011243 -3.13288 1 0 1 1 0 0 +EDGE2 5350 1470 0.0337007 0.00614174 -3.12509 1 0 1 1 0 0 +EDGE2 5350 1510 0.0900519 0.0211181 0.0212168 1 0 1 1 0 0 +EDGE2 5350 1530 0.0418683 -0.0395306 0.00699628 1 0 1 1 0 0 +EDGE2 5350 1370 0.025802 -0.043348 -0.00248577 1 0 1 1 0 0 +EDGE2 5350 2351 0.0682952 0.957271 1.5507 1 0 1 1 0 0 +EDGE2 5350 2371 0.09389 1.04767 1.55815 1 0 1 1 0 0 +EDGE2 5350 1371 -0.0474753 0.972415 1.57516 1 0 1 1 0 0 +EDGE2 5350 1531 0.0265389 0.947811 1.57587 1 0 1 1 0 0 +EDGE2 5350 1651 0.000270106 0.981969 1.57135 1 0 1 1 0 0 +EDGE2 5350 2331 0.0282734 1.04811 1.56861 1 0 1 1 0 0 +EDGE2 5350 1511 -0.0229299 1.01134 1.5956 1 0 1 1 0 0 +EDGE2 5350 2349 -0.990968 -0.148091 0.0186932 1 0 1 1 0 0 +EDGE2 5350 2369 -0.987096 -0.0396321 -0.00546755 1 0 1 1 0 0 +EDGE2 5350 5349 -1.01779 0.0445724 -0.00952513 1 0 1 1 0 0 +EDGE2 5350 1509 -0.992622 -0.0500906 -0.0525805 1 0 1 1 0 0 +EDGE2 5350 1649 -0.972548 0.00915746 -0.0109037 1 0 1 1 0 0 +EDGE2 5350 1929 -1.05674 0.00339556 0.0187556 1 0 1 1 0 0 +EDGE2 5350 2329 -0.94505 0.0381185 -0.0379382 1 0 1 1 0 0 +EDGE2 5350 1529 -0.968088 0.0731945 0.00439755 1 0 1 1 0 0 +EDGE2 5350 1369 -1.05128 0.0893922 -0.0220414 1 0 1 1 0 0 +EDGE2 5351 2372 0.974102 -0.0661336 -0.000476789 1 0 1 1 0 0 +EDGE2 5351 2330 -0.939289 0.025605 -1.56117 1 0 1 1 0 0 +EDGE2 5351 2370 -0.99587 -0.0147366 -1.56923 1 0 1 1 0 0 +EDGE2 5351 5350 -1.03488 0.0531017 -1.55508 1 0 1 1 0 0 +EDGE2 5351 2350 -0.960552 0.0588335 -1.5629 1 0 1 1 0 0 +EDGE2 5351 1650 -1.02934 -0.0207306 -1.59539 1 0 1 1 0 0 +EDGE2 5351 1710 -0.95434 -0.0137849 1.55903 1 0 1 1 0 0 +EDGE2 5351 1870 -1.06263 -0.0627725 1.5304 1 0 1 1 0 0 +EDGE2 5351 1930 -0.960119 0.107458 -1.59727 1 0 1 1 0 0 +EDGE2 5351 1670 -1.0509 -0.0877845 1.5492 1 0 1 1 0 0 +EDGE2 5351 1470 -0.987818 0.076763 1.54921 1 0 1 1 0 0 +EDGE2 5351 1510 -1.05552 -0.068145 -1.59472 1 0 1 1 0 0 +EDGE2 5351 1530 -0.999695 -0.0054447 -1.59187 1 0 1 1 0 0 +EDGE2 5351 1370 -1.17716 0.0880138 -1.55377 1 0 1 1 0 0 +EDGE2 5351 2351 0.0278346 0.00619592 -0.0278055 1 0 1 1 0 0 +EDGE2 5351 2371 -0.00782589 0.0123126 0.0469691 1 0 1 1 0 0 +EDGE2 5351 1371 -0.021764 -0.0353909 0.0225203 1 0 1 1 0 0 +EDGE2 5351 1531 -0.0514387 0.0155183 -0.00860236 1 0 1 1 0 0 +EDGE2 5351 1651 -0.0307471 0.0243294 0.0064331 1 0 1 1 0 0 +EDGE2 5351 2331 -0.0125329 -0.0153194 -4.58704e-05 1 0 1 1 0 0 +EDGE2 5351 1511 -0.045369 -0.121391 0.0112805 1 0 1 1 0 0 +EDGE2 5351 1512 0.973415 0.0112799 0.00160344 1 0 1 1 0 0 +EDGE2 5351 1652 0.920492 -0.0979175 0.00519285 1 0 1 1 0 0 +EDGE2 5351 2332 0.936873 -0.0348767 0.0185517 1 0 1 1 0 0 +EDGE2 5351 2352 0.961655 -0.0244745 0.0109293 1 0 1 1 0 0 +EDGE2 5351 1532 1.0349 0.0205209 -0.0202811 1 0 1 1 0 0 +EDGE2 5351 1372 1.05859 0.0133011 -0.0303994 1 0 1 1 0 0 +EDGE2 5352 2372 -0.120932 0.0238792 -0.0209156 1 0 1 1 0 0 +EDGE2 5352 2351 -0.955029 0.0535439 -0.0158494 1 0 1 1 0 0 +EDGE2 5352 2371 -1.01574 -0.0327537 -0.000747847 1 0 1 1 0 0 +EDGE2 5352 5351 -1.04258 -0.0432558 0.00687427 1 0 1 1 0 0 +EDGE2 5352 1371 -1.11328 0.039293 0.000127408 1 0 1 1 0 0 +EDGE2 5352 1531 -0.988907 -0.0846602 0.00663802 1 0 1 1 0 0 +EDGE2 5352 1651 -1.04345 -0.00290525 0.00743133 1 0 1 1 0 0 +EDGE2 5352 2331 -1.05804 -0.00702908 -0.0034241 1 0 1 1 0 0 +EDGE2 5352 1511 -1.10233 -0.0885148 0.0162983 1 0 1 1 0 0 +EDGE2 5352 2373 0.977505 0.0353258 0.00507584 1 0 1 1 0 0 +EDGE2 5352 1512 0.00139957 0.00151798 -0.0185601 1 0 1 1 0 0 +EDGE2 5352 1652 -0.0404426 -0.0180528 -0.0495193 1 0 1 1 0 0 +EDGE2 5352 2332 0.0783183 0.0168461 0.00995308 1 0 1 1 0 0 +EDGE2 5352 2352 0.0125401 0.0502114 0.0323846 1 0 1 1 0 0 +EDGE2 5352 1532 -0.0970049 0.0168654 0.0314072 1 0 1 1 0 0 +EDGE2 5352 1372 -0.0485452 0.0748625 0.026785 1 0 1 1 0 0 +EDGE2 5352 1513 1.01939 0.0249045 0.00549044 1 0 1 1 0 0 +EDGE2 5352 1653 1.07797 -0.0817533 0.0321697 1 0 1 1 0 0 +EDGE2 5352 2333 0.987084 -0.0160353 -0.00141041 1 0 1 1 0 0 +EDGE2 5352 2353 1.02172 -0.0393905 0.00147101 1 0 1 1 0 0 +EDGE2 5352 1533 1.02412 0.00501011 0.0092972 1 0 1 1 0 0 +EDGE2 5352 1373 0.992842 -0.0728669 -4.70243e-06 1 0 1 1 0 0 +EDGE2 5353 2372 -1.02885 0.0162075 -0.0263756 1 0 1 1 0 0 +EDGE2 5353 5352 -0.972124 -0.0405667 0.0346461 1 0 1 1 0 0 +EDGE2 5353 2374 1.01977 -0.0271912 -0.000661555 1 0 1 1 0 0 +EDGE2 5353 2373 -0.0379101 0.0328109 0.0219376 1 0 1 1 0 0 +EDGE2 5353 1512 -0.945967 -0.000257802 0.0349715 1 0 1 1 0 0 +EDGE2 5353 1652 -0.96385 0.0165507 -0.02448 1 0 1 1 0 0 +EDGE2 5353 2332 -0.967165 0.0409665 -0.00443627 1 0 1 1 0 0 +EDGE2 5353 2352 -0.989287 0.0511511 -0.0250658 1 0 1 1 0 0 +EDGE2 5353 1532 -1.04395 -0.0949483 -0.0197675 1 0 1 1 0 0 +EDGE2 5353 1372 -1.00947 -0.0406001 0.00992423 1 0 1 1 0 0 +EDGE2 5353 1513 0.0408896 0.00833679 0.0192494 1 0 1 1 0 0 +EDGE2 5353 1653 -0.0707065 -0.0281348 0.0272826 1 0 1 1 0 0 +EDGE2 5353 2333 -0.0662582 0.0385056 0.0312398 1 0 1 1 0 0 +EDGE2 5353 2353 0.0570854 0.0500607 -0.0273184 1 0 1 1 0 0 +EDGE2 5353 1533 -0.114406 0.078915 -0.000963321 1 0 1 1 0 0 +EDGE2 5353 1373 0.048986 -0.0375739 0.00224274 1 0 1 1 0 0 +EDGE2 5353 1514 1.00129 0.0396968 -0.00559849 1 0 1 1 0 0 +EDGE2 5353 1654 1.05507 -0.0677556 -0.0235629 1 0 1 1 0 0 +EDGE2 5353 2334 1.0188 0.0173968 0.0169789 1 0 1 1 0 0 +EDGE2 5353 2354 1.00656 0.0416939 -0.00863308 1 0 1 1 0 0 +EDGE2 5353 1534 1.07987 0.0540818 0.00273746 1 0 1 1 0 0 +EDGE2 5353 1374 1.06285 -0.0744163 -0.00981951 1 0 1 1 0 0 +EDGE2 5354 1535 0.918389 -0.0759057 -0.0292664 1 0 1 1 0 0 +EDGE2 5354 2374 0.0431181 0.0341079 -0.000200752 1 0 1 1 0 0 +EDGE2 5354 2373 -1.02279 0.0525321 0.00124139 1 0 1 1 0 0 +EDGE2 5354 5353 -0.995414 0.00450167 0.00769686 1 0 1 1 0 0 +EDGE2 5354 1513 -0.985803 0.0203292 -0.0476788 1 0 1 1 0 0 +EDGE2 5354 1653 -0.955421 0.0251766 0.0108204 1 0 1 1 0 0 +EDGE2 5354 2333 -0.959633 0.0260546 0.00494283 1 0 1 1 0 0 +EDGE2 5354 2353 -0.930174 0.00680826 0.00770987 1 0 1 1 0 0 +EDGE2 5354 1533 -0.958179 -0.0329847 0.0220716 1 0 1 1 0 0 +EDGE2 5354 1373 -1.00376 -0.102432 0.0299781 1 0 1 1 0 0 +EDGE2 5354 2395 0.894818 -0.0410427 -3.13725 1 0 1 1 0 0 +EDGE2 5354 1514 -0.0360325 -0.000913662 -0.0329528 1 0 1 1 0 0 +EDGE2 5354 1654 -0.0103623 -0.0169128 0.0300772 1 0 1 1 0 0 +EDGE2 5354 2334 0.00517586 0.000136372 0.0185663 1 0 1 1 0 0 +EDGE2 5354 2354 0.0911904 -0.0739626 -0.0194969 1 0 1 1 0 0 +EDGE2 5354 1534 -0.00210505 -0.0088341 -0.00792979 1 0 1 1 0 0 +EDGE2 5354 1374 -0.0010494 -0.174237 -0.00798963 1 0 1 1 0 0 +EDGE2 5354 1855 1.05202 0.0123029 -3.15626 1 0 1 1 0 0 +EDGE2 5354 2335 0.986881 0.0432742 -0.0145438 1 0 1 1 0 0 +EDGE2 5354 2355 0.974295 -0.0422267 0.0162 1 0 1 1 0 0 +EDGE2 5354 2375 1.04637 0.0399377 0.00219712 1 0 1 1 0 0 +EDGE2 5354 2315 1.0045 0.0243019 -3.12109 1 0 1 1 0 0 +EDGE2 5354 1595 0.957105 -0.00525827 -3.12802 1 0 1 1 0 0 +EDGE2 5354 1655 0.979491 -0.0154212 0.00418943 1 0 1 1 0 0 +EDGE2 5354 1575 1.00307 0.0179293 -3.17137 1 0 1 1 0 0 +EDGE2 5354 1375 1.11248 0.0375961 -0.0199749 1 0 1 1 0 0 +EDGE2 5354 1515 1.00827 0.0712753 0.00689455 1 0 1 1 0 0 +EDGE2 5355 1656 -0.0780599 -0.920583 -1.57341 1 0 1 1 0 0 +EDGE2 5355 2376 -0.0455715 -0.977125 -1.55466 1 0 1 1 0 0 +EDGE2 5355 2396 -0.0170312 -1.00229 -1.60438 1 0 1 1 0 0 +EDGE2 5355 1856 -0.00110725 -1.02207 -1.54662 1 0 1 1 0 0 +EDGE2 5355 1536 -0.0947111 -1.07631 -1.55773 1 0 1 1 0 0 +EDGE2 5355 1576 0.0522992 -0.944018 -1.54976 1 0 1 1 0 0 +EDGE2 5355 1376 -0.0646752 -1.0036 -1.54197 1 0 1 1 0 0 +EDGE2 5355 1535 -0.00766951 0.0123315 0.0231611 1 0 1 1 0 0 +EDGE2 5355 2374 -1.00106 0.0508568 -0.00279517 1 0 1 1 0 0 +EDGE2 5355 5354 -0.964496 -0.0166844 -0.020585 1 0 1 1 0 0 +EDGE2 5355 2395 0.0513036 0.0104373 -3.15485 1 0 1 1 0 0 +EDGE2 5355 1514 -0.998162 0.0151085 -0.00386396 1 0 1 1 0 0 +EDGE2 5355 1654 -1.07676 0.00618939 0.00753941 1 0 1 1 0 0 +EDGE2 5355 2334 -0.954413 -0.00780842 -0.050949 1 0 1 1 0 0 +EDGE2 5355 2354 -0.983181 -0.0647605 0.0354443 1 0 1 1 0 0 +EDGE2 5355 1534 -1.04705 0.0616489 -0.00902844 1 0 1 1 0 0 +EDGE2 5355 1374 -1.00466 -0.00600534 0.00573251 1 0 1 1 0 0 +EDGE2 5355 1855 0.0127777 -0.0539207 -3.12184 1 0 1 1 0 0 +EDGE2 5355 2335 -0.0714463 -0.0890545 0.0210137 1 0 1 1 0 0 +EDGE2 5355 2355 0.042842 -0.0225298 -0.00257532 1 0 1 1 0 0 +EDGE2 5355 2375 0.000424178 -0.0407218 0.0117176 1 0 1 1 0 0 +EDGE2 5355 2315 -0.0328092 0.0420669 -3.11782 1 0 1 1 0 0 +EDGE2 5355 1595 0.106849 -0.0061505 -3.17397 1 0 1 1 0 0 +EDGE2 5355 1655 0.0720765 0.0570952 -0.0130288 1 0 1 1 0 0 +EDGE2 5355 1575 -0.0620717 -0.0443308 -3.1514 1 0 1 1 0 0 +EDGE2 5355 1854 0.864561 0.00835608 -3.17035 1 0 1 1 0 0 +EDGE2 5355 2394 1.03726 -0.16053 -3.12876 1 0 1 1 0 0 +EDGE2 5355 1375 0.0645822 0.0373905 0.0162009 1 0 1 1 0 0 +EDGE2 5355 1515 -0.088037 -0.00410766 -0.00704366 1 0 1 1 0 0 +EDGE2 5355 2314 0.966998 -0.0699416 -3.15136 1 0 1 1 0 0 +EDGE2 5355 1574 0.975906 0.0188948 -3.14738 1 0 1 1 0 0 +EDGE2 5355 1594 0.998947 0.0772288 -3.10482 1 0 1 1 0 0 +EDGE2 5355 2336 -0.0841847 0.952172 1.55461 1 0 1 1 0 0 +EDGE2 5355 2356 0.0613529 0.973971 1.58905 1 0 1 1 0 0 +EDGE2 5355 1516 0.0390864 1.03937 1.58671 1 0 1 1 0 0 +EDGE2 5355 1596 -0.0264495 0.97601 1.56191 1 0 1 1 0 0 +EDGE2 5355 2316 -0.0411541 0.933204 1.59827 1 0 1 1 0 0 +EDGE2 5356 1535 -1.01027 0.0615977 -1.58368 1 0 1 1 0 0 +EDGE2 5356 2395 -0.942611 -0.0565928 1.57232 1 0 1 1 0 0 +EDGE2 5356 5355 -0.973829 -0.0741906 -1.56833 1 0 1 1 0 0 +EDGE2 5356 1855 -1.01268 -0.0655028 1.57293 1 0 1 1 0 0 +EDGE2 5356 2335 -1.0445 0.0754607 -1.58605 1 0 1 1 0 0 +EDGE2 5356 2355 -0.981951 0.0411769 -1.59028 1 0 1 1 0 0 +EDGE2 5356 2375 -0.91897 0.0196725 -1.54608 1 0 1 1 0 0 +EDGE2 5356 2315 -1.03405 0.0514426 1.57105 1 0 1 1 0 0 +EDGE2 5356 1595 -0.884793 -0.0453324 1.5747 1 0 1 1 0 0 +EDGE2 5356 1655 -1.09667 0.0282104 -1.58606 1 0 1 1 0 0 +EDGE2 5356 1575 -0.939522 -0.0865114 1.57759 1 0 1 1 0 0 +EDGE2 5356 1375 -1.08401 -0.0234687 -1.55618 1 0 1 1 0 0 +EDGE2 5356 1515 -1.06364 -0.0252306 -1.57109 1 0 1 1 0 0 +EDGE2 5356 2336 -0.0145274 0.0409928 0.036769 1 0 1 1 0 0 +EDGE2 5356 2356 -0.0644547 0.0202218 -0.0350086 1 0 1 1 0 0 +EDGE2 5356 1516 0.0387661 -0.0428475 0.00678625 1 0 1 1 0 0 +EDGE2 5356 1596 -0.0318968 -0.046929 -0.0174647 1 0 1 1 0 0 +EDGE2 5356 2316 0.0677259 0.0160208 0.000834984 1 0 1 1 0 0 +EDGE2 5356 2337 0.984736 0.0590884 0.0198525 1 0 1 1 0 0 +EDGE2 5356 2357 1.03041 0.00877123 -0.00609663 1 0 1 1 0 0 +EDGE2 5356 1597 0.990739 0.017383 -0.00653955 1 0 1 1 0 0 +EDGE2 5356 2317 1.03472 -0.0538826 -0.0120333 1 0 1 1 0 0 +EDGE2 5356 1517 1.08296 0.0387987 0.00654708 1 0 1 1 0 0 +EDGE2 5357 2336 -0.967809 0.0312888 0.0455579 1 0 1 1 0 0 +EDGE2 5357 5356 -1.04189 0.0253737 -0.0296658 1 0 1 1 0 0 +EDGE2 5357 2356 -0.978982 0.0274554 -0.00872817 1 0 1 1 0 0 +EDGE2 5357 1516 -0.964896 0.00587053 0.00285722 1 0 1 1 0 0 +EDGE2 5357 1596 -0.991998 0.0944316 -0.0158881 1 0 1 1 0 0 +EDGE2 5357 2316 -0.916727 -0.0490594 -0.00328471 1 0 1 1 0 0 +EDGE2 5357 2337 0.00532715 -0.0356397 0.00184589 1 0 1 1 0 0 +EDGE2 5357 2357 0.0310556 0.00289613 0.00119193 1 0 1 1 0 0 +EDGE2 5357 1597 -0.00726499 -0.0461532 0.0278825 1 0 1 1 0 0 +EDGE2 5357 2317 0.038386 0.0831556 0.00825181 1 0 1 1 0 0 +EDGE2 5357 1517 -0.0239218 -0.0631319 0.0495384 1 0 1 1 0 0 +EDGE2 5357 1598 0.981206 -0.0189957 0.0059274 1 0 1 1 0 0 +EDGE2 5357 2338 0.914263 0.0637399 0.0328771 1 0 1 1 0 0 +EDGE2 5357 2358 1.05153 0.0348098 -0.000546989 1 0 1 1 0 0 +EDGE2 5357 2318 0.972139 0.0098768 -0.00454876 1 0 1 1 0 0 +EDGE2 5357 1518 1.03881 -0.00924815 -0.0292266 1 0 1 1 0 0 +EDGE2 5358 2337 -0.992101 0.0595243 0.0153008 1 0 1 1 0 0 +EDGE2 5358 5357 -0.967171 -0.0109926 0.00484677 1 0 1 1 0 0 +EDGE2 5358 2357 -0.991195 -0.023529 -0.0533304 1 0 1 1 0 0 +EDGE2 5358 1597 -1.01226 0.0325361 0.0190724 1 0 1 1 0 0 +EDGE2 5358 2317 -0.967877 0.0687904 -0.0181295 1 0 1 1 0 0 +EDGE2 5358 1517 -0.984959 0.0546131 -0.00681053 1 0 1 1 0 0 +EDGE2 5358 1598 0.00805544 0.0165282 -0.000730116 1 0 1 1 0 0 +EDGE2 5358 2338 -0.0297803 0.0593966 0.0152653 1 0 1 1 0 0 +EDGE2 5358 2358 0.0241087 0.0358288 0.000174938 1 0 1 1 0 0 +EDGE2 5358 2318 0.013265 -0.0218677 0.0164691 1 0 1 1 0 0 +EDGE2 5358 2359 1.04682 -0.0443136 0.0344031 1 0 1 1 0 0 +EDGE2 5358 1518 0.0564908 0.00837974 -0.00300087 1 0 1 1 0 0 +EDGE2 5358 1599 0.970766 0.0117058 -0.00889082 1 0 1 1 0 0 +EDGE2 5358 2319 0.9388 -1.53517e-05 0.0101606 1 0 1 1 0 0 +EDGE2 5358 2339 0.954356 -0.0871386 -0.0263206 1 0 1 1 0 0 +EDGE2 5358 1519 1.05782 -0.0484067 -0.0013937 1 0 1 1 0 0 +EDGE2 5359 1598 -0.939646 0.0168475 -0.0154065 1 0 1 1 0 0 +EDGE2 5359 2338 -1.04845 -0.0379553 0.0248973 1 0 1 1 0 0 +EDGE2 5359 5358 -0.958606 -0.0878194 0.00363748 1 0 1 1 0 0 +EDGE2 5359 2358 -1.05968 0.0351989 0.0137687 1 0 1 1 0 0 +EDGE2 5359 2318 -1.01591 0.0604269 0.00730107 1 0 1 1 0 0 +EDGE2 5359 2359 0.0997926 -0.0105635 0.0114563 1 0 1 1 0 0 +EDGE2 5359 1518 -1.04037 0.00967837 0.00423269 1 0 1 1 0 0 +EDGE2 5359 1599 0.0555691 -0.0266658 -0.00509908 1 0 1 1 0 0 +EDGE2 5359 2319 0.0174963 -0.0422222 0.0141489 1 0 1 1 0 0 +EDGE2 5359 2339 0.0211956 0.0490435 -0.00902317 1 0 1 1 0 0 +EDGE2 5359 1519 0.0030509 0.0172826 -0.0181339 1 0 1 1 0 0 +EDGE2 5359 2340 0.97598 -0.0736224 -0.0172854 1 0 1 1 0 0 +EDGE2 5359 5340 1.02324 0.0716045 -3.14084 1 0 1 1 0 0 +EDGE2 5359 2360 0.916103 0.020559 -0.00525073 1 0 1 1 0 0 +EDGE2 5359 1520 0.913518 0.0827425 0.0210455 1 0 1 1 0 0 +EDGE2 5359 1620 0.980772 0.0255535 -3.13581 1 0 1 1 0 0 +EDGE2 5359 1640 0.988441 0.0136933 -3.13312 1 0 1 1 0 0 +EDGE2 5359 2320 0.877816 -0.0432331 -0.00365173 1 0 1 1 0 0 +EDGE2 5359 1600 0.941473 -0.0235617 0.0233154 1 0 1 1 0 0 +EDGE2 5359 1320 1.02631 -0.00870029 -3.16023 1 0 1 1 0 0 +EDGE2 5360 2359 -0.96279 -0.0837814 -0.00784289 1 0 1 1 0 0 +EDGE2 5360 5359 -1.04401 -0.00903916 0.0257892 1 0 1 1 0 0 +EDGE2 5360 1599 -0.967321 0.00197311 0.00542611 1 0 1 1 0 0 +EDGE2 5360 2319 -1.04745 0.0104856 -0.014172 1 0 1 1 0 0 +EDGE2 5360 2339 -0.924717 0.0202939 -0.00926773 1 0 1 1 0 0 +EDGE2 5360 1519 -1.03191 0.00917458 0.0166788 1 0 1 1 0 0 +EDGE2 5360 2340 -0.0246767 0.00329401 -0.0319088 1 0 1 1 0 0 +EDGE2 5360 2341 0.0192078 1.02784 1.56512 1 0 1 1 0 0 +EDGE2 5360 5341 0.0120011 0.899799 1.54437 1 0 1 1 0 0 +EDGE2 5360 2361 -0.0354443 1.0257 1.54802 1 0 1 1 0 0 +EDGE2 5360 1521 -0.151665 1.04227 1.56326 1 0 1 1 0 0 +EDGE2 5360 1641 -0.0484636 0.984737 1.57026 1 0 1 1 0 0 +EDGE2 5360 2321 0.0245421 0.986666 1.5874 1 0 1 1 0 0 +EDGE2 5360 1321 0.0395176 1.0538 1.58668 1 0 1 1 0 0 +EDGE2 5360 5340 0.0116703 0.013436 -3.17131 1 0 1 1 0 0 +EDGE2 5360 2360 0.0171008 -0.0218443 -0.00882707 1 0 1 1 0 0 +EDGE2 5360 1520 -0.00422555 0.0519515 0.0249986 1 0 1 1 0 0 +EDGE2 5360 1620 0.0165503 -0.0683629 -3.11446 1 0 1 1 0 0 +EDGE2 5360 1640 0.0626927 0.031512 -3.16053 1 0 1 1 0 0 +EDGE2 5360 2320 -0.0361071 -0.0497156 -0.0358524 1 0 1 1 0 0 +EDGE2 5360 1600 0.0548601 -0.0445496 0.0011082 1 0 1 1 0 0 +EDGE2 5360 1621 0.0465223 -0.944293 -1.56366 1 0 1 1 0 0 +EDGE2 5360 1320 -0.0564344 -0.0167008 -3.15063 1 0 1 1 0 0 +EDGE2 5360 1601 0.0298702 -1.0672 -1.5847 1 0 1 1 0 0 +EDGE2 5360 1619 0.975083 -0.055948 -3.15267 1 0 1 1 0 0 +EDGE2 5360 5339 1.03321 -0.0460537 -3.14865 1 0 1 1 0 0 +EDGE2 5360 1639 1.01031 0.0747846 -3.11766 1 0 1 1 0 0 +EDGE2 5360 1319 0.996448 -0.0524514 -3.15431 1 0 1 1 0 0 +EDGE2 5361 2362 1.00796 0.0547018 -0.005241 1 0 1 1 0 0 +EDGE2 5361 5342 0.965823 -0.110621 -0.00313741 1 0 1 1 0 0 +EDGE2 5361 2340 -1.01665 0.010624 -1.60647 1 0 1 1 0 0 +EDGE2 5361 2341 -0.0858563 -0.00398109 -0.0163508 1 0 1 1 0 0 +EDGE2 5361 1322 1.03418 -0.0228199 0.0162368 1 0 1 1 0 0 +EDGE2 5361 1642 0.964346 0.0351097 0.0260437 1 0 1 1 0 0 +EDGE2 5361 2322 1.0393 -0.0358637 0.0311089 1 0 1 1 0 0 +EDGE2 5361 2342 0.945295 -0.0253456 -0.00140748 1 0 1 1 0 0 +EDGE2 5361 1522 0.985217 -0.0217005 -0.00825201 1 0 1 1 0 0 +EDGE2 5361 5341 -0.071304 0.0320662 0.00997648 1 0 1 1 0 0 +EDGE2 5361 2361 0.0338023 -0.0341657 0.00483247 1 0 1 1 0 0 +EDGE2 5361 1521 0.0309583 -0.083478 -0.00401538 1 0 1 1 0 0 +EDGE2 5361 1641 0.025817 -0.0524477 -0.0330336 1 0 1 1 0 0 +EDGE2 5361 2321 0.031263 0.0484347 -0.0155938 1 0 1 1 0 0 +EDGE2 5361 1321 0.00545744 -0.00562864 -0.00378645 1 0 1 1 0 0 +EDGE2 5361 5340 -0.969145 -0.145548 1.55505 1 0 1 1 0 0 +EDGE2 5361 5360 -0.877516 0.0484077 -1.55226 1 0 1 1 0 0 +EDGE2 5361 2360 -0.975841 0.0196524 -1.57521 1 0 1 1 0 0 +EDGE2 5361 1520 -0.931622 0.0335151 -1.56103 1 0 1 1 0 0 +EDGE2 5361 1620 -0.994592 0.0739684 1.56219 1 0 1 1 0 0 +EDGE2 5361 1640 -1.0419 0.0325873 1.52803 1 0 1 1 0 0 +EDGE2 5361 2320 -1.05928 -0.0124286 -1.57805 1 0 1 1 0 0 +EDGE2 5361 1600 -0.978399 0.00670612 -1.57222 1 0 1 1 0 0 +EDGE2 5361 1320 -0.93334 -0.0665041 1.57759 1 0 1 1 0 0 +EDGE2 5362 2362 0.0359201 0.00253408 -0.021022 1 0 1 1 0 0 +EDGE2 5362 2363 0.965632 0.00596367 0.000555495 1 0 1 1 0 0 +EDGE2 5362 5343 1.00295 -0.0168824 -0.0267672 1 0 1 1 0 0 +EDGE2 5362 1323 1.00578 0.00581799 0.0294849 1 0 1 1 0 0 +EDGE2 5362 1643 1.03927 -0.0840771 -0.0469229 1 0 1 1 0 0 +EDGE2 5362 2323 0.976481 0.0516322 0.000446006 1 0 1 1 0 0 +EDGE2 5362 2343 0.923991 -0.00122316 0.00749662 1 0 1 1 0 0 +EDGE2 5362 1523 1.08424 -0.0537024 0.0389174 1 0 1 1 0 0 +EDGE2 5362 5342 0.179329 0.0145942 0.00730088 1 0 1 1 0 0 +EDGE2 5362 2341 -0.996208 -0.0127078 0.000658142 1 0 1 1 0 0 +EDGE2 5362 1322 -0.0938333 0.0206538 -0.00677828 1 0 1 1 0 0 +EDGE2 5362 1642 0.054252 -0.086174 -0.00757787 1 0 1 1 0 0 +EDGE2 5362 2322 -0.0499198 0.0126281 0.0192182 1 0 1 1 0 0 +EDGE2 5362 2342 0.0682042 -0.00504617 -0.0110854 1 0 1 1 0 0 +EDGE2 5362 1522 -0.0313389 -0.100218 0.0175608 1 0 1 1 0 0 +EDGE2 5362 5341 -0.936482 -0.0141151 -0.0327439 1 0 1 1 0 0 +EDGE2 5362 5361 -1.06623 -0.0169293 -0.0291315 1 0 1 1 0 0 +EDGE2 5362 2361 -1.02012 0.00164057 0.00432966 1 0 1 1 0 0 +EDGE2 5362 1521 -1.01586 -0.0129084 0.0319601 1 0 1 1 0 0 +EDGE2 5362 1641 -0.93652 0.0529222 -0.0121571 1 0 1 1 0 0 +EDGE2 5362 2321 -0.985395 0.0882482 -0.00475321 1 0 1 1 0 0 +EDGE2 5362 1321 -0.954745 0.0163848 -0.00432151 1 0 1 1 0 0 +EDGE2 5363 2362 -1.07572 -0.0796243 0.0290436 1 0 1 1 0 0 +EDGE2 5363 5344 0.994922 -0.0573976 -0.0132025 1 0 1 1 0 0 +EDGE2 5363 2363 -0.0523773 -0.0179398 0.013079 1 0 1 1 0 0 +EDGE2 5363 1524 0.993875 -0.0554925 0.00938023 1 0 1 1 0 0 +EDGE2 5363 2324 1.04241 -0.0101768 0.00447452 1 0 1 1 0 0 +EDGE2 5363 2344 0.966582 0.0201014 0.00376326 1 0 1 1 0 0 +EDGE2 5363 2364 0.993177 0.0530598 -0.0150286 1 0 1 1 0 0 +EDGE2 5363 1644 0.939348 0.0687588 -0.010234 1 0 1 1 0 0 +EDGE2 5363 1324 1.00151 0.0349009 0.00743779 1 0 1 1 0 0 +EDGE2 5363 5343 -0.0205467 -0.0912333 0.00239454 1 0 1 1 0 0 +EDGE2 5363 1323 -0.0170213 -0.0286891 0.00751525 1 0 1 1 0 0 +EDGE2 5363 1643 -0.000515064 -0.0366671 0.000546652 1 0 1 1 0 0 +EDGE2 5363 2323 -0.0502788 0.0371756 -0.0281164 1 0 1 1 0 0 +EDGE2 5363 2343 0.00529383 0.0380411 -0.0261166 1 0 1 1 0 0 +EDGE2 5363 1523 -0.0125253 -0.00941479 0.0241377 1 0 1 1 0 0 +EDGE2 5363 5362 -1.1029 0.0707249 0.0246868 1 0 1 1 0 0 +EDGE2 5363 5342 -1.04608 -0.0859134 -0.0146234 1 0 1 1 0 0 +EDGE2 5363 1322 -0.991422 -0.109063 0.00811416 1 0 1 1 0 0 +EDGE2 5363 1642 -1.01811 0.026374 0.0275379 1 0 1 1 0 0 +EDGE2 5363 2322 -1.02293 -0.0673347 -0.00404894 1 0 1 1 0 0 +EDGE2 5363 2342 -1.02245 -0.0157598 -0.0166471 1 0 1 1 0 0 +EDGE2 5363 1522 -1.01882 0.0254016 -0.00871739 1 0 1 1 0 0 +EDGE2 5364 1345 1.06727 -0.0179639 -3.12249 1 0 1 1 0 0 +EDGE2 5364 2345 1.03968 -0.0662889 0.0305686 1 0 1 1 0 0 +EDGE2 5364 5345 1.02252 0.0296137 -0.0180278 1 0 1 1 0 0 +EDGE2 5364 2365 0.833461 0.111362 -0.0142681 1 0 1 1 0 0 +EDGE2 5364 1525 0.993497 0.0089011 0.00583666 1 0 1 1 0 0 +EDGE2 5364 1905 1.06634 0.0770766 -3.16451 1 0 1 1 0 0 +EDGE2 5364 1925 0.958175 -0.0373089 -3.1585 1 0 1 1 0 0 +EDGE2 5364 2325 1.01118 -0.0125719 -0.0142472 1 0 1 1 0 0 +EDGE2 5364 1645 1.00183 0.0168269 -0.010046 1 0 1 1 0 0 +EDGE2 5364 1485 1.03335 0.0143853 -3.10701 1 0 1 1 0 0 +EDGE2 5364 1505 0.914642 0.0478986 -3.13682 1 0 1 1 0 0 +EDGE2 5364 1365 0.98649 0.0610818 -3.15587 1 0 1 1 0 0 +EDGE2 5364 5344 -0.00107905 0.0210296 -0.0224083 1 0 1 1 0 0 +EDGE2 5364 1325 0.942012 -0.0217319 0.00118724 1 0 1 1 0 0 +EDGE2 5364 2363 -0.995629 -0.0246701 -0.0239258 1 0 1 1 0 0 +EDGE2 5364 1524 -0.0110467 0.0428537 0.0210102 1 0 1 1 0 0 +EDGE2 5364 2324 -0.0097709 -0.0398705 0.00247959 1 0 1 1 0 0 +EDGE2 5364 2344 -0.0348628 -0.0150784 -0.00586032 1 0 1 1 0 0 +EDGE2 5364 2364 0.0320644 -0.0444766 -0.0169085 1 0 1 1 0 0 +EDGE2 5364 1644 0.00949167 0.00145496 -0.0291545 1 0 1 1 0 0 +EDGE2 5364 5363 -1.00701 -0.0478829 0.0246721 1 0 1 1 0 0 +EDGE2 5364 1324 -0.0992676 -0.00955671 0.0200815 1 0 1 1 0 0 +EDGE2 5364 5343 -1.00051 0.0219134 -9.21129e-06 1 0 1 1 0 0 +EDGE2 5364 1323 -0.999706 0.0578145 0.0198461 1 0 1 1 0 0 +EDGE2 5364 1643 -0.941761 0.0369264 0.00571897 1 0 1 1 0 0 +EDGE2 5364 2323 -0.998974 -0.0925903 0.0188212 1 0 1 1 0 0 +EDGE2 5364 2343 -1.03202 -0.0316193 0.00366182 1 0 1 1 0 0 +EDGE2 5364 1523 -1.03248 0.0401556 -0.000369436 1 0 1 1 0 0 +EDGE2 5365 1345 0.0339037 0.0655893 -3.1296 1 0 1 1 0 0 +EDGE2 5365 1526 0.0374277 1.04697 1.57081 1 0 1 1 0 0 +EDGE2 5365 2366 0.00969111 1.01298 1.57552 1 0 1 1 0 0 +EDGE2 5365 5346 0.0310638 1.02917 1.55702 1 0 1 1 0 0 +EDGE2 5365 1926 -0.00719292 1.03781 1.59838 1 0 1 1 0 0 +EDGE2 5365 2326 -0.075656 1.06602 1.56355 1 0 1 1 0 0 +EDGE2 5365 2346 -0.0532399 1.08287 1.61159 1 0 1 1 0 0 +EDGE2 5365 1646 -0.0495234 1.13604 1.58751 1 0 1 1 0 0 +EDGE2 5365 1366 -0.0097932 1.04779 1.59423 1 0 1 1 0 0 +EDGE2 5365 1506 -0.0196817 0.940248 1.5667 1 0 1 1 0 0 +EDGE2 5365 1924 1.05677 -0.068623 -3.13381 1 0 1 1 0 0 +EDGE2 5365 2345 0.0323413 -0.0634562 -0.0202834 1 0 1 1 0 0 +EDGE2 5365 1344 0.857818 -0.11091 -3.15649 1 0 1 1 0 0 +EDGE2 5365 1484 1.00067 -0.0306695 -3.13877 1 0 1 1 0 0 +EDGE2 5365 1504 0.926486 0.0607423 -3.08052 1 0 1 1 0 0 +EDGE2 5365 1904 1.05612 0.0674418 -3.14146 1 0 1 1 0 0 +EDGE2 5365 1364 1.00126 0.0133303 -3.16025 1 0 1 1 0 0 +EDGE2 5365 5345 0.040176 0.026263 0.0102688 1 0 1 1 0 0 +EDGE2 5365 2365 0.0138476 -0.0432998 0.012633 1 0 1 1 0 0 +EDGE2 5365 1525 0.0132436 0.0369583 -0.0102653 1 0 1 1 0 0 +EDGE2 5365 1905 0.00644171 -0.0499392 -3.14316 1 0 1 1 0 0 +EDGE2 5365 1925 0.0104126 0.030698 -3.13281 1 0 1 1 0 0 +EDGE2 5365 2325 0.0787568 0.0921305 -0.0169553 1 0 1 1 0 0 +EDGE2 5365 1645 0.00820786 -0.023985 0.000210236 1 0 1 1 0 0 +EDGE2 5365 1485 0.0278486 0.0671921 -3.12484 1 0 1 1 0 0 +EDGE2 5365 1505 -0.00108308 0.0588182 -3.1593 1 0 1 1 0 0 +EDGE2 5365 1365 0.0238953 -0.00248971 -3.11729 1 0 1 1 0 0 +EDGE2 5365 5344 -1.09369 0.0819463 0.0229708 1 0 1 1 0 0 +EDGE2 5365 1325 -0.0781819 -0.0344435 0.0325438 1 0 1 1 0 0 +EDGE2 5365 5364 -1.03641 0.0152041 0.00713221 1 0 1 1 0 0 +EDGE2 5365 1524 -1.06005 -0.00912613 -0.0127462 1 0 1 1 0 0 +EDGE2 5365 2324 -0.960366 -0.0880757 -0.00182712 1 0 1 1 0 0 +EDGE2 5365 2344 -1.00848 -0.141052 -0.00585135 1 0 1 1 0 0 +EDGE2 5365 2364 -0.974492 -0.0255202 0.0235397 1 0 1 1 0 0 +EDGE2 5365 1644 -0.905638 0.0516751 -0.0295405 1 0 1 1 0 0 +EDGE2 5365 1324 -1.00465 0.0421486 0.022451 1 0 1 1 0 0 +EDGE2 5365 1486 -0.00126353 -1.07206 -1.55621 1 0 1 1 0 0 +EDGE2 5365 1906 0.016257 -0.986495 -1.55178 1 0 1 1 0 0 +EDGE2 5365 1326 -0.0601068 -1.07612 -1.59104 1 0 1 1 0 0 +EDGE2 5365 1346 0.0707055 -1.06783 -1.59089 1 0 1 1 0 0 +EDGE2 5366 2327 1.10145 0.0632351 0.00798807 1 0 1 1 0 0 +EDGE2 5366 2367 0.983654 -0.0337532 0.0263416 1 0 1 1 0 0 +EDGE2 5366 5347 0.940141 -0.00055868 -0.0099166 1 0 1 1 0 0 +EDGE2 5366 2347 0.960073 -0.0625997 -0.000605504 1 0 1 1 0 0 +EDGE2 5366 1345 -0.950374 -0.0268322 1.57749 1 0 1 1 0 0 +EDGE2 5366 1526 -0.0122307 -0.015465 -0.0343297 1 0 1 1 0 0 +EDGE2 5366 1507 1.00377 -0.0826072 0.00752204 1 0 1 1 0 0 +EDGE2 5366 1527 0.943393 -0.0172794 -0.0139809 1 0 1 1 0 0 +EDGE2 5366 1647 1.07852 0.0399259 -0.00218544 1 0 1 1 0 0 +EDGE2 5366 1927 1.0499 0.05337 -0.0100703 1 0 1 1 0 0 +EDGE2 5366 2366 -0.0529737 0.055277 -0.0184419 1 0 1 1 0 0 +EDGE2 5366 1367 0.976509 -0.0886834 -0.0157297 1 0 1 1 0 0 +EDGE2 5366 5346 0.0028306 0.0350281 0.015292 1 0 1 1 0 0 +EDGE2 5366 1926 0.0400941 -0.0163919 -0.0167425 1 0 1 1 0 0 +EDGE2 5366 2326 -0.0674528 -0.0933681 0.00702961 1 0 1 1 0 0 +EDGE2 5366 2346 0.0769941 -0.0227006 0.0170507 1 0 1 1 0 0 +EDGE2 5366 1646 0.0289326 0.0232537 -0.00102875 1 0 1 1 0 0 +EDGE2 5366 1366 0.0321492 0.0673368 0.00801324 1 0 1 1 0 0 +EDGE2 5366 1506 0.0230797 0.0555724 -0.016718 1 0 1 1 0 0 +EDGE2 5366 2345 -0.999726 0.00292944 -1.55191 1 0 1 1 0 0 +EDGE2 5366 5345 -0.919926 0.0581348 -1.56564 1 0 1 1 0 0 +EDGE2 5366 5365 -1.08441 0.0410724 -1.57465 1 0 1 1 0 0 +EDGE2 5366 2365 -1.00485 -0.047268 -1.55121 1 0 1 1 0 0 +EDGE2 5366 1525 -0.907136 0.0555 -1.5616 1 0 1 1 0 0 +EDGE2 5366 1905 -1.01876 0.025609 1.56089 1 0 1 1 0 0 +EDGE2 5366 1925 -1.09188 0.0153152 1.59685 1 0 1 1 0 0 +EDGE2 5366 2325 -1.06822 -0.0486326 -1.56319 1 0 1 1 0 0 +EDGE2 5366 1645 -0.99498 0.0262664 -1.56758 1 0 1 1 0 0 +EDGE2 5366 1485 -0.960689 -0.00877858 1.53542 1 0 1 1 0 0 +EDGE2 5366 1505 -0.984038 -0.0072968 1.59437 1 0 1 1 0 0 +EDGE2 5366 1365 -0.957816 0.0695467 1.59369 1 0 1 1 0 0 +EDGE2 5366 1325 -1.12151 0.0129 -1.61827 1 0 1 1 0 0 +EDGE2 5367 2327 -0.0167649 0.052613 -0.00644496 1 0 1 1 0 0 +EDGE2 5367 2368 0.994671 0.0367084 0.0131529 1 0 1 1 0 0 +EDGE2 5367 5348 1.00863 -0.0986892 -0.00896708 1 0 1 1 0 0 +EDGE2 5367 1648 0.966397 0.00506284 0.0229458 1 0 1 1 0 0 +EDGE2 5367 1928 1.03866 -0.0337404 0.0124164 1 0 1 1 0 0 +EDGE2 5367 2328 1.05276 0.0516968 -0.0095694 1 0 1 1 0 0 +EDGE2 5367 2348 0.985575 0.108698 -0.010701 1 0 1 1 0 0 +EDGE2 5367 1368 0.960616 0.0846711 0.0248237 1 0 1 1 0 0 +EDGE2 5367 1508 0.946338 0.0123547 -0.0313951 1 0 1 1 0 0 +EDGE2 5367 1528 0.993091 -0.0275399 0.016511 1 0 1 1 0 0 +EDGE2 5367 2367 0.0653447 0.039254 -0.00332446 1 0 1 1 0 0 +EDGE2 5367 5347 0.0201816 -0.0521676 -0.0270286 1 0 1 1 0 0 +EDGE2 5367 2347 0.087218 0.00838674 0.0128718 1 0 1 1 0 0 +EDGE2 5367 1526 -0.985034 0.05165 0.0203658 1 0 1 1 0 0 +EDGE2 5367 1507 0.0135763 0.0393429 -0.0201208 1 0 1 1 0 0 +EDGE2 5367 1527 0.0443448 -0.0234698 -0.0197167 1 0 1 1 0 0 +EDGE2 5367 1647 -0.0687758 -0.109 0.0114701 1 0 1 1 0 0 +EDGE2 5367 1927 0.0155886 -0.0349697 -0.0329869 1 0 1 1 0 0 +EDGE2 5367 2366 -0.949915 -0.0397454 0.00510707 1 0 1 1 0 0 +EDGE2 5367 5366 -0.935242 0.0474172 -0.0385543 1 0 1 1 0 0 +EDGE2 5367 1367 0.0173514 0.0594745 0.00767376 1 0 1 1 0 0 +EDGE2 5367 5346 -0.974174 -0.0445942 -0.00998095 1 0 1 1 0 0 +EDGE2 5367 1926 -0.948265 0.0282023 0.0068106 1 0 1 1 0 0 +EDGE2 5367 2326 -0.94833 0.0685699 0.00100522 1 0 1 1 0 0 +EDGE2 5367 2346 -1.01576 0.0212657 0.0157897 1 0 1 1 0 0 +EDGE2 5367 1646 -0.940701 0.0642878 -0.0229184 1 0 1 1 0 0 +EDGE2 5367 1366 -1.05465 -0.0434631 0.011306 1 0 1 1 0 0 +EDGE2 5367 1506 -1.0347 -0.0610059 0.0076498 1 0 1 1 0 0 +EDGE2 5368 2327 -0.938524 -0.0349974 -0.0244683 1 0 1 1 0 0 +EDGE2 5368 2368 0.0550564 0.000827312 -0.00643305 1 0 1 1 0 0 +EDGE2 5368 2349 1.00161 -0.00195047 0.00887686 1 0 1 1 0 0 +EDGE2 5368 2369 1.07129 -0.0607027 -0.0233984 1 0 1 1 0 0 +EDGE2 5368 5349 1.01138 0.0857064 -0.00975452 1 0 1 1 0 0 +EDGE2 5368 1509 1.04091 -0.0632658 -0.00763086 1 0 1 1 0 0 +EDGE2 5368 1649 0.993376 -0.0149752 -0.00721723 1 0 1 1 0 0 +EDGE2 5368 1929 1.07255 -0.0251697 0.0165628 1 0 1 1 0 0 +EDGE2 5368 2329 1.00326 0.00280931 0.0187006 1 0 1 1 0 0 +EDGE2 5368 1529 1.0346 0.0393343 -0.0057355 1 0 1 1 0 0 +EDGE2 5368 1369 1.08141 0.0653566 -0.00799091 1 0 1 1 0 0 +EDGE2 5368 5348 0.0241357 -0.0632441 -0.000413459 1 0 1 1 0 0 +EDGE2 5368 1648 -0.0481918 0.0568251 0.000777933 1 0 1 1 0 0 +EDGE2 5368 1928 -0.0455111 0.0152827 0.0115522 1 0 1 1 0 0 +EDGE2 5368 2328 0.0968475 -0.086218 0.0191393 1 0 1 1 0 0 +EDGE2 5368 2348 0.0440024 0.0164668 0.0125875 1 0 1 1 0 0 +EDGE2 5368 5367 -1.03052 0.0696638 -0.021729 1 0 1 1 0 0 +EDGE2 5368 1368 -0.0286784 -0.0464808 0.0095057 1 0 1 1 0 0 +EDGE2 5368 1508 -0.00258463 -0.0495823 -0.020532 1 0 1 1 0 0 +EDGE2 5368 1528 0.0111104 -0.010744 0.0230015 1 0 1 1 0 0 +EDGE2 5368 2367 -0.998741 0.0108972 -0.0088614 1 0 1 1 0 0 +EDGE2 5368 5347 -1.00652 0.0487923 0.00507264 1 0 1 1 0 0 +EDGE2 5368 2347 -1.07804 0.0979274 -0.00919162 1 0 1 1 0 0 +EDGE2 5368 1507 -1.07102 -0.02419 -0.0449054 1 0 1 1 0 0 +EDGE2 5368 1527 -1.11624 0.0610809 -0.00822761 1 0 1 1 0 0 +EDGE2 5368 1647 -1.02574 0.0439816 -0.0198401 1 0 1 1 0 0 +EDGE2 5368 1927 -0.974936 0.0166689 0.0358856 1 0 1 1 0 0 +EDGE2 5368 1367 -1.00864 -0.0875293 0.0108858 1 0 1 1 0 0 +EDGE2 5369 2330 1.0813 -0.0471958 0.0333312 1 0 1 1 0 0 +EDGE2 5369 2370 0.972143 -0.0316124 -0.00641363 1 0 1 1 0 0 +EDGE2 5369 5350 0.975583 -0.0275866 0.0324915 1 0 1 1 0 0 +EDGE2 5369 2350 1.05614 -0.0241177 0.0145908 1 0 1 1 0 0 +EDGE2 5369 1650 1.01153 0.0457851 0.0286349 1 0 1 1 0 0 +EDGE2 5369 1710 1.0472 -0.03049 -3.10774 1 0 1 1 0 0 +EDGE2 5369 1870 0.989279 -0.0282738 -3.11572 1 0 1 1 0 0 +EDGE2 5369 1930 1.00344 0.0371076 0.0116144 1 0 1 1 0 0 +EDGE2 5369 1670 0.966579 -0.0622048 -3.12577 1 0 1 1 0 0 +EDGE2 5369 1470 1.06541 0.0132305 -3.16122 1 0 1 1 0 0 +EDGE2 5369 1510 1.06797 0.0544645 0.0132201 1 0 1 1 0 0 +EDGE2 5369 1530 0.94812 0.0041083 -0.0118266 1 0 1 1 0 0 +EDGE2 5369 1370 0.94517 0.0161528 -0.0220803 1 0 1 1 0 0 +EDGE2 5369 2368 -1.07046 0.0135433 0.0183473 1 0 1 1 0 0 +EDGE2 5369 2349 -0.0658418 0.0338475 0.0285728 1 0 1 1 0 0 +EDGE2 5369 2369 0.0144585 0.055888 0.0075708 1 0 1 1 0 0 +EDGE2 5369 5349 0.0171902 0.0670898 -0.00823993 1 0 1 1 0 0 +EDGE2 5369 1509 0.111858 -0.0457036 0.000291339 1 0 1 1 0 0 +EDGE2 5369 1649 -0.00692118 0.0417087 -0.000201288 1 0 1 1 0 0 +EDGE2 5369 1929 -0.0324366 -0.04062 0.00966486 1 0 1 1 0 0 +EDGE2 5369 2329 0.0406658 -0.0361686 0.00127135 1 0 1 1 0 0 +EDGE2 5369 1529 -0.0282874 -0.0210769 -0.00606008 1 0 1 1 0 0 +EDGE2 5369 5368 -0.868232 0.0580388 0.0136554 1 0 1 1 0 0 +EDGE2 5369 1369 -0.0317713 0.0802725 -0.013183 1 0 1 1 0 0 +EDGE2 5369 5348 -0.983543 0.0195411 -0.00928822 1 0 1 1 0 0 +EDGE2 5369 1648 -1.03214 -0.0456163 0.00544127 1 0 1 1 0 0 +EDGE2 5369 1928 -1.04657 -0.0688023 -0.0023792 1 0 1 1 0 0 +EDGE2 5369 2328 -0.988824 0.00098657 -0.0238342 1 0 1 1 0 0 +EDGE2 5369 2348 -0.991242 0.0183567 0.00850526 1 0 1 1 0 0 +EDGE2 5369 1368 -0.985308 0.0148843 0.00532344 1 0 1 1 0 0 +EDGE2 5369 1508 -1.06098 -0.0357213 -0.0298488 1 0 1 1 0 0 +EDGE2 5369 1528 -1.016 0.0830676 0.0137289 1 0 1 1 0 0 +EDGE2 5370 1931 -0.0180914 -1.04451 -1.56633 1 0 1 1 0 0 +EDGE2 5370 1669 1.0069 -0.047968 -3.15473 1 0 1 1 0 0 +EDGE2 5370 1709 0.920947 -0.0852669 -3.1582 1 0 1 1 0 0 +EDGE2 5370 1869 0.991271 0.00612572 -3.13569 1 0 1 1 0 0 +EDGE2 5370 1469 0.888932 -0.0306546 -3.13226 1 0 1 1 0 0 +EDGE2 5370 2330 -0.0104933 0.00662928 0.00480552 1 0 1 1 0 0 +EDGE2 5370 1671 0.0221315 -0.953424 -1.55478 1 0 1 1 0 0 +EDGE2 5370 1711 -0.0413316 -1.05036 -1.57875 1 0 1 1 0 0 +EDGE2 5370 1871 -0.0876393 -1.04224 -1.58138 1 0 1 1 0 0 +EDGE2 5370 1471 0.0290209 -1.01372 -1.53175 1 0 1 1 0 0 +EDGE2 5370 2370 -0.0118816 0.0567607 -0.0227181 1 0 1 1 0 0 +EDGE2 5370 5350 -0.108367 0.0461917 0.0125518 1 0 1 1 0 0 +EDGE2 5370 2350 0.00217232 0.0298675 0.0102408 1 0 1 1 0 0 +EDGE2 5370 1650 -0.0233926 -0.0323689 0.00831288 1 0 1 1 0 0 +EDGE2 5370 1710 -0.0165057 -0.0104084 -3.14622 1 0 1 1 0 0 +EDGE2 5370 1870 -0.0298081 0.0528368 -3.16405 1 0 1 1 0 0 +EDGE2 5370 1930 -0.0599929 -0.0170079 0.0249519 1 0 1 1 0 0 +EDGE2 5370 1670 0.0754409 -0.00039245 -3.12127 1 0 1 1 0 0 +EDGE2 5370 1470 0.0463087 -0.00333888 -3.12875 1 0 1 1 0 0 +EDGE2 5370 1510 0.0144345 0.0301597 -0.00114387 1 0 1 1 0 0 +EDGE2 5370 1530 0.0216622 0.0326366 -0.0164648 1 0 1 1 0 0 +EDGE2 5370 1370 0.0769887 -0.0192618 -0.00376307 1 0 1 1 0 0 +EDGE2 5370 2351 0.00141213 0.964768 1.56809 1 0 1 1 0 0 +EDGE2 5370 2371 -0.00761244 0.956825 1.58674 1 0 1 1 0 0 +EDGE2 5370 5351 0.017282 1.11839 1.56966 1 0 1 1 0 0 +EDGE2 5370 1371 0.0564469 0.928624 1.57296 1 0 1 1 0 0 +EDGE2 5370 1531 0.0102547 1.01758 1.55877 1 0 1 1 0 0 +EDGE2 5370 1651 -0.0190721 0.956926 1.58117 1 0 1 1 0 0 +EDGE2 5370 2331 0.0543106 1.03004 1.58598 1 0 1 1 0 0 +EDGE2 5370 1511 0.0184616 0.997989 1.55997 1 0 1 1 0 0 +EDGE2 5370 2349 -0.964867 -0.103758 0.0212956 1 0 1 1 0 0 +EDGE2 5370 2369 -1.01365 0.093863 -0.00562583 1 0 1 1 0 0 +EDGE2 5370 5349 -1.05591 -0.00831331 -0.00979433 1 0 1 1 0 0 +EDGE2 5370 5369 -1.02294 -0.0439232 0.0171254 1 0 1 1 0 0 +EDGE2 5370 1509 -0.970902 0.00312254 -0.00947483 1 0 1 1 0 0 +EDGE2 5370 1649 -0.955265 -0.0306012 0.0115331 1 0 1 1 0 0 +EDGE2 5370 1929 -1.02431 0.0793217 0.00740907 1 0 1 1 0 0 +EDGE2 5370 2329 -0.995318 -0.0687338 0.0250975 1 0 1 1 0 0 +EDGE2 5370 1529 -0.952763 -0.0100746 0.0114336 1 0 1 1 0 0 +EDGE2 5370 1369 -1.03315 0.113216 0.00114804 1 0 1 1 0 0 +EDGE2 5371 2372 1.07825 0.098395 0.0282109 1 0 1 1 0 0 +EDGE2 5371 2330 -1.14153 0.034339 -1.582 1 0 1 1 0 0 +EDGE2 5371 2370 -1.04611 -0.0377041 -1.57791 1 0 1 1 0 0 +EDGE2 5371 5350 -0.970621 -0.0173809 -1.56954 1 0 1 1 0 0 +EDGE2 5371 5370 -1.00174 0.0726786 -1.59313 1 0 1 1 0 0 +EDGE2 5371 2350 -0.99431 0.00666825 -1.56833 1 0 1 1 0 0 +EDGE2 5371 1650 -1.0086 -0.0449277 -1.58415 1 0 1 1 0 0 +EDGE2 5371 1710 -1.02985 0.0192096 1.5598 1 0 1 1 0 0 +EDGE2 5371 1870 -1.00652 0.0501154 1.56999 1 0 1 1 0 0 +EDGE2 5371 1930 -1.16624 0.0292128 -1.58777 1 0 1 1 0 0 +EDGE2 5371 1670 -1.02697 0.045469 1.56554 1 0 1 1 0 0 +EDGE2 5371 1470 -0.975702 0.0326682 1.59417 1 0 1 1 0 0 +EDGE2 5371 1510 -1.02094 0.109664 -1.57196 1 0 1 1 0 0 +EDGE2 5371 1530 -0.924049 0.0144008 -1.57159 1 0 1 1 0 0 +EDGE2 5371 1370 -1.00492 0.0446594 -1.59095 1 0 1 1 0 0 +EDGE2 5371 2351 0.0268986 -0.0347173 0.0265632 1 0 1 1 0 0 +EDGE2 5371 2371 0.0440162 -0.0409836 0.0286057 1 0 1 1 0 0 +EDGE2 5371 5351 -0.0158186 0.0616501 0.0110816 1 0 1 1 0 0 +EDGE2 5371 1371 -0.0682101 0.071678 -0.0218886 1 0 1 1 0 0 +EDGE2 5371 1531 -0.0127274 0.0167837 -0.00143217 1 0 1 1 0 0 +EDGE2 5371 1651 -0.00478546 0.0603061 -0.0144357 1 0 1 1 0 0 +EDGE2 5371 2331 0.00163586 0.00592093 0.0151126 1 0 1 1 0 0 +EDGE2 5371 1511 -0.0392992 0.0466598 -0.00860066 1 0 1 1 0 0 +EDGE2 5371 5352 0.977587 0.0320872 0.00170963 1 0 1 1 0 0 +EDGE2 5371 1512 1.03785 0.0101212 -0.0220909 1 0 1 1 0 0 +EDGE2 5371 1652 1.0829 0.00590621 0.0193041 1 0 1 1 0 0 +EDGE2 5371 2332 0.939321 0.0345065 0.0102857 1 0 1 1 0 0 +EDGE2 5371 2352 1.10407 0.000671032 -0.0193802 1 0 1 1 0 0 +EDGE2 5371 1532 0.948125 -0.0215079 -0.0335224 1 0 1 1 0 0 +EDGE2 5371 1372 1.00094 0.0393167 -0.0100082 1 0 1 1 0 0 +EDGE2 5372 2372 0.0246212 -0.0492713 -0.0114854 1 0 1 1 0 0 +EDGE2 5372 2351 -1.12574 -0.0414194 -0.00771053 1 0 1 1 0 0 +EDGE2 5372 2371 -1.01156 0.0395691 -0.0262546 1 0 1 1 0 0 +EDGE2 5372 5351 -1.03116 -0.0278914 -0.0100773 1 0 1 1 0 0 +EDGE2 5372 5371 -0.990438 0.000457975 0.00286429 1 0 1 1 0 0 +EDGE2 5372 1371 -1.06146 0.0373759 -0.00979965 1 0 1 1 0 0 +EDGE2 5372 1531 -0.989721 -0.0238927 -0.0254856 1 0 1 1 0 0 +EDGE2 5372 1651 -0.900128 -0.0427753 -0.0414549 1 0 1 1 0 0 +EDGE2 5372 2331 -0.95804 -0.0430025 -0.00450239 1 0 1 1 0 0 +EDGE2 5372 1511 -1.00633 0.0494132 -0.0382514 1 0 1 1 0 0 +EDGE2 5372 5352 -0.0310236 -0.0609141 -0.00391062 1 0 1 1 0 0 +EDGE2 5372 2373 0.953636 0.000764798 0.00975508 1 0 1 1 0 0 +EDGE2 5372 1512 0.0189508 0.0296123 -0.0131852 1 0 1 1 0 0 +EDGE2 5372 1652 0.0494312 -0.0963543 -0.00863729 1 0 1 1 0 0 +EDGE2 5372 2332 0.0437813 -0.00217522 0.0357788 1 0 1 1 0 0 +EDGE2 5372 2352 0.0595233 0.060749 -0.017355 1 0 1 1 0 0 +EDGE2 5372 1532 0.0498155 -0.0256504 -0.000214751 1 0 1 1 0 0 +EDGE2 5372 1372 0.0391836 -0.00546827 -0.000350513 1 0 1 1 0 0 +EDGE2 5372 5353 1.01881 -0.0564266 -0.0455723 1 0 1 1 0 0 +EDGE2 5372 1513 1.01309 0.0660489 0.0117154 1 0 1 1 0 0 +EDGE2 5372 1653 1.0502 -0.00613311 0.0127382 1 0 1 1 0 0 +EDGE2 5372 2333 0.999065 -0.0287791 0.0301918 1 0 1 1 0 0 +EDGE2 5372 2353 1.03989 -0.12127 0.0161408 1 0 1 1 0 0 +EDGE2 5372 1533 1.04938 0.100387 0.00573777 1 0 1 1 0 0 +EDGE2 5372 1373 0.900167 0.0564052 -0.0175992 1 0 1 1 0 0 +EDGE2 5373 2372 -0.989176 0.016503 0.0190928 1 0 1 1 0 0 +EDGE2 5373 5372 -1.09283 0.0879684 -0.0333765 1 0 1 1 0 0 +EDGE2 5373 5352 -1.02457 -0.0513027 0.00269372 1 0 1 1 0 0 +EDGE2 5373 2374 0.927785 -0.0520757 -0.0178126 1 0 1 1 0 0 +EDGE2 5373 2373 -0.0772065 -0.0704846 -0.0178496 1 0 1 1 0 0 +EDGE2 5373 1512 -1.0118 0.045466 0.0530957 1 0 1 1 0 0 +EDGE2 5373 1652 -0.998117 0.0483453 0.0175275 1 0 1 1 0 0 +EDGE2 5373 2332 -0.994164 -0.0900503 -0.0338522 1 0 1 1 0 0 +EDGE2 5373 2352 -0.984053 0.00263189 -0.0020854 1 0 1 1 0 0 +EDGE2 5373 1532 -0.935669 -0.079178 -0.0307272 1 0 1 1 0 0 +EDGE2 5373 1372 -0.949722 0.0730891 -0.00840928 1 0 1 1 0 0 +EDGE2 5373 5353 -0.0483002 -0.00795863 0.0311557 1 0 1 1 0 0 +EDGE2 5373 1513 -0.0237863 0.0514552 -0.00696275 1 0 1 1 0 0 +EDGE2 5373 1653 -0.123756 -0.0453335 0.00824456 1 0 1 1 0 0 +EDGE2 5373 2333 -0.00508702 0.0465255 -0.00659992 1 0 1 1 0 0 +EDGE2 5373 2353 0.00665362 0.0178324 0.00162306 1 0 1 1 0 0 +EDGE2 5373 1533 -0.0649352 0.0310784 0.0300407 1 0 1 1 0 0 +EDGE2 5373 1373 0.0712206 0.00558515 -0.00630715 1 0 1 1 0 0 +EDGE2 5373 5354 0.955183 0.0141913 0.0222669 1 0 1 1 0 0 +EDGE2 5373 1514 1.0159 0.0115075 -0.00928246 1 0 1 1 0 0 +EDGE2 5373 1654 0.979133 -0.0541374 0.00157999 1 0 1 1 0 0 +EDGE2 5373 2334 1.12944 0.0437438 -0.000325756 1 0 1 1 0 0 +EDGE2 5373 2354 1.07437 -0.0338632 0.0384607 1 0 1 1 0 0 +EDGE2 5373 1534 0.927789 0.0157723 0.0469867 1 0 1 1 0 0 +EDGE2 5373 1374 1.00894 0.0290094 -0.0228028 1 0 1 1 0 0 +EDGE2 5374 1535 1.02365 -0.0242446 -0.0230415 1 0 1 1 0 0 +EDGE2 5374 2374 0.0177403 0.024489 0.0132338 1 0 1 1 0 0 +EDGE2 5374 2373 -1.04784 -0.0438177 -0.0124363 1 0 1 1 0 0 +EDGE2 5374 5373 -1.15002 -0.0713096 0.0347617 1 0 1 1 0 0 +EDGE2 5374 5353 -0.998832 0.0762094 0.0229683 1 0 1 1 0 0 +EDGE2 5374 1513 -1.03185 0.0323194 0.02183 1 0 1 1 0 0 +EDGE2 5374 1653 -0.981064 -0.015099 0.0153798 1 0 1 1 0 0 +EDGE2 5374 2333 -1.0468 -0.0429556 0.0522505 1 0 1 1 0 0 +EDGE2 5374 2353 -1.02236 -0.0260605 -0.00341821 1 0 1 1 0 0 +EDGE2 5374 1533 -0.95782 -0.0606985 -0.0250172 1 0 1 1 0 0 +EDGE2 5374 1373 -0.979342 0.138352 0.00120765 1 0 1 1 0 0 +EDGE2 5374 5354 -0.0892338 0.0268234 -0.0335679 1 0 1 1 0 0 +EDGE2 5374 2395 1.029 0.0227313 -3.13941 1 0 1 1 0 0 +EDGE2 5374 1514 0.00851111 -0.0708502 -0.0240447 1 0 1 1 0 0 +EDGE2 5374 1654 -0.0520649 0.0102849 0.0150735 1 0 1 1 0 0 +EDGE2 5374 2334 0.0327096 0.0277534 -0.00919998 1 0 1 1 0 0 +EDGE2 5374 2354 0.0108905 0.0640482 -0.0290118 1 0 1 1 0 0 +EDGE2 5374 1534 0.116184 -0.0260462 0.00423755 1 0 1 1 0 0 +EDGE2 5374 1374 -0.000242649 -0.00902269 0.0235575 1 0 1 1 0 0 +EDGE2 5374 5355 0.956274 -0.0742825 -0.0153467 1 0 1 1 0 0 +EDGE2 5374 1855 1.05935 -0.00960727 -3.16595 1 0 1 1 0 0 +EDGE2 5374 2335 1.01163 -0.00703557 0.0274235 1 0 1 1 0 0 +EDGE2 5374 2355 1.0051 -0.0962056 -0.00876148 1 0 1 1 0 0 +EDGE2 5374 2375 0.999913 -0.000470671 -0.026405 1 0 1 1 0 0 +EDGE2 5374 2315 0.968653 -0.0338748 -3.1362 1 0 1 1 0 0 +EDGE2 5374 1595 0.945986 0.01135 -3.1362 1 0 1 1 0 0 +EDGE2 5374 1655 0.959464 -0.0129217 0.0326768 1 0 1 1 0 0 +EDGE2 5374 1575 0.955895 0.0375905 -3.12172 1 0 1 1 0 0 +EDGE2 5374 1375 0.981977 0.103316 -0.0375984 1 0 1 1 0 0 +EDGE2 5374 1515 1.01059 0.036876 -0.0127373 1 0 1 1 0 0 +EDGE2 5375 1656 -0.0556171 -1.05626 -1.5943 1 0 1 1 0 0 +EDGE2 5375 2376 0.00104186 -1.01446 -1.5692 1 0 1 1 0 0 +EDGE2 5375 2396 -0.115397 -1.10266 -1.56516 1 0 1 1 0 0 +EDGE2 5375 1856 0.104429 -0.958318 -1.53286 1 0 1 1 0 0 +EDGE2 5375 1536 -0.000364539 -1.05636 -1.59699 1 0 1 1 0 0 +EDGE2 5375 1576 0.00526769 -1.06166 -1.56176 1 0 1 1 0 0 +EDGE2 5375 1376 -0.0221627 -1.03492 -1.54036 1 0 1 1 0 0 +EDGE2 5375 1535 0.0157152 -0.00549746 0.0100317 1 0 1 1 0 0 +EDGE2 5375 2374 -0.950393 -0.0333538 -0.000733157 1 0 1 1 0 0 +EDGE2 5375 5374 -1.05867 0.0760959 0.00167572 1 0 1 1 0 0 +EDGE2 5375 5354 -0.931584 -0.0455614 -0.0130566 1 0 1 1 0 0 +EDGE2 5375 2395 -0.0526979 0.083914 -3.15733 1 0 1 1 0 0 +EDGE2 5375 1514 -0.95315 -0.0339592 -0.00478332 1 0 1 1 0 0 +EDGE2 5375 1654 -0.963776 0.0099668 -0.0345672 1 0 1 1 0 0 +EDGE2 5375 2334 -1.05797 -0.0115743 0.0191546 1 0 1 1 0 0 +EDGE2 5375 2354 -1.00303 -0.0110762 -0.024308 1 0 1 1 0 0 +EDGE2 5375 1534 -1.0069 -0.0286641 -0.00372714 1 0 1 1 0 0 +EDGE2 5375 1374 -1.03629 0.0279969 0.0180201 1 0 1 1 0 0 +EDGE2 5375 5355 0.0246584 0.10984 0.0386169 1 0 1 1 0 0 +EDGE2 5375 1855 0.00828703 -0.0791871 -3.12516 1 0 1 1 0 0 +EDGE2 5375 2335 -0.0359535 0.00219279 0.0240962 1 0 1 1 0 0 +EDGE2 5375 2355 -0.0227749 -0.0193484 0.0394455 1 0 1 1 0 0 +EDGE2 5375 2375 0.0295828 -0.0139606 -0.00659739 1 0 1 1 0 0 +EDGE2 5375 2315 -0.0690865 -0.0975116 -3.12717 1 0 1 1 0 0 +EDGE2 5375 1595 -0.0135331 0.0192076 -3.15924 1 0 1 1 0 0 +EDGE2 5375 1655 0.0199218 0.114886 0.00213399 1 0 1 1 0 0 +EDGE2 5375 1575 -0.030498 0.00246301 -3.12048 1 0 1 1 0 0 +EDGE2 5375 1854 1.043 -0.109104 -3.10892 1 0 1 1 0 0 +EDGE2 5375 2394 0.966926 0.0910479 -3.13183 1 0 1 1 0 0 +EDGE2 5375 1375 0.0529246 -0.039138 -0.00583203 1 0 1 1 0 0 +EDGE2 5375 1515 0.0206497 0.0559545 -0.00437367 1 0 1 1 0 0 +EDGE2 5375 2314 1.07059 -0.125868 -3.15308 1 0 1 1 0 0 +EDGE2 5375 1574 0.977925 -0.0278275 -3.12986 1 0 1 1 0 0 +EDGE2 5375 1594 1.06809 0.0234074 -3.11027 1 0 1 1 0 0 +EDGE2 5375 2336 0.0161519 1.0086 1.56807 1 0 1 1 0 0 +EDGE2 5375 5356 0.0277305 0.954237 1.57742 1 0 1 1 0 0 +EDGE2 5375 2356 0.0328522 0.991618 1.57524 1 0 1 1 0 0 +EDGE2 5375 1516 0.0522283 0.960832 1.56425 1 0 1 1 0 0 +EDGE2 5375 1596 -0.0194236 1.09173 1.52231 1 0 1 1 0 0 +EDGE2 5375 2316 -0.0060935 0.955548 1.58151 1 0 1 1 0 0 +EDGE2 5376 1535 -0.937976 0.00781479 -1.55641 1 0 1 1 0 0 +EDGE2 5376 2395 -0.905821 -0.00524753 1.54646 1 0 1 1 0 0 +EDGE2 5376 5375 -1.02352 -0.0166695 -1.56056 1 0 1 1 0 0 +EDGE2 5376 5355 -0.973897 -0.0195703 -1.56689 1 0 1 1 0 0 +EDGE2 5376 1855 -1.00989 0.0022907 1.58087 1 0 1 1 0 0 +EDGE2 5376 2335 -0.992984 -0.0280034 -1.568 1 0 1 1 0 0 +EDGE2 5376 2355 -0.962835 -0.0445815 -1.55214 1 0 1 1 0 0 +EDGE2 5376 2375 -1.04357 -0.0305148 -1.57008 1 0 1 1 0 0 +EDGE2 5376 2315 -0.929223 -0.0169684 1.59419 1 0 1 1 0 0 +EDGE2 5376 1595 -0.997453 0.00139419 1.55016 1 0 1 1 0 0 +EDGE2 5376 1655 -0.9785 -0.00375989 -1.55466 1 0 1 1 0 0 +EDGE2 5376 1575 -0.921815 -0.0648236 1.567 1 0 1 1 0 0 +EDGE2 5376 1375 -0.99061 -0.0380354 -1.55695 1 0 1 1 0 0 +EDGE2 5376 1515 -1.01018 0.000536244 -1.58748 1 0 1 1 0 0 +EDGE2 5376 2336 0.0249237 0.0406837 -0.00754855 1 0 1 1 0 0 +EDGE2 5376 5356 0.0218196 0.00526519 0.0171177 1 0 1 1 0 0 +EDGE2 5376 2356 -0.0365032 0.0276465 -0.0425344 1 0 1 1 0 0 +EDGE2 5376 1516 -0.0358062 0.102443 -0.0140868 1 0 1 1 0 0 +EDGE2 5376 1596 -0.0351912 0.00575366 0.00945043 1 0 1 1 0 0 +EDGE2 5376 2316 0.0755287 -0.0211801 -0.0247006 1 0 1 1 0 0 +EDGE2 5376 2337 0.920302 0.00644993 -0.0222084 1 0 1 1 0 0 +EDGE2 5376 5357 1.03211 0.0321196 -0.0254141 1 0 1 1 0 0 +EDGE2 5376 2357 0.936486 0.0238493 0.00196092 1 0 1 1 0 0 +EDGE2 5376 1597 0.967968 0.0849285 -0.0216163 1 0 1 1 0 0 +EDGE2 5376 2317 1.00248 0.112898 0.0140292 1 0 1 1 0 0 +EDGE2 5376 1517 1.0172 -0.0476441 0.0164577 1 0 1 1 0 0 +EDGE2 5377 2336 -0.982642 -0.0216192 -0.0109334 1 0 1 1 0 0 +EDGE2 5377 5356 -1.08382 -0.0324569 0.00744194 1 0 1 1 0 0 +EDGE2 5377 5376 -1.00633 0.0579398 0.0160702 1 0 1 1 0 0 +EDGE2 5377 2356 -0.928812 -0.0106398 -0.0391062 1 0 1 1 0 0 +EDGE2 5377 1516 -1.01208 0.0697055 -0.0300478 1 0 1 1 0 0 +EDGE2 5377 1596 -0.923385 -0.0521669 0.00714353 1 0 1 1 0 0 +EDGE2 5377 2316 -0.955233 -0.0309956 -0.00156164 1 0 1 1 0 0 +EDGE2 5377 2337 0.0251785 0.00305091 -0.00591938 1 0 1 1 0 0 +EDGE2 5377 5357 -0.0182361 0.146122 -0.0176037 1 0 1 1 0 0 +EDGE2 5377 2357 0.0612095 -0.0141405 -0.0293932 1 0 1 1 0 0 +EDGE2 5377 1597 0.0188915 -0.026067 -0.024327 1 0 1 1 0 0 +EDGE2 5377 2317 0.0204008 0.0210223 -0.00127553 1 0 1 1 0 0 +EDGE2 5377 1517 0.000647666 0.0791275 0.00769902 1 0 1 1 0 0 +EDGE2 5377 1598 0.902143 -0.101738 -0.000913272 1 0 1 1 0 0 +EDGE2 5377 2338 1.0913 -0.046047 0.01109 1 0 1 1 0 0 +EDGE2 5377 5358 1.02856 0.0307421 -0.0115397 1 0 1 1 0 0 +EDGE2 5377 2358 0.990879 -0.000744663 0.00466871 1 0 1 1 0 0 +EDGE2 5377 2318 0.974965 -0.0284082 -0.00205491 1 0 1 1 0 0 +EDGE2 5377 1518 0.934152 -0.0225189 0.0130439 1 0 1 1 0 0 +EDGE2 5378 5377 -0.991165 0.0498183 0.00737217 1 0 1 1 0 0 +EDGE2 5378 2337 -0.95444 0.0489246 -0.0143158 1 0 1 1 0 0 +EDGE2 5378 5357 -1.07782 0.0163764 -0.000255989 1 0 1 1 0 0 +EDGE2 5378 2357 -0.994489 0.00500796 0.00306796 1 0 1 1 0 0 +EDGE2 5378 1597 -0.926231 -0.079093 0.015085 1 0 1 1 0 0 +EDGE2 5378 2317 -0.95342 -0.0455727 0.0531715 1 0 1 1 0 0 +EDGE2 5378 1517 -1.04673 -0.0476384 0.012313 1 0 1 1 0 0 +EDGE2 5378 1598 -0.00287249 -0.000869226 0.00448438 1 0 1 1 0 0 +EDGE2 5378 2338 0.0124059 0.0314147 -0.0144043 1 0 1 1 0 0 +EDGE2 5378 5358 -0.0633707 0.00683017 -0.0346791 1 0 1 1 0 0 +EDGE2 5378 2358 -0.034885 -0.0320023 0.0108064 1 0 1 1 0 0 +EDGE2 5378 2318 -0.0259527 -0.0220036 0.017847 1 0 1 1 0 0 +EDGE2 5378 2359 1.00355 0.110196 -0.0244874 1 0 1 1 0 0 +EDGE2 5378 1518 -0.0433949 -0.0305439 -0.00623565 1 0 1 1 0 0 +EDGE2 5378 5359 1.05039 -0.0620242 0.0237785 1 0 1 1 0 0 +EDGE2 5378 1599 0.950481 -0.0240117 0.0165206 1 0 1 1 0 0 +EDGE2 5378 2319 1.0266 0.0378071 -0.0119822 1 0 1 1 0 0 +EDGE2 5378 2339 1.05266 0.00339169 -0.0243935 1 0 1 1 0 0 +EDGE2 5378 1519 1.0858 -0.0387229 -0.00117877 1 0 1 1 0 0 +EDGE2 5379 1598 -0.992462 0.0090047 -0.000841282 1 0 1 1 0 0 +EDGE2 5379 2338 -0.978962 0.0311216 0.0188426 1 0 1 1 0 0 +EDGE2 5379 5358 -1.03678 -0.0474759 -0.00304407 1 0 1 1 0 0 +EDGE2 5379 5378 -0.957337 -0.0761488 -0.0468173 1 0 1 1 0 0 +EDGE2 5379 2358 -1.01052 0.0212938 -0.0117363 1 0 1 1 0 0 +EDGE2 5379 2318 -1.01794 0.0693773 0.000491816 1 0 1 1 0 0 +EDGE2 5379 2359 0.0298101 -0.0829444 0.010693 1 0 1 1 0 0 +EDGE2 5379 1518 -1.10652 0.0254041 0.0371291 1 0 1 1 0 0 +EDGE2 5379 5359 -0.0563599 -0.0191084 -0.0164191 1 0 1 1 0 0 +EDGE2 5379 1599 -0.0500799 -0.0467835 -0.0117173 1 0 1 1 0 0 +EDGE2 5379 2319 -0.0361743 -0.0127382 0.0207198 1 0 1 1 0 0 +EDGE2 5379 2339 0.0437922 -0.0173011 0.0156512 1 0 1 1 0 0 +EDGE2 5379 1519 -0.072861 0.060329 -0.0184553 1 0 1 1 0 0 +EDGE2 5379 2340 0.945873 -0.0692758 -0.00956426 1 0 1 1 0 0 +EDGE2 5379 5340 0.923007 -0.0621553 -3.13886 1 0 1 1 0 0 +EDGE2 5379 5360 1.03172 0.05022 0.00486215 1 0 1 1 0 0 +EDGE2 5379 2360 1.03385 -0.0294664 -0.0202934 1 0 1 1 0 0 +EDGE2 5379 1520 0.936471 -0.0669757 0.00225455 1 0 1 1 0 0 +EDGE2 5379 1620 0.992463 -0.0145714 -3.11475 1 0 1 1 0 0 +EDGE2 5379 1640 0.94482 -0.0930656 -3.11213 1 0 1 1 0 0 +EDGE2 5379 2320 1.14701 -0.00948266 0.0274668 1 0 1 1 0 0 +EDGE2 5379 1600 1.02007 -0.0887728 0.00564728 1 0 1 1 0 0 +EDGE2 5379 1320 0.937956 -0.0258119 -3.13025 1 0 1 1 0 0 +EDGE2 5380 2359 -0.998596 -0.0391683 0.0065468 1 0 1 1 0 0 +EDGE2 5380 5379 -1.05031 0.057504 -0.00954899 1 0 1 1 0 0 +EDGE2 5380 5359 -1.00035 -0.106046 -0.00153114 1 0 1 1 0 0 +EDGE2 5380 1599 -0.905951 -0.0183234 0.00951083 1 0 1 1 0 0 +EDGE2 5380 2319 -1.09567 0.01476 0.0102934 1 0 1 1 0 0 +EDGE2 5380 2339 -1.03464 0.000162836 -0.0266865 1 0 1 1 0 0 +EDGE2 5380 1519 -0.972428 0.027913 0.0103344 1 0 1 1 0 0 +EDGE2 5380 2340 0.102804 -0.0407243 0.0244095 1 0 1 1 0 0 +EDGE2 5380 2341 0.0107575 0.975838 1.55948 1 0 1 1 0 0 +EDGE2 5380 5341 0.0693855 1.04524 1.55296 1 0 1 1 0 0 +EDGE2 5380 5361 -0.00580739 0.986102 1.54272 1 0 1 1 0 0 +EDGE2 5380 2361 0.0524973 1.02218 1.5684 1 0 1 1 0 0 +EDGE2 5380 1521 -0.102256 1.02475 1.589 1 0 1 1 0 0 +EDGE2 5380 1641 0.0351536 0.938551 1.53823 1 0 1 1 0 0 +EDGE2 5380 2321 0.0349787 1.02897 1.58006 1 0 1 1 0 0 +EDGE2 5380 1321 -0.0454874 0.994762 1.6076 1 0 1 1 0 0 +EDGE2 5380 5340 -0.102053 0.0943212 -3.14239 1 0 1 1 0 0 +EDGE2 5380 5360 -0.0274215 0.0369206 -0.00354538 1 0 1 1 0 0 +EDGE2 5380 2360 0.0202214 -0.0186182 -0.0111966 1 0 1 1 0 0 +EDGE2 5380 1520 -0.00604149 0.107338 -0.0350406 1 0 1 1 0 0 +EDGE2 5380 1620 -0.0273931 -0.0163203 -3.1524 1 0 1 1 0 0 +EDGE2 5380 1640 0.0273661 -0.0721714 -3.12585 1 0 1 1 0 0 +EDGE2 5380 2320 0.0259309 0.000830157 0.0640315 1 0 1 1 0 0 +EDGE2 5380 1600 0.0290596 -0.00108391 -0.00302994 1 0 1 1 0 0 +EDGE2 5380 1621 0.0186043 -1.03351 -1.59504 1 0 1 1 0 0 +EDGE2 5380 1320 0.0438705 -0.0458444 -3.15911 1 0 1 1 0 0 +EDGE2 5380 1601 -0.10336 -1.04383 -1.58756 1 0 1 1 0 0 +EDGE2 5380 1619 1.02026 -0.0571368 -3.11024 1 0 1 1 0 0 +EDGE2 5380 5339 1.0205 -0.00765046 -3.16377 1 0 1 1 0 0 +EDGE2 5380 1639 0.957285 0.069726 -3.15964 1 0 1 1 0 0 +EDGE2 5380 1319 0.975734 0.0225974 -3.14675 1 0 1 1 0 0 +EDGE2 5381 2362 0.977311 -0.0277405 -0.0317735 1 0 1 1 0 0 +EDGE2 5381 5362 1.01778 0.0486752 0.00177587 1 0 1 1 0 0 +EDGE2 5381 5342 0.855652 0.0428036 -0.00547327 1 0 1 1 0 0 +EDGE2 5381 2340 -0.994421 0.0751384 -1.58054 1 0 1 1 0 0 +EDGE2 5381 2341 0.00145953 -0.00972709 -0.0381828 1 0 1 1 0 0 +EDGE2 5381 1322 1.07071 -0.0230373 0.0178733 1 0 1 1 0 0 +EDGE2 5381 1642 1.00826 0.0244349 -0.00141606 1 0 1 1 0 0 +EDGE2 5381 2322 1.02317 -0.00558993 0.00583982 1 0 1 1 0 0 +EDGE2 5381 2342 1.02638 -0.0445605 -0.0192383 1 0 1 1 0 0 +EDGE2 5381 1522 0.928605 -0.0693192 -0.00669247 1 0 1 1 0 0 +EDGE2 5381 5341 0.0148978 -0.134862 -0.0206095 1 0 1 1 0 0 +EDGE2 5381 5361 -0.0158826 0.15074 0.00282831 1 0 1 1 0 0 +EDGE2 5381 2361 -0.0145256 -0.0282707 -0.0235816 1 0 1 1 0 0 +EDGE2 5381 1521 -0.0188167 -0.0464306 0.025745 1 0 1 1 0 0 +EDGE2 5381 1641 0.0136011 0.0063898 0.0147784 1 0 1 1 0 0 +EDGE2 5381 2321 -0.0885164 -0.037667 0.0184805 1 0 1 1 0 0 +EDGE2 5381 1321 0.063523 -0.0299658 0.0237851 1 0 1 1 0 0 +EDGE2 5381 5340 -1.06397 -0.0420594 1.61649 1 0 1 1 0 0 +EDGE2 5381 5360 -0.933594 -0.0489196 -1.56706 1 0 1 1 0 0 +EDGE2 5381 5380 -1.08363 0.0197235 -1.56591 1 0 1 1 0 0 +EDGE2 5381 2360 -1.0141 0.0584497 -1.56633 1 0 1 1 0 0 +EDGE2 5381 1520 -1.0002 0.0292542 -1.59527 1 0 1 1 0 0 +EDGE2 5381 1620 -1.00122 0.0150803 1.59797 1 0 1 1 0 0 +EDGE2 5381 1640 -0.997017 0.0648595 1.54207 1 0 1 1 0 0 +EDGE2 5381 2320 -0.885279 -0.0952512 -1.55358 1 0 1 1 0 0 +EDGE2 5381 1600 -0.962448 -0.0362441 -1.56924 1 0 1 1 0 0 +EDGE2 5381 1320 -0.970914 0.0356549 1.58123 1 0 1 1 0 0 +EDGE2 5382 2362 -0.0719594 -0.0455718 0.022223 1 0 1 1 0 0 +EDGE2 5382 2363 1.00542 0.0170518 0.00491183 1 0 1 1 0 0 +EDGE2 5382 5363 1.02828 0.00910491 0.0031332 1 0 1 1 0 0 +EDGE2 5382 5343 1.01504 -0.0155525 -0.0100911 1 0 1 1 0 0 +EDGE2 5382 1323 0.917031 -0.0624645 -0.04426 1 0 1 1 0 0 +EDGE2 5382 1643 0.975888 0.0304843 0.0151099 1 0 1 1 0 0 +EDGE2 5382 2323 0.8812 -0.0290106 -0.014651 1 0 1 1 0 0 +EDGE2 5382 2343 1.0718 -0.0216448 0.0531463 1 0 1 1 0 0 +EDGE2 5382 1523 1.05406 -0.00946532 0.00664071 1 0 1 1 0 0 +EDGE2 5382 5362 -0.00166035 -0.0102716 -0.0132704 1 0 1 1 0 0 +EDGE2 5382 5342 -0.0407332 -0.00033835 -0.0123124 1 0 1 1 0 0 +EDGE2 5382 2341 -1.07786 0.0448338 0.0242719 1 0 1 1 0 0 +EDGE2 5382 1322 -0.0543211 0.0186288 0.00384142 1 0 1 1 0 0 +EDGE2 5382 1642 -0.0470967 0.00822529 0.0184088 1 0 1 1 0 0 +EDGE2 5382 2322 0.0560536 0.0321259 -0.0300988 1 0 1 1 0 0 +EDGE2 5382 2342 0.0891583 0.0265525 0.00865958 1 0 1 1 0 0 +EDGE2 5382 1522 -0.0665503 0.0491131 0.0115563 1 0 1 1 0 0 +EDGE2 5382 5341 -1.0637 0.0644248 -0.00286528 1 0 1 1 0 0 +EDGE2 5382 5361 -1.00029 -0.068855 -0.0358155 1 0 1 1 0 0 +EDGE2 5382 5381 -1.03505 -0.014539 -0.00853172 1 0 1 1 0 0 +EDGE2 5382 2361 -1.01489 -0.0276851 -0.0151011 1 0 1 1 0 0 +EDGE2 5382 1521 -0.971786 -0.00486622 0.00639985 1 0 1 1 0 0 +EDGE2 5382 1641 -0.934499 0.0747835 0.0243199 1 0 1 1 0 0 +EDGE2 5382 2321 -0.976092 -0.00196249 0.00921403 1 0 1 1 0 0 +EDGE2 5382 1321 -1.06174 0.0572589 -0.00655372 1 0 1 1 0 0 +EDGE2 5383 2362 -1.05105 0.0485108 -0.00144314 1 0 1 1 0 0 +EDGE2 5383 5344 0.96423 0.057781 -0.00934649 1 0 1 1 0 0 +EDGE2 5383 5364 1.08341 -0.00302272 0.00457146 1 0 1 1 0 0 +EDGE2 5383 2363 0.00966934 0.0153532 0.0116527 1 0 1 1 0 0 +EDGE2 5383 1524 1.07136 -0.0389583 0.00310028 1 0 1 1 0 0 +EDGE2 5383 2324 1.00945 0.0179411 -0.0147605 1 0 1 1 0 0 +EDGE2 5383 2344 1.03515 -0.0551869 0.0129549 1 0 1 1 0 0 +EDGE2 5383 2364 0.960652 0.0105488 -0.0104192 1 0 1 1 0 0 +EDGE2 5383 1644 1.04801 -0.0142855 0.00222251 1 0 1 1 0 0 +EDGE2 5383 5363 -0.0191681 0.028986 0.0380413 1 0 1 1 0 0 +EDGE2 5383 1324 1.028 -0.012194 0.00608409 1 0 1 1 0 0 +EDGE2 5383 5343 -0.0236052 0.0436206 0.0104083 1 0 1 1 0 0 +EDGE2 5383 1323 0.060152 -0.0762135 0.00262977 1 0 1 1 0 0 +EDGE2 5383 1643 -0.011638 0.0264142 0.015338 1 0 1 1 0 0 +EDGE2 5383 2323 0.0626443 -0.0108746 -0.0366882 1 0 1 1 0 0 +EDGE2 5383 2343 -0.0510707 0.04845 0.00971872 1 0 1 1 0 0 +EDGE2 5383 1523 0.0059705 -0.0204694 -0.00508087 1 0 1 1 0 0 +EDGE2 5383 5362 -1.03641 -0.0327592 0.0160668 1 0 1 1 0 0 +EDGE2 5383 5382 -0.962343 0.00339346 -0.0103023 1 0 1 1 0 0 +EDGE2 5383 5342 -0.989604 -0.080394 -0.0211222 1 0 1 1 0 0 +EDGE2 5383 1322 -0.977767 0.0967516 0.0104453 1 0 1 1 0 0 +EDGE2 5383 1642 -0.946854 -0.0655408 0.0113646 1 0 1 1 0 0 +EDGE2 5383 2322 -1.02903 0.0226353 -0.00691024 1 0 1 1 0 0 +EDGE2 5383 2342 -1.02441 0.0650267 0.0287615 1 0 1 1 0 0 +EDGE2 5383 1522 -0.949727 -0.0412545 -0.0209508 1 0 1 1 0 0 +EDGE2 5384 1345 1.00357 -0.104825 -3.11459 1 0 1 1 0 0 +EDGE2 5384 2345 0.991607 0.105609 0.00317874 1 0 1 1 0 0 +EDGE2 5384 5345 0.986171 0.0158019 -0.00612154 1 0 1 1 0 0 +EDGE2 5384 5365 0.928667 -0.0589028 -0.00582912 1 0 1 1 0 0 +EDGE2 5384 2365 0.987405 -0.0109466 -0.0220939 1 0 1 1 0 0 +EDGE2 5384 1525 0.922722 0.0484064 -0.00466996 1 0 1 1 0 0 +EDGE2 5384 1905 0.969927 -0.0423314 -3.15463 1 0 1 1 0 0 +EDGE2 5384 1925 0.908728 -0.00430183 -3.11964 1 0 1 1 0 0 +EDGE2 5384 2325 0.946169 0.0485748 0.00619398 1 0 1 1 0 0 +EDGE2 5384 1645 0.925343 0.0142856 -0.0456973 1 0 1 1 0 0 +EDGE2 5384 1485 0.971356 -0.0489337 -3.16793 1 0 1 1 0 0 +EDGE2 5384 1505 1.00249 -0.0190707 -3.16334 1 0 1 1 0 0 +EDGE2 5384 1365 0.910314 -0.0431523 -3.15624 1 0 1 1 0 0 +EDGE2 5384 5344 0.0225766 0.00433746 -0.0230981 1 0 1 1 0 0 +EDGE2 5384 1325 1.10693 0.0277272 0.0232675 1 0 1 1 0 0 +EDGE2 5384 5364 -0.00352991 -0.0320999 -0.0185271 1 0 1 1 0 0 +EDGE2 5384 2363 -0.994083 -0.0353573 -0.0340797 1 0 1 1 0 0 +EDGE2 5384 1524 0.0282529 0.0110104 -0.00558727 1 0 1 1 0 0 +EDGE2 5384 2324 0.0741638 0.00243274 0.0448841 1 0 1 1 0 0 +EDGE2 5384 2344 0.0280979 -0.0726156 0.00500759 1 0 1 1 0 0 +EDGE2 5384 2364 0.0503073 -0.0349491 0.0474187 1 0 1 1 0 0 +EDGE2 5384 1644 0.0293693 -0.0694055 -0.0113368 1 0 1 1 0 0 +EDGE2 5384 5363 -0.876059 -0.0377995 0.00338708 1 0 1 1 0 0 +EDGE2 5384 5383 -1.05071 -0.0360215 -0.000202049 1 0 1 1 0 0 +EDGE2 5384 1324 0.0087857 0.064123 0.00883426 1 0 1 1 0 0 +EDGE2 5384 5343 -1.07594 0.00119152 0.01144 1 0 1 1 0 0 +EDGE2 5384 1323 -1.08112 0.0133315 -0.00550755 1 0 1 1 0 0 +EDGE2 5384 1643 -1.0695 0.00228457 -0.000721593 1 0 1 1 0 0 +EDGE2 5384 2323 -1.00507 0.045613 0.0181851 1 0 1 1 0 0 +EDGE2 5384 2343 -0.997943 -0.107144 -0.00978583 1 0 1 1 0 0 +EDGE2 5384 1523 -0.942808 -0.000492437 0.0315951 1 0 1 1 0 0 +EDGE2 5385 1345 -0.0406884 0.00718108 -3.12855 1 0 1 1 0 0 +EDGE2 5385 1526 -0.0459203 1.00923 1.5807 1 0 1 1 0 0 +EDGE2 5385 2366 -0.00822839 1.10415 1.58439 1 0 1 1 0 0 +EDGE2 5385 5366 -0.00981531 0.978229 1.57085 1 0 1 1 0 0 +EDGE2 5385 5346 -0.000654894 0.993518 1.5694 1 0 1 1 0 0 +EDGE2 5385 1926 0.0159347 1.07895 1.579 1 0 1 1 0 0 +EDGE2 5385 2326 -0.0341124 1.05274 1.55983 1 0 1 1 0 0 +EDGE2 5385 2346 0.0718128 0.940271 1.57099 1 0 1 1 0 0 +EDGE2 5385 1646 0.031656 0.993367 1.55286 1 0 1 1 0 0 +EDGE2 5385 1366 0.0285668 1.00396 1.55772 1 0 1 1 0 0 +EDGE2 5385 1506 -0.0106352 1.00826 1.54012 1 0 1 1 0 0 +EDGE2 5385 1924 1.02774 -0.0252946 -3.14828 1 0 1 1 0 0 +EDGE2 5385 2345 -0.0304486 -0.000801431 -0.0181521 1 0 1 1 0 0 +EDGE2 5385 1344 1.03375 0.0489477 -3.1576 1 0 1 1 0 0 +EDGE2 5385 1484 1.02676 0.0102019 -3.13596 1 0 1 1 0 0 +EDGE2 5385 1504 1.09016 -0.130698 -3.1225 1 0 1 1 0 0 +EDGE2 5385 1904 1.09005 0.0260254 -3.1779 1 0 1 1 0 0 +EDGE2 5385 1364 0.958964 -0.000715422 -3.147 1 0 1 1 0 0 +EDGE2 5385 5345 0.0314723 -0.00212031 -0.00742547 1 0 1 1 0 0 +EDGE2 5385 5365 0.124938 0.0140355 0.00597465 1 0 1 1 0 0 +EDGE2 5385 2365 0.00480156 0.00336195 0.024882 1 0 1 1 0 0 +EDGE2 5385 1525 -0.0336229 -0.101643 -0.0215129 1 0 1 1 0 0 +EDGE2 5385 1905 0.0645616 -0.0874834 -3.12328 1 0 1 1 0 0 +EDGE2 5385 1925 -0.020847 -0.111881 -3.1455 1 0 1 1 0 0 +EDGE2 5385 2325 -0.0870894 -0.029347 -0.0102002 1 0 1 1 0 0 +EDGE2 5385 1645 0.0677486 -0.0514887 0.0109839 1 0 1 1 0 0 +EDGE2 5385 1485 -0.0193338 -0.0200747 -3.09645 1 0 1 1 0 0 +EDGE2 5385 1505 0.0146533 0.105991 -3.15196 1 0 1 1 0 0 +EDGE2 5385 1365 -0.00583889 0.032219 -3.16116 1 0 1 1 0 0 +EDGE2 5385 5344 -0.962523 -0.0177952 0.0139765 1 0 1 1 0 0 +EDGE2 5385 5384 -0.949974 -0.0739125 -0.00575307 1 0 1 1 0 0 +EDGE2 5385 1325 -0.00979188 0.0248315 -0.0179131 1 0 1 1 0 0 +EDGE2 5385 5364 -0.951348 -0.0574795 0.00179691 1 0 1 1 0 0 +EDGE2 5385 1524 -0.948386 -0.037491 0.00753438 1 0 1 1 0 0 +EDGE2 5385 2324 -0.919763 -0.029582 -0.02169 1 0 1 1 0 0 +EDGE2 5385 2344 -1.01566 -0.0779474 0.0130951 1 0 1 1 0 0 +EDGE2 5385 2364 -1.09942 0.0633928 0.0134777 1 0 1 1 0 0 +EDGE2 5385 1644 -1.04527 -0.0818039 -0.0374168 1 0 1 1 0 0 +EDGE2 5385 1324 -1.05363 -0.0230907 -0.00448872 1 0 1 1 0 0 +EDGE2 5385 1486 0.0903857 -1.03571 -1.55554 1 0 1 1 0 0 +EDGE2 5385 1906 -0.0383615 -1.01357 -1.61139 1 0 1 1 0 0 +EDGE2 5385 1326 -0.0211799 -0.97734 -1.5486 1 0 1 1 0 0 +EDGE2 5385 1346 0.0115057 -1.06013 -1.5815 1 0 1 1 0 0 +EDGE2 5386 2327 1.14762 -0.028168 0.0055663 1 0 1 1 0 0 +EDGE2 5386 5367 1.04059 -0.0469751 -0.0102745 1 0 1 1 0 0 +EDGE2 5386 2367 1.06675 0.082197 -0.00879869 1 0 1 1 0 0 +EDGE2 5386 5347 0.962 0.012956 0.0172141 1 0 1 1 0 0 +EDGE2 5386 2347 1.1508 -0.0450091 0.00225478 1 0 1 1 0 0 +EDGE2 5386 1345 -0.949452 0.0196536 1.57299 1 0 1 1 0 0 +EDGE2 5386 1526 -0.0844426 -0.0529126 0.0229077 1 0 1 1 0 0 +EDGE2 5386 1507 1.03702 0.102116 0.00596117 1 0 1 1 0 0 +EDGE2 5386 1527 1.08545 -0.0344761 0.00547458 1 0 1 1 0 0 +EDGE2 5386 1647 1.02439 0.00455512 0.00594459 1 0 1 1 0 0 +EDGE2 5386 1927 0.95451 0.103269 4.05e-05 1 0 1 1 0 0 +EDGE2 5386 2366 0.0642814 -0.00155624 -0.00975739 1 0 1 1 0 0 +EDGE2 5386 5366 0.0937568 0.0564423 0.00906872 1 0 1 1 0 0 +EDGE2 5386 1367 0.987141 -0.0699428 0.0188173 1 0 1 1 0 0 +EDGE2 5386 5346 -0.111369 -0.0326771 -0.000709324 1 0 1 1 0 0 +EDGE2 5386 1926 -0.0205283 0.0334173 0.0339719 1 0 1 1 0 0 +EDGE2 5386 2326 0.0868368 -0.04604 -0.00402147 1 0 1 1 0 0 +EDGE2 5386 2346 0.0293061 0.0434111 0.0186071 1 0 1 1 0 0 +EDGE2 5386 1646 -0.00801728 0.0245179 0.0504347 1 0 1 1 0 0 +EDGE2 5386 1366 0.0409461 0.0496528 0.0456079 1 0 1 1 0 0 +EDGE2 5386 1506 0.0662201 -0.008574 -0.0100142 1 0 1 1 0 0 +EDGE2 5386 2345 -0.98404 -0.0681202 -1.55986 1 0 1 1 0 0 +EDGE2 5386 5345 -0.986775 0.0359105 -1.56212 1 0 1 1 0 0 +EDGE2 5386 5365 -1.01863 -0.0389436 -1.58472 1 0 1 1 0 0 +EDGE2 5386 5385 -0.954306 0.0567722 -1.60566 1 0 1 1 0 0 +EDGE2 5386 2365 -0.92253 -0.000297521 -1.55908 1 0 1 1 0 0 +EDGE2 5386 1525 -1.03098 -0.0358211 -1.60345 1 0 1 1 0 0 +EDGE2 5386 1905 -1.03421 0.00576021 1.57068 1 0 1 1 0 0 +EDGE2 5386 1925 -1.02825 -0.0670675 1.54896 1 0 1 1 0 0 +EDGE2 5386 2325 -0.98998 -0.0173681 -1.58693 1 0 1 1 0 0 +EDGE2 5386 1645 -0.924489 0.0156166 -1.55761 1 0 1 1 0 0 +EDGE2 5386 1485 -1.01016 0.111983 1.50965 1 0 1 1 0 0 +EDGE2 5386 1505 -1.04996 0.0261894 1.54438 1 0 1 1 0 0 +EDGE2 5386 1365 -0.899744 0.0318822 1.59298 1 0 1 1 0 0 +EDGE2 5386 1325 -1.00293 0.10684 -1.56099 1 0 1 1 0 0 +EDGE2 5387 2327 0.0289194 -0.050319 -0.0171595 1 0 1 1 0 0 +EDGE2 5387 2368 0.962549 -0.0619913 -0.00342439 1 0 1 1 0 0 +EDGE2 5387 5368 0.993478 0.0550334 0.0235418 1 0 1 1 0 0 +EDGE2 5387 5348 0.96374 0.0567366 -0.0254888 1 0 1 1 0 0 +EDGE2 5387 1648 0.949998 0.0383322 0.0245456 1 0 1 1 0 0 +EDGE2 5387 1928 0.9781 0.0340132 0.00940418 1 0 1 1 0 0 +EDGE2 5387 2328 1.09702 0.0207711 0.0138097 1 0 1 1 0 0 +EDGE2 5387 2348 0.926606 -0.0454093 -0.0326546 1 0 1 1 0 0 +EDGE2 5387 5367 -0.0228233 -0.0920764 0.0118955 1 0 1 1 0 0 +EDGE2 5387 1368 0.922925 -0.0986051 -0.0302764 1 0 1 1 0 0 +EDGE2 5387 1508 0.997891 -0.00751425 -0.0131198 1 0 1 1 0 0 +EDGE2 5387 1528 0.988543 -0.0539664 -0.0151375 1 0 1 1 0 0 +EDGE2 5387 2367 0.000280607 0.00279059 -0.0256537 1 0 1 1 0 0 +EDGE2 5387 5347 0.0673341 -0.0345888 -0.0106328 1 0 1 1 0 0 +EDGE2 5387 2347 0.0559903 -0.037831 -0.00740047 1 0 1 1 0 0 +EDGE2 5387 1526 -0.994004 -0.0225687 -0.00431556 1 0 1 1 0 0 +EDGE2 5387 1507 0.00511843 0.012221 0.0114699 1 0 1 1 0 0 +EDGE2 5387 1527 -0.0424671 0.0114205 -0.013932 1 0 1 1 0 0 +EDGE2 5387 1647 -0.0406799 -0.105054 0.0249231 1 0 1 1 0 0 +EDGE2 5387 1927 0.0196041 0.0730834 -0.0303918 1 0 1 1 0 0 +EDGE2 5387 2366 -0.997357 5.27284e-06 0.0359233 1 0 1 1 0 0 +EDGE2 5387 5366 -0.989865 0.0188653 -0.0114505 1 0 1 1 0 0 +EDGE2 5387 5386 -1.06587 -0.102751 -0.012698 1 0 1 1 0 0 +EDGE2 5387 1367 -0.0929655 -0.0519818 -0.011015 1 0 1 1 0 0 +EDGE2 5387 5346 -0.95723 0.0440364 -0.00445496 1 0 1 1 0 0 +EDGE2 5387 1926 -1.0747 -0.0878364 -0.017231 1 0 1 1 0 0 +EDGE2 5387 2326 -0.987607 -0.0136999 -0.00458329 1 0 1 1 0 0 +EDGE2 5387 2346 -0.994812 0.0924209 -0.0224436 1 0 1 1 0 0 +EDGE2 5387 1646 -1.03347 -0.0341574 -0.0236177 1 0 1 1 0 0 +EDGE2 5387 1366 -0.937823 0.00206448 0.0206632 1 0 1 1 0 0 +EDGE2 5387 1506 -0.999766 0.0242402 0.0230975 1 0 1 1 0 0 +EDGE2 5388 2327 -1.04121 0.0780187 0.00246141 1 0 1 1 0 0 +EDGE2 5388 2368 -0.0549633 0.00482458 -0.0115523 1 0 1 1 0 0 +EDGE2 5388 2349 0.921383 -0.0625506 -0.0177086 1 0 1 1 0 0 +EDGE2 5388 2369 1.00847 -0.0159582 0.00234112 1 0 1 1 0 0 +EDGE2 5388 5349 1.00439 0.0265655 0.0499728 1 0 1 1 0 0 +EDGE2 5388 5369 0.986154 0.0442585 0.00416004 1 0 1 1 0 0 +EDGE2 5388 1509 1.06435 -0.0718113 0.0317374 1 0 1 1 0 0 +EDGE2 5388 1649 0.960682 -0.0399688 -0.0155258 1 0 1 1 0 0 +EDGE2 5388 1929 1.07081 0.0793682 0.00845634 1 0 1 1 0 0 +EDGE2 5388 2329 1.01366 0.0138715 0.00380429 1 0 1 1 0 0 +EDGE2 5388 1529 0.952383 0.0181584 -0.0357118 1 0 1 1 0 0 +EDGE2 5388 5368 -0.0665363 -0.00158504 0.0291344 1 0 1 1 0 0 +EDGE2 5388 1369 1.03648 -0.0271606 -0.0226111 1 0 1 1 0 0 +EDGE2 5388 5348 0.0384263 0.00381396 -0.0136907 1 0 1 1 0 0 +EDGE2 5388 1648 0.0500428 0.0536868 -0.0186496 1 0 1 1 0 0 +EDGE2 5388 1928 -0.0653453 -0.00349385 -0.00652102 1 0 1 1 0 0 +EDGE2 5388 2328 -0.12888 -0.0618969 -0.0327036 1 0 1 1 0 0 +EDGE2 5388 2348 -0.0621425 0.0450238 0.00358278 1 0 1 1 0 0 +EDGE2 5388 5367 -1.03416 0.0612964 -0.0186151 1 0 1 1 0 0 +EDGE2 5388 1368 0.0394376 -0.0455173 -0.0425332 1 0 1 1 0 0 +EDGE2 5388 1508 -0.0516621 -0.0807584 0.0356445 1 0 1 1 0 0 +EDGE2 5388 1528 -0.0309069 -0.0267082 -0.00363879 1 0 1 1 0 0 +EDGE2 5388 5387 -0.957567 0.0165681 0.0231029 1 0 1 1 0 0 +EDGE2 5388 2367 -0.964573 0.0348651 0.00515612 1 0 1 1 0 0 +EDGE2 5388 5347 -1.06377 0.0419403 -0.0295911 1 0 1 1 0 0 +EDGE2 5388 2347 -1.04625 -0.00931585 -0.00136332 1 0 1 1 0 0 +EDGE2 5388 1507 -0.987155 -0.0893718 -0.00320914 1 0 1 1 0 0 +EDGE2 5388 1527 -0.97526 0.0102698 -0.00502906 1 0 1 1 0 0 +EDGE2 5388 1647 -0.978897 -0.0174487 -0.0242072 1 0 1 1 0 0 +EDGE2 5388 1927 -1.02848 -0.0132865 -0.0121398 1 0 1 1 0 0 +EDGE2 5388 1367 -1.10384 -0.0238206 0.0308433 1 0 1 1 0 0 +EDGE2 5389 2330 1.00726 -0.0365549 -0.00718722 1 0 1 1 0 0 +EDGE2 5389 2370 1.01309 -0.0179365 -0.0409601 1 0 1 1 0 0 +EDGE2 5389 5350 1.00758 0.0232013 -0.0248606 1 0 1 1 0 0 +EDGE2 5389 5370 0.98085 -0.0861822 0.027359 1 0 1 1 0 0 +EDGE2 5389 2350 0.94396 0.00186778 -0.0186777 1 0 1 1 0 0 +EDGE2 5389 1650 0.95508 -0.0163451 -0.0105013 1 0 1 1 0 0 +EDGE2 5389 1710 1.00949 -0.0739619 -3.16964 1 0 1 1 0 0 +EDGE2 5389 1870 1.00658 -0.0476385 -3.11639 1 0 1 1 0 0 +EDGE2 5389 1930 1.04319 0.0195467 0.0165042 1 0 1 1 0 0 +EDGE2 5389 1670 0.98436 0.0203557 -3.14491 1 0 1 1 0 0 +EDGE2 5389 1470 0.952366 0.0900795 -3.16164 1 0 1 1 0 0 +EDGE2 5389 1510 0.958651 -0.00866436 0.0140727 1 0 1 1 0 0 +EDGE2 5389 1530 0.938067 -0.096103 -0.0463982 1 0 1 1 0 0 +EDGE2 5389 1370 0.914187 -0.0142208 0.00380623 1 0 1 1 0 0 +EDGE2 5389 2368 -1.00006 -0.00124967 -0.00132428 1 0 1 1 0 0 +EDGE2 5389 2349 -0.0806719 0.0499602 0.0221298 1 0 1 1 0 0 +EDGE2 5389 2369 -0.0797521 -0.0453102 0.00452744 1 0 1 1 0 0 +EDGE2 5389 5349 0.0158135 -0.00403368 -0.0199813 1 0 1 1 0 0 +EDGE2 5389 5369 -0.0223829 -0.0270661 0.00641421 1 0 1 1 0 0 +EDGE2 5389 1509 0.0101149 0.0429345 0.0250201 1 0 1 1 0 0 +EDGE2 5389 1649 0.0710341 0.045251 0.0454135 1 0 1 1 0 0 +EDGE2 5389 1929 0.0556361 -0.104701 0.0140233 1 0 1 1 0 0 +EDGE2 5389 2329 -0.00411552 -0.00235391 -0.0214766 1 0 1 1 0 0 +EDGE2 5389 1529 -0.0897408 -0.0509125 -0.0335604 1 0 1 1 0 0 +EDGE2 5389 5368 -0.954411 0.0345975 -0.00797469 1 0 1 1 0 0 +EDGE2 5389 5388 -0.990705 0.0349651 -0.00533277 1 0 1 1 0 0 +EDGE2 5389 1369 0.0205423 0.0253178 0.0171334 1 0 1 1 0 0 +EDGE2 5389 5348 -0.951947 -0.0242378 0.0192561 1 0 1 1 0 0 +EDGE2 5389 1648 -0.946232 0.0269337 -0.0157878 1 0 1 1 0 0 +EDGE2 5389 1928 -0.958183 -0.0737606 0.0163339 1 0 1 1 0 0 +EDGE2 5389 2328 -1.02851 0.0834673 -0.0178426 1 0 1 1 0 0 +EDGE2 5389 2348 -1.006 0.0490912 0.00564315 1 0 1 1 0 0 +EDGE2 5389 1368 -1.05862 0.0411833 -0.00807301 1 0 1 1 0 0 +EDGE2 5389 1508 -0.982388 -0.0134519 -0.0169808 1 0 1 1 0 0 +EDGE2 5389 1528 -0.941261 0.0433259 -0.0105569 1 0 1 1 0 0 +EDGE2 5390 1931 0.0692339 -1.03334 -1.55473 1 0 1 1 0 0 +EDGE2 5390 1669 1.04824 0.0456495 -3.17277 1 0 1 1 0 0 +EDGE2 5390 1709 0.994933 0.0476244 -3.13424 1 0 1 1 0 0 +EDGE2 5390 1869 1.0177 -0.0119963 -3.15548 1 0 1 1 0 0 +EDGE2 5390 1469 0.965537 -0.0792103 -3.14826 1 0 1 1 0 0 +EDGE2 5390 5389 -1.10665 -0.0508952 0.0122686 1 0 1 1 0 0 +EDGE2 5390 2330 0.0534368 -0.0474575 0.00939185 1 0 1 1 0 0 +EDGE2 5390 1671 0.0129079 -1.04021 -1.54039 1 0 1 1 0 0 +EDGE2 5390 1711 -0.0493043 -0.976513 -1.57184 1 0 1 1 0 0 +EDGE2 5390 1871 0.00832695 -1.04622 -1.58808 1 0 1 1 0 0 +EDGE2 5390 1471 -0.119487 -0.996065 -1.56514 1 0 1 1 0 0 +EDGE2 5390 2370 0.0432371 -0.0785377 -0.00555088 1 0 1 1 0 0 +EDGE2 5390 5350 0.0438305 -0.0779977 0.0111695 1 0 1 1 0 0 +EDGE2 5390 5370 0.0279202 0.0578459 0.0299615 1 0 1 1 0 0 +EDGE2 5390 2350 0.0395627 -0.000959066 -0.0207997 1 0 1 1 0 0 +EDGE2 5390 1650 0.0465829 -0.00671539 0.0184663 1 0 1 1 0 0 +EDGE2 5390 1710 -0.100988 0.0870941 -3.10838 1 0 1 1 0 0 +EDGE2 5390 1870 -0.0272708 0.047273 -3.15956 1 0 1 1 0 0 +EDGE2 5390 1930 -0.100648 -0.0653369 -0.0186994 1 0 1 1 0 0 +EDGE2 5390 1670 -0.0268383 0.0137648 -3.16015 1 0 1 1 0 0 +EDGE2 5390 1470 0.0602105 0.020017 -3.15111 1 0 1 1 0 0 +EDGE2 5390 1510 0.0644924 -0.0368572 0.00502658 1 0 1 1 0 0 +EDGE2 5390 1530 0.00509467 -0.0557276 0.0152155 1 0 1 1 0 0 +EDGE2 5390 1370 -0.0207109 -0.0252389 0.00600299 1 0 1 1 0 0 +EDGE2 5390 2351 -0.0533817 1.09458 1.56162 1 0 1 1 0 0 +EDGE2 5390 2371 -0.0571825 1.04754 1.57663 1 0 1 1 0 0 +EDGE2 5390 5351 0.022661 1.02212 1.57255 1 0 1 1 0 0 +EDGE2 5390 5371 -0.0234047 0.991508 1.58603 1 0 1 1 0 0 +EDGE2 5390 1371 0.0184692 0.945336 1.54274 1 0 1 1 0 0 +EDGE2 5390 1531 0.0818086 0.952726 1.60409 1 0 1 1 0 0 +EDGE2 5390 1651 -0.0373282 0.955917 1.54464 1 0 1 1 0 0 +EDGE2 5390 2331 0.0612524 0.988307 1.57059 1 0 1 1 0 0 +EDGE2 5390 1511 -0.101062 1.03209 1.59622 1 0 1 1 0 0 +EDGE2 5390 2349 -0.970963 -0.0759875 0.0174224 1 0 1 1 0 0 +EDGE2 5390 2369 -1.02173 -0.00551162 0.0177798 1 0 1 1 0 0 +EDGE2 5390 5349 -0.906108 0.0632247 0.0334431 1 0 1 1 0 0 +EDGE2 5390 5369 -0.977444 0.0621201 -0.0346341 1 0 1 1 0 0 +EDGE2 5390 1509 -0.996604 -0.0735249 -0.00643219 1 0 1 1 0 0 +EDGE2 5390 1649 -0.971603 0.0360086 0.0201071 1 0 1 1 0 0 +EDGE2 5390 1929 -0.979206 -0.0217054 -0.000474786 1 0 1 1 0 0 +EDGE2 5390 2329 -0.926688 0.0110054 -0.00819091 1 0 1 1 0 0 +EDGE2 5390 1529 -0.984666 -0.00645658 0.0142318 1 0 1 1 0 0 +EDGE2 5390 1369 -0.913601 -0.108997 -0.0174142 1 0 1 1 0 0 +EDGE2 5391 2372 0.941439 -0.0130494 0.0110051 1 0 1 1 0 0 +EDGE2 5391 2330 -0.985413 0.0587254 -1.58558 1 0 1 1 0 0 +EDGE2 5391 5390 -1.0084 0.00913387 -1.5733 1 0 1 1 0 0 +EDGE2 5391 2370 -0.994384 -0.0104588 -1.60042 1 0 1 1 0 0 +EDGE2 5391 5350 -1.08545 0.060493 -1.55402 1 0 1 1 0 0 +EDGE2 5391 5370 -0.940274 0.0382486 -1.57377 1 0 1 1 0 0 +EDGE2 5391 2350 -0.959533 -0.0742545 -1.55779 1 0 1 1 0 0 +EDGE2 5391 1650 -0.928542 0.0165836 -1.54921 1 0 1 1 0 0 +EDGE2 5391 1710 -1.05178 0.0506082 1.57101 1 0 1 1 0 0 +EDGE2 5391 1870 -1.03167 0.0561093 1.5736 1 0 1 1 0 0 +EDGE2 5391 1930 -0.905085 0.0397874 -1.57026 1 0 1 1 0 0 +EDGE2 5391 1670 -0.857423 0.018833 1.57167 1 0 1 1 0 0 +EDGE2 5391 1470 -1.01601 -0.00303885 1.5881 1 0 1 1 0 0 +EDGE2 5391 1510 -0.99579 -0.0420962 -1.57172 1 0 1 1 0 0 +EDGE2 5391 1530 -0.972742 0.0124999 -1.54811 1 0 1 1 0 0 +EDGE2 5391 1370 -1.03844 -0.00611205 -1.54303 1 0 1 1 0 0 +EDGE2 5391 2351 0.0456505 0.0372468 -0.0151036 1 0 1 1 0 0 +EDGE2 5391 2371 -0.0133722 -0.00148171 0.0183716 1 0 1 1 0 0 +EDGE2 5391 5351 0.0625158 0.0282998 0.0248177 1 0 1 1 0 0 +EDGE2 5391 5371 0.0578674 -0.0682092 0.0358391 1 0 1 1 0 0 +EDGE2 5391 1371 -0.0475181 -0.0219341 -0.0193661 1 0 1 1 0 0 +EDGE2 5391 1531 0.0433982 0.0160996 -0.0175361 1 0 1 1 0 0 +EDGE2 5391 1651 -0.0389015 -0.0209113 0.00145985 1 0 1 1 0 0 +EDGE2 5391 2331 0.0912862 -0.01961 -0.0189467 1 0 1 1 0 0 +EDGE2 5391 1511 -0.0525871 -0.00536794 -0.0180614 1 0 1 1 0 0 +EDGE2 5391 5372 0.951561 -0.00488104 -0.0284624 1 0 1 1 0 0 +EDGE2 5391 5352 0.994971 -0.00710416 0.00395197 1 0 1 1 0 0 +EDGE2 5391 1512 0.987179 -0.0678187 -0.00768119 1 0 1 1 0 0 +EDGE2 5391 1652 1.03075 -0.147016 0.0116684 1 0 1 1 0 0 +EDGE2 5391 2332 1.0766 -0.0782949 -0.0041423 1 0 1 1 0 0 +EDGE2 5391 2352 1.06158 0.0504777 0.0279741 1 0 1 1 0 0 +EDGE2 5391 1532 0.997553 -0.067936 0.045338 1 0 1 1 0 0 +EDGE2 5391 1372 0.94612 0.0527257 -0.00941106 1 0 1 1 0 0 +EDGE2 5392 2372 0.0430753 -0.0470021 -0.0379162 1 0 1 1 0 0 +EDGE2 5392 5391 -0.989078 -0.0242059 0.0447307 1 0 1 1 0 0 +EDGE2 5392 2351 -1.02045 -0.0353008 0.00349541 1 0 1 1 0 0 +EDGE2 5392 2371 -0.986039 -0.0273339 0.00383962 1 0 1 1 0 0 +EDGE2 5392 5351 -0.94731 -0.0527805 0.0214382 1 0 1 1 0 0 +EDGE2 5392 5371 -1.01935 0.0166343 0.031412 1 0 1 1 0 0 +EDGE2 5392 1371 -1.05511 0.00423339 0.0311551 1 0 1 1 0 0 +EDGE2 5392 1531 -0.927055 -0.0202759 -0.0208653 1 0 1 1 0 0 +EDGE2 5392 1651 -1.04805 0.089461 -0.00497861 1 0 1 1 0 0 +EDGE2 5392 2331 -0.923651 0.0426605 -0.0129864 1 0 1 1 0 0 +EDGE2 5392 1511 -0.953071 0.0301578 -0.011559 1 0 1 1 0 0 +EDGE2 5392 5372 0.0455618 -0.0456715 0.0197528 1 0 1 1 0 0 +EDGE2 5392 5352 -0.0100228 -0.0615239 0.0243523 1 0 1 1 0 0 +EDGE2 5392 2373 1.04608 0.0377357 0.0143017 1 0 1 1 0 0 +EDGE2 5392 1512 -0.0257688 0.026496 0.00890313 1 0 1 1 0 0 +EDGE2 5392 1652 -0.0436198 -0.00156798 0.0168884 1 0 1 1 0 0 +EDGE2 5392 2332 0.019034 -0.0907843 0.00213182 1 0 1 1 0 0 +EDGE2 5392 2352 0.0151096 0.023569 -0.0470584 1 0 1 1 0 0 +EDGE2 5392 1532 0.144072 0.0406794 -0.0043203 1 0 1 1 0 0 +EDGE2 5392 5373 1.06751 -0.0279543 0.0225583 1 0 1 1 0 0 +EDGE2 5392 1372 -0.0207526 -0.0538255 -0.0171064 1 0 1 1 0 0 +EDGE2 5392 5353 0.995251 0.0164652 -0.0138704 1 0 1 1 0 0 +EDGE2 5392 1513 1.02255 -0.022285 -0.0380475 1 0 1 1 0 0 +EDGE2 5392 1653 0.994306 0.0806588 -0.00190413 1 0 1 1 0 0 +EDGE2 5392 2333 1.05108 -0.0648789 -0.0501657 1 0 1 1 0 0 +EDGE2 5392 2353 1.03331 -0.000995595 0.0111126 1 0 1 1 0 0 +EDGE2 5392 1533 0.929992 0.0591797 -0.0443862 1 0 1 1 0 0 +EDGE2 5392 1373 1.07809 -0.066186 0.0115511 1 0 1 1 0 0 +EDGE2 5393 2372 -1.03564 0.153485 -0.00815326 1 0 1 1 0 0 +EDGE2 5393 5372 -0.988585 -0.000902528 -0.00253367 1 0 1 1 0 0 +EDGE2 5393 5392 -1.11279 0.0224147 0.0196208 1 0 1 1 0 0 +EDGE2 5393 5352 -1.00113 -0.0209774 -0.00441266 1 0 1 1 0 0 +EDGE2 5393 2374 1.005 0.0192514 0.0158409 1 0 1 1 0 0 +EDGE2 5393 2373 0.0548551 -0.0267689 -0.00606824 1 0 1 1 0 0 +EDGE2 5393 1512 -1.00848 0.0850422 0.0167852 1 0 1 1 0 0 +EDGE2 5393 1652 -1.01635 0.0325127 0.0166589 1 0 1 1 0 0 +EDGE2 5393 2332 -0.955568 0.0617191 -0.0145973 1 0 1 1 0 0 +EDGE2 5393 2352 -1.02581 0.00644252 0.0180507 1 0 1 1 0 0 +EDGE2 5393 1532 -1.01132 -0.0181886 -0.0226967 1 0 1 1 0 0 +EDGE2 5393 5373 0.0502351 0.0083302 -0.0327945 1 0 1 1 0 0 +EDGE2 5393 1372 -1.0195 -0.0177282 -0.0179731 1 0 1 1 0 0 +EDGE2 5393 5353 -0.0884052 -0.0631798 -0.000669015 1 0 1 1 0 0 +EDGE2 5393 1513 -0.0445577 -0.0113639 -0.000555161 1 0 1 1 0 0 +EDGE2 5393 1653 -0.0281227 0.0441505 -0.0251619 1 0 1 1 0 0 +EDGE2 5393 2333 0.0702913 -0.0275702 0.018072 1 0 1 1 0 0 +EDGE2 5393 2353 0.0681139 -0.0384282 -0.0362287 1 0 1 1 0 0 +EDGE2 5393 1533 0.130069 -0.0159242 -0.00102126 1 0 1 1 0 0 +EDGE2 5393 5374 1.04968 -0.0712812 -0.00788087 1 0 1 1 0 0 +EDGE2 5393 1373 -0.043832 -0.0629042 0.0274906 1 0 1 1 0 0 +EDGE2 5393 5354 1.02141 -0.0766201 -0.0194738 1 0 1 1 0 0 +EDGE2 5393 1514 0.942554 0.00175538 0.00346191 1 0 1 1 0 0 +EDGE2 5393 1654 0.915452 0.0205627 0.0082032 1 0 1 1 0 0 +EDGE2 5393 2334 1.04313 0.0571311 -0.00174165 1 0 1 1 0 0 +EDGE2 5393 2354 0.930633 0.0464181 0.0181815 1 0 1 1 0 0 +EDGE2 5393 1534 1.05293 -0.0818679 -0.00210443 1 0 1 1 0 0 +EDGE2 5393 1374 1.00278 -0.038629 -0.0145462 1 0 1 1 0 0 +EDGE2 5394 1535 1.03635 0.0326146 0.0269694 1 0 1 1 0 0 +EDGE2 5394 2374 0.0102069 0.0774466 0.00174891 1 0 1 1 0 0 +EDGE2 5394 2373 -1.06009 -0.0456261 0.00272586 1 0 1 1 0 0 +EDGE2 5394 5373 -1.02178 -0.0779211 -0.0293029 1 0 1 1 0 0 +EDGE2 5394 5393 -0.994534 0.0288138 0.00294814 1 0 1 1 0 0 +EDGE2 5394 5353 -0.946923 0.0105763 0.0208669 1 0 1 1 0 0 +EDGE2 5394 1513 -0.9926 -0.0127022 -0.0109955 1 0 1 1 0 0 +EDGE2 5394 1653 -0.936503 0.0178909 0.0048712 1 0 1 1 0 0 +EDGE2 5394 2333 -0.995891 0.0593776 -0.0489188 1 0 1 1 0 0 +EDGE2 5394 2353 -1.05241 0.0618142 -0.00754486 1 0 1 1 0 0 +EDGE2 5394 1533 -1.05941 0.0180312 -0.00130029 1 0 1 1 0 0 +EDGE2 5394 5374 -0.0479243 -0.0417373 -0.0436946 1 0 1 1 0 0 +EDGE2 5394 1373 -1.06417 0.0576434 0.0282243 1 0 1 1 0 0 +EDGE2 5394 5354 -0.0287752 -0.0334299 0.0144069 1 0 1 1 0 0 +EDGE2 5394 2395 0.931239 0.0351971 -3.14375 1 0 1 1 0 0 +EDGE2 5394 1514 -0.0301378 0.017105 0.00425313 1 0 1 1 0 0 +EDGE2 5394 1654 -0.0243464 -0.0852024 0.0322068 1 0 1 1 0 0 +EDGE2 5394 2334 -0.0661709 -0.0537079 0.0432861 1 0 1 1 0 0 +EDGE2 5394 2354 0.0165155 0.0153282 0.00984351 1 0 1 1 0 0 +EDGE2 5394 1534 -0.180804 0.0138 0.00878481 1 0 1 1 0 0 +EDGE2 5394 5375 0.938608 -0.015265 -0.0041289 1 0 1 1 0 0 +EDGE2 5394 1374 -0.0348782 0.0135623 -0.0446869 1 0 1 1 0 0 +EDGE2 5394 5355 0.955174 0.0224126 -0.000541589 1 0 1 1 0 0 +EDGE2 5394 1855 1.03039 -0.0538023 -3.15179 1 0 1 1 0 0 +EDGE2 5394 2335 1.07073 -0.0117675 0.0181976 1 0 1 1 0 0 +EDGE2 5394 2355 1.02772 -0.102491 0.0135225 1 0 1 1 0 0 +EDGE2 5394 2375 0.935493 -0.0365585 -0.0214734 1 0 1 1 0 0 +EDGE2 5394 2315 0.990407 -0.159573 -3.15455 1 0 1 1 0 0 +EDGE2 5394 1595 1.08057 -0.0162525 -3.10445 1 0 1 1 0 0 +EDGE2 5394 1655 0.924908 -0.0506459 0.0416982 1 0 1 1 0 0 +EDGE2 5394 1575 1.01144 0.0675967 -3.14265 1 0 1 1 0 0 +EDGE2 5394 1375 0.895173 0.0360413 -0.000976872 1 0 1 1 0 0 +EDGE2 5394 1515 0.992283 0.01362 -0.00396769 1 0 1 1 0 0 +EDGE2 5395 1656 -0.070514 -1.00855 -1.53662 1 0 1 1 0 0 +EDGE2 5395 2376 0.0507438 -1.02595 -1.52594 1 0 1 1 0 0 +EDGE2 5395 2396 0.0123959 -1.05203 -1.56666 1 0 1 1 0 0 +EDGE2 5395 1856 0.0136978 -0.948291 -1.57392 1 0 1 1 0 0 +EDGE2 5395 1536 0.0731835 -0.937619 -1.53754 1 0 1 1 0 0 +EDGE2 5395 1576 -0.0514509 -0.986472 -1.57118 1 0 1 1 0 0 +EDGE2 5395 1376 0.0533525 -1.04947 -1.57371 1 0 1 1 0 0 +EDGE2 5395 1535 -0.0776144 0.0235289 0.00785671 1 0 1 1 0 0 +EDGE2 5395 2374 -0.943677 -0.0225044 0.0202258 1 0 1 1 0 0 +EDGE2 5395 5374 -1.03885 -0.0609933 -0.0113195 1 0 1 1 0 0 +EDGE2 5395 5394 -1.07187 0.000725489 -0.02601 1 0 1 1 0 0 +EDGE2 5395 5354 -0.969301 0.0266868 -0.00706839 1 0 1 1 0 0 +EDGE2 5395 2395 0.00992991 -0.0621558 -3.14443 1 0 1 1 0 0 +EDGE2 5395 1514 -0.948352 -0.042172 0.00304784 1 0 1 1 0 0 +EDGE2 5395 1654 -1.03543 -0.0297606 -0.0264753 1 0 1 1 0 0 +EDGE2 5395 2334 -1.00817 0.0189999 0.026335 1 0 1 1 0 0 +EDGE2 5395 2354 -0.972358 -0.034661 0.0189718 1 0 1 1 0 0 +EDGE2 5395 1534 -0.976007 0.0467966 0.0091167 1 0 1 1 0 0 +EDGE2 5395 5375 0.0279272 -0.0255741 0.00621802 1 0 1 1 0 0 +EDGE2 5395 1374 -1.07007 -0.0380188 -0.00673796 1 0 1 1 0 0 +EDGE2 5395 5355 0.0445484 0.114134 0.0014098 1 0 1 1 0 0 +EDGE2 5395 1855 0.00538859 0.0119298 -3.16717 1 0 1 1 0 0 +EDGE2 5395 2335 0.0656455 0.0224346 -0.00355905 1 0 1 1 0 0 +EDGE2 5395 2355 -0.112442 0.0256775 -0.00460394 1 0 1 1 0 0 +EDGE2 5395 2375 -0.0377192 0.0437342 0.0012477 1 0 1 1 0 0 +EDGE2 5395 2315 -0.00334114 -0.0204348 -3.12796 1 0 1 1 0 0 +EDGE2 5395 1595 0.0359866 -0.0319758 -3.17844 1 0 1 1 0 0 +EDGE2 5395 1655 0.0552311 -0.0281289 0.00815067 1 0 1 1 0 0 +EDGE2 5395 1575 -0.0655326 0.0452107 -3.12706 1 0 1 1 0 0 +EDGE2 5395 1854 0.997464 0.0212994 -3.1721 1 0 1 1 0 0 +EDGE2 5395 2394 1.03186 0.016185 -3.14172 1 0 1 1 0 0 +EDGE2 5395 1375 -0.0130901 -0.0549777 -0.0464949 1 0 1 1 0 0 +EDGE2 5395 1515 0.00552928 -0.00738838 -0.0196107 1 0 1 1 0 0 +EDGE2 5395 2314 0.933166 0.0601769 -3.14099 1 0 1 1 0 0 +EDGE2 5395 1574 1.03153 0.0586105 -3.13953 1 0 1 1 0 0 +EDGE2 5395 1594 1.02763 0.00649188 -3.16196 1 0 1 1 0 0 +EDGE2 5395 2336 0.0443863 1.00251 1.56737 1 0 1 1 0 0 +EDGE2 5395 5356 0.0163114 1.06235 1.56157 1 0 1 1 0 0 +EDGE2 5395 5376 -0.0104097 1.00453 1.56679 1 0 1 1 0 0 +EDGE2 5395 2356 0.0349487 1.04112 1.56242 1 0 1 1 0 0 +EDGE2 5395 1516 0.0434176 1.08508 1.56442 1 0 1 1 0 0 +EDGE2 5395 1596 0.0359862 1.01328 1.60272 1 0 1 1 0 0 +EDGE2 5395 2316 0.0311364 1.07804 1.56707 1 0 1 1 0 0 +EDGE2 5396 1535 -0.952284 0.043923 -1.57234 1 0 1 1 0 0 +EDGE2 5396 2395 -1.00219 0.0365751 1.5901 1 0 1 1 0 0 +EDGE2 5396 5375 -0.953981 -0.0337396 -1.57083 1 0 1 1 0 0 +EDGE2 5396 5395 -1.03487 0.0162629 -1.58184 1 0 1 1 0 0 +EDGE2 5396 5355 -0.963161 -0.00878575 -1.5697 1 0 1 1 0 0 +EDGE2 5396 1855 -0.954845 -0.00898898 1.57572 1 0 1 1 0 0 +EDGE2 5396 2335 -1.06591 0.0518231 -1.57822 1 0 1 1 0 0 +EDGE2 5396 2355 -1.00407 0.0670932 -1.5458 1 0 1 1 0 0 +EDGE2 5396 2375 -1.00024 0.0447549 -1.55034 1 0 1 1 0 0 +EDGE2 5396 2315 -1.04257 -0.0126054 1.57522 1 0 1 1 0 0 +EDGE2 5396 1595 -1.07038 -0.0194759 1.55286 1 0 1 1 0 0 +EDGE2 5396 1655 -1.0075 0.00859539 -1.55926 1 0 1 1 0 0 +EDGE2 5396 1575 -1.08523 0.0163639 1.57834 1 0 1 1 0 0 +EDGE2 5396 1375 -1.01134 -0.0114293 -1.64063 1 0 1 1 0 0 +EDGE2 5396 1515 -0.990612 0.022579 -1.57207 1 0 1 1 0 0 +EDGE2 5396 5377 1.00323 0.0539504 -0.00991954 1 0 1 1 0 0 +EDGE2 5396 2336 -0.0538211 0.0165316 -0.018757 1 0 1 1 0 0 +EDGE2 5396 5356 0.0201409 -0.0643102 -0.00426798 1 0 1 1 0 0 +EDGE2 5396 5376 0.00874696 0.0454177 -0.00460857 1 0 1 1 0 0 +EDGE2 5396 2356 -0.0362106 -0.0923601 0.0191913 1 0 1 1 0 0 +EDGE2 5396 1516 -0.011532 -0.00180324 -0.0261901 1 0 1 1 0 0 +EDGE2 5396 1596 0.0221726 0.0279755 0.00760815 1 0 1 1 0 0 +EDGE2 5396 2316 0.0311105 0.0171519 0.0184904 1 0 1 1 0 0 +EDGE2 5396 2337 1.06405 -0.0154825 0.00502002 1 0 1 1 0 0 +EDGE2 5396 5357 1.02569 0.0134622 0.0159815 1 0 1 1 0 0 +EDGE2 5396 2357 0.944466 0.0369313 -0.0238109 1 0 1 1 0 0 +EDGE2 5396 1597 0.941326 -0.0380778 -0.00820912 1 0 1 1 0 0 +EDGE2 5396 2317 1.07825 -0.0634712 -0.0123864 1 0 1 1 0 0 +EDGE2 5396 1517 1.00945 0.101911 -0.0404915 1 0 1 1 0 0 +EDGE2 5397 5377 0.0270495 0.020674 -0.0251906 1 0 1 1 0 0 +EDGE2 5397 2336 -0.938065 0.0561263 -0.00749805 1 0 1 1 0 0 +EDGE2 5397 5356 -1.02051 -0.0941486 0.00649721 1 0 1 1 0 0 +EDGE2 5397 5376 -0.999803 -0.00455639 0.00969898 1 0 1 1 0 0 +EDGE2 5397 5396 -1.02417 0.00830701 0.0493248 1 0 1 1 0 0 +EDGE2 5397 2356 -0.964348 0.0842162 -0.0192496 1 0 1 1 0 0 +EDGE2 5397 1516 -1.01057 -0.0532497 -0.00152558 1 0 1 1 0 0 +EDGE2 5397 1596 -0.955491 -0.0699495 -0.0056211 1 0 1 1 0 0 +EDGE2 5397 2316 -1.02411 -0.064092 0.0172595 1 0 1 1 0 0 +EDGE2 5397 2337 -0.00903335 -0.0352947 -0.00272709 1 0 1 1 0 0 +EDGE2 5397 5357 -0.0102698 0.0800752 -0.00149421 1 0 1 1 0 0 +EDGE2 5397 2357 -0.0774431 0.00470639 -0.00636975 1 0 1 1 0 0 +EDGE2 5397 1597 -0.0336895 -0.0403188 0.0122774 1 0 1 1 0 0 +EDGE2 5397 2317 -0.11771 -0.0208824 -0.0205328 1 0 1 1 0 0 +EDGE2 5397 1517 -0.00334388 -0.00792987 -0.0153175 1 0 1 1 0 0 +EDGE2 5397 1598 0.96886 -0.0040406 0.0222056 1 0 1 1 0 0 +EDGE2 5397 2338 1.024 -0.0294288 0.0115821 1 0 1 1 0 0 +EDGE2 5397 5358 0.991598 0.000500414 -0.0103014 1 0 1 1 0 0 +EDGE2 5397 5378 1.0112 0.0160396 -0.0242643 1 0 1 1 0 0 +EDGE2 5397 2358 0.974768 0.0554358 0.0036296 1 0 1 1 0 0 +EDGE2 5397 2318 1.05947 0.116809 -0.0348138 1 0 1 1 0 0 +EDGE2 5397 1518 0.949069 0.0422305 -0.0432081 1 0 1 1 0 0 +EDGE2 5398 5377 -0.944945 -0.0886051 -0.0101065 1 0 1 1 0 0 +EDGE2 5398 5397 -1.01342 0.0604129 -0.00224357 1 0 1 1 0 0 +EDGE2 5398 2337 -0.983882 -0.0459734 0.0125744 1 0 1 1 0 0 +EDGE2 5398 5357 -0.990161 0.0243814 0.0105075 1 0 1 1 0 0 +EDGE2 5398 2357 -0.978847 -0.0267175 0.00634845 1 0 1 1 0 0 +EDGE2 5398 1597 -0.878402 -0.00703667 -0.024468 1 0 1 1 0 0 +EDGE2 5398 2317 -1.00646 -0.00907473 0.0115657 1 0 1 1 0 0 +EDGE2 5398 1517 -1.039 0.0308586 -0.0353454 1 0 1 1 0 0 +EDGE2 5398 1598 -0.0505763 0.00180914 0.00923487 1 0 1 1 0 0 +EDGE2 5398 2338 -0.0611117 0.0701397 0.00672924 1 0 1 1 0 0 +EDGE2 5398 5358 -0.0316829 -0.0659147 0.0104918 1 0 1 1 0 0 +EDGE2 5398 5378 -0.0264498 -0.0422656 0.0141394 1 0 1 1 0 0 +EDGE2 5398 2358 -0.00180477 0.019791 0.014387 1 0 1 1 0 0 +EDGE2 5398 2318 0.065805 -0.0674807 -0.0235677 1 0 1 1 0 0 +EDGE2 5398 2359 1.0249 -0.00202444 -0.0248719 1 0 1 1 0 0 +EDGE2 5398 5379 0.959998 -0.0541198 -0.005409 1 0 1 1 0 0 +EDGE2 5398 1518 0.0375234 -0.0375331 -0.0160445 1 0 1 1 0 0 +EDGE2 5398 5359 1.02068 -0.0393336 0.0184464 1 0 1 1 0 0 +EDGE2 5398 1599 1.05368 -0.0103785 -0.0177344 1 0 1 1 0 0 +EDGE2 5398 2319 1.02299 0.0124215 -0.00249282 1 0 1 1 0 0 +EDGE2 5398 2339 0.922169 0.0169949 0.00101783 1 0 1 1 0 0 +EDGE2 5398 1519 0.964081 -0.01398 0.00542305 1 0 1 1 0 0 +EDGE2 5399 1598 -0.942397 0.0274573 0.0112599 1 0 1 1 0 0 +EDGE2 5399 2338 -0.986422 0.0612077 0.0158203 1 0 1 1 0 0 +EDGE2 5399 5358 -0.991488 -0.031304 0.0136643 1 0 1 1 0 0 +EDGE2 5399 5378 -0.959131 0.0148873 -0.0173064 1 0 1 1 0 0 +EDGE2 5399 5398 -0.960675 0.0382382 -0.0332279 1 0 1 1 0 0 +EDGE2 5399 2358 -0.998213 0.07183 0.0158766 1 0 1 1 0 0 +EDGE2 5399 2318 -0.961072 0.0115947 0.00729964 1 0 1 1 0 0 +EDGE2 5399 2359 -0.0188246 -0.0220473 0.00355688 1 0 1 1 0 0 +EDGE2 5399 5379 0.00692315 -0.0320792 -0.0153231 1 0 1 1 0 0 +EDGE2 5399 1518 -0.911886 0.121127 -0.00909289 1 0 1 1 0 0 +EDGE2 5399 5359 -0.00672033 0.030455 0.00475938 1 0 1 1 0 0 +EDGE2 5399 1599 -0.0160784 -0.054294 0.0086963 1 0 1 1 0 0 +EDGE2 5399 2319 -0.062175 -0.078052 0.00927749 1 0 1 1 0 0 +EDGE2 5399 2339 0.0412553 0.0118441 0.00988264 1 0 1 1 0 0 +EDGE2 5399 1519 0.0470626 -0.0146526 -7.7734e-05 1 0 1 1 0 0 +EDGE2 5399 2340 1.00322 -0.0203667 0.0092585 1 0 1 1 0 0 +EDGE2 5399 5340 0.980486 -0.0139044 -3.13564 1 0 1 1 0 0 +EDGE2 5399 5360 0.996382 0.042625 0.035382 1 0 1 1 0 0 +EDGE2 5399 5380 0.951827 0.0248334 0.0162562 1 0 1 1 0 0 +EDGE2 5399 2360 1.10793 -0.167123 -0.0267767 1 0 1 1 0 0 +EDGE2 5399 1520 0.988034 -0.0473005 -0.0145763 1 0 1 1 0 0 +EDGE2 5399 1620 0.996324 0.0167682 -3.13522 1 0 1 1 0 0 +EDGE2 5399 1640 0.994499 -0.0819293 -3.15187 1 0 1 1 0 0 +EDGE2 5399 2320 1.02916 0.0204253 -0.00449193 1 0 1 1 0 0 +EDGE2 5399 1600 0.96437 0.00279925 0.00542139 1 0 1 1 0 0 +EDGE2 5399 1320 1.01935 0.0120427 -3.17464 1 0 1 1 0 0 +EDGE2 5400 2359 -1.02665 -0.013756 -0.0168077 1 0 1 1 0 0 +EDGE2 5400 5379 -1.05164 -0.00301938 -0.00266513 1 0 1 1 0 0 +EDGE2 5400 5399 -1.06533 -0.0255426 -0.00324243 1 0 1 1 0 0 +EDGE2 5400 5359 -0.999246 -0.117464 0.0189706 1 0 1 1 0 0 +EDGE2 5400 1599 -0.997655 -0.0212593 -0.0242149 1 0 1 1 0 0 +EDGE2 5400 2319 -0.988855 -0.0129426 -0.000372338 1 0 1 1 0 0 +EDGE2 5400 2339 -0.93986 -0.0441136 0.000852906 1 0 1 1 0 0 +EDGE2 5400 1519 -0.980788 -0.0759119 0.0177111 1 0 1 1 0 0 +EDGE2 5400 2340 0.0416878 0.0329029 0.00553129 1 0 1 1 0 0 +EDGE2 5400 2341 -0.019637 0.98639 1.59355 1 0 1 1 0 0 +EDGE2 5400 5341 -0.0445342 0.951909 1.56339 1 0 1 1 0 0 +EDGE2 5400 5361 0.0647433 1.03022 1.58613 1 0 1 1 0 0 +EDGE2 5400 5381 0.0806921 1.02223 1.5651 1 0 1 1 0 0 +EDGE2 5400 2361 0.0555746 0.94534 1.56297 1 0 1 1 0 0 +EDGE2 5400 1521 0.0685429 0.982109 1.5848 1 0 1 1 0 0 +EDGE2 5400 1641 -0.0442961 1.06985 1.55919 1 0 1 1 0 0 +EDGE2 5400 2321 -0.0534192 1.04439 1.53497 1 0 1 1 0 0 +EDGE2 5400 1321 -0.0490728 1.03422 1.57569 1 0 1 1 0 0 +EDGE2 5400 5340 -0.0347118 -0.0725594 -3.1878 1 0 1 1 0 0 +EDGE2 5400 5360 0.0947053 -0.0297503 0.00150423 1 0 1 1 0 0 +EDGE2 5400 5380 0.000341402 -0.0415773 0.0200032 1 0 1 1 0 0 +EDGE2 5400 2360 -0.0629875 0.0659471 0.0191741 1 0 1 1 0 0 +EDGE2 5400 1520 -0.0353598 -0.0281742 -0.0111963 1 0 1 1 0 0 +EDGE2 5400 1620 0.0529941 0.0170786 -3.13212 1 0 1 1 0 0 +EDGE2 5400 1640 -0.0549535 0.00155572 -3.10517 1 0 1 1 0 0 +EDGE2 5400 2320 -0.056545 -0.0180873 -0.00921218 1 0 1 1 0 0 +EDGE2 5400 1600 -0.00619174 0.0521902 0.031199 1 0 1 1 0 0 +EDGE2 5400 1621 0.0229356 -1.00533 -1.55774 1 0 1 1 0 0 +EDGE2 5400 1320 0.0281235 -0.0721511 -3.12953 1 0 1 1 0 0 +EDGE2 5400 1601 0.0440817 -1.03401 -1.54354 1 0 1 1 0 0 +EDGE2 5400 1619 0.952166 -0.0812463 -3.12908 1 0 1 1 0 0 +EDGE2 5400 5339 1.02899 -0.0252782 -3.10032 1 0 1 1 0 0 +EDGE2 5400 1639 1.02573 0.0165644 -3.14468 1 0 1 1 0 0 +EDGE2 5400 1319 1.03301 0.0374597 -3.13135 1 0 1 1 0 0 +EDGE2 5401 2340 -1.00326 0.00970466 1.56028 1 0 1 1 0 0 +EDGE2 5401 5400 -0.977595 -0.0750499 1.56177 1 0 1 1 0 0 +EDGE2 5401 5340 -1.05781 0.0205514 -1.5887 1 0 1 1 0 0 +EDGE2 5401 5360 -1.05422 -0.0736096 1.54586 1 0 1 1 0 0 +EDGE2 5401 5380 -1.03247 -0.0268382 1.56761 1 0 1 1 0 0 +EDGE2 5401 2360 -1.05881 -0.0470404 1.55331 1 0 1 1 0 0 +EDGE2 5401 1520 -0.965873 0.0495535 1.54486 1 0 1 1 0 0 +EDGE2 5401 1620 -0.998432 0.0441501 -1.58853 1 0 1 1 0 0 +EDGE2 5401 1640 -1.05329 -0.0206574 -1.59995 1 0 1 1 0 0 +EDGE2 5401 2320 -1.01801 0.022784 1.55997 1 0 1 1 0 0 +EDGE2 5401 1600 -0.958082 -0.0521398 1.57583 1 0 1 1 0 0 +EDGE2 5401 1621 0.0121032 -0.0960437 -0.0036426 1 0 1 1 0 0 +EDGE2 5401 1320 -1.04363 0.0383038 -1.56176 1 0 1 1 0 0 +EDGE2 5401 1601 -0.0282802 0.0125671 -0.00351111 1 0 1 1 0 0 +EDGE2 5401 1602 1.03763 -0.0510846 0.013333 1 0 1 1 0 0 +EDGE2 5401 1622 1.02475 -0.0702486 -0.0090857 1 0 1 1 0 0 +EDGE2 5402 1621 -1.02336 0.0130041 0.0306808 1 0 1 1 0 0 +EDGE2 5402 5401 -0.959156 -0.0184961 0.0294806 1 0 1 1 0 0 +EDGE2 5402 1601 -1.0262 -0.0585903 -0.0282389 1 0 1 1 0 0 +EDGE2 5402 1603 0.933884 -0.0103621 -0.0142933 1 0 1 1 0 0 +EDGE2 5402 1602 -0.060334 0.0131738 -0.014332 1 0 1 1 0 0 +EDGE2 5402 1622 0.0501321 0.0356553 0.0449516 1 0 1 1 0 0 +EDGE2 5402 1623 1.07805 -0.0252785 -0.00867629 1 0 1 1 0 0 +EDGE2 5403 5402 -0.929441 -0.0720167 0.0158884 1 0 1 1 0 0 +EDGE2 5403 1603 0.0245509 -0.0236336 -0.00401229 1 0 1 1 0 0 +EDGE2 5403 1602 -1.00094 -0.0213714 -0.0311096 1 0 1 1 0 0 +EDGE2 5403 1622 -1.07651 0.0518196 -0.0201021 1 0 1 1 0 0 +EDGE2 5403 1623 -0.0632566 0.0349198 -0.00121538 1 0 1 1 0 0 +EDGE2 5403 1624 1.02292 0.00831696 -0.0101913 1 0 1 1 0 0 +EDGE2 5403 1604 1.00132 -0.11057 -0.0201439 1 0 1 1 0 0 +EDGE2 5404 1603 -0.973397 0.0386099 -0.000453481 1 0 1 1 0 0 +EDGE2 5404 5403 -0.999136 -0.00133667 0.0160327 1 0 1 1 0 0 +EDGE2 5404 1623 -0.896389 0.108446 0.010876 1 0 1 1 0 0 +EDGE2 5404 1624 0.0144108 0.00348982 -0.0227139 1 0 1 1 0 0 +EDGE2 5404 1604 -0.0362392 0.00493834 0.0163866 1 0 1 1 0 0 +EDGE2 5404 1625 0.981078 0.0374315 -0.0210155 1 0 1 1 0 0 +EDGE2 5404 2825 0.9453 0.0441801 -3.1465 1 0 1 1 0 0 +EDGE2 5404 1285 0.988497 -0.0851471 -3.14152 1 0 1 1 0 0 +EDGE2 5404 1305 0.909507 0.0124646 -3.13165 1 0 1 1 0 0 +EDGE2 5404 1605 1.07956 -0.0619554 0.00327326 1 0 1 1 0 0 +EDGE2 5405 1624 -1.01754 -0.0348546 0.0149957 1 0 1 1 0 0 +EDGE2 5405 5404 -1.05487 0.0171116 0.0223963 1 0 1 1 0 0 +EDGE2 5405 1604 -0.939346 0.0499743 -0.0184388 1 0 1 1 0 0 +EDGE2 5405 1304 0.991621 0.0417019 -3.13515 1 0 1 1 0 0 +EDGE2 5405 1625 0.0438567 -0.0205923 -0.00164275 1 0 1 1 0 0 +EDGE2 5405 1286 -0.0623724 -1.09397 -1.57726 1 0 1 1 0 0 +EDGE2 5405 2826 -0.00112308 -1.05655 -1.57642 1 0 1 1 0 0 +EDGE2 5405 2825 0.0904826 -0.00286734 -3.16237 1 0 1 1 0 0 +EDGE2 5405 1285 0.0684938 0.0466001 -3.14295 1 0 1 1 0 0 +EDGE2 5405 1305 -0.0110881 0.0227488 -3.1259 1 0 1 1 0 0 +EDGE2 5405 1605 0.0894126 -0.0158131 -0.0224322 1 0 1 1 0 0 +EDGE2 5405 2824 1.10658 0.028924 -3.11742 1 0 1 1 0 0 +EDGE2 5405 1284 1.05468 0.0280364 -3.09246 1 0 1 1 0 0 +EDGE2 5405 1606 0.0589226 1.05045 1.56907 1 0 1 1 0 0 +EDGE2 5405 1626 -0.0715311 1.02843 1.58143 1 0 1 1 0 0 +EDGE2 5405 1306 0.0221975 0.942843 1.58804 1 0 1 1 0 0 +EDGE2 5406 1625 -1.04588 0.0263747 -1.59768 1 0 1 1 0 0 +EDGE2 5406 5405 -0.96459 -0.0192677 -1.55955 1 0 1 1 0 0 +EDGE2 5406 2825 -1.00961 0.119119 1.58175 1 0 1 1 0 0 +EDGE2 5406 1285 -0.922393 0.0242603 1.59371 1 0 1 1 0 0 +EDGE2 5406 1305 -1.04607 -0.0297663 1.53031 1 0 1 1 0 0 +EDGE2 5406 1605 -0.985611 -0.0999906 -1.575 1 0 1 1 0 0 +EDGE2 5406 1606 -0.0340824 0.00326921 -0.0232981 1 0 1 1 0 0 +EDGE2 5406 1626 -0.0176266 -0.0565867 0.014137 1 0 1 1 0 0 +EDGE2 5406 1306 -0.0922191 0.00310107 -0.0227803 1 0 1 1 0 0 +EDGE2 5406 1607 1.04281 -0.0627108 0.0129475 1 0 1 1 0 0 +EDGE2 5406 1627 0.991199 -0.0395906 -0.0151295 1 0 1 1 0 0 +EDGE2 5406 1307 0.957181 0.0592944 -0.0127387 1 0 1 1 0 0 +EDGE2 5407 1606 -1.04707 0.0374918 0.0143511 1 0 1 1 0 0 +EDGE2 5407 1626 -1.00075 -0.0473341 -0.0156439 1 0 1 1 0 0 +EDGE2 5407 5406 -0.955763 0.00650336 -0.0398195 1 0 1 1 0 0 +EDGE2 5407 1306 -0.920536 -0.0624047 -0.00205914 1 0 1 1 0 0 +EDGE2 5407 1607 -0.0587574 0.0250962 -0.02042 1 0 1 1 0 0 +EDGE2 5407 1627 -0.0202638 -0.0168523 -0.0119343 1 0 1 1 0 0 +EDGE2 5407 1307 -0.0360428 -0.00125152 0.0117844 1 0 1 1 0 0 +EDGE2 5407 1308 1.0167 -0.0180987 0.0299799 1 0 1 1 0 0 +EDGE2 5407 1608 1.00806 0.0333388 -0.019174 1 0 1 1 0 0 +EDGE2 5407 1628 1.03753 0.0424254 -0.0349354 1 0 1 1 0 0 +EDGE2 5408 1607 -1.064 0.0722172 -0.0124749 1 0 1 1 0 0 +EDGE2 5408 1627 -0.966777 -0.0259059 0.0301404 1 0 1 1 0 0 +EDGE2 5408 5407 -0.992856 0.00307657 -0.0158033 1 0 1 1 0 0 +EDGE2 5408 1307 -0.970388 0.0412962 -0.0204461 1 0 1 1 0 0 +EDGE2 5408 1609 0.987427 0.0449009 -0.00318623 1 0 1 1 0 0 +EDGE2 5408 1629 0.947899 -0.0327702 -0.0112666 1 0 1 1 0 0 +EDGE2 5408 1308 -0.00306005 0.0463696 0.0143658 1 0 1 1 0 0 +EDGE2 5408 1608 -0.0856292 -0.0630517 -0.016565 1 0 1 1 0 0 +EDGE2 5408 1628 -0.00491978 0.012692 0.00988128 1 0 1 1 0 0 +EDGE2 5408 1309 1.00664 -0.0466696 0.00570758 1 0 1 1 0 0 +EDGE2 5409 5408 -0.97268 -0.0426527 -0.00375082 1 0 1 1 0 0 +EDGE2 5409 1609 -0.00648202 0.00516753 0.00110205 1 0 1 1 0 0 +EDGE2 5409 1629 -0.00115333 -0.0388592 0.00921125 1 0 1 1 0 0 +EDGE2 5409 1308 -1.02576 -0.0523702 0.0380065 1 0 1 1 0 0 +EDGE2 5409 1608 -1.02528 0.0684429 -0.00011862 1 0 1 1 0 0 +EDGE2 5409 1628 -1.10112 -0.108188 -0.0255099 1 0 1 1 0 0 +EDGE2 5409 1309 -0.0134828 0.0150983 -0.0214084 1 0 1 1 0 0 +EDGE2 5409 1610 1.05662 -0.014702 -0.0318027 1 0 1 1 0 0 +EDGE2 5409 1630 0.981594 0.0371573 0.00942239 1 0 1 1 0 0 +EDGE2 5409 4730 1.01152 -0.0527845 -3.14611 1 0 1 1 0 0 +EDGE2 5409 1310 1.01673 -0.0319595 -0.0209196 1 0 1 1 0 0 +EDGE2 5410 1609 -1.03018 -0.049806 -0.0152039 1 0 1 1 0 0 +EDGE2 5410 1629 -0.985234 0.0721728 -0.00507816 1 0 1 1 0 0 +EDGE2 5410 5409 -0.963373 -0.000351033 -0.0105658 1 0 1 1 0 0 +EDGE2 5410 1309 -1.04355 -0.033949 0.0160619 1 0 1 1 0 0 +EDGE2 5410 1611 -0.0527178 1.05864 1.56374 1 0 1 1 0 0 +EDGE2 5410 1631 -0.0469522 1.01778 1.57371 1 0 1 1 0 0 +EDGE2 5410 1311 -0.0101708 1.02349 1.58748 1 0 1 1 0 0 +EDGE2 5410 1610 0.0315281 0.046684 0.039845 1 0 1 1 0 0 +EDGE2 5410 1630 0.0286542 0.0483341 -0.0190485 1 0 1 1 0 0 +EDGE2 5410 4730 0.0183394 0.0356573 -3.12148 1 0 1 1 0 0 +EDGE2 5410 1310 0.0403126 -0.051123 -0.0212879 1 0 1 1 0 0 +EDGE2 5410 4731 0.00518712 -0.987184 -1.57716 1 0 1 1 0 0 +EDGE2 5410 4729 0.996147 -0.0107015 -3.12616 1 0 1 1 0 0 +EDGE2 5411 5410 -1.059 -0.0564007 1.59591 1 0 1 1 0 0 +EDGE2 5411 1610 -1.00919 0.0142786 1.59903 1 0 1 1 0 0 +EDGE2 5411 1630 -1.00019 0.0294524 1.56001 1 0 1 1 0 0 +EDGE2 5411 4730 -0.911436 -0.0197211 -1.57506 1 0 1 1 0 0 +EDGE2 5411 1310 -0.968074 0.0672575 1.54151 1 0 1 1 0 0 +EDGE2 5411 4731 -0.0101917 0.0154056 0.0105459 1 0 1 1 0 0 +EDGE2 5411 4732 0.968731 0.0194712 -0.00145278 1 0 1 1 0 0 +EDGE2 5412 5411 -0.977521 -0.0480169 -0.0339337 1 0 1 1 0 0 +EDGE2 5412 4731 -0.949333 -0.0820209 0.00732675 1 0 1 1 0 0 +EDGE2 5412 4732 -0.0831765 -0.0751291 -0.0117558 1 0 1 1 0 0 +EDGE2 5412 4733 0.984229 -0.0147422 -0.00381469 1 0 1 1 0 0 +EDGE2 5413 5412 -1.02499 0.0114428 0.0140115 1 0 1 1 0 0 +EDGE2 5413 4732 -0.997065 -0.0336231 0.00444516 1 0 1 1 0 0 +EDGE2 5413 4734 0.954655 0.00784651 -0.0148028 1 0 1 1 0 0 +EDGE2 5413 4733 -0.0100053 -0.0173299 -0.0282377 1 0 1 1 0 0 +EDGE2 5414 5413 -0.984727 -0.0642826 0.043859 1 0 1 1 0 0 +EDGE2 5414 2815 0.97464 -0.0236546 -3.13039 1 0 1 1 0 0 +EDGE2 5414 4755 1.0743 0.0703007 -3.16958 1 0 1 1 0 0 +EDGE2 5414 4734 0.057002 -0.0198711 -0.0062492 1 0 1 1 0 0 +EDGE2 5414 4733 -1.01244 0.00642179 -0.0136103 1 0 1 1 0 0 +EDGE2 5414 4735 1.01263 -0.100287 -0.00970681 1 0 1 1 0 0 +EDGE2 5414 2795 0.96993 0.00263152 -3.1437 1 0 1 1 0 0 +EDGE2 5415 2816 -0.066199 -1.04627 -1.60112 1 0 1 1 0 0 +EDGE2 5415 4736 0.0686398 -1.07765 -1.57298 1 0 1 1 0 0 +EDGE2 5415 2796 -0.0188894 -0.986869 -1.59321 1 0 1 1 0 0 +EDGE2 5415 2815 0.0155639 0.0192469 -3.15068 1 0 1 1 0 0 +EDGE2 5415 4755 0.0596601 -0.0196872 -3.12255 1 0 1 1 0 0 +EDGE2 5415 4734 -1.02333 -0.0339782 0.0470931 1 0 1 1 0 0 +EDGE2 5415 5414 -1.04516 0.114297 -0.0329902 1 0 1 1 0 0 +EDGE2 5415 4735 0.0405564 0.028506 -0.00607157 1 0 1 1 0 0 +EDGE2 5415 2814 1.04022 -0.00882296 -3.15847 1 0 1 1 0 0 +EDGE2 5415 4754 1.01805 -0.0304171 -3.12046 1 0 1 1 0 0 +EDGE2 5415 2795 0.0058093 -0.00830125 -3.13843 1 0 1 1 0 0 +EDGE2 5415 2794 1.05026 3.20481e-05 -3.13997 1 0 1 1 0 0 +EDGE2 5415 4756 0.0280315 1.02022 1.54077 1 0 1 1 0 0 +EDGE2 5416 2817 1.00724 -0.00601852 0.0221078 1 0 1 1 0 0 +EDGE2 5416 4737 1.0306 -0.0683043 0.0132656 1 0 1 1 0 0 +EDGE2 5416 2797 1.00861 -0.0363852 0.0191468 1 0 1 1 0 0 +EDGE2 5416 2816 0.0429674 0.050846 -0.0205601 1 0 1 1 0 0 +EDGE2 5416 4736 -0.0773627 -0.00789371 0.0271777 1 0 1 1 0 0 +EDGE2 5416 2796 0.0647175 -0.0720713 0.0135735 1 0 1 1 0 0 +EDGE2 5416 2815 -0.961503 0.0305534 -1.55109 1 0 1 1 0 0 +EDGE2 5416 4755 -1.05103 0.00897858 -1.59403 1 0 1 1 0 0 +EDGE2 5416 5415 -0.997801 -0.00391264 1.57041 1 0 1 1 0 0 +EDGE2 5416 4735 -0.959191 -0.0858682 1.60329 1 0 1 1 0 0 +EDGE2 5416 2795 -0.952358 -0.00558599 -1.50809 1 0 1 1 0 0 +EDGE2 5417 2818 0.961453 0.00296786 0.0162288 1 0 1 1 0 0 +EDGE2 5417 4738 0.950161 -0.0356381 0.000252749 1 0 1 1 0 0 +EDGE2 5417 2798 0.986381 0.0832466 -0.0289533 1 0 1 1 0 0 +EDGE2 5417 2817 0.0351268 0.0590825 -0.036233 1 0 1 1 0 0 +EDGE2 5417 4737 -0.00800105 0.0176666 -0.0197289 1 0 1 1 0 0 +EDGE2 5417 2797 0.0324646 -0.0237468 0.00455161 1 0 1 1 0 0 +EDGE2 5417 2816 -1.05331 -0.0268668 -0.00720458 1 0 1 1 0 0 +EDGE2 5417 4736 -1.07684 0.0197692 -0.023483 1 0 1 1 0 0 +EDGE2 5417 5416 -1.01962 -0.0122862 -0.00758178 1 0 1 1 0 0 +EDGE2 5417 2796 -0.962385 0.0244412 0.000587186 1 0 1 1 0 0 +EDGE2 5418 4739 0.965375 -0.0827722 0.0389549 1 0 1 1 0 0 +EDGE2 5418 2819 1.01249 -0.0487291 -0.024726 1 0 1 1 0 0 +EDGE2 5418 2799 1.11051 0.00352816 0.00812978 1 0 1 1 0 0 +EDGE2 5418 2818 0.112813 -0.0324857 -0.00519175 1 0 1 1 0 0 +EDGE2 5418 4738 -0.111667 0.0250539 0.00479094 1 0 1 1 0 0 +EDGE2 5418 2798 0.0347212 0.0305451 0.0216296 1 0 1 1 0 0 +EDGE2 5418 2817 -0.887541 0.0111987 -0.0107618 1 0 1 1 0 0 +EDGE2 5418 4737 -1.07022 -0.104331 -0.00133461 1 0 1 1 0 0 +EDGE2 5418 5417 -1.02239 -0.00471423 0.0160664 1 0 1 1 0 0 +EDGE2 5418 2797 -0.96098 -0.0529076 -0.0101276 1 0 1 1 0 0 +EDGE2 5419 2840 0.998874 0.0894485 -3.15211 1 0 1 1 0 0 +EDGE2 5419 4740 0.99356 0.00583716 0.00979887 1 0 1 1 0 0 +EDGE2 5419 1300 1.05433 0.0483541 -3.13833 1 0 1 1 0 0 +EDGE2 5419 2800 1.10523 -0.0214268 0.00358608 1 0 1 1 0 0 +EDGE2 5419 2820 1.01002 -0.0230495 -0.0051397 1 0 1 1 0 0 +EDGE2 5419 1280 1.01445 0.0298459 -3.15634 1 0 1 1 0 0 +EDGE2 5419 4739 0.0128327 -0.0655237 -0.00691055 1 0 1 1 0 0 +EDGE2 5419 5418 -0.990489 -0.0933816 0.0186366 1 0 1 1 0 0 +EDGE2 5419 2819 -0.0832475 0.0110345 0.00507658 1 0 1 1 0 0 +EDGE2 5419 2799 0.108825 -0.0146113 0.0397798 1 0 1 1 0 0 +EDGE2 5419 2818 -0.894913 0.0401279 0.0279174 1 0 1 1 0 0 +EDGE2 5419 4738 -1.10159 0.0475769 4.31262e-05 1 0 1 1 0 0 +EDGE2 5419 2798 -0.962618 0.00714425 0.0259643 1 0 1 1 0 0 +EDGE2 5420 1299 1.04155 -0.0571981 -3.13178 1 0 1 1 0 0 +EDGE2 5420 2839 0.953833 -0.022711 -3.14693 1 0 1 1 0 0 +EDGE2 5420 1279 1.04468 0.0777033 -3.13258 1 0 1 1 0 0 +EDGE2 5420 2840 0.00278034 0.0350471 -3.15833 1 0 1 1 0 0 +EDGE2 5420 2821 0.00171427 -1.02994 -1.5587 1 0 1 1 0 0 +EDGE2 5420 1281 -0.00976269 -0.977702 -1.53695 1 0 1 1 0 0 +EDGE2 5420 1301 -0.0318773 -1.09148 -1.57193 1 0 1 1 0 0 +EDGE2 5420 4740 -0.081712 -0.0230858 0.0033507 1 0 1 1 0 0 +EDGE2 5420 1300 0.0771553 0.0973347 -3.14371 1 0 1 1 0 0 +EDGE2 5420 2800 0.0386569 0.0314034 -0.0234564 1 0 1 1 0 0 +EDGE2 5420 2820 -0.05535 0.00872969 0.0334815 1 0 1 1 0 0 +EDGE2 5420 1280 0.0429523 -0.00166871 -3.10038 1 0 1 1 0 0 +EDGE2 5420 2801 0.00904533 1.12126 1.5534 1 0 1 1 0 0 +EDGE2 5420 2841 -0.0117808 1.01641 1.56399 1 0 1 1 0 0 +EDGE2 5420 4741 0.0781892 1.02204 1.54898 1 0 1 1 0 0 +EDGE2 5420 4739 -0.995516 -0.0575327 -0.00721775 1 0 1 1 0 0 +EDGE2 5420 5419 -0.927798 0.099768 0.00114054 1 0 1 1 0 0 +EDGE2 5420 2819 -0.899226 0.007685 0.0133484 1 0 1 1 0 0 +EDGE2 5420 2799 -1.03551 0.00470989 0.00218083 1 0 1 1 0 0 +EDGE2 5421 4742 1.0201 -0.0493036 0.0142301 1 0 1 1 0 0 +EDGE2 5421 2840 -1.04385 -0.000479845 1.55296 1 0 1 1 0 0 +EDGE2 5421 5420 -0.927779 0.0133632 -1.56438 1 0 1 1 0 0 +EDGE2 5421 4740 -0.985712 0.0227697 -1.57056 1 0 1 1 0 0 +EDGE2 5421 1300 -1.03305 -0.00336669 1.56699 1 0 1 1 0 0 +EDGE2 5421 2800 -0.989398 0.0101787 -1.5611 1 0 1 1 0 0 +EDGE2 5421 2820 -0.917167 -0.0254032 -1.58419 1 0 1 1 0 0 +EDGE2 5421 1280 -0.986194 0.0034973 1.52704 1 0 1 1 0 0 +EDGE2 5421 2801 -0.0200927 0.0157589 0.0357944 1 0 1 1 0 0 +EDGE2 5421 2841 0.0340927 0.0184032 0.0150778 1 0 1 1 0 0 +EDGE2 5421 4741 0.0882895 0.0740187 0.0325691 1 0 1 1 0 0 +EDGE2 5421 2802 1.02169 -0.0120616 -0.00299382 1 0 1 1 0 0 +EDGE2 5421 2842 0.901843 0.00595341 -0.00498408 1 0 1 1 0 0 +EDGE2 5422 4742 -0.0331871 -0.03805 0.00201168 1 0 1 1 0 0 +EDGE2 5422 5421 -0.944545 0.0133223 -0.0246281 1 0 1 1 0 0 +EDGE2 5422 2801 -1.06423 0.0174411 0.0126743 1 0 1 1 0 0 +EDGE2 5422 2841 -1.02214 0.00923972 0.00339233 1 0 1 1 0 0 +EDGE2 5422 4741 -0.997486 -0.0459251 -0.0332623 1 0 1 1 0 0 +EDGE2 5422 2802 -0.0638906 0.0786282 -0.0219139 1 0 1 1 0 0 +EDGE2 5422 2842 -0.00969162 0.0125276 -0.0168186 1 0 1 1 0 0 +EDGE2 5422 2843 1.04722 0.0117037 0.00706655 1 0 1 1 0 0 +EDGE2 5422 4743 1.03703 -0.048824 -0.0171259 1 0 1 1 0 0 +EDGE2 5422 2803 1.01369 -0.0355654 0.020611 1 0 1 1 0 0 +EDGE2 5423 4742 -0.989826 0.00937167 0.00147785 1 0 1 1 0 0 +EDGE2 5423 5422 -0.991971 -0.0294928 0.00949289 1 0 1 1 0 0 +EDGE2 5423 2802 -1.02467 -0.0832445 0.0295999 1 0 1 1 0 0 +EDGE2 5423 2842 -1.0305 0.0325093 -0.0125747 1 0 1 1 0 0 +EDGE2 5423 2843 0.0188988 0.081485 -0.0267013 1 0 1 1 0 0 +EDGE2 5423 4743 0.0552775 -0.0631534 -0.0216752 1 0 1 1 0 0 +EDGE2 5423 2803 0.0787762 -0.0400517 -0.0291213 1 0 1 1 0 0 +EDGE2 5423 2804 0.943005 -0.0186141 -0.0172156 1 0 1 1 0 0 +EDGE2 5423 2844 0.972412 -0.00773131 -0.0176133 1 0 1 1 0 0 +EDGE2 5423 4744 0.978846 -0.0834058 0.0182591 1 0 1 1 0 0 +EDGE2 5424 4745 0.910685 0.0125086 0.012552 1 0 1 1 0 0 +EDGE2 5424 2843 -1.08644 -0.0232089 0.0214242 1 0 1 1 0 0 +EDGE2 5424 4743 -0.886282 -0.04954 -0.036749 1 0 1 1 0 0 +EDGE2 5424 5423 -0.916994 -0.0480774 0.00632414 1 0 1 1 0 0 +EDGE2 5424 2803 -0.932583 -0.0633353 -0.0166637 1 0 1 1 0 0 +EDGE2 5424 2804 -0.0041869 0.0253953 -0.0169404 1 0 1 1 0 0 +EDGE2 5424 2844 0.0518546 0.115757 0.0339176 1 0 1 1 0 0 +EDGE2 5424 4744 -0.0348883 -0.0370753 0.0115636 1 0 1 1 0 0 +EDGE2 5424 2685 0.881333 -0.0415876 -3.17455 1 0 1 1 0 0 +EDGE2 5424 2785 1.01634 -0.0287264 -3.13633 1 0 1 1 0 0 +EDGE2 5424 2805 1.0487 -0.0288408 0.0151813 1 0 1 1 0 0 +EDGE2 5424 2845 1.04948 -0.0704126 0.0206908 1 0 1 1 0 0 +EDGE2 5424 2765 0.984915 -0.0172753 -3.12043 1 0 1 1 0 0 +EDGE2 5424 2625 0.945168 -0.0712368 -3.15067 1 0 1 1 0 0 +EDGE2 5425 2766 0.025177 -1.05098 -1.57195 1 0 1 1 0 0 +EDGE2 5425 2846 0.00414783 -0.950809 -1.56569 1 0 1 1 0 0 +EDGE2 5425 2686 -0.0277585 -0.906883 -1.57644 1 0 1 1 0 0 +EDGE2 5425 2626 -0.017902 -1.01693 -1.591 1 0 1 1 0 0 +EDGE2 5425 2786 0.0158835 0.986306 1.56532 1 0 1 1 0 0 +EDGE2 5425 2624 1.00225 -0.00616981 -3.12627 1 0 1 1 0 0 +EDGE2 5425 4745 -0.0585661 -0.0354407 -0.0219245 1 0 1 1 0 0 +EDGE2 5425 5424 -1.0135 0.0660343 0.0316119 1 0 1 1 0 0 +EDGE2 5425 2804 -0.966895 0.0449148 -0.0290561 1 0 1 1 0 0 +EDGE2 5425 2844 -0.977942 -0.0207848 -0.0254482 1 0 1 1 0 0 +EDGE2 5425 4744 -0.973757 0.0374256 0.0158213 1 0 1 1 0 0 +EDGE2 5425 2685 -0.0617215 -0.0267573 -3.14225 1 0 1 1 0 0 +EDGE2 5425 2785 -0.0021984 0.0104368 -3.18008 1 0 1 1 0 0 +EDGE2 5425 2805 0.121077 0.0372164 0.00843912 1 0 1 1 0 0 +EDGE2 5425 2845 0.0175949 0.0278318 -0.0495307 1 0 1 1 0 0 +EDGE2 5425 2765 0.0133154 0.0324818 -3.16807 1 0 1 1 0 0 +EDGE2 5425 2764 0.998456 0.11404 -3.15191 1 0 1 1 0 0 +EDGE2 5425 2784 0.989779 -0.0442962 -3.16749 1 0 1 1 0 0 +EDGE2 5425 2625 -0.0107553 -0.0290482 -3.16026 1 0 1 1 0 0 +EDGE2 5425 2684 0.941564 0.0457378 -3.18076 1 0 1 1 0 0 +EDGE2 5425 4746 0.0360983 0.995492 1.5545 1 0 1 1 0 0 +EDGE2 5425 2806 0.0227423 0.983026 1.55378 1 0 1 1 0 0 +EDGE2 5426 2766 -0.0700324 -0.0268407 -0.0173738 1 0 1 1 0 0 +EDGE2 5426 2687 0.998478 0.0243933 0.0118439 1 0 1 1 0 0 +EDGE2 5426 2847 1.10335 -0.0430852 -0.0267512 1 0 1 1 0 0 +EDGE2 5426 2767 0.881239 -0.000275498 0.03702 1 0 1 1 0 0 +EDGE2 5426 2627 1.02524 -0.0167035 0.0152573 1 0 1 1 0 0 +EDGE2 5426 2846 -0.0326437 0.0312054 0.0166983 1 0 1 1 0 0 +EDGE2 5426 2686 -0.0101338 0.0069654 0.00733445 1 0 1 1 0 0 +EDGE2 5426 2626 -0.0439858 0.00156313 -0.0284005 1 0 1 1 0 0 +EDGE2 5426 4745 -0.990525 -0.0483066 1.54051 1 0 1 1 0 0 +EDGE2 5426 5425 -0.984787 0.0268577 1.57503 1 0 1 1 0 0 +EDGE2 5426 2685 -1.04769 0.0489465 -1.56269 1 0 1 1 0 0 +EDGE2 5426 2785 -1.02116 0.0414096 -1.55687 1 0 1 1 0 0 +EDGE2 5426 2805 -0.959333 -0.0177998 1.55954 1 0 1 1 0 0 +EDGE2 5426 2845 -0.914375 0.0309475 1.58674 1 0 1 1 0 0 +EDGE2 5426 2765 -0.957931 -0.0771225 -1.5913 1 0 1 1 0 0 +EDGE2 5426 2625 -1.05418 0.0022683 -1.56262 1 0 1 1 0 0 +EDGE2 5427 2766 -1.05956 0.0176853 -0.0122757 1 0 1 1 0 0 +EDGE2 5427 2687 0.0110164 -0.0847674 -0.00610411 1 0 1 1 0 0 +EDGE2 5427 2688 1.03307 -0.0244937 0.0122745 1 0 1 1 0 0 +EDGE2 5427 2848 1.04922 0.0161872 0.0148112 1 0 1 1 0 0 +EDGE2 5427 2768 0.92239 -0.0714379 0.023205 1 0 1 1 0 0 +EDGE2 5427 2847 -0.0203337 0.0148391 0.0308343 1 0 1 1 0 0 +EDGE2 5427 2628 0.98771 0.0713808 0.0116659 1 0 1 1 0 0 +EDGE2 5427 2767 0.0517361 0.114456 0.00591794 1 0 1 1 0 0 +EDGE2 5427 5426 -0.964818 0.000612641 -0.00622641 1 0 1 1 0 0 +EDGE2 5427 2627 0.00662328 0.0251189 0.0114038 1 0 1 1 0 0 +EDGE2 5427 2846 -0.917793 0.00599421 0.0435555 1 0 1 1 0 0 +EDGE2 5427 2686 -0.954179 0.0234147 0.0300128 1 0 1 1 0 0 +EDGE2 5427 2626 -1.027 -0.00237503 -0.0163712 1 0 1 1 0 0 +EDGE2 5428 2689 1.06343 -0.0153488 -0.00667592 1 0 1 1 0 0 +EDGE2 5428 2849 0.979479 -0.0436957 0.0010667 1 0 1 1 0 0 +EDGE2 5428 2769 1.04162 0.0372334 -0.0255548 1 0 1 1 0 0 +EDGE2 5428 2687 -1.05164 -0.0396062 -0.049724 1 0 1 1 0 0 +EDGE2 5428 2688 -0.0369851 0.0581825 -0.0220316 1 0 1 1 0 0 +EDGE2 5428 2848 0.00772905 0.0288078 0.0118494 1 0 1 1 0 0 +EDGE2 5428 2629 1.05349 -0.00925221 -0.00962555 1 0 1 1 0 0 +EDGE2 5428 2768 0.0507799 0.111407 0.00807028 1 0 1 1 0 0 +EDGE2 5428 2847 -0.894633 0.0166422 -0.00590634 1 0 1 1 0 0 +EDGE2 5428 5427 -1.03616 0.00343613 0.00339442 1 0 1 1 0 0 +EDGE2 5428 2628 0.0052432 0.00879753 0.00676891 1 0 1 1 0 0 +EDGE2 5428 2767 -1.06247 -0.108658 0.0249529 1 0 1 1 0 0 +EDGE2 5428 2627 -0.954361 0.0460451 0.000165272 1 0 1 1 0 0 +EDGE2 5429 2689 0.0250722 -0.0617383 -0.000156407 1 0 1 1 0 0 +EDGE2 5429 2690 1.03053 0.00212344 0.0105423 1 0 1 1 0 0 +EDGE2 5429 2850 1.03372 0.063617 -0.0217256 1 0 1 1 0 0 +EDGE2 5429 2770 0.939356 0.01183 0.0106056 1 0 1 1 0 0 +EDGE2 5429 2510 1.0054 -0.0887681 -3.14224 1 0 1 1 0 0 +EDGE2 5429 2630 1.0396 0.0594393 -0.01862 1 0 1 1 0 0 +EDGE2 5429 2650 0.957337 0.0187364 -3.12855 1 0 1 1 0 0 +EDGE2 5429 2670 0.983519 -0.0238281 -3.18585 1 0 1 1 0 0 +EDGE2 5429 2610 1.03871 -0.044952 -3.15544 1 0 1 1 0 0 +EDGE2 5429 2849 -0.0369492 -0.13777 -0.00534098 1 0 1 1 0 0 +EDGE2 5429 2769 -0.026132 -0.0451777 -0.0172655 1 0 1 1 0 0 +EDGE2 5429 2688 -1.13095 0.0914125 0.00419437 1 0 1 1 0 0 +EDGE2 5429 2848 -1.01257 -0.0347461 0.00224505 1 0 1 1 0 0 +EDGE2 5429 5428 -0.965682 0.0581683 0.00772077 1 0 1 1 0 0 +EDGE2 5429 2629 -0.0472333 0.00563769 0.0124891 1 0 1 1 0 0 +EDGE2 5429 2768 -0.953959 0.0954477 0.0279781 1 0 1 1 0 0 +EDGE2 5429 2628 -1.0127 0.0128275 0.0258957 1 0 1 1 0 0 +EDGE2 5430 2609 0.976115 -0.0384586 -3.17066 1 0 1 1 0 0 +EDGE2 5430 2649 1.04634 0.0784947 -3.15091 1 0 1 1 0 0 +EDGE2 5430 2669 0.995934 0.101279 -3.16397 1 0 1 1 0 0 +EDGE2 5430 2509 1.0476 0.0161223 -3.13146 1 0 1 1 0 0 +EDGE2 5430 2689 -1.04488 0.0433897 0.0112503 1 0 1 1 0 0 +EDGE2 5430 2631 -0.100913 -0.993675 -1.59779 1 0 1 1 0 0 +EDGE2 5430 2651 0.00755946 -0.991001 -1.53655 1 0 1 1 0 0 +EDGE2 5430 2690 0.0590403 0.00574696 0.0287552 1 0 1 1 0 0 +EDGE2 5430 2850 0.0574567 0.015895 0.0137922 1 0 1 1 0 0 +EDGE2 5430 2511 0.0313682 -1.03914 -1.5593 1 0 1 1 0 0 +EDGE2 5430 2770 0.0512256 -0.0304506 0.00137191 1 0 1 1 0 0 +EDGE2 5430 2510 -0.057914 0.0359048 -3.15302 1 0 1 1 0 0 +EDGE2 5430 2630 0.0257146 -0.0500142 0.0226903 1 0 1 1 0 0 +EDGE2 5430 2650 0.0352717 0.0474127 -3.15575 1 0 1 1 0 0 +EDGE2 5430 2670 -0.0357144 -0.0866031 -3.13038 1 0 1 1 0 0 +EDGE2 5430 2610 -0.0776011 0.0517989 -3.13041 1 0 1 1 0 0 +EDGE2 5430 2849 -0.921129 0.112431 0.0307392 1 0 1 1 0 0 +EDGE2 5430 5429 -1.07252 0.0569208 0.00350325 1 0 1 1 0 0 +EDGE2 5430 2769 -0.98373 0.027437 -0.0315047 1 0 1 1 0 0 +EDGE2 5430 2629 -0.98566 -0.0187008 0.0172912 1 0 1 1 0 0 +EDGE2 5430 2671 0.0497355 0.983758 1.59762 1 0 1 1 0 0 +EDGE2 5430 2771 -0.0521464 0.969186 1.57368 1 0 1 1 0 0 +EDGE2 5430 2851 -0.0370964 0.899921 1.59792 1 0 1 1 0 0 +EDGE2 5430 2691 0.111188 1.10759 1.55981 1 0 1 1 0 0 +EDGE2 5430 2611 -0.0113593 0.985091 1.57962 1 0 1 1 0 0 +EDGE2 5431 2690 -0.997504 -0.0657807 -1.54612 1 0 1 1 0 0 +EDGE2 5431 2850 -1.00615 -0.0173678 -1.55427 1 0 1 1 0 0 +EDGE2 5431 5430 -0.97708 -0.0662879 -1.57743 1 0 1 1 0 0 +EDGE2 5431 2770 -0.882462 0.083874 -1.60164 1 0 1 1 0 0 +EDGE2 5431 2510 -1.05075 -0.0186034 1.58306 1 0 1 1 0 0 +EDGE2 5431 2630 -0.970731 -0.0710763 -1.55487 1 0 1 1 0 0 +EDGE2 5431 2650 -1.02552 -0.0284835 1.58357 1 0 1 1 0 0 +EDGE2 5431 2670 -1.01445 -0.034742 1.57309 1 0 1 1 0 0 +EDGE2 5431 2610 -1.00081 -0.0211417 1.60104 1 0 1 1 0 0 +EDGE2 5431 2692 0.993337 0.102929 -0.0420138 1 0 1 1 0 0 +EDGE2 5431 2671 -0.0607365 -0.0608224 0.0187968 1 0 1 1 0 0 +EDGE2 5431 2771 -0.00420639 0.0169583 -0.00307913 1 0 1 1 0 0 +EDGE2 5431 2851 0.0610358 -0.00301857 0.00885746 1 0 1 1 0 0 +EDGE2 5431 2691 0.0706948 -0.0404921 -0.00458388 1 0 1 1 0 0 +EDGE2 5431 2852 0.960984 0.0532224 0.0219195 1 0 1 1 0 0 +EDGE2 5431 2611 -0.0701613 -0.0190272 -0.00643619 1 0 1 1 0 0 +EDGE2 5431 2772 1.04335 0.0256847 0.0134842 1 0 1 1 0 0 +EDGE2 5431 2612 1.06102 0.0287461 0.0246501 1 0 1 1 0 0 +EDGE2 5431 2672 1.01719 0.12049 -0.00849178 1 0 1 1 0 0 +EDGE2 5432 2692 0.0405928 0.0264562 0.0242893 1 0 1 1 0 0 +EDGE2 5432 2671 -1.04083 0.0605412 -0.00281881 1 0 1 1 0 0 +EDGE2 5432 2771 -1.00901 0.0234262 -0.00968639 1 0 1 1 0 0 +EDGE2 5432 2851 -0.970658 0.0200101 -0.0112419 1 0 1 1 0 0 +EDGE2 5432 5431 -1.13762 -0.0172537 0.0102065 1 0 1 1 0 0 +EDGE2 5432 2691 -0.940661 0.0208551 0.0395719 1 0 1 1 0 0 +EDGE2 5432 2852 -0.0485486 0.0342695 -0.0172512 1 0 1 1 0 0 +EDGE2 5432 2611 -0.918363 0.0440615 0.0485321 1 0 1 1 0 0 +EDGE2 5432 2772 -0.0844644 0.0228095 -0.01927 1 0 1 1 0 0 +EDGE2 5432 2773 1.02697 -0.00892108 0.00573275 1 0 1 1 0 0 +EDGE2 5432 2612 0.0305389 0.0693221 -0.00445492 1 0 1 1 0 0 +EDGE2 5432 2672 -0.0504027 -0.00046457 -0.0314204 1 0 1 1 0 0 +EDGE2 5432 2853 0.983807 -0.0395178 0.00137146 1 0 1 1 0 0 +EDGE2 5432 2613 0.961213 -0.0201194 0.00468709 1 0 1 1 0 0 +EDGE2 5432 2673 0.985619 -0.090732 0.00800829 1 0 1 1 0 0 +EDGE2 5432 2693 1.0803 -0.0162814 -0.0250978 1 0 1 1 0 0 +EDGE2 5433 2854 0.977158 0.014811 -0.0302807 1 0 1 1 0 0 +EDGE2 5433 2692 -1.01958 -0.00998586 -0.0258463 1 0 1 1 0 0 +EDGE2 5433 2852 -1.03357 0.118638 0.0211522 1 0 1 1 0 0 +EDGE2 5433 5432 -0.997905 0.0789242 -0.00979786 1 0 1 1 0 0 +EDGE2 5433 2772 -1.05759 -0.041601 0.00734291 1 0 1 1 0 0 +EDGE2 5433 2773 -0.00133093 -0.013966 0.00737376 1 0 1 1 0 0 +EDGE2 5433 2612 -1.05001 -0.0436994 -0.0182354 1 0 1 1 0 0 +EDGE2 5433 2672 -1.02735 -0.021604 -0.0290049 1 0 1 1 0 0 +EDGE2 5433 2853 0.0715787 -0.0205852 -0.000723099 1 0 1 1 0 0 +EDGE2 5433 2613 -0.0156096 0.0146113 -0.00383766 1 0 1 1 0 0 +EDGE2 5433 2673 0.01944 0.15084 0.0065864 1 0 1 1 0 0 +EDGE2 5433 2693 -0.0242951 0.0234516 -0.00635278 1 0 1 1 0 0 +EDGE2 5433 2674 1.06312 -0.0557389 0.0318947 1 0 1 1 0 0 +EDGE2 5433 2694 0.992543 0.0324069 0.0239049 1 0 1 1 0 0 +EDGE2 5433 2774 0.928086 0.0065105 0.00983024 1 0 1 1 0 0 +EDGE2 5433 2614 1.0773 -0.0358303 -0.0226665 1 0 1 1 0 0 +EDGE2 5434 2854 -0.00611947 0.0234742 -0.00227518 1 0 1 1 0 0 +EDGE2 5434 2773 -1.02196 0.0641644 0.00451263 1 0 1 1 0 0 +EDGE2 5434 5433 -1.00095 0.0134354 -0.0411421 1 0 1 1 0 0 +EDGE2 5434 2853 -0.986612 0.073423 0.0335837 1 0 1 1 0 0 +EDGE2 5434 2613 -1.0409 0.0304897 0.0338187 1 0 1 1 0 0 +EDGE2 5434 2673 -1.13249 -0.0165013 -0.0163542 1 0 1 1 0 0 +EDGE2 5434 2693 -1.01887 0.0280354 -0.010619 1 0 1 1 0 0 +EDGE2 5434 2775 0.939722 -0.020208 0.00744741 1 0 1 1 0 0 +EDGE2 5434 2674 -0.010647 0.0134044 5.21169e-05 1 0 1 1 0 0 +EDGE2 5434 2694 0.0627972 -0.0575855 -0.00797205 1 0 1 1 0 0 +EDGE2 5434 2774 0.0465224 -0.0180449 -0.0114665 1 0 1 1 0 0 +EDGE2 5434 2614 -0.077526 0.0676676 0.018555 1 0 1 1 0 0 +EDGE2 5434 2975 0.981211 0.0103434 -3.12742 1 0 1 1 0 0 +EDGE2 5434 3275 1.00159 0.0706298 -3.13692 1 0 1 1 0 0 +EDGE2 5434 3295 0.992862 0.0849309 -3.15417 1 0 1 1 0 0 +EDGE2 5434 2855 0.911893 -0.0221666 0.0138685 1 0 1 1 0 0 +EDGE2 5434 2615 1.01419 -0.0195918 -0.0158553 1 0 1 1 0 0 +EDGE2 5434 2675 1.06595 0.0104607 -0.0162131 1 0 1 1 0 0 +EDGE2 5434 2695 1.06397 -0.0337981 -0.0158382 1 0 1 1 0 0 +EDGE2 5435 3296 0.10863 -0.941162 -1.54672 1 0 1 1 0 0 +EDGE2 5435 2976 -0.0787667 -0.964829 -1.55936 1 0 1 1 0 0 +EDGE2 5435 3276 0.108434 -0.856672 -1.57855 1 0 1 1 0 0 +EDGE2 5435 2854 -0.993798 0.0322278 -0.00535522 1 0 1 1 0 0 +EDGE2 5435 5434 -1.00322 -0.0453946 -0.0051166 1 0 1 1 0 0 +EDGE2 5435 2775 0.0124102 0.00572683 -0.017557 1 0 1 1 0 0 +EDGE2 5435 2674 -1.03941 0.0418735 -0.00711999 1 0 1 1 0 0 +EDGE2 5435 2694 -0.942237 -0.0720938 -0.0146174 1 0 1 1 0 0 +EDGE2 5435 2774 -0.983766 -0.0112632 0.0162175 1 0 1 1 0 0 +EDGE2 5435 2614 -0.989228 0.0230573 -0.0208164 1 0 1 1 0 0 +EDGE2 5435 2975 -0.060906 -0.0186016 -3.12952 1 0 1 1 0 0 +EDGE2 5435 3275 -0.065964 -0.0314693 -3.15617 1 0 1 1 0 0 +EDGE2 5435 3295 -0.0750659 -0.0524656 -3.12163 1 0 1 1 0 0 +EDGE2 5435 2855 0.0522416 0.0561074 -0.004693 1 0 1 1 0 0 +EDGE2 5435 3274 0.9415 -0.0319257 -3.14085 1 0 1 1 0 0 +EDGE2 5435 2615 0.00743335 -0.0362131 -0.00148239 1 0 1 1 0 0 +EDGE2 5435 2675 0.0770283 0.0710431 0.0256552 1 0 1 1 0 0 +EDGE2 5435 2695 0.055236 -0.0570928 -0.00679235 1 0 1 1 0 0 +EDGE2 5435 3294 0.955706 -0.050853 -3.13801 1 0 1 1 0 0 +EDGE2 5435 2974 0.97814 0.0195638 -3.15732 1 0 1 1 0 0 +EDGE2 5435 2676 -0.0538591 1.0227 1.5503 1 0 1 1 0 0 +EDGE2 5435 2776 0.138949 1.02952 1.57847 1 0 1 1 0 0 +EDGE2 5435 2856 -0.0665279 0.908958 1.53737 1 0 1 1 0 0 +EDGE2 5435 2696 -0.0220886 0.986434 1.59026 1 0 1 1 0 0 +EDGE2 5435 2616 -0.103338 0.91755 1.56825 1 0 1 1 0 0 +EDGE2 5436 2775 -1.02279 -0.0125886 -1.57962 1 0 1 1 0 0 +EDGE2 5436 5435 -0.981869 -0.0654814 -1.57093 1 0 1 1 0 0 +EDGE2 5436 2975 -1.0205 -0.0812594 1.60057 1 0 1 1 0 0 +EDGE2 5436 3275 -1.00732 0.019466 1.56899 1 0 1 1 0 0 +EDGE2 5436 3295 -1.01287 -0.0499112 1.56785 1 0 1 1 0 0 +EDGE2 5436 2855 -0.908889 0.0467312 -1.57386 1 0 1 1 0 0 +EDGE2 5436 2615 -0.963145 0.0568683 -1.5542 1 0 1 1 0 0 +EDGE2 5436 2675 -1.0081 0.00862137 -1.56856 1 0 1 1 0 0 +EDGE2 5436 2695 -1.02865 -0.00812264 -1.5934 1 0 1 1 0 0 +EDGE2 5436 2677 0.984296 0.0084483 -0.00534181 1 0 1 1 0 0 +EDGE2 5436 2697 1.04049 -0.0274092 0.027727 1 0 1 1 0 0 +EDGE2 5436 2676 -0.117086 0.12675 -0.0255203 1 0 1 1 0 0 +EDGE2 5436 2776 -0.0444089 -0.00923504 0.00153543 1 0 1 1 0 0 +EDGE2 5436 2856 0.0898881 0.0391291 0.0107071 1 0 1 1 0 0 +EDGE2 5436 2696 0.0541425 0.00812768 0.0185214 1 0 1 1 0 0 +EDGE2 5436 2857 1.04826 0.015269 -0.0371232 1 0 1 1 0 0 +EDGE2 5436 2616 0.0131336 -0.0223012 0.00634478 1 0 1 1 0 0 +EDGE2 5436 2777 0.947753 0.0275691 0.00359046 1 0 1 1 0 0 +EDGE2 5436 2617 0.971938 0.0445324 0.000914321 1 0 1 1 0 0 +EDGE2 5437 2677 -0.00339524 -0.00113079 -0.00946867 1 0 1 1 0 0 +EDGE2 5437 2697 -0.00306135 0.0108004 0.00298621 1 0 1 1 0 0 +EDGE2 5437 2676 -0.867921 -0.00768998 -0.00204662 1 0 1 1 0 0 +EDGE2 5437 2776 -0.984628 -0.0852701 -0.01192 1 0 1 1 0 0 +EDGE2 5437 2856 -1.02089 -0.014664 0.00178301 1 0 1 1 0 0 +EDGE2 5437 5436 -1.00868 -0.0401158 0.000985737 1 0 1 1 0 0 +EDGE2 5437 2696 -1.0563 0.0884877 -0.0621789 1 0 1 1 0 0 +EDGE2 5437 2857 0.0533126 -0.0355357 0.019766 1 0 1 1 0 0 +EDGE2 5437 2616 -0.916336 -0.0230928 0.00378997 1 0 1 1 0 0 +EDGE2 5437 2777 -0.0843364 -0.0451806 0.0309728 1 0 1 1 0 0 +EDGE2 5437 2698 0.953405 -0.0255617 -0.0265438 1 0 1 1 0 0 +EDGE2 5437 2858 1.07012 0.000892019 0.0188688 1 0 1 1 0 0 +EDGE2 5437 2617 -0.0199749 -0.00762168 -0.0272608 1 0 1 1 0 0 +EDGE2 5437 2778 0.999151 -0.0673969 -0.0254814 1 0 1 1 0 0 +EDGE2 5437 2618 1.03257 0.0303313 -0.013005 1 0 1 1 0 0 +EDGE2 5437 2678 1.05005 0.00792102 0.0431702 1 0 1 1 0 0 +EDGE2 5438 2677 -1.02626 -0.0674779 0.0544987 1 0 1 1 0 0 +EDGE2 5438 2697 -0.944715 -0.0908998 -0.0221622 1 0 1 1 0 0 +EDGE2 5438 2857 -0.991777 0.0194572 0.00713608 1 0 1 1 0 0 +EDGE2 5438 5437 -0.96754 -0.0139562 0.0126493 1 0 1 1 0 0 +EDGE2 5438 2777 -0.999155 0.0450632 0.019027 1 0 1 1 0 0 +EDGE2 5438 2698 -0.013201 0.017947 -0.00489164 1 0 1 1 0 0 +EDGE2 5438 2858 -0.00456466 0.0819546 -0.00312951 1 0 1 1 0 0 +EDGE2 5438 2617 -1.02702 -0.0487223 -0.0228381 1 0 1 1 0 0 +EDGE2 5438 2778 -0.0313893 -0.0863253 0.0172832 1 0 1 1 0 0 +EDGE2 5438 2618 -0.0763097 0.0554404 0.0267621 1 0 1 1 0 0 +EDGE2 5438 2678 -0.0759255 0.0425357 0.0148999 1 0 1 1 0 0 +EDGE2 5438 2699 1.07672 0.0616158 -0.00781116 1 0 1 1 0 0 +EDGE2 5438 2859 1.08754 -0.0530832 0.00840661 1 0 1 1 0 0 +EDGE2 5438 2779 0.936745 0.00739407 -0.0216241 1 0 1 1 0 0 +EDGE2 5438 2619 1.01275 0.0292359 -0.00499846 1 0 1 1 0 0 +EDGE2 5438 2679 0.997414 -0.00447317 -0.0120775 1 0 1 1 0 0 +EDGE2 5439 2698 -0.997403 0.00552314 0.0346798 1 0 1 1 0 0 +EDGE2 5439 2858 -1.03096 0.0152615 0.0367588 1 0 1 1 0 0 +EDGE2 5439 5438 -0.975073 -0.0112467 0.00949035 1 0 1 1 0 0 +EDGE2 5439 2778 -1.04078 -0.0497136 -0.0407995 1 0 1 1 0 0 +EDGE2 5439 2618 -0.992814 -0.0427368 -0.0233529 1 0 1 1 0 0 +EDGE2 5439 2678 -1.03703 0.0104294 -0.00171376 1 0 1 1 0 0 +EDGE2 5439 2699 0.0445954 0.0434169 0.00145518 1 0 1 1 0 0 +EDGE2 5439 2859 0.038385 -0.0304812 -0.00733138 1 0 1 1 0 0 +EDGE2 5439 2779 0.116142 -0.00137855 -0.0476002 1 0 1 1 0 0 +EDGE2 5439 2619 -0.0160111 0.0269056 -0.00742626 1 0 1 1 0 0 +EDGE2 5439 2679 -0.0273797 -0.0399106 0.00943598 1 0 1 1 0 0 +EDGE2 5439 2760 0.926666 -0.0169308 -3.136 1 0 1 1 0 0 +EDGE2 5439 2860 0.972561 0.0225917 0.0250278 1 0 1 1 0 0 +EDGE2 5439 2880 1.02074 0.0508241 -3.12339 1 0 1 1 0 0 +EDGE2 5439 2960 0.960667 0.00652717 -3.15204 1 0 1 1 0 0 +EDGE2 5439 2780 1.01045 -0.0247013 -0.0257674 1 0 1 1 0 0 +EDGE2 5439 2620 0.945544 -0.0176348 0.0375511 1 0 1 1 0 0 +EDGE2 5439 2680 0.961685 0.05027 0.006051 1 0 1 1 0 0 +EDGE2 5439 2700 1.03256 -0.031575 -0.00594582 1 0 1 1 0 0 +EDGE2 5440 5439 -0.947381 0.0245076 -0.0238859 1 0 1 1 0 0 +EDGE2 5440 2699 -0.973352 -0.0275198 0.0602941 1 0 1 1 0 0 +EDGE2 5440 2859 -0.938313 -0.0486553 0.00747469 1 0 1 1 0 0 +EDGE2 5440 2779 -1.03826 0.0806531 0.00132612 1 0 1 1 0 0 +EDGE2 5440 2619 -1.03553 -0.0494285 0.0132506 1 0 1 1 0 0 +EDGE2 5440 2679 -0.904159 0.0271765 -0.0173505 1 0 1 1 0 0 +EDGE2 5440 2760 0.0672955 0.0412361 -3.15807 1 0 1 1 0 0 +EDGE2 5440 2681 0.0134487 1.03133 1.55607 1 0 1 1 0 0 +EDGE2 5440 2761 0.00961079 0.864927 1.5661 1 0 1 1 0 0 +EDGE2 5440 2781 -0.0103807 0.965868 1.56867 1 0 1 1 0 0 +EDGE2 5440 2621 -0.0712762 0.952978 1.5882 1 0 1 1 0 0 +EDGE2 5440 2860 -0.0316664 -0.00690627 -0.00898606 1 0 1 1 0 0 +EDGE2 5440 2880 -0.0784212 0.04514 -3.14774 1 0 1 1 0 0 +EDGE2 5440 2960 -0.0104001 0.0216984 -3.15094 1 0 1 1 0 0 +EDGE2 5440 2780 0.0144539 -0.0207673 -0.00833784 1 0 1 1 0 0 +EDGE2 5440 2961 -0.0616862 -0.962332 -1.5641 1 0 1 1 0 0 +EDGE2 5440 2620 -0.00394106 -0.00559215 -0.0137499 1 0 1 1 0 0 +EDGE2 5440 2680 -0.0824516 0.0240132 -0.0149643 1 0 1 1 0 0 +EDGE2 5440 2700 0.0221741 -0.0886151 0.00424139 1 0 1 1 0 0 +EDGE2 5440 2701 -0.0218898 -1.03723 -1.57001 1 0 1 1 0 0 +EDGE2 5440 2861 -0.00878131 -0.877503 -1.59113 1 0 1 1 0 0 +EDGE2 5440 2881 -0.0498174 -0.978349 -1.59903 1 0 1 1 0 0 +EDGE2 5440 2759 1.06652 0.0859939 -3.12187 1 0 1 1 0 0 +EDGE2 5440 2879 1.03202 0.123514 -3.12437 1 0 1 1 0 0 +EDGE2 5440 2959 1.05509 -0.0722736 -3.14623 1 0 1 1 0 0 +EDGE2 5441 2760 -1.08086 0.00806297 -1.5997 1 0 1 1 0 0 +EDGE2 5441 5440 -1.01192 0.0273204 1.57918 1 0 1 1 0 0 +EDGE2 5441 2860 -0.987988 -0.0562979 1.57758 1 0 1 1 0 0 +EDGE2 5441 2880 -1.08518 -0.06937 -1.54414 1 0 1 1 0 0 +EDGE2 5441 2960 -0.95928 0.0506057 -1.57412 1 0 1 1 0 0 +EDGE2 5441 2780 -0.978167 -0.0612945 1.6069 1 0 1 1 0 0 +EDGE2 5441 2962 0.930954 -0.0154924 0.00401742 1 0 1 1 0 0 +EDGE2 5441 2961 0.0327858 -0.0221576 -0.0208661 1 0 1 1 0 0 +EDGE2 5441 2620 -1.04643 0.00566497 1.58418 1 0 1 1 0 0 +EDGE2 5441 2680 -1.00418 0.0978416 1.55933 1 0 1 1 0 0 +EDGE2 5441 2700 -0.993852 -0.0366508 1.59192 1 0 1 1 0 0 +EDGE2 5441 2701 -0.0208694 0.0644486 0.0218137 1 0 1 1 0 0 +EDGE2 5441 2861 0.032934 0.0327888 -0.00982379 1 0 1 1 0 0 +EDGE2 5441 2881 0.00690543 -0.0461265 -0.00959895 1 0 1 1 0 0 +EDGE2 5441 2702 0.927913 0.0282659 -0.00134648 1 0 1 1 0 0 +EDGE2 5441 2862 0.994567 -0.0050707 0.014965 1 0 1 1 0 0 +EDGE2 5441 2882 0.953495 -0.0180922 0.0575579 1 0 1 1 0 0 +EDGE2 5442 2962 -0.0428079 0.0537422 0.0198586 1 0 1 1 0 0 +EDGE2 5442 2961 -0.999923 -0.0737147 -0.00265274 1 0 1 1 0 0 +EDGE2 5442 5441 -1.10114 -0.0618611 0.0151995 1 0 1 1 0 0 +EDGE2 5442 2701 -0.989384 0.0487652 0.0091471 1 0 1 1 0 0 +EDGE2 5442 2861 -0.984426 0.0746393 0.0228985 1 0 1 1 0 0 +EDGE2 5442 2881 -0.896194 0.0462452 0.0141449 1 0 1 1 0 0 +EDGE2 5442 2963 0.969629 0.018732 0.00671013 1 0 1 1 0 0 +EDGE2 5442 2702 0.00734298 -0.0412381 0.0204262 1 0 1 1 0 0 +EDGE2 5442 2862 0.0102106 -0.0911646 -0.0119878 1 0 1 1 0 0 +EDGE2 5442 2882 0.00714443 -0.0816825 -0.0337575 1 0 1 1 0 0 +EDGE2 5442 2703 0.944601 -0.0059425 -0.011906 1 0 1 1 0 0 +EDGE2 5442 2863 0.956772 0.0174174 0.00103965 1 0 1 1 0 0 +EDGE2 5442 2883 1.0072 -0.0488861 0.0110344 1 0 1 1 0 0 +EDGE2 5443 2964 1.0282 0.000202102 0.00948646 1 0 1 1 0 0 +EDGE2 5443 2962 -1.00771 -0.0126808 -0.00273467 1 0 1 1 0 0 +EDGE2 5443 5442 -1.09144 0.00432335 0.0229813 1 0 1 1 0 0 +EDGE2 5443 2963 0.104232 -0.00988212 0.0301016 1 0 1 1 0 0 +EDGE2 5443 2702 -1.04142 0.00326783 -0.0123444 1 0 1 1 0 0 +EDGE2 5443 2862 -1.06955 -0.00487545 -0.0133674 1 0 1 1 0 0 +EDGE2 5443 2882 -1.04153 -0.0196977 -0.00866113 1 0 1 1 0 0 +EDGE2 5443 2703 0.0984693 0.038827 0.000163963 1 0 1 1 0 0 +EDGE2 5443 2863 -0.0179996 -0.0518736 -0.0401844 1 0 1 1 0 0 +EDGE2 5443 2883 -0.0585003 0.0408232 -0.0135867 1 0 1 1 0 0 +EDGE2 5443 2704 0.905116 0.0345982 0.0322101 1 0 1 1 0 0 +EDGE2 5443 2864 0.978404 0.00669463 0.0200737 1 0 1 1 0 0 +EDGE2 5443 2884 0.97299 -0.0572954 0.0261302 1 0 1 1 0 0 +EDGE2 5444 2964 0.0339637 -0.0894315 -0.0288885 1 0 1 1 0 0 +EDGE2 5444 2963 -0.994553 0.0330293 0.0284948 1 0 1 1 0 0 +EDGE2 5444 5443 -1.04225 -0.054445 -0.0164465 1 0 1 1 0 0 +EDGE2 5444 2703 -1.02918 0.0163915 -0.00207224 1 0 1 1 0 0 +EDGE2 5444 2863 -1.00308 -0.0226302 0.00760196 1 0 1 1 0 0 +EDGE2 5444 2883 -1.03515 0.0182093 0.031299 1 0 1 1 0 0 +EDGE2 5444 2704 0.00927242 0.0341204 -0.00184454 1 0 1 1 0 0 +EDGE2 5444 2864 -0.0109285 -0.0110609 0.00289975 1 0 1 1 0 0 +EDGE2 5444 2884 -0.0256077 0.0501577 -0.0218035 1 0 1 1 0 0 +EDGE2 5444 2705 1.08434 0.0466993 -0.008304 1 0 1 1 0 0 +EDGE2 5444 2865 0.997305 -0.0385271 0.0153988 1 0 1 1 0 0 +EDGE2 5444 2885 0.951239 -0.0170558 -0.00636056 1 0 1 1 0 0 +EDGE2 5444 2965 1.00279 -0.0174069 -0.0310693 1 0 1 1 0 0 +EDGE2 5444 2745 1.01338 -0.0293556 -3.11541 1 0 1 1 0 0 +EDGE2 5445 2964 -0.991855 0.040431 0.000565654 1 0 1 1 0 0 +EDGE2 5445 5444 -1.02492 0.0399372 -0.00924005 1 0 1 1 0 0 +EDGE2 5445 2704 -0.927779 -0.00569596 -0.0177817 1 0 1 1 0 0 +EDGE2 5445 2864 -1.03627 0.0110159 0.00615452 1 0 1 1 0 0 +EDGE2 5445 2884 -0.949391 -0.0164337 0.0518778 1 0 1 1 0 0 +EDGE2 5445 2706 0.0286701 -1.015 -1.55697 1 0 1 1 0 0 +EDGE2 5445 2966 -0.0422227 -1.06874 -1.58195 1 0 1 1 0 0 +EDGE2 5445 2705 -0.0140199 0.0943922 0.0300938 1 0 1 1 0 0 +EDGE2 5445 2865 -0.000514431 -0.00242222 -0.00162857 1 0 1 1 0 0 +EDGE2 5445 2885 -0.0835901 0.0280723 -0.00311513 1 0 1 1 0 0 +EDGE2 5445 2965 0.000358701 0.0634343 0.0219779 1 0 1 1 0 0 +EDGE2 5445 2745 -0.00655891 -0.0425434 -3.16668 1 0 1 1 0 0 +EDGE2 5445 2746 -0.0137629 0.982086 1.56299 1 0 1 1 0 0 +EDGE2 5445 2866 -0.00102705 0.996787 1.5544 1 0 1 1 0 0 +EDGE2 5445 2886 -0.0122943 1.0392 1.61563 1 0 1 1 0 0 +EDGE2 5445 2744 1.00445 -0.00175519 -3.14374 1 0 1 1 0 0 +EDGE2 5446 5445 -1.05194 0.0225034 1.61139 1 0 1 1 0 0 +EDGE2 5446 2706 -0.00206439 -0.000197298 0.0119143 1 0 1 1 0 0 +EDGE2 5446 2707 1.07987 0.0308616 -0.0373941 1 0 1 1 0 0 +EDGE2 5446 2967 1.06936 -0.0136578 -0.0421881 1 0 1 1 0 0 +EDGE2 5446 2966 0.0395572 -0.0956766 0.000141774 1 0 1 1 0 0 +EDGE2 5446 2705 -1.0041 0.0304257 1.55153 1 0 1 1 0 0 +EDGE2 5446 2865 -0.995411 0.0844744 1.58857 1 0 1 1 0 0 +EDGE2 5446 2885 -1.00944 -0.0451567 1.58265 1 0 1 1 0 0 +EDGE2 5446 2965 -0.864327 0.046229 1.58212 1 0 1 1 0 0 +EDGE2 5446 2745 -0.893985 -0.00708145 -1.57324 1 0 1 1 0 0 +EDGE2 5447 5446 -1.05721 -0.00568346 0.048196 1 0 1 1 0 0 +EDGE2 5447 2706 -1.04455 -0.00643655 -0.012197 1 0 1 1 0 0 +EDGE2 5447 2968 0.947237 0.0761849 -0.0352038 1 0 1 1 0 0 +EDGE2 5447 2707 -0.0493819 0.0655387 -0.00823699 1 0 1 1 0 0 +EDGE2 5447 2967 0.0337558 -0.0438636 0.0142451 1 0 1 1 0 0 +EDGE2 5447 2708 1.08899 -0.0470628 0.00130445 1 0 1 1 0 0 +EDGE2 5447 2966 -0.997585 -0.0809064 -0.0192086 1 0 1 1 0 0 +EDGE2 5448 5447 -1.01497 -0.0463363 -0.0484244 1 0 1 1 0 0 +EDGE2 5448 2968 0.045448 0.015772 0.000926199 1 0 1 1 0 0 +EDGE2 5448 2969 0.976524 0.0188243 -0.0334078 1 0 1 1 0 0 +EDGE2 5448 2709 0.940408 0.0459804 -0.0353415 1 0 1 1 0 0 +EDGE2 5448 2707 -0.959005 -0.0695704 0.00573255 1 0 1 1 0 0 +EDGE2 5448 2967 -1.03595 0.0267916 0.00021411 1 0 1 1 0 0 +EDGE2 5448 2708 -0.0379225 -0.0267724 -0.00718171 1 0 1 1 0 0 +EDGE2 5449 5448 -1.03395 -0.0471147 0.00321065 1 0 1 1 0 0 +EDGE2 5449 3290 1.02688 0.00334857 -3.12468 1 0 1 1 0 0 +EDGE2 5449 2970 1.07171 0.0228471 0.00536678 1 0 1 1 0 0 +EDGE2 5449 3270 1.01779 -0.0229712 -3.11326 1 0 1 1 0 0 +EDGE2 5449 3010 0.897243 0.0239858 -3.1347 1 0 1 1 0 0 +EDGE2 5449 2710 0.984859 0.021071 0.0254445 1 0 1 1 0 0 +EDGE2 5449 2968 -1.00395 -0.0514209 -0.0270074 1 0 1 1 0 0 +EDGE2 5449 2969 -0.0372823 0.0802448 0.00701713 1 0 1 1 0 0 +EDGE2 5449 2709 0.0520209 -0.0372973 0.06495 1 0 1 1 0 0 +EDGE2 5449 2708 -0.971124 -0.0323129 -0.00919458 1 0 1 1 0 0 +EDGE2 5450 3271 0.0386569 -0.961767 -1.55089 1 0 1 1 0 0 +EDGE2 5450 3291 0.0529039 -1.03267 -1.54637 1 0 1 1 0 0 +EDGE2 5450 2971 -0.011588 -1.0124 -1.52492 1 0 1 1 0 0 +EDGE2 5450 5449 -0.932156 0.00895716 -0.0253367 1 0 1 1 0 0 +EDGE2 5450 2711 -0.0868106 0.943929 1.55152 1 0 1 1 0 0 +EDGE2 5450 3290 -0.106542 -0.0226484 -3.12732 1 0 1 1 0 0 +EDGE2 5450 3269 1.04375 0.0384184 -3.18425 1 0 1 1 0 0 +EDGE2 5450 3289 0.971325 0.0215844 -3.14358 1 0 1 1 0 0 +EDGE2 5450 3009 1.01352 -0.158018 -3.16345 1 0 1 1 0 0 +EDGE2 5450 2970 -0.00445786 -0.0262236 -0.00565495 1 0 1 1 0 0 +EDGE2 5450 3270 0.0476385 0.0852553 -3.13642 1 0 1 1 0 0 +EDGE2 5450 3010 -0.080064 -0.0625476 -3.15555 1 0 1 1 0 0 +EDGE2 5450 2710 0.101129 0.0597644 0.0208397 1 0 1 1 0 0 +EDGE2 5450 3011 -0.0322079 0.946561 1.57654 1 0 1 1 0 0 +EDGE2 5450 2969 -1.03929 0.125621 -0.00454717 1 0 1 1 0 0 +EDGE2 5450 2709 -0.915842 -0.0292461 0.0486969 1 0 1 1 0 0 +EDGE2 5451 5450 -0.991031 -0.0151178 -1.5834 1 0 1 1 0 0 +EDGE2 5451 2711 0.0651044 0.0612599 -0.033261 1 0 1 1 0 0 +EDGE2 5451 3290 -0.96062 -0.0355847 1.58067 1 0 1 1 0 0 +EDGE2 5451 2970 -1.0031 -0.0640752 -1.58634 1 0 1 1 0 0 +EDGE2 5451 3270 -0.883708 0.00562744 1.54991 1 0 1 1 0 0 +EDGE2 5451 3010 -1.01886 0.0851955 1.56828 1 0 1 1 0 0 +EDGE2 5451 2710 -1.02302 -0.0386472 -1.5688 1 0 1 1 0 0 +EDGE2 5451 3011 -0.021137 0.0316216 -0.00539815 1 0 1 1 0 0 +EDGE2 5451 3012 1.02245 -0.023771 -0.0111527 1 0 1 1 0 0 +EDGE2 5451 2712 1.11184 -0.030268 0.0341139 1 0 1 1 0 0 +EDGE2 5452 2711 -0.998808 0.105253 0.0136981 1 0 1 1 0 0 +EDGE2 5452 5451 -1.0175 -0.0511386 0.00855311 1 0 1 1 0 0 +EDGE2 5452 3011 -0.979762 -0.0438438 -0.0532323 1 0 1 1 0 0 +EDGE2 5452 3012 0.060328 -0.026179 -0.0352789 1 0 1 1 0 0 +EDGE2 5452 2713 1.02528 0.0600021 0.0190169 1 0 1 1 0 0 +EDGE2 5452 2712 0.0202993 -0.0466735 -0.0359036 1 0 1 1 0 0 +EDGE2 5452 3013 0.956924 0.0252621 -0.00481576 1 0 1 1 0 0 +EDGE2 5453 3012 -0.973654 -0.00940534 -0.012141 1 0 1 1 0 0 +EDGE2 5453 5452 -1.05153 -0.0384064 0.0113504 1 0 1 1 0 0 +EDGE2 5453 2713 -0.00831745 -0.0580093 -0.0197782 1 0 1 1 0 0 +EDGE2 5453 2712 -0.987311 -0.025023 0.00239171 1 0 1 1 0 0 +EDGE2 5453 3013 -0.0727615 0.0337865 0.0303128 1 0 1 1 0 0 +EDGE2 5453 3014 1.04499 0.0469469 0.00869252 1 0 1 1 0 0 +EDGE2 5453 2714 1.01823 -0.0692708 -0.0117581 1 0 1 1 0 0 +EDGE2 5454 2713 -0.958212 0.0105368 0.0399682 1 0 1 1 0 0 +EDGE2 5454 5453 -0.973715 -0.00914902 0.00230441 1 0 1 1 0 0 +EDGE2 5454 3013 -1.01001 -0.069152 -0.000793998 1 0 1 1 0 0 +EDGE2 5454 3014 0.0594525 0.056843 -0.0299797 1 0 1 1 0 0 +EDGE2 5454 2714 0.0323954 0.0172202 0.0147947 1 0 1 1 0 0 +EDGE2 5454 2715 0.987883 -0.0451532 -0.0202624 1 0 1 1 0 0 +EDGE2 5454 3015 0.953513 -0.0387328 -0.0151457 1 0 1 1 0 0 +EDGE2 5454 3515 1.06684 0.100059 -3.15333 1 0 1 1 0 0 +EDGE2 5455 3014 -0.970553 0.0206148 0.00669303 1 0 1 1 0 0 +EDGE2 5455 5454 -1.01191 0.0514419 0.0109532 1 0 1 1 0 0 +EDGE2 5455 2714 -1.01819 -0.0452823 0.000844707 1 0 1 1 0 0 +EDGE2 5455 3516 -0.0345938 0.967116 1.58323 1 0 1 1 0 0 +EDGE2 5455 3016 -0.0101738 -1.03617 -1.58748 1 0 1 1 0 0 +EDGE2 5455 2715 0.0295141 0.0311739 -0.0292933 1 0 1 1 0 0 +EDGE2 5455 3015 -0.117122 -0.0104168 0.0057584 1 0 1 1 0 0 +EDGE2 5455 3515 -0.0192176 0.0333763 -3.15105 1 0 1 1 0 0 +EDGE2 5455 3514 0.965199 0.0761477 -3.14093 1 0 1 1 0 0 +EDGE2 5455 2716 0.0223114 1.074 1.56812 1 0 1 1 0 0 +EDGE2 5456 3516 -0.00642412 0.0235246 0.0370279 1 0 1 1 0 0 +EDGE2 5456 5455 -1.09957 0.0130679 -1.56291 1 0 1 1 0 0 +EDGE2 5456 2715 -1.0695 -0.00460621 -1.58281 1 0 1 1 0 0 +EDGE2 5456 3015 -1.03871 0.0106707 -1.54748 1 0 1 1 0 0 +EDGE2 5456 3515 -0.995541 -0.108571 1.56514 1 0 1 1 0 0 +EDGE2 5456 2716 -0.064414 -0.0267873 -0.0118477 1 0 1 1 0 0 +EDGE2 5456 2717 1.0387 0.02596 -0.0379232 1 0 1 1 0 0 +EDGE2 5456 3517 0.982376 -0.024733 0.00424825 1 0 1 1 0 0 +EDGE2 5457 3516 -1.04503 -0.0258575 0.00932232 1 0 1 1 0 0 +EDGE2 5457 5456 -1.05833 0.0353316 0.00237844 1 0 1 1 0 0 +EDGE2 5457 2716 -1.02901 0.0560694 -0.0204404 1 0 1 1 0 0 +EDGE2 5457 2718 1.00745 -0.0187632 0.0135623 1 0 1 1 0 0 +EDGE2 5457 2717 -0.091101 -0.0262066 -0.00927931 1 0 1 1 0 0 +EDGE2 5457 3517 -0.0329886 -0.0207873 0.0080944 1 0 1 1 0 0 +EDGE2 5457 3518 1.01775 -0.00441292 0.00229279 1 0 1 1 0 0 +EDGE2 5458 5457 -1.00821 0.0115338 0.00826852 1 0 1 1 0 0 +EDGE2 5458 2718 -0.0506002 -0.00130717 0.0138358 1 0 1 1 0 0 +EDGE2 5458 2717 -0.972867 -0.0262517 -0.00803087 1 0 1 1 0 0 +EDGE2 5458 3517 -1.0446 -0.0735404 0.00798423 1 0 1 1 0 0 +EDGE2 5458 3518 -0.00227314 0.0593627 0.0129518 1 0 1 1 0 0 +EDGE2 5458 2719 0.972336 0.00745452 0.0353406 1 0 1 1 0 0 +EDGE2 5458 3519 1.01323 0.0896349 0.00849053 1 0 1 1 0 0 +EDGE2 5459 3520 0.902586 -0.00535427 0.033349 1 0 1 1 0 0 +EDGE2 5459 2718 -0.985621 0.0309788 0.0143094 1 0 1 1 0 0 +EDGE2 5459 5458 -0.96406 0.0404491 -0.0119917 1 0 1 1 0 0 +EDGE2 5459 3518 -0.969733 -0.00906506 -0.014805 1 0 1 1 0 0 +EDGE2 5459 2719 0.0143834 -0.0541905 0.0125876 1 0 1 1 0 0 +EDGE2 5459 3519 -0.0578641 0.0381184 -0.0329894 1 0 1 1 0 0 +EDGE2 5459 2720 0.963987 -0.158189 -0.0245735 1 0 1 1 0 0 +EDGE2 5459 2740 1.02139 -0.0459675 -3.15081 1 0 1 1 0 0 +EDGE2 5460 2741 0.0498689 1.03464 1.53186 1 0 1 1 0 0 +EDGE2 5460 3520 0.0374248 -0.0484004 -0.0314317 1 0 1 1 0 0 +EDGE2 5460 2719 -0.959696 -0.0379185 -0.00201051 1 0 1 1 0 0 +EDGE2 5460 3519 -0.886097 0.0955929 0.0123774 1 0 1 1 0 0 +EDGE2 5460 5459 -0.993277 -0.0166632 -0.0258687 1 0 1 1 0 0 +EDGE2 5460 2721 0.0691419 -1.01566 -1.57592 1 0 1 1 0 0 +EDGE2 5460 2720 0.0305708 -0.0362027 0.0182942 1 0 1 1 0 0 +EDGE2 5460 2740 0.0554994 -0.0597679 -3.13747 1 0 1 1 0 0 +EDGE2 5460 3521 0.0764508 -0.994298 -1.59232 1 0 1 1 0 0 +EDGE2 5460 2739 1.07451 -0.0556996 -3.126 1 0 1 1 0 0 +EDGE2 5461 3520 -0.996816 -0.00898265 1.58725 1 0 1 1 0 0 +EDGE2 5461 5460 -0.976047 -0.00621907 1.58254 1 0 1 1 0 0 +EDGE2 5461 2721 -0.028264 -0.00489509 -0.0123667 1 0 1 1 0 0 +EDGE2 5461 2720 -1.04219 -0.0800248 1.57832 1 0 1 1 0 0 +EDGE2 5461 2740 -1.03699 -0.00537639 -1.56211 1 0 1 1 0 0 +EDGE2 5461 3521 0.0530106 0.0125468 0.0177124 1 0 1 1 0 0 +EDGE2 5461 3522 1.05986 -0.0132325 0.0136456 1 0 1 1 0 0 +EDGE2 5461 2722 0.957826 0.00236215 0.0197944 1 0 1 1 0 0 +EDGE2 5462 2721 -0.994736 0.0596105 -0.0138008 1 0 1 1 0 0 +EDGE2 5462 5461 -0.969893 0.068192 0.00388619 1 0 1 1 0 0 +EDGE2 5462 3521 -1.01554 -0.0388163 -0.0146927 1 0 1 1 0 0 +EDGE2 5462 3522 0.058987 0.0277439 -0.00542416 1 0 1 1 0 0 +EDGE2 5462 2722 0.0367417 0.121592 -0.000337712 1 0 1 1 0 0 +EDGE2 5462 2723 1.01133 0.0378105 -0.0233223 1 0 1 1 0 0 +EDGE2 5462 3523 0.942739 -0.0132699 -0.0176673 1 0 1 1 0 0 +EDGE2 5463 3522 -1.04293 -0.120639 -0.00246105 1 0 1 1 0 0 +EDGE2 5463 5462 -1.06026 0.0224984 0.0017427 1 0 1 1 0 0 +EDGE2 5463 2722 -0.910722 0.0410601 -0.0206673 1 0 1 1 0 0 +EDGE2 5463 2724 1.00963 0.153533 -0.0234729 1 0 1 1 0 0 +EDGE2 5463 2723 0.0536066 -0.062394 -0.00309272 1 0 1 1 0 0 +EDGE2 5463 3523 -0.0118155 0.0544866 -0.00479104 1 0 1 1 0 0 +EDGE2 5463 3524 0.984261 -0.0641546 0.0235867 1 0 1 1 0 0 +EDGE2 5464 5463 -0.962663 -0.00550272 -0.0125576 1 0 1 1 0 0 +EDGE2 5464 3525 1.01365 0.0578057 0.00254471 1 0 1 1 0 0 +EDGE2 5464 2724 0.0854062 -0.0319185 0.0137717 1 0 1 1 0 0 +EDGE2 5464 2723 -0.959592 0.0374844 -0.00971733 1 0 1 1 0 0 +EDGE2 5464 3523 -0.968535 -0.0491177 -0.000364198 1 0 1 1 0 0 +EDGE2 5464 3524 -0.00863838 -0.00401782 0.0164497 1 0 1 1 0 0 +EDGE2 5464 2725 0.973522 -0.00356406 -0.0349266 1 0 1 1 0 0 +EDGE2 5465 3525 -0.0597786 0.0781142 -0.0367132 1 0 1 1 0 0 +EDGE2 5465 2724 -0.906933 -0.00299434 -0.000147226 1 0 1 1 0 0 +EDGE2 5465 5464 -0.981234 0.0379077 0.0155636 1 0 1 1 0 0 +EDGE2 5465 3524 -0.981199 0.0988124 0.023268 1 0 1 1 0 0 +EDGE2 5465 3526 -0.00259357 0.965183 1.5385 1 0 1 1 0 0 +EDGE2 5465 2725 0.121813 0.100594 0.0115172 1 0 1 1 0 0 +EDGE2 5465 2726 0.060799 0.992137 1.53961 1 0 1 1 0 0 +EDGE2 5466 3525 -1.07518 -0.0324879 -1.56575 1 0 1 1 0 0 +EDGE2 5466 5465 -1.01005 0.000514666 -1.58014 1 0 1 1 0 0 +EDGE2 5466 3526 -0.00837923 0.0372412 0.00628945 1 0 1 1 0 0 +EDGE2 5466 2725 -0.933781 -0.0256554 -1.56584 1 0 1 1 0 0 +EDGE2 5466 2726 0.000437871 -0.00172752 -0.0147781 1 0 1 1 0 0 +EDGE2 5466 2727 1.11411 0.112578 -0.012346 1 0 1 1 0 0 +EDGE2 5466 3527 0.955374 0.00834124 0.00108735 1 0 1 1 0 0 +EDGE2 5467 2728 0.984456 0.0215898 -0.00461514 1 0 1 1 0 0 +EDGE2 5467 3526 -1.02858 -0.010005 4.55697e-05 1 0 1 1 0 0 +EDGE2 5467 5466 -0.910248 -0.0889884 0.0254269 1 0 1 1 0 0 +EDGE2 5467 2726 -1.06279 -0.0646316 0.0245769 1 0 1 1 0 0 +EDGE2 5467 2727 0.0223985 -0.0467721 0.0145214 1 0 1 1 0 0 +EDGE2 5467 3527 -0.0667714 0.0138586 -0.0202044 1 0 1 1 0 0 +EDGE2 5467 3528 1.10909 -0.0107408 -0.00459823 1 0 1 1 0 0 +EDGE2 5468 2728 0.012791 -0.00616791 -0.0222524 1 0 1 1 0 0 +EDGE2 5468 5467 -1.06409 -0.0166656 -0.00572615 1 0 1 1 0 0 +EDGE2 5468 2727 -0.959986 -0.0132047 -0.0213942 1 0 1 1 0 0 +EDGE2 5468 3527 -1.02294 -0.0612342 -0.0105441 1 0 1 1 0 0 +EDGE2 5468 3528 0.0527718 0.0266643 -0.0080892 1 0 1 1 0 0 +EDGE2 5468 2729 0.998704 0.0634471 -0.00667203 1 0 1 1 0 0 +EDGE2 5468 3529 1.04617 -0.057837 -0.031488 1 0 1 1 0 0 +EDGE2 5469 2728 -1.05541 0.0452765 0.00539941 1 0 1 1 0 0 +EDGE2 5469 5468 -0.956655 -0.0659557 -0.0216557 1 0 1 1 0 0 +EDGE2 5469 3528 -0.965391 0.00432024 -0.0122585 1 0 1 1 0 0 +EDGE2 5469 2729 0.0677638 0.0173163 -0.00814809 1 0 1 1 0 0 +EDGE2 5469 3529 -0.0411782 -0.0341944 -0.035243 1 0 1 1 0 0 +EDGE2 5469 2730 1.00187 -0.00493575 0.0273938 1 0 1 1 0 0 +EDGE2 5469 3530 0.986228 -0.0303463 0.0227845 1 0 1 1 0 0 +EDGE2 5470 2731 -0.0953631 0.968685 1.57175 1 0 1 1 0 0 +EDGE2 5470 2729 -1.11874 -0.00591029 -0.00746757 1 0 1 1 0 0 +EDGE2 5470 3529 -0.977508 0.0243908 -0.045297 1 0 1 1 0 0 +EDGE2 5470 5469 -1.03504 0.0281733 0.00789191 1 0 1 1 0 0 +EDGE2 5470 2730 0.0191801 0.0244261 0.00519876 1 0 1 1 0 0 +EDGE2 5470 3530 -0.0175909 0.0119374 -0.0310994 1 0 1 1 0 0 +EDGE2 5470 3531 0.0305108 -1.04776 -1.58874 1 0 1 1 0 0 +EDGE2 5471 5470 -0.914289 0.0127147 1.55585 1 0 1 1 0 0 +EDGE2 5471 2730 -1.02567 0.0292182 1.59476 1 0 1 1 0 0 +EDGE2 5471 3530 -0.923262 0.0290402 1.58448 1 0 1 1 0 0 +EDGE2 5471 3532 0.98761 0.0204229 0.00370102 1 0 1 1 0 0 +EDGE2 5471 3531 -0.0341796 -0.0359225 -0.00352408 1 0 1 1 0 0 +EDGE2 5472 3532 -0.0458806 -0.0506798 -0.0194448 1 0 1 1 0 0 +EDGE2 5472 3531 -0.968409 0.0616441 0.0148075 1 0 1 1 0 0 +EDGE2 5472 5471 -1.00726 -0.121837 0.00661022 1 0 1 1 0 0 +EDGE2 5472 3533 0.934635 -0.00258897 -0.0333936 1 0 1 1 0 0 +EDGE2 5473 3532 -0.950525 -0.0322668 0.0138532 1 0 1 1 0 0 +EDGE2 5473 5472 -0.960528 -0.0493245 -0.014462 1 0 1 1 0 0 +EDGE2 5473 3533 -0.0029061 -0.0228667 -0.00974021 1 0 1 1 0 0 +EDGE2 5473 3534 1.06514 0.00140845 0.018805 1 0 1 1 0 0 +EDGE2 5474 3533 -1.04568 0.0427551 -0.0307324 1 0 1 1 0 0 +EDGE2 5474 5473 -1.00183 -0.0577262 0.00516223 1 0 1 1 0 0 +EDGE2 5474 3534 0.00777352 -0.065547 0.025596 1 0 1 1 0 0 +EDGE2 5474 3535 1.00788 -0.0532083 -0.0135829 1 0 1 1 0 0 +EDGE2 5475 5474 -0.954964 -0.00817192 -0.0475384 1 0 1 1 0 0 +EDGE2 5475 3534 -1.006 -0.118193 0.00131921 1 0 1 1 0 0 +EDGE2 5475 3535 0.0281421 0.0254834 -0.0229053 1 0 1 1 0 0 +EDGE2 5475 3536 0.0821158 1.05076 1.55923 1 0 1 1 0 0 +EDGE2 5476 5475 -0.97114 -0.0631036 -1.56368 1 0 1 1 0 0 +EDGE2 5476 3535 -0.92363 0.0343284 -1.55337 1 0 1 1 0 0 +EDGE2 5476 3537 0.968359 -0.016146 0.0417199 1 0 1 1 0 0 +EDGE2 5476 3536 0.00657651 -0.0119681 0.0217276 1 0 1 1 0 0 +EDGE2 5477 3537 -0.0427916 0.00402032 -0.0165764 1 0 1 1 0 0 +EDGE2 5477 3536 -0.942478 0.0412546 0.0139876 1 0 1 1 0 0 +EDGE2 5477 5476 -1.02711 0.0103013 0.020726 1 0 1 1 0 0 +EDGE2 5477 3538 1.13789 -0.0702778 -0.0161968 1 0 1 1 0 0 +EDGE2 5478 3537 -0.988641 -0.0502825 -0.00410748 1 0 1 1 0 0 +EDGE2 5478 5477 -0.987157 0.0125715 0.0253096 1 0 1 1 0 0 +EDGE2 5478 3538 -0.0437756 0.0501353 0.00842707 1 0 1 1 0 0 +EDGE2 5478 3539 1.02201 -0.0923863 -0.0289151 1 0 1 1 0 0 +EDGE2 5479 3538 -1.00817 -0.0270346 -0.0088059 1 0 1 1 0 0 +EDGE2 5479 5478 -1.00436 0.0717478 0.0378562 1 0 1 1 0 0 +EDGE2 5479 3539 0.0290892 0.00714312 -0.0229678 1 0 1 1 0 0 +EDGE2 5479 3540 0.995231 0.072689 -0.00538429 1 0 1 1 0 0 +EDGE2 5480 5479 -1.07137 0.0488665 0.0117976 1 0 1 1 0 0 +EDGE2 5480 3539 -1.07101 -0.060019 -0.00488292 1 0 1 1 0 0 +EDGE2 5480 3541 0.0563214 0.848977 1.6033 1 0 1 1 0 0 +EDGE2 5480 3540 0.0814647 -0.00534051 -0.0065385 1 0 1 1 0 0 +EDGE2 5481 3542 0.96882 -0.0788754 0.01063 1 0 1 1 0 0 +EDGE2 5481 5480 -0.949201 -0.142451 -1.58051 1 0 1 1 0 0 +EDGE2 5481 3541 -0.0293634 -0.0276712 -0.014939 1 0 1 1 0 0 +EDGE2 5481 3540 -1.0425 -0.0228438 -1.55331 1 0 1 1 0 0 +EDGE2 5482 3542 -0.0218962 -0.00408311 -0.000728285 1 0 1 1 0 0 +EDGE2 5482 3543 0.966956 -0.03664 -0.0197083 1 0 1 1 0 0 +EDGE2 5482 3541 -1.02105 -0.161868 -0.00655564 1 0 1 1 0 0 +EDGE2 5482 5481 -0.9583 -0.0457337 0.0349897 1 0 1 1 0 0 +EDGE2 5483 3542 -0.951808 0.0284663 -0.0383362 1 0 1 1 0 0 +EDGE2 5483 3543 -0.0212814 0.0252384 -0.0145328 1 0 1 1 0 0 +EDGE2 5483 3544 1.08327 -0.0946563 0.0136926 1 0 1 1 0 0 +EDGE2 5483 5482 -0.969771 0.014328 -0.0100358 1 0 1 1 0 0 +EDGE2 5484 3545 1.02885 0.0571643 -0.00905613 1 0 1 1 0 0 +EDGE2 5484 3543 -1.01804 -0.0926084 0.0258583 1 0 1 1 0 0 +EDGE2 5484 5483 -0.992313 0.0471229 -0.0320113 1 0 1 1 0 0 +EDGE2 5484 3544 0.104673 0.00392978 0.0254136 1 0 1 1 0 0 +EDGE2 5485 3546 0.0130212 -1.02643 -1.60552 1 0 1 1 0 0 +EDGE2 5485 3545 -0.0297324 -0.00111204 0.0193395 1 0 1 1 0 0 +EDGE2 5485 5484 -1.00813 0.0193013 -0.0383478 1 0 1 1 0 0 +EDGE2 5485 3544 -1.0302 0.0273556 0.0299175 1 0 1 1 0 0 +EDGE2 5486 5485 -1.03005 -0.0935227 -1.53964 1 0 1 1 0 0 +EDGE2 5486 3545 -0.992358 0.0669536 -1.61447 1 0 1 1 0 0 +EDGE2 5487 5486 -1.0237 0.0113261 0.0267554 1 0 1 1 0 0 +EDGE2 5488 5487 -0.960114 -0.00353773 0.0327925 1 0 1 1 0 0 +EDGE2 5489 5470 1.01583 -0.034929 -3.14617 1 0 1 1 0 0 +EDGE2 5489 2730 0.926735 0.0419264 -3.13893 1 0 1 1 0 0 +EDGE2 5489 3530 0.922334 0.0447093 -3.13607 1 0 1 1 0 0 +EDGE2 5489 5488 -1.05387 0.00909808 0.00453404 1 0 1 1 0 0 +EDGE2 5490 2731 -0.00820173 -1.09198 -1.54506 1 0 1 1 0 0 +EDGE2 5490 5470 0.0196945 -0.133147 -3.12313 1 0 1 1 0 0 +EDGE2 5490 2729 1.03054 -9.84693e-05 -3.12317 1 0 1 1 0 0 +EDGE2 5490 3529 1.02485 0.0301053 -3.14197 1 0 1 1 0 0 +EDGE2 5490 5469 1.01921 0.0368063 -3.17026 1 0 1 1 0 0 +EDGE2 5490 2730 -0.096253 -0.017622 -3.1474 1 0 1 1 0 0 +EDGE2 5490 3530 -0.0209606 -0.00981499 -3.13676 1 0 1 1 0 0 +EDGE2 5490 5489 -1.0681 0.0502191 0.0153667 1 0 1 1 0 0 +EDGE2 5490 3531 0.0165614 1.05657 1.55058 1 0 1 1 0 0 +EDGE2 5490 5471 0.0225136 0.907808 1.56669 1 0 1 1 0 0 +EDGE2 5491 5470 -1.06207 -0.0250129 1.59644 1 0 1 1 0 0 +EDGE2 5491 5490 -0.959857 0.0149538 -1.56566 1 0 1 1 0 0 +EDGE2 5491 2730 -1.04596 -0.0574438 1.54115 1 0 1 1 0 0 +EDGE2 5491 3530 -1.0469 0.063074 1.60074 1 0 1 1 0 0 +EDGE2 5491 3532 0.932325 0.00238772 -0.00522192 1 0 1 1 0 0 +EDGE2 5491 3531 0.0437782 0.0552565 0.00825349 1 0 1 1 0 0 +EDGE2 5491 5471 -0.00495777 -0.0229481 0.0102 1 0 1 1 0 0 +EDGE2 5491 5472 0.975015 -0.0100487 -0.0137493 1 0 1 1 0 0 +EDGE2 5492 3532 0.0562077 0.0163898 0.0240757 1 0 1 1 0 0 +EDGE2 5492 5491 -0.998068 0.0458671 -0.0090741 1 0 1 1 0 0 +EDGE2 5492 3531 -0.922716 -0.153843 -0.00431374 1 0 1 1 0 0 +EDGE2 5492 5471 -1.00901 -0.00683 -0.018662 1 0 1 1 0 0 +EDGE2 5492 5472 0.0113655 -0.0242107 -0.0303065 1 0 1 1 0 0 +EDGE2 5492 3533 0.982859 -0.0724694 -0.0199603 1 0 1 1 0 0 +EDGE2 5492 5473 0.975152 0.0628792 -0.0111384 1 0 1 1 0 0 +EDGE2 5493 3532 -1.06484 -0.0813704 -0.00798507 1 0 1 1 0 0 +EDGE2 5493 5492 -1.0052 0.0134163 -0.00835963 1 0 1 1 0 0 +EDGE2 5493 5472 -0.999971 -0.078889 0.00970958 1 0 1 1 0 0 +EDGE2 5493 5474 0.950205 -0.0551664 -0.00113231 1 0 1 1 0 0 +EDGE2 5493 3533 -0.0123077 -0.0934761 0.0150955 1 0 1 1 0 0 +EDGE2 5493 5473 -0.0365331 0.0434332 -0.00105783 1 0 1 1 0 0 +EDGE2 5493 3534 0.907961 -0.00585465 -0.00855868 1 0 1 1 0 0 +EDGE2 5494 5474 -0.0681711 -0.0785427 -0.016384 1 0 1 1 0 0 +EDGE2 5494 3533 -0.984666 0.0124765 -0.0367806 1 0 1 1 0 0 +EDGE2 5494 5473 -1.00176 0.067934 -0.0364695 1 0 1 1 0 0 +EDGE2 5494 5493 -1.04505 0.0911452 0.00071212 1 0 1 1 0 0 +EDGE2 5494 5475 0.943002 0.0869422 -0.00307814 1 0 1 1 0 0 +EDGE2 5494 3534 -0.0418783 0.0397011 -0.0268658 1 0 1 1 0 0 +EDGE2 5494 3535 0.983344 -0.00646416 0.0250372 1 0 1 1 0 0 +EDGE2 5495 5474 -1.04265 0.0124883 0.0150997 1 0 1 1 0 0 +EDGE2 5495 5494 -1.08655 0.01973 0.00533793 1 0 1 1 0 0 +EDGE2 5495 5475 -0.0491407 0.0145944 -0.0294361 1 0 1 1 0 0 +EDGE2 5495 3534 -0.986117 -0.0745863 0.0236998 1 0 1 1 0 0 +EDGE2 5495 3535 0.0940396 0.0432131 -0.00347031 1 0 1 1 0 0 +EDGE2 5495 3536 0.000768307 1.07525 1.55102 1 0 1 1 0 0 +EDGE2 5495 5476 -0.0787842 1.07608 1.61037 1 0 1 1 0 0 +EDGE2 5496 5475 -0.9755 0.0973069 1.60163 1 0 1 1 0 0 +EDGE2 5496 5495 -0.979934 -0.021096 1.60088 1 0 1 1 0 0 +EDGE2 5496 3535 -0.915248 0.0384157 1.58395 1 0 1 1 0 0 +EDGE2 5497 5496 -0.986819 0.013151 -0.0186979 1 0 1 1 0 0 +EDGE2 5498 5497 -1.01227 0.0108896 0.0178248 1 0 1 1 0 0 +EDGE2 5499 5498 -1.02902 0.0953755 0.0145477 1 0 1 1 0 0 +EDGE2 5500 5499 -1.03139 0.0509302 0.00596699 1 0 1 1 0 0 +EDGE2 5501 5500 -0.962543 0.0677851 -1.55551 1 0 1 1 0 0 +EDGE2 5502 5501 -0.99767 0.0260894 -0.0139167 1 0 1 1 0 0 +EDGE2 5503 5502 -0.989399 0.0406586 -0.0170057 1 0 1 1 0 0 +EDGE2 5504 5503 -0.915252 -0.015484 0.0207171 1 0 1 1 0 0 +EDGE2 5505 5504 -0.946737 0.0401526 -0.0248791 1 0 1 1 0 0 +EDGE2 5506 5505 -1.07947 -0.0530967 -1.57027 1 0 1 1 0 0 +EDGE2 5507 5506 -0.964162 -0.0895522 -0.0059465 1 0 1 1 0 0 +EDGE2 5508 5507 -0.970574 0.0528561 0.0317861 1 0 1 1 0 0 +EDGE2 5509 5508 -1.05736 -0.0602671 0.0167329 1 0 1 1 0 0 +EDGE2 5510 5509 -1.11033 0.0166669 -0.0272448 1 0 1 1 0 0 +EDGE2 5511 5510 -0.997534 -0.0188242 1.55938 1 0 1 1 0 0 +EDGE2 5512 5511 -0.957683 0.0110492 0.0553125 1 0 1 1 0 0 +EDGE2 5513 5512 -1.07324 0.0330864 0.0233987 1 0 1 1 0 0 +EDGE2 5514 5513 -1.02348 -0.0680962 0.0234293 1 0 1 1 0 0 +EDGE2 5515 5514 -0.965323 0.0424829 0.0018701 1 0 1 1 0 0 +EDGE2 5516 5515 -1.03562 0.0298329 -1.59205 1 0 1 1 0 0 +EDGE2 5517 5516 -1.06267 -0.00092706 0.0171815 1 0 1 1 0 0 +EDGE2 5518 5517 -0.909519 -0.0890094 -0.00855964 1 0 1 1 0 0 +EDGE2 5519 4380 1.04685 0.0253712 -3.10839 1 0 1 1 0 0 +EDGE2 5519 5518 -0.968463 0.0182027 0.00134151 1 0 1 1 0 0 +EDGE2 5519 4420 1.10317 0.0135302 -3.14156 1 0 1 1 0 0 +EDGE2 5519 4400 1.01518 0.159491 -3.14062 1 0 1 1 0 0 +EDGE2 5520 4381 -0.0131538 1.06614 1.58763 1 0 1 1 0 0 +EDGE2 5520 4380 -0.0559595 -0.0647399 -3.12131 1 0 1 1 0 0 +EDGE2 5520 5519 -1.00703 0.0422 0.0220626 1 0 1 1 0 0 +EDGE2 5520 4420 0.0209659 -0.00908002 -3.13271 1 0 1 1 0 0 +EDGE2 5520 4400 0.00091361 -0.00734493 -3.16109 1 0 1 1 0 0 +EDGE2 5520 4401 0.0234111 -0.904321 -1.57313 1 0 1 1 0 0 +EDGE2 5520 4421 -0.0387902 -1.02309 -1.58064 1 0 1 1 0 0 +EDGE2 5520 4399 1.04411 0.0488138 -3.16258 1 0 1 1 0 0 +EDGE2 5520 4419 0.984967 -0.010816 -3.14105 1 0 1 1 0 0 +EDGE2 5520 4379 0.970349 0.0203479 -3.1497 1 0 1 1 0 0 +EDGE2 5521 4382 1.0018 -0.0140632 0.00551947 1 0 1 1 0 0 +EDGE2 5521 4381 -0.110819 0.00996675 -0.0279334 1 0 1 1 0 0 +EDGE2 5521 4380 -0.947136 -0.0311906 1.57419 1 0 1 1 0 0 +EDGE2 5521 4420 -0.96121 -0.0637292 1.57428 1 0 1 1 0 0 +EDGE2 5521 5520 -1.05908 -0.0227243 -1.54925 1 0 1 1 0 0 +EDGE2 5521 4400 -0.887231 -0.0158133 1.56455 1 0 1 1 0 0 +EDGE2 5522 4382 -0.0117471 -0.0844899 -0.0348444 1 0 1 1 0 0 +EDGE2 5522 4383 0.987289 0.0156142 0.0180415 1 0 1 1 0 0 +EDGE2 5522 5521 -0.895312 0.0134232 0.00863828 1 0 1 1 0 0 +EDGE2 5522 4381 -0.931414 0.0203535 -0.00321372 1 0 1 1 0 0 +EDGE2 5523 4382 -1.04195 0.0685041 0.00424313 1 0 1 1 0 0 +EDGE2 5523 4384 1.09958 -0.0126098 0.0302473 1 0 1 1 0 0 +EDGE2 5523 4383 0.00895573 0.0367183 -0.000167394 1 0 1 1 0 0 +EDGE2 5523 5522 -0.909643 -0.00565017 0.019961 1 0 1 1 0 0 +EDGE2 5524 4385 0.941576 -0.0565184 -0.0130005 1 0 1 1 0 0 +EDGE2 5524 5523 -0.973284 -0.00487397 -0.000662618 1 0 1 1 0 0 +EDGE2 5524 4384 -0.0703121 -0.0541327 0.0434569 1 0 1 1 0 0 +EDGE2 5524 4383 -1.05017 0.0772045 0.0253706 1 0 1 1 0 0 +EDGE2 5525 4385 0.00581554 -0.0589266 0.0384874 1 0 1 1 0 0 +EDGE2 5525 4384 -1.03035 0.0250052 -0.0296818 1 0 1 1 0 0 +EDGE2 5525 5524 -0.985907 0.0532984 -0.0134715 1 0 1 1 0 0 +EDGE2 5525 4386 0.0147333 -1.05087 -1.58915 1 0 1 1 0 0 +EDGE2 5526 4385 -0.966422 -0.0119651 -1.55199 1 0 1 1 0 0 +EDGE2 5526 5525 -0.993078 0.0469307 -1.57867 1 0 1 1 0 0 +EDGE2 5527 5526 -0.921363 0.0126199 0.0207944 1 0 1 1 0 0 +EDGE2 5528 5527 -0.909645 0.0139618 -0.0158661 1 0 1 1 0 0 +EDGE2 5529 5510 0.964038 0.0583879 -3.12343 1 0 1 1 0 0 +EDGE2 5529 5528 -0.980476 0.109599 -0.0200612 1 0 1 1 0 0 +EDGE2 5530 5509 1.00972 -0.0188511 -3.14953 1 0 1 1 0 0 +EDGE2 5530 5510 -0.0592085 -0.00947353 -3.10976 1 0 1 1 0 0 +EDGE2 5530 5511 0.0331983 1.05248 1.54504 1 0 1 1 0 0 +EDGE2 5530 5529 -1.0224 0.0534668 -0.01281 1 0 1 1 0 0 +EDGE2 5531 5510 -1.00492 -0.0107613 1.58598 1 0 1 1 0 0 +EDGE2 5531 5530 -1.09316 0.0552036 -1.57749 1 0 1 1 0 0 +EDGE2 5531 5511 -0.0722117 -0.0076145 0.00241334 1 0 1 1 0 0 +EDGE2 5531 5512 0.975047 0.0357637 -0.0230758 1 0 1 1 0 0 +EDGE2 5532 5511 -0.97076 0.0645032 0.0248184 1 0 1 1 0 0 +EDGE2 5532 5531 -0.997629 0.0570761 -0.00902674 1 0 1 1 0 0 +EDGE2 5532 5512 -0.0194734 -0.111938 -0.00963286 1 0 1 1 0 0 +EDGE2 5532 5513 0.978973 -0.00557859 -0.00724414 1 0 1 1 0 0 +EDGE2 5533 5512 -0.981248 -0.0196513 -0.0155337 1 0 1 1 0 0 +EDGE2 5533 5532 -0.976654 0.0553332 0.00868103 1 0 1 1 0 0 +EDGE2 5533 5513 0.0571932 0.0286693 0.0106209 1 0 1 1 0 0 +EDGE2 5533 5514 0.99892 -0.0207748 -0.0316596 1 0 1 1 0 0 +EDGE2 5534 5513 -1.04687 0.0308102 -0.00270588 1 0 1 1 0 0 +EDGE2 5534 5533 -0.921904 -0.0667493 -0.0126769 1 0 1 1 0 0 +EDGE2 5534 5514 -0.0232288 -0.000619822 -0.00607836 1 0 1 1 0 0 +EDGE2 5534 5515 0.942328 -0.0348029 -0.00271928 1 0 1 1 0 0 +EDGE2 5535 5534 -1.02728 -0.109747 0.00906913 1 0 1 1 0 0 +EDGE2 5535 5514 -1.0343 -0.0140781 -0.00735097 1 0 1 1 0 0 +EDGE2 5535 5515 0.024632 -0.0412583 -0.0278086 1 0 1 1 0 0 +EDGE2 5535 5516 0.0465405 1.00919 1.54134 1 0 1 1 0 0 +EDGE2 5536 5515 -1.02875 -0.00961655 -1.58177 1 0 1 1 0 0 +EDGE2 5536 5535 -0.965224 0.0899546 -1.59376 1 0 1 1 0 0 +EDGE2 5536 5516 0.0147547 0.0254739 0.0047166 1 0 1 1 0 0 +EDGE2 5536 5517 1.02522 0.000148643 0.00216704 1 0 1 1 0 0 +EDGE2 5537 5516 -1.04737 0.11636 0.0286891 1 0 1 1 0 0 +EDGE2 5537 5536 -1.02492 0.0458209 -0.00522382 1 0 1 1 0 0 +EDGE2 5537 5518 1.06795 -0.0418792 -0.011972 1 0 1 1 0 0 +EDGE2 5537 5517 -0.0615742 -0.0864761 0.00445007 1 0 1 1 0 0 +EDGE2 5538 5537 -0.973546 0.0534118 0.00832277 1 0 1 1 0 0 +EDGE2 5538 5518 -0.0181143 0.0361903 -0.0164314 1 0 1 1 0 0 +EDGE2 5538 5517 -1.00679 -0.0823869 -0.00323152 1 0 1 1 0 0 +EDGE2 5538 5519 1.0363 -0.00615737 0.00966918 1 0 1 1 0 0 +EDGE2 5539 4380 0.962417 -0.0411876 -3.13767 1 0 1 1 0 0 +EDGE2 5539 5518 -1.02648 -0.0367531 -0.0165546 1 0 1 1 0 0 +EDGE2 5539 5538 -1.05181 -0.133966 0.00536282 1 0 1 1 0 0 +EDGE2 5539 5519 0.0470819 -0.028315 -0.0224523 1 0 1 1 0 0 +EDGE2 5539 4420 1.03173 0.0121244 -3.1212 1 0 1 1 0 0 +EDGE2 5539 5520 1.07503 -0.0148528 0.0195521 1 0 1 1 0 0 +EDGE2 5539 4400 0.988221 -0.0386808 -3.14399 1 0 1 1 0 0 +EDGE2 5540 5521 -0.00134066 0.99654 1.57976 1 0 1 1 0 0 +EDGE2 5540 4381 -0.00930354 1.04081 1.57369 1 0 1 1 0 0 +EDGE2 5540 4380 -0.0526984 -0.0500519 -3.08747 1 0 1 1 0 0 +EDGE2 5540 5539 -0.999217 0.011879 -0.0132042 1 0 1 1 0 0 +EDGE2 5540 5519 -1.02834 0.0137091 0.0168622 1 0 1 1 0 0 +EDGE2 5540 4420 0.0963784 0.0296252 -3.13447 1 0 1 1 0 0 +EDGE2 5540 5520 -0.048424 0.0153575 0.00801885 1 0 1 1 0 0 +EDGE2 5540 4400 -0.00457805 -0.0713842 -3.15493 1 0 1 1 0 0 +EDGE2 5540 4401 0.0052971 -0.988817 -1.52426 1 0 1 1 0 0 +EDGE2 5540 4421 -0.0571642 -1.01094 -1.55203 1 0 1 1 0 0 +EDGE2 5540 4399 0.938102 0.0130947 -3.13647 1 0 1 1 0 0 +EDGE2 5540 4419 1.02278 0.00031818 -3.13161 1 0 1 1 0 0 +EDGE2 5540 4379 1.03193 -0.0440027 -3.12537 1 0 1 1 0 0 +EDGE2 5541 4380 -1.01024 0.0878831 -1.57555 1 0 1 1 0 0 +EDGE2 5541 5540 -1.00013 0.0230832 1.58891 1 0 1 1 0 0 +EDGE2 5541 4420 -1.14301 0.0236914 -1.60575 1 0 1 1 0 0 +EDGE2 5541 5520 -0.965705 0.00277248 1.58587 1 0 1 1 0 0 +EDGE2 5541 4400 -1.05352 -0.0423575 -1.59812 1 0 1 1 0 0 +EDGE2 5541 4422 0.961667 0.0209943 -0.022742 1 0 1 1 0 0 +EDGE2 5541 4401 0.0307859 0.00797314 0.0102039 1 0 1 1 0 0 +EDGE2 5541 4421 -0.0617114 -0.0185945 -0.00462612 1 0 1 1 0 0 +EDGE2 5541 4402 0.968672 0.0373619 -0.0197402 1 0 1 1 0 0 +EDGE2 5542 4422 -0.0167171 -0.00915935 -0.00753017 1 0 1 1 0 0 +EDGE2 5542 4401 -1.00354 0.0718167 0.0108458 1 0 1 1 0 0 +EDGE2 5542 4421 -0.999302 0.0146386 0.0247366 1 0 1 1 0 0 +EDGE2 5542 5541 -0.912322 -0.0379548 0.0038117 1 0 1 1 0 0 +EDGE2 5542 4402 -0.0718677 -0.00832799 0.0479352 1 0 1 1 0 0 +EDGE2 5542 4403 1.01905 -0.0762246 -0.0134414 1 0 1 1 0 0 +EDGE2 5542 4423 0.981312 -0.037875 -0.0536965 1 0 1 1 0 0 +EDGE2 5543 4422 -0.952806 -0.0705434 -0.0179045 1 0 1 1 0 0 +EDGE2 5543 5542 -0.994619 0.0468616 -0.0347615 1 0 1 1 0 0 +EDGE2 5543 4402 -0.948709 0.0184918 -0.00209015 1 0 1 1 0 0 +EDGE2 5543 4404 1.01778 -0.0173967 -0.0153394 1 0 1 1 0 0 +EDGE2 5543 4403 -0.0714013 -0.024016 0.0317086 1 0 1 1 0 0 +EDGE2 5543 4423 -0.0525999 -0.0333757 -0.00479418 1 0 1 1 0 0 +EDGE2 5543 4424 0.884678 0.0527295 0.0120498 1 0 1 1 0 0 +EDGE2 5544 5543 -1.01578 -0.0162642 0.0380631 1 0 1 1 0 0 +EDGE2 5544 4404 0.0457978 -0.0489292 0.0220261 1 0 1 1 0 0 +EDGE2 5544 4403 -1.01668 -0.0567708 0.0175248 1 0 1 1 0 0 +EDGE2 5544 4423 -1.00405 0.0259065 0.0188346 1 0 1 1 0 0 +EDGE2 5544 4424 0.0251465 0.115712 -0.0225374 1 0 1 1 0 0 +EDGE2 5544 4405 1.00542 -0.0560929 -0.00700931 1 0 1 1 0 0 +EDGE2 5544 4425 0.998236 -0.0317403 -0.0199164 1 0 1 1 0 0 +EDGE2 5545 4406 -0.0198425 0.94884 1.62404 1 0 1 1 0 0 +EDGE2 5545 4404 -0.972583 -0.0251939 -0.0179843 1 0 1 1 0 0 +EDGE2 5545 5544 -1.00766 -0.00486533 0.0057856 1 0 1 1 0 0 +EDGE2 5545 4424 -1.0615 0.00316533 -0.00805178 1 0 1 1 0 0 +EDGE2 5545 4405 0.0789575 -0.0767277 0.0118505 1 0 1 1 0 0 +EDGE2 5545 4425 0.0426282 0.0586145 -0.0167398 1 0 1 1 0 0 +EDGE2 5545 4426 -0.0449282 1.0224 1.5669 1 0 1 1 0 0 +EDGE2 5546 4405 -0.969718 -0.0209433 1.57518 1 0 1 1 0 0 +EDGE2 5546 4425 -1.11318 0.0916547 1.55536 1 0 1 1 0 0 +EDGE2 5546 5545 -0.925502 -0.0453573 1.55578 1 0 1 1 0 0 +EDGE2 5547 5546 -0.998684 -0.0548891 0.0134128 1 0 1 1 0 0 +EDGE2 5548 5547 -0.983816 -0.0352137 -0.0257052 1 0 1 1 0 0 +EDGE2 5549 5548 -1.06188 -0.093958 0.00745593 1 0 1 1 0 0 +EDGE2 5550 5549 -1.04023 -0.00737051 0.035038 1 0 1 1 0 0 +EDGE2 5551 5550 -1.03494 -0.0299454 1.58037 1 0 1 1 0 0 +EDGE2 5552 5551 -1.01629 0.0222933 0.0148386 1 0 1 1 0 0 +EDGE2 5553 5552 -1.05517 -0.0128232 0.0123587 1 0 1 1 0 0 +EDGE2 5554 5515 0.989443 0.10762 -3.13933 1 0 1 1 0 0 +EDGE2 5554 5535 0.975059 -0.000436417 -3.13014 1 0 1 1 0 0 +EDGE2 5554 5553 -1.0166 -0.0092698 -0.0197124 1 0 1 1 0 0 +EDGE2 5555 5534 1.03095 -0.100167 -3.13234 1 0 1 1 0 0 +EDGE2 5555 5514 1.02395 -0.0142495 -3.12422 1 0 1 1 0 0 +EDGE2 5555 5554 -0.935252 0.00401272 -0.0210743 1 0 1 1 0 0 +EDGE2 5555 5515 0.0392301 -0.0650125 -3.13457 1 0 1 1 0 0 +EDGE2 5555 5535 -0.00336675 -0.0527951 -3.14409 1 0 1 1 0 0 +EDGE2 5555 5516 -0.00422992 -0.976577 -1.55764 1 0 1 1 0 0 +EDGE2 5555 5536 -0.00677779 -0.988557 -1.57827 1 0 1 1 0 0 +EDGE2 5556 5555 -0.9878 0.0576572 1.58152 1 0 1 1 0 0 +EDGE2 5556 5537 1.13587 0.00369295 0.00879822 1 0 1 1 0 0 +EDGE2 5556 5515 -0.980412 -0.144005 -1.55154 1 0 1 1 0 0 +EDGE2 5556 5535 -0.97261 -0.0821417 -1.57531 1 0 1 1 0 0 +EDGE2 5556 5516 -0.0726014 0.071171 -0.0202178 1 0 1 1 0 0 +EDGE2 5556 5536 -0.0499991 -0.00627654 -0.0210627 1 0 1 1 0 0 +EDGE2 5556 5517 0.981113 -0.0572251 -0.00991463 1 0 1 1 0 0 +EDGE2 5557 5537 -0.0227599 -0.0176616 0.0288586 1 0 1 1 0 0 +EDGE2 5557 5556 -1.03013 -0.100272 -0.00978343 1 0 1 1 0 0 +EDGE2 5557 5516 -0.995549 0.000942048 0.011814 1 0 1 1 0 0 +EDGE2 5557 5536 -0.955296 -0.0621334 0.00914375 1 0 1 1 0 0 +EDGE2 5557 5518 0.934566 -0.089748 0.00469588 1 0 1 1 0 0 +EDGE2 5557 5517 -0.0761441 0.0638913 -0.00992097 1 0 1 1 0 0 +EDGE2 5557 5538 0.993897 0.00314902 -0.0135512 1 0 1 1 0 0 +EDGE2 5558 5537 -1.00579 -0.0963896 0.0171741 1 0 1 1 0 0 +EDGE2 5558 5557 -0.945549 0.0185054 -0.0162755 1 0 1 1 0 0 +EDGE2 5558 5518 -0.0108015 0.0177646 -0.0165225 1 0 1 1 0 0 +EDGE2 5558 5517 -1.08048 -0.0293759 0.030216 1 0 1 1 0 0 +EDGE2 5558 5538 0.0183929 0.0253366 0.0185778 1 0 1 1 0 0 +EDGE2 5558 5539 1.00567 0.0434002 -0.0104429 1 0 1 1 0 0 +EDGE2 5558 5519 0.895625 -0.0898521 0.0139464 1 0 1 1 0 0 +EDGE2 5559 4380 1.01685 -0.0154992 -3.17322 1 0 1 1 0 0 +EDGE2 5559 5518 -1.06533 0.0381282 0.0090877 1 0 1 1 0 0 +EDGE2 5559 5558 -1.04465 0.0257437 0.0365778 1 0 1 1 0 0 +EDGE2 5559 5538 -1.00729 -0.000595701 -0.0148032 1 0 1 1 0 0 +EDGE2 5559 5539 0.0161745 -0.0896253 -0.0164524 1 0 1 1 0 0 +EDGE2 5559 5519 -0.00857632 0.00647657 -0.0227372 1 0 1 1 0 0 +EDGE2 5559 5540 1.09727 -0.0415134 -0.0143972 1 0 1 1 0 0 +EDGE2 5559 4420 0.983841 -0.0289465 -3.11409 1 0 1 1 0 0 +EDGE2 5559 5520 1.05441 -0.00914238 -0.00723574 1 0 1 1 0 0 +EDGE2 5559 4400 0.890662 0.049061 -3.13901 1 0 1 1 0 0 +EDGE2 5560 5521 0.106729 1.07225 1.56451 1 0 1 1 0 0 +EDGE2 5560 4381 0.0177627 1.02998 1.56063 1 0 1 1 0 0 +EDGE2 5560 4380 0.0656555 0.0671788 -3.14072 1 0 1 1 0 0 +EDGE2 5560 5539 -1.01925 -0.102232 -0.00077012 1 0 1 1 0 0 +EDGE2 5560 5559 -0.880281 -0.0620249 0.0119599 1 0 1 1 0 0 +EDGE2 5560 5519 -1.02091 -0.0900179 -0.0673199 1 0 1 1 0 0 +EDGE2 5560 5540 0.0621218 0.00742923 -0.00731956 1 0 1 1 0 0 +EDGE2 5560 4420 -0.0265302 0.0876312 -3.13312 1 0 1 1 0 0 +EDGE2 5560 5520 0.0305457 0.019989 -0.044016 1 0 1 1 0 0 +EDGE2 5560 4400 0.0243743 0.0622836 -3.16604 1 0 1 1 0 0 +EDGE2 5560 4401 0.0444453 -0.98221 -1.56349 1 0 1 1 0 0 +EDGE2 5560 4421 -0.0896976 -0.956784 -1.55824 1 0 1 1 0 0 +EDGE2 5560 5541 -0.0955508 -1.01425 -1.54327 1 0 1 1 0 0 +EDGE2 5560 4399 0.990094 -0.0318129 -3.14058 1 0 1 1 0 0 +EDGE2 5560 4419 1.05312 -0.0906511 -3.12211 1 0 1 1 0 0 +EDGE2 5560 4379 0.965322 -0.069516 -3.12012 1 0 1 1 0 0 +EDGE2 5561 4382 1.05606 0.061508 0.0292643 1 0 1 1 0 0 +EDGE2 5561 5522 1.02564 -0.0720227 -0.0173264 1 0 1 1 0 0 +EDGE2 5561 5521 -0.00741426 0.0624967 -0.0345068 1 0 1 1 0 0 +EDGE2 5561 4381 0.00324412 0.00105709 0.00234211 1 0 1 1 0 0 +EDGE2 5561 4380 -1.07853 0.0716153 1.54501 1 0 1 1 0 0 +EDGE2 5561 5540 -1.11879 -0.0460783 -1.56116 1 0 1 1 0 0 +EDGE2 5561 5560 -1.02731 0.0368268 -1.55083 1 0 1 1 0 0 +EDGE2 5561 4420 -0.976391 0.0302509 1.56392 1 0 1 1 0 0 +EDGE2 5561 5520 -0.959234 -0.104352 -1.5722 1 0 1 1 0 0 +EDGE2 5561 4400 -0.964214 0.0404919 1.5551 1 0 1 1 0 0 +EDGE2 5562 4382 -0.0745894 0.0463431 0.0439333 1 0 1 1 0 0 +EDGE2 5562 5523 0.977996 0.00111593 0.0239495 1 0 1 1 0 0 +EDGE2 5562 4383 0.990287 0.020876 0.00249746 1 0 1 1 0 0 +EDGE2 5562 5522 0.00655313 -0.0519058 -0.0236874 1 0 1 1 0 0 +EDGE2 5562 5521 -1.04553 0.0115124 0.0290991 1 0 1 1 0 0 +EDGE2 5562 5561 -1.00783 -0.0474113 -0.0211185 1 0 1 1 0 0 +EDGE2 5562 4381 -0.952362 0.111641 0.03785 1 0 1 1 0 0 +EDGE2 5563 4382 -1.02952 0.0304256 -0.0252769 1 0 1 1 0 0 +EDGE2 5563 5523 -0.0184388 -0.00528094 0.0132323 1 0 1 1 0 0 +EDGE2 5563 4384 0.976761 0.126044 0.000253153 1 0 1 1 0 0 +EDGE2 5563 5524 0.969592 -0.0426484 0.0235759 1 0 1 1 0 0 +EDGE2 5563 5562 -0.952982 0.0267706 0.0152757 1 0 1 1 0 0 +EDGE2 5563 4383 -0.00984991 -0.0410823 0.00668797 1 0 1 1 0 0 +EDGE2 5563 5522 -1.04883 0.0341061 -0.0315959 1 0 1 1 0 0 +EDGE2 5564 4385 1.0508 0.0179801 -0.0278842 1 0 1 1 0 0 +EDGE2 5564 5525 1.02004 -0.057257 0.0112911 1 0 1 1 0 0 +EDGE2 5564 5523 -0.964957 -0.0450962 -0.00595585 1 0 1 1 0 0 +EDGE2 5564 4384 -0.00430211 0.0333283 -0.00465958 1 0 1 1 0 0 +EDGE2 5564 5524 0.0455939 0.0186813 0.0135834 1 0 1 1 0 0 +EDGE2 5564 5563 -1.01188 -0.0212948 0.0141468 1 0 1 1 0 0 +EDGE2 5564 4383 -1.06144 0.0415828 0.00148001 1 0 1 1 0 0 +EDGE2 5565 5526 -0.121092 0.975916 1.49854 1 0 1 1 0 0 +EDGE2 5565 5564 -0.9076 -0.0227573 0.00956767 1 0 1 1 0 0 +EDGE2 5565 4385 0.00277931 0.0431357 0.0265621 1 0 1 1 0 0 +EDGE2 5565 5525 -0.0617044 0.045472 0.0117596 1 0 1 1 0 0 +EDGE2 5565 4384 -0.986163 -0.0728988 -0.0014082 1 0 1 1 0 0 +EDGE2 5565 5524 -0.951941 0.0428234 0.013572 1 0 1 1 0 0 +EDGE2 5565 4386 0.00604725 -1.02288 -1.59498 1 0 1 1 0 0 +EDGE2 5566 5527 1.03186 -0.0434652 0.00877241 1 0 1 1 0 0 +EDGE2 5566 5526 0.014877 0.104323 -0.0375894 1 0 1 1 0 0 +EDGE2 5566 4385 -0.960604 -0.00195718 -1.57711 1 0 1 1 0 0 +EDGE2 5566 5525 -0.997394 -0.0323354 -1.60222 1 0 1 1 0 0 +EDGE2 5566 5565 -0.965136 0.00732629 -1.57405 1 0 1 1 0 0 +EDGE2 5567 5527 0.0256422 -0.0515755 0.00166453 1 0 1 1 0 0 +EDGE2 5567 5528 0.999703 -0.0678167 0.00542141 1 0 1 1 0 0 +EDGE2 5567 5566 -1.08559 -0.0504219 -0.00978942 1 0 1 1 0 0 +EDGE2 5567 5526 -1.0204 -0.00107762 0.0194606 1 0 1 1 0 0 +EDGE2 5568 5529 0.903043 0.0172695 0.0346246 1 0 1 1 0 0 +EDGE2 5568 5527 -1.01156 0.0436343 -0.00352274 1 0 1 1 0 0 +EDGE2 5568 5528 0.0262125 -0.163722 0.00950979 1 0 1 1 0 0 +EDGE2 5568 5567 -1.02389 -0.0290554 -0.024945 1 0 1 1 0 0 +EDGE2 5569 5510 1.04546 0.140926 -3.16049 1 0 1 1 0 0 +EDGE2 5569 5530 1.00295 -0.0443676 -0.0152295 1 0 1 1 0 0 +EDGE2 5569 5529 0.016596 -0.0168065 0.00207078 1 0 1 1 0 0 +EDGE2 5569 5528 -1.11215 0.0386442 0.0135502 1 0 1 1 0 0 +EDGE2 5569 5568 -1.07094 -0.0267319 0.0104038 1 0 1 1 0 0 +EDGE2 5570 5509 1.02845 -0.0490298 -3.11714 1 0 1 1 0 0 +EDGE2 5570 5510 0.0098649 0.0421772 -3.1388 1 0 1 1 0 0 +EDGE2 5570 5530 -0.0859891 0.0392721 0.0250509 1 0 1 1 0 0 +EDGE2 5570 5511 -0.0191763 1.01575 1.58461 1 0 1 1 0 0 +EDGE2 5570 5531 -0.00436249 1.01793 1.60258 1 0 1 1 0 0 +EDGE2 5570 5529 -0.960226 0.0155418 -0.0190902 1 0 1 1 0 0 +EDGE2 5570 5569 -0.98271 -0.0599432 -0.0126804 1 0 1 1 0 0 +EDGE2 5571 5510 -0.974688 0.10701 1.58169 1 0 1 1 0 0 +EDGE2 5571 5530 -0.98078 0.0198019 -1.54187 1 0 1 1 0 0 +EDGE2 5571 5570 -1.06455 -0.0375952 -1.57451 1 0 1 1 0 0 +EDGE2 5571 5511 0.0117193 -0.00803684 0.00461147 1 0 1 1 0 0 +EDGE2 5571 5531 -0.115256 0.00063685 -0.030237 1 0 1 1 0 0 +EDGE2 5571 5512 1.04201 0.00554099 0.0391037 1 0 1 1 0 0 +EDGE2 5571 5532 0.930597 -0.0128571 -0.00649869 1 0 1 1 0 0 +EDGE2 5572 5571 -0.987994 0.0373893 -0.0183405 1 0 1 1 0 0 +EDGE2 5572 5511 -1.0061 0.0214148 -0.0167851 1 0 1 1 0 0 +EDGE2 5572 5531 -0.991644 0.0261333 -0.0244496 1 0 1 1 0 0 +EDGE2 5572 5512 -0.0159087 0.0612544 -0.00461148 1 0 1 1 0 0 +EDGE2 5572 5532 -0.0626417 -0.00320512 0.00712806 1 0 1 1 0 0 +EDGE2 5572 5513 0.945252 0.0610167 0.0024229 1 0 1 1 0 0 +EDGE2 5572 5533 0.892165 0.0348075 -0.0222419 1 0 1 1 0 0 +EDGE2 5573 5572 -0.985293 -0.0155134 0.00666448 1 0 1 1 0 0 +EDGE2 5573 5512 -0.996726 -0.00189243 0.0153556 1 0 1 1 0 0 +EDGE2 5573 5532 -0.942835 0.0081481 -0.0304317 1 0 1 1 0 0 +EDGE2 5573 5534 1.02889 -0.0495688 0.0486857 1 0 1 1 0 0 +EDGE2 5573 5513 -0.0101276 -0.0832449 0.0119881 1 0 1 1 0 0 +EDGE2 5573 5533 0.0757553 -0.0347475 0.000662969 1 0 1 1 0 0 +EDGE2 5573 5514 1.00258 -0.103631 -0.0190347 1 0 1 1 0 0 +EDGE2 5574 5555 0.963069 0.0059855 -3.15485 1 0 1 1 0 0 +EDGE2 5574 5573 -1.022 0.0132666 -0.0115146 1 0 1 1 0 0 +EDGE2 5574 5534 0.0755255 0.00238739 -0.032442 1 0 1 1 0 0 +EDGE2 5574 5513 -0.986928 -0.0324583 0.00104973 1 0 1 1 0 0 +EDGE2 5574 5533 -0.950276 -0.00957071 0.0298422 1 0 1 1 0 0 +EDGE2 5574 5514 -0.0276539 -0.0459821 -0.025232 1 0 1 1 0 0 +EDGE2 5574 5515 0.974163 -0.0097001 0.018069 1 0 1 1 0 0 +EDGE2 5574 5535 0.985698 -0.00891785 -0.00429623 1 0 1 1 0 0 +EDGE2 5575 5555 -0.0567828 0.0552327 -3.14162 1 0 1 1 0 0 +EDGE2 5575 5534 -1.04974 -0.00947015 -0.00622134 1 0 1 1 0 0 +EDGE2 5575 5574 -0.961639 0.030412 0.0185908 1 0 1 1 0 0 +EDGE2 5575 5514 -1.01974 -0.00311678 0.00191253 1 0 1 1 0 0 +EDGE2 5575 5554 1.00227 0.00482752 -3.13811 1 0 1 1 0 0 +EDGE2 5575 5556 -0.107031 1.04245 1.53841 1 0 1 1 0 0 +EDGE2 5575 5515 0.030078 0.131456 -0.023751 1 0 1 1 0 0 +EDGE2 5575 5535 0.0473953 0.0472574 -0.0267987 1 0 1 1 0 0 +EDGE2 5575 5516 0.0342013 1.01535 1.57874 1 0 1 1 0 0 +EDGE2 5575 5536 -0.0616811 1.05565 1.59893 1 0 1 1 0 0 +EDGE2 5576 5555 -1.01676 -0.115916 -1.58119 1 0 1 1 0 0 +EDGE2 5576 5575 -0.973456 -0.0511817 1.56992 1 0 1 1 0 0 +EDGE2 5576 5515 -0.942279 -0.0365528 1.58767 1 0 1 1 0 0 +EDGE2 5576 5535 -1.01038 0.0444441 1.56237 1 0 1 1 0 0 +EDGE2 5577 5576 -1.02204 -0.0559235 -0.00330082 1 0 1 1 0 0 +EDGE2 5578 5577 -1.01657 -0.100273 -0.0330045 1 0 1 1 0 0 +EDGE2 5579 5578 -1.01113 -0.0253654 -0.0123947 1 0 1 1 0 0 +EDGE2 5580 5579 -1.0625 -0.0135522 0.00135538 1 0 1 1 0 0 +EDGE2 5581 5580 -1.06538 -0.067365 -1.57729 1 0 1 1 0 0 +EDGE2 5582 5581 -1.06128 -0.0461207 0.0030049 1 0 1 1 0 0 +EDGE2 5583 5582 -0.902825 0.0335849 0.00245017 1 0 1 1 0 0 +EDGE2 5584 5583 -0.935753 -0.0458598 0.0132041 1 0 1 1 0 0 +EDGE2 5585 5584 -1.02603 -0.000805101 0.00782514 1 0 1 1 0 0 +EDGE2 5586 5585 -1.03916 0.0221907 -1.56168 1 0 1 1 0 0 +EDGE2 5587 5586 -1.0454 -0.0466807 -0.0254831 1 0 1 1 0 0 +EDGE2 5588 5587 -0.930901 -0.0600826 -0.0317464 1 0 1 1 0 0 +EDGE2 5589 5588 -1.00871 0.0791594 0.000103321 1 0 1 1 0 0 +EDGE2 5589 5550 0.93057 -0.0305083 -3.16369 1 0 1 1 0 0 +EDGE2 5590 5589 -0.964241 -0.0367675 0.00873688 1 0 1 1 0 0 +EDGE2 5590 5550 -0.0631271 -0.00505293 -3.15129 1 0 1 1 0 0 +EDGE2 5590 5551 0.0624546 1.01643 1.58104 1 0 1 1 0 0 +EDGE2 5590 5549 1.02133 -0.00989487 -3.16956 1 0 1 1 0 0 +EDGE2 5591 5552 0.965796 0.0508154 0.0146767 1 0 1 1 0 0 +EDGE2 5591 5550 -1.08553 -0.0117849 1.58827 1 0 1 1 0 0 +EDGE2 5591 5590 -0.926395 -0.0640331 -1.54461 1 0 1 1 0 0 +EDGE2 5591 5551 0.0657503 0.0450618 -0.0352451 1 0 1 1 0 0 +EDGE2 5592 5591 -1.15016 0.0884517 -0.0258189 1 0 1 1 0 0 +EDGE2 5592 5553 1.05154 -0.000479302 -0.0153861 1 0 1 1 0 0 +EDGE2 5592 5552 0.00935489 -0.031094 -0.0089798 1 0 1 1 0 0 +EDGE2 5592 5551 -0.9459 -0.0530339 0.0132592 1 0 1 1 0 0 +EDGE2 5593 5554 1.00558 -0.0276107 0.00969092 1 0 1 1 0 0 +EDGE2 5593 5592 -1.13731 -0.0116892 0.0237463 1 0 1 1 0 0 +EDGE2 5593 5553 0.0193708 -0.0499648 -0.00597616 1 0 1 1 0 0 +EDGE2 5593 5552 -1.02147 -0.0556812 -0.0199269 1 0 1 1 0 0 +EDGE2 5594 5555 1.05698 0.0473743 -0.0144637 1 0 1 1 0 0 +EDGE2 5594 5575 0.996962 0.0422767 -3.1725 1 0 1 1 0 0 +EDGE2 5594 5554 -0.0792135 -0.0965808 -0.0184516 1 0 1 1 0 0 +EDGE2 5594 5515 0.931226 -0.0277313 -3.15363 1 0 1 1 0 0 +EDGE2 5594 5535 0.964655 -0.0153993 -3.12834 1 0 1 1 0 0 +EDGE2 5594 5553 -0.986951 -0.0445358 -0.00448557 1 0 1 1 0 0 +EDGE2 5594 5593 -1.01305 -0.00518059 0.0620369 1 0 1 1 0 0 +EDGE2 5595 5576 0.0297574 0.905012 1.57763 1 0 1 1 0 0 +EDGE2 5595 5555 -0.110273 0.0181201 -0.0202472 1 0 1 1 0 0 +EDGE2 5595 5534 0.961912 -0.0251332 -3.16634 1 0 1 1 0 0 +EDGE2 5595 5574 1.0047 0.0668769 -3.14542 1 0 1 1 0 0 +EDGE2 5595 5514 0.939233 0.0549808 -3.12976 1 0 1 1 0 0 +EDGE2 5595 5575 0.00973606 0.017988 -3.13907 1 0 1 1 0 0 +EDGE2 5595 5554 -1.12992 0.00777537 -0.0357042 1 0 1 1 0 0 +EDGE2 5595 5556 -0.0207817 -1.01966 -1.55608 1 0 1 1 0 0 +EDGE2 5595 5594 -0.932572 -0.0437506 -0.000714085 1 0 1 1 0 0 +EDGE2 5595 5515 -0.0459588 -0.00860468 -3.11915 1 0 1 1 0 0 +EDGE2 5595 5535 0.00460816 0.0688899 -3.15244 1 0 1 1 0 0 +EDGE2 5595 5516 -0.0216639 -1.02596 -1.55584 1 0 1 1 0 0 +EDGE2 5595 5536 0.0388705 -0.978256 -1.59139 1 0 1 1 0 0 +EDGE2 5596 5555 -1.03946 -0.0783485 1.54885 1 0 1 1 0 0 +EDGE2 5596 5595 -1.02508 0.042334 1.58991 1 0 1 1 0 0 +EDGE2 5596 5575 -0.927183 -0.0268527 -1.54245 1 0 1 1 0 0 +EDGE2 5596 5537 1.08029 -0.0231945 -0.0130297 1 0 1 1 0 0 +EDGE2 5596 5556 -0.00599277 0.103052 0.0170835 1 0 1 1 0 0 +EDGE2 5596 5515 -1.00131 0.0465675 -1.57586 1 0 1 1 0 0 +EDGE2 5596 5535 -0.943473 0.0589622 -1.60729 1 0 1 1 0 0 +EDGE2 5596 5516 -0.0396238 0.0989814 -0.0417906 1 0 1 1 0 0 +EDGE2 5596 5536 0.0650009 0.0361563 0.00683937 1 0 1 1 0 0 +EDGE2 5596 5557 0.996758 -0.0157819 -0.0162782 1 0 1 1 0 0 +EDGE2 5596 5517 1.01426 -0.0091941 -0.000438761 1 0 1 1 0 0 +EDGE2 5597 5537 -0.0435525 0.025815 0.00556619 1 0 1 1 0 0 +EDGE2 5597 5556 -0.92961 0.0636237 -0.0113726 1 0 1 1 0 0 +EDGE2 5597 5596 -0.964185 -0.0416004 -0.0471068 1 0 1 1 0 0 +EDGE2 5597 5516 -0.995122 -0.00185537 0.0306985 1 0 1 1 0 0 +EDGE2 5597 5536 -1.01347 -0.0797316 0.00746162 1 0 1 1 0 0 +EDGE2 5597 5557 0.0319042 0.0718649 -0.00453628 1 0 1 1 0 0 +EDGE2 5597 5518 1.02889 0.0372525 0.0020281 1 0 1 1 0 0 +EDGE2 5597 5558 1.08619 0.00616897 -0.0172189 1 0 1 1 0 0 +EDGE2 5597 5517 -0.0748543 -0.00107413 0.0136639 1 0 1 1 0 0 +EDGE2 5597 5538 0.976026 0.032922 0.0163332 1 0 1 1 0 0 +EDGE2 5598 5537 -0.942518 -0.0435492 -0.0199579 1 0 1 1 0 0 +EDGE2 5598 5597 -1.07579 0.00417986 -0.00301694 1 0 1 1 0 0 +EDGE2 5598 5557 -1.07177 -0.00453194 0.0305031 1 0 1 1 0 0 +EDGE2 5598 5518 0.0200126 0.0381209 0.0160992 1 0 1 1 0 0 +EDGE2 5598 5558 0.0326501 0.0089792 -0.0048338 1 0 1 1 0 0 +EDGE2 5598 5517 -1.00824 -0.0110369 -0.0122687 1 0 1 1 0 0 +EDGE2 5598 5538 0.0112907 0.048907 0.0144166 1 0 1 1 0 0 +EDGE2 5598 5539 1.0724 -0.0199218 -0.010383 1 0 1 1 0 0 +EDGE2 5598 5559 1.01368 0.126668 -0.00789776 1 0 1 1 0 0 +EDGE2 5598 5519 0.974105 0.0839043 0.0345429 1 0 1 1 0 0 +EDGE2 5599 4380 1.06805 -0.0606801 -3.15888 1 0 1 1 0 0 +EDGE2 5599 5518 -0.889554 -0.00386436 0.0336562 1 0 1 1 0 0 +EDGE2 5599 5558 -1.01046 -0.0117044 0.000937563 1 0 1 1 0 0 +EDGE2 5599 5598 -0.996515 -0.0324813 0.0240499 1 0 1 1 0 0 +EDGE2 5599 5538 -0.99792 0.016542 -0.00316568 1 0 1 1 0 0 +EDGE2 5599 5539 -0.00409956 -0.00113606 -0.0370892 1 0 1 1 0 0 +EDGE2 5599 5559 0.02059 0.00992376 -0.0205031 1 0 1 1 0 0 +EDGE2 5599 5519 0.0622038 0.0250667 -0.00597935 1 0 1 1 0 0 +EDGE2 5599 5540 0.970279 0.0202847 -0.0227668 1 0 1 1 0 0 +EDGE2 5599 5560 1.02057 -0.0321616 -0.00686849 1 0 1 1 0 0 +EDGE2 5599 4420 0.994303 0.0175753 -3.13631 1 0 1 1 0 0 +EDGE2 5599 5520 1.01318 -0.137403 -0.00242878 1 0 1 1 0 0 +EDGE2 5599 4400 1.04511 -0.0202167 -3.09678 1 0 1 1 0 0 +EDGE2 5600 5521 -0.0404785 0.916537 1.56322 1 0 1 1 0 0 +EDGE2 5600 5561 0.0042417 0.943423 1.5736 1 0 1 1 0 0 +EDGE2 5600 4381 -0.104934 1.05715 1.59344 1 0 1 1 0 0 +EDGE2 5600 4380 0.0909086 -0.04174 -3.15862 1 0 1 1 0 0 +EDGE2 5600 5539 -1.05124 0.0386832 -0.0130767 1 0 1 1 0 0 +EDGE2 5600 5559 -1.14279 -0.0495072 0.0269641 1 0 1 1 0 0 +EDGE2 5600 5599 -0.977417 -0.00244915 0.0177674 1 0 1 1 0 0 +EDGE2 5600 5519 -0.988793 -0.00510951 0.0119245 1 0 1 1 0 0 +EDGE2 5600 5540 0.13267 -0.0579694 0.00534098 1 0 1 1 0 0 +EDGE2 5600 5560 -0.0622188 0.0148532 -0.00322047 1 0 1 1 0 0 +EDGE2 5600 4420 -0.0648949 -0.069936 -3.14993 1 0 1 1 0 0 +EDGE2 5600 5520 0.0163328 0.0357637 0.000915581 1 0 1 1 0 0 +EDGE2 5600 4400 -0.0211434 0.08036 -3.16541 1 0 1 1 0 0 +EDGE2 5600 4401 -0.0108134 -1.04543 -1.57071 1 0 1 1 0 0 +EDGE2 5600 4421 0.0462378 -1.01364 -1.56106 1 0 1 1 0 0 +EDGE2 5600 5541 0.0489351 -0.933808 -1.54213 1 0 1 1 0 0 +EDGE2 5600 4399 0.942996 -0.00222779 -3.13528 1 0 1 1 0 0 +EDGE2 5600 4419 1.03316 -0.00793998 -3.15701 1 0 1 1 0 0 +EDGE2 5600 4379 0.991554 0.0559245 -3.12187 1 0 1 1 0 0 +EDGE2 5601 4382 1.04527 0.00873037 0.00609214 1 0 1 1 0 0 +EDGE2 5601 5562 0.986726 0.0211329 -0.0118625 1 0 1 1 0 0 +EDGE2 5601 5522 0.917104 0.0590061 -0.0100236 1 0 1 1 0 0 +EDGE2 5601 5521 0.0208175 -0.00373351 -0.0147144 1 0 1 1 0 0 +EDGE2 5601 5561 -0.0568311 -0.0583017 -0.0265922 1 0 1 1 0 0 +EDGE2 5601 4381 0.0526322 0.00860136 -0.0266192 1 0 1 1 0 0 +EDGE2 5601 4380 -1.00278 -0.0505633 1.54967 1 0 1 1 0 0 +EDGE2 5601 5600 -0.991773 -0.0373291 -1.5769 1 0 1 1 0 0 +EDGE2 5601 5540 -1.09131 -0.0373753 -1.57048 1 0 1 1 0 0 +EDGE2 5601 5560 -1.04928 -0.038083 -1.54812 1 0 1 1 0 0 +EDGE2 5601 4420 -0.998643 0.110722 1.56794 1 0 1 1 0 0 +EDGE2 5601 5520 -0.967954 0.00120084 -1.56617 1 0 1 1 0 0 +EDGE2 5601 4400 -0.888716 -0.0957043 1.59353 1 0 1 1 0 0 +EDGE2 5602 4382 0.00725949 0.000142828 -0.0197283 1 0 1 1 0 0 +EDGE2 5602 5523 1.06389 -0.0267965 0.000111108 1 0 1 1 0 0 +EDGE2 5602 5563 0.982397 0.0298413 0.0207216 1 0 1 1 0 0 +EDGE2 5602 5562 -0.00587318 0.0469553 0.0246288 1 0 1 1 0 0 +EDGE2 5602 4383 0.956787 0.0334357 0.00910158 1 0 1 1 0 0 +EDGE2 5602 5522 0.0366835 0.0307879 0.0196428 1 0 1 1 0 0 +EDGE2 5602 5521 -1.02592 0.0129547 0.0134532 1 0 1 1 0 0 +EDGE2 5602 5561 -0.994545 0.0219626 -0.0173924 1 0 1 1 0 0 +EDGE2 5602 5601 -0.992233 -0.0327072 0.0158181 1 0 1 1 0 0 +EDGE2 5602 4381 -1.10529 0.0524237 0.0109999 1 0 1 1 0 0 +EDGE2 5603 4382 -0.97668 0.0162604 -0.0165784 1 0 1 1 0 0 +EDGE2 5603 5564 1.05727 -0.000890277 0.00895334 1 0 1 1 0 0 +EDGE2 5603 5523 -0.0142174 -0.082073 0.0158504 1 0 1 1 0 0 +EDGE2 5603 4384 1.03798 0.00684833 -0.00503895 1 0 1 1 0 0 +EDGE2 5603 5524 1.03328 0.034365 0.0141284 1 0 1 1 0 0 +EDGE2 5603 5563 -0.0673488 0.0616755 -0.0168075 1 0 1 1 0 0 +EDGE2 5603 5562 -0.934867 0.0270749 0.0102439 1 0 1 1 0 0 +EDGE2 5603 5602 -0.985274 0.0970829 -0.0125773 1 0 1 1 0 0 +EDGE2 5603 4383 -0.0229238 -0.0258253 -0.0155262 1 0 1 1 0 0 +EDGE2 5603 5522 -1.00281 0.0899237 0.0123423 1 0 1 1 0 0 +EDGE2 5604 5564 -0.0105325 -0.0228433 -0.00157612 1 0 1 1 0 0 +EDGE2 5604 4385 0.976052 -0.0549723 -0.0263226 1 0 1 1 0 0 +EDGE2 5604 5525 1.01164 0.0113681 0.00982913 1 0 1 1 0 0 +EDGE2 5604 5565 1.05808 0.015057 0.000565102 1 0 1 1 0 0 +EDGE2 5604 5523 -0.908039 -0.0244109 0.0388178 1 0 1 1 0 0 +EDGE2 5604 5603 -1.04684 -0.0358471 0.00506447 1 0 1 1 0 0 +EDGE2 5604 4384 -0.0279886 -0.0039272 -0.00861361 1 0 1 1 0 0 +EDGE2 5604 5524 -0.00349828 -0.0500637 -0.0232061 1 0 1 1 0 0 +EDGE2 5604 5563 -1.011 -0.0348057 2.42304e-05 1 0 1 1 0 0 +EDGE2 5604 4383 -0.909095 -0.00934191 -0.00591546 1 0 1 1 0 0 +EDGE2 5605 5566 -0.00905839 0.915073 1.56243 1 0 1 1 0 0 +EDGE2 5605 5526 0.0595762 0.929722 1.59658 1 0 1 1 0 0 +EDGE2 5605 5564 -0.977114 0.00202821 -0.00752472 1 0 1 1 0 0 +EDGE2 5605 4385 0.00163055 -0.00902092 -0.0135088 1 0 1 1 0 0 +EDGE2 5605 5525 -0.029181 0.0192995 0.0173772 1 0 1 1 0 0 +EDGE2 5605 5565 -0.0427092 0.0640282 0.0303009 1 0 1 1 0 0 +EDGE2 5605 5604 -1.04646 0.0287117 -0.0239757 1 0 1 1 0 0 +EDGE2 5605 4384 -0.958212 0.0500173 0.0275902 1 0 1 1 0 0 +EDGE2 5605 5524 -0.997334 0.00480571 -0.00642989 1 0 1 1 0 0 +EDGE2 5605 4386 0.0847198 -0.983478 -1.58475 1 0 1 1 0 0 +EDGE2 5606 5527 0.992589 0.00194138 -0.012107 1 0 1 1 0 0 +EDGE2 5606 5567 1.11789 0.0979831 0.0171618 1 0 1 1 0 0 +EDGE2 5606 5566 -0.0109637 -0.00512971 -0.000457066 1 0 1 1 0 0 +EDGE2 5606 5526 0.0273169 0.0397596 0.0229125 1 0 1 1 0 0 +EDGE2 5606 5605 -0.986904 0.0117374 -1.55272 1 0 1 1 0 0 +EDGE2 5606 4385 -1.06053 -0.0154101 -1.58709 1 0 1 1 0 0 +EDGE2 5606 5525 -1.05165 -0.0484347 -1.58061 1 0 1 1 0 0 +EDGE2 5606 5565 -1.1223 -0.0780676 -1.57283 1 0 1 1 0 0 +EDGE2 5607 5527 0.0735762 0.00265275 8.97801e-05 1 0 1 1 0 0 +EDGE2 5607 5528 0.974414 0.00362935 -0.00585268 1 0 1 1 0 0 +EDGE2 5607 5568 1.00429 0.0286094 -0.0336157 1 0 1 1 0 0 +EDGE2 5607 5567 0.0491434 -0.0292405 -0.0239102 1 0 1 1 0 0 +EDGE2 5607 5566 -0.993641 0.0301248 0.0357276 1 0 1 1 0 0 +EDGE2 5607 5606 -0.967594 0.0429976 0.0293094 1 0 1 1 0 0 +EDGE2 5607 5526 -0.977476 0.0522765 -0.0160491 1 0 1 1 0 0 +EDGE2 5608 5529 1.00253 -0.00799848 0.0291718 1 0 1 1 0 0 +EDGE2 5608 5569 1.00708 0.00635183 0.0203268 1 0 1 1 0 0 +EDGE2 5608 5527 -1.05967 -0.0226007 -0.0262406 1 0 1 1 0 0 +EDGE2 5608 5607 -1.0254 0.0512847 -0.0125727 1 0 1 1 0 0 +EDGE2 5608 5528 -0.00760775 0.0486096 -0.00586206 1 0 1 1 0 0 +EDGE2 5608 5568 -0.0597623 -0.0114014 0.00984918 1 0 1 1 0 0 +EDGE2 5608 5567 -1.0145 0.036039 0.0137854 1 0 1 1 0 0 +EDGE2 5609 5510 0.98361 0.0213576 -3.1221 1 0 1 1 0 0 +EDGE2 5609 5530 1.01996 -0.0723639 -0.0329801 1 0 1 1 0 0 +EDGE2 5609 5570 1.06868 0.00635492 0.0115249 1 0 1 1 0 0 +EDGE2 5609 5529 -0.0361102 0.0395276 -0.00735461 1 0 1 1 0 0 +EDGE2 5609 5569 -0.030653 0.0703652 0.0323817 1 0 1 1 0 0 +EDGE2 5609 5608 -1.04827 -0.0162169 0.00286254 1 0 1 1 0 0 +EDGE2 5609 5528 -0.969021 0.0606315 0.00360803 1 0 1 1 0 0 +EDGE2 5609 5568 -0.830523 -0.040771 0.00739105 1 0 1 1 0 0 +EDGE2 5610 5509 0.99615 0.0231017 -3.13541 1 0 1 1 0 0 +EDGE2 5610 5571 0.0454572 0.944859 1.56646 1 0 1 1 0 0 +EDGE2 5610 5510 -0.0104879 -0.0568735 -3.1407 1 0 1 1 0 0 +EDGE2 5610 5530 -0.0168183 0.077355 -0.0384304 1 0 1 1 0 0 +EDGE2 5610 5570 -0.0186786 -0.0539411 0.00245715 1 0 1 1 0 0 +EDGE2 5610 5511 -0.032444 1.0057 1.57302 1 0 1 1 0 0 +EDGE2 5610 5531 -0.040271 0.969277 1.54904 1 0 1 1 0 0 +EDGE2 5610 5529 -1.12941 -0.02466 -0.00485234 1 0 1 1 0 0 +EDGE2 5610 5569 -0.940078 -0.0738214 -0.0174067 1 0 1 1 0 0 +EDGE2 5610 5609 -0.996661 0.0239587 -0.00250387 1 0 1 1 0 0 +EDGE2 5611 5572 0.932885 0.041001 -0.0202211 1 0 1 1 0 0 +EDGE2 5611 5610 -1.02142 0.0783942 -1.55812 1 0 1 1 0 0 +EDGE2 5611 5571 -0.076769 -0.057197 -0.00378771 1 0 1 1 0 0 +EDGE2 5611 5510 -0.973703 -0.0402975 1.562 1 0 1 1 0 0 +EDGE2 5611 5530 -1.0387 0.0598485 -1.56733 1 0 1 1 0 0 +EDGE2 5611 5570 -1.06719 0.0582458 -1.56157 1 0 1 1 0 0 +EDGE2 5611 5511 0.0835993 -0.0139979 -0.0137372 1 0 1 1 0 0 +EDGE2 5611 5531 0.0573051 0.0836814 -0.0202787 1 0 1 1 0 0 +EDGE2 5611 5512 1.02783 0.0555113 0.00656924 1 0 1 1 0 0 +EDGE2 5611 5532 1.03128 -0.0840132 0.00219407 1 0 1 1 0 0 +EDGE2 5612 5572 0.0791622 0.030322 0.017884 1 0 1 1 0 0 +EDGE2 5612 5571 -1.08082 0.00339636 0.0207094 1 0 1 1 0 0 +EDGE2 5612 5611 -1.00732 0.0188058 0.017987 1 0 1 1 0 0 +EDGE2 5612 5511 -1.07138 0.0517393 -0.0516738 1 0 1 1 0 0 +EDGE2 5612 5531 -1.04453 0.0441766 -0.00634514 1 0 1 1 0 0 +EDGE2 5612 5573 1.04698 0.0167095 0.00391987 1 0 1 1 0 0 +EDGE2 5612 5512 0.13363 0.015908 0.0310549 1 0 1 1 0 0 +EDGE2 5612 5532 0.0326143 -0.0607745 0.0256599 1 0 1 1 0 0 +EDGE2 5612 5513 0.93821 -0.0391077 0.00273096 1 0 1 1 0 0 +EDGE2 5612 5533 1.03414 -0.0331557 0.0119983 1 0 1 1 0 0 +EDGE2 5613 5572 -0.996264 -0.0915821 -0.00866295 1 0 1 1 0 0 +EDGE2 5613 5612 -0.979345 -0.0321636 -0.0188243 1 0 1 1 0 0 +EDGE2 5613 5573 0.0674062 -0.0437982 0.00471038 1 0 1 1 0 0 +EDGE2 5613 5512 -1.01395 0.00358254 0.0099569 1 0 1 1 0 0 +EDGE2 5613 5532 -0.889272 -0.0914032 -0.00473021 1 0 1 1 0 0 +EDGE2 5613 5534 0.969568 -0.00875319 -0.0163267 1 0 1 1 0 0 +EDGE2 5613 5513 0.0386166 0.0179266 0.0444997 1 0 1 1 0 0 +EDGE2 5613 5533 -0.0112293 -0.0692562 0.0112944 1 0 1 1 0 0 +EDGE2 5613 5574 1.05447 0.00894296 -0.00537656 1 0 1 1 0 0 +EDGE2 5613 5514 0.958845 -0.0194297 0.00183112 1 0 1 1 0 0 +EDGE2 5614 5555 1.01691 0.00357357 -3.14478 1 0 1 1 0 0 +EDGE2 5614 5573 -0.949591 -0.00772748 0.0128108 1 0 1 1 0 0 +EDGE2 5614 5613 -1.01685 0.00121947 -0.0124156 1 0 1 1 0 0 +EDGE2 5614 5534 -0.0542874 0.0379432 -0.0331927 1 0 1 1 0 0 +EDGE2 5614 5513 -0.971066 -0.00320739 -0.0160781 1 0 1 1 0 0 +EDGE2 5614 5533 -1.0258 0.000510299 0.00570684 1 0 1 1 0 0 +EDGE2 5614 5574 -0.0909497 0.0010197 -0.021396 1 0 1 1 0 0 +EDGE2 5614 5595 1.07862 -0.143482 -3.15704 1 0 1 1 0 0 +EDGE2 5614 5514 -0.0843995 0.000610538 -0.00577836 1 0 1 1 0 0 +EDGE2 5614 5575 0.919668 -0.0498548 -0.00726621 1 0 1 1 0 0 +EDGE2 5614 5515 1.03103 -0.0487181 0.00454813 1 0 1 1 0 0 +EDGE2 5614 5535 1.02899 0.0769266 0.000173387 1 0 1 1 0 0 +EDGE2 5615 5576 -0.0505091 -0.990846 -1.56703 1 0 1 1 0 0 +EDGE2 5615 5555 -0.0358362 0.0633351 -3.17402 1 0 1 1 0 0 +EDGE2 5615 5534 -1.03389 0.0568676 0.0041238 1 0 1 1 0 0 +EDGE2 5615 5614 -0.919408 -0.0371425 0.0199189 1 0 1 1 0 0 +EDGE2 5615 5574 -1.05417 0.0635488 0.0153252 1 0 1 1 0 0 +EDGE2 5615 5595 -0.0676885 0.0337168 -3.13417 1 0 1 1 0 0 +EDGE2 5615 5514 -0.957789 0.0276902 -0.00270574 1 0 1 1 0 0 +EDGE2 5615 5575 -0.0264394 -0.0415322 0.00558627 1 0 1 1 0 0 +EDGE2 5615 5554 0.95349 0.0492804 -3.1701 1 0 1 1 0 0 +EDGE2 5615 5556 0.00465809 0.939362 1.60271 1 0 1 1 0 0 +EDGE2 5615 5594 0.973835 -0.0225918 -3.11109 1 0 1 1 0 0 +EDGE2 5615 5515 0.0384346 -0.102694 0.0210579 1 0 1 1 0 0 +EDGE2 5615 5535 0.0451052 0.0335509 -0.00254127 1 0 1 1 0 0 +EDGE2 5615 5596 0.0560782 1.02723 1.57397 1 0 1 1 0 0 +EDGE2 5615 5516 -0.0447444 0.893645 1.57376 1 0 1 1 0 0 +EDGE2 5615 5536 0.0151744 0.984928 1.56046 1 0 1 1 0 0 +EDGE2 5616 5577 1.04788 -0.00509842 0.00890747 1 0 1 1 0 0 +EDGE2 5616 5576 0.0352699 -0.00170315 0.00391585 1 0 1 1 0 0 +EDGE2 5616 5555 -1.0049 -0.0307287 -1.5684 1 0 1 1 0 0 +EDGE2 5616 5595 -1.02089 0.0325963 -1.58328 1 0 1 1 0 0 +EDGE2 5616 5615 -1.01814 -0.0278347 1.5664 1 0 1 1 0 0 +EDGE2 5616 5575 -0.941096 -0.0171808 1.55052 1 0 1 1 0 0 +EDGE2 5616 5515 -0.910974 -0.0285127 1.58384 1 0 1 1 0 0 +EDGE2 5616 5535 -1.08115 0.0194256 1.59583 1 0 1 1 0 0 +EDGE2 5617 5578 0.962825 0.0395574 -0.0191002 1 0 1 1 0 0 +EDGE2 5617 5616 -1.03834 0.0292256 0.00967056 1 0 1 1 0 0 +EDGE2 5617 5577 -0.0151367 0.0474806 -0.0505582 1 0 1 1 0 0 +EDGE2 5617 5576 -1.06529 -0.0222785 0.0165467 1 0 1 1 0 0 +EDGE2 5618 5578 -0.0219413 -0.0466319 -0.0101329 1 0 1 1 0 0 +EDGE2 5618 5579 1.07572 0.0091286 -0.0549353 1 0 1 1 0 0 +EDGE2 5618 5577 -1.01899 -0.0186729 0.018618 1 0 1 1 0 0 +EDGE2 5618 5617 -1.00835 0.024383 -0.00270105 1 0 1 1 0 0 +EDGE2 5619 5580 1.09437 -0.05553 -0.0211936 1 0 1 1 0 0 +EDGE2 5619 5578 -1.1002 0.0222559 -0.013955 1 0 1 1 0 0 +EDGE2 5619 5579 -0.067671 0.0413271 -0.000921614 1 0 1 1 0 0 +EDGE2 5619 5618 -0.950901 -0.0485677 -0.0345646 1 0 1 1 0 0 +EDGE2 5620 5580 -0.0365335 0.0717117 0.0148015 1 0 1 1 0 0 +EDGE2 5620 5581 0.00631918 0.983116 1.54991 1 0 1 1 0 0 +EDGE2 5620 5579 -1.00692 -0.0150573 0.0344077 1 0 1 1 0 0 +EDGE2 5620 5619 -1.0984 -0.0342682 0.0136681 1 0 1 1 0 0 +EDGE2 5621 5582 0.960638 -0.0284802 0.0283163 1 0 1 1 0 0 +EDGE2 5621 5580 -1.0247 0.0702764 -1.58192 1 0 1 1 0 0 +EDGE2 5621 5620 -1.01497 -0.0408294 -1.60336 1 0 1 1 0 0 +EDGE2 5621 5581 0.0741634 0.0412287 0.0141852 1 0 1 1 0 0 +EDGE2 5622 5582 -0.103997 -0.0462698 0.0417247 1 0 1 1 0 0 +EDGE2 5622 5621 -1.0128 -0.000410288 -0.0281175 1 0 1 1 0 0 +EDGE2 5622 5581 -0.98125 -0.0744587 0.000972331 1 0 1 1 0 0 +EDGE2 5622 5583 1.05746 0.0136186 0.00910964 1 0 1 1 0 0 +EDGE2 5623 5582 -0.958395 0.0916947 0.0219981 1 0 1 1 0 0 +EDGE2 5623 5622 -1.0236 0.0460708 -0.0140499 1 0 1 1 0 0 +EDGE2 5623 5583 -0.0904353 -0.00538127 0.00575772 1 0 1 1 0 0 +EDGE2 5623 5584 1.04762 -0.00316311 -0.0389313 1 0 1 1 0 0 +EDGE2 5624 5583 -0.962967 0.0152995 0.0320734 1 0 1 1 0 0 +EDGE2 5624 5623 -1.01279 -0.0335861 -0.0210842 1 0 1 1 0 0 +EDGE2 5624 5584 0.046304 0.0596624 -0.000333662 1 0 1 1 0 0 +EDGE2 5624 5585 0.924321 0.0148721 0.00542607 1 0 1 1 0 0 +EDGE2 5625 5586 0.020351 1.03473 1.5235 1 0 1 1 0 0 +EDGE2 5625 5584 -0.840571 -0.0817899 -0.0156872 1 0 1 1 0 0 +EDGE2 5625 5624 -1.01732 -0.025478 0.00981997 1 0 1 1 0 0 +EDGE2 5625 5585 0.0179538 0.0366523 0.00978411 1 0 1 1 0 0 +EDGE2 5626 5625 -0.939864 0.0639613 1.54685 1 0 1 1 0 0 +EDGE2 5626 5585 -0.939198 -0.0418261 1.57597 1 0 1 1 0 0 +EDGE2 5627 5626 -0.934942 -0.0550453 -0.0124083 1 0 1 1 0 0 +EDGE2 5628 5627 -1.01378 0.0991454 -0.00522852 1 0 1 1 0 0 +EDGE2 5629 5628 -0.965434 -0.0691538 -0.0173571 1 0 1 1 0 0 +EDGE2 5630 5629 -1.06919 0.0731312 0.00215542 1 0 1 1 0 0 +EDGE2 5631 5630 -1.00665 0.0215994 1.58349 1 0 1 1 0 0 +EDGE2 5632 5631 -0.979256 0.096283 -0.00796855 1 0 1 1 0 0 +EDGE2 5633 5632 -0.906495 -0.0401249 -0.0395671 1 0 1 1 0 0 +EDGE2 5634 5633 -1.10103 -0.0405885 -0.00886672 1 0 1 1 0 0 +EDGE2 5635 5634 -0.962956 0.0391064 0.0309699 1 0 1 1 0 0 +EDGE2 5636 5635 -1.00049 0.0726056 -1.59502 1 0 1 1 0 0 +EDGE2 5637 5636 -0.99036 -0.0727395 -0.0172959 1 0 1 1 0 0 +EDGE2 5638 5637 -1.0535 -0.0830581 0.0562286 1 0 1 1 0 0 +EDGE2 5639 5638 -0.978138 -0.0257023 -0.0520478 1 0 1 1 0 0 +EDGE2 5640 5639 -1.0335 -0.056329 -0.0270653 1 0 1 1 0 0 +EDGE2 5641 5640 -1.00387 0.0412721 1.58741 1 0 1 1 0 0 +EDGE2 5642 5641 -1.09773 -0.0115244 0.000182772 1 0 1 1 0 0 +EDGE2 5643 5642 -1.10092 0.0493938 0.0274005 1 0 1 1 0 0 +EDGE2 5644 5643 -0.963893 0.0388961 -0.00524579 1 0 1 1 0 0 +EDGE2 5645 5644 -0.946325 -0.0370551 0.000736454 1 0 1 1 0 0 +EDGE2 5646 5645 -0.965355 -0.00485282 1.5414 1 0 1 1 0 0 +EDGE2 5647 5646 -0.978013 0.0679479 0.0148377 1 0 1 1 0 0 +EDGE2 5648 5647 -1.00283 -0.007543 0.0025815 1 0 1 1 0 0 +EDGE2 5649 5648 -0.965652 -0.0175083 -0.0155776 1 0 1 1 0 0 +EDGE2 5650 5649 -0.9792 -0.0649283 -0.0254969 1 0 1 1 0 0 +EDGE2 5651 5650 -0.938906 0.0043209 -1.56337 1 0 1 1 0 0 +EDGE2 5652 5651 -0.952323 -0.0161103 -0.0076914 1 0 1 1 0 0 +EDGE2 5653 5652 -0.985153 -0.0393644 0.00551452 1 0 1 1 0 0 +EDGE2 5654 5653 -0.995504 0.0188228 0.0375876 1 0 1 1 0 0 +EDGE2 5655 5654 -0.924569 -0.0505017 0.013666 1 0 1 1 0 0 +EDGE2 5656 5655 -0.95401 0.084506 -1.56545 1 0 1 1 0 0 +EDGE2 5657 5656 -1.03211 0.0180179 0.0223369 1 0 1 1 0 0 +EDGE2 5658 5657 -1.04694 -0.0338072 -0.0147197 1 0 1 1 0 0 +EDGE2 5659 1100 1.02052 0.0934587 -3.13384 1 0 1 1 0 0 +EDGE2 5659 1140 0.910377 -0.0750065 -3.11423 1 0 1 1 0 0 +EDGE2 5659 3040 0.94088 -0.0302489 -3.15278 1 0 1 1 0 0 +EDGE2 5659 1120 0.929562 -0.0172944 -3.17751 1 0 1 1 0 0 +EDGE2 5659 5658 -0.999279 -0.0292932 0.00542126 1 0 1 1 0 0 +EDGE2 5660 1139 1.03338 -0.055463 -3.15084 1 0 1 1 0 0 +EDGE2 5660 3039 0.990017 -0.106423 -3.18028 1 0 1 1 0 0 +EDGE2 5660 1099 1.02656 -0.0106014 -3.13307 1 0 1 1 0 0 +EDGE2 5660 1119 1.04672 -0.00879352 -3.1478 1 0 1 1 0 0 +EDGE2 5660 1121 -0.00574256 -0.977798 -1.60649 1 0 1 1 0 0 +EDGE2 5660 3041 -0.0184464 -0.997171 -1.57309 1 0 1 1 0 0 +EDGE2 5660 1141 -0.0789482 -1.06019 -1.56511 1 0 1 1 0 0 +EDGE2 5660 1101 0.0793378 -1.00679 -1.60997 1 0 1 1 0 0 +EDGE2 5660 1100 -0.0182325 0.037923 -3.16022 1 0 1 1 0 0 +EDGE2 5660 1140 -0.0157685 -0.0447879 -3.13358 1 0 1 1 0 0 +EDGE2 5660 3040 -0.00246034 0.0218549 -3.16327 1 0 1 1 0 0 +EDGE2 5660 1120 -0.0264822 0.00927333 -3.12315 1 0 1 1 0 0 +EDGE2 5660 5659 -0.957206 0.0689828 0.00889597 1 0 1 1 0 0 +EDGE2 5661 1100 -1.02841 0.0538664 1.56055 1 0 1 1 0 0 +EDGE2 5661 1140 -1.04218 -0.0868703 1.5911 1 0 1 1 0 0 +EDGE2 5661 3040 -0.95122 0.0184177 1.56803 1 0 1 1 0 0 +EDGE2 5661 5660 -1.00934 0.0398368 -1.57457 1 0 1 1 0 0 +EDGE2 5661 1120 -0.96255 -0.00739571 1.57737 1 0 1 1 0 0 +EDGE2 5662 5661 -0.926086 -0.0180088 0.00125543 1 0 1 1 0 0 +EDGE2 5663 5662 -1.03765 0.0227414 -0.0356762 1 0 1 1 0 0 +EDGE2 5664 5645 1.04943 -0.0504127 -3.13197 1 0 1 1 0 0 +EDGE2 5664 5663 -1.08161 0.0114507 0.00470599 1 0 1 1 0 0 +EDGE2 5665 5645 0.0414791 -0.0437517 -3.1416 1 0 1 1 0 0 +EDGE2 5665 5664 -1.00717 -0.106893 0.011218 1 0 1 1 0 0 +EDGE2 5665 5644 1.10758 0.0610699 -3.16273 1 0 1 1 0 0 +EDGE2 5665 5646 -0.061676 0.944001 1.53683 1 0 1 1 0 0 +EDGE2 5666 5645 -1.0019 0.0465332 1.55131 1 0 1 1 0 0 +EDGE2 5666 5665 -1.07731 0.0204568 -1.55478 1 0 1 1 0 0 +EDGE2 5666 5646 0.0242277 0.0880767 -0.00549725 1 0 1 1 0 0 +EDGE2 5666 5647 1.03995 0.073924 -0.0213044 1 0 1 1 0 0 +EDGE2 5667 5646 -0.932418 -0.0165992 -0.0289922 1 0 1 1 0 0 +EDGE2 5667 5666 -0.99427 -0.0233291 0.00358121 1 0 1 1 0 0 +EDGE2 5667 5647 0.0184244 -0.00602332 0.000192032 1 0 1 1 0 0 +EDGE2 5667 5648 0.991057 -0.00283271 0.0107889 1 0 1 1 0 0 +EDGE2 5668 5647 -0.97004 0.0289863 0.0106846 1 0 1 1 0 0 +EDGE2 5668 5667 -0.996569 0.0352936 -0.0173695 1 0 1 1 0 0 +EDGE2 5668 5649 0.959928 -0.000861558 0.0217405 1 0 1 1 0 0 +EDGE2 5668 5648 0.00751665 -0.0162084 -0.00541374 1 0 1 1 0 0 +EDGE2 5669 5668 -1.02764 -0.093897 -0.0111502 1 0 1 1 0 0 +EDGE2 5669 5649 0.0425707 -0.00441475 -0.0173384 1 0 1 1 0 0 +EDGE2 5669 5648 -1.03847 0.0233372 -0.0111442 1 0 1 1 0 0 +EDGE2 5669 5650 0.928892 0.0931789 0.0308664 1 0 1 1 0 0 +EDGE2 5670 5649 -0.929263 0.0559609 -0.0303804 1 0 1 1 0 0 +EDGE2 5670 5669 -0.947899 -0.0165106 0.0025922 1 0 1 1 0 0 +EDGE2 5670 5651 -0.00532147 0.965314 1.57133 1 0 1 1 0 0 +EDGE2 5670 5650 -0.0224916 -0.00953788 0.0296001 1 0 1 1 0 0 +EDGE2 5671 5670 -0.917319 0.082375 1.5726 1 0 1 1 0 0 +EDGE2 5671 5650 -1.00884 -0.0247648 1.57177 1 0 1 1 0 0 +EDGE2 5672 5671 -0.972108 -0.00666474 -0.00492308 1 0 1 1 0 0 +EDGE2 5673 5672 -0.991941 0.0335271 -0.00105975 1 0 1 1 0 0 +EDGE2 5674 5673 -1.03 -0.000817824 -0.00598553 1 0 1 1 0 0 +EDGE2 5674 5635 1.05028 -0.00483813 -3.1524 1 0 1 1 0 0 +EDGE2 5675 5674 -0.989081 -0.0518148 -0.00289784 1 0 1 1 0 0 +EDGE2 5675 5636 -0.00535109 -1.00637 -1.58001 1 0 1 1 0 0 +EDGE2 5675 5635 0.00250519 -0.0829159 -3.11011 1 0 1 1 0 0 +EDGE2 5675 5634 1.08268 -0.0611927 -3.15052 1 0 1 1 0 0 +EDGE2 5676 5637 1.01605 0.0413248 -0.00432648 1 0 1 1 0 0 +EDGE2 5676 5636 0.0127824 0.024491 -0.0169869 1 0 1 1 0 0 +EDGE2 5676 5675 -0.951133 0.0709974 1.58738 1 0 1 1 0 0 +EDGE2 5676 5635 -0.974775 0.0773128 -1.5627 1 0 1 1 0 0 +EDGE2 5677 5637 -0.0265016 -0.0541173 0.0038782 1 0 1 1 0 0 +EDGE2 5677 5638 0.988582 0.00461571 0.00971921 1 0 1 1 0 0 +EDGE2 5677 5676 -0.995163 -0.0874755 0.0211902 1 0 1 1 0 0 +EDGE2 5677 5636 -1.01027 -0.0355479 -0.00489178 1 0 1 1 0 0 +EDGE2 5678 5639 0.966471 -0.0903209 0.0276319 1 0 1 1 0 0 +EDGE2 5678 5637 -0.901824 0.0603928 -0.00546298 1 0 1 1 0 0 +EDGE2 5678 5638 0.083529 -0.0329222 0.00925087 1 0 1 1 0 0 +EDGE2 5678 5677 -1.05371 0.0483277 0.0119152 1 0 1 1 0 0 +EDGE2 5679 5640 1.12073 0.0263304 0.0143428 1 0 1 1 0 0 +EDGE2 5679 5639 -0.0561627 -0.0548797 -0.0140648 1 0 1 1 0 0 +EDGE2 5679 5678 -0.930656 -0.0239581 0.0216955 1 0 1 1 0 0 +EDGE2 5679 5638 -0.988968 0.0572449 0.00203356 1 0 1 1 0 0 +EDGE2 5680 5641 -0.00259735 -1.00992 -1.59553 1 0 1 1 0 0 +EDGE2 5680 5640 0.0167658 -0.0446966 -0.0146818 1 0 1 1 0 0 +EDGE2 5680 5679 -1.01366 -0.0428331 -0.0158763 1 0 1 1 0 0 +EDGE2 5680 5639 -0.949792 0.0771882 -0.0126833 1 0 1 1 0 0 +EDGE2 5681 5640 -0.979005 -0.0451625 -1.59437 1 0 1 1 0 0 +EDGE2 5681 5680 -1.08292 0.0142352 -1.57307 1 0 1 1 0 0 +EDGE2 5682 5681 -0.960474 -0.0102418 0.0253996 1 0 1 1 0 0 +EDGE2 5683 5682 -1.00974 -0.0443995 0.00945395 1 0 1 1 0 0 +EDGE2 5684 5683 -1.03082 -0.0131635 0.0292445 1 0 1 1 0 0 +EDGE2 5685 5684 -1.00235 0.0550934 0.0149314 1 0 1 1 0 0 +EDGE2 5686 5685 -1.03056 -0.0324873 -1.57131 1 0 1 1 0 0 +EDGE2 5687 5686 -0.9798 -0.0246418 0.00670152 1 0 1 1 0 0 +EDGE2 5688 5687 -0.950505 0.0219769 -0.0298535 1 0 1 1 0 0 +EDGE2 5689 5688 -1.01238 0.100442 0.0241934 1 0 1 1 0 0 +EDGE2 5689 5630 1.03513 -0.103034 -3.10064 1 0 1 1 0 0 +EDGE2 5690 5689 -1.02323 0.0402727 0.0198596 1 0 1 1 0 0 +EDGE2 5690 5630 0.0174647 -0.0201397 -3.1231 1 0 1 1 0 0 +EDGE2 5690 5631 0.0136592 0.993154 1.55505 1 0 1 1 0 0 +EDGE2 5690 5629 1.04377 -0.0613469 -3.14987 1 0 1 1 0 0 +EDGE2 5691 5632 0.938851 0.0130832 -0.0067538 1 0 1 1 0 0 +EDGE2 5691 5630 -0.978969 0.130033 1.51811 1 0 1 1 0 0 +EDGE2 5691 5631 0.0294211 -0.0078625 0.0239059 1 0 1 1 0 0 +EDGE2 5691 5690 -0.976877 -0.074259 -1.56495 1 0 1 1 0 0 +EDGE2 5692 5691 -1.0239 0.00119135 0.0238833 1 0 1 1 0 0 +EDGE2 5692 5633 0.98679 0.0423495 -0.019839 1 0 1 1 0 0 +EDGE2 5692 5632 -0.0441904 -0.0276909 0.0196061 1 0 1 1 0 0 +EDGE2 5692 5631 -1.02085 0.0794609 0.00616079 1 0 1 1 0 0 +EDGE2 5693 5634 0.941885 -0.0646055 0.00559655 1 0 1 1 0 0 +EDGE2 5693 5692 -0.923491 -0.0576368 -0.00983112 1 0 1 1 0 0 +EDGE2 5693 5633 -0.0492668 0.0146008 0.0281911 1 0 1 1 0 0 +EDGE2 5693 5632 -1.05317 -0.073896 -0.0077146 1 0 1 1 0 0 +EDGE2 5694 5675 0.983793 -0.00960534 -3.16144 1 0 1 1 0 0 +EDGE2 5694 5635 0.906217 0.0522282 -0.00239934 1 0 1 1 0 0 +EDGE2 5694 5634 0.0196866 -0.0431814 0.0243227 1 0 1 1 0 0 +EDGE2 5694 5633 -0.972514 0.0390218 0.0187611 1 0 1 1 0 0 +EDGE2 5694 5693 -1.00411 -0.0081527 -0.0139874 1 0 1 1 0 0 +EDGE2 5695 5674 0.88929 0.0134077 -3.13178 1 0 1 1 0 0 +EDGE2 5695 5676 -0.0191912 1.00367 1.55765 1 0 1 1 0 0 +EDGE2 5695 5636 -0.0433462 1.05296 1.564 1 0 1 1 0 0 +EDGE2 5695 5675 -0.00886758 -0.03883 -3.14786 1 0 1 1 0 0 +EDGE2 5695 5635 -0.0591431 -0.00219517 0.0240503 1 0 1 1 0 0 +EDGE2 5695 5634 -1.00946 -0.0516264 0.00460906 1 0 1 1 0 0 +EDGE2 5695 5694 -1.02213 -0.0782521 0.0240025 1 0 1 1 0 0 +EDGE2 5696 5637 1.04063 0.0111445 0.0174901 1 0 1 1 0 0 +EDGE2 5696 5677 1.01624 0.00889355 -0.000615438 1 0 1 1 0 0 +EDGE2 5696 5676 0.019524 0.0249013 -0.00574941 1 0 1 1 0 0 +EDGE2 5696 5636 0.052503 0.114656 0.00699997 1 0 1 1 0 0 +EDGE2 5696 5675 -1.0356 -0.01871 1.5433 1 0 1 1 0 0 +EDGE2 5696 5695 -0.999194 -0.0325419 -1.53831 1 0 1 1 0 0 +EDGE2 5696 5635 -1.02015 0.00982982 -1.58869 1 0 1 1 0 0 +EDGE2 5697 5678 0.957558 -0.0979956 0.00568669 1 0 1 1 0 0 +EDGE2 5697 5637 -0.0682737 0.0450081 0.00897781 1 0 1 1 0 0 +EDGE2 5697 5638 0.976738 0.0196596 -0.00852443 1 0 1 1 0 0 +EDGE2 5697 5677 -0.0250412 0.00319227 -0.0281935 1 0 1 1 0 0 +EDGE2 5697 5676 -0.985232 -0.023886 -0.0184643 1 0 1 1 0 0 +EDGE2 5697 5696 -1.02447 -0.0712495 0.00598645 1 0 1 1 0 0 +EDGE2 5697 5636 -0.97366 0.0796619 0.010677 1 0 1 1 0 0 +EDGE2 5698 5679 0.984255 -0.0492206 0.000797466 1 0 1 1 0 0 +EDGE2 5698 5639 0.993787 0.0408519 -0.0113906 1 0 1 1 0 0 +EDGE2 5698 5678 0.0594285 -0.0423138 0.00441168 1 0 1 1 0 0 +EDGE2 5698 5637 -1.07715 -0.0275047 -0.0196054 1 0 1 1 0 0 +EDGE2 5698 5697 -1.06487 0.0155008 -0.0165646 1 0 1 1 0 0 +EDGE2 5698 5638 -0.0222032 0.060198 0.00387449 1 0 1 1 0 0 +EDGE2 5698 5677 -1.02632 -0.110196 0.00298946 1 0 1 1 0 0 +EDGE2 5699 5640 1.06661 -0.0382269 0.0172705 1 0 1 1 0 0 +EDGE2 5699 5680 1.07306 0.0284276 -0.0306029 1 0 1 1 0 0 +EDGE2 5699 5679 -5.37508e-05 -0.00703896 -0.01057 1 0 1 1 0 0 +EDGE2 5699 5639 -0.00184962 0.0593293 -0.00252982 1 0 1 1 0 0 +EDGE2 5699 5678 -1.03167 0.0336647 0.0081442 1 0 1 1 0 0 +EDGE2 5699 5698 -1.00974 -0.012782 -0.0050785 1 0 1 1 0 0 +EDGE2 5699 5638 -1.0307 0.0631802 -0.00485763 1 0 1 1 0 0 +EDGE2 5700 5641 -0.00637921 -0.996112 -1.54873 1 0 1 1 0 0 +EDGE2 5700 5640 0.099951 0.0486585 -0.0371624 1 0 1 1 0 0 +EDGE2 5700 5680 0.0329029 -0.142198 -0.00254162 1 0 1 1 0 0 +EDGE2 5700 5681 0.0864242 0.98173 1.51364 1 0 1 1 0 0 +EDGE2 5700 5679 -1.00949 0.0119276 -0.0054642 1 0 1 1 0 0 +EDGE2 5700 5699 -0.946796 0.0793327 -0.00745698 1 0 1 1 0 0 +EDGE2 5700 5639 -1.0046 0.010214 0.0493142 1 0 1 1 0 0 +EDGE2 5701 5640 -0.972064 0.0309291 -1.57062 1 0 1 1 0 0 +EDGE2 5701 5680 -0.960804 -0.00755128 -1.58261 1 0 1 1 0 0 +EDGE2 5701 5700 -0.861187 0.0311411 -1.56779 1 0 1 1 0 0 +EDGE2 5701 5681 -0.000859189 0.00261805 0.0115094 1 0 1 1 0 0 +EDGE2 5701 5682 0.956553 0.0724728 -0.00297101 1 0 1 1 0 0 +EDGE2 5702 5701 -0.962795 -0.0357105 0.0122046 1 0 1 1 0 0 +EDGE2 5702 5681 -1.03344 -0.0351572 0.010614 1 0 1 1 0 0 +EDGE2 5702 5682 -0.0446942 0.0152023 0.0145476 1 0 1 1 0 0 +EDGE2 5702 5683 0.915674 -0.0565518 -0.010839 1 0 1 1 0 0 +EDGE2 5703 5684 1.03076 -0.0239694 0.0249847 1 0 1 1 0 0 +EDGE2 5703 5702 -1.0505 -0.0713046 -0.000673079 1 0 1 1 0 0 +EDGE2 5703 5682 -0.905069 -0.00863705 0.0108502 1 0 1 1 0 0 +EDGE2 5703 5683 0.0122862 0.021152 -0.00442529 1 0 1 1 0 0 +EDGE2 5704 5684 6.53937e-05 -0.0668868 0.0145908 1 0 1 1 0 0 +EDGE2 5704 5683 -1.00094 0.015151 -0.0261569 1 0 1 1 0 0 +EDGE2 5704 5703 -0.917278 0.071035 -0.0337736 1 0 1 1 0 0 +EDGE2 5704 5685 0.941018 0.0400171 -0.0206944 1 0 1 1 0 0 +EDGE2 5705 5684 -1.03473 0.101306 -0.0427428 1 0 1 1 0 0 +EDGE2 5705 5704 -0.97501 -0.0491182 -0.0269892 1 0 1 1 0 0 +EDGE2 5705 5685 -0.0375569 0.142535 0.00206529 1 0 1 1 0 0 +EDGE2 5705 5686 0.00868673 0.967337 1.57783 1 0 1 1 0 0 +EDGE2 5706 5685 -0.88174 -0.0235385 -1.60489 1 0 1 1 0 0 +EDGE2 5706 5705 -1.08958 -0.00551224 -1.59669 1 0 1 1 0 0 +EDGE2 5706 5686 0.088344 0.0259825 -0.0221309 1 0 1 1 0 0 +EDGE2 5706 5687 0.921757 -0.0865436 0.0104859 1 0 1 1 0 0 +EDGE2 5707 5706 -0.946687 -0.039831 0.00250216 1 0 1 1 0 0 +EDGE2 5707 5686 -0.998225 -0.0062552 0.0149683 1 0 1 1 0 0 +EDGE2 5707 5687 0.000857749 -0.0134576 -0.0221776 1 0 1 1 0 0 +EDGE2 5707 5688 1.02006 -0.093754 0.028182 1 0 1 1 0 0 +EDGE2 5708 5687 -0.913802 0.0489468 -0.0132963 1 0 1 1 0 0 +EDGE2 5708 5707 -1.0618 0.066878 -0.0351834 1 0 1 1 0 0 +EDGE2 5708 5688 -0.0406031 0.0151813 -0.0243224 1 0 1 1 0 0 +EDGE2 5708 5689 0.995485 -0.0321183 0.0209252 1 0 1 1 0 0 +EDGE2 5709 5708 -1.00413 -0.0130217 -0.0129223 1 0 1 1 0 0 +EDGE2 5709 5688 -0.927936 0.0381412 0.010029 1 0 1 1 0 0 +EDGE2 5709 5689 -0.0856179 0.135097 -0.0018793 1 0 1 1 0 0 +EDGE2 5709 5630 0.964864 -0.00819968 -3.14586 1 0 1 1 0 0 +EDGE2 5709 5690 0.985433 -0.00904194 -0.0153335 1 0 1 1 0 0 +EDGE2 5710 5691 0.0724807 0.971779 1.60087 1 0 1 1 0 0 +EDGE2 5710 5709 -1.06532 -0.0602574 0.00279587 1 0 1 1 0 0 +EDGE2 5710 5689 -0.977826 0.00646684 0.0112316 1 0 1 1 0 0 +EDGE2 5710 5630 0.0300863 -0.0104204 -3.14165 1 0 1 1 0 0 +EDGE2 5710 5631 -0.0154357 1.04793 1.56013 1 0 1 1 0 0 +EDGE2 5710 5690 -0.0301507 -0.0317482 0.0100974 1 0 1 1 0 0 +EDGE2 5710 5629 0.982284 -0.13565 -3.13423 1 0 1 1 0 0 +EDGE2 5711 5691 0.0729259 -0.0249038 -0.0356263 1 0 1 1 0 0 +EDGE2 5711 5692 1.00773 -0.0837746 -0.000505756 1 0 1 1 0 0 +EDGE2 5711 5632 1.04952 0.0399132 -0.0297891 1 0 1 1 0 0 +EDGE2 5711 5630 -0.894289 0.0488592 1.55893 1 0 1 1 0 0 +EDGE2 5711 5710 -1.07202 -0.0243543 -1.54171 1 0 1 1 0 0 +EDGE2 5711 5631 0.0547135 0.00715827 -0.00551159 1 0 1 1 0 0 +EDGE2 5711 5690 -0.952964 0.0765554 -1.55783 1 0 1 1 0 0 +EDGE2 5712 5691 -0.97679 -0.0408587 0.0457082 1 0 1 1 0 0 +EDGE2 5712 5692 0.0236965 0.0338704 -0.00264131 1 0 1 1 0 0 +EDGE2 5712 5633 1.07567 -0.050022 0.00694033 1 0 1 1 0 0 +EDGE2 5712 5693 0.978959 -0.0239838 -0.00661317 1 0 1 1 0 0 +EDGE2 5712 5632 0.0348526 -0.0392662 -0.00976835 1 0 1 1 0 0 +EDGE2 5712 5711 -0.96899 0.0261486 -0.0118273 1 0 1 1 0 0 +EDGE2 5712 5631 -0.968168 0.084076 -0.0172272 1 0 1 1 0 0 +EDGE2 5713 5634 0.959669 -0.0387879 -0.0012775 1 0 1 1 0 0 +EDGE2 5713 5694 0.966724 -0.0817555 0.00781454 1 0 1 1 0 0 +EDGE2 5713 5692 -0.986434 -0.078463 0.0431706 1 0 1 1 0 0 +EDGE2 5713 5633 0.101121 -0.00439182 0.00107345 1 0 1 1 0 0 +EDGE2 5713 5693 -0.0202027 0.0841958 0.0205041 1 0 1 1 0 0 +EDGE2 5713 5712 -0.967864 -0.0301977 -0.0186662 1 0 1 1 0 0 +EDGE2 5713 5632 -1.01119 -0.0399044 -0.0105259 1 0 1 1 0 0 +EDGE2 5714 5713 -0.914067 0.0128889 0.00864445 1 0 1 1 0 0 +EDGE2 5714 5675 0.932286 -0.0213773 -3.13543 1 0 1 1 0 0 +EDGE2 5714 5695 1.01844 0.00729164 0.00545796 1 0 1 1 0 0 +EDGE2 5714 5635 1.03498 0.00834565 -0.00668297 1 0 1 1 0 0 +EDGE2 5714 5634 0.0136914 -0.0131062 0.0112905 1 0 1 1 0 0 +EDGE2 5714 5694 0.00764712 0.0873553 0.00916643 1 0 1 1 0 0 +EDGE2 5714 5633 -1.07822 0.0342629 0.00161404 1 0 1 1 0 0 +EDGE2 5714 5693 -0.989311 0.0848511 -0.00317189 1 0 1 1 0 0 +EDGE2 5715 5674 0.976157 -0.0359112 -3.11345 1 0 1 1 0 0 +EDGE2 5715 5676 -0.0521788 0.988118 1.57052 1 0 1 1 0 0 +EDGE2 5715 5696 0.0609101 0.930959 1.54429 1 0 1 1 0 0 +EDGE2 5715 5636 -0.0334349 0.873457 1.55204 1 0 1 1 0 0 +EDGE2 5715 5675 0.0342838 0.0202709 -3.138 1 0 1 1 0 0 +EDGE2 5715 5695 -0.102987 0.0570366 0.0295172 1 0 1 1 0 0 +EDGE2 5715 5635 0.0194868 -0.0687694 0.0146558 1 0 1 1 0 0 +EDGE2 5715 5634 -0.985309 0.0091167 -0.00701922 1 0 1 1 0 0 +EDGE2 5715 5694 -1.01604 -0.0186979 -0.0229999 1 0 1 1 0 0 +EDGE2 5715 5714 -1.00273 -0.105559 0.0344 1 0 1 1 0 0 +EDGE2 5716 5637 1.01833 -0.0716375 0.0201517 1 0 1 1 0 0 +EDGE2 5716 5697 0.98647 -0.0663136 0.0201496 1 0 1 1 0 0 +EDGE2 5716 5677 0.96693 -0.0183227 0.0281038 1 0 1 1 0 0 +EDGE2 5716 5676 0.0346904 0.0158308 -0.0375821 1 0 1 1 0 0 +EDGE2 5716 5696 -0.0187888 -0.00840143 -0.00147361 1 0 1 1 0 0 +EDGE2 5716 5636 -0.0345281 -0.0333064 -0.0155805 1 0 1 1 0 0 +EDGE2 5716 5675 -0.969058 -0.0327446 1.55823 1 0 1 1 0 0 +EDGE2 5716 5695 -1.10149 0.106067 -1.60079 1 0 1 1 0 0 +EDGE2 5716 5715 -0.963485 0.0554216 -1.58689 1 0 1 1 0 0 +EDGE2 5716 5635 -1.0588 0.017867 -1.54403 1 0 1 1 0 0 +EDGE2 5717 5678 0.971445 -0.0811021 0.0477145 1 0 1 1 0 0 +EDGE2 5717 5698 0.888133 0.111571 -0.00218276 1 0 1 1 0 0 +EDGE2 5717 5637 0.0197276 -0.0280716 -0.00220577 1 0 1 1 0 0 +EDGE2 5717 5697 0.0749002 0.099697 0.000173311 1 0 1 1 0 0 +EDGE2 5717 5638 1.02874 -0.0432406 -0.0162459 1 0 1 1 0 0 +EDGE2 5717 5677 -0.0204973 -0.106141 -9.83706e-05 1 0 1 1 0 0 +EDGE2 5717 5676 -1.06458 0.0420872 0.0146939 1 0 1 1 0 0 +EDGE2 5717 5696 -0.925361 0.0503172 -0.00289962 1 0 1 1 0 0 +EDGE2 5717 5716 -1.01184 -0.0447324 -0.0519374 1 0 1 1 0 0 +EDGE2 5717 5636 -0.98074 0.000413961 0.00179102 1 0 1 1 0 0 +EDGE2 5718 5679 0.91767 0.0541724 -0.00482425 1 0 1 1 0 0 +EDGE2 5718 5699 0.968746 0.023332 -0.00953609 1 0 1 1 0 0 +EDGE2 5718 5639 0.932853 0.00748942 0.0226809 1 0 1 1 0 0 +EDGE2 5718 5678 -0.00943214 0.0225176 0.00353228 1 0 1 1 0 0 +EDGE2 5718 5698 -0.0224032 -0.0242658 -0.00638576 1 0 1 1 0 0 +EDGE2 5718 5637 -0.955505 0.0468718 -0.0131902 1 0 1 1 0 0 +EDGE2 5718 5697 -0.986277 -0.0232932 0.00500491 1 0 1 1 0 0 +EDGE2 5718 5717 -1.08272 -0.0380022 -0.00161238 1 0 1 1 0 0 +EDGE2 5718 5638 -0.0337348 -0.0071214 -0.0091684 1 0 1 1 0 0 +EDGE2 5718 5677 -1.02899 -0.017231 -0.021981 1 0 1 1 0 0 +EDGE2 5719 5640 1.10408 0.0209853 -0.00441902 1 0 1 1 0 0 +EDGE2 5719 5680 0.953615 -0.0201603 0.0210808 1 0 1 1 0 0 +EDGE2 5719 5700 1.01974 -0.106711 0.0217152 1 0 1 1 0 0 +EDGE2 5719 5679 0.0180141 0.162021 0.0116932 1 0 1 1 0 0 +EDGE2 5719 5699 0.0479011 -0.0262501 -0.0167344 1 0 1 1 0 0 +EDGE2 5719 5639 0.00633723 -0.0102914 -0.0140452 1 0 1 1 0 0 +EDGE2 5719 5678 -1.0147 0.119459 -0.0254323 1 0 1 1 0 0 +EDGE2 5719 5718 -1.04392 -0.0166286 0.0317503 1 0 1 1 0 0 +EDGE2 5719 5698 -1.01263 -0.0114833 -0.0261466 1 0 1 1 0 0 +EDGE2 5719 5638 -1.08241 -0.0410528 0.000127896 1 0 1 1 0 0 +EDGE2 5720 5701 0.0401851 1.01023 1.55309 1 0 1 1 0 0 +EDGE2 5720 5641 0.0117198 -1.10227 -1.54559 1 0 1 1 0 0 +EDGE2 5720 5640 0.00213183 0.0348502 0.00870341 1 0 1 1 0 0 +EDGE2 5720 5680 -0.0229034 0.00846884 -0.0111995 1 0 1 1 0 0 +EDGE2 5720 5700 0.0507438 -0.00629162 -0.0147293 1 0 1 1 0 0 +EDGE2 5720 5681 -0.00857749 1.0558 1.55046 1 0 1 1 0 0 +EDGE2 5720 5679 -0.989619 0.0881455 0.00616248 1 0 1 1 0 0 +EDGE2 5720 5699 -1.08708 0.0296694 0.0244788 1 0 1 1 0 0 +EDGE2 5720 5719 -0.972444 0.00104918 0.00174524 1 0 1 1 0 0 +EDGE2 5720 5639 -0.934141 -0.0161952 0.00860409 1 0 1 1 0 0 +EDGE2 5721 5701 -0.000742319 0.0248634 -0.0230121 1 0 1 1 0 0 +EDGE2 5721 5720 -1.08194 -0.0555841 -1.60331 1 0 1 1 0 0 +EDGE2 5721 5640 -1.03136 -0.0196174 -1.57041 1 0 1 1 0 0 +EDGE2 5721 5680 -0.969454 0.000672421 -1.56082 1 0 1 1 0 0 +EDGE2 5721 5700 -0.982498 0.0112295 -1.55607 1 0 1 1 0 0 +EDGE2 5721 5702 1.05194 0.0436685 0.0357851 1 0 1 1 0 0 +EDGE2 5721 5681 -0.0557295 0.0155543 0.0103547 1 0 1 1 0 0 +EDGE2 5721 5682 1.03344 0.0140664 0.0241277 1 0 1 1 0 0 +EDGE2 5722 5701 -1.03646 0.0132363 0.00716884 1 0 1 1 0 0 +EDGE2 5722 5721 -1.0871 -0.0390481 -0.00790123 1 0 1 1 0 0 +EDGE2 5722 5702 0.000394727 -0.0396551 -0.00303433 1 0 1 1 0 0 +EDGE2 5722 5681 -0.928992 0.0388957 0.0017297 1 0 1 1 0 0 +EDGE2 5722 5682 0.000976832 -0.0611595 0.0054014 1 0 1 1 0 0 +EDGE2 5722 5683 1.08831 -0.0205044 0.0184005 1 0 1 1 0 0 +EDGE2 5722 5703 0.928883 0.0744232 -0.0119136 1 0 1 1 0 0 +EDGE2 5723 5684 1.05078 -0.0464491 -0.00754812 1 0 1 1 0 0 +EDGE2 5723 5702 -0.961467 -0.098545 0.00480388 1 0 1 1 0 0 +EDGE2 5723 5722 -1.00628 0.0141613 -0.0144108 1 0 1 1 0 0 +EDGE2 5723 5682 -0.937198 0.0474305 -0.012755 1 0 1 1 0 0 +EDGE2 5723 5683 -0.0553702 -0.0968616 -0.00489983 1 0 1 1 0 0 +EDGE2 5723 5703 -0.0528184 0.0218222 0.0152117 1 0 1 1 0 0 +EDGE2 5723 5704 0.91653 -0.0452715 0.023133 1 0 1 1 0 0 +EDGE2 5724 5684 -0.0195655 0.0129121 -0.00693599 1 0 1 1 0 0 +EDGE2 5724 5723 -1.02278 -0.0321339 -0.0134703 1 0 1 1 0 0 +EDGE2 5724 5683 -1.02957 0.0136057 -0.00485144 1 0 1 1 0 0 +EDGE2 5724 5703 -0.992914 -0.0663229 -0.0165321 1 0 1 1 0 0 +EDGE2 5724 5704 -0.0269564 -0.0228652 -0.0145088 1 0 1 1 0 0 +EDGE2 5724 5685 1.01671 -0.0134005 0.0373393 1 0 1 1 0 0 +EDGE2 5724 5705 0.967528 -0.0405399 -0.00885996 1 0 1 1 0 0 +EDGE2 5725 5706 0.0675303 1.01093 1.5702 1 0 1 1 0 0 +EDGE2 5725 5684 -1.01407 -0.0138015 -0.01414 1 0 1 1 0 0 +EDGE2 5725 5724 -0.986593 0.0309608 0.0297516 1 0 1 1 0 0 +EDGE2 5725 5704 -1.00106 0.0222298 0.0150709 1 0 1 1 0 0 +EDGE2 5725 5685 0.054352 -0.0257139 0.0210254 1 0 1 1 0 0 +EDGE2 5725 5705 -0.0195794 0.0158266 0.00941398 1 0 1 1 0 0 +EDGE2 5725 5686 0.00876612 0.987625 1.59104 1 0 1 1 0 0 +EDGE2 5726 5725 -0.95795 -0.0644105 1.57984 1 0 1 1 0 0 +EDGE2 5726 5685 -1.0413 0.00371721 1.55661 1 0 1 1 0 0 +EDGE2 5726 5705 -0.933129 0.0224103 1.56291 1 0 1 1 0 0 +EDGE2 5727 5726 -1.0248 -0.0437019 0.0100027 1 0 1 1 0 0 +EDGE2 5728 5727 -0.955343 -0.0487613 0.0301041 1 0 1 1 0 0 +EDGE2 5729 5728 -0.982089 0.0409844 -0.0324323 1 0 1 1 0 0 +EDGE2 5730 5729 -1.04335 -0.00116114 -0.0163351 1 0 1 1 0 0 +EDGE2 5731 5730 -0.937135 -0.00887729 -1.55226 1 0 1 1 0 0 +EDGE2 5732 5731 -0.935764 -0.0376213 -0.0198239 1 0 1 1 0 0 +EDGE2 5733 5732 -1.01199 0.0356001 0.00369964 1 0 1 1 0 0 +EDGE2 5734 5733 -1.08183 -0.111736 -0.0220556 1 0 1 1 0 0 +EDGE2 5735 5734 -0.980776 -0.00415275 0.0303629 1 0 1 1 0 0 +EDGE2 5736 5735 -0.993207 -0.00158724 -1.55398 1 0 1 1 0 0 +EDGE2 5737 5736 -0.998285 0.00415489 -0.00445087 1 0 1 1 0 0 +EDGE2 5738 5737 -0.990926 0.0245657 -0.0499271 1 0 1 1 0 0 +EDGE2 5739 5738 -0.991654 -0.0526452 -0.0335237 1 0 1 1 0 0 +EDGE2 5740 5739 -0.930016 -0.0662884 -0.0159492 1 0 1 1 0 0 +EDGE2 5741 5740 -1.1176 0.0236827 -1.56763 1 0 1 1 0 0 +EDGE2 5742 5741 -1.09357 -0.0528214 -0.00362597 1 0 1 1 0 0 +EDGE2 5743 5742 -0.966828 -0.0275578 -0.0134522 1 0 1 1 0 0 +EDGE2 5744 5725 1.05635 0.0265957 -3.13379 1 0 1 1 0 0 +EDGE2 5744 5685 0.993928 -0.0961532 -3.14754 1 0 1 1 0 0 +EDGE2 5744 5705 0.952045 0.0490801 -3.16651 1 0 1 1 0 0 +EDGE2 5744 5743 -0.952911 -0.0279204 0.0159659 1 0 1 1 0 0 +EDGE2 5745 5706 0.0732243 -1.0627 -1.55047 1 0 1 1 0 0 +EDGE2 5745 5726 -0.0448947 1.00267 1.57757 1 0 1 1 0 0 +EDGE2 5745 5684 0.868633 0.0147174 -3.15725 1 0 1 1 0 0 +EDGE2 5745 5724 0.9971 0.0440542 -3.14692 1 0 1 1 0 0 +EDGE2 5745 5704 1.06231 -0.0203496 -3.11371 1 0 1 1 0 0 +EDGE2 5745 5725 0.0767528 0.0250077 -3.13988 1 0 1 1 0 0 +EDGE2 5745 5744 -0.95718 0.0169005 -0.018753 1 0 1 1 0 0 +EDGE2 5745 5685 0.0180171 -0.0197073 -3.15003 1 0 1 1 0 0 +EDGE2 5745 5705 -0.00595949 -0.0442251 -3.13015 1 0 1 1 0 0 +EDGE2 5745 5686 0.0427464 -0.986788 -1.58462 1 0 1 1 0 0 +EDGE2 5746 5706 -0.00787237 0.0559339 -0.00096375 1 0 1 1 0 0 +EDGE2 5746 5725 -1.01944 0.0794394 -1.59763 1 0 1 1 0 0 +EDGE2 5746 5745 -1.03595 -0.00234652 1.56406 1 0 1 1 0 0 +EDGE2 5746 5685 -1.07354 -0.166661 -1.58033 1 0 1 1 0 0 +EDGE2 5746 5705 -1.02994 -0.0327671 -1.54702 1 0 1 1 0 0 +EDGE2 5746 5686 0.0440232 0.0181973 -0.0354349 1 0 1 1 0 0 +EDGE2 5746 5687 1.034 0.0408971 -0.0247498 1 0 1 1 0 0 +EDGE2 5746 5707 0.971651 0.00659821 0.00197743 1 0 1 1 0 0 +EDGE2 5747 5706 -1.08463 -0.10784 0.00251703 1 0 1 1 0 0 +EDGE2 5747 5746 -0.930463 -0.00612467 -0.00320888 1 0 1 1 0 0 +EDGE2 5747 5686 -1.03465 -0.0265688 -0.0186792 1 0 1 1 0 0 +EDGE2 5747 5708 0.970692 -0.0900398 0.0118937 1 0 1 1 0 0 +EDGE2 5747 5687 0.0194789 0.0312107 -0.0160552 1 0 1 1 0 0 +EDGE2 5747 5707 -0.00559284 0.039172 -0.0119467 1 0 1 1 0 0 +EDGE2 5747 5688 1.07386 0.074763 -0.00117037 1 0 1 1 0 0 +EDGE2 5748 5708 -0.0794203 -0.00639552 -0.00508554 1 0 1 1 0 0 +EDGE2 5748 5687 -0.938949 0.0388839 -0.00113701 1 0 1 1 0 0 +EDGE2 5748 5707 -1.033 -0.0185925 0.0167381 1 0 1 1 0 0 +EDGE2 5748 5747 -1.02723 -0.0750111 0.0253469 1 0 1 1 0 0 +EDGE2 5748 5709 1.00231 0.0455711 -0.0183136 1 0 1 1 0 0 +EDGE2 5748 5688 0.0870498 -0.0394494 0.0278524 1 0 1 1 0 0 +EDGE2 5748 5689 0.887723 0.00343707 -0.0283856 1 0 1 1 0 0 +EDGE2 5749 5708 -1.00549 -0.0578854 0.00478209 1 0 1 1 0 0 +EDGE2 5749 5748 -0.999591 0.0253028 -0.00250434 1 0 1 1 0 0 +EDGE2 5749 5709 0.0696301 0.0460579 -0.030235 1 0 1 1 0 0 +EDGE2 5749 5688 -1.04474 0.0120954 -0.00967497 1 0 1 1 0 0 +EDGE2 5749 5689 -0.0195887 -0.0872883 0.00780532 1 0 1 1 0 0 +EDGE2 5749 5630 1.00654 0.0176823 -3.16254 1 0 1 1 0 0 +EDGE2 5749 5710 0.948979 -0.0483957 0.0270389 1 0 1 1 0 0 +EDGE2 5749 5690 1.16799 0.00111332 -0.0383136 1 0 1 1 0 0 +EDGE2 5750 5691 0.033923 0.899383 1.57963 1 0 1 1 0 0 +EDGE2 5750 5709 -0.941691 -0.0687632 -0.00248893 1 0 1 1 0 0 +EDGE2 5750 5749 -1.01752 -0.0385182 0.0246007 1 0 1 1 0 0 +EDGE2 5750 5689 -0.934685 -0.00919919 0.00823809 1 0 1 1 0 0 +EDGE2 5750 5711 0.0301458 1.00324 1.59964 1 0 1 1 0 0 +EDGE2 5750 5630 0.00659463 -0.0339968 -3.1206 1 0 1 1 0 0 +EDGE2 5750 5710 -0.00411846 -0.0263414 0.0092028 1 0 1 1 0 0 +EDGE2 5750 5631 -0.08292 1.0237 1.56998 1 0 1 1 0 0 +EDGE2 5750 5690 0.0379132 0.0072247 0.0177551 1 0 1 1 0 0 +EDGE2 5750 5629 0.92523 -0.0195829 -3.12288 1 0 1 1 0 0 +EDGE2 5751 5691 -0.0133691 -0.026008 -0.0376719 1 0 1 1 0 0 +EDGE2 5751 5692 0.848792 0.0691558 -0.0136244 1 0 1 1 0 0 +EDGE2 5751 5712 1.02857 0.0343376 0.00400283 1 0 1 1 0 0 +EDGE2 5751 5632 0.948828 -0.0570284 -0.0207393 1 0 1 1 0 0 +EDGE2 5751 5711 -0.0236289 0.00595004 0.00454198 1 0 1 1 0 0 +EDGE2 5751 5630 -1.04602 0.0166813 1.56838 1 0 1 1 0 0 +EDGE2 5751 5710 -0.95518 -0.0684296 -1.56785 1 0 1 1 0 0 +EDGE2 5751 5750 -1.02432 -0.00522536 -1.58267 1 0 1 1 0 0 +EDGE2 5751 5631 -0.0556993 0.0252208 -0.0241681 1 0 1 1 0 0 +EDGE2 5751 5690 -1.02541 0.02179 -1.57745 1 0 1 1 0 0 +EDGE2 5752 5691 -0.942784 -0.0209537 0.02442 1 0 1 1 0 0 +EDGE2 5752 5713 1.04535 -0.029936 0.0112307 1 0 1 1 0 0 +EDGE2 5752 5692 -0.017168 0.0377476 -0.010334 1 0 1 1 0 0 +EDGE2 5752 5633 1.02172 -0.0364724 0.0321036 1 0 1 1 0 0 +EDGE2 5752 5693 0.962031 -0.00799679 0.0240106 1 0 1 1 0 0 +EDGE2 5752 5712 -0.0202809 -0.0290953 7.98196e-05 1 0 1 1 0 0 +EDGE2 5752 5751 -0.977476 -0.0166982 0.00995688 1 0 1 1 0 0 +EDGE2 5752 5632 0.0254765 0.0922651 -0.0179402 1 0 1 1 0 0 +EDGE2 5752 5711 -0.957173 0.0374904 -0.0259991 1 0 1 1 0 0 +EDGE2 5752 5631 -0.967755 -0.00850212 -0.025536 1 0 1 1 0 0 +EDGE2 5753 5713 0.108276 0.0202587 0.00837548 1 0 1 1 0 0 +EDGE2 5753 5634 1.06785 0.00120635 -0.0103399 1 0 1 1 0 0 +EDGE2 5753 5694 0.973659 -0.0544816 0.0108354 1 0 1 1 0 0 +EDGE2 5753 5714 0.983582 0.0513876 -0.000359111 1 0 1 1 0 0 +EDGE2 5753 5692 -1.04453 -0.0198075 0.00296616 1 0 1 1 0 0 +EDGE2 5753 5752 -0.951171 0.00817557 0.0358213 1 0 1 1 0 0 +EDGE2 5753 5633 0.0291447 0.0741574 -0.0243959 1 0 1 1 0 0 +EDGE2 5753 5693 0.0393211 -0.0376987 0.0220871 1 0 1 1 0 0 +EDGE2 5753 5712 -1.03453 -0.0666251 0.0385878 1 0 1 1 0 0 +EDGE2 5753 5632 -0.884133 -0.0403943 -0.0272244 1 0 1 1 0 0 +EDGE2 5754 5713 -0.999461 0.00721543 0.00868304 1 0 1 1 0 0 +EDGE2 5754 5675 0.92826 -0.0458337 -3.16952 1 0 1 1 0 0 +EDGE2 5754 5695 1.10383 0.0835578 -0.0159847 1 0 1 1 0 0 +EDGE2 5754 5715 0.918929 -0.0102096 -0.00348758 1 0 1 1 0 0 +EDGE2 5754 5635 0.982982 -0.025146 0.0236426 1 0 1 1 0 0 +EDGE2 5754 5634 0.0181968 0.00355081 0.0205409 1 0 1 1 0 0 +EDGE2 5754 5694 -0.0391811 0.00347977 -0.00493081 1 0 1 1 0 0 +EDGE2 5754 5714 0.00248247 0.070983 0.045137 1 0 1 1 0 0 +EDGE2 5754 5753 -0.993807 -0.0351517 0.0205648 1 0 1 1 0 0 +EDGE2 5754 5633 -0.97822 -0.0112592 -0.00109877 1 0 1 1 0 0 +EDGE2 5754 5693 -0.994416 0.00901089 0.00302374 1 0 1 1 0 0 +EDGE2 5755 5674 1.02546 0.038381 -3.11119 1 0 1 1 0 0 +EDGE2 5755 5676 0.0218013 0.928753 1.52619 1 0 1 1 0 0 +EDGE2 5755 5696 0.00487608 1.01088 1.54975 1 0 1 1 0 0 +EDGE2 5755 5716 0.04318 0.948487 1.5409 1 0 1 1 0 0 +EDGE2 5755 5636 0.0541424 1.03496 1.53799 1 0 1 1 0 0 +EDGE2 5755 5754 -0.994784 -0.0178446 0.0021017 1 0 1 1 0 0 +EDGE2 5755 5675 0.0297002 -0.0664876 -3.11449 1 0 1 1 0 0 +EDGE2 5755 5695 0.0760548 -0.00924402 0.00885124 1 0 1 1 0 0 +EDGE2 5755 5715 -0.0122105 0.0718071 -0.0131719 1 0 1 1 0 0 +EDGE2 5755 5635 -0.00378342 -0.0338308 -0.0185641 1 0 1 1 0 0 +EDGE2 5755 5634 -0.995081 -0.096453 -0.0143182 1 0 1 1 0 0 +EDGE2 5755 5694 -0.970608 0.0457555 0.009582 1 0 1 1 0 0 +EDGE2 5755 5714 -0.974669 -0.044265 -0.0111 1 0 1 1 0 0 +EDGE2 5756 5755 -0.931041 -0.0216666 1.56379 1 0 1 1 0 0 +EDGE2 5756 5675 -0.989897 0.0554864 -1.57184 1 0 1 1 0 0 +EDGE2 5756 5695 -1.02701 0.0940169 1.59882 1 0 1 1 0 0 +EDGE2 5756 5715 -1.05252 0.108025 1.53443 1 0 1 1 0 0 +EDGE2 5756 5635 -1.02708 -0.0185414 1.57461 1 0 1 1 0 0 +EDGE2 5757 5756 -0.999549 -0.0318567 -0.00916053 1 0 1 1 0 0 +EDGE2 5758 5757 -0.927625 -0.0169195 -0.0257997 1 0 1 1 0 0 +EDGE2 5759 5758 -1.08697 -0.00122151 0.0118972 1 0 1 1 0 0 +EDGE2 5759 5580 1.01471 0.0742024 -3.12631 1 0 1 1 0 0 +EDGE2 5759 5620 1.02659 0.0252825 -3.1472 1 0 1 1 0 0 +EDGE2 5760 5759 -1.02556 0.0180629 -0.0053662 1 0 1 1 0 0 +EDGE2 5760 5621 0.00201691 -1.02768 -1.5466 1 0 1 1 0 0 +EDGE2 5760 5580 -0.0303722 0.0246991 -3.14816 1 0 1 1 0 0 +EDGE2 5760 5620 -0.0242087 0.0369004 -3.15588 1 0 1 1 0 0 +EDGE2 5760 5581 0.054364 -1.03341 -1.57074 1 0 1 1 0 0 +EDGE2 5760 5579 0.981043 0.0493281 -3.1415 1 0 1 1 0 0 +EDGE2 5760 5619 0.957635 0.0878662 -3.15719 1 0 1 1 0 0 +EDGE2 5761 5760 -1.09074 -0.0569773 -1.57179 1 0 1 1 0 0 +EDGE2 5761 5580 -0.927972 -0.0606328 1.55157 1 0 1 1 0 0 +EDGE2 5761 5620 -1.01407 -0.0313761 1.54774 1 0 1 1 0 0 +EDGE2 5762 5761 -1.00968 0.0487992 -0.023872 1 0 1 1 0 0 +EDGE2 5763 5762 -1.00229 0.0203786 -0.00695294 1 0 1 1 0 0 +EDGE2 5764 5763 -1.00696 0.0223978 0.00166843 1 0 1 1 0 0 +EDGE2 5764 5505 1.02563 0.0238481 -3.14495 1 0 1 1 0 0 +EDGE2 5765 5504 1.01676 0.106674 -3.14569 1 0 1 1 0 0 +EDGE2 5765 5764 -1.02949 -0.0316076 -0.0261203 1 0 1 1 0 0 +EDGE2 5765 5505 0.0415425 -0.067758 -3.16047 1 0 1 1 0 0 +EDGE2 5765 5506 0.0673038 -1.0643 -1.56949 1 0 1 1 0 0 +EDGE2 5766 5765 -0.928322 -0.0764834 -1.57697 1 0 1 1 0 0 +EDGE2 5766 5505 -1.05216 -0.00196503 1.55942 1 0 1 1 0 0 +EDGE2 5767 5766 -0.932467 0.0696514 0.0129024 1 0 1 1 0 0 +EDGE2 5768 5767 -1.09146 0.0748512 0.00889587 1 0 1 1 0 0 +EDGE2 5769 5670 1.05102 -0.00195358 -3.13035 1 0 1 1 0 0 +EDGE2 5769 5650 1.0594 0.0169027 -3.15296 1 0 1 1 0 0 +EDGE2 5769 5768 -1.10343 0.0507024 -0.0134772 1 0 1 1 0 0 +EDGE2 5770 5649 1.00366 0.0754315 -3.15641 1 0 1 1 0 0 +EDGE2 5770 5669 0.96794 0.00782518 -3.14011 1 0 1 1 0 0 +EDGE2 5770 5670 0.0732902 0.00909325 -3.10968 1 0 1 1 0 0 +EDGE2 5770 5651 -0.0579463 -1.03392 -1.58218 1 0 1 1 0 0 +EDGE2 5770 5671 -0.0194482 0.905998 1.54019 1 0 1 1 0 0 +EDGE2 5770 5650 0.00571108 0.113157 -3.1383 1 0 1 1 0 0 +EDGE2 5770 5769 -1.12048 -0.0146309 -0.0144317 1 0 1 1 0 0 +EDGE2 5771 5670 -1.04046 0.0453373 -1.60223 1 0 1 1 0 0 +EDGE2 5771 5770 -0.961749 0.0196508 1.55347 1 0 1 1 0 0 +EDGE2 5771 5652 1.00653 0.0176753 -0.00254288 1 0 1 1 0 0 +EDGE2 5771 5651 0.0263128 -0.00293828 -0.00755702 1 0 1 1 0 0 +EDGE2 5771 5650 -0.881811 -0.0619756 -1.56721 1 0 1 1 0 0 +EDGE2 5772 5653 0.988201 0.0267313 -0.0127291 1 0 1 1 0 0 +EDGE2 5772 5771 -0.994428 -0.0665158 0.00481078 1 0 1 1 0 0 +EDGE2 5772 5652 -0.083788 0.0295669 -0.0148717 1 0 1 1 0 0 +EDGE2 5772 5651 -1.01416 0.00672026 0.00552847 1 0 1 1 0 0 +EDGE2 5773 5653 0.0273437 0.0156882 -0.0233849 1 0 1 1 0 0 +EDGE2 5773 5654 1.01867 -0.051816 -0.014187 1 0 1 1 0 0 +EDGE2 5773 5652 -0.935372 0.0477775 0.0110994 1 0 1 1 0 0 +EDGE2 5773 5772 -1.12654 -0.00707788 0.0249886 1 0 1 1 0 0 +EDGE2 5774 5653 -1.03066 0.0306288 0.0141664 1 0 1 1 0 0 +EDGE2 5774 5654 0.00846435 -0.0403109 0.0117923 1 0 1 1 0 0 +EDGE2 5774 5655 1.03103 -0.0809835 -0.00755954 1 0 1 1 0 0 +EDGE2 5774 5773 -0.915884 -0.0621671 -0.00248193 1 0 1 1 0 0 +EDGE2 5775 5654 -1.00006 0.0927736 0.0117835 1 0 1 1 0 0 +EDGE2 5775 5655 0.0205191 0.0209715 -0.0376671 1 0 1 1 0 0 +EDGE2 5775 5656 -0.003496 1.00122 1.5836 1 0 1 1 0 0 +EDGE2 5775 5774 -0.901936 -0.0343662 -0.00308491 1 0 1 1 0 0 +EDGE2 5776 5657 1.13036 0.0298546 -0.00854678 1 0 1 1 0 0 +EDGE2 5776 5655 -0.936624 -0.00633122 -1.62785 1 0 1 1 0 0 +EDGE2 5776 5775 -0.959444 0.00892831 -1.52477 1 0 1 1 0 0 +EDGE2 5776 5656 -0.0257729 0.0145203 -0.011692 1 0 1 1 0 0 +EDGE2 5777 5776 -1.01318 -0.0868874 0.0125694 1 0 1 1 0 0 +EDGE2 5777 5658 1.02523 -0.0199154 -0.0110538 1 0 1 1 0 0 +EDGE2 5777 5657 0.0593327 -0.0450468 0.00347392 1 0 1 1 0 0 +EDGE2 5777 5656 -0.963075 -0.0266522 -0.0272681 1 0 1 1 0 0 +EDGE2 5778 5659 0.943284 0.042467 -0.029903 1 0 1 1 0 0 +EDGE2 5778 5777 -0.986733 0.0828542 -0.0195788 1 0 1 1 0 0 +EDGE2 5778 5658 0.00866457 0.0430849 0.0105404 1 0 1 1 0 0 +EDGE2 5778 5657 -1.04386 0.00772358 -0.0125687 1 0 1 1 0 0 +EDGE2 5779 1100 0.994528 -0.0880463 -3.1316 1 0 1 1 0 0 +EDGE2 5779 1140 1.03513 -0.0343502 -3.11657 1 0 1 1 0 0 +EDGE2 5779 3040 0.99542 -0.0143245 -3.13285 1 0 1 1 0 0 +EDGE2 5779 5660 1.12267 -0.00930126 0.00101044 1 0 1 1 0 0 +EDGE2 5779 1120 0.931864 0.0330786 -3.10895 1 0 1 1 0 0 +EDGE2 5779 5659 0.0719599 -0.00626951 -0.00359977 1 0 1 1 0 0 +EDGE2 5779 5658 -0.953302 0.00286424 0.00148453 1 0 1 1 0 0 +EDGE2 5779 5778 -1.04194 -0.0224379 -0.0195295 1 0 1 1 0 0 +EDGE2 5780 1139 1.03279 0.10737 -3.15239 1 0 1 1 0 0 +EDGE2 5780 3039 1.05847 -0.0304057 -3.17225 1 0 1 1 0 0 +EDGE2 5780 1099 0.918591 0.0251866 -3.15728 1 0 1 1 0 0 +EDGE2 5780 1119 1.07737 -0.0130849 -3.12439 1 0 1 1 0 0 +EDGE2 5780 1121 -0.00289441 -1.04633 -1.55314 1 0 1 1 0 0 +EDGE2 5780 3041 -0.0103097 -1.02697 -1.5673 1 0 1 1 0 0 +EDGE2 5780 1141 -0.00447499 -0.963622 -1.56346 1 0 1 1 0 0 +EDGE2 5780 1101 0.00989883 -0.983155 -1.54286 1 0 1 1 0 0 +EDGE2 5780 1100 0.0430632 -0.039854 -3.12526 1 0 1 1 0 0 +EDGE2 5780 1140 0.0678917 0.00768416 -3.10663 1 0 1 1 0 0 +EDGE2 5780 3040 -0.0392669 0.0667629 -3.10897 1 0 1 1 0 0 +EDGE2 5780 5660 0.102341 -0.0677405 -0.0138688 1 0 1 1 0 0 +EDGE2 5780 1120 -0.0688471 -0.0760947 -3.12435 1 0 1 1 0 0 +EDGE2 5780 5661 -0.0313106 1.02289 1.59881 1 0 1 1 0 0 +EDGE2 5780 5659 -0.964094 -0.0759186 0.00131585 1 0 1 1 0 0 +EDGE2 5780 5779 -0.883794 -0.0541985 -0.00920143 1 0 1 1 0 0 +EDGE2 5781 5780 -1.06947 -0.0672274 1.56744 1 0 1 1 0 0 +EDGE2 5781 3042 0.988552 0.0646545 -0.0218575 1 0 1 1 0 0 +EDGE2 5781 1102 1.01532 -0.0335976 0.00221539 1 0 1 1 0 0 +EDGE2 5781 1122 0.971496 0.0329106 -0.0406401 1 0 1 1 0 0 +EDGE2 5781 1142 0.994487 0.00937871 0.0131837 1 0 1 1 0 0 +EDGE2 5781 1121 -0.0472061 -0.0508538 0.0102784 1 0 1 1 0 0 +EDGE2 5781 3041 -0.0496636 0.0320359 0.00416302 1 0 1 1 0 0 +EDGE2 5781 1141 -0.0854758 -0.0104149 -0.0181604 1 0 1 1 0 0 +EDGE2 5781 1101 -0.0369311 0.0326268 -0.0516752 1 0 1 1 0 0 +EDGE2 5781 1100 -1.03592 -0.0145142 -1.58472 1 0 1 1 0 0 +EDGE2 5781 1140 -0.999786 -0.0161985 -1.58225 1 0 1 1 0 0 +EDGE2 5781 3040 -1.04098 0.00754898 -1.58095 1 0 1 1 0 0 +EDGE2 5781 5660 -0.994759 -0.0456264 1.62584 1 0 1 1 0 0 +EDGE2 5781 1120 -1.00752 0.0273897 -1.56944 1 0 1 1 0 0 +EDGE2 5782 1123 1.00727 0.0978742 0.0200245 1 0 1 1 0 0 +EDGE2 5782 3043 1.16301 -0.0111055 -0.0102213 1 0 1 1 0 0 +EDGE2 5782 1143 1.01439 -0.0556805 0.000293675 1 0 1 1 0 0 +EDGE2 5782 3042 -0.0146821 -0.117194 0.00781283 1 0 1 1 0 0 +EDGE2 5782 1103 0.957312 -0.118721 0.00657631 1 0 1 1 0 0 +EDGE2 5782 1102 0.102056 0.0750241 -0.0220891 1 0 1 1 0 0 +EDGE2 5782 1122 -0.0579837 -0.0449669 -0.0163958 1 0 1 1 0 0 +EDGE2 5782 1142 -0.0311001 0.0564839 0.00384757 1 0 1 1 0 0 +EDGE2 5782 1121 -1.0734 -0.006179 0.0129766 1 0 1 1 0 0 +EDGE2 5782 3041 -1.0012 0.0181766 -0.0136935 1 0 1 1 0 0 +EDGE2 5782 5781 -0.946681 -0.0236612 0.0210068 1 0 1 1 0 0 +EDGE2 5782 1141 -0.994945 0.0314653 -0.0176421 1 0 1 1 0 0 +EDGE2 5782 1101 -0.987788 -0.0278759 -0.00878325 1 0 1 1 0 0 +EDGE2 5783 1123 0.0577708 0.0449435 0.0110827 1 0 1 1 0 0 +EDGE2 5783 1124 0.952842 0.00997107 -0.0117968 1 0 1 1 0 0 +EDGE2 5783 1144 1.06436 -0.0250031 -0.0194588 1 0 1 1 0 0 +EDGE2 5783 3044 0.982368 0.0428586 0.0382007 1 0 1 1 0 0 +EDGE2 5783 1104 0.984881 -0.0080618 0.0167611 1 0 1 1 0 0 +EDGE2 5783 3043 0.111715 0.0430785 0.0433111 1 0 1 1 0 0 +EDGE2 5783 1143 0.0423269 0.0179583 -0.00764311 1 0 1 1 0 0 +EDGE2 5783 3042 -1.01667 0.00635629 -0.0151639 1 0 1 1 0 0 +EDGE2 5783 1103 -0.0146442 -0.0611279 -0.0154023 1 0 1 1 0 0 +EDGE2 5783 5782 -0.981967 -0.0141877 -0.0727848 1 0 1 1 0 0 +EDGE2 5783 1102 -1.01296 -0.000985006 0.0140708 1 0 1 1 0 0 +EDGE2 5783 1122 -1.02385 -0.0287552 0.00191414 1 0 1 1 0 0 +EDGE2 5783 1142 -0.994824 0.00752594 0.0378476 1 0 1 1 0 0 +EDGE2 5784 1123 -1.01257 0.0858971 -0.00256464 1 0 1 1 0 0 +EDGE2 5784 1145 1.04306 0.00864368 -0.00355812 1 0 1 1 0 0 +EDGE2 5784 3045 0.924202 -0.0110426 0.0275773 1 0 1 1 0 0 +EDGE2 5784 3505 1.03811 0.0165889 -3.1459 1 0 1 1 0 0 +EDGE2 5784 3025 0.959946 -0.0263981 -3.14299 1 0 1 1 0 0 +EDGE2 5784 1105 0.889327 -0.0568909 -0.0254258 1 0 1 1 0 0 +EDGE2 5784 1125 1.02687 -0.00798382 0.000791148 1 0 1 1 0 0 +EDGE2 5784 1124 0.0274752 -0.00515835 -0.0176217 1 0 1 1 0 0 +EDGE2 5784 1144 0.086326 -0.0782091 -0.00639159 1 0 1 1 0 0 +EDGE2 5784 3044 0.00884133 -0.109123 0.024993 1 0 1 1 0 0 +EDGE2 5784 1104 0.00833217 -0.0901273 -0.0219098 1 0 1 1 0 0 +EDGE2 5784 3043 -1.02812 -0.021049 -0.00607461 1 0 1 1 0 0 +EDGE2 5784 5783 -0.953131 0.0151048 0.0240781 1 0 1 1 0 0 +EDGE2 5784 1143 -1.05045 -0.0351314 0.0371242 1 0 1 1 0 0 +EDGE2 5784 1103 -1.01339 0.123231 0.00502149 1 0 1 1 0 0 +EDGE2 5785 3504 0.915075 0.022495 -3.1271 1 0 1 1 0 0 +EDGE2 5785 3024 1.07181 -0.0703042 -3.14048 1 0 1 1 0 0 +EDGE2 5785 3046 0.00712968 0.969038 1.57633 1 0 1 1 0 0 +EDGE2 5785 1126 -0.000198642 0.985304 1.6063 1 0 1 1 0 0 +EDGE2 5785 1146 -0.0548391 1.08795 1.57535 1 0 1 1 0 0 +EDGE2 5785 3026 0.0495628 1.07104 1.52103 1 0 1 1 0 0 +EDGE2 5785 1106 -0.0269128 0.998288 1.56928 1 0 1 1 0 0 +EDGE2 5785 5784 -1.08288 0.0466073 0.0217467 1 0 1 1 0 0 +EDGE2 5785 1145 -0.0859285 -0.00930973 -0.000612331 1 0 1 1 0 0 +EDGE2 5785 3045 -0.0872379 -0.00292062 -0.0218259 1 0 1 1 0 0 +EDGE2 5785 3505 -0.159749 -0.0596411 -3.14433 1 0 1 1 0 0 +EDGE2 5785 3025 -0.0356738 -0.111139 -3.13578 1 0 1 1 0 0 +EDGE2 5785 1105 0.0224492 0.0017063 0.0341946 1 0 1 1 0 0 +EDGE2 5785 1125 -0.0325434 -0.0808742 0.00105063 1 0 1 1 0 0 +EDGE2 5785 1124 -0.949305 0.0810353 0.00378822 1 0 1 1 0 0 +EDGE2 5785 1144 -0.987441 0.0381347 -0.0343812 1 0 1 1 0 0 +EDGE2 5785 3044 -1.07318 -0.0647052 0.0227028 1 0 1 1 0 0 +EDGE2 5785 1104 -1.01313 0.0343761 0.00318807 1 0 1 1 0 0 +EDGE2 5785 3506 -0.038079 -0.893027 -1.54762 1 0 1 1 0 0 +EDGE2 5786 3027 0.969539 -0.0221937 0.0100915 1 0 1 1 0 0 +EDGE2 5786 3047 1.0647 -0.00710739 0.0130525 1 0 1 1 0 0 +EDGE2 5786 1127 1.02796 -0.0105091 -0.00383938 1 0 1 1 0 0 +EDGE2 5786 1147 0.987881 -0.0598058 0.0303767 1 0 1 1 0 0 +EDGE2 5786 1107 1.04427 -0.0485172 -0.00608583 1 0 1 1 0 0 +EDGE2 5786 3046 0.0307762 0.0157779 -0.00252327 1 0 1 1 0 0 +EDGE2 5786 1126 0.0458881 0.0134768 -0.0221517 1 0 1 1 0 0 +EDGE2 5786 1146 -0.0114814 0.00880725 0.00283665 1 0 1 1 0 0 +EDGE2 5786 3026 0.04457 -0.0103869 -0.0188595 1 0 1 1 0 0 +EDGE2 5786 1106 -0.0896801 -0.0550329 0.0216974 1 0 1 1 0 0 +EDGE2 5786 1145 -1.0081 -0.10236 -1.55014 1 0 1 1 0 0 +EDGE2 5786 3045 -0.978571 -0.0163429 -1.59023 1 0 1 1 0 0 +EDGE2 5786 3505 -0.995469 0.0622206 1.57013 1 0 1 1 0 0 +EDGE2 5786 5785 -0.969395 0.0601262 -1.59971 1 0 1 1 0 0 +EDGE2 5786 3025 -1.03036 0.0369564 1.57458 1 0 1 1 0 0 +EDGE2 5786 1105 -0.96741 -0.000539596 -1.58867 1 0 1 1 0 0 +EDGE2 5786 1125 -1.01801 0.0176006 -1.55325 1 0 1 1 0 0 +EDGE2 5787 3027 -0.0169172 0.0817986 -0.00805036 1 0 1 1 0 0 +EDGE2 5787 3048 1.02684 0.0655219 0.0158583 1 0 1 1 0 0 +EDGE2 5787 3028 0.991329 -0.0596546 0.0346082 1 0 1 1 0 0 +EDGE2 5787 1108 0.989248 0.0156889 0.0086202 1 0 1 1 0 0 +EDGE2 5787 1128 1.06356 -0.0156307 0.00927848 1 0 1 1 0 0 +EDGE2 5787 1148 1.08117 -0.00358876 -0.00251339 1 0 1 1 0 0 +EDGE2 5787 3047 -0.0127613 0.0151346 0.0109569 1 0 1 1 0 0 +EDGE2 5787 1127 -0.00297504 -0.0463747 -0.0149414 1 0 1 1 0 0 +EDGE2 5787 1147 -0.0511359 -0.0395428 0.0266994 1 0 1 1 0 0 +EDGE2 5787 1107 -0.0128455 -0.0846175 0.00709571 1 0 1 1 0 0 +EDGE2 5787 3046 -1.11943 -0.0708139 0.00257245 1 0 1 1 0 0 +EDGE2 5787 5786 -0.960919 -0.146706 0.00741887 1 0 1 1 0 0 +EDGE2 5787 1126 -0.940694 -0.0317779 0.0160223 1 0 1 1 0 0 +EDGE2 5787 1146 -0.854687 -0.0447367 0.00215224 1 0 1 1 0 0 +EDGE2 5787 3026 -1.04602 0.010759 0.0059545 1 0 1 1 0 0 +EDGE2 5787 1106 -0.964428 -0.0117282 0.0144558 1 0 1 1 0 0 +EDGE2 5788 3027 -0.87091 0.01325 0.0194598 1 0 1 1 0 0 +EDGE2 5788 3048 0.0145382 -0.0744374 0.033594 1 0 1 1 0 0 +EDGE2 5788 1109 1.04759 0.0112165 -0.00694464 1 0 1 1 0 0 +EDGE2 5788 1149 1.09245 -0.00672455 -0.022794 1 0 1 1 0 0 +EDGE2 5788 3029 1.03506 -0.0659904 -0.0156151 1 0 1 1 0 0 +EDGE2 5788 3049 1.03994 0.00117497 0.0401816 1 0 1 1 0 0 +EDGE2 5788 1129 0.981126 0.0360956 0.0134228 1 0 1 1 0 0 +EDGE2 5788 3028 0.0665222 0.0507567 0.00508069 1 0 1 1 0 0 +EDGE2 5788 1108 -0.0222478 -0.0459138 0.0147434 1 0 1 1 0 0 +EDGE2 5788 1128 0.0654702 0.000759567 -0.00723736 1 0 1 1 0 0 +EDGE2 5788 1148 0.0187827 0.0259599 -0.0253563 1 0 1 1 0 0 +EDGE2 5788 5787 -1.06368 -0.0479735 -0.0178326 1 0 1 1 0 0 +EDGE2 5788 3047 -1.00905 0.0455251 -0.00787706 1 0 1 1 0 0 +EDGE2 5788 1127 -1.00796 0.0626649 0.0218713 1 0 1 1 0 0 +EDGE2 5788 1147 -0.984681 -0.00340504 -0.0302753 1 0 1 1 0 0 +EDGE2 5788 1107 -0.902419 0.0107514 -0.0462911 1 0 1 1 0 0 +EDGE2 5789 3050 0.995657 0.0742525 0.00311352 1 0 1 1 0 0 +EDGE2 5789 3170 0.998214 -0.011824 -3.14998 1 0 1 1 0 0 +EDGE2 5789 3490 1.02528 -0.047411 -3.15071 1 0 1 1 0 0 +EDGE2 5789 3110 0.985482 0.0449769 -3.14715 1 0 1 1 0 0 +EDGE2 5789 3130 0.990735 0.00832628 -3.16106 1 0 1 1 0 0 +EDGE2 5789 3090 1.03216 -0.0397517 -3.1061 1 0 1 1 0 0 +EDGE2 5789 3048 -1.01861 0.111027 -0.00247102 1 0 1 1 0 0 +EDGE2 5789 1130 1.01453 0.063551 -0.017071 1 0 1 1 0 0 +EDGE2 5789 1170 0.926644 -0.0388625 -3.1395 1 0 1 1 0 0 +EDGE2 5789 1190 1.05261 0.0651848 -3.09893 1 0 1 1 0 0 +EDGE2 5789 3030 1.00859 -0.0175239 -0.00845923 1 0 1 1 0 0 +EDGE2 5789 1150 0.989475 -0.0674556 -0.0215733 1 0 1 1 0 0 +EDGE2 5789 1110 0.936845 0.0368211 -0.0132957 1 0 1 1 0 0 +EDGE2 5789 1109 -0.0583763 0.00231287 -0.0111337 1 0 1 1 0 0 +EDGE2 5789 1149 0.0356191 -0.049476 -0.000981894 1 0 1 1 0 0 +EDGE2 5789 3029 -0.050387 0.0639669 0.0253612 1 0 1 1 0 0 +EDGE2 5789 3049 -0.0212398 0.00465295 -0.0102235 1 0 1 1 0 0 +EDGE2 5789 1129 0.128909 -0.0387164 -0.0145395 1 0 1 1 0 0 +EDGE2 5789 5788 -0.9905 0.0285061 0.0127572 1 0 1 1 0 0 +EDGE2 5789 3028 -0.968163 -0.0285698 -0.0100057 1 0 1 1 0 0 +EDGE2 5789 1108 -1.01922 -0.0442611 -0.00113759 1 0 1 1 0 0 +EDGE2 5789 1128 -1.08883 0.00335769 -0.0327181 1 0 1 1 0 0 +EDGE2 5789 1148 -1.00365 0.0335785 -0.0184927 1 0 1 1 0 0 +EDGE2 5790 3109 1.00611 -0.038404 -3.15664 1 0 1 1 0 0 +EDGE2 5790 3169 0.949083 -0.0469906 -3.14473 1 0 1 1 0 0 +EDGE2 5790 3489 1.01432 0.0184364 -3.14297 1 0 1 1 0 0 +EDGE2 5790 3129 0.935167 -0.00900245 -3.1738 1 0 1 1 0 0 +EDGE2 5790 1189 0.978559 -0.042023 -3.1483 1 0 1 1 0 0 +EDGE2 5790 3089 1.01624 -0.101249 -3.1622 1 0 1 1 0 0 +EDGE2 5790 1169 0.984064 0.00437128 -3.13982 1 0 1 1 0 0 +EDGE2 5790 3050 0.0267955 0.048369 -0.0191271 1 0 1 1 0 0 +EDGE2 5790 3131 0.0149793 -1.01896 -1.55079 1 0 1 1 0 0 +EDGE2 5790 3491 0.0683994 -0.993529 -1.5863 1 0 1 1 0 0 +EDGE2 5790 3171 -0.0154521 -1.00929 -1.57674 1 0 1 1 0 0 +EDGE2 5790 1151 0.00724067 -0.949478 -1.56116 1 0 1 1 0 0 +EDGE2 5790 1191 0.0943266 -1.02754 -1.57394 1 0 1 1 0 0 +EDGE2 5790 3091 0.0270639 -0.997524 -1.56291 1 0 1 1 0 0 +EDGE2 5790 3111 0.0383553 -0.878305 -1.54987 1 0 1 1 0 0 +EDGE2 5790 1171 0.0468553 -0.998949 -1.5658 1 0 1 1 0 0 +EDGE2 5790 3170 -0.0213304 -0.0776773 -3.14761 1 0 1 1 0 0 +EDGE2 5790 3490 0.0565151 -0.00561576 -3.13606 1 0 1 1 0 0 +EDGE2 5790 3110 0.123339 0.0147303 -3.0997 1 0 1 1 0 0 +EDGE2 5790 3130 -0.00185372 -0.0437985 -3.14194 1 0 1 1 0 0 +EDGE2 5790 3090 0.042559 -0.0853401 -3.12695 1 0 1 1 0 0 +EDGE2 5790 5789 -1.02398 -0.0138737 -0.019013 1 0 1 1 0 0 +EDGE2 5790 1130 -0.00405548 -0.0892562 -0.0233811 1 0 1 1 0 0 +EDGE2 5790 1170 0.0518675 0.0736979 -3.14405 1 0 1 1 0 0 +EDGE2 5790 1190 0.0416005 0.0762569 -3.13571 1 0 1 1 0 0 +EDGE2 5790 3030 -0.0326819 0.0624373 0.00735701 1 0 1 1 0 0 +EDGE2 5790 1150 0.0836883 0.100416 -0.0343275 1 0 1 1 0 0 +EDGE2 5790 1110 0.0603869 -0.0867965 -0.0333996 1 0 1 1 0 0 +EDGE2 5790 1109 -1.00692 -0.00390911 -0.0225093 1 0 1 1 0 0 +EDGE2 5790 1149 -1.01083 -0.0599253 -0.00117231 1 0 1 1 0 0 +EDGE2 5790 3029 -0.96845 -0.0261321 -0.00869587 1 0 1 1 0 0 +EDGE2 5790 3049 -1.03436 0.051622 0.00635252 1 0 1 1 0 0 +EDGE2 5790 1129 -1.05386 -0.0257394 -0.0190975 1 0 1 1 0 0 +EDGE2 5790 1111 0.0142681 1.06056 1.55329 1 0 1 1 0 0 +EDGE2 5790 3031 0.0539913 0.951107 1.54821 1 0 1 1 0 0 +EDGE2 5790 3051 -0.0875401 0.895334 1.57495 1 0 1 1 0 0 +EDGE2 5790 1131 0.0803119 0.902266 1.58198 1 0 1 1 0 0 +EDGE2 5791 3050 -0.992907 -0.00982634 -1.60756 1 0 1 1 0 0 +EDGE2 5791 3170 -0.979734 0.107993 1.58479 1 0 1 1 0 0 +EDGE2 5791 5790 -0.962253 0.00971118 -1.56426 1 0 1 1 0 0 +EDGE2 5791 3490 -0.970704 -0.010287 1.55355 1 0 1 1 0 0 +EDGE2 5791 3110 -0.915885 -0.0301099 1.60032 1 0 1 1 0 0 +EDGE2 5791 3130 -1.14143 -0.0512403 1.56275 1 0 1 1 0 0 +EDGE2 5791 3090 -0.995292 -0.0178856 1.56549 1 0 1 1 0 0 +EDGE2 5791 1130 -0.983767 0.013307 -1.55704 1 0 1 1 0 0 +EDGE2 5791 1170 -0.963102 0.0172701 1.57908 1 0 1 1 0 0 +EDGE2 5791 1190 -0.956343 0.0633194 1.57792 1 0 1 1 0 0 +EDGE2 5791 3030 -1.00915 -0.00337341 -1.58567 1 0 1 1 0 0 +EDGE2 5791 1150 -0.952467 -0.0462202 -1.58823 1 0 1 1 0 0 +EDGE2 5791 1110 -1.03139 0.043116 -1.56421 1 0 1 1 0 0 +EDGE2 5791 3052 0.987939 -0.00975332 -0.0137663 1 0 1 1 0 0 +EDGE2 5791 1111 -0.0174698 0.0369132 -0.0362322 1 0 1 1 0 0 +EDGE2 5791 3031 -0.0262632 -0.0370994 0.0216196 1 0 1 1 0 0 +EDGE2 5791 3051 -0.0252204 0.0501588 -0.000951565 1 0 1 1 0 0 +EDGE2 5791 1131 0.0349891 0.0569402 -0.0176706 1 0 1 1 0 0 +EDGE2 5791 1112 1.06406 0.0251227 0.0140428 1 0 1 1 0 0 +EDGE2 5791 1132 1.07452 0.0554756 0.0256807 1 0 1 1 0 0 +EDGE2 5791 3032 0.981992 0.0799401 -0.00306674 1 0 1 1 0 0 +EDGE2 5792 1133 1.00187 0.00214653 0.00144896 1 0 1 1 0 0 +EDGE2 5792 3052 0.0735333 0.0390321 0.00890771 1 0 1 1 0 0 +EDGE2 5792 1111 -0.95104 -0.0465381 -0.014026 1 0 1 1 0 0 +EDGE2 5792 3031 -1.01615 -0.0269659 -0.0284647 1 0 1 1 0 0 +EDGE2 5792 3051 -1.03222 0.00930122 -0.00978173 1 0 1 1 0 0 +EDGE2 5792 5791 -0.857185 -0.0298674 -5.15535e-05 1 0 1 1 0 0 +EDGE2 5792 1131 -0.985479 -0.0148175 -0.0280352 1 0 1 1 0 0 +EDGE2 5792 1112 0.0567258 -0.00354681 0.00932326 1 0 1 1 0 0 +EDGE2 5792 1132 0.0490587 0.0153644 -0.00386634 1 0 1 1 0 0 +EDGE2 5792 3032 0.011011 -0.0230634 0.00691368 1 0 1 1 0 0 +EDGE2 5792 3053 1.00994 -0.0606255 -0.0298498 1 0 1 1 0 0 +EDGE2 5792 3033 0.997429 0.0351163 0.0287152 1 0 1 1 0 0 +EDGE2 5792 1113 0.973081 -0.0784487 -0.00367469 1 0 1 1 0 0 +EDGE2 5793 1133 0.00533666 0.0638285 -0.0329565 1 0 1 1 0 0 +EDGE2 5793 3052 -1.06315 0.00625199 -0.0117059 1 0 1 1 0 0 +EDGE2 5793 5792 -1.10534 -0.0214386 -0.00111503 1 0 1 1 0 0 +EDGE2 5793 1112 -0.979272 -0.109653 -0.0182419 1 0 1 1 0 0 +EDGE2 5793 1132 -1.01192 0.0180207 0.00687885 1 0 1 1 0 0 +EDGE2 5793 3032 -1.06714 -0.0672049 0.0285199 1 0 1 1 0 0 +EDGE2 5793 3053 0.00532382 -0.0316755 0.0403142 1 0 1 1 0 0 +EDGE2 5793 3033 0.0036569 -0.025263 0.00631438 1 0 1 1 0 0 +EDGE2 5793 1113 0.0341096 -0.0549257 -0.0132312 1 0 1 1 0 0 +EDGE2 5793 1134 0.998063 -0.00708469 -0.00441011 1 0 1 1 0 0 +EDGE2 5793 3034 0.905586 0.0716001 -0.00661629 1 0 1 1 0 0 +EDGE2 5793 3054 1.04156 0.0185699 0.0264814 1 0 1 1 0 0 +EDGE2 5793 1114 0.940866 0.00448721 0.00418395 1 0 1 1 0 0 +EDGE2 5794 1133 -0.970758 0.0601556 -0.00311572 1 0 1 1 0 0 +EDGE2 5794 3053 -1.04779 -0.0314783 0.00222199 1 0 1 1 0 0 +EDGE2 5794 5793 -0.999076 0.0250384 -0.00200498 1 0 1 1 0 0 +EDGE2 5794 3033 -0.99832 -0.0135169 0.0287519 1 0 1 1 0 0 +EDGE2 5794 1113 -0.965156 -0.0227783 0.0114836 1 0 1 1 0 0 +EDGE2 5794 1134 -0.0512034 -0.0308728 -0.0176283 1 0 1 1 0 0 +EDGE2 5794 3034 0.0143794 0.0559616 0.0224367 1 0 1 1 0 0 +EDGE2 5794 3054 -0.0216278 -0.0674924 0.000453957 1 0 1 1 0 0 +EDGE2 5794 1114 -0.0600221 0.0154625 0.000315385 1 0 1 1 0 0 +EDGE2 5794 3035 0.917944 -0.135786 -0.00764286 1 0 1 1 0 0 +EDGE2 5794 3055 0.933449 0.0842148 0.0151863 1 0 1 1 0 0 +EDGE2 5794 1095 1.11108 -0.0368591 -3.15562 1 0 1 1 0 0 +EDGE2 5794 1115 1.06416 0.0850726 0.0167899 1 0 1 1 0 0 +EDGE2 5794 1135 0.969232 0.0402946 -0.0246951 1 0 1 1 0 0 +EDGE2 5795 3056 -0.0487615 -1.02488 -1.56996 1 0 1 1 0 0 +EDGE2 5795 5794 -1.01546 -0.0291625 -0.00847492 1 0 1 1 0 0 +EDGE2 5795 1134 -0.962294 -0.0208051 0.00189894 1 0 1 1 0 0 +EDGE2 5795 3034 -0.960865 0.0507964 0.0159471 1 0 1 1 0 0 +EDGE2 5795 3054 -0.991357 0.0246889 0.0294995 1 0 1 1 0 0 +EDGE2 5795 1114 -1.04185 0.00198611 0.0348696 1 0 1 1 0 0 +EDGE2 5795 3035 -0.00608517 -0.021729 -0.00287249 1 0 1 1 0 0 +EDGE2 5795 3055 -0.0818183 0.0367917 0.0143119 1 0 1 1 0 0 +EDGE2 5795 1095 0.0327244 -0.0303043 -3.1734 1 0 1 1 0 0 +EDGE2 5795 1115 0.0246981 0.00631864 -0.0280241 1 0 1 1 0 0 +EDGE2 5795 1135 -0.0454348 0.0428436 -0.00835347 1 0 1 1 0 0 +EDGE2 5795 1094 0.97626 0.013919 -3.14559 1 0 1 1 0 0 +EDGE2 5795 1116 0.00688281 0.949963 1.53549 1 0 1 1 0 0 +EDGE2 5795 3036 0.0400475 1.002 1.54246 1 0 1 1 0 0 +EDGE2 5795 1136 0.0110392 0.983811 1.57895 1 0 1 1 0 0 +EDGE2 5795 1096 0.174465 1.06105 1.58056 1 0 1 1 0 0 +EDGE2 5796 5795 -1.07018 -0.0320498 -1.5838 1 0 1 1 0 0 +EDGE2 5796 3035 -0.990628 -0.0270245 -1.56851 1 0 1 1 0 0 +EDGE2 5796 3055 -0.981832 -0.0131589 -1.57489 1 0 1 1 0 0 +EDGE2 5796 1095 -0.938951 -0.0145294 1.57208 1 0 1 1 0 0 +EDGE2 5796 1115 -1.01239 -0.028731 -1.54577 1 0 1 1 0 0 +EDGE2 5796 1135 -1.00628 0.095966 -1.58018 1 0 1 1 0 0 +EDGE2 5796 1116 0.012401 0.0599396 0.00337402 1 0 1 1 0 0 +EDGE2 5796 3036 0.025469 0.036071 -0.0422358 1 0 1 1 0 0 +EDGE2 5796 1136 0.0665719 0.0274074 -0.00752535 1 0 1 1 0 0 +EDGE2 5796 1096 -0.00228863 0.0526825 0.0632706 1 0 1 1 0 0 +EDGE2 5796 1097 0.976905 -0.0659088 0.000147259 1 0 1 1 0 0 +EDGE2 5796 1137 1.06798 -0.0643816 -0.00502091 1 0 1 1 0 0 +EDGE2 5796 3037 1.04107 -0.0698125 -0.00390248 1 0 1 1 0 0 +EDGE2 5796 1117 1.0126 -0.0664425 0.02533 1 0 1 1 0 0 +EDGE2 5797 1118 0.941048 -0.0361425 -0.000322059 1 0 1 1 0 0 +EDGE2 5797 1116 -1.12061 0.0653338 -0.0151822 1 0 1 1 0 0 +EDGE2 5797 3036 -1.10558 0.102195 -0.00406143 1 0 1 1 0 0 +EDGE2 5797 5796 -1.01427 0.0086342 0.0383656 1 0 1 1 0 0 +EDGE2 5797 1136 -1.01958 0.0341676 -0.0205335 1 0 1 1 0 0 +EDGE2 5797 1096 -1.01348 -0.0361956 -0.0132973 1 0 1 1 0 0 +EDGE2 5797 1097 0.0355435 -0.0706063 -0.00126165 1 0 1 1 0 0 +EDGE2 5797 1137 -0.0372844 0.0195631 0.0217845 1 0 1 1 0 0 +EDGE2 5797 3037 -0.0327618 -0.044245 -0.0024638 1 0 1 1 0 0 +EDGE2 5797 1117 0.0606951 -0.0594347 -0.0182417 1 0 1 1 0 0 +EDGE2 5797 3038 0.933148 0.00617348 -0.0200324 1 0 1 1 0 0 +EDGE2 5797 1138 1.09556 -0.0155798 0.0238169 1 0 1 1 0 0 +EDGE2 5797 1098 0.968603 0.0571346 -0.0375014 1 0 1 1 0 0 +EDGE2 5798 1118 -0.14588 -0.00592876 0.000919051 1 0 1 1 0 0 +EDGE2 5798 1097 -0.975077 0.0380195 -0.0358957 1 0 1 1 0 0 +EDGE2 5798 1137 -0.988421 -0.062324 -0.00471505 1 0 1 1 0 0 +EDGE2 5798 3037 -1.03544 0.0222619 -0.0100416 1 0 1 1 0 0 +EDGE2 5798 5797 -1.02002 -0.00141232 -0.0177404 1 0 1 1 0 0 +EDGE2 5798 1117 -1.00429 0.0347418 0.00679684 1 0 1 1 0 0 +EDGE2 5798 3038 0.0176775 -0.0556233 -0.023804 1 0 1 1 0 0 +EDGE2 5798 1138 0.00186733 -0.0762432 -0.0333355 1 0 1 1 0 0 +EDGE2 5798 1139 1.00017 -0.056224 0.0133907 1 0 1 1 0 0 +EDGE2 5798 1098 0.0678531 -0.0383565 0.0489189 1 0 1 1 0 0 +EDGE2 5798 3039 0.985652 0.00637288 -0.0095553 1 0 1 1 0 0 +EDGE2 5798 1099 0.928167 -0.0277554 -0.0117859 1 0 1 1 0 0 +EDGE2 5798 1119 0.93809 0.0542868 0.0226778 1 0 1 1 0 0 +EDGE2 5799 5780 1.02944 0.0517251 -3.15186 1 0 1 1 0 0 +EDGE2 5799 1118 -1.06698 -0.0569022 -0.0251865 1 0 1 1 0 0 +EDGE2 5799 3038 -1.01103 0.0143862 -0.0124077 1 0 1 1 0 0 +EDGE2 5799 5798 -0.982738 0.0254064 -0.0122625 1 0 1 1 0 0 +EDGE2 5799 1138 -1.01739 -0.0524549 0.0328057 1 0 1 1 0 0 +EDGE2 5799 1139 -0.0288282 0.0206782 -0.00574568 1 0 1 1 0 0 +EDGE2 5799 1098 -1.05539 -0.0269509 -0.0145415 1 0 1 1 0 0 +EDGE2 5799 3039 -0.0102597 -0.0236878 0.0130445 1 0 1 1 0 0 +EDGE2 5799 1099 0.0294151 -0.0423845 -0.0146163 1 0 1 1 0 0 +EDGE2 5799 1119 0.00262314 0.0410719 -0.00104317 1 0 1 1 0 0 +EDGE2 5799 1100 0.974641 -0.0552485 -0.00550317 1 0 1 1 0 0 +EDGE2 5799 1140 0.958276 -0.030735 -0.00372728 1 0 1 1 0 0 +EDGE2 5799 3040 0.974646 0.0234632 -0.035899 1 0 1 1 0 0 +EDGE2 5799 5660 0.987967 -0.0122537 -3.12843 1 0 1 1 0 0 +EDGE2 5799 1120 1.03893 -0.0616684 0.0211339 1 0 1 1 0 0 +EDGE2 5800 5780 -0.036396 -0.0453306 -3.11251 1 0 1 1 0 0 +EDGE2 5800 1139 -1.0768 0.0227055 -0.0481731 1 0 1 1 0 0 +EDGE2 5800 5799 -1.00522 -0.0159401 0.0135577 1 0 1 1 0 0 +EDGE2 5800 3039 -1.03871 0.017623 -0.0136377 1 0 1 1 0 0 +EDGE2 5800 1099 -1.0295 0.0269268 -0.017526 1 0 1 1 0 0 +EDGE2 5800 1119 -0.976217 0.0191867 -0.0503126 1 0 1 1 0 0 +EDGE2 5800 1121 0.067866 0.971487 1.58619 1 0 1 1 0 0 +EDGE2 5800 3041 0.0289275 1.05694 1.56063 1 0 1 1 0 0 +EDGE2 5800 5781 -0.0795369 1.07202 1.60935 1 0 1 1 0 0 +EDGE2 5800 1141 0.0184716 0.937392 1.55511 1 0 1 1 0 0 +EDGE2 5800 1101 -0.0452513 1.05623 1.57395 1 0 1 1 0 0 +EDGE2 5800 1100 -0.0108887 -0.0273332 0.00861396 1 0 1 1 0 0 +EDGE2 5800 1140 -0.0391825 -0.110017 0.00796344 1 0 1 1 0 0 +EDGE2 5800 3040 0.0637762 0.0315062 0.00390588 1 0 1 1 0 0 +EDGE2 5800 5660 0.00740488 -0.0926295 -3.13437 1 0 1 1 0 0 +EDGE2 5800 1120 -0.056182 0.127596 0.0312248 1 0 1 1 0 0 +EDGE2 5800 5661 0.0576434 -1.01364 -1.53463 1 0 1 1 0 0 +EDGE2 5800 5659 0.929229 0.0217993 -3.13674 1 0 1 1 0 0 +EDGE2 5800 5779 1.06396 -0.00951628 -3.14235 1 0 1 1 0 0 +EDGE2 5801 5780 -1.08328 0.0170305 1.56769 1 0 1 1 0 0 +EDGE2 5801 3042 1.12246 0.0707711 0.0168492 1 0 1 1 0 0 +EDGE2 5801 5782 0.98252 0.0802634 -0.0136386 1 0 1 1 0 0 +EDGE2 5801 1102 0.888709 0.0302491 -0.00287025 1 0 1 1 0 0 +EDGE2 5801 1122 0.989296 0.0720334 -0.0449058 1 0 1 1 0 0 +EDGE2 5801 1142 0.976943 -0.00786181 -0.00106732 1 0 1 1 0 0 +EDGE2 5801 1121 0.0771821 -0.00650932 -0.00730637 1 0 1 1 0 0 +EDGE2 5801 3041 -0.0404272 -0.0433343 0.00350053 1 0 1 1 0 0 +EDGE2 5801 5781 -0.0434142 0.0431839 0.00887177 1 0 1 1 0 0 +EDGE2 5801 1141 0.076687 -0.0384563 0.0422191 1 0 1 1 0 0 +EDGE2 5801 1101 0.0661698 0.0562228 0.000717177 1 0 1 1 0 0 +EDGE2 5801 5800 -0.961844 0.0103612 -1.55797 1 0 1 1 0 0 +EDGE2 5801 1100 -0.974602 0.0752881 -1.58062 1 0 1 1 0 0 +EDGE2 5801 1140 -1.04781 -0.0513403 -1.58141 1 0 1 1 0 0 +EDGE2 5801 3040 -1.04347 0.0150402 -1.52724 1 0 1 1 0 0 +EDGE2 5801 5660 -1.10528 -0.0675629 1.59143 1 0 1 1 0 0 +EDGE2 5801 1120 -1.06152 -0.0138554 -1.55533 1 0 1 1 0 0 +EDGE2 5802 1123 0.985113 0.0291417 0.0422167 1 0 1 1 0 0 +EDGE2 5802 3043 1.00794 -0.0423495 0.00393973 1 0 1 1 0 0 +EDGE2 5802 5783 1.13715 -0.057612 0.0171061 1 0 1 1 0 0 +EDGE2 5802 1143 1.03152 0.0617196 0.00487638 1 0 1 1 0 0 +EDGE2 5802 3042 0.0386966 0.0945041 0.0317064 1 0 1 1 0 0 +EDGE2 5802 1103 0.911982 -0.0293667 -0.0157 1 0 1 1 0 0 +EDGE2 5802 5782 0.113226 -0.0301062 -0.00630456 1 0 1 1 0 0 +EDGE2 5802 1102 -0.0676171 0.0384779 -0.01999 1 0 1 1 0 0 +EDGE2 5802 1122 0.0126648 0.00352717 0.0211935 1 0 1 1 0 0 +EDGE2 5802 1142 -0.0714102 -0.0607481 -0.0271043 1 0 1 1 0 0 +EDGE2 5802 1121 -0.96306 0.04746 0.019763 1 0 1 1 0 0 +EDGE2 5802 3041 -1.07189 0.13996 -0.00176078 1 0 1 1 0 0 +EDGE2 5802 5781 -0.969159 -0.0101568 -0.00299407 1 0 1 1 0 0 +EDGE2 5802 5801 -1.03865 -0.0101698 -0.00754241 1 0 1 1 0 0 +EDGE2 5802 1141 -1.03028 0.0188115 0.0111389 1 0 1 1 0 0 +EDGE2 5802 1101 -1.10359 0.0184631 0.0139389 1 0 1 1 0 0 +EDGE2 5803 1123 0.0745358 -0.0291005 -0.0126556 1 0 1 1 0 0 +EDGE2 5803 5784 1.03729 0.0548593 0.0322284 1 0 1 1 0 0 +EDGE2 5803 1124 0.886925 -0.115335 -0.0396738 1 0 1 1 0 0 +EDGE2 5803 1144 1.00075 0.00116216 0.0044304 1 0 1 1 0 0 +EDGE2 5803 3044 1.02377 0.0394755 0.0136432 1 0 1 1 0 0 +EDGE2 5803 1104 1.10619 0.014414 0.00923579 1 0 1 1 0 0 +EDGE2 5803 3043 -0.0474878 -0.00446884 -0.0220774 1 0 1 1 0 0 +EDGE2 5803 5783 -0.0750428 -0.0503145 0.0432691 1 0 1 1 0 0 +EDGE2 5803 1143 0.0735156 -0.0513683 -0.0388827 1 0 1 1 0 0 +EDGE2 5803 3042 -0.993781 -0.0294752 0.068962 1 0 1 1 0 0 +EDGE2 5803 5802 -1.01787 0.080946 0.0064925 1 0 1 1 0 0 +EDGE2 5803 1103 0.000783718 -0.00629618 0.0159937 1 0 1 1 0 0 +EDGE2 5803 5782 -1.09851 -0.00239004 0.00964372 1 0 1 1 0 0 +EDGE2 5803 1102 -0.956493 0.0403268 0.00551447 1 0 1 1 0 0 +EDGE2 5803 1122 -1.0474 0.0145517 0.033634 1 0 1 1 0 0 +EDGE2 5803 1142 -1.0017 0.000607017 -0.00734016 1 0 1 1 0 0 +EDGE2 5804 1123 -1.05541 -0.027289 -0.00167528 1 0 1 1 0 0 +EDGE2 5804 5784 0.0314567 -0.0752461 -0.00490428 1 0 1 1 0 0 +EDGE2 5804 1145 0.965194 -0.0404261 -0.0418653 1 0 1 1 0 0 +EDGE2 5804 3045 0.96389 0.102439 -0.0358645 1 0 1 1 0 0 +EDGE2 5804 3505 0.983897 0.0450495 -3.12836 1 0 1 1 0 0 +EDGE2 5804 5785 0.911261 0.0354593 0.000372761 1 0 1 1 0 0 +EDGE2 5804 3025 1.01817 0.00240041 -3.13032 1 0 1 1 0 0 +EDGE2 5804 1105 1.05324 -0.12621 0.0216228 1 0 1 1 0 0 +EDGE2 5804 1125 1.04483 -0.00553785 -0.0173663 1 0 1 1 0 0 +EDGE2 5804 1124 0.0047089 0.00138959 -0.000425058 1 0 1 1 0 0 +EDGE2 5804 1144 0.0161204 -0.070763 -0.00992886 1 0 1 1 0 0 +EDGE2 5804 3044 0.0282126 -0.0940628 0.0357694 1 0 1 1 0 0 +EDGE2 5804 1104 0.0667851 -0.00393974 -0.0221493 1 0 1 1 0 0 +EDGE2 5804 3043 -1.03468 -0.0316759 -0.0379923 1 0 1 1 0 0 +EDGE2 5804 5783 -0.942158 -0.000813774 -0.0107768 1 0 1 1 0 0 +EDGE2 5804 5803 -1.04254 0.00499488 -0.00902844 1 0 1 1 0 0 +EDGE2 5804 1143 -0.947389 0.000243325 0.0212599 1 0 1 1 0 0 +EDGE2 5804 1103 -0.977245 -0.0715046 -0.0104722 1 0 1 1 0 0 +EDGE2 5805 3504 0.966898 0.036552 -3.14193 1 0 1 1 0 0 +EDGE2 5805 3024 1.00492 -0.0474605 -3.121 1 0 1 1 0 0 +EDGE2 5805 3046 -0.00531113 0.975532 1.56344 1 0 1 1 0 0 +EDGE2 5805 5786 0.0331357 0.958955 1.60297 1 0 1 1 0 0 +EDGE2 5805 1126 -0.0189947 0.929021 1.57737 1 0 1 1 0 0 +EDGE2 5805 1146 -0.0702573 0.958371 1.56781 1 0 1 1 0 0 +EDGE2 5805 3026 -0.0640797 0.986117 1.6072 1 0 1 1 0 0 +EDGE2 5805 1106 -0.0373632 0.95742 1.57888 1 0 1 1 0 0 +EDGE2 5805 5784 -1.00847 0.0260401 0.00876033 1 0 1 1 0 0 +EDGE2 5805 1145 0.0807164 -0.0115397 0.0243249 1 0 1 1 0 0 +EDGE2 5805 3045 0.00533647 0.0138581 0.00350332 1 0 1 1 0 0 +EDGE2 5805 3505 -0.0194318 0.0738201 -3.11137 1 0 1 1 0 0 +EDGE2 5805 5785 0.0673045 -0.0002316 -0.0173056 1 0 1 1 0 0 +EDGE2 5805 3025 -0.0191307 -0.00926823 -3.11315 1 0 1 1 0 0 +EDGE2 5805 1105 -0.0226761 0.0415359 0.0171365 1 0 1 1 0 0 +EDGE2 5805 1125 -0.075353 -0.0559841 -0.0202977 1 0 1 1 0 0 +EDGE2 5805 5804 -1.01603 -0.0569096 0.0739798 1 0 1 1 0 0 +EDGE2 5805 1124 -0.977134 0.0250114 -0.0244379 1 0 1 1 0 0 +EDGE2 5805 1144 -0.924705 -0.0577234 0.00772199 1 0 1 1 0 0 +EDGE2 5805 3044 -1.01884 0.036566 -0.0102548 1 0 1 1 0 0 +EDGE2 5805 1104 -1.03251 0.0685606 -1.53753e-05 1 0 1 1 0 0 +EDGE2 5805 3506 0.0276434 -0.927256 -1.5944 1 0 1 1 0 0 +EDGE2 5806 3027 0.981869 0.0045911 0.0220361 1 0 1 1 0 0 +EDGE2 5806 5787 1.02468 0.0455282 0.0288927 1 0 1 1 0 0 +EDGE2 5806 3047 0.961935 0.00235784 -0.00118665 1 0 1 1 0 0 +EDGE2 5806 5805 -0.916995 0.0750316 -1.57856 1 0 1 1 0 0 +EDGE2 5806 1127 0.977654 -0.061025 -0.00671486 1 0 1 1 0 0 +EDGE2 5806 1147 0.985989 -0.072415 -0.0103241 1 0 1 1 0 0 +EDGE2 5806 1107 0.970895 -0.0617124 -0.00444174 1 0 1 1 0 0 +EDGE2 5806 3046 0.00941442 0.0683145 0.00895996 1 0 1 1 0 0 +EDGE2 5806 5786 0.0143201 0.0507804 -0.00748671 1 0 1 1 0 0 +EDGE2 5806 1126 0.0974329 0.0308044 0.0155145 1 0 1 1 0 0 +EDGE2 5806 1146 -0.111539 0.00893252 0.0144287 1 0 1 1 0 0 +EDGE2 5806 3026 0.0110308 0.0816539 0.037831 1 0 1 1 0 0 +EDGE2 5806 1106 -0.00961355 -0.00791328 -0.0185612 1 0 1 1 0 0 +EDGE2 5806 1145 -1.05969 -0.126267 -1.54738 1 0 1 1 0 0 +EDGE2 5806 3045 -1.0418 0.0108416 -1.59956 1 0 1 1 0 0 +EDGE2 5806 3505 -0.968653 0.025112 1.56892 1 0 1 1 0 0 +EDGE2 5806 5785 -1.01645 -0.0432979 -1.57362 1 0 1 1 0 0 +EDGE2 5806 3025 -0.970712 -0.0629025 1.59459 1 0 1 1 0 0 +EDGE2 5806 1105 -0.974703 -0.0101133 -1.59027 1 0 1 1 0 0 +EDGE2 5806 1125 -1.10627 0.00859208 -1.58735 1 0 1 1 0 0 +EDGE2 5807 3027 0.0080061 -0.00238671 -0.00541063 1 0 1 1 0 0 +EDGE2 5807 3048 1.04751 0.0246294 3.95906e-05 1 0 1 1 0 0 +EDGE2 5807 5788 1.01074 0.00917638 0.0272251 1 0 1 1 0 0 +EDGE2 5807 3028 0.893887 0.106779 0.00690121 1 0 1 1 0 0 +EDGE2 5807 1108 1.00764 -0.0390568 0.0190313 1 0 1 1 0 0 +EDGE2 5807 1128 0.940954 0.0215759 0.000841032 1 0 1 1 0 0 +EDGE2 5807 1148 0.970855 0.0108553 0.00624594 1 0 1 1 0 0 +EDGE2 5807 5787 -0.0161348 -0.0196644 -0.0309437 1 0 1 1 0 0 +EDGE2 5807 3047 0.0723058 0.0539386 -0.019645 1 0 1 1 0 0 +EDGE2 5807 1127 -0.0509401 -0.0251243 -0.0180821 1 0 1 1 0 0 +EDGE2 5807 1147 0.00828243 0.00923872 0.000955541 1 0 1 1 0 0 +EDGE2 5807 1107 -0.0693175 0.0585755 0.0115701 1 0 1 1 0 0 +EDGE2 5807 3046 -1.11397 0.0228496 0.0031434 1 0 1 1 0 0 +EDGE2 5807 5806 -0.941712 -0.0232058 -0.02186 1 0 1 1 0 0 +EDGE2 5807 5786 -1.01997 0.00235784 0.0129464 1 0 1 1 0 0 +EDGE2 5807 1126 -1.03469 0.0823176 -0.0176049 1 0 1 1 0 0 +EDGE2 5807 1146 -1.06658 0.0168464 0.0114307 1 0 1 1 0 0 +EDGE2 5807 3026 -0.999344 -0.0177015 -0.0109067 1 0 1 1 0 0 +EDGE2 5807 1106 -1.02943 -0.028196 0.000193521 1 0 1 1 0 0 +EDGE2 5808 3027 -0.998404 0.0428317 -0.0295123 1 0 1 1 0 0 +EDGE2 5808 3048 -0.0234559 0.0122816 -0.0131549 1 0 1 1 0 0 +EDGE2 5808 5789 1.03364 -0.0460728 -0.00698123 1 0 1 1 0 0 +EDGE2 5808 1109 1.04429 -0.0152832 -0.0106032 1 0 1 1 0 0 +EDGE2 5808 1149 1.00486 -0.0801656 0.0159768 1 0 1 1 0 0 +EDGE2 5808 3029 0.967353 -0.0217705 0.0228667 1 0 1 1 0 0 +EDGE2 5808 3049 0.995929 -0.0985821 0.0117179 1 0 1 1 0 0 +EDGE2 5808 1129 1.06924 -0.0272712 0.0221447 1 0 1 1 0 0 +EDGE2 5808 5788 -0.0648073 -0.0664158 0.00320289 1 0 1 1 0 0 +EDGE2 5808 3028 -0.000462832 0.0771577 -0.00545638 1 0 1 1 0 0 +EDGE2 5808 1108 0.0305969 -0.119405 -0.00906469 1 0 1 1 0 0 +EDGE2 5808 1128 -0.0420678 0.0583917 0.00563982 1 0 1 1 0 0 +EDGE2 5808 1148 -0.0573715 0.0469457 -0.0245369 1 0 1 1 0 0 +EDGE2 5808 5787 -0.931956 -0.009982 0.0165079 1 0 1 1 0 0 +EDGE2 5808 5807 -1.05076 -0.0140725 -0.0238076 1 0 1 1 0 0 +EDGE2 5808 3047 -0.944611 -0.0698366 0.0117309 1 0 1 1 0 0 +EDGE2 5808 1127 -0.983258 0.0214202 -0.0239035 1 0 1 1 0 0 +EDGE2 5808 1147 -1.02227 -0.0381676 0.0255481 1 0 1 1 0 0 +EDGE2 5808 1107 -0.992083 -0.0268149 0.00621679 1 0 1 1 0 0 +EDGE2 5809 3050 0.926858 -0.053706 0.00549443 1 0 1 1 0 0 +EDGE2 5809 3170 1.06144 0.0181564 -3.18484 1 0 1 1 0 0 +EDGE2 5809 5790 0.965374 0.0317921 0.0402253 1 0 1 1 0 0 +EDGE2 5809 3490 0.946168 0.0657984 -3.13988 1 0 1 1 0 0 +EDGE2 5809 3110 0.97372 0.0666404 -3.1645 1 0 1 1 0 0 +EDGE2 5809 3130 1.01202 -0.0464048 -3.13587 1 0 1 1 0 0 +EDGE2 5809 3090 0.956312 0.0612229 -3.12332 1 0 1 1 0 0 +EDGE2 5809 3048 -1.07348 0.0238382 -0.00878527 1 0 1 1 0 0 +EDGE2 5809 5789 -0.0401958 -0.0252956 0.00976843 1 0 1 1 0 0 +EDGE2 5809 1130 0.960968 0.022859 -0.00480002 1 0 1 1 0 0 +EDGE2 5809 1170 1.04707 0.0918589 -3.14921 1 0 1 1 0 0 +EDGE2 5809 1190 1.0734 -0.0807026 -3.13893 1 0 1 1 0 0 +EDGE2 5809 3030 1.07008 -0.00213512 0.00766733 1 0 1 1 0 0 +EDGE2 5809 1150 1.00848 -0.0404334 0.0118699 1 0 1 1 0 0 +EDGE2 5809 1110 0.895659 -0.0398227 0.00200915 1 0 1 1 0 0 +EDGE2 5809 1109 0.0152716 -0.0314801 0.00539183 1 0 1 1 0 0 +EDGE2 5809 1149 0.0280857 0.03904 -0.00806958 1 0 1 1 0 0 +EDGE2 5809 3029 0.0607534 0.0473635 0.0136751 1 0 1 1 0 0 +EDGE2 5809 3049 0.00378409 -0.0901298 -0.0538719 1 0 1 1 0 0 +EDGE2 5809 1129 -0.00196707 -0.0395512 -0.00280319 1 0 1 1 0 0 +EDGE2 5809 5808 -0.985122 0.0407252 0.0114461 1 0 1 1 0 0 +EDGE2 5809 5788 -1.02087 0.0687247 -0.000922273 1 0 1 1 0 0 +EDGE2 5809 3028 -0.932377 -0.0121321 -0.00406198 1 0 1 1 0 0 +EDGE2 5809 1108 -0.901085 0.0610552 -0.000686373 1 0 1 1 0 0 +EDGE2 5809 1128 -0.995043 -0.0143539 -0.0129361 1 0 1 1 0 0 +EDGE2 5809 1148 -0.943051 -0.0622281 0.0105032 1 0 1 1 0 0 +EDGE2 5810 3109 0.991518 -0.023098 -3.14673 1 0 1 1 0 0 +EDGE2 5810 3169 1.03455 0.0311271 -3.14699 1 0 1 1 0 0 +EDGE2 5810 3489 1.04606 -0.00925903 -3.11731 1 0 1 1 0 0 +EDGE2 5810 3129 0.991293 -0.0452282 -3.14929 1 0 1 1 0 0 +EDGE2 5810 1189 1.02276 -0.040664 -3.14054 1 0 1 1 0 0 +EDGE2 5810 3089 1.0057 0.00734043 -3.16014 1 0 1 1 0 0 +EDGE2 5810 1169 0.978823 0.0184004 -3.11675 1 0 1 1 0 0 +EDGE2 5810 3050 -0.0531599 0.0442676 -0.0205119 1 0 1 1 0 0 +EDGE2 5810 3131 0.0584822 -1.01916 -1.56294 1 0 1 1 0 0 +EDGE2 5810 3491 -0.0228706 -0.931741 -1.58411 1 0 1 1 0 0 +EDGE2 5810 3171 0.0216293 -0.977672 -1.55927 1 0 1 1 0 0 +EDGE2 5810 1151 0.0124003 -1.08818 -1.56689 1 0 1 1 0 0 +EDGE2 5810 1191 0.0589778 -1.0489 -1.59119 1 0 1 1 0 0 +EDGE2 5810 3091 0.0331161 -1.02038 -1.55047 1 0 1 1 0 0 +EDGE2 5810 3111 0.00200945 -0.976569 -1.57338 1 0 1 1 0 0 +EDGE2 5810 1171 -0.00534234 -0.874385 -1.57263 1 0 1 1 0 0 +EDGE2 5810 3170 0.0171435 0.0555397 -3.16355 1 0 1 1 0 0 +EDGE2 5810 5790 0.034244 -0.0564341 -0.0135826 1 0 1 1 0 0 +EDGE2 5810 3490 -0.067005 -0.052946 -3.13441 1 0 1 1 0 0 +EDGE2 5810 3110 -0.0490606 0.0642742 -3.13882 1 0 1 1 0 0 +EDGE2 5810 3130 0.0192074 0.0388613 -3.12703 1 0 1 1 0 0 +EDGE2 5810 3090 -0.000414475 -0.00933235 -3.15226 1 0 1 1 0 0 +EDGE2 5810 5789 -0.961596 0.00295445 0.0246199 1 0 1 1 0 0 +EDGE2 5810 1130 -0.0724664 0.157313 -0.0101171 1 0 1 1 0 0 +EDGE2 5810 1170 0.0797263 0.0369377 -3.12644 1 0 1 1 0 0 +EDGE2 5810 1190 0.0220254 -0.0424864 -3.13945 1 0 1 1 0 0 +EDGE2 5810 3030 0.108104 -0.00334253 -0.0272288 1 0 1 1 0 0 +EDGE2 5810 1150 -0.0127573 -0.0361085 0.00996859 1 0 1 1 0 0 +EDGE2 5810 1110 0.0275136 -0.0230993 0.0229151 1 0 1 1 0 0 +EDGE2 5810 5809 -0.944328 0.03798 -0.0158905 1 0 1 1 0 0 +EDGE2 5810 1109 -1.03206 -0.00997729 0.0178804 1 0 1 1 0 0 +EDGE2 5810 1149 -1.04479 -0.0275102 -0.0175858 1 0 1 1 0 0 +EDGE2 5810 3029 -1.07417 0.0341852 -0.0179396 1 0 1 1 0 0 +EDGE2 5810 3049 -1.06836 0.0157936 -0.0154274 1 0 1 1 0 0 +EDGE2 5810 1129 -1.0624 -0.0084606 0.00795808 1 0 1 1 0 0 +EDGE2 5810 1111 -0.0239769 0.975591 1.57819 1 0 1 1 0 0 +EDGE2 5810 3031 -0.069641 1.01559 1.61019 1 0 1 1 0 0 +EDGE2 5810 3051 -0.00906185 1.00118 1.58387 1 0 1 1 0 0 +EDGE2 5810 5791 -0.00848222 0.966713 1.57374 1 0 1 1 0 0 +EDGE2 5810 1131 0.0612634 1.02014 1.58063 1 0 1 1 0 0 +EDGE2 5811 3050 -1.03459 -0.137015 1.53197 1 0 1 1 0 0 +EDGE2 5811 3131 0.00321725 -0.0780349 -0.00631666 1 0 1 1 0 0 +EDGE2 5811 3092 0.962477 -0.00351945 -0.0146986 1 0 1 1 0 0 +EDGE2 5811 3132 1.01369 -0.0655715 -0.0291867 1 0 1 1 0 0 +EDGE2 5811 3172 1.00829 0.00578529 -0.0350987 1 0 1 1 0 0 +EDGE2 5811 3492 1.0047 0.0140584 -0.0335509 1 0 1 1 0 0 +EDGE2 5811 3112 1.06974 0.0374483 0.0012496 1 0 1 1 0 0 +EDGE2 5811 1152 0.991271 0.0433317 -0.00244587 1 0 1 1 0 0 +EDGE2 5811 1172 0.988297 -0.138673 0.00748986 1 0 1 1 0 0 +EDGE2 5811 1192 0.960598 -0.0277088 -0.00471841 1 0 1 1 0 0 +EDGE2 5811 3491 -0.0475644 -0.0426352 -0.0067524 1 0 1 1 0 0 +EDGE2 5811 3171 0.0439002 0.0962614 -0.0330034 1 0 1 1 0 0 +EDGE2 5811 1151 -0.0486322 -0.00625259 -0.0485517 1 0 1 1 0 0 +EDGE2 5811 1191 -0.0482737 -0.0483211 -0.00434439 1 0 1 1 0 0 +EDGE2 5811 3091 0.0249666 0.0127176 0.0553404 1 0 1 1 0 0 +EDGE2 5811 3111 -0.0351684 -0.0584349 -0.0107861 1 0 1 1 0 0 +EDGE2 5811 1171 -0.0767522 -0.030088 0.00571732 1 0 1 1 0 0 +EDGE2 5811 3170 -0.990851 -0.104846 -1.54619 1 0 1 1 0 0 +EDGE2 5811 5790 -0.98001 -0.057805 1.58995 1 0 1 1 0 0 +EDGE2 5811 5810 -0.864794 0.00602944 1.57313 1 0 1 1 0 0 +EDGE2 5811 3490 -1.02771 0.077997 -1.57216 1 0 1 1 0 0 +EDGE2 5811 3110 -1.00264 0.0655086 -1.54535 1 0 1 1 0 0 +EDGE2 5811 3130 -0.967304 -0.0438375 -1.54887 1 0 1 1 0 0 +EDGE2 5811 3090 -1.06013 0.0300611 -1.56531 1 0 1 1 0 0 +EDGE2 5811 1130 -1.03572 0.0567428 1.59025 1 0 1 1 0 0 +EDGE2 5811 1170 -1.03094 -0.124528 -1.55187 1 0 1 1 0 0 +EDGE2 5811 1190 -1.03778 0.00345663 -1.57835 1 0 1 1 0 0 +EDGE2 5811 3030 -1.06793 0.0668426 1.6181 1 0 1 1 0 0 +EDGE2 5811 1150 -0.973431 -0.00967713 1.57591 1 0 1 1 0 0 +EDGE2 5811 1110 -0.991821 -0.00677751 1.57024 1 0 1 1 0 0 +EDGE2 5812 1173 0.991535 -0.0275764 -0.0378206 1 0 1 1 0 0 +EDGE2 5812 3133 0.949128 0.0137895 -0.0223085 1 0 1 1 0 0 +EDGE2 5812 3493 0.961314 -0.103531 -0.00432007 1 0 1 1 0 0 +EDGE2 5812 3173 0.869154 0.0215473 0.0243014 1 0 1 1 0 0 +EDGE2 5812 3093 1.0365 -0.102609 0.00585874 1 0 1 1 0 0 +EDGE2 5812 3113 1.00524 0.0253477 -0.0118192 1 0 1 1 0 0 +EDGE2 5812 1193 1.12277 -0.0275863 0.0158636 1 0 1 1 0 0 +EDGE2 5812 3131 -0.978919 0.0470878 0.015105 1 0 1 1 0 0 +EDGE2 5812 3092 0.0403685 -0.0167553 0.00928218 1 0 1 1 0 0 +EDGE2 5812 1153 1.02704 0.0395921 -0.00169568 1 0 1 1 0 0 +EDGE2 5812 3132 -0.0807144 -0.0166314 -0.00258397 1 0 1 1 0 0 +EDGE2 5812 3172 -0.0471545 0.0831993 -0.0203421 1 0 1 1 0 0 +EDGE2 5812 3492 -0.122198 -0.0221603 0.0172997 1 0 1 1 0 0 +EDGE2 5812 3112 -0.0253384 -0.02648 -0.0208291 1 0 1 1 0 0 +EDGE2 5812 1152 -0.034459 -0.0147103 0.00462585 1 0 1 1 0 0 +EDGE2 5812 1172 -0.0464027 -0.0181968 -0.0224751 1 0 1 1 0 0 +EDGE2 5812 1192 0.0258116 -0.0288794 -0.0224465 1 0 1 1 0 0 +EDGE2 5812 3491 -1.02172 0.0282031 -0.00753554 1 0 1 1 0 0 +EDGE2 5812 5811 -0.985524 -0.0192596 0.0204827 1 0 1 1 0 0 +EDGE2 5812 3171 -0.948322 -0.00328934 0.0158943 1 0 1 1 0 0 +EDGE2 5812 1151 -1.09477 0.0165991 -0.0083689 1 0 1 1 0 0 +EDGE2 5812 1191 -1.02238 -0.00735286 -0.0188478 1 0 1 1 0 0 +EDGE2 5812 3091 -1.09311 -0.0954214 0.00367195 1 0 1 1 0 0 +EDGE2 5812 3111 -1.05818 -0.0142334 0.00780787 1 0 1 1 0 0 +EDGE2 5812 1171 -0.996526 -0.0597615 -0.00498216 1 0 1 1 0 0 +EDGE2 5813 1173 0.0274422 -0.0814387 0.00717632 1 0 1 1 0 0 +EDGE2 5813 1174 1.00138 0.0117289 -0.00504518 1 0 1 1 0 0 +EDGE2 5813 3174 1.06 0.0576235 -0.0368787 1 0 1 1 0 0 +EDGE2 5813 3494 1.04712 -0.0321852 -0.0261577 1 0 1 1 0 0 +EDGE2 5813 3094 0.994148 0.057675 -0.00424889 1 0 1 1 0 0 +EDGE2 5813 3114 0.967422 0.0456616 -0.0124586 1 0 1 1 0 0 +EDGE2 5813 3134 1.00184 -0.08493 0.00603485 1 0 1 1 0 0 +EDGE2 5813 1194 1.08015 -0.0732559 -0.022188 1 0 1 1 0 0 +EDGE2 5813 1154 1.04017 0.0296415 0.0155073 1 0 1 1 0 0 +EDGE2 5813 3133 -0.0853477 0.0125983 0.0377029 1 0 1 1 0 0 +EDGE2 5813 3493 0.0553224 0.0216043 -0.0159371 1 0 1 1 0 0 +EDGE2 5813 3173 -0.04573 -0.0872958 0.0123501 1 0 1 1 0 0 +EDGE2 5813 3093 0.0169498 -0.101035 0.0448322 1 0 1 1 0 0 +EDGE2 5813 3113 -0.0013892 -0.05983 -0.00820712 1 0 1 1 0 0 +EDGE2 5813 1193 -0.0266931 -0.033276 0.00105162 1 0 1 1 0 0 +EDGE2 5813 3092 -1.05934 0.0392893 -0.0371053 1 0 1 1 0 0 +EDGE2 5813 5812 -0.976938 0.0642123 -0.0256287 1 0 1 1 0 0 +EDGE2 5813 1153 0.0641185 -0.0973384 0.00307259 1 0 1 1 0 0 +EDGE2 5813 3132 -0.971364 0.00345957 -0.0296983 1 0 1 1 0 0 +EDGE2 5813 3172 -0.95103 0.0458687 0.00123773 1 0 1 1 0 0 +EDGE2 5813 3492 -1.02677 0.0247817 0.0101135 1 0 1 1 0 0 +EDGE2 5813 3112 -1.02896 0.0559548 -0.0367643 1 0 1 1 0 0 +EDGE2 5813 1152 -0.984836 -0.0292667 -0.0269517 1 0 1 1 0 0 +EDGE2 5813 1172 -0.943207 0.0413662 0.000890213 1 0 1 1 0 0 +EDGE2 5813 1192 -1.08967 -0.0842654 -0.0199523 1 0 1 1 0 0 +EDGE2 5814 3495 0.995055 -0.0568003 0.0561335 1 0 1 1 0 0 +EDGE2 5814 1173 -0.948695 0.0562473 -0.000298415 1 0 1 1 0 0 +EDGE2 5814 1174 -0.0646775 0.0281583 0.0126467 1 0 1 1 0 0 +EDGE2 5814 3115 0.95172 -0.0666094 0.0117126 1 0 1 1 0 0 +EDGE2 5814 3175 0.966935 -0.06411 -0.0192389 1 0 1 1 0 0 +EDGE2 5814 3375 0.953117 -0.0590386 -3.14708 1 0 1 1 0 0 +EDGE2 5814 3475 0.958571 -0.0187305 -3.14113 1 0 1 1 0 0 +EDGE2 5814 3135 1.0123 0.0351294 -0.00280062 1 0 1 1 0 0 +EDGE2 5814 1175 1.04012 -0.00442362 -0.0320981 1 0 1 1 0 0 +EDGE2 5814 1195 0.994157 -0.00879488 0.0181681 1 0 1 1 0 0 +EDGE2 5814 3095 1.04083 0.0229465 0.0202407 1 0 1 1 0 0 +EDGE2 5814 1155 0.944753 0.0094457 0.0184819 1 0 1 1 0 0 +EDGE2 5814 3174 0.00403455 -0.0183646 0.0435866 1 0 1 1 0 0 +EDGE2 5814 3494 0.0281379 -0.0899413 -0.0180599 1 0 1 1 0 0 +EDGE2 5814 3094 -0.0507404 -0.07066 0.0134654 1 0 1 1 0 0 +EDGE2 5814 3114 0.0182188 0.0150101 0.0171309 1 0 1 1 0 0 +EDGE2 5814 3134 -0.036053 -0.0138724 -0.0180912 1 0 1 1 0 0 +EDGE2 5814 1194 -0.0385946 -0.0458048 0.00426062 1 0 1 1 0 0 +EDGE2 5814 1154 0.115232 -0.00594469 0.00659279 1 0 1 1 0 0 +EDGE2 5814 3133 -1.07548 0.00904212 0.0310556 1 0 1 1 0 0 +EDGE2 5814 3493 -0.969472 -0.0295951 -0.00796368 1 0 1 1 0 0 +EDGE2 5814 5813 -1.05207 0.000984554 -0.0029316 1 0 1 1 0 0 +EDGE2 5814 3173 -0.905785 -0.00398699 -0.0129445 1 0 1 1 0 0 +EDGE2 5814 3093 -0.972854 -0.0354158 -0.00241068 1 0 1 1 0 0 +EDGE2 5814 3113 -0.98786 0.00471231 -0.011062 1 0 1 1 0 0 +EDGE2 5814 1193 -1.05804 0.047708 0.0167343 1 0 1 1 0 0 +EDGE2 5814 1153 -0.978317 0.0358447 -0.00665281 1 0 1 1 0 0 +EDGE2 5815 3495 -0.0670359 0.0547012 0.00117819 1 0 1 1 0 0 +EDGE2 5815 3474 0.969456 0.114036 -3.12003 1 0 1 1 0 0 +EDGE2 5815 3374 0.937586 -0.0206108 -3.14981 1 0 1 1 0 0 +EDGE2 5815 1196 -0.0172017 0.933567 1.56592 1 0 1 1 0 0 +EDGE2 5815 3476 0.0157649 0.922771 1.55479 1 0 1 1 0 0 +EDGE2 5815 3116 -0.00605113 1.02056 1.55758 1 0 1 1 0 0 +EDGE2 5815 3136 0.034534 1.01941 1.55475 1 0 1 1 0 0 +EDGE2 5815 3376 -0.0161757 1.01073 1.54785 1 0 1 1 0 0 +EDGE2 5815 3096 -0.0103125 0.882005 1.59298 1 0 1 1 0 0 +EDGE2 5815 1156 0.0259684 1.00323 1.56548 1 0 1 1 0 0 +EDGE2 5815 1176 -0.0120271 0.93965 1.58966 1 0 1 1 0 0 +EDGE2 5815 1174 -0.988789 0.0729016 -0.00682777 1 0 1 1 0 0 +EDGE2 5815 3115 0.0390445 0.0202287 0.00469326 1 0 1 1 0 0 +EDGE2 5815 3175 -0.0261494 -0.113384 -0.00554806 1 0 1 1 0 0 +EDGE2 5815 3375 0.0187113 -0.0194824 -3.13305 1 0 1 1 0 0 +EDGE2 5815 3475 -0.00820761 0.0314746 -3.14815 1 0 1 1 0 0 +EDGE2 5815 3135 0.0410563 -0.0807411 0.00414832 1 0 1 1 0 0 +EDGE2 5815 1175 0.0833747 0.0394213 -0.0164842 1 0 1 1 0 0 +EDGE2 5815 1195 -0.0833506 -0.0150891 -0.0078077 1 0 1 1 0 0 +EDGE2 5815 3095 0.00725967 -0.0667147 0.0293194 1 0 1 1 0 0 +EDGE2 5815 1155 0.110131 0.0260035 -0.0249412 1 0 1 1 0 0 +EDGE2 5815 3174 -0.917518 0.0787447 -0.00524996 1 0 1 1 0 0 +EDGE2 5815 5814 -0.935181 0.00822131 -0.0193373 1 0 1 1 0 0 +EDGE2 5815 3494 -0.99838 0.0961335 -0.00689942 1 0 1 1 0 0 +EDGE2 5815 3094 -1.02437 -0.0566494 0.0282575 1 0 1 1 0 0 +EDGE2 5815 3114 -1.08774 -0.0904351 0.000240527 1 0 1 1 0 0 +EDGE2 5815 3134 -1.07557 0.0406912 0.0288349 1 0 1 1 0 0 +EDGE2 5815 1194 -1.0104 -0.0112269 0.0106758 1 0 1 1 0 0 +EDGE2 5815 1154 -0.982371 -0.0193887 0.00193176 1 0 1 1 0 0 +EDGE2 5815 3176 -0.0112501 -0.985415 -1.56857 1 0 1 1 0 0 +EDGE2 5815 3496 0.00886095 -1.00374 -1.57994 1 0 1 1 0 0 +EDGE2 5816 3495 -1.02644 -0.0586772 -1.58961 1 0 1 1 0 0 +EDGE2 5816 1197 1.00603 -0.0141765 -0.0227097 1 0 1 1 0 0 +EDGE2 5816 3477 1.0177 0.0526943 -0.0341231 1 0 1 1 0 0 +EDGE2 5816 3117 1.06374 -0.0211216 -0.0261577 1 0 1 1 0 0 +EDGE2 5816 3137 0.93917 -0.0336117 0.00692998 1 0 1 1 0 0 +EDGE2 5816 3377 0.999742 0.0407755 0.0154553 1 0 1 1 0 0 +EDGE2 5816 3097 1.07637 0.0209519 0.00215586 1 0 1 1 0 0 +EDGE2 5816 1177 0.918316 0.0160449 -0.0133258 1 0 1 1 0 0 +EDGE2 5816 1157 0.883609 0.0825668 -0.0282012 1 0 1 1 0 0 +EDGE2 5816 1196 0.068565 -0.0411364 0.0208899 1 0 1 1 0 0 +EDGE2 5816 3476 -0.0632099 -0.0308197 6.79246e-05 1 0 1 1 0 0 +EDGE2 5816 3116 0.0647448 0.0509255 -0.00162977 1 0 1 1 0 0 +EDGE2 5816 3136 0.0187264 -0.042169 0.00545588 1 0 1 1 0 0 +EDGE2 5816 3376 -0.00934341 -0.00579873 -0.0117668 1 0 1 1 0 0 +EDGE2 5816 3096 -0.0425633 0.0116569 -0.012677 1 0 1 1 0 0 +EDGE2 5816 1156 -0.0135663 0.0773634 0.00196672 1 0 1 1 0 0 +EDGE2 5816 1176 -0.0337146 -0.0184649 0.028249 1 0 1 1 0 0 +EDGE2 5816 5815 -1.05118 0.0103381 -1.60282 1 0 1 1 0 0 +EDGE2 5816 3115 -0.975706 0.0375976 -1.57435 1 0 1 1 0 0 +EDGE2 5816 3175 -1.0107 -0.0316289 -1.57726 1 0 1 1 0 0 +EDGE2 5816 3375 -1.02467 0.0399428 1.58622 1 0 1 1 0 0 +EDGE2 5816 3475 -0.989006 0.0658555 1.56343 1 0 1 1 0 0 +EDGE2 5816 3135 -0.971912 0.0500158 -1.54705 1 0 1 1 0 0 +EDGE2 5816 1175 -0.989466 0.021381 -1.57497 1 0 1 1 0 0 +EDGE2 5816 1195 -1.04457 -0.0699164 -1.58767 1 0 1 1 0 0 +EDGE2 5816 3095 -0.971575 0.011533 -1.54629 1 0 1 1 0 0 +EDGE2 5816 1155 -0.992501 0.0381899 -1.56018 1 0 1 1 0 0 +EDGE2 5817 1197 -0.0755496 0.0938387 -0.00103047 1 0 1 1 0 0 +EDGE2 5817 3098 0.977563 0.0137506 0.0233903 1 0 1 1 0 0 +EDGE2 5817 3138 0.91917 -0.0718017 -0.00353098 1 0 1 1 0 0 +EDGE2 5817 3378 0.916063 0.0226593 0.00934124 1 0 1 1 0 0 +EDGE2 5817 3478 1.09059 0.0424973 0.0452185 1 0 1 1 0 0 +EDGE2 5817 3118 1.12031 -0.0637395 -0.00157668 1 0 1 1 0 0 +EDGE2 5817 1178 0.887606 -0.0168481 -0.0260467 1 0 1 1 0 0 +EDGE2 5817 1198 1.11015 0.0213203 -0.0113642 1 0 1 1 0 0 +EDGE2 5817 1158 1.04523 0.0616082 -0.0117867 1 0 1 1 0 0 +EDGE2 5817 3477 0.0322029 -0.069191 -0.0319221 1 0 1 1 0 0 +EDGE2 5817 3117 0.0338327 0.0264676 0.0193868 1 0 1 1 0 0 +EDGE2 5817 3137 0.041075 -0.0111306 0.0086001 1 0 1 1 0 0 +EDGE2 5817 3377 -0.0365215 0.0354126 -0.0194073 1 0 1 1 0 0 +EDGE2 5817 3097 0.00979541 -0.0452854 -0.00179824 1 0 1 1 0 0 +EDGE2 5817 1177 0.0881722 -0.116454 0.00343285 1 0 1 1 0 0 +EDGE2 5817 1157 -0.012314 0.0977727 0.0105646 1 0 1 1 0 0 +EDGE2 5817 1196 -1.0323 0.012891 0.0241677 1 0 1 1 0 0 +EDGE2 5817 3476 -0.989024 -0.0527841 0.0164728 1 0 1 1 0 0 +EDGE2 5817 5816 -1.00375 -0.0183612 -0.015013 1 0 1 1 0 0 +EDGE2 5817 3116 -0.974186 0.00922352 -0.0263496 1 0 1 1 0 0 +EDGE2 5817 3136 -1.01427 -0.0311145 -0.0174249 1 0 1 1 0 0 +EDGE2 5817 3376 -0.984125 0.0836633 0.0115842 1 0 1 1 0 0 +EDGE2 5817 3096 -1.08728 0.0691576 0.0101285 1 0 1 1 0 0 +EDGE2 5817 1156 -1.03917 0.0305038 -0.0161342 1 0 1 1 0 0 +EDGE2 5817 1176 -0.916058 -0.0203951 0.00959251 1 0 1 1 0 0 +EDGE2 5818 1197 -1.03868 -0.0606241 0.0277994 1 0 1 1 0 0 +EDGE2 5818 3119 1.11426 0.01943 -0.00304226 1 0 1 1 0 0 +EDGE2 5818 3379 0.965556 0.000102848 -0.0020186 1 0 1 1 0 0 +EDGE2 5818 3479 0.998102 -0.00090473 0.0308008 1 0 1 1 0 0 +EDGE2 5818 3139 0.964029 -0.0400959 -0.0213827 1 0 1 1 0 0 +EDGE2 5818 1179 1.066 0.0228619 0.00292957 1 0 1 1 0 0 +EDGE2 5818 1199 1.0538 -0.0126937 0.0136032 1 0 1 1 0 0 +EDGE2 5818 3099 1.00244 0.0513659 0.0209278 1 0 1 1 0 0 +EDGE2 5818 1159 0.944532 -0.00785547 0.0248641 1 0 1 1 0 0 +EDGE2 5818 3098 0.0721242 0.00260759 0.0154619 1 0 1 1 0 0 +EDGE2 5818 3138 0.00499805 0.0198732 -0.0165124 1 0 1 1 0 0 +EDGE2 5818 3378 0.0071289 0.0196625 0.0104414 1 0 1 1 0 0 +EDGE2 5818 3478 0.0284383 -0.0240936 -0.00315581 1 0 1 1 0 0 +EDGE2 5818 3118 0.0101249 -0.0167527 -3.26957e-05 1 0 1 1 0 0 +EDGE2 5818 1178 0.0468721 0.0179926 -0.0145689 1 0 1 1 0 0 +EDGE2 5818 1198 -0.0488805 -8.43271e-06 -0.000784099 1 0 1 1 0 0 +EDGE2 5818 1158 -0.0243007 0.0551571 -0.0168255 1 0 1 1 0 0 +EDGE2 5818 3477 -1.02784 0.0243686 0.0128214 1 0 1 1 0 0 +EDGE2 5818 5817 -0.924601 -0.0478519 0.0215485 1 0 1 1 0 0 +EDGE2 5818 3117 -0.972546 -0.0162599 -0.0143618 1 0 1 1 0 0 +EDGE2 5818 3137 -1.03814 -0.00739619 -0.017669 1 0 1 1 0 0 +EDGE2 5818 3377 -0.941056 -0.0513089 -0.0305472 1 0 1 1 0 0 +EDGE2 5818 3097 -0.95214 0.0525486 0.0108036 1 0 1 1 0 0 +EDGE2 5818 1177 -1.00651 0.0172518 -0.00920563 1 0 1 1 0 0 +EDGE2 5818 1157 -0.976064 0.065867 0.0184348 1 0 1 1 0 0 +EDGE2 5819 1160 1.12102 -0.00989139 -0.023894 1 0 1 1 0 0 +EDGE2 5819 3140 0.996059 -0.0485046 -0.0103226 1 0 1 1 0 0 +EDGE2 5819 3420 1.0612 -0.107091 -3.14672 1 0 1 1 0 0 +EDGE2 5819 3440 1.13544 -0.0360972 -3.13355 1 0 1 1 0 0 +EDGE2 5819 3480 0.974184 0.0190593 0.0356669 1 0 1 1 0 0 +EDGE2 5819 3380 0.973772 -0.00590175 0.0094994 1 0 1 1 0 0 +EDGE2 5819 1200 0.934636 0.000205708 -0.0436082 1 0 1 1 0 0 +EDGE2 5819 3100 1.0545 -0.0568163 -0.00191968 1 0 1 1 0 0 +EDGE2 5819 3120 0.978317 -0.00707629 -0.0188291 1 0 1 1 0 0 +EDGE2 5819 1180 0.954161 -0.0182222 0.00151279 1 0 1 1 0 0 +EDGE2 5819 900 0.98773 0.0369139 -3.09597 1 0 1 1 0 0 +EDGE2 5819 840 0.98648 -0.0807375 -3.10141 1 0 1 1 0 0 +EDGE2 5819 860 1.0252 -0.0276506 -3.14658 1 0 1 1 0 0 +EDGE2 5819 3119 -0.0149729 -0.0148811 0.00673133 1 0 1 1 0 0 +EDGE2 5819 3379 -0.0642777 -0.019803 0.0268746 1 0 1 1 0 0 +EDGE2 5819 3479 -0.0112978 0.0264541 -0.0104435 1 0 1 1 0 0 +EDGE2 5819 3139 0.0233075 -0.0140606 -0.0144575 1 0 1 1 0 0 +EDGE2 5819 1179 -0.0334372 0.00744511 0.0200079 1 0 1 1 0 0 +EDGE2 5819 1199 -0.00187028 -0.0686668 0.00639822 1 0 1 1 0 0 +EDGE2 5819 3099 0.0177704 -0.0177338 0.00330049 1 0 1 1 0 0 +EDGE2 5819 1159 0.0631305 0.0064436 0.0225391 1 0 1 1 0 0 +EDGE2 5819 5818 -1.07876 -0.0201645 0.00579756 1 0 1 1 0 0 +EDGE2 5819 3098 -1.07897 0.0682034 -0.0179767 1 0 1 1 0 0 +EDGE2 5819 3138 -1.04413 0.0123697 -0.027958 1 0 1 1 0 0 +EDGE2 5819 3378 -0.983585 0.0310937 -0.0222397 1 0 1 1 0 0 +EDGE2 5819 3478 -0.937017 0.0574872 -0.0110924 1 0 1 1 0 0 +EDGE2 5819 3118 -0.986755 -0.0392908 0.0306678 1 0 1 1 0 0 +EDGE2 5819 1178 -0.986977 -0.0244698 -0.00955114 1 0 1 1 0 0 +EDGE2 5819 1198 -0.989546 -0.0244749 0.0168133 1 0 1 1 0 0 +EDGE2 5819 1158 -0.999517 -0.0427846 0.0108722 1 0 1 1 0 0 +EDGE2 5820 839 1.02682 0.0236568 -3.14599 1 0 1 1 0 0 +EDGE2 5820 899 1.05302 0.0029801 -3.14853 1 0 1 1 0 0 +EDGE2 5820 3419 1.01077 -0.0543036 -3.13491 1 0 1 1 0 0 +EDGE2 5820 3439 1.04205 -0.066682 -3.13889 1 0 1 1 0 0 +EDGE2 5820 859 1.04377 0.0198616 -3.12722 1 0 1 1 0 0 +EDGE2 5820 3441 0.0267161 -1.06329 -1.54904 1 0 1 1 0 0 +EDGE2 5820 841 0.0481135 -1.02396 -1.57539 1 0 1 1 0 0 +EDGE2 5820 901 -0.00317033 -1.055 -1.59554 1 0 1 1 0 0 +EDGE2 5820 1201 0.0205308 -0.979713 -1.55942 1 0 1 1 0 0 +EDGE2 5820 3421 -0.0280272 -0.99707 -1.57904 1 0 1 1 0 0 +EDGE2 5820 861 0.0341866 -0.934101 -1.5694 1 0 1 1 0 0 +EDGE2 5820 1160 -0.0683256 0.0538806 -0.00699938 1 0 1 1 0 0 +EDGE2 5820 3140 -0.0389546 0.00976501 0.00602078 1 0 1 1 0 0 +EDGE2 5820 3420 0.0565921 0.0567762 -3.14705 1 0 1 1 0 0 +EDGE2 5820 3440 0.10726 0.0176327 -3.1523 1 0 1 1 0 0 +EDGE2 5820 3480 -0.0728691 0.0555917 -0.0315427 1 0 1 1 0 0 +EDGE2 5820 3380 -0.00093224 0.00087704 0.0386238 1 0 1 1 0 0 +EDGE2 5820 1200 -0.0206004 0.0156338 -0.0100889 1 0 1 1 0 0 +EDGE2 5820 3100 -0.0513196 0.0607823 0.015647 1 0 1 1 0 0 +EDGE2 5820 3120 -0.0724028 0.0334182 -0.00109443 1 0 1 1 0 0 +EDGE2 5820 1180 0.0709643 0.00877407 0.0119054 1 0 1 1 0 0 +EDGE2 5820 900 -0.0730745 0.0466666 -3.15939 1 0 1 1 0 0 +EDGE2 5820 840 0.01591 -0.047308 -3.10924 1 0 1 1 0 0 +EDGE2 5820 860 -0.0267376 -0.0430422 -3.14554 1 0 1 1 0 0 +EDGE2 5820 3101 0.0970732 0.982277 1.58632 1 0 1 1 0 0 +EDGE2 5820 3141 0.0196911 1.01135 1.58827 1 0 1 1 0 0 +EDGE2 5820 3381 -0.0453147 0.963328 1.58751 1 0 1 1 0 0 +EDGE2 5820 3481 0.0341518 1.0066 1.61804 1 0 1 1 0 0 +EDGE2 5820 3121 -0.0379213 0.980462 1.58265 1 0 1 1 0 0 +EDGE2 5820 1161 -0.012 0.841189 1.55996 1 0 1 1 0 0 +EDGE2 5820 1181 0.021856 1.02908 1.59844 1 0 1 1 0 0 +EDGE2 5820 3119 -0.976047 0.0509836 -0.00408957 1 0 1 1 0 0 +EDGE2 5820 3379 -1.01925 0.0856444 0.0128712 1 0 1 1 0 0 +EDGE2 5820 3479 -0.963344 -0.109764 -0.00214295 1 0 1 1 0 0 +EDGE2 5820 5819 -1.08012 0.0078908 0.0147972 1 0 1 1 0 0 +EDGE2 5820 3139 -0.991002 0.0307059 -0.0113214 1 0 1 1 0 0 +EDGE2 5820 1179 -1.02078 0.0212503 -0.00471932 1 0 1 1 0 0 +EDGE2 5820 1199 -1.02216 0.059374 -0.00671941 1 0 1 1 0 0 +EDGE2 5820 3099 -0.967682 0.0343342 0.0174074 1 0 1 1 0 0 +EDGE2 5820 1159 -0.978206 -0.0119463 -0.0170898 1 0 1 1 0 0 +EDGE2 5821 5820 -0.957055 0.020811 -1.58994 1 0 1 1 0 0 +EDGE2 5821 1160 -1.02556 0.0282263 -1.57705 1 0 1 1 0 0 +EDGE2 5821 3140 -0.966221 0.0694155 -1.57795 1 0 1 1 0 0 +EDGE2 5821 3420 -1.06682 0.0323947 1.55814 1 0 1 1 0 0 +EDGE2 5821 3440 -0.936227 0.0470155 1.54788 1 0 1 1 0 0 +EDGE2 5821 3480 -1.02945 0.0785372 -1.59726 1 0 1 1 0 0 +EDGE2 5821 3380 -1.00961 0.00800607 -1.56254 1 0 1 1 0 0 +EDGE2 5821 1200 -0.986481 -0.0153826 -1.60006 1 0 1 1 0 0 +EDGE2 5821 3100 -0.951808 0.0642288 -1.61282 1 0 1 1 0 0 +EDGE2 5821 3120 -0.965794 0.0451049 -1.57671 1 0 1 1 0 0 +EDGE2 5821 1180 -1.02393 0.047169 -1.57832 1 0 1 1 0 0 +EDGE2 5821 900 -1.01843 0.0346772 1.55066 1 0 1 1 0 0 +EDGE2 5821 840 -1.0967 -0.0356889 1.57212 1 0 1 1 0 0 +EDGE2 5821 860 -0.987687 -0.0433006 1.58187 1 0 1 1 0 0 +EDGE2 5821 3482 0.998979 -0.029806 -0.0128825 1 0 1 1 0 0 +EDGE2 5821 3101 0.00565529 -1.58936e-05 -0.0221866 1 0 1 1 0 0 +EDGE2 5821 3141 -0.0186879 0.0133833 -0.0562523 1 0 1 1 0 0 +EDGE2 5821 3381 0.0504026 -0.0720605 0.00832163 1 0 1 1 0 0 +EDGE2 5821 3481 -0.0314127 0.0125133 0.00724429 1 0 1 1 0 0 +EDGE2 5821 3121 -0.0382853 -0.0454872 -0.00921854 1 0 1 1 0 0 +EDGE2 5821 1161 -0.0872425 0.016916 0.0288721 1 0 1 1 0 0 +EDGE2 5821 1181 -0.0655904 -0.0375772 0.0356872 1 0 1 1 0 0 +EDGE2 5821 1182 1.05442 0.1076 0.0252252 1 0 1 1 0 0 +EDGE2 5821 3122 1.05574 -0.100186 -0.0374581 1 0 1 1 0 0 +EDGE2 5821 3142 1.018 -0.0418106 -0.0016153 1 0 1 1 0 0 +EDGE2 5821 3382 0.94653 0.0339379 -0.0284284 1 0 1 1 0 0 +EDGE2 5821 3102 0.957703 0.0360933 -0.00978794 1 0 1 1 0 0 +EDGE2 5821 1162 0.943142 0.0646133 -0.0137074 1 0 1 1 0 0 +EDGE2 5822 5821 -1.01714 -0.0167505 0.00992057 1 0 1 1 0 0 +EDGE2 5822 3383 1.00017 0.009642 -0.00192079 1 0 1 1 0 0 +EDGE2 5822 3482 0.101572 0.0489891 0.00773003 1 0 1 1 0 0 +EDGE2 5822 3101 -1.0349 -0.06662 0.00315598 1 0 1 1 0 0 +EDGE2 5822 3141 -0.980183 0.040125 -0.0199285 1 0 1 1 0 0 +EDGE2 5822 3381 -0.981648 0.0547265 -0.00230297 1 0 1 1 0 0 +EDGE2 5822 3481 -1.0014 0.0048132 -0.0214248 1 0 1 1 0 0 +EDGE2 5822 3121 -1.03817 0.0271326 -0.0137688 1 0 1 1 0 0 +EDGE2 5822 1161 -1.08499 0.0303107 0.0270696 1 0 1 1 0 0 +EDGE2 5822 1181 -1.01084 0.0426795 0.0195062 1 0 1 1 0 0 +EDGE2 5822 1182 -0.10002 0.0502105 -0.0256355 1 0 1 1 0 0 +EDGE2 5822 3122 0.0674255 0.0294143 0.0174215 1 0 1 1 0 0 +EDGE2 5822 3142 0.000580044 -0.0346749 0.0229281 1 0 1 1 0 0 +EDGE2 5822 3382 0.000498628 0.0628789 0.00272841 1 0 1 1 0 0 +EDGE2 5822 3102 -0.0114886 -0.0700994 0.0115834 1 0 1 1 0 0 +EDGE2 5822 1162 -0.00372661 -0.0111028 -0.000325455 1 0 1 1 0 0 +EDGE2 5822 3483 0.951666 -0.0973918 0.00612236 1 0 1 1 0 0 +EDGE2 5822 1163 1.02021 0.0634972 0.0166228 1 0 1 1 0 0 +EDGE2 5822 3103 1.02626 -0.00706809 -0.00067035 1 0 1 1 0 0 +EDGE2 5822 3123 0.99889 -0.0131542 0.00184655 1 0 1 1 0 0 +EDGE2 5822 3143 0.934274 -0.0308456 -0.00746999 1 0 1 1 0 0 +EDGE2 5822 1183 0.963112 -0.00766764 0.0251876 1 0 1 1 0 0 +EDGE2 5823 3383 -0.0887054 0.0415112 0.0038914 1 0 1 1 0 0 +EDGE2 5823 3482 -0.975677 0.0344795 -0.0272447 1 0 1 1 0 0 +EDGE2 5823 5822 -1.07857 -0.0516464 -0.00149546 1 0 1 1 0 0 +EDGE2 5823 1182 -0.966241 0.0307547 0.0181737 1 0 1 1 0 0 +EDGE2 5823 3122 -1.08334 -0.00427007 -0.0114743 1 0 1 1 0 0 +EDGE2 5823 3142 -0.994154 -0.000795585 -0.0127647 1 0 1 1 0 0 +EDGE2 5823 3382 -1.07464 0.0233541 0.000896201 1 0 1 1 0 0 +EDGE2 5823 3102 -1.02601 0.00807345 -0.011148 1 0 1 1 0 0 +EDGE2 5823 1162 -1.04459 -0.143997 0.00596534 1 0 1 1 0 0 +EDGE2 5823 3483 0.020054 0.0407689 -0.0265881 1 0 1 1 0 0 +EDGE2 5823 3144 0.989641 0.0355192 0.0199085 1 0 1 1 0 0 +EDGE2 5823 1163 0.0866952 -0.00690823 0.00508778 1 0 1 1 0 0 +EDGE2 5823 3103 0.0129361 0.0566532 -0.00806395 1 0 1 1 0 0 +EDGE2 5823 3123 -0.0270795 0.0255924 0.00646866 1 0 1 1 0 0 +EDGE2 5823 3143 0.0254053 0.0715508 -0.0204193 1 0 1 1 0 0 +EDGE2 5823 1183 -0.0304692 0.0601918 -0.00819514 1 0 1 1 0 0 +EDGE2 5823 3484 1.07757 0.0170058 0.0086472 1 0 1 1 0 0 +EDGE2 5823 3384 0.96001 -0.0441552 -0.0121466 1 0 1 1 0 0 +EDGE2 5823 1184 0.954984 0.0526606 -0.0146245 1 0 1 1 0 0 +EDGE2 5823 3104 0.885091 -0.0555291 0.0270622 1 0 1 1 0 0 +EDGE2 5823 3124 0.939846 -0.0089881 -0.000627406 1 0 1 1 0 0 +EDGE2 5823 1164 0.949336 0.0233085 -0.00982021 1 0 1 1 0 0 +EDGE2 5824 3383 -1.09478 0.00744969 0.00851915 1 0 1 1 0 0 +EDGE2 5824 5823 -0.984461 -0.0255688 -0.00962754 1 0 1 1 0 0 +EDGE2 5824 3483 -1.00511 0.0501643 0.029798 1 0 1 1 0 0 +EDGE2 5824 3144 -0.0404402 -0.021387 -0.0246496 1 0 1 1 0 0 +EDGE2 5824 1163 -1.02878 -0.0316747 0.00630351 1 0 1 1 0 0 +EDGE2 5824 3103 -0.956998 -0.0193411 -0.000121027 1 0 1 1 0 0 +EDGE2 5824 3123 -0.9582 -0.0528399 -0.0239994 1 0 1 1 0 0 +EDGE2 5824 3143 -0.99825 0.0595232 0.0199789 1 0 1 1 0 0 +EDGE2 5824 1183 -0.924439 -0.0377183 0.0210855 1 0 1 1 0 0 +EDGE2 5824 3484 0.0186335 0.0359345 -0.00670479 1 0 1 1 0 0 +EDGE2 5824 3384 0.116241 -0.0736797 0.0222835 1 0 1 1 0 0 +EDGE2 5824 1184 -0.0297582 -0.0634168 -0.0147744 1 0 1 1 0 0 +EDGE2 5824 3104 -0.0202119 -0.0279709 -0.0176368 1 0 1 1 0 0 +EDGE2 5824 3124 -0.0119856 -0.0624875 -0.0327323 1 0 1 1 0 0 +EDGE2 5824 1164 -0.0214679 -0.064162 -0.0423062 1 0 1 1 0 0 +EDGE2 5824 3105 1.02208 0.106088 -0.00903641 1 0 1 1 0 0 +EDGE2 5824 3485 0.995443 0.037212 -0.0243798 1 0 1 1 0 0 +EDGE2 5824 3145 1.00011 0.0672746 0.0231977 1 0 1 1 0 0 +EDGE2 5824 3165 0.97304 0.00123174 -3.10982 1 0 1 1 0 0 +EDGE2 5824 3385 0.94204 -0.0152 -0.0122481 1 0 1 1 0 0 +EDGE2 5824 3125 0.984202 0.0601236 -0.0259737 1 0 1 1 0 0 +EDGE2 5824 1185 0.983218 0.0256898 -0.0268825 1 0 1 1 0 0 +EDGE2 5824 3065 1.02001 0.00895864 -3.13708 1 0 1 1 0 0 +EDGE2 5824 3085 0.986254 9.38321e-05 -3.17591 1 0 1 1 0 0 +EDGE2 5824 1165 0.9748 0.0174712 0.0223341 1 0 1 1 0 0 +EDGE2 5825 3146 0.0638143 -1.01746 -1.59355 1 0 1 1 0 0 +EDGE2 5825 3386 -0.0108161 -0.908039 -1.54832 1 0 1 1 0 0 +EDGE2 5825 3066 0.0568504 -1.03304 -1.60635 1 0 1 1 0 0 +EDGE2 5825 3144 -0.959066 -0.00233882 0.0113538 1 0 1 1 0 0 +EDGE2 5825 3484 -0.960561 -0.0243063 0.0633352 1 0 1 1 0 0 +EDGE2 5825 5824 -1.08454 0.0012006 -0.0027679 1 0 1 1 0 0 +EDGE2 5825 3384 -1.07147 0.0191785 -0.00947797 1 0 1 1 0 0 +EDGE2 5825 1184 -0.999574 0.0185047 0.0141575 1 0 1 1 0 0 +EDGE2 5825 3104 -0.97237 0.0759453 0.00236017 1 0 1 1 0 0 +EDGE2 5825 3124 -0.995851 -0.0106337 -0.0296724 1 0 1 1 0 0 +EDGE2 5825 1164 -0.940711 0.0171245 -0.0426385 1 0 1 1 0 0 +EDGE2 5825 3166 -0.0205702 0.994566 1.57872 1 0 1 1 0 0 +EDGE2 5825 3105 -0.0546165 0.0580748 0.00405718 1 0 1 1 0 0 +EDGE2 5825 3485 0.027749 -0.0627947 -0.0314625 1 0 1 1 0 0 +EDGE2 5825 3145 0.0328284 0.0568008 -0.00325802 1 0 1 1 0 0 +EDGE2 5825 3165 -0.0398889 0.169438 -3.15425 1 0 1 1 0 0 +EDGE2 5825 3385 0.0207171 0.0389734 -0.00876517 1 0 1 1 0 0 +EDGE2 5825 3125 -0.0442883 0.0235978 0.0165582 1 0 1 1 0 0 +EDGE2 5825 1185 -0.0164345 -0.0208576 0.00872122 1 0 1 1 0 0 +EDGE2 5825 3065 -0.0462855 -0.0149072 -3.14704 1 0 1 1 0 0 +EDGE2 5825 3085 -0.0563797 -0.0348444 -3.11766 1 0 1 1 0 0 +EDGE2 5825 1165 -0.0375866 0.00425228 0.00519124 1 0 1 1 0 0 +EDGE2 5825 3486 0.0224583 0.973656 1.55864 1 0 1 1 0 0 +EDGE2 5825 1166 0.0312689 1.00299 1.54732 1 0 1 1 0 0 +EDGE2 5825 3086 0.008572 0.973751 1.58651 1 0 1 1 0 0 +EDGE2 5825 3106 0.00181572 1.06074 1.56815 1 0 1 1 0 0 +EDGE2 5825 3126 0.118095 1.06077 1.59983 1 0 1 1 0 0 +EDGE2 5825 1186 -0.0397299 0.960395 1.60216 1 0 1 1 0 0 +EDGE2 5825 3064 1.13899 0.00865031 -3.15035 1 0 1 1 0 0 +EDGE2 5825 3164 1.04149 -0.0174262 -3.12258 1 0 1 1 0 0 +EDGE2 5825 3084 1.04309 0.0207143 -3.12096 1 0 1 1 0 0 +EDGE2 5826 3166 -0.0187821 -0.0509189 -0.0243249 1 0 1 1 0 0 +EDGE2 5826 3105 -0.997674 0.00171933 -1.57434 1 0 1 1 0 0 +EDGE2 5826 3485 -1.0184 0.0701786 -1.57922 1 0 1 1 0 0 +EDGE2 5826 5825 -0.965905 0.0105939 -1.59827 1 0 1 1 0 0 +EDGE2 5826 3145 -0.938156 0.0315366 -1.54106 1 0 1 1 0 0 +EDGE2 5826 3165 -0.905985 0.0243126 1.51615 1 0 1 1 0 0 +EDGE2 5826 3385 -0.935037 0.0380692 -1.5788 1 0 1 1 0 0 +EDGE2 5826 3125 -0.992678 -0.00252629 -1.55238 1 0 1 1 0 0 +EDGE2 5826 1185 -0.960233 -0.0081153 -1.56885 1 0 1 1 0 0 +EDGE2 5826 3065 -1.02021 0.0116995 1.56969 1 0 1 1 0 0 +EDGE2 5826 3085 -1.05648 -0.0211441 1.55413 1 0 1 1 0 0 +EDGE2 5826 1165 -0.969304 -0.0333599 -1.53891 1 0 1 1 0 0 +EDGE2 5826 3486 -0.000937639 -0.029505 0.0241872 1 0 1 1 0 0 +EDGE2 5826 1166 0.0254833 -0.0229351 -0.0115696 1 0 1 1 0 0 +EDGE2 5826 3086 0.0710262 -0.00965836 0.0341529 1 0 1 1 0 0 +EDGE2 5826 3106 0.0897915 0.0128303 0.00327493 1 0 1 1 0 0 +EDGE2 5826 3126 0.0697535 0.0788774 0.0351259 1 0 1 1 0 0 +EDGE2 5826 1186 -0.0590022 -0.168184 -0.00742529 1 0 1 1 0 0 +EDGE2 5826 3107 1.01253 -0.0323621 0.044545 1 0 1 1 0 0 +EDGE2 5826 3167 1.0021 0.0236387 -0.0138136 1 0 1 1 0 0 +EDGE2 5826 3487 0.901687 0.00708668 0.00384847 1 0 1 1 0 0 +EDGE2 5826 3127 1.06823 -0.0315085 0.00462184 1 0 1 1 0 0 +EDGE2 5826 1187 1.04291 -0.00224082 -0.0134448 1 0 1 1 0 0 +EDGE2 5826 3087 0.957317 0.0786947 0.0146964 1 0 1 1 0 0 +EDGE2 5826 1167 1.04906 0.0459195 -0.0209597 1 0 1 1 0 0 +EDGE2 5827 3166 -0.941067 0.0235158 -0.0380782 1 0 1 1 0 0 +EDGE2 5827 5826 -1.01848 0.00268157 -0.0334852 1 0 1 1 0 0 +EDGE2 5827 3486 -0.919376 0.035841 -0.00130357 1 0 1 1 0 0 +EDGE2 5827 1166 -0.933261 0.0370728 -0.0121744 1 0 1 1 0 0 +EDGE2 5827 3086 -1.05275 -0.00826867 -0.000761889 1 0 1 1 0 0 +EDGE2 5827 3106 -0.967475 0.112233 0.0208106 1 0 1 1 0 0 +EDGE2 5827 3126 -1.07138 -0.0255241 0.0188667 1 0 1 1 0 0 +EDGE2 5827 1186 -0.892961 0.0264318 -0.00599767 1 0 1 1 0 0 +EDGE2 5827 3107 -0.0396228 0.0233233 0.0224317 1 0 1 1 0 0 +EDGE2 5827 3167 -0.0415705 -0.0605916 -0.00776889 1 0 1 1 0 0 +EDGE2 5827 3487 -0.00327082 0.0369419 -0.0123608 1 0 1 1 0 0 +EDGE2 5827 3127 0.0248561 0.0139604 -0.0461288 1 0 1 1 0 0 +EDGE2 5827 1187 0.0405198 0.00255097 -0.00437987 1 0 1 1 0 0 +EDGE2 5827 3087 0.0123746 0.0747024 0.000777394 1 0 1 1 0 0 +EDGE2 5827 1167 -0.0505262 0.0943507 -0.00867129 1 0 1 1 0 0 +EDGE2 5827 3128 0.93761 -0.0341789 -0.0172866 1 0 1 1 0 0 +EDGE2 5827 3488 0.940899 0.0669007 0.0251683 1 0 1 1 0 0 +EDGE2 5827 3168 0.907961 0.0465239 -0.00241533 1 0 1 1 0 0 +EDGE2 5827 1188 1.02674 -0.0557427 -0.0268496 1 0 1 1 0 0 +EDGE2 5827 3088 1.07869 0.13719 -0.00415825 1 0 1 1 0 0 +EDGE2 5827 3108 1.07116 -0.0747988 -0.0100256 1 0 1 1 0 0 +EDGE2 5827 1168 1.09652 -0.00275676 -0.0225187 1 0 1 1 0 0 +EDGE2 5828 3107 -1.04712 0.0613281 -0.00694989 1 0 1 1 0 0 +EDGE2 5828 3167 -0.975431 -0.014432 0.0198916 1 0 1 1 0 0 +EDGE2 5828 3487 -0.998187 0.0594165 -0.0168531 1 0 1 1 0 0 +EDGE2 5828 5827 -1.02148 0.00690423 -0.053339 1 0 1 1 0 0 +EDGE2 5828 3127 -1.02082 0.0107675 0.00920305 1 0 1 1 0 0 +EDGE2 5828 1187 -1.02596 0.00169648 0.0290065 1 0 1 1 0 0 +EDGE2 5828 3087 -0.973579 -0.0686922 -0.00653748 1 0 1 1 0 0 +EDGE2 5828 1167 -1.00928 0.0143247 0.00960502 1 0 1 1 0 0 +EDGE2 5828 3128 0.0182431 0.0570733 0.0309625 1 0 1 1 0 0 +EDGE2 5828 3488 0.0451968 -0.0180292 -0.00942031 1 0 1 1 0 0 +EDGE2 5828 3168 0.0212902 0.0550192 0.0147384 1 0 1 1 0 0 +EDGE2 5828 1188 0.00262342 0.058765 -0.0140794 1 0 1 1 0 0 +EDGE2 5828 3088 -0.0238432 0.00348173 0.00122535 1 0 1 1 0 0 +EDGE2 5828 3108 -0.0243134 0.0140867 -0.0149432 1 0 1 1 0 0 +EDGE2 5828 1168 0.00348101 -0.0275953 -0.0205133 1 0 1 1 0 0 +EDGE2 5828 3109 0.942997 0.0062934 -0.00917292 1 0 1 1 0 0 +EDGE2 5828 3169 1.02427 0.0196285 -0.0133383 1 0 1 1 0 0 +EDGE2 5828 3489 1.04593 0.0861104 0.0150119 1 0 1 1 0 0 +EDGE2 5828 3129 0.980137 0.0414948 -0.00510059 1 0 1 1 0 0 +EDGE2 5828 1189 1.06144 0.0267936 0.033979 1 0 1 1 0 0 +EDGE2 5828 3089 1.03718 0.101436 -0.0215516 1 0 1 1 0 0 +EDGE2 5828 1169 1.03094 -0.0142616 0.000833881 1 0 1 1 0 0 +EDGE2 5829 3128 -0.917403 -0.115134 0.00431293 1 0 1 1 0 0 +EDGE2 5829 3488 -1.01577 0.0468098 -0.0172278 1 0 1 1 0 0 +EDGE2 5829 5828 -1.00816 0.0581819 0.00811929 1 0 1 1 0 0 +EDGE2 5829 3168 -0.940761 0.00302733 -0.00197157 1 0 1 1 0 0 +EDGE2 5829 1188 -1.04314 0.0764145 -0.00913358 1 0 1 1 0 0 +EDGE2 5829 3088 -1.03099 0.00494391 -0.0166291 1 0 1 1 0 0 +EDGE2 5829 3108 -0.959929 0.0462144 -0.0277123 1 0 1 1 0 0 +EDGE2 5829 1168 -1.04757 -0.0340484 0.0197866 1 0 1 1 0 0 +EDGE2 5829 3109 -0.0388473 -0.0129505 0.00749002 1 0 1 1 0 0 +EDGE2 5829 3169 0.0479954 -0.0449114 0.0317955 1 0 1 1 0 0 +EDGE2 5829 3489 0.0144649 -0.0333447 0.0017074 1 0 1 1 0 0 +EDGE2 5829 3129 0.0123771 0.0241899 -0.00792688 1 0 1 1 0 0 +EDGE2 5829 1189 -0.0714139 0.0173675 0.00279654 1 0 1 1 0 0 +EDGE2 5829 3089 -0.0387517 0.0340261 0.0117532 1 0 1 1 0 0 +EDGE2 5829 1169 -0.0456773 -0.0547456 -0.0300465 1 0 1 1 0 0 +EDGE2 5829 3050 1.01759 -0.0137558 -3.14933 1 0 1 1 0 0 +EDGE2 5829 3170 0.925036 0.00871979 0.0321846 1 0 1 1 0 0 +EDGE2 5829 5790 0.995839 -0.0208781 -3.10856 1 0 1 1 0 0 +EDGE2 5829 5810 0.923728 -0.0580061 -3.12833 1 0 1 1 0 0 +EDGE2 5829 3490 0.986165 -0.0202643 -0.0110443 1 0 1 1 0 0 +EDGE2 5829 3110 1.02109 0.0495772 0.0101195 1 0 1 1 0 0 +EDGE2 5829 3130 0.955508 -0.0304996 -0.00501243 1 0 1 1 0 0 +EDGE2 5829 3090 1.06738 0.0791013 0.00623838 1 0 1 1 0 0 +EDGE2 5829 1130 0.945767 -0.023023 -3.13961 1 0 1 1 0 0 +EDGE2 5829 1170 1.02669 0.0223907 -0.00703587 1 0 1 1 0 0 +EDGE2 5829 1190 1.06001 0.0125864 -0.0453762 1 0 1 1 0 0 +EDGE2 5829 3030 1.00559 -0.0210227 -3.09888 1 0 1 1 0 0 +EDGE2 5829 1150 1.0862 0.0232838 -3.13747 1 0 1 1 0 0 +EDGE2 5829 1110 1.05706 -0.0563812 -3.1372 1 0 1 1 0 0 +EDGE2 5830 3109 -0.993342 -0.0617275 -0.000504946 1 0 1 1 0 0 +EDGE2 5830 3169 -1.06991 -0.0268109 0.0253286 1 0 1 1 0 0 +EDGE2 5830 3489 -1.06157 0.0971179 0.000953215 1 0 1 1 0 0 +EDGE2 5830 5829 -1.08647 0.0237439 -0.0232411 1 0 1 1 0 0 +EDGE2 5830 3129 -1.0722 -0.0391729 -0.00163242 1 0 1 1 0 0 +EDGE2 5830 1189 -1.05934 0.0562514 -0.0135008 1 0 1 1 0 0 +EDGE2 5830 3089 -0.954282 -0.086311 0.00681432 1 0 1 1 0 0 +EDGE2 5830 1169 -0.951255 -0.014258 0.0306581 1 0 1 1 0 0 +EDGE2 5830 3050 -0.0750397 -0.0216022 -3.15986 1 0 1 1 0 0 +EDGE2 5830 3131 -0.0566528 1.05648 1.56253 1 0 1 1 0 0 +EDGE2 5830 3491 -0.105522 1.03838 1.54988 1 0 1 1 0 0 +EDGE2 5830 5811 -0.0160463 1.03826 1.57869 1 0 1 1 0 0 +EDGE2 5830 3171 -0.0711013 1.04149 1.58261 1 0 1 1 0 0 +EDGE2 5830 1151 0.067688 0.962721 1.54633 1 0 1 1 0 0 +EDGE2 5830 1191 0.0527006 0.929317 1.58151 1 0 1 1 0 0 +EDGE2 5830 3091 -0.032434 0.9579 1.5959 1 0 1 1 0 0 +EDGE2 5830 3111 0.0233891 0.93653 1.54935 1 0 1 1 0 0 +EDGE2 5830 1171 0.0769558 0.977988 1.55508 1 0 1 1 0 0 +EDGE2 5830 3170 -0.0760236 -0.0689977 0.0140194 1 0 1 1 0 0 +EDGE2 5830 5790 0.0801987 -0.0104884 -3.13898 1 0 1 1 0 0 +EDGE2 5830 5810 -0.0816235 -0.0335954 -3.13354 1 0 1 1 0 0 +EDGE2 5830 3490 -0.0218736 -0.0174951 0.0271291 1 0 1 1 0 0 +EDGE2 5830 3110 0.0305959 0.00947182 -0.0140634 1 0 1 1 0 0 +EDGE2 5830 3130 -0.0487736 -0.124961 -0.00114854 1 0 1 1 0 0 +EDGE2 5830 3090 -0.0251415 -0.00417359 -0.0122191 1 0 1 1 0 0 +EDGE2 5830 5789 0.992109 -0.0450471 -3.10807 1 0 1 1 0 0 +EDGE2 5830 1130 -0.0417744 -0.0882674 -3.13335 1 0 1 1 0 0 +EDGE2 5830 1170 0.0695116 -0.0373555 -0.012516 1 0 1 1 0 0 +EDGE2 5830 1190 -0.00907533 -0.101445 0.00398893 1 0 1 1 0 0 +EDGE2 5830 3030 0.00773219 -0.00222858 -3.12424 1 0 1 1 0 0 +EDGE2 5830 1150 -0.0722599 0.073289 -3.1261 1 0 1 1 0 0 +EDGE2 5830 1110 -0.0489218 0.008192 -3.14799 1 0 1 1 0 0 +EDGE2 5830 5809 1.02171 -0.115774 -3.16126 1 0 1 1 0 0 +EDGE2 5830 1109 1.1523 0.055124 -3.15682 1 0 1 1 0 0 +EDGE2 5830 1149 0.909115 -0.0866419 -3.16386 1 0 1 1 0 0 +EDGE2 5830 3029 0.951417 0.0229122 -3.09972 1 0 1 1 0 0 +EDGE2 5830 3049 1.01098 -0.0128428 -3.12166 1 0 1 1 0 0 +EDGE2 5830 1129 0.904053 0.0206574 -3.09254 1 0 1 1 0 0 +EDGE2 5830 1111 -0.0100182 -1.00976 -1.57463 1 0 1 1 0 0 +EDGE2 5830 3031 0.0271071 -0.955185 -1.55495 1 0 1 1 0 0 +EDGE2 5830 3051 0.0151736 -1.0172 -1.53101 1 0 1 1 0 0 +EDGE2 5830 5791 0.0700941 -1.02887 -1.52827 1 0 1 1 0 0 +EDGE2 5830 1131 -0.00756333 -0.98493 -1.56092 1 0 1 1 0 0 +EDGE2 5831 3050 -1.0152 0.0241698 1.55889 1 0 1 1 0 0 +EDGE2 5831 3131 -0.0393713 0.0154893 -0.00303952 1 0 1 1 0 0 +EDGE2 5831 3092 1.01595 0.00322029 0.0271306 1 0 1 1 0 0 +EDGE2 5831 5812 1.01541 0.0609014 -0.0128266 1 0 1 1 0 0 +EDGE2 5831 3132 0.961032 -0.0544032 0.0292984 1 0 1 1 0 0 +EDGE2 5831 3172 1.04095 0.0413051 -0.012434 1 0 1 1 0 0 +EDGE2 5831 3492 1.03471 0.0281965 -0.0180654 1 0 1 1 0 0 +EDGE2 5831 3112 1.00999 0.0161998 -0.0339724 1 0 1 1 0 0 +EDGE2 5831 1152 1.08827 0.0985009 0.0365629 1 0 1 1 0 0 +EDGE2 5831 1172 1.00209 -0.0353299 0.0438177 1 0 1 1 0 0 +EDGE2 5831 1192 1.01444 0.0216285 0.0184671 1 0 1 1 0 0 +EDGE2 5831 3491 0.0695792 -0.090199 -0.00737172 1 0 1 1 0 0 +EDGE2 5831 5811 0.0809512 -0.109722 -0.0135604 1 0 1 1 0 0 +EDGE2 5831 3171 -0.00212894 0.00302695 0.0157908 1 0 1 1 0 0 +EDGE2 5831 1151 -0.00342258 0.0104069 -0.00298216 1 0 1 1 0 0 +EDGE2 5831 1191 0.0470051 0.00827888 0.0367361 1 0 1 1 0 0 +EDGE2 5831 3091 -0.0759792 0.0149708 0.0244856 1 0 1 1 0 0 +EDGE2 5831 3111 0.0313252 0.0632387 0.00372176 1 0 1 1 0 0 +EDGE2 5831 1171 0.00637641 -0.0676529 -0.00200857 1 0 1 1 0 0 +EDGE2 5831 3170 -0.933418 0.0808546 -1.57774 1 0 1 1 0 0 +EDGE2 5831 5790 -0.965262 -0.0859912 1.55278 1 0 1 1 0 0 +EDGE2 5831 5810 -0.972591 -0.0906598 1.54821 1 0 1 1 0 0 +EDGE2 5831 5830 -0.978612 -0.0106355 -1.60169 1 0 1 1 0 0 +EDGE2 5831 3490 -0.979887 0.00587514 -1.54555 1 0 1 1 0 0 +EDGE2 5831 3110 -0.946779 0.0164851 -1.56614 1 0 1 1 0 0 +EDGE2 5831 3130 -0.928566 0.00961966 -1.5652 1 0 1 1 0 0 +EDGE2 5831 3090 -1.04247 -0.0345194 -1.54249 1 0 1 1 0 0 +EDGE2 5831 1130 -1.05273 0.0778359 1.58799 1 0 1 1 0 0 +EDGE2 5831 1170 -0.996893 -0.0671391 -1.55195 1 0 1 1 0 0 +EDGE2 5831 1190 -0.928643 -0.029989 -1.57355 1 0 1 1 0 0 +EDGE2 5831 3030 -0.996854 0.0108702 1.56604 1 0 1 1 0 0 +EDGE2 5831 1150 -0.943735 0.022433 1.56373 1 0 1 1 0 0 +EDGE2 5831 1110 -1.00623 -0.0440341 1.56077 1 0 1 1 0 0 +EDGE2 5832 1173 1.03391 -0.0149476 0.00157379 1 0 1 1 0 0 +EDGE2 5832 3133 1.01341 0.0675325 -0.0127162 1 0 1 1 0 0 +EDGE2 5832 3493 1.07939 -0.0737158 -0.0430222 1 0 1 1 0 0 +EDGE2 5832 5813 1.0534 0.00877466 0.00910921 1 0 1 1 0 0 +EDGE2 5832 3173 0.971413 -0.0193239 -0.0159623 1 0 1 1 0 0 +EDGE2 5832 3093 0.990784 -0.00951789 0.0138481 1 0 1 1 0 0 +EDGE2 5832 3113 1.02044 0.000325583 0.0229537 1 0 1 1 0 0 +EDGE2 5832 1193 0.998604 -0.0275426 0.0479163 1 0 1 1 0 0 +EDGE2 5832 3131 -0.983787 0.0679282 -0.0077801 1 0 1 1 0 0 +EDGE2 5832 3092 -0.0379402 -0.0672531 0.0281459 1 0 1 1 0 0 +EDGE2 5832 5812 -0.00739206 -0.0161493 0.0365994 1 0 1 1 0 0 +EDGE2 5832 1153 1.03242 0.0866366 0.00441536 1 0 1 1 0 0 +EDGE2 5832 3132 0.0469894 -0.0175676 -0.019266 1 0 1 1 0 0 +EDGE2 5832 3172 -0.036074 -0.0697112 -0.0145327 1 0 1 1 0 0 +EDGE2 5832 3492 -0.0416834 0.0664303 -0.0387618 1 0 1 1 0 0 +EDGE2 5832 3112 0.0835929 -0.0269207 0.00462826 1 0 1 1 0 0 +EDGE2 5832 1152 0.0113659 0.0430896 0.0166521 1 0 1 1 0 0 +EDGE2 5832 1172 -0.00821011 0.0260688 -0.0126241 1 0 1 1 0 0 +EDGE2 5832 1192 -0.0475196 0.0582745 -0.0234974 1 0 1 1 0 0 +EDGE2 5832 3491 -1.00707 -0.0140342 -0.00882183 1 0 1 1 0 0 +EDGE2 5832 5811 -0.963039 -0.043265 -0.0162256 1 0 1 1 0 0 +EDGE2 5832 5831 -1.01894 -0.0670704 0.0114072 1 0 1 1 0 0 +EDGE2 5832 3171 -0.914219 0.0227543 -0.00805264 1 0 1 1 0 0 +EDGE2 5832 1151 -1.04398 0.055523 -0.0181533 1 0 1 1 0 0 +EDGE2 5832 1191 -0.963386 0.0139316 -0.0258304 1 0 1 1 0 0 +EDGE2 5832 3091 -1.00583 0.0329617 -0.00534041 1 0 1 1 0 0 +EDGE2 5832 3111 -0.942233 0.0367778 -0.0328463 1 0 1 1 0 0 +EDGE2 5832 1171 -0.993776 -0.0546726 -0.00187313 1 0 1 1 0 0 +EDGE2 5833 1173 -0.00516297 -0.0409377 0.0269697 1 0 1 1 0 0 +EDGE2 5833 1174 0.993118 -0.0432737 0.0115075 1 0 1 1 0 0 +EDGE2 5833 3174 0.962821 0.0131652 -0.0157068 1 0 1 1 0 0 +EDGE2 5833 5814 0.943873 -0.10312 -0.0454084 1 0 1 1 0 0 +EDGE2 5833 3494 1.01851 -0.00392269 0.00154316 1 0 1 1 0 0 +EDGE2 5833 3094 1.06067 -0.030192 0.0360081 1 0 1 1 0 0 +EDGE2 5833 3114 0.922108 -0.0676365 0.00137167 1 0 1 1 0 0 +EDGE2 5833 3134 1.0122 -0.00791027 -0.00393834 1 0 1 1 0 0 +EDGE2 5833 1194 1.0953 0.0653433 0.00831504 1 0 1 1 0 0 +EDGE2 5833 1154 1.01951 0.0607063 -0.000209036 1 0 1 1 0 0 +EDGE2 5833 3133 -0.0608758 -0.0522791 0.000472637 1 0 1 1 0 0 +EDGE2 5833 3493 0.0632979 -0.0159946 0.00437301 1 0 1 1 0 0 +EDGE2 5833 5813 -0.0927241 -0.0112645 -6.89701e-05 1 0 1 1 0 0 +EDGE2 5833 3173 -0.0333699 0.0420925 -0.00930933 1 0 1 1 0 0 +EDGE2 5833 3093 0.00826986 0.0427905 -0.0126712 1 0 1 1 0 0 +EDGE2 5833 3113 0.0537567 0.0794896 0.00406807 1 0 1 1 0 0 +EDGE2 5833 1193 0.0742357 0.0364821 -0.0141658 1 0 1 1 0 0 +EDGE2 5833 3092 -0.951486 0.0455603 0.00225083 1 0 1 1 0 0 +EDGE2 5833 5812 -1.0221 0.0390132 0.0233116 1 0 1 1 0 0 +EDGE2 5833 1153 -0.0738534 -0.0508277 0.0181094 1 0 1 1 0 0 +EDGE2 5833 5832 -0.990847 0.0387551 0.0312981 1 0 1 1 0 0 +EDGE2 5833 3132 -1.07498 -0.0268174 0.0152595 1 0 1 1 0 0 +EDGE2 5833 3172 -0.970953 -0.0971614 0.0475116 1 0 1 1 0 0 +EDGE2 5833 3492 -0.957613 -0.0260221 0.00280712 1 0 1 1 0 0 +EDGE2 5833 3112 -1.0096 -0.00815101 -0.0178324 1 0 1 1 0 0 +EDGE2 5833 1152 -1.03402 0.0685112 -0.00239808 1 0 1 1 0 0 +EDGE2 5833 1172 -1.00718 -0.00517902 0.0228289 1 0 1 1 0 0 +EDGE2 5833 1192 -1.07307 -0.0407922 -0.00346571 1 0 1 1 0 0 +EDGE2 5834 3495 0.999867 -0.0460891 -0.00763946 1 0 1 1 0 0 +EDGE2 5834 5815 0.950069 0.127927 0.0326778 1 0 1 1 0 0 +EDGE2 5834 1173 -1.02955 -0.0110635 -0.0336967 1 0 1 1 0 0 +EDGE2 5834 1174 0.00874654 -0.00180553 0.0102897 1 0 1 1 0 0 +EDGE2 5834 3115 1.00011 0.0156236 -0.0014748 1 0 1 1 0 0 +EDGE2 5834 3175 0.987301 -0.0486492 -0.00570797 1 0 1 1 0 0 +EDGE2 5834 3375 1.02833 0.0450977 -3.14328 1 0 1 1 0 0 +EDGE2 5834 3475 1.03516 -0.101417 -3.15568 1 0 1 1 0 0 +EDGE2 5834 3135 1.00904 -0.0748833 0.00103141 1 0 1 1 0 0 +EDGE2 5834 1175 1.0218 -0.0654981 -0.00364735 1 0 1 1 0 0 +EDGE2 5834 1195 1.00887 0.0402392 -0.023768 1 0 1 1 0 0 +EDGE2 5834 3095 0.956931 -0.0336504 0.00791851 1 0 1 1 0 0 +EDGE2 5834 1155 0.967724 0.0158831 0.0148405 1 0 1 1 0 0 +EDGE2 5834 3174 0.00796076 0.0834186 0.00958499 1 0 1 1 0 0 +EDGE2 5834 5814 -0.050067 0.00927829 0.017981 1 0 1 1 0 0 +EDGE2 5834 3494 0.00613159 -0.0942475 -0.000468056 1 0 1 1 0 0 +EDGE2 5834 3094 -0.032224 0.0429827 0.021991 1 0 1 1 0 0 +EDGE2 5834 3114 -0.0789845 -0.00589727 0.0156525 1 0 1 1 0 0 +EDGE2 5834 3134 0.0619449 0.0251783 -0.00407141 1 0 1 1 0 0 +EDGE2 5834 1194 -0.111524 -0.0105524 -0.00565318 1 0 1 1 0 0 +EDGE2 5834 1154 -0.0495179 -0.0840059 -0.012448 1 0 1 1 0 0 +EDGE2 5834 3133 -0.952578 -0.024919 0.0190132 1 0 1 1 0 0 +EDGE2 5834 3493 -1.0183 0.0168361 -0.0133722 1 0 1 1 0 0 +EDGE2 5834 5813 -0.921699 0.0363926 -0.000548368 1 0 1 1 0 0 +EDGE2 5834 5833 -0.980362 -0.10485 0.00415972 1 0 1 1 0 0 +EDGE2 5834 3173 -0.956345 -0.033494 -0.0032555 1 0 1 1 0 0 +EDGE2 5834 3093 -1.0097 0.0215435 0.00412133 1 0 1 1 0 0 +EDGE2 5834 3113 -1.00326 -0.0177135 0.0131835 1 0 1 1 0 0 +EDGE2 5834 1193 -0.948394 0.0167744 -0.0164811 1 0 1 1 0 0 +EDGE2 5834 1153 -0.994876 -0.013331 -0.00872757 1 0 1 1 0 0 +EDGE2 5835 3495 -0.0962274 0.0830559 -0.000860276 1 0 1 1 0 0 +EDGE2 5835 3474 0.920668 0.00956734 -3.14086 1 0 1 1 0 0 +EDGE2 5835 3374 0.964467 -0.0546238 -3.18473 1 0 1 1 0 0 +EDGE2 5835 1196 -0.0487933 0.988427 1.57764 1 0 1 1 0 0 +EDGE2 5835 3476 0.00755273 1.09612 1.56104 1 0 1 1 0 0 +EDGE2 5835 5816 -0.0554044 0.996026 1.54909 1 0 1 1 0 0 +EDGE2 5835 3116 0.0623 1.05551 1.53484 1 0 1 1 0 0 +EDGE2 5835 3136 -0.0248098 1.05162 1.57499 1 0 1 1 0 0 +EDGE2 5835 3376 0.101952 1.01177 1.55025 1 0 1 1 0 0 +EDGE2 5835 3096 -0.063352 0.964793 1.57137 1 0 1 1 0 0 +EDGE2 5835 1156 0.0032392 1.09504 1.56273 1 0 1 1 0 0 +EDGE2 5835 1176 -0.0180416 1.07374 1.57541 1 0 1 1 0 0 +EDGE2 5835 5815 -0.0131278 -0.0267666 -0.0145429 1 0 1 1 0 0 +EDGE2 5835 1174 -1.04602 0.0479665 -0.0113136 1 0 1 1 0 0 +EDGE2 5835 3115 0.0694322 -0.00470682 0.0066071 1 0 1 1 0 0 +EDGE2 5835 3175 -0.050956 0.0189308 -0.0375428 1 0 1 1 0 0 +EDGE2 5835 3375 0.0385477 0.0405124 -3.14252 1 0 1 1 0 0 +EDGE2 5835 3475 -0.0105384 0.0188508 -3.168 1 0 1 1 0 0 +EDGE2 5835 3135 -0.101099 0.0894794 0.0130588 1 0 1 1 0 0 +EDGE2 5835 1175 0.00073659 0.0586132 -0.0425767 1 0 1 1 0 0 +EDGE2 5835 1195 -0.0110984 -0.0256897 -0.00439732 1 0 1 1 0 0 +EDGE2 5835 3095 0.0951905 0.0137378 -0.0137175 1 0 1 1 0 0 +EDGE2 5835 1155 -0.0345782 -0.0862056 -0.0320884 1 0 1 1 0 0 +EDGE2 5835 3174 -0.951382 -0.0594066 0.0260088 1 0 1 1 0 0 +EDGE2 5835 5814 -1.021 0.0784033 -0.0142656 1 0 1 1 0 0 +EDGE2 5835 5834 -0.96642 0.0423398 -0.0241624 1 0 1 1 0 0 +EDGE2 5835 3494 -0.915323 -0.0385439 0.00147904 1 0 1 1 0 0 +EDGE2 5835 3094 -0.99021 -0.00349457 0.0116425 1 0 1 1 0 0 +EDGE2 5835 3114 -0.977562 0.0582515 0.0338268 1 0 1 1 0 0 +EDGE2 5835 3134 -1.07795 0.0583212 -0.0207429 1 0 1 1 0 0 +EDGE2 5835 1194 -1.04021 -0.0616755 -0.0227155 1 0 1 1 0 0 +EDGE2 5835 1154 -1.04249 -0.0169374 0.0225446 1 0 1 1 0 0 +EDGE2 5835 3176 0.0575371 -0.993296 -1.54174 1 0 1 1 0 0 +EDGE2 5835 3496 -0.0364754 -1.11068 -1.56364 1 0 1 1 0 0 +EDGE2 5836 3495 -0.990408 0.00766455 -1.5747 1 0 1 1 0 0 +EDGE2 5836 1197 1.05018 -0.040897 -0.00468351 1 0 1 1 0 0 +EDGE2 5836 3477 1.03021 -0.0269716 -0.0360846 1 0 1 1 0 0 +EDGE2 5836 5817 1.01406 -0.032596 0.00821976 1 0 1 1 0 0 +EDGE2 5836 3117 1.04724 0.0346442 -0.00576492 1 0 1 1 0 0 +EDGE2 5836 3137 1.02556 0.0594945 -0.0030695 1 0 1 1 0 0 +EDGE2 5836 3377 1.04424 0.0532624 -0.0152996 1 0 1 1 0 0 +EDGE2 5836 3097 0.938501 0.00878543 -0.00813397 1 0 1 1 0 0 +EDGE2 5836 1177 1.09123 0.0726669 0.00192555 1 0 1 1 0 0 +EDGE2 5836 1157 0.985771 0.00610308 0.0299611 1 0 1 1 0 0 +EDGE2 5836 1196 0.0294507 -0.0264418 0.00422834 1 0 1 1 0 0 +EDGE2 5836 3476 0.00593198 0.0617477 0.00962947 1 0 1 1 0 0 +EDGE2 5836 5816 0.0122923 0.0473303 -0.0218031 1 0 1 1 0 0 +EDGE2 5836 3116 -0.0941082 0.0158498 0.0103073 1 0 1 1 0 0 +EDGE2 5836 3136 -0.0168237 0.031151 -0.0226347 1 0 1 1 0 0 +EDGE2 5836 3376 -0.0175357 -0.0115346 -0.00578093 1 0 1 1 0 0 +EDGE2 5836 3096 -0.124673 -0.00252489 -0.0239676 1 0 1 1 0 0 +EDGE2 5836 1156 -0.0251265 -0.0210597 -0.0517897 1 0 1 1 0 0 +EDGE2 5836 1176 -0.0094769 0.0593575 0.00743293 1 0 1 1 0 0 +EDGE2 5836 5835 -0.958986 -0.0782218 -1.59748 1 0 1 1 0 0 +EDGE2 5836 5815 -0.988512 0.0590059 -1.58142 1 0 1 1 0 0 +EDGE2 5836 3115 -0.982227 0.030567 -1.57479 1 0 1 1 0 0 +EDGE2 5836 3175 -0.987152 -0.016523 -1.56069 1 0 1 1 0 0 +EDGE2 5836 3375 -1.02524 0.0690072 1.53966 1 0 1 1 0 0 +EDGE2 5836 3475 -0.947317 -0.0564536 1.56862 1 0 1 1 0 0 +EDGE2 5836 3135 -0.974751 0.00273845 -1.52064 1 0 1 1 0 0 +EDGE2 5836 1175 -1.05796 -0.0522944 -1.56827 1 0 1 1 0 0 +EDGE2 5836 1195 -1.04217 -0.0563574 -1.58134 1 0 1 1 0 0 +EDGE2 5836 3095 -1.00046 0.00592968 -1.55039 1 0 1 1 0 0 +EDGE2 5836 1155 -0.995209 -0.0205192 -1.56902 1 0 1 1 0 0 +EDGE2 5837 1197 -0.0366238 0.0651298 -0.0128598 1 0 1 1 0 0 +EDGE2 5837 5818 0.962877 -0.0660324 0.00979427 1 0 1 1 0 0 +EDGE2 5837 3098 1.07063 0.00719258 -0.00235907 1 0 1 1 0 0 +EDGE2 5837 3138 0.942941 0.00894118 0.00849347 1 0 1 1 0 0 +EDGE2 5837 3378 0.977111 0.0349255 0.00576044 1 0 1 1 0 0 +EDGE2 5837 3478 1.08746 -0.0154055 -0.0100669 1 0 1 1 0 0 +EDGE2 5837 3118 0.90654 -0.0308782 -0.0281204 1 0 1 1 0 0 +EDGE2 5837 1178 1.02055 0.0109427 -0.00179828 1 0 1 1 0 0 +EDGE2 5837 1198 1.00409 0.085357 -0.012764 1 0 1 1 0 0 +EDGE2 5837 1158 0.909566 0.0501676 0.016012 1 0 1 1 0 0 +EDGE2 5837 3477 -0.0124515 0.0127165 0.00785173 1 0 1 1 0 0 +EDGE2 5837 5817 0.037171 0.0571637 -0.0320769 1 0 1 1 0 0 +EDGE2 5837 3117 -0.114892 -0.0665254 0.0196462 1 0 1 1 0 0 +EDGE2 5837 3137 0.0956646 -0.149981 -0.000329709 1 0 1 1 0 0 +EDGE2 5837 3377 0.0238703 -0.038256 -0.0210565 1 0 1 1 0 0 +EDGE2 5837 3097 -0.0270405 0.0286075 -0.026319 1 0 1 1 0 0 +EDGE2 5837 1177 -0.0544248 -0.11279 0.0263407 1 0 1 1 0 0 +EDGE2 5837 1157 -0.0462131 -0.0198755 0.00577034 1 0 1 1 0 0 +EDGE2 5837 1196 -0.986726 -0.0138495 0.0228256 1 0 1 1 0 0 +EDGE2 5837 3476 -0.995181 -0.0616314 0.0349104 1 0 1 1 0 0 +EDGE2 5837 5836 -1.02008 0.00904543 0.0230179 1 0 1 1 0 0 +EDGE2 5837 5816 -1.0007 0.0134979 -0.0117669 1 0 1 1 0 0 +EDGE2 5837 3116 -0.924895 -0.0671696 -0.0208853 1 0 1 1 0 0 +EDGE2 5837 3136 -0.939487 -0.0596039 0.00491761 1 0 1 1 0 0 +EDGE2 5837 3376 -1.06024 0.0348135 -0.00323544 1 0 1 1 0 0 +EDGE2 5837 3096 -0.951979 -0.0775429 -0.017306 1 0 1 1 0 0 +EDGE2 5837 1156 -0.92737 0.00810975 0.0121796 1 0 1 1 0 0 +EDGE2 5837 1176 -0.961565 -0.0662728 0.00205295 1 0 1 1 0 0 +EDGE2 5838 1197 -1.11237 0.0320801 -0.00826218 1 0 1 1 0 0 +EDGE2 5838 3119 1.06753 -0.00720885 0.0170858 1 0 1 1 0 0 +EDGE2 5838 3379 0.99576 0.0448079 0.00916991 1 0 1 1 0 0 +EDGE2 5838 3479 0.963733 0.0391005 -0.028866 1 0 1 1 0 0 +EDGE2 5838 5819 0.99652 -0.0897214 -0.00685478 1 0 1 1 0 0 +EDGE2 5838 3139 0.985658 -0.0509804 -0.00092935 1 0 1 1 0 0 +EDGE2 5838 1179 0.941573 0.048773 3.3124e-05 1 0 1 1 0 0 +EDGE2 5838 1199 1.01942 -6.47611e-05 -0.0228037 1 0 1 1 0 0 +EDGE2 5838 3099 1.07369 -0.00735573 -0.0287521 1 0 1 1 0 0 +EDGE2 5838 1159 1.0686 -0.0725647 -0.0223093 1 0 1 1 0 0 +EDGE2 5838 5818 0.01883 0.00831573 0.0160282 1 0 1 1 0 0 +EDGE2 5838 3098 0.0432192 0.0415582 0.00709586 1 0 1 1 0 0 +EDGE2 5838 3138 0.037252 0.0809651 -0.0189217 1 0 1 1 0 0 +EDGE2 5838 3378 -0.0354808 0.0615708 0.00413033 1 0 1 1 0 0 +EDGE2 5838 3478 0.00176575 0.0599448 -0.0405451 1 0 1 1 0 0 +EDGE2 5838 3118 -0.0182902 0.032641 0.000632855 1 0 1 1 0 0 +EDGE2 5838 1178 0.0347201 -0.0935505 -0.0120119 1 0 1 1 0 0 +EDGE2 5838 1198 -0.00438477 -0.0198183 -0.00336568 1 0 1 1 0 0 +EDGE2 5838 1158 -0.0111767 -0.0256391 0.0165359 1 0 1 1 0 0 +EDGE2 5838 3477 -0.951797 0.0156688 -0.0032723 1 0 1 1 0 0 +EDGE2 5838 5837 -1.03305 0.064624 0.0370587 1 0 1 1 0 0 +EDGE2 5838 5817 -0.979053 0.0197294 0.00421171 1 0 1 1 0 0 +EDGE2 5838 3117 -1.09761 0.0686815 -0.00952613 1 0 1 1 0 0 +EDGE2 5838 3137 -0.968665 0.0100147 0.0128513 1 0 1 1 0 0 +EDGE2 5838 3377 -1.03475 -0.017725 0.0220018 1 0 1 1 0 0 +EDGE2 5838 3097 -0.991566 0.0915039 -0.0147416 1 0 1 1 0 0 +EDGE2 5838 1177 -0.942667 -0.0228049 -0.00713766 1 0 1 1 0 0 +EDGE2 5838 1157 -1.07886 -0.0671884 -0.0084906 1 0 1 1 0 0 +EDGE2 5839 5820 0.994701 0.0646403 0.00848999 1 0 1 1 0 0 +EDGE2 5839 1160 1.0844 -0.0178681 0.0343489 1 0 1 1 0 0 +EDGE2 5839 3140 1.05027 -0.0221818 0.00877048 1 0 1 1 0 0 +EDGE2 5839 3420 1.03751 -0.0176273 -3.20168 1 0 1 1 0 0 +EDGE2 5839 3440 0.998774 0.0944424 -3.12821 1 0 1 1 0 0 +EDGE2 5839 3480 1.00452 -0.0727092 -0.00455694 1 0 1 1 0 0 +EDGE2 5839 3380 0.968054 0.0544201 0.00868648 1 0 1 1 0 0 +EDGE2 5839 1200 0.973674 0.0665092 0.0134062 1 0 1 1 0 0 +EDGE2 5839 3100 1.01734 -0.0213113 0.00909304 1 0 1 1 0 0 +EDGE2 5839 3120 0.990376 -0.0597018 -0.0190796 1 0 1 1 0 0 +EDGE2 5839 1180 1.02653 -0.106012 -0.0122366 1 0 1 1 0 0 +EDGE2 5839 900 1.01499 0.0181693 -3.15451 1 0 1 1 0 0 +EDGE2 5839 840 1.02732 -0.0625444 -3.11958 1 0 1 1 0 0 +EDGE2 5839 860 1.04497 0.0465143 -3.15596 1 0 1 1 0 0 +EDGE2 5839 3119 -0.0432334 -0.0381041 -0.00393466 1 0 1 1 0 0 +EDGE2 5839 3379 -0.0143652 0.00929342 0.0212365 1 0 1 1 0 0 +EDGE2 5839 3479 0.0304538 -0.0985547 0.0200013 1 0 1 1 0 0 +EDGE2 5839 5819 -0.0506768 -0.0648019 0.00757462 1 0 1 1 0 0 +EDGE2 5839 3139 0.0148457 0.0109194 -0.0189923 1 0 1 1 0 0 +EDGE2 5839 1179 -0.0334367 0.0239894 0.0140502 1 0 1 1 0 0 +EDGE2 5839 1199 -0.0413118 -0.00833922 -0.0172561 1 0 1 1 0 0 +EDGE2 5839 3099 -0.00760933 -0.0046159 -0.00487569 1 0 1 1 0 0 +EDGE2 5839 1159 0.00934091 0.0343737 -0.0106124 1 0 1 1 0 0 +EDGE2 5839 5818 -0.957254 -0.0890446 -0.00407182 1 0 1 1 0 0 +EDGE2 5839 5838 -0.968963 0.023612 0.00239656 1 0 1 1 0 0 +EDGE2 5839 3098 -1.00636 -0.099952 0.0280358 1 0 1 1 0 0 +EDGE2 5839 3138 -0.949792 -0.0969036 0.00645159 1 0 1 1 0 0 +EDGE2 5839 3378 -0.961 0.0324034 -0.0211998 1 0 1 1 0 0 +EDGE2 5839 3478 -0.940487 0.0880922 -0.00695938 1 0 1 1 0 0 +EDGE2 5839 3118 -1.04174 -0.0299193 -0.000313478 1 0 1 1 0 0 +EDGE2 5839 1178 -0.921034 0.00567575 -0.000134768 1 0 1 1 0 0 +EDGE2 5839 1198 -1.04134 -0.0379148 -0.0289917 1 0 1 1 0 0 +EDGE2 5839 1158 -0.940769 -0.0175641 -0.000717335 1 0 1 1 0 0 +EDGE2 5840 5820 0.00352297 -0.0376198 -0.00325618 1 0 1 1 0 0 +EDGE2 5840 839 0.952587 0.0400445 -3.13443 1 0 1 1 0 0 +EDGE2 5840 899 1.05803 0.0383379 -3.15787 1 0 1 1 0 0 +EDGE2 5840 3419 1.02308 -0.0922433 -3.14502 1 0 1 1 0 0 +EDGE2 5840 3439 0.977626 -0.0323415 -3.15087 1 0 1 1 0 0 +EDGE2 5840 859 1.04191 -0.0852185 -3.14639 1 0 1 1 0 0 +EDGE2 5840 3441 -0.0251009 -1.03364 -1.58203 1 0 1 1 0 0 +EDGE2 5840 841 0.0518016 -0.968931 -1.58989 1 0 1 1 0 0 +EDGE2 5840 901 0.0842034 -1.02072 -1.59367 1 0 1 1 0 0 +EDGE2 5840 1201 0.029734 -1.09513 -1.59126 1 0 1 1 0 0 +EDGE2 5840 3421 -0.0102455 -0.980214 -1.57288 1 0 1 1 0 0 +EDGE2 5840 861 -0.0328688 -1.02149 -1.62696 1 0 1 1 0 0 +EDGE2 5840 5821 0.0225404 1.06153 1.58276 1 0 1 1 0 0 +EDGE2 5840 1160 -0.00124515 -0.0640258 -0.0106139 1 0 1 1 0 0 +EDGE2 5840 3140 0.0636225 -0.0470096 0.0267799 1 0 1 1 0 0 +EDGE2 5840 3420 -0.0462324 0.078001 -3.14357 1 0 1 1 0 0 +EDGE2 5840 3440 0.0116292 -0.0136152 -3.15294 1 0 1 1 0 0 +EDGE2 5840 3480 0.176224 0.0252221 -0.0281193 1 0 1 1 0 0 +EDGE2 5840 3380 0.0656899 0.0240283 0.0408684 1 0 1 1 0 0 +EDGE2 5840 1200 0.107021 -0.0589744 -0.041806 1 0 1 1 0 0 +EDGE2 5840 3100 -0.0260602 -0.0881714 0.01263 1 0 1 1 0 0 +EDGE2 5840 3120 0.104741 0.0135268 0.0156985 1 0 1 1 0 0 +EDGE2 5840 1180 0.0102496 0.0233502 -0.0162864 1 0 1 1 0 0 +EDGE2 5840 900 -0.00329379 -0.0189518 -3.15093 1 0 1 1 0 0 +EDGE2 5840 840 0.0171252 -0.0253855 -3.1011 1 0 1 1 0 0 +EDGE2 5840 860 -0.00244245 -0.0878842 -3.13254 1 0 1 1 0 0 +EDGE2 5840 3101 0.0149872 1.02482 1.54778 1 0 1 1 0 0 +EDGE2 5840 3141 0.0234112 1.00606 1.53812 1 0 1 1 0 0 +EDGE2 5840 3381 -0.0294102 0.993642 1.59175 1 0 1 1 0 0 +EDGE2 5840 3481 -0.0666335 0.979781 1.60971 1 0 1 1 0 0 +EDGE2 5840 3121 0.0126022 0.947859 1.54824 1 0 1 1 0 0 +EDGE2 5840 1161 -0.0310787 0.949949 1.58034 1 0 1 1 0 0 +EDGE2 5840 1181 -0.0112058 0.96384 1.5068 1 0 1 1 0 0 +EDGE2 5840 5839 -1.02158 0.044937 -0.0117759 1 0 1 1 0 0 +EDGE2 5840 3119 -1.07497 -0.0208057 0.00493443 1 0 1 1 0 0 +EDGE2 5840 3379 -0.909517 0.00589824 0.0371077 1 0 1 1 0 0 +EDGE2 5840 3479 -1.01069 -0.0509545 -0.0145866 1 0 1 1 0 0 +EDGE2 5840 5819 -1.0478 0.0531458 -0.0126657 1 0 1 1 0 0 +EDGE2 5840 3139 -0.995088 -0.0027751 0.0164691 1 0 1 1 0 0 +EDGE2 5840 1179 -0.990556 -0.0599332 0.0125914 1 0 1 1 0 0 +EDGE2 5840 1199 -0.991917 -0.0751453 0.00265244 1 0 1 1 0 0 +EDGE2 5840 3099 -1.06203 0.0767376 0.0262868 1 0 1 1 0 0 +EDGE2 5840 1159 -1.06356 -0.0294165 0.00655818 1 0 1 1 0 0 +EDGE2 5841 5820 -0.995302 0.00361082 -1.58396 1 0 1 1 0 0 +EDGE2 5841 5840 -1.00995 -0.0331678 -1.56546 1 0 1 1 0 0 +EDGE2 5841 5821 -0.0010666 0.0427756 -0.00211387 1 0 1 1 0 0 +EDGE2 5841 1160 -0.983689 0.00919521 -1.54195 1 0 1 1 0 0 +EDGE2 5841 3140 -1.09033 -0.0829718 -1.56872 1 0 1 1 0 0 +EDGE2 5841 3420 -1.01253 0.00857046 1.54185 1 0 1 1 0 0 +EDGE2 5841 3440 -0.961478 0.0213536 1.58962 1 0 1 1 0 0 +EDGE2 5841 3480 -0.983705 0.0403355 -1.60033 1 0 1 1 0 0 +EDGE2 5841 3380 -0.987505 -0.0272645 -1.57022 1 0 1 1 0 0 +EDGE2 5841 1200 -0.91964 -0.0107868 -1.53498 1 0 1 1 0 0 +EDGE2 5841 3100 -1.09812 0.145103 -1.58068 1 0 1 1 0 0 +EDGE2 5841 3120 -0.961024 -0.0532275 -1.54459 1 0 1 1 0 0 +EDGE2 5841 1180 -0.991876 0.00549089 -1.57842 1 0 1 1 0 0 +EDGE2 5841 900 -1.03753 -0.0206531 1.58156 1 0 1 1 0 0 +EDGE2 5841 840 -0.975928 0.0139919 1.56187 1 0 1 1 0 0 +EDGE2 5841 860 -1.0048 0.0524264 1.54697 1 0 1 1 0 0 +EDGE2 5841 3482 0.949084 -0.111255 -0.00599715 1 0 1 1 0 0 +EDGE2 5841 3101 0.048429 0.126296 -0.00263891 1 0 1 1 0 0 +EDGE2 5841 3141 0.0185522 0.0771375 -0.000703039 1 0 1 1 0 0 +EDGE2 5841 3381 -0.0484243 -0.0634358 0.0182929 1 0 1 1 0 0 +EDGE2 5841 3481 -0.0472953 0.0254711 -0.00611226 1 0 1 1 0 0 +EDGE2 5841 3121 -0.0632999 0.0162586 -0.0320875 1 0 1 1 0 0 +EDGE2 5841 1161 0.00823227 0.0173002 -0.00400524 1 0 1 1 0 0 +EDGE2 5841 1181 -0.0120757 0.00908895 -0.0118657 1 0 1 1 0 0 +EDGE2 5841 5822 0.995019 0.0129981 -0.00799603 1 0 1 1 0 0 +EDGE2 5841 1182 0.962764 -0.0644855 -0.0070097 1 0 1 1 0 0 +EDGE2 5841 3122 0.987362 0.0440074 -0.0319654 1 0 1 1 0 0 +EDGE2 5841 3142 1.01868 0.0538767 -0.00941439 1 0 1 1 0 0 +EDGE2 5841 3382 0.931854 -0.0376453 0.0113585 1 0 1 1 0 0 +EDGE2 5841 3102 0.973611 0.0833999 -0.00274506 1 0 1 1 0 0 +EDGE2 5841 1162 1.03637 -0.0340784 -0.0100399 1 0 1 1 0 0 +EDGE2 5842 5821 -0.999659 0.0702157 0.0404106 1 0 1 1 0 0 +EDGE2 5842 5841 -0.928848 0.00614931 0.0218015 1 0 1 1 0 0 +EDGE2 5842 3383 1.13148 -0.0667071 -0.00441491 1 0 1 1 0 0 +EDGE2 5842 3482 -0.0567396 -0.0329099 -0.0161657 1 0 1 1 0 0 +EDGE2 5842 3101 -0.93015 0.00656454 0.00873579 1 0 1 1 0 0 +EDGE2 5842 3141 -1.03206 -0.0497053 0.00668379 1 0 1 1 0 0 +EDGE2 5842 3381 -0.946846 -0.0355166 0.00659864 1 0 1 1 0 0 +EDGE2 5842 3481 -1.07805 0.0115448 0.030971 1 0 1 1 0 0 +EDGE2 5842 3121 -0.947516 -0.023837 -0.0186792 1 0 1 1 0 0 +EDGE2 5842 1161 -1.07657 0.105225 -0.00343687 1 0 1 1 0 0 +EDGE2 5842 1181 -0.992343 0.0259861 0.0248983 1 0 1 1 0 0 +EDGE2 5842 5822 0.0175399 -0.00425106 0.00631981 1 0 1 1 0 0 +EDGE2 5842 1182 -0.0797372 -0.00846542 0.0161051 1 0 1 1 0 0 +EDGE2 5842 3122 -0.139517 0.0309047 0.0475954 1 0 1 1 0 0 +EDGE2 5842 3142 -0.0097739 -0.0488378 0.00471289 1 0 1 1 0 0 +EDGE2 5842 3382 0.00596302 -0.0255805 -0.0761176 1 0 1 1 0 0 +EDGE2 5842 3102 0.0139014 0.00600905 0.0017041 1 0 1 1 0 0 +EDGE2 5842 5823 0.995801 0.071211 -0.00340413 1 0 1 1 0 0 +EDGE2 5842 1162 -0.027847 0.0361016 0.0112292 1 0 1 1 0 0 +EDGE2 5842 3483 1.08919 -0.0327379 -0.0101004 1 0 1 1 0 0 +EDGE2 5842 1163 0.99456 -0.0576897 -0.00130368 1 0 1 1 0 0 +EDGE2 5842 3103 1.05232 -0.0109895 -0.0103682 1 0 1 1 0 0 +EDGE2 5842 3123 1.1313 0.00420563 0.0260363 1 0 1 1 0 0 +EDGE2 5842 3143 1.04853 -0.0248107 -0.0251043 1 0 1 1 0 0 +EDGE2 5842 1183 1.02734 -0.0351421 0.0250819 1 0 1 1 0 0 +EDGE2 5843 3383 -0.00451957 -0.0826353 -0.0140567 1 0 1 1 0 0 +EDGE2 5843 3482 -0.904084 -0.0589281 0.00291081 1 0 1 1 0 0 +EDGE2 5843 5842 -0.934078 0.0317922 -0.0158437 1 0 1 1 0 0 +EDGE2 5843 5822 -1.02145 -0.0238322 -0.0151998 1 0 1 1 0 0 +EDGE2 5843 1182 -0.968617 0.0361681 -0.0224719 1 0 1 1 0 0 +EDGE2 5843 3122 -0.935444 0.00214701 0.00931891 1 0 1 1 0 0 +EDGE2 5843 3142 -0.992114 0.114484 -0.00573887 1 0 1 1 0 0 +EDGE2 5843 3382 -1.03883 -0.000502463 -0.000597334 1 0 1 1 0 0 +EDGE2 5843 3102 -1.02663 0.0353486 0.0019232 1 0 1 1 0 0 +EDGE2 5843 5823 -0.0476364 -0.0318962 -0.0197369 1 0 1 1 0 0 +EDGE2 5843 1162 -0.998886 -0.0177535 0.0186306 1 0 1 1 0 0 +EDGE2 5843 3483 0.00500337 0.0696502 -0.0297319 1 0 1 1 0 0 +EDGE2 5843 3144 1.05035 0.0348833 0.0208958 1 0 1 1 0 0 +EDGE2 5843 1163 -0.0374294 -0.0591243 0.0258174 1 0 1 1 0 0 +EDGE2 5843 3103 -0.0222236 -0.0289212 0.0218555 1 0 1 1 0 0 +EDGE2 5843 3123 0.00249146 -0.0195568 0.0219591 1 0 1 1 0 0 +EDGE2 5843 3143 0.0296819 -0.0341446 0.0496593 1 0 1 1 0 0 +EDGE2 5843 1183 -0.0422297 -0.0210469 0.0384184 1 0 1 1 0 0 +EDGE2 5843 3484 0.974634 0.0189813 0.0148876 1 0 1 1 0 0 +EDGE2 5843 5824 1.01546 0.00597535 -0.0193796 1 0 1 1 0 0 +EDGE2 5843 3384 0.978928 0.0287892 -0.0183949 1 0 1 1 0 0 +EDGE2 5843 1184 1.05669 -0.0996752 0.00273115 1 0 1 1 0 0 +EDGE2 5843 3104 0.961225 -0.0488985 0.0185984 1 0 1 1 0 0 +EDGE2 5843 3124 0.980754 0.0517931 -8.2528e-05 1 0 1 1 0 0 +EDGE2 5843 1164 0.92613 -0.0377607 -0.0218414 1 0 1 1 0 0 +EDGE2 5844 3383 -0.973026 -0.0386909 0.0204542 1 0 1 1 0 0 +EDGE2 5844 5823 -0.964249 0.07535 -0.0141355 1 0 1 1 0 0 +EDGE2 5844 5843 -0.989837 -0.0070948 -0.00760413 1 0 1 1 0 0 +EDGE2 5844 3483 -0.993466 0.0393935 0.00304014 1 0 1 1 0 0 +EDGE2 5844 3144 -0.0802983 -0.0294559 0.048682 1 0 1 1 0 0 +EDGE2 5844 1163 -1.02724 -0.0219033 -0.0295869 1 0 1 1 0 0 +EDGE2 5844 3103 -1.01225 -0.0447338 -0.0243828 1 0 1 1 0 0 +EDGE2 5844 3123 -1.05554 0.0595684 -0.00291405 1 0 1 1 0 0 +EDGE2 5844 3143 -1.10175 0.0592126 -0.0261977 1 0 1 1 0 0 +EDGE2 5844 1183 -1.07999 -0.00947798 -0.0126788 1 0 1 1 0 0 +EDGE2 5844 3484 0.0406053 -0.0567633 -0.000461685 1 0 1 1 0 0 +EDGE2 5844 5824 0.0349045 -0.0214004 -0.0123017 1 0 1 1 0 0 +EDGE2 5844 3384 -0.0598492 -0.0333112 -0.0107992 1 0 1 1 0 0 +EDGE2 5844 1184 0.0350916 -0.00468845 0.0307324 1 0 1 1 0 0 +EDGE2 5844 3104 0.00264656 -0.0248218 0.00121387 1 0 1 1 0 0 +EDGE2 5844 3124 0.00585533 0.00454218 0.00428411 1 0 1 1 0 0 +EDGE2 5844 1164 0.0463453 0.0704986 0.0049702 1 0 1 1 0 0 +EDGE2 5844 3105 1.03706 -0.0789771 0.00449013 1 0 1 1 0 0 +EDGE2 5844 3485 0.970782 0.0491684 0.015037 1 0 1 1 0 0 +EDGE2 5844 5825 0.944178 -0.022685 -0.0056868 1 0 1 1 0 0 +EDGE2 5844 3145 0.983992 -0.0100436 0.0159013 1 0 1 1 0 0 +EDGE2 5844 3165 1.04746 0.0111497 -3.12857 1 0 1 1 0 0 +EDGE2 5844 3385 1.04975 -0.0279401 -0.0161567 1 0 1 1 0 0 +EDGE2 5844 3125 0.924507 -0.0374058 0.00674087 1 0 1 1 0 0 +EDGE2 5844 1185 0.936185 0.0386319 -0.00675012 1 0 1 1 0 0 +EDGE2 5844 3065 1.01069 0.0509371 -3.11996 1 0 1 1 0 0 +EDGE2 5844 3085 1.05367 0.0274889 -3.16932 1 0 1 1 0 0 +EDGE2 5844 1165 1.00392 -0.0111095 0.00494838 1 0 1 1 0 0 +EDGE2 5845 3146 -0.0230717 -1.02517 -1.55467 1 0 1 1 0 0 +EDGE2 5845 3386 -0.0112204 -1.02101 -1.55375 1 0 1 1 0 0 +EDGE2 5845 3066 0.0119831 -1.0813 -1.56612 1 0 1 1 0 0 +EDGE2 5845 3144 -0.978582 -0.0123083 -0.0345864 1 0 1 1 0 0 +EDGE2 5845 3484 -0.980318 0.0644553 -0.0244603 1 0 1 1 0 0 +EDGE2 5845 5824 -1.04429 -0.0919646 -0.0300307 1 0 1 1 0 0 +EDGE2 5845 5844 -1.03447 0.0494002 0.045888 1 0 1 1 0 0 +EDGE2 5845 3384 -0.954797 0.064174 -0.00286559 1 0 1 1 0 0 +EDGE2 5845 1184 -1.0645 0.0136646 -0.000710202 1 0 1 1 0 0 +EDGE2 5845 3104 -1.06972 -0.00738304 0.00274362 1 0 1 1 0 0 +EDGE2 5845 3124 -1.01575 0.0307319 0.00811166 1 0 1 1 0 0 +EDGE2 5845 1164 -0.960042 -0.0622779 -0.0121284 1 0 1 1 0 0 +EDGE2 5845 3166 -0.101939 0.997516 1.55071 1 0 1 1 0 0 +EDGE2 5845 3105 0.0175082 0.0405137 -0.0286151 1 0 1 1 0 0 +EDGE2 5845 3485 -0.0279177 0.0246528 0.0109331 1 0 1 1 0 0 +EDGE2 5845 5825 -0.0137947 -0.04361 -0.032921 1 0 1 1 0 0 +EDGE2 5845 3145 -0.0775682 0.0589747 0.00029713 1 0 1 1 0 0 +EDGE2 5845 3165 0.0330782 -0.0580732 -3.16014 1 0 1 1 0 0 +EDGE2 5845 3385 -0.0898523 -0.0154636 0.00586352 1 0 1 1 0 0 +EDGE2 5845 3125 -0.0142648 0.0353332 -0.0107495 1 0 1 1 0 0 +EDGE2 5845 1185 -0.00181478 0.00452918 0.0467737 1 0 1 1 0 0 +EDGE2 5845 3065 -0.00692099 -0.0240282 -3.11613 1 0 1 1 0 0 +EDGE2 5845 3085 0.0560715 0.00337398 -3.162 1 0 1 1 0 0 +EDGE2 5845 1165 -0.0425647 -0.047006 0.020041 1 0 1 1 0 0 +EDGE2 5845 5826 0.028502 0.980107 1.59189 1 0 1 1 0 0 +EDGE2 5845 3486 0.143528 1.00545 1.56259 1 0 1 1 0 0 +EDGE2 5845 1166 0.0024635 0.986974 1.55388 1 0 1 1 0 0 +EDGE2 5845 3086 -0.0181188 1.00882 1.53888 1 0 1 1 0 0 +EDGE2 5845 3106 -0.0208086 1.01551 1.5885 1 0 1 1 0 0 +EDGE2 5845 3126 0.0352874 0.992455 1.55284 1 0 1 1 0 0 +EDGE2 5845 1186 0.090289 1.00788 1.57783 1 0 1 1 0 0 +EDGE2 5845 3064 0.959448 -0.00818438 -3.14492 1 0 1 1 0 0 +EDGE2 5845 3164 0.9141 -0.0773309 -3.17327 1 0 1 1 0 0 +EDGE2 5845 3084 1.05544 0.0106772 -3.16645 1 0 1 1 0 0 +EDGE2 5846 3166 -0.112328 0.0378254 -0.0189189 1 0 1 1 0 0 +EDGE2 5846 3105 -0.937989 0.0256434 -1.5771 1 0 1 1 0 0 +EDGE2 5846 3485 -1.0527 -0.0512639 -1.59361 1 0 1 1 0 0 +EDGE2 5846 5845 -0.984844 0.0271676 -1.54904 1 0 1 1 0 0 +EDGE2 5846 5825 -1.0256 -0.0688933 -1.5956 1 0 1 1 0 0 +EDGE2 5846 3145 -1.04702 -0.0504771 -1.56243 1 0 1 1 0 0 +EDGE2 5846 3165 -0.994817 -0.13334 1.5643 1 0 1 1 0 0 +EDGE2 5846 3385 -1.00039 0.047538 -1.58263 1 0 1 1 0 0 +EDGE2 5846 3125 -1.05712 0.0669259 -1.55032 1 0 1 1 0 0 +EDGE2 5846 1185 -1.03249 -0.0284871 -1.56764 1 0 1 1 0 0 +EDGE2 5846 3065 -0.974288 0.0314172 1.52001 1 0 1 1 0 0 +EDGE2 5846 3085 -0.999757 -0.0734466 1.58402 1 0 1 1 0 0 +EDGE2 5846 1165 -0.977187 -0.0893585 -1.55054 1 0 1 1 0 0 +EDGE2 5846 5826 -0.0280483 -0.0485182 -0.0215914 1 0 1 1 0 0 +EDGE2 5846 3486 -0.0558325 0.0335642 0.0148392 1 0 1 1 0 0 +EDGE2 5846 1166 9.9058e-05 -0.0547065 -0.0229194 1 0 1 1 0 0 +EDGE2 5846 3086 -0.110125 -0.0122302 0.0214288 1 0 1 1 0 0 +EDGE2 5846 3106 0.0675361 -0.0942875 -0.0193672 1 0 1 1 0 0 +EDGE2 5846 3126 -0.0103159 0.0410353 -0.0170886 1 0 1 1 0 0 +EDGE2 5846 1186 0.0471719 0.00259786 0.0154377 1 0 1 1 0 0 +EDGE2 5846 3107 0.929102 0.0205396 -0.0223486 1 0 1 1 0 0 +EDGE2 5846 3167 0.970406 -0.00299746 -0.00107874 1 0 1 1 0 0 +EDGE2 5846 3487 1.00448 0.0547487 0.0135202 1 0 1 1 0 0 +EDGE2 5846 5827 1.02062 -0.0393718 0.00165786 1 0 1 1 0 0 +EDGE2 5846 3127 1.0118 0.0480387 -0.0271439 1 0 1 1 0 0 +EDGE2 5846 1187 1.00005 -0.0650887 0.0101363 1 0 1 1 0 0 +EDGE2 5846 3087 1.16121 0.0492261 0.0155251 1 0 1 1 0 0 +EDGE2 5846 1167 0.959479 -0.133616 0.0227271 1 0 1 1 0 0 +EDGE2 5847 3166 -0.963981 0.0384419 -0.0288047 1 0 1 1 0 0 +EDGE2 5847 5826 -1.01911 -0.0920848 0.0107744 1 0 1 1 0 0 +EDGE2 5847 5846 -1.08293 0.0802773 -0.0119191 1 0 1 1 0 0 +EDGE2 5847 3486 -0.984669 -0.0191794 0.00270338 1 0 1 1 0 0 +EDGE2 5847 1166 -0.985619 -0.00264491 0.01634 1 0 1 1 0 0 +EDGE2 5847 3086 -1.00671 0.0165834 0.0124665 1 0 1 1 0 0 +EDGE2 5847 3106 -0.972985 0.0115592 -0.0147091 1 0 1 1 0 0 +EDGE2 5847 3126 -0.984223 -0.0280975 -0.00226341 1 0 1 1 0 0 +EDGE2 5847 1186 -0.85588 0.0860107 0.00772475 1 0 1 1 0 0 +EDGE2 5847 3107 -0.00826332 -0.0328107 -0.0248428 1 0 1 1 0 0 +EDGE2 5847 3167 0.0468171 0.00849193 0.0358223 1 0 1 1 0 0 +EDGE2 5847 3487 -0.00839208 -0.0663677 0.0361516 1 0 1 1 0 0 +EDGE2 5847 5827 -0.0025373 0.0274642 0.0252604 1 0 1 1 0 0 +EDGE2 5847 3127 -0.00722706 -0.0370699 -0.0242087 1 0 1 1 0 0 +EDGE2 5847 1187 0.0425365 -0.00449841 -0.00480894 1 0 1 1 0 0 +EDGE2 5847 3087 0.0423079 -0.0789425 -0.0254998 1 0 1 1 0 0 +EDGE2 5847 1167 -0.0435471 -0.0605863 -0.000477066 1 0 1 1 0 0 +EDGE2 5847 3128 0.977793 -0.0359616 -0.0579983 1 0 1 1 0 0 +EDGE2 5847 3488 1.04752 -0.0354187 0.00180622 1 0 1 1 0 0 +EDGE2 5847 5828 1.02091 -0.0186036 0.00275093 1 0 1 1 0 0 +EDGE2 5847 3168 0.996864 -0.0122352 -0.0218273 1 0 1 1 0 0 +EDGE2 5847 1188 1.059 0.0305908 0.00180587 1 0 1 1 0 0 +EDGE2 5847 3088 0.997102 -0.039939 -0.0375701 1 0 1 1 0 0 +EDGE2 5847 3108 0.977336 -0.0168064 -0.0137599 1 0 1 1 0 0 +EDGE2 5847 1168 0.952018 -0.0157372 0.0172925 1 0 1 1 0 0 +EDGE2 5848 5847 -1.03483 0.0386238 0.00800761 1 0 1 1 0 0 +EDGE2 5848 3107 -1.0049 -0.0246444 -0.00881265 1 0 1 1 0 0 +EDGE2 5848 3167 -1.03245 -0.091485 0.0137168 1 0 1 1 0 0 +EDGE2 5848 3487 -1.03678 -0.00796299 0.00288673 1 0 1 1 0 0 +EDGE2 5848 5827 -1.01198 -0.0353872 -0.0137719 1 0 1 1 0 0 +EDGE2 5848 3127 -1.07391 -0.045061 -0.0141807 1 0 1 1 0 0 +EDGE2 5848 1187 -0.91873 -0.0279152 -0.0251151 1 0 1 1 0 0 +EDGE2 5848 3087 -1.06696 0.0111349 -0.0475052 1 0 1 1 0 0 +EDGE2 5848 1167 -0.930576 -0.0550825 -0.0402399 1 0 1 1 0 0 +EDGE2 5848 3128 -0.044086 0.0931242 0.00166765 1 0 1 1 0 0 +EDGE2 5848 3488 -0.0844357 -0.00735101 0.0241725 1 0 1 1 0 0 +EDGE2 5848 5828 0.0927892 0.100157 0.0134333 1 0 1 1 0 0 +EDGE2 5848 3168 0.00227308 0.00875912 0.00262107 1 0 1 1 0 0 +EDGE2 5848 1188 -0.072766 -0.02272 0.00067779 1 0 1 1 0 0 +EDGE2 5848 3088 -0.0795264 0.0154776 -0.00200098 1 0 1 1 0 0 +EDGE2 5848 3108 0.0196549 -0.021153 0.0358054 1 0 1 1 0 0 +EDGE2 5848 1168 -0.112953 0.0229721 0.000963773 1 0 1 1 0 0 +EDGE2 5848 3109 1.01035 -0.054558 0.00470086 1 0 1 1 0 0 +EDGE2 5848 3169 1.00437 -0.00832714 0.0217868 1 0 1 1 0 0 +EDGE2 5848 3489 0.980819 -0.1142 0.0385459 1 0 1 1 0 0 +EDGE2 5848 5829 1.03219 -0.0173432 -0.0141174 1 0 1 1 0 0 +EDGE2 5848 3129 0.953992 -0.0747346 -0.00633212 1 0 1 1 0 0 +EDGE2 5848 1189 1.06891 0.0786016 0.0355692 1 0 1 1 0 0 +EDGE2 5848 3089 0.925957 -0.0243329 0.00116837 1 0 1 1 0 0 +EDGE2 5848 1169 1.07317 0.0657221 0.0244601 1 0 1 1 0 0 +EDGE2 5849 3128 -0.94221 0.0788226 0.0018069 1 0 1 1 0 0 +EDGE2 5849 3488 -0.91634 -0.00725549 -0.00267457 1 0 1 1 0 0 +EDGE2 5849 5828 -0.919413 -0.104238 0.0154216 1 0 1 1 0 0 +EDGE2 5849 5848 -0.990456 -0.0420789 -0.0210376 1 0 1 1 0 0 +EDGE2 5849 3168 -1.04938 -0.0343609 -0.00820367 1 0 1 1 0 0 +EDGE2 5849 1188 -0.973291 -0.103692 -0.0148029 1 0 1 1 0 0 +EDGE2 5849 3088 -0.974484 0.0380779 -0.0090391 1 0 1 1 0 0 +EDGE2 5849 3108 -1.05568 0.0400713 0.0197063 1 0 1 1 0 0 +EDGE2 5849 1168 -0.968176 0.0439531 -0.000673787 1 0 1 1 0 0 +EDGE2 5849 3109 0.0645289 -0.0049024 -0.00856961 1 0 1 1 0 0 +EDGE2 5849 3169 -0.0374461 -0.0166084 0.0270185 1 0 1 1 0 0 +EDGE2 5849 3489 0.00199654 -0.0581814 -0.0169554 1 0 1 1 0 0 +EDGE2 5849 5829 0.0665005 0.0638513 -0.0388794 1 0 1 1 0 0 +EDGE2 5849 3129 0.012814 -0.0424938 -0.0059475 1 0 1 1 0 0 +EDGE2 5849 1189 -0.0641519 -0.00897512 -0.000944238 1 0 1 1 0 0 +EDGE2 5849 3089 0.00798149 -0.0816608 -0.0207457 1 0 1 1 0 0 +EDGE2 5849 1169 0.0343622 -0.113649 -0.0094288 1 0 1 1 0 0 +EDGE2 5849 3050 1.03883 0.0405734 -3.16306 1 0 1 1 0 0 +EDGE2 5849 3170 1.06908 -0.0338932 -0.0106852 1 0 1 1 0 0 +EDGE2 5849 5790 0.979836 -0.0038454 -3.1191 1 0 1 1 0 0 +EDGE2 5849 5810 0.935097 0.0757723 -3.11005 1 0 1 1 0 0 +EDGE2 5849 5830 1.07174 0.0298279 -0.0291198 1 0 1 1 0 0 +EDGE2 5849 3490 1.0718 -0.0141216 0.0164797 1 0 1 1 0 0 +EDGE2 5849 3110 1.02639 -0.00375093 0.0287445 1 0 1 1 0 0 +EDGE2 5849 3130 1.09422 -0.0672006 0.00641415 1 0 1 1 0 0 +EDGE2 5849 3090 0.871815 -0.0667272 -0.00951887 1 0 1 1 0 0 +EDGE2 5849 1130 1.1284 -0.0258099 -3.16409 1 0 1 1 0 0 +EDGE2 5849 1170 0.983261 0.0649253 -0.0185991 1 0 1 1 0 0 +EDGE2 5849 1190 1.01823 -0.0134641 -0.0444223 1 0 1 1 0 0 +EDGE2 5849 3030 1.02253 -0.0568124 -3.13451 1 0 1 1 0 0 +EDGE2 5849 1150 1.00735 0.049168 -3.1124 1 0 1 1 0 0 +EDGE2 5849 1110 1.0357 -0.0107032 -3.12148 1 0 1 1 0 0 +EDGE2 5850 5849 -1.08406 -0.0330204 -0.0051571 1 0 1 1 0 0 +EDGE2 5850 3109 -0.938779 0.02399 0.00835711 1 0 1 1 0 0 +EDGE2 5850 3169 -1.00529 -0.000647391 0.0259016 1 0 1 1 0 0 +EDGE2 5850 3489 -1.00763 -0.0696958 -0.0221453 1 0 1 1 0 0 +EDGE2 5850 5829 -1.10064 -0.0363141 0.0266788 1 0 1 1 0 0 +EDGE2 5850 3129 -0.989828 0.000437274 0.0139152 1 0 1 1 0 0 +EDGE2 5850 1189 -0.978725 0.0304295 -0.0215451 1 0 1 1 0 0 +EDGE2 5850 3089 -0.951559 -0.0162319 0.0304497 1 0 1 1 0 0 +EDGE2 5850 1169 -0.991146 0.0806296 -0.00297123 1 0 1 1 0 0 +EDGE2 5850 3050 0.0143173 -0.0174938 -3.14641 1 0 1 1 0 0 +EDGE2 5850 3131 0.0292954 1.00501 1.57515 1 0 1 1 0 0 +EDGE2 5850 3491 -0.124483 1.06946 1.58655 1 0 1 1 0 0 +EDGE2 5850 5811 0.0172188 0.982242 1.60449 1 0 1 1 0 0 +EDGE2 5850 5831 0.155022 1.02434 1.58435 1 0 1 1 0 0 +EDGE2 5850 3171 0.0698216 1.04973 1.5633 1 0 1 1 0 0 +EDGE2 5850 1151 -0.0783978 0.959263 1.56753 1 0 1 1 0 0 +EDGE2 5850 1191 -0.0521693 1.03797 1.56535 1 0 1 1 0 0 +EDGE2 5850 3091 0.0290024 0.957587 1.57582 1 0 1 1 0 0 +EDGE2 5850 3111 0.0167603 0.947028 1.56787 1 0 1 1 0 0 +EDGE2 5850 1171 -0.066065 1.00486 1.53189 1 0 1 1 0 0 +EDGE2 5850 3170 0.0556671 -0.00330068 -0.00443857 1 0 1 1 0 0 +EDGE2 5850 5790 0.119377 -0.0793147 -3.15202 1 0 1 1 0 0 +EDGE2 5850 5810 -0.0206857 -0.0250614 -3.14809 1 0 1 1 0 0 +EDGE2 5850 5830 0.0208997 -0.073185 -0.0178869 1 0 1 1 0 0 +EDGE2 5850 3490 0.0151617 -0.0801494 0.00758626 1 0 1 1 0 0 +EDGE2 5850 3110 0.0104374 0.0206989 -0.0167273 1 0 1 1 0 0 +EDGE2 5850 3130 0.0860782 2.96971e-05 -0.0144257 1 0 1 1 0 0 +EDGE2 5850 3090 -0.013029 -0.0180004 0.00952887 1 0 1 1 0 0 +EDGE2 5850 5789 1.0243 -0.078192 -3.10586 1 0 1 1 0 0 +EDGE2 5850 1130 -0.0719319 -0.057998 -3.16438 1 0 1 1 0 0 +EDGE2 5850 1170 -0.0486546 0.0283656 -0.0332969 1 0 1 1 0 0 +EDGE2 5850 1190 -0.0329316 -0.0423488 0.0512677 1 0 1 1 0 0 +EDGE2 5850 3030 -0.0545769 0.0249374 -3.12374 1 0 1 1 0 0 +EDGE2 5850 1150 -0.0762982 -0.0795878 -3.14678 1 0 1 1 0 0 +EDGE2 5850 1110 0.0678473 -0.0449622 -3.14062 1 0 1 1 0 0 +EDGE2 5850 5809 1.01685 0.0233185 -3.12705 1 0 1 1 0 0 +EDGE2 5850 1109 1.08077 0.0585085 -3.17586 1 0 1 1 0 0 +EDGE2 5850 1149 0.954684 -0.0697378 -3.11103 1 0 1 1 0 0 +EDGE2 5850 3029 1.04531 -0.00507989 -3.13309 1 0 1 1 0 0 +EDGE2 5850 3049 0.997891 0.0180225 -3.11266 1 0 1 1 0 0 +EDGE2 5850 1129 1.04167 0.0345157 -3.14157 1 0 1 1 0 0 +EDGE2 5850 1111 -0.00716052 -0.986826 -1.54756 1 0 1 1 0 0 +EDGE2 5850 3031 -0.0897165 -1.04507 -1.5567 1 0 1 1 0 0 +EDGE2 5850 3051 -0.00694713 -0.99854 -1.56808 1 0 1 1 0 0 +EDGE2 5850 5791 0.0969965 -0.977071 -1.5691 1 0 1 1 0 0 +EDGE2 5850 1131 0.00309561 -0.938568 -1.60038 1 0 1 1 0 0 +EDGE2 5851 3050 -1.00024 -0.00957742 -1.57537 1 0 1 1 0 0 +EDGE2 5851 5850 -1.03801 0.00670448 1.59446 1 0 1 1 0 0 +EDGE2 5851 3170 -1.04343 0.0557743 1.5612 1 0 1 1 0 0 +EDGE2 5851 5790 -1.01708 -0.00619932 -1.58311 1 0 1 1 0 0 +EDGE2 5851 5810 -0.949357 0.0303251 -1.57919 1 0 1 1 0 0 +EDGE2 5851 5830 -0.99345 -0.0277555 1.57311 1 0 1 1 0 0 +EDGE2 5851 3490 -0.981459 -0.0605173 1.60387 1 0 1 1 0 0 +EDGE2 5851 3110 -0.936296 0.0291492 1.58877 1 0 1 1 0 0 +EDGE2 5851 3130 -1.04783 0.0804074 1.56006 1 0 1 1 0 0 +EDGE2 5851 3090 -0.949173 0.0222013 1.5428 1 0 1 1 0 0 +EDGE2 5851 1130 -0.985116 0.00318077 -1.55853 1 0 1 1 0 0 +EDGE2 5851 1170 -0.982475 -0.0264144 1.60258 1 0 1 1 0 0 +EDGE2 5851 1190 -1.01827 -0.0312068 1.56715 1 0 1 1 0 0 +EDGE2 5851 3030 -1.01745 -0.0200504 -1.5586 1 0 1 1 0 0 +EDGE2 5851 1150 -1.02521 -0.0350665 -1.56149 1 0 1 1 0 0 +EDGE2 5851 1110 -1.08798 -0.021277 -1.55974 1 0 1 1 0 0 +EDGE2 5851 3052 1.04804 -0.010253 0.0170162 1 0 1 1 0 0 +EDGE2 5851 1111 0.00016679 -0.0606826 0.0223349 1 0 1 1 0 0 +EDGE2 5851 3031 0.021471 0.000145942 -0.0165002 1 0 1 1 0 0 +EDGE2 5851 3051 -0.0604996 -0.109352 0.0226809 1 0 1 1 0 0 +EDGE2 5851 5791 -0.0998781 0.000900332 -0.0105927 1 0 1 1 0 0 +EDGE2 5851 1131 0.009242 0.0370342 -0.0134418 1 0 1 1 0 0 +EDGE2 5851 5792 1.05654 -0.0306895 -0.0132033 1 0 1 1 0 0 +EDGE2 5851 1112 0.987453 0.00511777 0.0176789 1 0 1 1 0 0 +EDGE2 5851 1132 1.00649 -0.0689072 0.00403878 1 0 1 1 0 0 +EDGE2 5851 3032 0.904054 -0.0553427 0.00715036 1 0 1 1 0 0 +EDGE2 5852 5851 -0.949011 -0.0147844 0.0265452 1 0 1 1 0 0 +EDGE2 5852 1133 0.975247 0.00429956 -0.0389821 1 0 1 1 0 0 +EDGE2 5852 3052 -0.090625 -0.0329614 -0.0351384 1 0 1 1 0 0 +EDGE2 5852 1111 -0.942907 -0.0283172 -0.0496403 1 0 1 1 0 0 +EDGE2 5852 3031 -0.911976 0.0370128 0.0152265 1 0 1 1 0 0 +EDGE2 5852 3051 -1.02615 0.0309064 0.000313169 1 0 1 1 0 0 +EDGE2 5852 5791 -0.999878 0.0636811 -0.0150762 1 0 1 1 0 0 +EDGE2 5852 1131 -1.04714 0.00853987 -0.0100489 1 0 1 1 0 0 +EDGE2 5852 5792 0.00481127 -0.00242169 0.0117663 1 0 1 1 0 0 +EDGE2 5852 1112 -0.0833328 0.0825485 -0.0024453 1 0 1 1 0 0 +EDGE2 5852 1132 0.0177596 0.0626107 -0.0466551 1 0 1 1 0 0 +EDGE2 5852 3032 -0.0712418 -0.0456918 0.036032 1 0 1 1 0 0 +EDGE2 5852 3053 0.993266 -0.0360246 0.00551234 1 0 1 1 0 0 +EDGE2 5852 5793 0.985425 -0.0391397 -0.021943 1 0 1 1 0 0 +EDGE2 5852 3033 1.01698 0.00105468 0.0155732 1 0 1 1 0 0 +EDGE2 5852 1113 1.04419 -0.0229965 -0.016933 1 0 1 1 0 0 +EDGE2 5853 1133 0.0536852 -0.0989702 0.00346474 1 0 1 1 0 0 +EDGE2 5853 3052 -0.99091 -0.0175555 -0.0428228 1 0 1 1 0 0 +EDGE2 5853 5852 -0.957031 0.0533304 0.00161952 1 0 1 1 0 0 +EDGE2 5853 5792 -1.08103 0.0125865 0.0144178 1 0 1 1 0 0 +EDGE2 5853 1112 -1.01129 0.00942517 0.0281146 1 0 1 1 0 0 +EDGE2 5853 1132 -0.976314 -0.0358533 -0.030179 1 0 1 1 0 0 +EDGE2 5853 3032 -1.04302 0.0565078 -0.000700371 1 0 1 1 0 0 +EDGE2 5853 3053 0.0270237 0.0170775 -0.00329602 1 0 1 1 0 0 +EDGE2 5853 5793 -0.08643 0.0143822 -0.00879255 1 0 1 1 0 0 +EDGE2 5853 3033 0.135095 -0.0765813 -0.0285662 1 0 1 1 0 0 +EDGE2 5853 5794 0.974886 -0.0708562 0.0138236 1 0 1 1 0 0 +EDGE2 5853 1113 0.0716734 0.0544278 -0.00496564 1 0 1 1 0 0 +EDGE2 5853 1134 0.977397 0.0440913 -0.00896112 1 0 1 1 0 0 +EDGE2 5853 3034 0.968588 -0.0595946 -0.00245782 1 0 1 1 0 0 +EDGE2 5853 3054 1.04191 0.0436626 -0.0211067 1 0 1 1 0 0 +EDGE2 5853 1114 0.983315 0.00578084 -0.0103152 1 0 1 1 0 0 +EDGE2 5854 5795 1.02744 0.111263 0.006542 1 0 1 1 0 0 +EDGE2 5854 1133 -0.990694 0.0113819 0.00116999 1 0 1 1 0 0 +EDGE2 5854 3053 -0.969537 0.0368224 0.00583558 1 0 1 1 0 0 +EDGE2 5854 5793 -0.946155 -0.0981925 0.00228664 1 0 1 1 0 0 +EDGE2 5854 5853 -1.05834 -0.0295343 0.0188738 1 0 1 1 0 0 +EDGE2 5854 3033 -1.06899 0.0970134 -0.00148039 1 0 1 1 0 0 +EDGE2 5854 5794 0.0516968 -0.00197141 0.0169774 1 0 1 1 0 0 +EDGE2 5854 1113 -1.01112 -0.039389 0.0128672 1 0 1 1 0 0 +EDGE2 5854 1134 0.0357492 -0.0652796 -0.0044278 1 0 1 1 0 0 +EDGE2 5854 3034 -0.0391056 -0.0260016 0.0365965 1 0 1 1 0 0 +EDGE2 5854 3054 0.00824102 -0.00725758 0.0075196 1 0 1 1 0 0 +EDGE2 5854 1114 0.00367733 0.0417572 0.00960472 1 0 1 1 0 0 +EDGE2 5854 3035 0.961837 0.0158735 -0.0206523 1 0 1 1 0 0 +EDGE2 5854 3055 1.00671 -0.030268 -0.0206833 1 0 1 1 0 0 +EDGE2 5854 1095 0.998444 0.017696 -3.16673 1 0 1 1 0 0 +EDGE2 5854 1115 1.05162 -0.0150725 -0.0188697 1 0 1 1 0 0 +EDGE2 5854 1135 0.972666 -0.0254579 -0.0287993 1 0 1 1 0 0 +EDGE2 5855 5795 -0.0452351 -0.101218 0.0109284 1 0 1 1 0 0 +EDGE2 5855 3056 -0.0427564 -0.994197 -1.58504 1 0 1 1 0 0 +EDGE2 5855 5794 -0.958416 0.031958 0.0103151 1 0 1 1 0 0 +EDGE2 5855 5854 -1.00354 -0.0164563 0.0243607 1 0 1 1 0 0 +EDGE2 5855 1134 -1.08545 0.0306168 -0.000680568 1 0 1 1 0 0 +EDGE2 5855 3034 -1.00171 0.0254846 0.0178729 1 0 1 1 0 0 +EDGE2 5855 3054 -1.10706 0.0162227 -0.00771158 1 0 1 1 0 0 +EDGE2 5855 1114 -0.966572 -0.00903288 -0.0239675 1 0 1 1 0 0 +EDGE2 5855 3035 0.00806892 -0.0379505 -0.0168069 1 0 1 1 0 0 +EDGE2 5855 3055 -0.00199207 -5.85189e-05 -0.0250126 1 0 1 1 0 0 +EDGE2 5855 1095 0.0543852 0.0277091 -3.15706 1 0 1 1 0 0 +EDGE2 5855 1115 0.0188329 -0.0653573 0.0265402 1 0 1 1 0 0 +EDGE2 5855 1135 -0.0683011 0.0360584 0.0056183 1 0 1 1 0 0 +EDGE2 5855 1094 1.00092 0.017782 -3.15271 1 0 1 1 0 0 +EDGE2 5855 1116 0.00210216 0.934157 1.54119 1 0 1 1 0 0 +EDGE2 5855 3036 -0.0111268 0.968857 1.57628 1 0 1 1 0 0 +EDGE2 5855 5796 0.0411762 1.00123 1.59207 1 0 1 1 0 0 +EDGE2 5855 1136 0.076524 0.966034 1.56959 1 0 1 1 0 0 +EDGE2 5855 1096 0.0414922 0.94181 1.57069 1 0 1 1 0 0 +EDGE2 5856 5795 -1.01134 0.034362 1.57342 1 0 1 1 0 0 +EDGE2 5856 3057 0.918896 -0.00671488 -0.00195835 1 0 1 1 0 0 +EDGE2 5856 3056 0.0303115 0.0471437 -0.0169377 1 0 1 1 0 0 +EDGE2 5856 5855 -1.04535 -0.0502096 1.5327 1 0 1 1 0 0 +EDGE2 5856 3035 -1.02232 -0.00723111 1.56149 1 0 1 1 0 0 +EDGE2 5856 3055 -1.07139 0.0311711 1.57525 1 0 1 1 0 0 +EDGE2 5856 1095 -0.954832 0.0416168 -1.59018 1 0 1 1 0 0 +EDGE2 5856 1115 -0.960248 -0.0397608 1.53311 1 0 1 1 0 0 +EDGE2 5856 1135 -1.01835 0.0428858 1.55172 1 0 1 1 0 0 +EDGE2 5857 3058 1.08903 0.0679121 0.012346 1 0 1 1 0 0 +EDGE2 5857 3057 -0.00629212 0.0637192 0.014397 1 0 1 1 0 0 +EDGE2 5857 5856 -1.08013 0.00620186 0.008346 1 0 1 1 0 0 +EDGE2 5857 3056 -1.09897 -0.0211542 -0.00617886 1 0 1 1 0 0 +EDGE2 5858 3059 0.999589 -0.0123544 -0.0335797 1 0 1 1 0 0 +EDGE2 5858 3058 -0.0251026 -0.0598099 -0.040031 1 0 1 1 0 0 +EDGE2 5858 3057 -1.03466 -0.00225677 0.0153277 1 0 1 1 0 0 +EDGE2 5858 5857 -1.05522 -0.0756431 -0.00558719 1 0 1 1 0 0 +EDGE2 5859 3060 1.02172 -0.0312827 0.0267106 1 0 1 1 0 0 +EDGE2 5859 3160 1.04936 -0.0317676 -3.10764 1 0 1 1 0 0 +EDGE2 5859 3080 0.929081 -0.00557176 -3.16873 1 0 1 1 0 0 +EDGE2 5859 1080 0.933818 -0.0624979 -3.15688 1 0 1 1 0 0 +EDGE2 5859 3059 0.0114421 0.0609855 5.58572e-05 1 0 1 1 0 0 +EDGE2 5859 3058 -1.08633 -0.00474546 0.0474725 1 0 1 1 0 0 +EDGE2 5859 5858 -0.98606 -0.00283339 -0.0189601 1 0 1 1 0 0 +EDGE2 5860 3079 0.995912 0.0601609 -3.15092 1 0 1 1 0 0 +EDGE2 5860 3159 0.984633 0.0318988 -3.17812 1 0 1 1 0 0 +EDGE2 5860 1079 1.01772 -0.0189516 -3.13285 1 0 1 1 0 0 +EDGE2 5860 3081 0.00494724 -0.97039 -1.59014 1 0 1 1 0 0 +EDGE2 5860 3161 -0.0595056 -1.0449 -1.56014 1 0 1 1 0 0 +EDGE2 5860 3061 -0.00526786 -1.01749 -1.57793 1 0 1 1 0 0 +EDGE2 5860 3060 -0.0133134 -0.0136045 -0.0292292 1 0 1 1 0 0 +EDGE2 5860 3160 -0.0667051 -0.0363093 -3.15482 1 0 1 1 0 0 +EDGE2 5860 3080 -0.0403806 -0.00394014 -3.16784 1 0 1 1 0 0 +EDGE2 5860 1080 0.0554232 -0.0293471 -3.1622 1 0 1 1 0 0 +EDGE2 5860 1081 0.0245177 1.02696 1.57801 1 0 1 1 0 0 +EDGE2 5860 5859 -1.07282 0.0136481 -0.00085236 1 0 1 1 0 0 +EDGE2 5860 3059 -1.00215 0.000171934 0.0132054 1 0 1 1 0 0 +EDGE2 5861 3060 -0.957245 -0.0495191 -1.57354 1 0 1 1 0 0 +EDGE2 5861 3160 -0.974647 0.0135685 1.54134 1 0 1 1 0 0 +EDGE2 5861 5860 -0.949086 0.000339635 -1.61563 1 0 1 1 0 0 +EDGE2 5861 3080 -1.02516 0.0282131 1.56839 1 0 1 1 0 0 +EDGE2 5861 1080 -0.956404 -0.0533934 1.57103 1 0 1 1 0 0 +EDGE2 5861 1081 0.0770075 -0.00891379 -0.0354902 1 0 1 1 0 0 +EDGE2 5861 1082 0.970567 0.0103767 -0.0271356 1 0 1 1 0 0 +EDGE2 5862 1081 -0.872186 0.0382465 -0.0088685 1 0 1 1 0 0 +EDGE2 5862 5861 -1.10463 0.0440031 0.00568731 1 0 1 1 0 0 +EDGE2 5862 1082 -0.0610153 -0.00438441 0.00872286 1 0 1 1 0 0 +EDGE2 5862 1083 1.05108 0.0657084 0.000336464 1 0 1 1 0 0 +EDGE2 5863 5862 -0.918782 0.0355926 0.034817 1 0 1 1 0 0 +EDGE2 5863 1082 -1.00814 0.0350612 -0.0183793 1 0 1 1 0 0 +EDGE2 5863 1083 0.044642 -0.0184455 -0.0225441 1 0 1 1 0 0 +EDGE2 5863 1084 0.936579 -0.00823038 0.0068091 1 0 1 1 0 0 +EDGE2 5864 1083 -0.981261 0.0310585 0.00490039 1 0 1 1 0 0 +EDGE2 5864 5863 -0.99435 0.0927814 0.0118505 1 0 1 1 0 0 +EDGE2 5864 1084 -0.0257052 0.0578918 -0.0249868 1 0 1 1 0 0 +EDGE2 5864 1045 0.938793 -0.0122714 -3.15699 1 0 1 1 0 0 +EDGE2 5864 1085 0.981739 0.0734038 -0.0134827 1 0 1 1 0 0 +EDGE2 5865 1046 0.0121443 -0.983015 -1.58589 1 0 1 1 0 0 +EDGE2 5865 1084 -1.05716 -0.0362766 -0.047644 1 0 1 1 0 0 +EDGE2 5865 5864 -1.01015 0.075501 -0.00220758 1 0 1 1 0 0 +EDGE2 5865 1045 -0.0112362 0.101245 -3.13051 1 0 1 1 0 0 +EDGE2 5865 1085 0.054892 0.123333 0.00750364 1 0 1 1 0 0 +EDGE2 5865 1044 0.907034 -0.0255322 -3.15347 1 0 1 1 0 0 +EDGE2 5865 1086 0.0290337 0.962643 1.57453 1 0 1 1 0 0 +EDGE2 5866 1045 -0.901193 -0.0285811 1.56335 1 0 1 1 0 0 +EDGE2 5866 1085 -1.01634 0.0494764 -1.59988 1 0 1 1 0 0 +EDGE2 5866 5865 -1.02526 -0.0526893 -1.55266 1 0 1 1 0 0 +EDGE2 5866 1086 0.0131923 -0.105401 0.0210995 1 0 1 1 0 0 +EDGE2 5866 1087 0.881723 0.0468639 0.017652 1 0 1 1 0 0 +EDGE2 5867 1086 -0.976428 0.0280419 0.0493539 1 0 1 1 0 0 +EDGE2 5867 5866 -1.06889 -0.0412442 0.0260412 1 0 1 1 0 0 +EDGE2 5867 1087 0.00258525 -0.0436985 -0.0242666 1 0 1 1 0 0 +EDGE2 5867 1088 0.950739 -0.00501604 -0.0142727 1 0 1 1 0 0 +EDGE2 5868 5867 -1.00776 -0.13984 -0.0282545 1 0 1 1 0 0 +EDGE2 5868 1087 -1.10809 -0.0917262 0.0300222 1 0 1 1 0 0 +EDGE2 5868 1088 0.0303408 -0.0138424 0.00853765 1 0 1 1 0 0 +EDGE2 5868 1089 1.00032 0.0749942 -0.0353299 1 0 1 1 0 0 +EDGE2 5869 1088 -1.00634 -0.00754755 0.00499839 1 0 1 1 0 0 +EDGE2 5869 5868 -1.07628 0.0529576 -0.0425386 1 0 1 1 0 0 +EDGE2 5869 1089 -0.0531092 -0.0295159 0.0513977 1 0 1 1 0 0 +EDGE2 5869 1090 1.0102 0.0138115 -0.000322464 1 0 1 1 0 0 +EDGE2 5870 5869 -0.988729 0.0366812 0.0327551 1 0 1 1 0 0 +EDGE2 5870 1089 -1.00064 0.0574371 0.0170204 1 0 1 1 0 0 +EDGE2 5870 1091 0.0322446 0.972097 1.50909 1 0 1 1 0 0 +EDGE2 5870 1090 -0.0269251 0.0581025 -0.00702439 1 0 1 1 0 0 +EDGE2 5871 1092 1.03042 -0.100192 -0.00860832 1 0 1 1 0 0 +EDGE2 5871 1091 -0.0278408 0.0154648 0.0209281 1 0 1 1 0 0 +EDGE2 5871 5870 -0.964481 0.0582638 -1.5672 1 0 1 1 0 0 +EDGE2 5871 1090 -0.996796 0.073761 -1.58589 1 0 1 1 0 0 +EDGE2 5872 1092 -0.068085 -0.0173163 0.00288168 1 0 1 1 0 0 +EDGE2 5872 1093 1.02893 0.00722544 0.0137359 1 0 1 1 0 0 +EDGE2 5872 1091 -1.06391 -0.0484567 0.0463225 1 0 1 1 0 0 +EDGE2 5872 5871 -0.981304 -0.0237349 0.010047 1 0 1 1 0 0 +EDGE2 5873 1092 -0.984442 0.0482393 0.00496475 1 0 1 1 0 0 +EDGE2 5873 1094 0.98491 -0.0872768 0.00114412 1 0 1 1 0 0 +EDGE2 5873 1093 0.0162169 -0.00498161 -0.00910842 1 0 1 1 0 0 +EDGE2 5873 5872 -0.978747 0.0283721 -0.000763067 1 0 1 1 0 0 +EDGE2 5874 5795 0.981973 0.00985627 -3.1238 1 0 1 1 0 0 +EDGE2 5874 5855 1.01116 0.0676273 -3.12701 1 0 1 1 0 0 +EDGE2 5874 3035 0.965896 0.0358321 -3.14228 1 0 1 1 0 0 +EDGE2 5874 3055 0.941533 0.0339368 -3.12279 1 0 1 1 0 0 +EDGE2 5874 1095 0.928174 -0.0363167 -0.0112572 1 0 1 1 0 0 +EDGE2 5874 1115 1.03141 0.111942 -3.15083 1 0 1 1 0 0 +EDGE2 5874 1135 1.03427 0.0770016 -3.16762 1 0 1 1 0 0 +EDGE2 5874 1094 -0.00685946 -0.0260058 -0.00617879 1 0 1 1 0 0 +EDGE2 5874 1093 -0.99062 -0.0495206 0.00759956 1 0 1 1 0 0 +EDGE2 5874 5873 -0.95661 0.0336819 0.0222269 1 0 1 1 0 0 +EDGE2 5875 5795 -0.0361365 -0.0763957 -3.13548 1 0 1 1 0 0 +EDGE2 5875 5856 0.0465892 0.986468 1.61007 1 0 1 1 0 0 +EDGE2 5875 3056 -0.0400591 1.0081 1.55971 1 0 1 1 0 0 +EDGE2 5875 5794 1.04287 -0.0544092 -3.12745 1 0 1 1 0 0 +EDGE2 5875 5854 1.00543 0.0446192 -3.13229 1 0 1 1 0 0 +EDGE2 5875 1134 1.0102 -0.0834647 -3.17969 1 0 1 1 0 0 +EDGE2 5875 3034 1.02568 0.0433976 -3.14463 1 0 1 1 0 0 +EDGE2 5875 3054 0.964164 0.0117473 -3.16511 1 0 1 1 0 0 +EDGE2 5875 1114 0.989549 -0.0778053 -3.12211 1 0 1 1 0 0 +EDGE2 5875 5855 0.0843133 0.0546698 -3.13084 1 0 1 1 0 0 +EDGE2 5875 3035 -0.0152276 0.118837 -3.1461 1 0 1 1 0 0 +EDGE2 5875 3055 0.0208384 -0.0463834 -3.10096 1 0 1 1 0 0 +EDGE2 5875 1095 0.00944145 0.0419852 0.0223523 1 0 1 1 0 0 +EDGE2 5875 1115 -0.096743 0.00475188 -3.12003 1 0 1 1 0 0 +EDGE2 5875 1135 -0.0578131 -0.00221175 -3.11189 1 0 1 1 0 0 +EDGE2 5875 1094 -1.03139 -0.0441736 0.0288005 1 0 1 1 0 0 +EDGE2 5875 5874 -1.05085 -0.0138259 -0.0257387 1 0 1 1 0 0 +EDGE2 5875 1116 0.0851923 -0.993305 -1.56959 1 0 1 1 0 0 +EDGE2 5875 3036 0.102433 -0.992904 -1.58645 1 0 1 1 0 0 +EDGE2 5875 5796 0.0837735 -1.07843 -1.57016 1 0 1 1 0 0 +EDGE2 5875 1136 0.0461125 -1.01656 -1.54657 1 0 1 1 0 0 +EDGE2 5875 1096 0.0196196 -1.02464 -1.57606 1 0 1 1 0 0 +EDGE2 5876 5795 -0.941401 -0.0188391 1.58023 1 0 1 1 0 0 +EDGE2 5876 3057 0.994013 -0.115714 0.00183359 1 0 1 1 0 0 +EDGE2 5876 5857 1.04262 0.0518359 -0.0170453 1 0 1 1 0 0 +EDGE2 5876 5856 0.0441315 0.0447515 0.0358456 1 0 1 1 0 0 +EDGE2 5876 3056 0.0546653 0.043812 -0.0089199 1 0 1 1 0 0 +EDGE2 5876 5875 -0.956402 0.0176792 -1.53597 1 0 1 1 0 0 +EDGE2 5876 5855 -1.04995 0.0433102 1.586 1 0 1 1 0 0 +EDGE2 5876 3035 -0.992851 0.0371227 1.61358 1 0 1 1 0 0 +EDGE2 5876 3055 -0.96886 -0.0487052 1.56915 1 0 1 1 0 0 +EDGE2 5876 1095 -1.01067 -0.0129159 -1.59174 1 0 1 1 0 0 +EDGE2 5876 1115 -1.10645 -0.019517 1.55415 1 0 1 1 0 0 +EDGE2 5876 1135 -1.07355 0.0254447 1.554 1 0 1 1 0 0 +EDGE2 5877 3058 0.947152 0.000871503 -0.0110685 1 0 1 1 0 0 +EDGE2 5877 5858 1.00631 0.0118134 0.0134291 1 0 1 1 0 0 +EDGE2 5877 3057 0.0041379 0.0446697 0.0111271 1 0 1 1 0 0 +EDGE2 5877 5857 -0.108369 0.00217424 0.0261157 1 0 1 1 0 0 +EDGE2 5877 5856 -0.986156 -0.0322935 -0.0082055 1 0 1 1 0 0 +EDGE2 5877 5876 -1.03007 -0.049056 -0.0297607 1 0 1 1 0 0 +EDGE2 5877 3056 -1.0274 -0.0269938 -0.0192937 1 0 1 1 0 0 +EDGE2 5878 5859 0.963254 -0.00272381 -0.0252901 1 0 1 1 0 0 +EDGE2 5878 3059 0.90094 0.0879377 -0.0367792 1 0 1 1 0 0 +EDGE2 5878 3058 0.0882936 0.0172339 -0.0181171 1 0 1 1 0 0 +EDGE2 5878 5858 -0.0508434 0.0551115 -0.013665 1 0 1 1 0 0 +EDGE2 5878 5877 -0.945468 0.020009 0.0224678 1 0 1 1 0 0 +EDGE2 5878 3057 -0.991765 0.0891631 0.0345879 1 0 1 1 0 0 +EDGE2 5878 5857 -1.03299 0.0838891 -0.0352395 1 0 1 1 0 0 +EDGE2 5879 3060 0.947056 -0.0219718 0.00410144 1 0 1 1 0 0 +EDGE2 5879 3160 1.00938 -0.0664285 -3.15971 1 0 1 1 0 0 +EDGE2 5879 5860 1.11326 0.0276094 0.00586969 1 0 1 1 0 0 +EDGE2 5879 3080 1.03915 0.0435145 -3.13666 1 0 1 1 0 0 +EDGE2 5879 1080 1.05114 0.0711912 -3.13935 1 0 1 1 0 0 +EDGE2 5879 5859 0.121078 -0.0203438 0.00439041 1 0 1 1 0 0 +EDGE2 5879 3059 -0.039559 -0.110119 0.00529708 1 0 1 1 0 0 +EDGE2 5879 3058 -1.0289 -0.00598796 0.00110774 1 0 1 1 0 0 +EDGE2 5879 5858 -0.998288 -0.0707823 -0.0256426 1 0 1 1 0 0 +EDGE2 5879 5878 -0.963022 -0.0118118 0.00918707 1 0 1 1 0 0 +EDGE2 5880 3079 0.927468 0.11034 -3.12159 1 0 1 1 0 0 +EDGE2 5880 3159 1.07516 -0.0223973 -3.13903 1 0 1 1 0 0 +EDGE2 5880 1079 1.01245 0.0101834 -3.12586 1 0 1 1 0 0 +EDGE2 5880 3081 -0.0320795 -0.925892 -1.58646 1 0 1 1 0 0 +EDGE2 5880 3161 -0.0129016 -0.997106 -1.56167 1 0 1 1 0 0 +EDGE2 5880 3061 -0.092891 -0.949346 -1.59514 1 0 1 1 0 0 +EDGE2 5880 3060 0.12116 -0.000937437 0.0175757 1 0 1 1 0 0 +EDGE2 5880 3160 -0.0280746 -0.0225264 -3.1627 1 0 1 1 0 0 +EDGE2 5880 5860 -0.00735381 -0.00643613 -0.0109349 1 0 1 1 0 0 +EDGE2 5880 3080 -0.0132063 -0.0742967 -3.13296 1 0 1 1 0 0 +EDGE2 5880 1080 -0.0179139 -0.0389757 -3.14615 1 0 1 1 0 0 +EDGE2 5880 1081 -0.014057 0.93494 1.6123 1 0 1 1 0 0 +EDGE2 5880 5861 0.0894116 0.937059 1.5427 1 0 1 1 0 0 +EDGE2 5880 5859 -0.956723 -0.00532922 0.0329012 1 0 1 1 0 0 +EDGE2 5880 5879 -0.935379 0.0151751 0.00585871 1 0 1 1 0 0 +EDGE2 5880 3059 -0.946056 -0.0139496 0.00682158 1 0 1 1 0 0 +EDGE2 5881 3082 1.07585 -0.0504645 0.00586187 1 0 1 1 0 0 +EDGE2 5881 3162 1.01284 -0.0378522 -0.0293096 1 0 1 1 0 0 +EDGE2 5881 3062 0.999906 -0.0361194 -0.00875857 1 0 1 1 0 0 +EDGE2 5881 3081 -0.100459 0.0220875 0.000240605 1 0 1 1 0 0 +EDGE2 5881 3161 0.0101204 0.0542268 0.00966796 1 0 1 1 0 0 +EDGE2 5881 3061 0.0324983 0.0356843 0.0127988 1 0 1 1 0 0 +EDGE2 5881 3060 -1.00487 0.0329676 1.56346 1 0 1 1 0 0 +EDGE2 5881 3160 -0.988028 -0.0526581 -1.55149 1 0 1 1 0 0 +EDGE2 5881 5860 -1.00906 -0.0358545 1.55991 1 0 1 1 0 0 +EDGE2 5881 5880 -1.07062 -0.0123997 1.56411 1 0 1 1 0 0 +EDGE2 5881 3080 -1.0039 0.0657655 -1.53934 1 0 1 1 0 0 +EDGE2 5881 1080 -0.969322 -0.078424 -1.59878 1 0 1 1 0 0 +EDGE2 5882 3083 1.01797 0.00145688 -0.0274897 1 0 1 1 0 0 +EDGE2 5882 3163 0.932942 -0.0273837 -0.00263323 1 0 1 1 0 0 +EDGE2 5882 3063 0.93326 0.0197177 0.0186728 1 0 1 1 0 0 +EDGE2 5882 3082 0.00792749 -0.0246023 0.0130996 1 0 1 1 0 0 +EDGE2 5882 3162 -0.0357341 0.0792416 0.00434452 1 0 1 1 0 0 +EDGE2 5882 3062 0.0405246 0.0164561 0.00939946 1 0 1 1 0 0 +EDGE2 5882 3081 -1.00717 -0.0375445 0.0119884 1 0 1 1 0 0 +EDGE2 5882 3161 -1.01839 -0.0115731 0.00608877 1 0 1 1 0 0 +EDGE2 5882 5881 -0.930263 0.0045959 -0.00668456 1 0 1 1 0 0 +EDGE2 5882 3061 -0.969998 0.00164784 0.0217645 1 0 1 1 0 0 +EDGE2 5883 3064 1.00391 0.0867076 -0.0338142 1 0 1 1 0 0 +EDGE2 5883 3164 1.00149 0.0752974 -0.00309904 1 0 1 1 0 0 +EDGE2 5883 3084 1.10863 -0.0235787 0.00945568 1 0 1 1 0 0 +EDGE2 5883 3083 -0.00563469 0.0217865 -0.0119227 1 0 1 1 0 0 +EDGE2 5883 3163 0.0104798 -0.0859804 -0.0149393 1 0 1 1 0 0 +EDGE2 5883 3063 0.0208337 -0.0367257 -0.0417356 1 0 1 1 0 0 +EDGE2 5883 3082 -0.980125 0.0228017 0.0303994 1 0 1 1 0 0 +EDGE2 5883 3162 -1.1379 -0.0226273 0.0390922 1 0 1 1 0 0 +EDGE2 5883 5882 -0.995566 0.0259375 0.0013805 1 0 1 1 0 0 +EDGE2 5883 3062 -0.946825 -0.0114992 -0.012244 1 0 1 1 0 0 +EDGE2 5884 3105 1.05302 -0.033479 -3.14927 1 0 1 1 0 0 +EDGE2 5884 3485 1.08951 0.0442988 -3.14085 1 0 1 1 0 0 +EDGE2 5884 5845 1.01033 -0.0147577 -3.17669 1 0 1 1 0 0 +EDGE2 5884 5825 1.04389 -0.0159723 -3.10155 1 0 1 1 0 0 +EDGE2 5884 3145 1.04795 -0.115526 -3.14097 1 0 1 1 0 0 +EDGE2 5884 3165 1.01947 -0.0550297 -0.0399938 1 0 1 1 0 0 +EDGE2 5884 3385 0.997614 -0.0369504 -3.15849 1 0 1 1 0 0 +EDGE2 5884 3125 1.00616 -0.0677575 -3.13712 1 0 1 1 0 0 +EDGE2 5884 1185 1.04252 -0.038066 -3.15461 1 0 1 1 0 0 +EDGE2 5884 3065 0.992692 -0.0382975 0.00841777 1 0 1 1 0 0 +EDGE2 5884 3085 0.903378 -0.0550893 0.00188489 1 0 1 1 0 0 +EDGE2 5884 1165 0.970896 -0.100325 -3.10564 1 0 1 1 0 0 +EDGE2 5884 3064 -0.14848 -0.0208673 -0.00403429 1 0 1 1 0 0 +EDGE2 5884 3164 -0.00616877 0.0536738 0.00501557 1 0 1 1 0 0 +EDGE2 5884 3084 0.0698326 0.0229447 -0.0257836 1 0 1 1 0 0 +EDGE2 5884 3083 -0.985242 -0.0722352 -0.0159732 1 0 1 1 0 0 +EDGE2 5884 3163 -0.981255 0.0947204 -0.025067 1 0 1 1 0 0 +EDGE2 5884 5883 -0.8904 -0.0137939 -0.0107886 1 0 1 1 0 0 +EDGE2 5884 3063 -1.03666 -0.0131044 -0.0107336 1 0 1 1 0 0 +EDGE2 5885 3146 0.018944 0.990923 1.609 1 0 1 1 0 0 +EDGE2 5885 3386 0.00484625 0.957726 1.56867 1 0 1 1 0 0 +EDGE2 5885 3066 -0.0454923 1.00484 1.59263 1 0 1 1 0 0 +EDGE2 5885 3144 1.03324 -0.0628204 -3.12053 1 0 1 1 0 0 +EDGE2 5885 3484 0.919764 0.0634802 -3.14769 1 0 1 1 0 0 +EDGE2 5885 5824 0.947687 -0.0706009 -3.17403 1 0 1 1 0 0 +EDGE2 5885 5844 0.983589 0.00854534 -3.1486 1 0 1 1 0 0 +EDGE2 5885 3384 0.985255 -0.0739725 -3.13077 1 0 1 1 0 0 +EDGE2 5885 1184 0.9358 -0.00993438 -3.1289 1 0 1 1 0 0 +EDGE2 5885 3104 1.06056 0.0850013 -3.14445 1 0 1 1 0 0 +EDGE2 5885 3124 1.02591 -0.0165658 -3.1227 1 0 1 1 0 0 +EDGE2 5885 1164 1.00817 -0.0492453 -3.17394 1 0 1 1 0 0 +EDGE2 5885 3166 0.00907181 -0.995231 -1.58349 1 0 1 1 0 0 +EDGE2 5885 3105 0.0571658 -0.00512851 -3.09884 1 0 1 1 0 0 +EDGE2 5885 3485 -0.110813 -0.0343521 -3.15384 1 0 1 1 0 0 +EDGE2 5885 5845 -0.00655282 0.0715185 -3.13003 1 0 1 1 0 0 +EDGE2 5885 5825 -0.0154937 -0.00762054 -3.13212 1 0 1 1 0 0 +EDGE2 5885 3145 0.0766535 -0.00876101 -3.16107 1 0 1 1 0 0 +EDGE2 5885 3165 -0.0117359 -0.0557764 0.00828921 1 0 1 1 0 0 +EDGE2 5885 3385 -0.0565622 0.045581 -3.15315 1 0 1 1 0 0 +EDGE2 5885 3125 -0.0464584 0.0190091 -3.11325 1 0 1 1 0 0 +EDGE2 5885 1185 0.04624 -0.0412925 -3.14813 1 0 1 1 0 0 +EDGE2 5885 3065 -0.0147208 -0.0720383 -0.0105864 1 0 1 1 0 0 +EDGE2 5885 3085 -0.0419133 0.0233474 0.00641834 1 0 1 1 0 0 +EDGE2 5885 1165 -0.0580939 -0.00833285 -3.14213 1 0 1 1 0 0 +EDGE2 5885 5826 0.012855 -0.912515 -1.60055 1 0 1 1 0 0 +EDGE2 5885 5846 -0.0466384 -0.94148 -1.56608 1 0 1 1 0 0 +EDGE2 5885 3486 -0.0468964 -0.944632 -1.55841 1 0 1 1 0 0 +EDGE2 5885 1166 0.0607415 -1.04314 -1.59444 1 0 1 1 0 0 +EDGE2 5885 3086 0.0596516 -0.983952 -1.57115 1 0 1 1 0 0 +EDGE2 5885 3106 -0.0360414 -1.08609 -1.57502 1 0 1 1 0 0 +EDGE2 5885 3126 0.0191212 -0.966451 -1.53144 1 0 1 1 0 0 +EDGE2 5885 1186 -0.0250838 -0.951002 -1.53244 1 0 1 1 0 0 +EDGE2 5885 3064 -0.937628 0.0196134 0.0167085 1 0 1 1 0 0 +EDGE2 5885 3164 -0.947413 0.0288499 -0.0264355 1 0 1 1 0 0 +EDGE2 5885 5884 -0.944129 -0.0444946 -0.0249114 1 0 1 1 0 0 +EDGE2 5885 3084 -1.04038 0.058773 -0.0119084 1 0 1 1 0 0 +EDGE2 5886 3147 1.00966 0.026183 -0.0161355 1 0 1 1 0 0 +EDGE2 5886 3387 0.9767 -0.0421237 0.00852736 1 0 1 1 0 0 +EDGE2 5886 3067 1.05889 -0.00178432 -0.0275723 1 0 1 1 0 0 +EDGE2 5886 3146 0.0281725 -0.0887476 -0.0174993 1 0 1 1 0 0 +EDGE2 5886 3386 -0.0296272 0.0926074 -0.00464071 1 0 1 1 0 0 +EDGE2 5886 3066 -0.0630094 0.00618731 0.0172847 1 0 1 1 0 0 +EDGE2 5886 3105 -0.961881 0.0831537 1.5675 1 0 1 1 0 0 +EDGE2 5886 3485 -1.00515 0.00482632 1.57111 1 0 1 1 0 0 +EDGE2 5886 5845 -1.00226 0.00494509 1.58166 1 0 1 1 0 0 +EDGE2 5886 5885 -0.948046 -0.0639468 -1.56124 1 0 1 1 0 0 +EDGE2 5886 5825 -0.98116 0.102357 1.61259 1 0 1 1 0 0 +EDGE2 5886 3145 -1.00612 0.0643939 1.62172 1 0 1 1 0 0 +EDGE2 5886 3165 -0.994134 -0.0388104 -1.59046 1 0 1 1 0 0 +EDGE2 5886 3385 -0.941593 0.0184042 1.5876 1 0 1 1 0 0 +EDGE2 5886 3125 -1.03951 0.00531972 1.54752 1 0 1 1 0 0 +EDGE2 5886 1185 -1.03885 -0.0180731 1.58165 1 0 1 1 0 0 +EDGE2 5886 3065 -1.05286 0.0751518 -1.58352 1 0 1 1 0 0 +EDGE2 5886 3085 -1.04252 -0.193636 -1.59984 1 0 1 1 0 0 +EDGE2 5886 1165 -0.969136 0.0290491 1.53451 1 0 1 1 0 0 +EDGE2 5887 3068 1.0073 -0.0223217 0.00479339 1 0 1 1 0 0 +EDGE2 5887 3148 0.990242 0.00453602 0.00525036 1 0 1 1 0 0 +EDGE2 5887 3388 1.06168 0.0554831 0.0104737 1 0 1 1 0 0 +EDGE2 5887 3147 -0.0501975 0.023598 -0.0168035 1 0 1 1 0 0 +EDGE2 5887 3387 0.00829227 -0.0147108 0.0323277 1 0 1 1 0 0 +EDGE2 5887 3067 0.030802 -0.0642954 -0.00388256 1 0 1 1 0 0 +EDGE2 5887 3146 -1.04616 -0.0271891 -0.00603021 1 0 1 1 0 0 +EDGE2 5887 3386 -0.982208 -0.0312929 0.0112962 1 0 1 1 0 0 +EDGE2 5887 5886 -0.985523 -0.0497438 -0.000320234 1 0 1 1 0 0 +EDGE2 5887 3066 -1.14794 0.0375852 -0.0255893 1 0 1 1 0 0 +EDGE2 5888 3149 0.970719 0.0447412 0.000666545 1 0 1 1 0 0 +EDGE2 5888 3389 0.996583 -0.0715544 -0.0230795 1 0 1 1 0 0 +EDGE2 5888 3069 1.04723 -0.075417 -0.00730932 1 0 1 1 0 0 +EDGE2 5888 3068 -0.0314272 -0.0456152 0.0347099 1 0 1 1 0 0 +EDGE2 5888 3148 -0.0772317 -0.0490994 -0.0270402 1 0 1 1 0 0 +EDGE2 5888 3388 -0.0683486 -0.0131655 -0.00651438 1 0 1 1 0 0 +EDGE2 5888 3147 -0.989631 -0.0799932 0.00104836 1 0 1 1 0 0 +EDGE2 5888 5887 -1.02514 0.101734 -0.0341832 1 0 1 1 0 0 +EDGE2 5888 3387 -0.981111 0.0265032 0.036773 1 0 1 1 0 0 +EDGE2 5888 3067 -1.10426 0.0724751 0.000490069 1 0 1 1 0 0 +EDGE2 5889 3070 1.08299 -0.0398351 0.00295314 1 0 1 1 0 0 +EDGE2 5889 3390 0.999994 0.059073 -0.0194307 1 0 1 1 0 0 +EDGE2 5889 3410 0.975042 -0.0806284 -3.09989 1 0 1 1 0 0 +EDGE2 5889 3150 1.01436 0.0260804 -0.0385827 1 0 1 1 0 0 +EDGE2 5889 3149 0.00136014 0.0934796 -0.00373616 1 0 1 1 0 0 +EDGE2 5889 3389 -0.0832218 0.00313097 -0.0051261 1 0 1 1 0 0 +EDGE2 5889 3069 0.073507 -0.0367328 0.0136783 1 0 1 1 0 0 +EDGE2 5889 5888 -0.986963 0.0475924 -0.00664097 1 0 1 1 0 0 +EDGE2 5889 3068 -1.07888 0.079414 -0.0135297 1 0 1 1 0 0 +EDGE2 5889 3148 -0.960205 -0.0412418 -0.0426238 1 0 1 1 0 0 +EDGE2 5889 3388 -0.99888 0.0482661 -0.016384 1 0 1 1 0 0 +EDGE2 5890 3409 0.972005 0.0798969 -3.16476 1 0 1 1 0 0 +EDGE2 5890 3411 0.108688 -1.07615 -1.55517 1 0 1 1 0 0 +EDGE2 5890 3391 -0.0858083 -1.01473 -1.56059 1 0 1 1 0 0 +EDGE2 5890 3070 -0.00409075 0.0317232 0.0212224 1 0 1 1 0 0 +EDGE2 5890 3390 0.00278873 -0.0658532 0.00792799 1 0 1 1 0 0 +EDGE2 5890 3410 -0.0850121 0.0221299 -3.14292 1 0 1 1 0 0 +EDGE2 5890 3150 0.031617 0.0564294 -0.00811026 1 0 1 1 0 0 +EDGE2 5890 5889 -0.936463 0.0574837 0.00587907 1 0 1 1 0 0 +EDGE2 5890 3149 -1.04582 -0.0392446 -0.0085372 1 0 1 1 0 0 +EDGE2 5890 3389 -0.939147 -0.0112168 -0.0268289 1 0 1 1 0 0 +EDGE2 5890 3069 -0.99282 0.0242497 -0.0016073 1 0 1 1 0 0 +EDGE2 5890 3151 0.08474 0.979447 1.55663 1 0 1 1 0 0 +EDGE2 5890 3071 0.0570963 0.991224 1.57605 1 0 1 1 0 0 +EDGE2 5891 3412 0.999689 -0.0239317 0.00037576 1 0 1 1 0 0 +EDGE2 5891 3392 1.00008 0.046025 -0.0317244 1 0 1 1 0 0 +EDGE2 5891 3411 0.0608709 0.0161349 -0.00760813 1 0 1 1 0 0 +EDGE2 5891 3391 -0.0282814 0.0581364 0.00301801 1 0 1 1 0 0 +EDGE2 5891 3070 -1.06972 -0.0705371 1.56177 1 0 1 1 0 0 +EDGE2 5891 3390 -1.03437 -0.0197629 1.5738 1 0 1 1 0 0 +EDGE2 5891 3410 -0.985701 -0.0143083 -1.58129 1 0 1 1 0 0 +EDGE2 5891 5890 -0.883793 0.0587324 1.58063 1 0 1 1 0 0 +EDGE2 5891 3150 -1.03633 0.0294743 1.55642 1 0 1 1 0 0 +EDGE2 5892 3413 0.918912 -0.00770341 -0.0423393 1 0 1 1 0 0 +EDGE2 5892 3393 0.978861 -0.0225362 0.00707184 1 0 1 1 0 0 +EDGE2 5892 3412 -0.0309208 -0.0523449 0.00870268 1 0 1 1 0 0 +EDGE2 5892 3392 0.0167728 -0.0141291 0.0259557 1 0 1 1 0 0 +EDGE2 5892 3411 -0.957364 -0.0263066 0.00664064 1 0 1 1 0 0 +EDGE2 5892 5891 -1.08733 -0.0068822 -0.0138277 1 0 1 1 0 0 +EDGE2 5892 3391 -1.01877 -0.053653 0.0294327 1 0 1 1 0 0 +EDGE2 5893 3414 1.00163 0.0182921 -0.00552372 1 0 1 1 0 0 +EDGE2 5893 3394 1.02815 -0.0584256 -0.000816173 1 0 1 1 0 0 +EDGE2 5893 3413 -0.0935673 0.00483767 -0.0148791 1 0 1 1 0 0 +EDGE2 5893 3393 0.046047 0.065798 0.00664288 1 0 1 1 0 0 +EDGE2 5893 3412 -0.953911 -0.013939 -0.0101542 1 0 1 1 0 0 +EDGE2 5893 5892 -0.950371 -0.0348698 0.0627038 1 0 1 1 0 0 +EDGE2 5893 3392 -0.995314 -0.0313465 0.00115391 1 0 1 1 0 0 +EDGE2 5894 3395 0.964286 0.0439686 0.012128 1 0 1 1 0 0 +EDGE2 5894 3435 1.04089 -0.00669628 -3.11966 1 0 1 1 0 0 +EDGE2 5894 3415 0.892874 -0.0289784 0.0178081 1 0 1 1 0 0 +EDGE2 5894 855 1.04373 0.0613242 -3.16367 1 0 1 1 0 0 +EDGE2 5894 895 0.909862 0.101158 -3.13746 1 0 1 1 0 0 +EDGE2 5894 915 1.01834 -0.098215 -3.16542 1 0 1 1 0 0 +EDGE2 5894 835 1.05927 -0.0429011 -3.13373 1 0 1 1 0 0 +EDGE2 5894 3414 0.0306605 -0.0643315 -0.0338704 1 0 1 1 0 0 +EDGE2 5894 3394 0.0464893 0.0262122 -0.0105657 1 0 1 1 0 0 +EDGE2 5894 3413 -1.00295 -0.0545737 0.00340819 1 0 1 1 0 0 +EDGE2 5894 5893 -1.02911 -0.0476606 0.00818703 1 0 1 1 0 0 +EDGE2 5894 3393 -0.985774 -0.0177065 -0.0324499 1 0 1 1 0 0 +EDGE2 5895 3395 0.0328747 0.0180143 -0.0334215 1 0 1 1 0 0 +EDGE2 5895 3396 -0.0462655 1.06849 1.58202 1 0 1 1 0 0 +EDGE2 5895 916 0.00107568 0.987155 1.5262 1 0 1 1 0 0 +EDGE2 5895 3434 1.05172 -0.0752918 -3.15806 1 0 1 1 0 0 +EDGE2 5895 894 0.952129 -0.0166856 -3.13938 1 0 1 1 0 0 +EDGE2 5895 914 0.985655 -0.0475489 -3.12632 1 0 1 1 0 0 +EDGE2 5895 834 0.971902 -0.0839196 -3.18767 1 0 1 1 0 0 +EDGE2 5895 854 0.967016 -0.0324339 -3.1613 1 0 1 1 0 0 +EDGE2 5895 3435 0.0464604 -0.00431924 -3.17027 1 0 1 1 0 0 +EDGE2 5895 3415 0.0282362 -0.0455433 0.0337948 1 0 1 1 0 0 +EDGE2 5895 855 -0.0908487 -0.08693 -3.16575 1 0 1 1 0 0 +EDGE2 5895 895 -0.0178526 -0.0230808 -3.16014 1 0 1 1 0 0 +EDGE2 5895 915 -0.101118 -0.0603039 -3.15808 1 0 1 1 0 0 +EDGE2 5895 835 -0.0699059 0.046786 -3.1414 1 0 1 1 0 0 +EDGE2 5895 3414 -0.961732 -0.0260122 -0.0172715 1 0 1 1 0 0 +EDGE2 5895 5894 -0.928443 -0.0144001 -0.00233628 1 0 1 1 0 0 +EDGE2 5895 3394 -1.04123 -0.085502 -0.00327231 1 0 1 1 0 0 +EDGE2 5895 3436 -0.0176503 -0.99901 -1.57265 1 0 1 1 0 0 +EDGE2 5895 856 -0.0177735 -0.992452 -1.58021 1 0 1 1 0 0 +EDGE2 5895 896 -0.0219932 -0.95303 -1.56384 1 0 1 1 0 0 +EDGE2 5895 3416 -0.038791 -0.99389 -1.55619 1 0 1 1 0 0 +EDGE2 5895 836 -0.0520236 -0.971541 -1.56222 1 0 1 1 0 0 +EDGE2 5896 3395 -1.00429 -0.0573778 -1.5228 1 0 1 1 0 0 +EDGE2 5896 917 0.999581 0.0409856 -0.021031 1 0 1 1 0 0 +EDGE2 5896 3397 1.03248 0.0122743 -0.00206932 1 0 1 1 0 0 +EDGE2 5896 3396 0.11328 0.0242551 0.00383213 1 0 1 1 0 0 +EDGE2 5896 916 0.0403305 0.0145918 0.0020115 1 0 1 1 0 0 +EDGE2 5896 3435 -1.00756 0.092279 1.53966 1 0 1 1 0 0 +EDGE2 5896 5895 -1.01496 -0.0595422 -1.56002 1 0 1 1 0 0 +EDGE2 5896 3415 -1.02685 -0.00542749 -1.55735 1 0 1 1 0 0 +EDGE2 5896 855 -0.94183 -0.0422458 1.56539 1 0 1 1 0 0 +EDGE2 5896 895 -0.994706 0.0840689 1.56604 1 0 1 1 0 0 +EDGE2 5896 915 -1.00959 0.07571 1.57391 1 0 1 1 0 0 +EDGE2 5896 835 -1.01622 0.120725 1.58153 1 0 1 1 0 0 +EDGE2 5897 918 0.880801 0.0623507 9.00877e-05 1 0 1 1 0 0 +EDGE2 5897 3398 1.00144 -0.0164549 0.0305174 1 0 1 1 0 0 +EDGE2 5897 917 0.0443378 -0.0266231 0.0136208 1 0 1 1 0 0 +EDGE2 5897 3397 0.025606 -0.0146116 -0.0191851 1 0 1 1 0 0 +EDGE2 5897 3396 -0.948574 0.0266711 0.0113974 1 0 1 1 0 0 +EDGE2 5897 5896 -1.00069 -0.0418802 0.021279 1 0 1 1 0 0 +EDGE2 5897 916 -0.982059 -0.000782588 -0.0313386 1 0 1 1 0 0 +EDGE2 5898 919 1.06046 -0.00829068 0.0270632 1 0 1 1 0 0 +EDGE2 5898 3399 0.984832 0.0099123 0.0234244 1 0 1 1 0 0 +EDGE2 5898 918 0.044975 0.0220932 0.0249076 1 0 1 1 0 0 +EDGE2 5898 3398 -0.0436779 -0.00844181 0.0184924 1 0 1 1 0 0 +EDGE2 5898 917 -0.934523 -0.0181749 -0.0270486 1 0 1 1 0 0 +EDGE2 5898 3397 -1.04455 0.0599953 -0.0403546 1 0 1 1 0 0 +EDGE2 5898 5897 -1.04339 -0.0171327 0.00401612 1 0 1 1 0 0 +EDGE2 5899 920 0.953232 -0.00554041 -0.0263598 1 0 1 1 0 0 +EDGE2 5899 3400 1.0187 -0.0881881 0.0165385 1 0 1 1 0 0 +EDGE2 5899 680 1.00739 0.0371848 -3.10347 1 0 1 1 0 0 +EDGE2 5899 919 -0.00500479 0.0579415 0.00411693 1 0 1 1 0 0 +EDGE2 5899 3399 0.0580466 0.0196906 -0.00458826 1 0 1 1 0 0 +EDGE2 5899 918 -0.978454 -0.0335235 0.0328199 1 0 1 1 0 0 +EDGE2 5899 3398 -0.98131 -0.0624656 0.0174176 1 0 1 1 0 0 +EDGE2 5899 5898 -1.01965 -0.0226319 -0.0187115 1 0 1 1 0 0 +EDGE2 5900 921 -0.0675098 0.946493 1.56536 1 0 1 1 0 0 +EDGE2 5900 679 0.872847 0.0171644 -3.12166 1 0 1 1 0 0 +EDGE2 5900 681 0.0273273 -1.03632 -1.55173 1 0 1 1 0 0 +EDGE2 5900 920 -0.0489079 0.0724373 0.00491812 1 0 1 1 0 0 +EDGE2 5900 3400 0.0668999 -0.044265 -0.0150805 1 0 1 1 0 0 +EDGE2 5900 680 -0.0111889 0.0501518 -3.12689 1 0 1 1 0 0 +EDGE2 5900 3401 -0.0284158 0.99352 1.62396 1 0 1 1 0 0 +EDGE2 5900 5899 -0.919756 -0.0108871 -0.0260771 1 0 1 1 0 0 +EDGE2 5900 919 -0.995236 0.0710838 -0.032049 1 0 1 1 0 0 +EDGE2 5900 3399 -0.912642 -0.0635976 0.0115665 1 0 1 1 0 0 +EDGE2 5901 681 0.0189811 -0.0328852 -0.0013056 1 0 1 1 0 0 +EDGE2 5901 682 0.896963 -0.00748104 -0.0074836 1 0 1 1 0 0 +EDGE2 5901 5900 -1.0171 -0.0370982 1.56303 1 0 1 1 0 0 +EDGE2 5901 920 -0.973191 -0.0279207 1.58728 1 0 1 1 0 0 +EDGE2 5901 3400 -0.941244 0.0520882 1.54124 1 0 1 1 0 0 +EDGE2 5901 680 -0.981596 0.0235941 -1.55397 1 0 1 1 0 0 +EDGE2 5902 681 -1.00965 0.021303 0.0129647 1 0 1 1 0 0 +EDGE2 5902 683 0.997873 -0.0355448 0.00298161 1 0 1 1 0 0 +EDGE2 5902 682 0.0297829 0.0287232 -0.0142657 1 0 1 1 0 0 +EDGE2 5902 5901 -0.879135 0.00386713 0.00673905 1 0 1 1 0 0 +EDGE2 5903 684 0.865321 -0.0651834 -0.00465009 1 0 1 1 0 0 +EDGE2 5903 5902 -0.991997 -0.0522398 -0.0135333 1 0 1 1 0 0 +EDGE2 5903 683 -0.0816201 0.0283733 0.0191963 1 0 1 1 0 0 +EDGE2 5903 682 -0.974633 -0.0990649 -0.000671409 1 0 1 1 0 0 +EDGE2 5904 885 0.92142 -0.0172342 -3.16563 1 0 1 1 0 0 +EDGE2 5904 685 1.09773 -0.00443154 0.020808 1 0 1 1 0 0 +EDGE2 5904 684 0.0360188 0.0815948 -0.0139217 1 0 1 1 0 0 +EDGE2 5904 683 -1.0539 -0.075001 -0.0140808 1 0 1 1 0 0 +EDGE2 5904 5903 -1.07085 -0.0810238 -0.00401934 1 0 1 1 0 0 +EDGE2 5905 884 1.01095 0.127106 -3.12562 1 0 1 1 0 0 +EDGE2 5905 885 -0.0534073 -0.102067 -3.1326 1 0 1 1 0 0 +EDGE2 5905 685 -0.000684469 -0.0379002 -0.0244542 1 0 1 1 0 0 +EDGE2 5905 684 -0.975823 0.00903269 -0.0058318 1 0 1 1 0 0 +EDGE2 5905 5904 -0.982948 -0.0439104 0.0108565 1 0 1 1 0 0 +EDGE2 5905 686 0.0145297 -0.923266 -1.61743 1 0 1 1 0 0 +EDGE2 5905 886 0.0242972 -1.00225 -1.58731 1 0 1 1 0 0 +EDGE2 5906 5905 -1.051 -0.0306942 -1.57717 1 0 1 1 0 0 +EDGE2 5906 885 -1.02692 -0.028823 1.57937 1 0 1 1 0 0 +EDGE2 5906 685 -1.01093 0.0258502 -1.59529 1 0 1 1 0 0 +EDGE2 5907 5906 -1.04038 0.0225394 -0.00393698 1 0 1 1 0 0 +EDGE2 5908 5907 -1.03209 -0.0579571 0.0448676 1 0 1 1 0 0 +EDGE2 5909 5908 -1.01387 -0.03424 -0.0020222 1 0 1 1 0 0 +EDGE2 5910 5909 -0.957992 0.0211762 -0.0151598 1 0 1 1 0 0 +EDGE2 5911 5910 -1.00887 -0.0354858 1.59413 1 0 1 1 0 0 +EDGE2 5912 5911 -1.02804 0.00651606 0.0273263 1 0 1 1 0 0 +EDGE2 5913 5912 -1.03976 -0.0120864 -0.0152428 1 0 1 1 0 0 +EDGE2 5914 5913 -1.04071 -0.0631845 -0.0133238 1 0 1 1 0 0 +EDGE2 5915 5914 -1.00217 -0.0326529 -2.99029e-05 1 0 1 1 0 0 +EDGE2 5916 5915 -0.924225 -0.00102355 -1.594 1 0 1 1 0 0 +EDGE2 5917 5916 -0.959631 -0.0118017 0.0143942 1 0 1 1 0 0 +EDGE2 5918 5917 -1.04716 0.0843496 -0.00350692 1 0 1 1 0 0 +EDGE2 5919 620 0.938054 -0.0774085 -3.12151 1 0 1 1 0 0 +EDGE2 5919 5918 -1.09618 0.0415552 -0.0054246 1 0 1 1 0 0 +EDGE2 5920 620 0.0723999 -0.0513147 -3.17198 1 0 1 1 0 0 +EDGE2 5920 619 1.06513 0.0400474 -3.12987 1 0 1 1 0 0 +EDGE2 5920 621 0.0138969 1.00726 1.58413 1 0 1 1 0 0 +EDGE2 5920 5919 -1.01581 -0.116778 0.018051 1 0 1 1 0 0 +EDGE2 5921 620 -1.02328 -0.00146608 1.5566 1 0 1 1 0 0 +EDGE2 5921 5920 -0.964433 0.0277758 -1.55083 1 0 1 1 0 0 +EDGE2 5921 622 0.951249 0.117578 0.0195252 1 0 1 1 0 0 +EDGE2 5921 621 0.00829327 -0.0738574 0.00118269 1 0 1 1 0 0 +EDGE2 5922 622 0.0276404 -0.000175274 0.00101497 1 0 1 1 0 0 +EDGE2 5922 621 -1.06535 -0.063147 -0.0147562 1 0 1 1 0 0 +EDGE2 5922 5921 -0.984644 -0.00487596 0.0090733 1 0 1 1 0 0 +EDGE2 5922 623 0.925284 -0.0158849 -0.0186244 1 0 1 1 0 0 +EDGE2 5923 622 -0.981962 -0.0384827 -0.0140181 1 0 1 1 0 0 +EDGE2 5923 5922 -1.01286 -0.028017 0.0180841 1 0 1 1 0 0 +EDGE2 5923 623 0.0519298 0.016032 -0.0443051 1 0 1 1 0 0 +EDGE2 5923 624 1.0426 -0.028546 0.0175727 1 0 1 1 0 0 +EDGE2 5924 623 -1.0323 0.0808865 0.0235028 1 0 1 1 0 0 +EDGE2 5924 5923 -1.11001 -0.087064 -0.00739996 1 0 1 1 0 0 +EDGE2 5924 624 -0.0253777 0.0444354 -0.024642 1 0 1 1 0 0 +EDGE2 5924 625 1.007 -0.0257162 -0.0190258 1 0 1 1 0 0 +EDGE2 5924 645 1.00309 -0.124878 -3.16809 1 0 1 1 0 0 +EDGE2 5925 5924 -1.08805 0.0419754 0.00722213 1 0 1 1 0 0 +EDGE2 5925 624 -1.08191 -0.0402773 -0.0256462 1 0 1 1 0 0 +EDGE2 5925 626 -0.0727044 -0.976271 -1.60424 1 0 1 1 0 0 +EDGE2 5925 646 0.0352533 -0.991314 -1.57019 1 0 1 1 0 0 +EDGE2 5925 644 1.0209 0.0265292 -3.13849 1 0 1 1 0 0 +EDGE2 5925 625 0.0263637 0.0588904 0.00271328 1 0 1 1 0 0 +EDGE2 5925 645 -0.0131177 -0.0574815 -3.16278 1 0 1 1 0 0 +EDGE2 5926 5925 -0.969361 0.0360143 -1.55539 1 0 1 1 0 0 +EDGE2 5926 625 -0.922758 0.0365378 -1.5754 1 0 1 1 0 0 +EDGE2 5926 645 -0.999339 -0.0682909 1.57158 1 0 1 1 0 0 +EDGE2 5927 5926 -0.979918 0.0075476 -0.0196731 1 0 1 1 0 0 +EDGE2 5928 5927 -0.922871 -0.0374551 -0.028443 1 0 1 1 0 0 +EDGE2 5929 5928 -1.08958 -0.0581733 0.0112366 1 0 1 1 0 0 +EDGE2 5929 5910 0.939307 0.0366444 -3.14145 1 0 1 1 0 0 +EDGE2 5930 5929 -0.955272 -0.067741 -0.0157952 1 0 1 1 0 0 +EDGE2 5930 5911 0.0100238 1.01024 1.58732 1 0 1 1 0 0 +EDGE2 5930 5910 0.0384654 -0.0594792 -3.13169 1 0 1 1 0 0 +EDGE2 5930 5909 1.01965 -0.0131708 -3.15349 1 0 1 1 0 0 +EDGE2 5931 5912 0.982565 0.0416632 -0.00909659 1 0 1 1 0 0 +EDGE2 5931 5911 0.0226031 0.101011 0.0105881 1 0 1 1 0 0 +EDGE2 5931 5910 -1.05537 0.0051187 1.57179 1 0 1 1 0 0 +EDGE2 5931 5930 -1.01342 0.0402112 -1.55978 1 0 1 1 0 0 +EDGE2 5932 5912 -0.037103 0.0158274 -0.00159061 1 0 1 1 0 0 +EDGE2 5932 5913 0.994934 -0.0602802 -0.0133772 1 0 1 1 0 0 +EDGE2 5932 5911 -1.07065 0.0821218 0.00152833 1 0 1 1 0 0 +EDGE2 5932 5931 -1.02269 0.0116274 0.0335306 1 0 1 1 0 0 +EDGE2 5933 5914 0.997924 0.0804017 0.00236046 1 0 1 1 0 0 +EDGE2 5933 5912 -0.965695 -0.053442 0.00814557 1 0 1 1 0 0 +EDGE2 5933 5913 0.072862 -0.0275469 -0.00225074 1 0 1 1 0 0 +EDGE2 5933 5932 -0.912235 -0.055793 0.0188456 1 0 1 1 0 0 +EDGE2 5934 5915 1.10098 -0.0207993 -0.0136575 1 0 1 1 0 0 +EDGE2 5934 5914 -0.00476542 0.0596179 0.0145739 1 0 1 1 0 0 +EDGE2 5934 5913 -1.03445 -0.00233718 0.00716518 1 0 1 1 0 0 +EDGE2 5934 5933 -1.05437 -0.00222747 -0.00603623 1 0 1 1 0 0 +EDGE2 5935 5915 -0.032346 -0.0247939 0.0209879 1 0 1 1 0 0 +EDGE2 5935 5916 0.0172092 0.996942 1.54856 1 0 1 1 0 0 +EDGE2 5935 5934 -1.03089 -0.0146903 -0.00263981 1 0 1 1 0 0 +EDGE2 5935 5914 -0.942951 -0.00874583 -0.000150406 1 0 1 1 0 0 +EDGE2 5936 5915 -1.0362 -0.031792 1.60643 1 0 1 1 0 0 +EDGE2 5936 5935 -1.01659 -0.0177696 1.55823 1 0 1 1 0 0 +EDGE2 5937 5936 -0.990474 0.0265172 0.00662007 1 0 1 1 0 0 +EDGE2 5938 5937 -0.912362 -0.0740271 0.00397294 1 0 1 1 0 0 +EDGE2 5939 5938 -1.09266 -0.0634145 -0.0349291 1 0 1 1 0 0 +EDGE2 5939 880 1.03176 -0.0187472 -3.16588 1 0 1 1 0 0 +EDGE2 5940 5939 -1.01027 0.0501664 0.0100461 1 0 1 1 0 0 +EDGE2 5940 880 -0.0727593 0.00263132 -3.13097 1 0 1 1 0 0 +EDGE2 5940 879 0.93958 0.0084993 -3.17518 1 0 1 1 0 0 +EDGE2 5940 881 0.0420091 -0.91425 -1.58061 1 0 1 1 0 0 +EDGE2 5941 880 -1.0338 0.103663 -1.5681 1 0 1 1 0 0 +EDGE2 5941 5940 -0.97058 0.0526229 1.6013 1 0 1 1 0 0 +EDGE2 5941 881 0.0377429 0.0146688 0.00256537 1 0 1 1 0 0 +EDGE2 5941 882 0.886874 0.0288947 0.0228717 1 0 1 1 0 0 +EDGE2 5942 883 0.867219 -0.0353765 0.030595 1 0 1 1 0 0 +EDGE2 5942 881 -1.06684 0.00416655 0.041804 1 0 1 1 0 0 +EDGE2 5942 5941 -0.975405 0.0816639 -0.00928083 1 0 1 1 0 0 +EDGE2 5942 882 0.000213308 0.0744123 0.00513338 1 0 1 1 0 0 +EDGE2 5943 884 1.00456 -0.00212935 0.027458 1 0 1 1 0 0 +EDGE2 5943 883 0.0227799 -0.0449385 0.0060875 1 0 1 1 0 0 +EDGE2 5943 5942 -0.958043 0.0137492 -0.0262263 1 0 1 1 0 0 +EDGE2 5943 882 -0.957186 -0.05967 0.00280463 1 0 1 1 0 0 +EDGE2 5944 884 -0.0635228 0.0409927 -0.00964226 1 0 1 1 0 0 +EDGE2 5944 883 -0.954664 0.0365062 -0.0248451 1 0 1 1 0 0 +EDGE2 5944 5943 -1.02241 0.0283486 0.0276731 1 0 1 1 0 0 +EDGE2 5944 5905 1.02196 0.0828328 -3.12277 1 0 1 1 0 0 +EDGE2 5944 885 1.01124 -0.108543 0.0163976 1 0 1 1 0 0 +EDGE2 5944 685 1.03523 0.0463609 -3.12886 1 0 1 1 0 0 +EDGE2 5945 884 -0.988189 -0.0564218 0.0330737 1 0 1 1 0 0 +EDGE2 5945 5906 0.0110744 -0.933292 -1.62168 1 0 1 1 0 0 +EDGE2 5945 5944 -1.05635 0.0905014 -0.00622321 1 0 1 1 0 0 +EDGE2 5945 5905 0.0207746 -0.0106923 -3.16837 1 0 1 1 0 0 +EDGE2 5945 885 0.00655757 -0.0289798 0.02697 1 0 1 1 0 0 +EDGE2 5945 685 0.00308906 0.0583272 -3.13767 1 0 1 1 0 0 +EDGE2 5945 684 0.916652 0.0458217 -3.13807 1 0 1 1 0 0 +EDGE2 5945 5904 0.929081 0.0150403 -3.15989 1 0 1 1 0 0 +EDGE2 5945 686 0.0127032 0.972531 1.54579 1 0 1 1 0 0 +EDGE2 5945 886 -0.0900532 0.968727 1.58236 1 0 1 1 0 0 +EDGE2 5946 5945 -0.939732 -0.0283338 -1.60031 1 0 1 1 0 0 +EDGE2 5946 5905 -1.01179 0.0118702 1.57353 1 0 1 1 0 0 +EDGE2 5946 885 -0.917403 -0.0276702 -1.56516 1 0 1 1 0 0 +EDGE2 5946 685 -1.097 0.0373746 1.56955 1 0 1 1 0 0 +EDGE2 5946 686 -0.0295901 -0.0314988 -0.00955872 1 0 1 1 0 0 +EDGE2 5946 886 -0.0465953 -0.0154934 0.0109526 1 0 1 1 0 0 +EDGE2 5946 687 1.02259 -0.0849077 -0.0233537 1 0 1 1 0 0 +EDGE2 5946 887 0.974316 -0.0535125 0.0174622 1 0 1 1 0 0 +EDGE2 5947 5946 -1.02436 -0.00180978 0.00453878 1 0 1 1 0 0 +EDGE2 5947 686 -1.01931 0.0377596 -0.0129802 1 0 1 1 0 0 +EDGE2 5947 886 -1.04567 0.018789 -0.0111921 1 0 1 1 0 0 +EDGE2 5947 888 1.0276 0.00973582 -0.0211338 1 0 1 1 0 0 +EDGE2 5947 687 -0.0226886 0.0330999 0.00541486 1 0 1 1 0 0 +EDGE2 5947 887 -0.100188 -0.0175646 -0.0121616 1 0 1 1 0 0 +EDGE2 5947 688 1.01491 -0.0830191 0.00927296 1 0 1 1 0 0 +EDGE2 5948 5947 -1.03312 0.103778 -0.00261084 1 0 1 1 0 0 +EDGE2 5948 888 0.0199207 0.0394359 -0.0160697 1 0 1 1 0 0 +EDGE2 5948 687 -0.9791 -0.00291143 0.017083 1 0 1 1 0 0 +EDGE2 5948 887 -0.935095 0.0999264 -0.0122603 1 0 1 1 0 0 +EDGE2 5948 688 0.044282 0.0364098 0.00280916 1 0 1 1 0 0 +EDGE2 5948 689 0.928204 0.0561959 -0.00942968 1 0 1 1 0 0 +EDGE2 5948 889 1.13385 0.0700248 -0.0024189 1 0 1 1 0 0 +EDGE2 5949 5948 -1.06151 0.00331545 -0.00231026 1 0 1 1 0 0 +EDGE2 5949 690 1.01512 -0.0118375 -0.01491 1 0 1 1 0 0 +EDGE2 5949 888 -0.997256 -0.0400834 -0.0324894 1 0 1 1 0 0 +EDGE2 5949 688 -0.988429 0.0032121 0.0243052 1 0 1 1 0 0 +EDGE2 5949 910 1.01436 0.0482001 -3.134 1 0 1 1 0 0 +EDGE2 5949 3450 0.968656 0.0749874 -3.119 1 0 1 1 0 0 +EDGE2 5949 689 0.00151211 -0.0205218 -0.0186154 1 0 1 1 0 0 +EDGE2 5949 889 -0.010115 0.0344776 0.000978716 1 0 1 1 0 0 +EDGE2 5949 3430 1.04522 0.0150856 -3.1383 1 0 1 1 0 0 +EDGE2 5949 850 1.02824 0.0566988 -3.15078 1 0 1 1 0 0 +EDGE2 5949 870 0.862233 0.0384214 -3.15062 1 0 1 1 0 0 +EDGE2 5949 890 1.03946 -0.0751727 -0.00122273 1 0 1 1 0 0 +EDGE2 5949 830 1.03697 0.0755708 -3.13682 1 0 1 1 0 0 +EDGE2 5950 5949 -0.927515 0.00506964 -0.0135312 1 0 1 1 0 0 +EDGE2 5950 691 0.0960983 0.954523 1.5608 1 0 1 1 0 0 +EDGE2 5950 871 -0.0347564 0.980485 1.56961 1 0 1 1 0 0 +EDGE2 5950 3451 -0.170676 1.01828 1.58224 1 0 1 1 0 0 +EDGE2 5950 690 0.0714347 0.0428394 -0.0232971 1 0 1 1 0 0 +EDGE2 5950 910 -0.0381429 -0.0098176 -3.14507 1 0 1 1 0 0 +EDGE2 5950 3450 0.0102839 0.0100071 -3.14271 1 0 1 1 0 0 +EDGE2 5950 689 -0.986619 0.043831 -0.0235029 1 0 1 1 0 0 +EDGE2 5950 889 -1.01094 -0.00779836 -0.0129408 1 0 1 1 0 0 +EDGE2 5950 3430 0.0329024 -0.0354282 -3.1678 1 0 1 1 0 0 +EDGE2 5950 850 -0.0109704 -0.0193521 -3.13502 1 0 1 1 0 0 +EDGE2 5950 870 -0.0324354 0.0483692 -3.12814 1 0 1 1 0 0 +EDGE2 5950 890 -0.119042 -0.0119744 0.019555 1 0 1 1 0 0 +EDGE2 5950 830 -0.0810725 0.0118259 -3.13669 1 0 1 1 0 0 +EDGE2 5950 851 0.097199 -0.896365 -1.56164 1 0 1 1 0 0 +EDGE2 5950 911 0.00696995 -0.952887 -1.57379 1 0 1 1 0 0 +EDGE2 5950 3431 -0.0432859 -1.07825 -1.53091 1 0 1 1 0 0 +EDGE2 5950 891 0.003971 -1.01532 -1.58573 1 0 1 1 0 0 +EDGE2 5950 831 0.0769814 -0.90397 -1.57783 1 0 1 1 0 0 +EDGE2 5950 869 0.980101 -0.0449626 -3.14973 1 0 1 1 0 0 +EDGE2 5950 3429 0.864703 0.0867734 -3.14668 1 0 1 1 0 0 +EDGE2 5950 3449 1.0398 0.019846 -3.14085 1 0 1 1 0 0 +EDGE2 5950 909 0.976294 0.074859 -3.12645 1 0 1 1 0 0 +EDGE2 5950 829 0.982735 -0.0631485 -3.13698 1 0 1 1 0 0 +EDGE2 5950 849 0.953935 0.00653141 -3.1768 1 0 1 1 0 0 +EDGE2 5951 872 0.976064 -0.0769624 -0.00135381 1 0 1 1 0 0 +EDGE2 5951 3452 0.980221 0.0197733 -0.0104233 1 0 1 1 0 0 +EDGE2 5951 692 1.02876 0.0587242 0.0189463 1 0 1 1 0 0 +EDGE2 5951 691 -0.0216259 0.00142575 0.00083627 1 0 1 1 0 0 +EDGE2 5951 871 0.0344424 -0.089991 -0.0059455 1 0 1 1 0 0 +EDGE2 5951 3451 -0.0423143 -0.0668279 -0.0291241 1 0 1 1 0 0 +EDGE2 5951 5950 -0.882118 -0.0583937 -1.60142 1 0 1 1 0 0 +EDGE2 5951 690 -1.03588 -0.0214209 -1.61588 1 0 1 1 0 0 +EDGE2 5951 910 -1.06925 0.0187523 1.59033 1 0 1 1 0 0 +EDGE2 5951 3450 -0.993378 -0.0110955 1.56016 1 0 1 1 0 0 +EDGE2 5951 3430 -1.14842 0.0348877 1.54234 1 0 1 1 0 0 +EDGE2 5951 850 -0.960346 0.0559021 1.58378 1 0 1 1 0 0 +EDGE2 5951 870 -1.0152 -0.00360096 1.56666 1 0 1 1 0 0 +EDGE2 5951 890 -1.00427 0.0720603 -1.58901 1 0 1 1 0 0 +EDGE2 5951 830 -0.990149 0.0442766 1.59106 1 0 1 1 0 0 +EDGE2 5952 5951 -0.970075 0.012954 -0.0366674 1 0 1 1 0 0 +EDGE2 5952 693 1.09065 0.0182135 0.0197498 1 0 1 1 0 0 +EDGE2 5952 3453 0.9958 0.00334884 -0.00143834 1 0 1 1 0 0 +EDGE2 5952 873 0.99489 -0.00426179 0.0145116 1 0 1 1 0 0 +EDGE2 5952 872 -0.0561385 0.0591018 -0.00759865 1 0 1 1 0 0 +EDGE2 5952 3452 0.0682752 -0.062486 0.0234156 1 0 1 1 0 0 +EDGE2 5952 692 0.1001 0.106014 0.0134377 1 0 1 1 0 0 +EDGE2 5952 691 -1.04271 0.00417752 -0.0448014 1 0 1 1 0 0 +EDGE2 5952 871 -0.988942 0.0244252 0.00647223 1 0 1 1 0 0 +EDGE2 5952 3451 -1.04817 0.0106911 -0.0456981 1 0 1 1 0 0 +EDGE2 5953 693 0.0804374 -0.0874708 -0.0031647 1 0 1 1 0 0 +EDGE2 5953 874 1.01001 -0.0699433 -0.0234443 1 0 1 1 0 0 +EDGE2 5953 3454 0.948825 -0.108026 0.00803057 1 0 1 1 0 0 +EDGE2 5953 694 0.953927 0.0329262 0.0282251 1 0 1 1 0 0 +EDGE2 5953 3453 -0.00391265 -0.0173747 0.0159193 1 0 1 1 0 0 +EDGE2 5953 873 -0.0374805 -0.0627645 -0.0135886 1 0 1 1 0 0 +EDGE2 5953 872 -0.991088 0.000738093 0.00718808 1 0 1 1 0 0 +EDGE2 5953 5952 -1.01192 0.0373032 -0.000425876 1 0 1 1 0 0 +EDGE2 5953 3452 -1.00161 -0.0193841 0.0400832 1 0 1 1 0 0 +EDGE2 5953 692 -0.978273 -0.0291134 0.0154972 1 0 1 1 0 0 +EDGE2 5954 3455 1.0428 -0.0713197 0.0285474 1 0 1 1 0 0 +EDGE2 5954 795 0.958105 0.0131143 -3.12714 1 0 1 1 0 0 +EDGE2 5954 875 0.958873 0.00694204 0.0220398 1 0 1 1 0 0 +EDGE2 5954 3335 1.01099 -0.0374768 -3.14262 1 0 1 1 0 0 +EDGE2 5954 3355 0.927766 -0.0489228 -3.1163 1 0 1 1 0 0 +EDGE2 5954 815 1.02866 -0.0429755 -3.17487 1 0 1 1 0 0 +EDGE2 5954 755 0.987821 -0.0177441 -3.15489 1 0 1 1 0 0 +EDGE2 5954 775 0.924192 0.017038 -3.11745 1 0 1 1 0 0 +EDGE2 5954 695 1.02001 -0.00249363 -0.00858843 1 0 1 1 0 0 +EDGE2 5954 693 -0.95068 0.0228743 0.0274932 1 0 1 1 0 0 +EDGE2 5954 874 0.0381326 0.092716 -0.0150609 1 0 1 1 0 0 +EDGE2 5954 3454 0.0356257 -0.0750818 -0.000714692 1 0 1 1 0 0 +EDGE2 5954 694 0.0474798 0.0176284 0.00361778 1 0 1 1 0 0 +EDGE2 5954 3453 -0.957759 -0.127269 0.0556003 1 0 1 1 0 0 +EDGE2 5954 5953 -0.9263 -0.0181661 0.0399205 1 0 1 1 0 0 +EDGE2 5954 873 -0.995566 -0.0180504 -0.00432859 1 0 1 1 0 0 +EDGE2 5955 876 -0.0458966 0.951655 1.55837 1 0 1 1 0 0 +EDGE2 5955 3455 -0.00345734 -0.0104395 -0.00455498 1 0 1 1 0 0 +EDGE2 5955 774 0.971934 -0.0218036 -3.1144 1 0 1 1 0 0 +EDGE2 5955 814 0.883715 -0.0231034 -3.1245 1 0 1 1 0 0 +EDGE2 5955 3334 1.01703 0.0786321 -3.12401 1 0 1 1 0 0 +EDGE2 5955 3354 1.03851 -0.0408588 -3.13849 1 0 1 1 0 0 +EDGE2 5955 794 1.09135 0.0710799 -3.13062 1 0 1 1 0 0 +EDGE2 5955 754 0.961377 -0.00375529 -3.16311 1 0 1 1 0 0 +EDGE2 5955 795 0.0397547 0.0404397 -3.10566 1 0 1 1 0 0 +EDGE2 5955 875 -0.00987845 0.0381429 0.0116467 1 0 1 1 0 0 +EDGE2 5955 3335 -0.0140941 0.0188838 -3.10967 1 0 1 1 0 0 +EDGE2 5955 3355 -0.0196234 -0.0893561 -3.13507 1 0 1 1 0 0 +EDGE2 5955 815 0.0395326 0.0305638 -3.12432 1 0 1 1 0 0 +EDGE2 5955 755 -0.0220174 0.0194328 -3.14273 1 0 1 1 0 0 +EDGE2 5955 775 0.00680155 -0.0447327 -3.16589 1 0 1 1 0 0 +EDGE2 5955 695 0.0210298 -0.00418837 -0.0113478 1 0 1 1 0 0 +EDGE2 5955 874 -1.05532 0.000867907 -0.00296919 1 0 1 1 0 0 +EDGE2 5955 3454 -0.953266 0.024459 -0.00407478 1 0 1 1 0 0 +EDGE2 5955 5954 -1.00413 0.0160493 0.0123519 1 0 1 1 0 0 +EDGE2 5955 694 -1.06235 0.0320623 0.0165496 1 0 1 1 0 0 +EDGE2 5955 796 -0.00986416 -1.1228 -1.58633 1 0 1 1 0 0 +EDGE2 5955 3336 -0.0217295 -1.05157 -1.55505 1 0 1 1 0 0 +EDGE2 5955 3356 -0.0123395 -1.01259 -1.58787 1 0 1 1 0 0 +EDGE2 5955 3456 -0.0322387 -0.945682 -1.57876 1 0 1 1 0 0 +EDGE2 5955 816 -0.0625269 -0.98541 -1.5577 1 0 1 1 0 0 +EDGE2 5955 696 -0.0481332 -0.934463 -1.58029 1 0 1 1 0 0 +EDGE2 5955 756 -0.00335837 -1.09139 -1.57003 1 0 1 1 0 0 +EDGE2 5955 776 -0.0162808 -1.1046 -1.53402 1 0 1 1 0 0 +EDGE2 5956 877 0.912192 0.025313 -0.00504981 1 0 1 1 0 0 +EDGE2 5956 876 -0.0699894 -0.0344092 -0.0064568 1 0 1 1 0 0 +EDGE2 5956 3455 -1.05531 0.0330113 -1.59841 1 0 1 1 0 0 +EDGE2 5956 5955 -0.925319 -0.00395151 -1.55493 1 0 1 1 0 0 +EDGE2 5956 795 -1.01163 0.0513699 1.57674 1 0 1 1 0 0 +EDGE2 5956 875 -0.895756 0.0937029 -1.58013 1 0 1 1 0 0 +EDGE2 5956 3335 -0.996435 -0.0075283 1.5915 1 0 1 1 0 0 +EDGE2 5956 3355 -0.997676 -0.0500921 1.56686 1 0 1 1 0 0 +EDGE2 5956 815 -1.01606 -0.00761311 1.57847 1 0 1 1 0 0 +EDGE2 5956 755 -1.06759 0.0121264 1.58563 1 0 1 1 0 0 +EDGE2 5956 775 -0.997363 0.0490982 1.56832 1 0 1 1 0 0 +EDGE2 5956 695 -0.906223 -0.0445281 -1.59651 1 0 1 1 0 0 +EDGE2 5957 878 1.02375 0.110589 0.0158649 1 0 1 1 0 0 +EDGE2 5957 877 -0.0106244 -0.0392199 -0.0253969 1 0 1 1 0 0 +EDGE2 5957 5956 -1.03506 0.0292792 -0.0483134 1 0 1 1 0 0 +EDGE2 5957 876 -1.01099 -0.0406085 0.00689379 1 0 1 1 0 0 +EDGE2 5958 878 0.13624 -0.047268 -0.00243157 1 0 1 1 0 0 +EDGE2 5958 879 1.01546 -0.0491863 -0.0125644 1 0 1 1 0 0 +EDGE2 5958 5957 -1.05244 -0.00296124 0.0126731 1 0 1 1 0 0 +EDGE2 5958 877 -0.999023 -0.0450488 0.0106078 1 0 1 1 0 0 +EDGE2 5959 880 1.0362 0.0103382 -0.0206685 1 0 1 1 0 0 +EDGE2 5959 5940 0.978996 -0.00862714 -3.17529 1 0 1 1 0 0 +EDGE2 5959 878 -0.918262 -0.0620102 0.00342278 1 0 1 1 0 0 +EDGE2 5959 879 -0.0341995 -0.0806066 0.000530025 1 0 1 1 0 0 +EDGE2 5959 5958 -1.10095 -0.0235088 0.0228231 1 0 1 1 0 0 +EDGE2 5960 5939 1.07812 -0.108365 -3.15484 1 0 1 1 0 0 +EDGE2 5960 880 -0.0199712 -0.0329708 -0.00408714 1 0 1 1 0 0 +EDGE2 5960 5940 -0.0791205 -0.0313864 -3.1636 1 0 1 1 0 0 +EDGE2 5960 879 -0.988111 -0.000374265 0.0174549 1 0 1 1 0 0 +EDGE2 5960 5959 -0.962346 -0.0457982 -0.00884521 1 0 1 1 0 0 +EDGE2 5960 881 0.131861 1.09273 1.58391 1 0 1 1 0 0 +EDGE2 5960 5941 -0.0173128 1.00843 1.56385 1 0 1 1 0 0 +EDGE2 5961 880 -1.06589 0.062805 -1.6091 1 0 1 1 0 0 +EDGE2 5961 5940 -1.00902 0.05407 1.58412 1 0 1 1 0 0 +EDGE2 5961 5960 -1.01207 -0.0490635 -1.57733 1 0 1 1 0 0 +EDGE2 5961 5942 0.985877 0.0212371 0.00743219 1 0 1 1 0 0 +EDGE2 5961 881 0.0312571 0.00717392 -0.00519233 1 0 1 1 0 0 +EDGE2 5961 5941 -0.0724936 0.0681319 -0.0291494 1 0 1 1 0 0 +EDGE2 5961 882 0.977497 0.0953244 0.0236838 1 0 1 1 0 0 +EDGE2 5962 5961 -0.974287 -0.00519028 -0.015645 1 0 1 1 0 0 +EDGE2 5962 883 0.983487 -0.0505446 0.00747959 1 0 1 1 0 0 +EDGE2 5962 5942 -0.0320488 0.00235218 0.00429223 1 0 1 1 0 0 +EDGE2 5962 881 -0.94232 0.0276899 -0.0015437 1 0 1 1 0 0 +EDGE2 5962 5941 -1.08577 0.0144713 0.00171599 1 0 1 1 0 0 +EDGE2 5962 882 -0.0448157 -0.035585 -0.0341029 1 0 1 1 0 0 +EDGE2 5962 5943 1.04155 0.0141993 -0.0144 1 0 1 1 0 0 +EDGE2 5963 884 1.06919 -0.0446444 0.0142279 1 0 1 1 0 0 +EDGE2 5963 883 -0.0465259 0.126597 -0.0345183 1 0 1 1 0 0 +EDGE2 5963 5942 -1.02926 0.0319138 -0.0210422 1 0 1 1 0 0 +EDGE2 5963 5962 -0.94643 -0.112976 0.0217693 1 0 1 1 0 0 +EDGE2 5963 882 -1.03603 0.0236726 0.0150133 1 0 1 1 0 0 +EDGE2 5963 5943 0.031874 0.0819599 0.00830257 1 0 1 1 0 0 +EDGE2 5963 5944 0.940177 -0.0454384 -0.0263714 1 0 1 1 0 0 +EDGE2 5964 884 -0.0766544 0.0176564 -0.010043 1 0 1 1 0 0 +EDGE2 5964 883 -1.07734 0.0616582 0.00967134 1 0 1 1 0 0 +EDGE2 5964 5963 -1.10722 0.0484876 0.0210348 1 0 1 1 0 0 +EDGE2 5964 5943 -0.969559 0.00744058 -0.000210189 1 0 1 1 0 0 +EDGE2 5964 5944 -0.0119506 -0.0342685 -0.0166518 1 0 1 1 0 0 +EDGE2 5964 5945 1.06854 0.00086221 -0.0249509 1 0 1 1 0 0 +EDGE2 5964 5905 0.965369 0.0281417 -3.20141 1 0 1 1 0 0 +EDGE2 5964 885 0.971213 0.0742041 0.0248792 1 0 1 1 0 0 +EDGE2 5964 685 0.987127 0.105263 -3.1516 1 0 1 1 0 0 +EDGE2 5965 884 -0.893284 0.00562309 0.0295908 1 0 1 1 0 0 +EDGE2 5965 5906 -0.0596493 -0.948719 -1.54235 1 0 1 1 0 0 +EDGE2 5965 5964 -1.03348 0.0693259 0.0350949 1 0 1 1 0 0 +EDGE2 5965 5944 -0.963999 -0.0499382 0.000200798 1 0 1 1 0 0 +EDGE2 5965 5946 -0.0678396 1.02626 1.55626 1 0 1 1 0 0 +EDGE2 5965 5945 0.00142767 0.0622401 -0.0208587 1 0 1 1 0 0 +EDGE2 5965 5905 -0.0396645 0.00832256 -3.13395 1 0 1 1 0 0 +EDGE2 5965 885 0.0343676 -0.0232487 0.00514671 1 0 1 1 0 0 +EDGE2 5965 685 -0.0225154 0.00757829 -3.13274 1 0 1 1 0 0 +EDGE2 5965 684 0.941847 0.0089448 -3.13161 1 0 1 1 0 0 +EDGE2 5965 5904 0.991555 -0.0456138 -3.13775 1 0 1 1 0 0 +EDGE2 5965 686 -0.0139878 1.07751 1.56917 1 0 1 1 0 0 +EDGE2 5965 886 -0.00104295 1.03503 1.57496 1 0 1 1 0 0 +EDGE2 5966 5946 0.0442895 -0.0193269 0.00775559 1 0 1 1 0 0 +EDGE2 5966 5945 -0.996971 0.0202584 -1.58593 1 0 1 1 0 0 +EDGE2 5966 5965 -1.00543 0.0163535 -1.56891 1 0 1 1 0 0 +EDGE2 5966 5905 -1.0071 -0.0553993 1.56911 1 0 1 1 0 0 +EDGE2 5966 5947 0.861802 0.0625472 0.00551724 1 0 1 1 0 0 +EDGE2 5966 885 -1.09573 0.0384256 -1.54889 1 0 1 1 0 0 +EDGE2 5966 685 -1.01498 0.0182806 1.55551 1 0 1 1 0 0 +EDGE2 5966 686 0.0500116 0.00663777 -0.00309356 1 0 1 1 0 0 +EDGE2 5966 886 0.00781204 0.0101612 -0.0139341 1 0 1 1 0 0 +EDGE2 5966 687 1.01383 0.0822412 -0.0254029 1 0 1 1 0 0 +EDGE2 5966 887 0.95576 0.0537125 -0.0177627 1 0 1 1 0 0 +EDGE2 5967 5946 -1.0779 0.0345368 0.017472 1 0 1 1 0 0 +EDGE2 5967 5966 -0.97988 -0.00750044 0.0132401 1 0 1 1 0 0 +EDGE2 5967 5947 0.0056077 0.0614738 0.0111533 1 0 1 1 0 0 +EDGE2 5967 5948 1.09123 0.0278506 0.0358633 1 0 1 1 0 0 +EDGE2 5967 686 -1.05258 -0.0501891 -0.00523652 1 0 1 1 0 0 +EDGE2 5967 886 -0.986011 0.125519 -0.0132283 1 0 1 1 0 0 +EDGE2 5967 888 1.04003 0.0585819 -0.0173531 1 0 1 1 0 0 +EDGE2 5967 687 0.0598057 0.0674087 0.0131624 1 0 1 1 0 0 +EDGE2 5967 887 0.0761945 0.0583078 -0.0354358 1 0 1 1 0 0 +EDGE2 5967 688 0.970504 0.0715806 -0.0217108 1 0 1 1 0 0 +EDGE2 5968 5947 -0.895491 0.0197186 -0.00943746 1 0 1 1 0 0 +EDGE2 5968 5967 -1.11732 -0.0214862 0.0217476 1 0 1 1 0 0 +EDGE2 5968 5948 0.00198131 -0.0194985 0.000275465 1 0 1 1 0 0 +EDGE2 5968 5949 1.05828 0.0450063 -0.0544792 1 0 1 1 0 0 +EDGE2 5968 888 -0.0187535 0.127229 0.0237114 1 0 1 1 0 0 +EDGE2 5968 687 -1.02 0.0936763 0.0208726 1 0 1 1 0 0 +EDGE2 5968 887 -0.980827 -0.0847736 -0.0234868 1 0 1 1 0 0 +EDGE2 5968 688 -0.046193 -0.0654545 -0.0117906 1 0 1 1 0 0 +EDGE2 5968 689 1.09084 -0.0674194 0.05173 1 0 1 1 0 0 +EDGE2 5968 889 1.02117 0.0172465 0.000347591 1 0 1 1 0 0 +EDGE2 5969 5968 -0.966289 -0.0331311 0.0217433 1 0 1 1 0 0 +EDGE2 5969 5948 -0.863396 -0.00351194 0.0187605 1 0 1 1 0 0 +EDGE2 5969 5949 -0.0212422 0.0619117 0.0150562 1 0 1 1 0 0 +EDGE2 5969 5950 1.02131 0.0160732 -0.0257202 1 0 1 1 0 0 +EDGE2 5969 690 0.953766 -0.00108066 0.0478685 1 0 1 1 0 0 +EDGE2 5969 888 -0.992105 0.0771787 0.0117258 1 0 1 1 0 0 +EDGE2 5969 688 -0.935212 0.00764804 0.0186325 1 0 1 1 0 0 +EDGE2 5969 910 0.960823 0.0537719 -3.14903 1 0 1 1 0 0 +EDGE2 5969 3450 1.06152 -0.0311774 -3.1532 1 0 1 1 0 0 +EDGE2 5969 689 0.0445569 0.0211101 -0.00254755 1 0 1 1 0 0 +EDGE2 5969 889 0.0608898 -0.133444 0.0199692 1 0 1 1 0 0 +EDGE2 5969 3430 0.978592 0.00425459 -3.16376 1 0 1 1 0 0 +EDGE2 5969 850 1.06063 -0.0272923 -3.13007 1 0 1 1 0 0 +EDGE2 5969 870 0.949799 0.0525263 -3.13146 1 0 1 1 0 0 +EDGE2 5969 890 1.10434 -0.102808 -0.00748368 1 0 1 1 0 0 +EDGE2 5969 830 0.983479 0.0114856 -3.14955 1 0 1 1 0 0 +EDGE2 5970 5951 -0.0953051 1.01638 1.56262 1 0 1 1 0 0 +EDGE2 5970 5969 -0.87595 0.0209348 0.0294046 1 0 1 1 0 0 +EDGE2 5970 5949 -1.02287 -0.0322899 0.00923668 1 0 1 1 0 0 +EDGE2 5970 691 -0.0438204 1.01958 1.55811 1 0 1 1 0 0 +EDGE2 5970 871 -0.0890244 1.00074 1.5689 1 0 1 1 0 0 +EDGE2 5970 3451 -0.0644271 1.07204 1.56754 1 0 1 1 0 0 +EDGE2 5970 5950 -0.00727098 0.0430589 0.0202526 1 0 1 1 0 0 +EDGE2 5970 690 -0.0152091 0.025208 0.00951245 1 0 1 1 0 0 +EDGE2 5970 910 0.00821682 -0.0769774 -3.13529 1 0 1 1 0 0 +EDGE2 5970 3450 5.74766e-05 -0.0306496 -3.13704 1 0 1 1 0 0 +EDGE2 5970 689 -0.954942 0.0356051 0.0187066 1 0 1 1 0 0 +EDGE2 5970 889 -0.984938 0.00686263 0.0227938 1 0 1 1 0 0 +EDGE2 5970 3430 -0.0547745 -0.0206839 -3.12977 1 0 1 1 0 0 +EDGE2 5970 850 -0.0168394 0.0814057 -3.11717 1 0 1 1 0 0 +EDGE2 5970 870 -0.037501 -0.0908197 -3.15757 1 0 1 1 0 0 +EDGE2 5970 890 -0.0116414 0.0566595 0.0213252 1 0 1 1 0 0 +EDGE2 5970 830 0.0741046 -0.00579416 -3.15464 1 0 1 1 0 0 +EDGE2 5970 851 0.0456407 -1.05292 -1.57243 1 0 1 1 0 0 +EDGE2 5970 911 -0.0327908 -0.944828 -1.57889 1 0 1 1 0 0 +EDGE2 5970 3431 -0.00224583 -0.96822 -1.58415 1 0 1 1 0 0 +EDGE2 5970 891 -0.0650248 -1.06464 -1.54853 1 0 1 1 0 0 +EDGE2 5970 831 -0.0165911 -0.922392 -1.56662 1 0 1 1 0 0 +EDGE2 5970 869 1.04447 -0.0849937 -3.16051 1 0 1 1 0 0 +EDGE2 5970 3429 0.966771 0.00983454 -3.10853 1 0 1 1 0 0 +EDGE2 5970 3449 0.912102 -0.0769265 -3.15306 1 0 1 1 0 0 +EDGE2 5970 909 0.944146 0.00956564 -3.14676 1 0 1 1 0 0 +EDGE2 5970 829 1.03217 -0.130036 -3.15413 1 0 1 1 0 0 +EDGE2 5970 849 0.992212 -0.0312815 -3.12978 1 0 1 1 0 0 +EDGE2 5971 5951 0.0282988 -0.00626222 -0.0183756 1 0 1 1 0 0 +EDGE2 5971 872 1.01575 -0.0507021 -0.0189351 1 0 1 1 0 0 +EDGE2 5971 5952 1.03689 -0.0990425 0.00505947 1 0 1 1 0 0 +EDGE2 5971 3452 0.981309 -0.0934187 0.0155019 1 0 1 1 0 0 +EDGE2 5971 692 0.971573 -0.0815183 0.0312971 1 0 1 1 0 0 +EDGE2 5971 691 -0.0123075 0.00901939 0.0145082 1 0 1 1 0 0 +EDGE2 5971 871 -0.0141031 0.0737363 0.0197104 1 0 1 1 0 0 +EDGE2 5971 3451 0.0736486 -0.00809811 0.0318966 1 0 1 1 0 0 +EDGE2 5971 5950 -0.986376 0.0463627 -1.57489 1 0 1 1 0 0 +EDGE2 5971 5970 -0.978825 -0.0352439 -1.5553 1 0 1 1 0 0 +EDGE2 5971 690 -0.956717 0.0421686 -1.59099 1 0 1 1 0 0 +EDGE2 5971 910 -0.856948 -0.0128543 1.59497 1 0 1 1 0 0 +EDGE2 5971 3450 -1.08769 0.034088 1.56546 1 0 1 1 0 0 +EDGE2 5971 3430 -1.05916 0.00941781 1.58257 1 0 1 1 0 0 +EDGE2 5971 850 -1.01807 0.0602631 1.56554 1 0 1 1 0 0 +EDGE2 5971 870 -1.01679 0.0160059 1.58847 1 0 1 1 0 0 +EDGE2 5971 890 -0.914925 -0.00929099 -1.56624 1 0 1 1 0 0 +EDGE2 5971 830 -1.0768 0.139464 1.54565 1 0 1 1 0 0 +EDGE2 5972 5951 -1.05683 0.00225654 0.0185874 1 0 1 1 0 0 +EDGE2 5972 693 1.09333 0.0461168 -0.0159107 1 0 1 1 0 0 +EDGE2 5972 3453 0.995339 0.00988902 -0.0436212 1 0 1 1 0 0 +EDGE2 5972 5953 0.970121 0.019753 0.00238349 1 0 1 1 0 0 +EDGE2 5972 873 1.01699 -0.0359445 -0.013635 1 0 1 1 0 0 +EDGE2 5972 872 -0.0152254 -0.0909164 -0.00402584 1 0 1 1 0 0 +EDGE2 5972 5952 0.0485911 -0.0296496 -0.0194624 1 0 1 1 0 0 +EDGE2 5972 3452 0.0105806 -0.00355612 0.0301023 1 0 1 1 0 0 +EDGE2 5972 692 0.0550616 0.0433835 -0.0610723 1 0 1 1 0 0 +EDGE2 5972 5971 -0.940958 -0.0226215 0.00788046 1 0 1 1 0 0 +EDGE2 5972 691 -1.03184 -0.0447228 -0.0215553 1 0 1 1 0 0 +EDGE2 5972 871 -1.04787 0.00419734 -0.0105262 1 0 1 1 0 0 +EDGE2 5972 3451 -1.00097 0.0262973 0.0123295 1 0 1 1 0 0 +EDGE2 5973 693 -0.0261888 0.0981717 0.00924559 1 0 1 1 0 0 +EDGE2 5973 874 0.930942 -0.00513661 0.042215 1 0 1 1 0 0 +EDGE2 5973 3454 0.94843 -0.0356293 -0.00390414 1 0 1 1 0 0 +EDGE2 5973 5954 1.05403 -0.16013 -0.0213867 1 0 1 1 0 0 +EDGE2 5973 694 1.01591 -0.0204054 0.0162269 1 0 1 1 0 0 +EDGE2 5973 3453 -0.0258176 0.0128032 0.0257988 1 0 1 1 0 0 +EDGE2 5973 5953 -0.0491847 0.0388153 -0.023039 1 0 1 1 0 0 +EDGE2 5973 873 0.00977498 -0.112603 0.00239652 1 0 1 1 0 0 +EDGE2 5973 872 -0.999456 0.0438661 -0.00350874 1 0 1 1 0 0 +EDGE2 5973 5952 -1.00699 0.0605006 0.0102048 1 0 1 1 0 0 +EDGE2 5973 5972 -1.11839 0.0113047 -0.0157324 1 0 1 1 0 0 +EDGE2 5973 3452 -0.940732 -0.12485 -0.00322116 1 0 1 1 0 0 +EDGE2 5973 692 -1.02311 0.00820036 -0.0215686 1 0 1 1 0 0 +EDGE2 5974 3455 1.02484 -0.0735242 -0.0251492 1 0 1 1 0 0 +EDGE2 5974 5955 1.01985 0.0127954 0.028914 1 0 1 1 0 0 +EDGE2 5974 795 1.01576 0.0846249 -3.15685 1 0 1 1 0 0 +EDGE2 5974 875 1.03392 -0.0806242 -0.0199155 1 0 1 1 0 0 +EDGE2 5974 3335 0.939621 0.0142834 -3.16128 1 0 1 1 0 0 +EDGE2 5974 3355 1.05771 0.0199137 -3.14985 1 0 1 1 0 0 +EDGE2 5974 815 1.01143 -0.000401961 -3.14861 1 0 1 1 0 0 +EDGE2 5974 755 0.972162 0.0544318 -3.11332 1 0 1 1 0 0 +EDGE2 5974 775 1.04349 -0.071869 -3.1543 1 0 1 1 0 0 +EDGE2 5974 695 0.952906 -0.0168154 -0.00902389 1 0 1 1 0 0 +EDGE2 5974 693 -1.05118 0.00238574 -0.036384 1 0 1 1 0 0 +EDGE2 5974 874 0.0700091 0.016819 -0.0107109 1 0 1 1 0 0 +EDGE2 5974 3454 0.0462953 0.0340487 0.0468959 1 0 1 1 0 0 +EDGE2 5974 5954 -0.0128585 -0.0166612 -0.00786451 1 0 1 1 0 0 +EDGE2 5974 694 -0.0500002 -0.024154 0.00946625 1 0 1 1 0 0 +EDGE2 5974 3453 -0.949328 -0.0141787 0.0334776 1 0 1 1 0 0 +EDGE2 5974 5953 -1.01253 0.0109235 0.0258681 1 0 1 1 0 0 +EDGE2 5974 5973 -0.912679 0.0527756 0.0024636 1 0 1 1 0 0 +EDGE2 5974 873 -1.08756 -0.038446 -0.0221607 1 0 1 1 0 0 +EDGE2 5975 5956 -0.0957099 0.995741 1.55767 1 0 1 1 0 0 +EDGE2 5975 876 -0.0641821 0.921924 1.6024 1 0 1 1 0 0 +EDGE2 5975 3455 0.0142546 0.0120532 0.0165281 1 0 1 1 0 0 +EDGE2 5975 774 0.995896 0.088266 -3.12431 1 0 1 1 0 0 +EDGE2 5975 814 1.00397 -0.0380769 -3.11542 1 0 1 1 0 0 +EDGE2 5975 3334 1.0151 0.0330258 -3.16425 1 0 1 1 0 0 +EDGE2 5975 3354 1.03184 0.000432202 -3.11439 1 0 1 1 0 0 +EDGE2 5975 794 0.906149 -0.0490334 -3.10364 1 0 1 1 0 0 +EDGE2 5975 754 0.962793 -0.108746 -3.12783 1 0 1 1 0 0 +EDGE2 5975 5955 0.00587088 -0.0913397 -0.0333052 1 0 1 1 0 0 +EDGE2 5975 795 0.0559941 0.039046 -3.1278 1 0 1 1 0 0 +EDGE2 5975 875 0.00434152 0.0710377 0.0027065 1 0 1 1 0 0 +EDGE2 5975 3335 -0.008211 0.0664735 -3.16745 1 0 1 1 0 0 +EDGE2 5975 3355 -0.00355974 0.0179063 -3.11642 1 0 1 1 0 0 +EDGE2 5975 815 0.0728917 0.00374793 -3.12084 1 0 1 1 0 0 +EDGE2 5975 755 0.0161462 -0.0196979 -3.13543 1 0 1 1 0 0 +EDGE2 5975 775 0.00772479 -0.0601316 -3.14727 1 0 1 1 0 0 +EDGE2 5975 695 -0.0402926 -0.0449001 0.0109553 1 0 1 1 0 0 +EDGE2 5975 5974 -0.982398 -0.00413194 -0.00484909 1 0 1 1 0 0 +EDGE2 5975 874 -0.96008 0.00817981 -0.0416596 1 0 1 1 0 0 +EDGE2 5975 3454 -0.999257 0.00119782 -0.0154743 1 0 1 1 0 0 +EDGE2 5975 5954 -1.05221 0.0818364 -0.0132353 1 0 1 1 0 0 +EDGE2 5975 694 -1.03963 -0.00547154 -0.00772686 1 0 1 1 0 0 +EDGE2 5975 796 0.00207565 -0.995198 -1.61136 1 0 1 1 0 0 +EDGE2 5975 3336 -0.00769779 -1.09066 -1.60617 1 0 1 1 0 0 +EDGE2 5975 3356 0.05284 -0.978638 -1.57067 1 0 1 1 0 0 +EDGE2 5975 3456 -0.018148 -1.01316 -1.61543 1 0 1 1 0 0 +EDGE2 5975 816 -0.065971 -0.995779 -1.57525 1 0 1 1 0 0 +EDGE2 5975 696 -0.0050489 -0.926968 -1.59233 1 0 1 1 0 0 +EDGE2 5975 756 0.0117694 -1.0416 -1.57907 1 0 1 1 0 0 +EDGE2 5975 776 0.0162156 -1.08014 -1.56838 1 0 1 1 0 0 +EDGE2 5976 5957 1.0071 -0.0127625 -0.0170832 1 0 1 1 0 0 +EDGE2 5976 877 0.971125 -0.0333057 -0.00651575 1 0 1 1 0 0 +EDGE2 5976 5956 -0.0527307 0.044585 -0.0341585 1 0 1 1 0 0 +EDGE2 5976 876 0.0570308 -0.0882961 0.00575029 1 0 1 1 0 0 +EDGE2 5976 3455 -0.918217 -0.0294722 -1.58576 1 0 1 1 0 0 +EDGE2 5976 5975 -0.953704 0.023028 -1.55547 1 0 1 1 0 0 +EDGE2 5976 5955 -0.985762 0.0594995 -1.59674 1 0 1 1 0 0 +EDGE2 5976 795 -1.06807 -0.0281297 1.51537 1 0 1 1 0 0 +EDGE2 5976 875 -1.04658 -0.0307819 -1.5689 1 0 1 1 0 0 +EDGE2 5976 3335 -1.04276 -0.0147605 1.59394 1 0 1 1 0 0 +EDGE2 5976 3355 -1.01831 0.0261041 1.56296 1 0 1 1 0 0 +EDGE2 5976 815 -1.09013 -0.106445 1.55204 1 0 1 1 0 0 +EDGE2 5976 755 -1.02556 0.024542 1.58331 1 0 1 1 0 0 +EDGE2 5976 775 -0.989257 0.0171006 1.59085 1 0 1 1 0 0 +EDGE2 5976 695 -0.952421 -0.0641327 -1.58281 1 0 1 1 0 0 +EDGE2 5977 878 0.975846 0.034702 -0.000723329 1 0 1 1 0 0 +EDGE2 5977 5958 0.961599 -0.0588299 0.00523796 1 0 1 1 0 0 +EDGE2 5977 5957 0.0116608 0.00901588 0.00354446 1 0 1 1 0 0 +EDGE2 5977 877 0.0730764 -0.00896608 -0.0114152 1 0 1 1 0 0 +EDGE2 5977 5956 -0.982051 0.00845654 -0.0257943 1 0 1 1 0 0 +EDGE2 5977 5976 -0.988502 0.013909 0.0179541 1 0 1 1 0 0 +EDGE2 5977 876 -0.950516 0.0124029 0.00201409 1 0 1 1 0 0 +EDGE2 5978 878 -0.0251241 0.0370302 0.0265329 1 0 1 1 0 0 +EDGE2 5978 879 0.974116 -0.0687906 -0.0138168 1 0 1 1 0 0 +EDGE2 5978 5959 0.989604 -0.0185963 0.02747 1 0 1 1 0 0 +EDGE2 5978 5958 0.0112569 0.0521147 0.000630158 1 0 1 1 0 0 +EDGE2 5978 5957 -1.05927 -0.000645097 -0.0675219 1 0 1 1 0 0 +EDGE2 5978 5977 -0.950427 -0.0132323 0.010222 1 0 1 1 0 0 +EDGE2 5978 877 -1.03808 -0.0163357 -0.0115631 1 0 1 1 0 0 +EDGE2 5979 880 0.973072 0.01804 -0.0106868 1 0 1 1 0 0 +EDGE2 5979 5940 0.985336 0.0119032 -3.0939 1 0 1 1 0 0 +EDGE2 5979 5960 1.04059 0.00985611 0.0247872 1 0 1 1 0 0 +EDGE2 5979 878 -0.947691 -0.129135 0.0262514 1 0 1 1 0 0 +EDGE2 5979 5978 -0.996552 0.0179771 0.00128994 1 0 1 1 0 0 +EDGE2 5979 879 0.0298933 -0.0618009 -0.0120218 1 0 1 1 0 0 +EDGE2 5979 5959 -0.00399158 -0.036587 0.0100784 1 0 1 1 0 0 +EDGE2 5979 5958 -0.989184 0.0538199 -0.0115305 1 0 1 1 0 0 +EDGE2 5980 5961 0.0265214 0.899531 1.54212 1 0 1 1 0 0 +EDGE2 5980 5939 1.00946 -0.0133857 -3.16758 1 0 1 1 0 0 +EDGE2 5980 880 -0.123799 0.117886 -0.00636961 1 0 1 1 0 0 +EDGE2 5980 5940 0.0212919 0.0391047 -3.12294 1 0 1 1 0 0 +EDGE2 5980 5960 -0.0228226 0.0249868 -0.0140956 1 0 1 1 0 0 +EDGE2 5980 879 -0.968964 0.0954431 -0.00501009 1 0 1 1 0 0 +EDGE2 5980 5959 -1.03718 -0.0418276 -0.00362471 1 0 1 1 0 0 +EDGE2 5980 5979 -1.01117 -0.00396433 -0.0136074 1 0 1 1 0 0 +EDGE2 5980 881 -0.0259938 0.937588 1.58994 1 0 1 1 0 0 +EDGE2 5980 5941 -0.0838492 0.938233 1.57356 1 0 1 1 0 0 +EDGE2 5981 5961 -0.0422761 0.015549 0.0125634 1 0 1 1 0 0 +EDGE2 5981 5980 -0.973133 -0.0359868 -1.57729 1 0 1 1 0 0 +EDGE2 5981 880 -1.00345 0.00349466 -1.5776 1 0 1 1 0 0 +EDGE2 5981 5940 -0.98369 -0.0613868 1.57483 1 0 1 1 0 0 +EDGE2 5981 5960 -1.03831 0.0322365 -1.53489 1 0 1 1 0 0 +EDGE2 5981 5942 1.0269 -0.0159651 -0.0126192 1 0 1 1 0 0 +EDGE2 5981 881 -0.0816518 -0.052832 -0.00402168 1 0 1 1 0 0 +EDGE2 5981 5941 -0.0565998 0.039316 0.0013767 1 0 1 1 0 0 +EDGE2 5981 5962 0.900621 -0.00150789 -0.00872246 1 0 1 1 0 0 +EDGE2 5981 882 1.00098 0.0210469 0.00934341 1 0 1 1 0 0 +EDGE2 5982 5961 -0.953496 0.0715349 0.0144518 1 0 1 1 0 0 +EDGE2 5982 5981 -0.96079 0.0527324 0.0104874 1 0 1 1 0 0 +EDGE2 5982 883 0.918524 0.0448879 -0.0134291 1 0 1 1 0 0 +EDGE2 5982 5942 -0.0371909 -0.0659898 0.00147166 1 0 1 1 0 0 +EDGE2 5982 881 -0.970044 -0.11483 0.0371138 1 0 1 1 0 0 +EDGE2 5982 5941 -1.12052 0.0105723 0.00996941 1 0 1 1 0 0 +EDGE2 5982 5962 -0.0602236 0.0399215 0.00659797 1 0 1 1 0 0 +EDGE2 5982 5963 1.02406 -0.0655452 0.00609855 1 0 1 1 0 0 +EDGE2 5982 882 0.0209863 -0.014196 -0.0312665 1 0 1 1 0 0 +EDGE2 5982 5943 1.02965 -0.0342227 0.0247259 1 0 1 1 0 0 +EDGE2 5983 884 0.99134 -0.0242326 0.0106342 1 0 1 1 0 0 +EDGE2 5983 883 0.0069461 0.0648264 -0.000119301 1 0 1 1 0 0 +EDGE2 5983 5942 -1.01128 -0.0278186 0.021192 1 0 1 1 0 0 +EDGE2 5983 5982 -1.0984 0.0284237 0.0229914 1 0 1 1 0 0 +EDGE2 5983 5962 -0.984154 -0.0316196 -0.0223095 1 0 1 1 0 0 +EDGE2 5983 5963 -0.0377497 -0.0458437 -0.0242541 1 0 1 1 0 0 +EDGE2 5983 882 -1.02884 -0.0246324 0.0265018 1 0 1 1 0 0 +EDGE2 5983 5943 0.0810804 -0.00528801 -0.0104754 1 0 1 1 0 0 +EDGE2 5983 5964 0.998197 0.0525903 -0.00655917 1 0 1 1 0 0 +EDGE2 5983 5944 1.00304 0.0754539 -0.0268871 1 0 1 1 0 0 +EDGE2 5984 884 0.0428818 0.0532366 0.00851301 1 0 1 1 0 0 +EDGE2 5984 883 -0.945155 -0.0305892 0.0133558 1 0 1 1 0 0 +EDGE2 5984 5963 -0.94409 0.0416538 0.0191396 1 0 1 1 0 0 +EDGE2 5984 5983 -0.977218 0.0356687 -0.00729789 1 0 1 1 0 0 +EDGE2 5984 5943 -1.01591 -0.0587212 0.0086247 1 0 1 1 0 0 +EDGE2 5984 5964 -0.0813764 -0.0325834 0.00256988 1 0 1 1 0 0 +EDGE2 5984 5944 0.155088 -0.0460851 -0.00465225 1 0 1 1 0 0 +EDGE2 5984 5945 1.00194 -0.0865994 0.00204945 1 0 1 1 0 0 +EDGE2 5984 5965 1.04501 0.064049 -0.0115664 1 0 1 1 0 0 +EDGE2 5984 5905 1.05555 0.0831911 -3.16246 1 0 1 1 0 0 +EDGE2 5984 885 1.05458 0.0506234 0.00903211 1 0 1 1 0 0 +EDGE2 5984 685 0.963971 0.0512849 -3.15487 1 0 1 1 0 0 +EDGE2 5985 884 -0.967732 0.013953 0.00984063 1 0 1 1 0 0 +EDGE2 5985 5906 0.0414023 -0.956943 -1.58228 1 0 1 1 0 0 +EDGE2 5985 5964 -1.02164 -0.0317414 0.00535815 1 0 1 1 0 0 +EDGE2 5985 5984 -0.953472 -0.0993526 -0.017866 1 0 1 1 0 0 +EDGE2 5985 5944 -0.926795 0.0483653 -0.0230034 1 0 1 1 0 0 +EDGE2 5985 5946 -0.0924816 0.989343 1.63667 1 0 1 1 0 0 +EDGE2 5985 5945 0.0211003 0.0507259 0.0221428 1 0 1 1 0 0 +EDGE2 5985 5965 0.0771904 0.0530462 0.00927466 1 0 1 1 0 0 +EDGE2 5985 5966 -0.0281744 1.00925 1.54824 1 0 1 1 0 0 +EDGE2 5985 5905 0.0926724 -0.0292905 -3.15062 1 0 1 1 0 0 +EDGE2 5985 885 0.0666006 -0.00199553 -0.0353454 1 0 1 1 0 0 +EDGE2 5985 685 -0.111024 -0.0357497 -3.1016 1 0 1 1 0 0 +EDGE2 5985 684 1.08726 -0.0309569 -3.15485 1 0 1 1 0 0 +EDGE2 5985 5904 0.926338 0.0142068 -3.13129 1 0 1 1 0 0 +EDGE2 5985 686 0.00774345 1.03827 1.5648 1 0 1 1 0 0 +EDGE2 5985 886 -0.0389404 1.00837 1.55424 1 0 1 1 0 0 +EDGE2 5986 5946 0.10236 -0.12588 -0.0171238 1 0 1 1 0 0 +EDGE2 5986 5945 -0.957119 -0.0832704 -1.60658 1 0 1 1 0 0 +EDGE2 5986 5985 -0.965528 0.0521645 -1.58028 1 0 1 1 0 0 +EDGE2 5986 5965 -1.09733 0.0207958 -1.56722 1 0 1 1 0 0 +EDGE2 5986 5966 -0.0466812 -0.0212956 -0.0165152 1 0 1 1 0 0 +EDGE2 5986 5905 -0.994134 0.0304213 1.55569 1 0 1 1 0 0 +EDGE2 5986 5947 0.979591 -0.0179822 0.0300153 1 0 1 1 0 0 +EDGE2 5986 5967 1.03056 0.0981744 -0.00113697 1 0 1 1 0 0 +EDGE2 5986 885 -0.944094 0.00227095 -1.55756 1 0 1 1 0 0 +EDGE2 5986 685 -0.948279 -0.0416298 1.56898 1 0 1 1 0 0 +EDGE2 5986 686 0.0447648 -0.0455222 -0.00170495 1 0 1 1 0 0 +EDGE2 5986 886 -0.0347932 -0.0867583 -0.0189194 1 0 1 1 0 0 +EDGE2 5986 687 0.97431 0.0353003 0.00348485 1 0 1 1 0 0 +EDGE2 5986 887 1.08654 -0.019364 -0.0164837 1 0 1 1 0 0 +EDGE2 5987 5946 -0.950001 0.0232157 0.0149646 1 0 1 1 0 0 +EDGE2 5987 5966 -1.06204 -0.125625 0.0112359 1 0 1 1 0 0 +EDGE2 5987 5986 -1.03446 0.00764629 0.0109573 1 0 1 1 0 0 +EDGE2 5987 5968 0.962372 0.0716184 -0.0433234 1 0 1 1 0 0 +EDGE2 5987 5947 0.00161958 -0.0282346 0.0186522 1 0 1 1 0 0 +EDGE2 5987 5967 0.045607 0.10981 -0.0012517 1 0 1 1 0 0 +EDGE2 5987 5948 1.04844 0.0854689 -0.0179554 1 0 1 1 0 0 +EDGE2 5987 686 -1.00491 0.0180307 0.0381509 1 0 1 1 0 0 +EDGE2 5987 886 -0.962891 0.0512851 0.0135553 1 0 1 1 0 0 +EDGE2 5987 888 1.00125 0.0636537 0.0234976 1 0 1 1 0 0 +EDGE2 5987 687 0.0442681 -0.00684862 -0.0162657 1 0 1 1 0 0 +EDGE2 5987 887 0.049231 -0.066165 -0.00304018 1 0 1 1 0 0 +EDGE2 5987 688 1.14015 0.00718728 0.0255523 1 0 1 1 0 0 +EDGE2 5988 5968 -0.0605535 -0.0578574 0.0119449 1 0 1 1 0 0 +EDGE2 5988 5947 -0.993765 0.10843 -0.00509594 1 0 1 1 0 0 +EDGE2 5988 5967 -1.06549 -0.0144657 0.0240552 1 0 1 1 0 0 +EDGE2 5988 5987 -1.07745 0.0379275 -0.00485457 1 0 1 1 0 0 +EDGE2 5988 5969 0.96789 -0.045262 -0.0156046 1 0 1 1 0 0 +EDGE2 5988 5948 -0.000187579 -0.105262 -0.0205134 1 0 1 1 0 0 +EDGE2 5988 5949 1.05065 -0.0310461 -0.029102 1 0 1 1 0 0 +EDGE2 5988 888 0.000107607 -0.0229327 -0.00208121 1 0 1 1 0 0 +EDGE2 5988 687 -0.955615 0.0669375 -0.00223513 1 0 1 1 0 0 +EDGE2 5988 887 -1.04162 0.0408671 -0.00656796 1 0 1 1 0 0 +EDGE2 5988 688 -0.00331903 0.0558186 0.0254437 1 0 1 1 0 0 +EDGE2 5988 689 1.08025 -0.0177793 -0.00794889 1 0 1 1 0 0 +EDGE2 5988 889 0.979442 0.0506599 0.0244206 1 0 1 1 0 0 +EDGE2 5989 5968 -0.96442 -0.0588794 -0.00746839 1 0 1 1 0 0 +EDGE2 5989 5988 -0.99787 -0.0367236 0.0154779 1 0 1 1 0 0 +EDGE2 5989 5969 0.0156848 0.0170134 -0.00551707 1 0 1 1 0 0 +EDGE2 5989 5948 -1.03104 -0.0360954 0.00965889 1 0 1 1 0 0 +EDGE2 5989 5949 -0.00657327 -0.053525 0.0352437 1 0 1 1 0 0 +EDGE2 5989 5950 0.996115 -0.0174974 -0.00522089 1 0 1 1 0 0 +EDGE2 5989 5970 1.02422 0.0787089 0.00572821 1 0 1 1 0 0 +EDGE2 5989 690 1.05171 -0.0684744 0.0243273 1 0 1 1 0 0 +EDGE2 5989 888 -0.955323 0.0840949 0.0166897 1 0 1 1 0 0 +EDGE2 5989 688 -1.01132 0.029104 -0.00220373 1 0 1 1 0 0 +EDGE2 5989 910 0.904077 0.0415503 -3.14084 1 0 1 1 0 0 +EDGE2 5989 3450 0.94748 0.0382019 -3.1249 1 0 1 1 0 0 +EDGE2 5989 689 0.0400918 -0.0229244 -0.0281806 1 0 1 1 0 0 +EDGE2 5989 889 -0.0596094 0.0702688 -0.0155421 1 0 1 1 0 0 +EDGE2 5989 3430 1.02832 0.0474571 -3.17195 1 0 1 1 0 0 +EDGE2 5989 850 0.972804 0.0261695 -3.12663 1 0 1 1 0 0 +EDGE2 5989 870 0.973307 -0.0811276 -3.14783 1 0 1 1 0 0 +EDGE2 5989 890 0.985503 0.0494088 -0.021982 1 0 1 1 0 0 +EDGE2 5989 830 1.01442 -0.00589948 -3.14849 1 0 1 1 0 0 +EDGE2 5990 5951 0.00605801 0.940268 1.55308 1 0 1 1 0 0 +EDGE2 5990 5969 -1.00157 -0.0279233 -0.0198163 1 0 1 1 0 0 +EDGE2 5990 5989 -1.02245 0.000867548 -0.0120493 1 0 1 1 0 0 +EDGE2 5990 5949 -0.952596 0.0419967 -0.0116205 1 0 1 1 0 0 +EDGE2 5990 5971 -0.00492049 0.94037 1.55729 1 0 1 1 0 0 +EDGE2 5990 691 -0.0497872 0.998776 1.57393 1 0 1 1 0 0 +EDGE2 5990 871 -0.0258418 0.999089 1.55943 1 0 1 1 0 0 +EDGE2 5990 3451 0.0286731 0.941613 1.58452 1 0 1 1 0 0 +EDGE2 5990 5950 -0.122308 0.0155429 -0.0110281 1 0 1 1 0 0 +EDGE2 5990 5970 -0.146302 -0.013617 -0.0216969 1 0 1 1 0 0 +EDGE2 5990 690 0.0459093 0.00227041 0.00702293 1 0 1 1 0 0 +EDGE2 5990 910 -0.0585017 0.0196259 -3.12042 1 0 1 1 0 0 +EDGE2 5990 3450 -0.041938 0.0412832 -3.16422 1 0 1 1 0 0 +EDGE2 5990 689 -1.07715 0.0206527 0.0207296 1 0 1 1 0 0 +EDGE2 5990 889 -1.05269 -0.051597 0.020876 1 0 1 1 0 0 +EDGE2 5990 3430 -0.0607852 -0.0327003 -3.12584 1 0 1 1 0 0 +EDGE2 5990 850 -0.0145876 -0.000197312 -3.15974 1 0 1 1 0 0 +EDGE2 5990 870 0.00147601 0.0137194 -3.13793 1 0 1 1 0 0 +EDGE2 5990 890 0.0415012 -0.0525501 -0.00466519 1 0 1 1 0 0 +EDGE2 5990 830 -0.0704289 -0.0583126 -3.13499 1 0 1 1 0 0 +EDGE2 5990 851 -0.0209273 -1.03679 -1.57647 1 0 1 1 0 0 +EDGE2 5990 911 -0.0835583 -0.972212 -1.55204 1 0 1 1 0 0 +EDGE2 5990 3431 0.0553282 -0.908301 -1.58013 1 0 1 1 0 0 +EDGE2 5990 891 -0.041405 -0.981906 -1.58787 1 0 1 1 0 0 +EDGE2 5990 831 0.0268448 -1.04768 -1.56377 1 0 1 1 0 0 +EDGE2 5990 869 1.01873 0.0088603 -3.16018 1 0 1 1 0 0 +EDGE2 5990 3429 1.03673 -0.0378434 -3.12093 1 0 1 1 0 0 +EDGE2 5990 3449 1.00195 -0.0266014 -3.19712 1 0 1 1 0 0 +EDGE2 5990 909 1.04534 -0.00578441 -3.12389 1 0 1 1 0 0 +EDGE2 5990 829 1.06276 0.0206882 -3.14066 1 0 1 1 0 0 +EDGE2 5990 849 0.946015 -0.00641602 -3.13956 1 0 1 1 0 0 +EDGE2 5991 5951 -0.0682564 -0.0705645 0.0229661 1 0 1 1 0 0 +EDGE2 5991 872 0.911153 -0.10865 0.00329731 1 0 1 1 0 0 +EDGE2 5991 5952 0.958886 -0.0746313 -0.0191197 1 0 1 1 0 0 +EDGE2 5991 5972 0.976549 0.00752963 0.0368559 1 0 1 1 0 0 +EDGE2 5991 3452 1.01044 -0.011043 0.0191204 1 0 1 1 0 0 +EDGE2 5991 692 0.990275 0.0220476 0.0298265 1 0 1 1 0 0 +EDGE2 5991 5971 0.0591931 -0.010328 -0.00723785 1 0 1 1 0 0 +EDGE2 5991 5990 -0.948581 -0.0780669 -1.58855 1 0 1 1 0 0 +EDGE2 5991 691 -0.00278126 0.0758333 0.0117807 1 0 1 1 0 0 +EDGE2 5991 871 -0.0272264 0.0761335 0.0133487 1 0 1 1 0 0 +EDGE2 5991 3451 -0.0573871 0.0237517 -0.0282503 1 0 1 1 0 0 +EDGE2 5991 5950 -0.885894 0.112628 -1.56793 1 0 1 1 0 0 +EDGE2 5991 5970 -0.971161 -0.0898951 -1.58112 1 0 1 1 0 0 +EDGE2 5991 690 -0.989983 0.0719239 -1.55535 1 0 1 1 0 0 +EDGE2 5991 910 -0.994914 -0.0315328 1.55109 1 0 1 1 0 0 +EDGE2 5991 3450 -0.960341 0.00367032 1.56654 1 0 1 1 0 0 +EDGE2 5991 3430 -1.0734 0.0541729 1.5615 1 0 1 1 0 0 +EDGE2 5991 850 -1.0225 -0.00244476 1.57774 1 0 1 1 0 0 +EDGE2 5991 870 -0.945677 0.0155983 1.58111 1 0 1 1 0 0 +EDGE2 5991 890 -1.01695 0.088773 -1.592 1 0 1 1 0 0 +EDGE2 5991 830 -1.03918 -0.0125045 1.56078 1 0 1 1 0 0 +EDGE2 5992 5951 -1.07828 0.130953 -0.00562668 1 0 1 1 0 0 +EDGE2 5992 693 0.998094 -0.0154866 0.0281064 1 0 1 1 0 0 +EDGE2 5992 3453 0.942517 0.0679932 0.0018707 1 0 1 1 0 0 +EDGE2 5992 5953 0.998438 -0.00882315 -0.00929393 1 0 1 1 0 0 +EDGE2 5992 5973 0.953202 -0.0248515 0.0443022 1 0 1 1 0 0 +EDGE2 5992 873 1.09606 0.000747855 0.0185756 1 0 1 1 0 0 +EDGE2 5992 872 -0.0460792 -0.051998 -0.0505004 1 0 1 1 0 0 +EDGE2 5992 5952 0.00897384 0.001521 0.0245226 1 0 1 1 0 0 +EDGE2 5992 5972 0.0287014 0.0230101 -0.0104675 1 0 1 1 0 0 +EDGE2 5992 3452 0.00957132 -0.0841507 -0.0117867 1 0 1 1 0 0 +EDGE2 5992 5991 -0.922645 0.0330007 -0.0111199 1 0 1 1 0 0 +EDGE2 5992 692 -0.031432 0.0723496 -0.0320069 1 0 1 1 0 0 +EDGE2 5992 5971 -1.01523 -0.0386277 -0.0058427 1 0 1 1 0 0 +EDGE2 5992 691 -1.01325 -0.0362667 0.0371249 1 0 1 1 0 0 +EDGE2 5992 871 -0.99271 0.0650137 -0.0166849 1 0 1 1 0 0 +EDGE2 5992 3451 -1.00835 0.0592558 0.0103469 1 0 1 1 0 0 +EDGE2 5993 5974 1.02585 -0.0282021 0.00627385 1 0 1 1 0 0 +EDGE2 5993 693 0.038141 -0.0638397 0.0375614 1 0 1 1 0 0 +EDGE2 5993 874 0.95082 -0.0286432 -0.0443549 1 0 1 1 0 0 +EDGE2 5993 3454 0.975928 -0.0362361 -0.00333405 1 0 1 1 0 0 +EDGE2 5993 5954 1.03493 -0.00438124 0.0257076 1 0 1 1 0 0 +EDGE2 5993 694 1.0382 -0.0224388 -0.0265031 1 0 1 1 0 0 +EDGE2 5993 3453 0.0323737 -0.0103144 0.0121481 1 0 1 1 0 0 +EDGE2 5993 5953 0.0632683 0.0175981 0.0249603 1 0 1 1 0 0 +EDGE2 5993 5973 -0.0228788 2.8995e-05 -0.00682226 1 0 1 1 0 0 +EDGE2 5993 873 -0.0116768 0.100394 0.00871253 1 0 1 1 0 0 +EDGE2 5993 872 -0.951501 0.00375516 0.0307082 1 0 1 1 0 0 +EDGE2 5993 5952 -1.02579 -0.110589 0.00769457 1 0 1 1 0 0 +EDGE2 5993 5972 -1.00169 -0.00928937 -0.026462 1 0 1 1 0 0 +EDGE2 5993 5992 -0.954431 -0.0432124 -0.00268983 1 0 1 1 0 0 +EDGE2 5993 3452 -1.00441 0.0173018 0.00430982 1 0 1 1 0 0 +EDGE2 5993 692 -0.973595 -0.0462045 -0.0250763 1 0 1 1 0 0 +EDGE2 5994 3455 1.05205 0.00518629 -0.00969998 1 0 1 1 0 0 +EDGE2 5994 5975 1.07832 0.0703221 0.0138137 1 0 1 1 0 0 +EDGE2 5994 5955 0.899243 -0.0725163 -0.0229605 1 0 1 1 0 0 +EDGE2 5994 795 0.982164 -0.0192555 -3.12971 1 0 1 1 0 0 +EDGE2 5994 875 1.08388 0.0686278 -0.0154005 1 0 1 1 0 0 +EDGE2 5994 3335 0.907015 0.0556313 -3.15027 1 0 1 1 0 0 +EDGE2 5994 3355 1.09658 0.0246649 -3.15073 1 0 1 1 0 0 +EDGE2 5994 815 1.00054 0.032434 -3.13594 1 0 1 1 0 0 +EDGE2 5994 755 0.927314 -0.0377605 -3.11992 1 0 1 1 0 0 +EDGE2 5994 775 0.938703 0.00283915 -3.11948 1 0 1 1 0 0 +EDGE2 5994 695 1.02899 -0.0188628 0.00201431 1 0 1 1 0 0 +EDGE2 5994 5974 0.0918096 0.0347537 -0.0325737 1 0 1 1 0 0 +EDGE2 5994 693 -0.905245 0.0748105 0.0548175 1 0 1 1 0 0 +EDGE2 5994 5993 -1.00533 0.0289779 -0.0448774 1 0 1 1 0 0 +EDGE2 5994 874 0.0199562 0.0156496 -0.00884175 1 0 1 1 0 0 +EDGE2 5994 3454 -0.0755329 0.0219223 0.0181882 1 0 1 1 0 0 +EDGE2 5994 5954 0.0692074 -0.0565398 -0.00181409 1 0 1 1 0 0 +EDGE2 5994 694 0.0277851 0.0194257 -0.0427952 1 0 1 1 0 0 +EDGE2 5994 3453 -1.06575 -0.00117385 -0.0146006 1 0 1 1 0 0 +EDGE2 5994 5953 -0.873821 -0.0130833 -0.0246507 1 0 1 1 0 0 +EDGE2 5994 5973 -0.983238 0.0517507 0.0131075 1 0 1 1 0 0 +EDGE2 5994 873 -1.02785 -0.0516075 0.0227305 1 0 1 1 0 0 +EDGE2 5995 5956 -0.0301826 0.981685 1.56126 1 0 1 1 0 0 +EDGE2 5995 5976 -0.0314126 0.963785 1.5733 1 0 1 1 0 0 +EDGE2 5995 876 0.0141403 0.954112 1.54034 1 0 1 1 0 0 +EDGE2 5995 3455 0.000762195 0.100216 -0.00107569 1 0 1 1 0 0 +EDGE2 5995 774 1.04814 -0.0562501 -3.15932 1 0 1 1 0 0 +EDGE2 5995 814 0.946969 0.10264 -3.13105 1 0 1 1 0 0 +EDGE2 5995 3334 1.00096 -0.0392191 -3.15559 1 0 1 1 0 0 +EDGE2 5995 3354 1.06547 0.0463255 -3.15684 1 0 1 1 0 0 +EDGE2 5995 794 0.985602 0.0849572 -3.12781 1 0 1 1 0 0 +EDGE2 5995 5975 -0.0176606 0.0840043 -0.00809804 1 0 1 1 0 0 +EDGE2 5995 754 1.04775 -0.0347606 -3.14035 1 0 1 1 0 0 +EDGE2 5995 5955 -0.0824671 0.0425127 0.00283828 1 0 1 1 0 0 +EDGE2 5995 795 0.0120021 0.00707797 -3.12963 1 0 1 1 0 0 +EDGE2 5995 875 -0.0934945 0.00993316 -0.0416623 1 0 1 1 0 0 +EDGE2 5995 3335 0.00564171 0.0235925 -3.11878 1 0 1 1 0 0 +EDGE2 5995 3355 -0.0545071 -0.0491312 -3.15436 1 0 1 1 0 0 +EDGE2 5995 815 -0.0144619 -0.0391919 -3.15833 1 0 1 1 0 0 +EDGE2 5995 755 0.0355937 0.0131277 -3.16114 1 0 1 1 0 0 +EDGE2 5995 775 -0.0257585 -0.0343628 -3.1326 1 0 1 1 0 0 +EDGE2 5995 695 0.0219974 -0.00661182 0.00901603 1 0 1 1 0 0 +EDGE2 5995 5974 -0.986305 0.111887 -0.0185101 1 0 1 1 0 0 +EDGE2 5995 5994 -1.04081 -0.0153957 0.0105644 1 0 1 1 0 0 +EDGE2 5995 874 -1.03199 0.0444818 0.0215168 1 0 1 1 0 0 +EDGE2 5995 3454 -1.00463 -0.0941957 -0.00221442 1 0 1 1 0 0 +EDGE2 5995 5954 -0.960003 -0.0550476 0.0159564 1 0 1 1 0 0 +EDGE2 5995 694 -1.08213 -0.0138121 -0.00239102 1 0 1 1 0 0 +EDGE2 5995 796 -0.110523 -0.968683 -1.6039 1 0 1 1 0 0 +EDGE2 5995 3336 -0.0206407 -0.952059 -1.57094 1 0 1 1 0 0 +EDGE2 5995 3356 -0.0697069 -1.05438 -1.57055 1 0 1 1 0 0 +EDGE2 5995 3456 0.0595391 -1.00331 -1.57921 1 0 1 1 0 0 +EDGE2 5995 816 0.0278338 -0.9228 -1.55692 1 0 1 1 0 0 +EDGE2 5995 696 0.0317702 -0.948519 -1.55659 1 0 1 1 0 0 +EDGE2 5995 756 0.00749311 -0.969543 -1.56 1 0 1 1 0 0 +EDGE2 5995 776 0.0278826 -1.02092 -1.56303 1 0 1 1 0 0 +EDGE2 5996 5957 1.02771 0.00927184 -0.0129605 1 0 1 1 0 0 +EDGE2 5996 5977 1.01686 -0.110612 -0.00350356 1 0 1 1 0 0 +EDGE2 5996 877 0.967782 -0.0710836 -0.0142013 1 0 1 1 0 0 +EDGE2 5996 5956 -0.0247829 0.00439556 -0.0130555 1 0 1 1 0 0 +EDGE2 5996 5976 -0.0398246 0.0254797 -0.0153757 1 0 1 1 0 0 +EDGE2 5996 876 0.0120263 0.0798148 0.00242808 1 0 1 1 0 0 +EDGE2 5996 3455 -1.01949 -0.052525 -1.57197 1 0 1 1 0 0 +EDGE2 5996 5975 -0.95467 0.0937467 -1.55453 1 0 1 1 0 0 +EDGE2 5996 5995 -0.981369 0.0374862 -1.56491 1 0 1 1 0 0 +EDGE2 5996 5955 -0.964051 -0.101889 -1.55421 1 0 1 1 0 0 +EDGE2 5996 795 -0.931004 -0.0493943 1.56633 1 0 1 1 0 0 +EDGE2 5996 875 -0.967914 0.0138531 -1.58682 1 0 1 1 0 0 +EDGE2 5996 3335 -0.973941 -0.0230944 1.57486 1 0 1 1 0 0 +EDGE2 5996 3355 -1.05939 0.01165 1.59782 1 0 1 1 0 0 +EDGE2 5996 815 -0.996537 0.108027 1.55601 1 0 1 1 0 0 +EDGE2 5996 755 -0.886473 0.0111361 1.55643 1 0 1 1 0 0 +EDGE2 5996 775 -0.986656 -0.0778468 1.57266 1 0 1 1 0 0 +EDGE2 5996 695 -1.01617 0.0945633 -1.54787 1 0 1 1 0 0 +EDGE2 5997 878 1.00967 0.102822 0.00917634 1 0 1 1 0 0 +EDGE2 5997 5978 0.946221 0.02719 -0.0133208 1 0 1 1 0 0 +EDGE2 5997 5958 1.05243 -0.0306386 -0.0372259 1 0 1 1 0 0 +EDGE2 5997 5996 -0.930226 0.00344549 0.0178446 1 0 1 1 0 0 +EDGE2 5997 5957 0.0148624 0.0240424 -0.0133621 1 0 1 1 0 0 +EDGE2 5997 5977 0.0536156 -0.023168 0.000835743 1 0 1 1 0 0 +EDGE2 5997 877 0.047603 0.0864813 0.0122882 1 0 1 1 0 0 +EDGE2 5997 5956 -0.988951 -0.00024233 0.00586599 1 0 1 1 0 0 +EDGE2 5997 5976 -1.07937 -0.0252083 0.00612502 1 0 1 1 0 0 +EDGE2 5997 876 -1.0944 0.00960104 0.00528765 1 0 1 1 0 0 +EDGE2 5998 878 0.0221247 -0.13085 -0.0149966 1 0 1 1 0 0 +EDGE2 5998 5978 -0.0350452 0.0208247 0.00999526 1 0 1 1 0 0 +EDGE2 5998 879 1.0006 0.0509178 -0.0105578 1 0 1 1 0 0 +EDGE2 5998 5959 1.01339 -0.0248421 0.00443313 1 0 1 1 0 0 +EDGE2 5998 5979 1.02479 0.0222981 -0.0315858 1 0 1 1 0 0 +EDGE2 5998 5958 0.00252001 -0.0358069 -0.000988678 1 0 1 1 0 0 +EDGE2 5998 5957 -0.923445 0.0649407 -0.00462589 1 0 1 1 0 0 +EDGE2 5998 5977 -1.00049 0.065197 -0.0313009 1 0 1 1 0 0 +EDGE2 5998 5997 -0.943973 0.0411785 -0.0128318 1 0 1 1 0 0 +EDGE2 5998 877 -1.03682 -0.066372 -0.0307822 1 0 1 1 0 0 +EDGE2 5999 5980 1.01871 0.0155773 0.0202135 1 0 1 1 0 0 +EDGE2 5999 880 0.909204 0.0637552 -0.0138115 1 0 1 1 0 0 +EDGE2 5999 5940 1.06179 -0.027163 -3.1837 1 0 1 1 0 0 +EDGE2 5999 5960 1.03863 0.0360115 -0.0268404 1 0 1 1 0 0 +EDGE2 5999 878 -1.0522 0.0122595 -0.0188391 1 0 1 1 0 0 +EDGE2 5999 5978 -0.971953 0.0726667 -0.0421056 1 0 1 1 0 0 +EDGE2 5999 879 0.0572238 -0.0498644 -0.0119919 1 0 1 1 0 0 +EDGE2 5999 5959 -0.00959828 0.00693465 -0.000480963 1 0 1 1 0 0 +EDGE2 5999 5979 0.046367 -0.0228197 0.0106845 1 0 1 1 0 0 +EDGE2 5999 5998 -1.00438 -0.0222191 -0.0622437 1 0 1 1 0 0 +EDGE2 5999 5958 -1.01209 -0.088004 -0.0193725 1 0 1 1 0 0 +EDGE2 6000 5961 -0.0814838 1.04916 1.5712 1 0 1 1 0 0 +EDGE2 6000 5999 -1.03211 0.0999407 0.0111821 1 0 1 1 0 0 +EDGE2 6000 5980 -0.00541918 -0.0187298 -0.0305865 1 0 1 1 0 0 +EDGE2 6000 5939 1.03381 -0.0467997 -3.14468 1 0 1 1 0 0 +EDGE2 6000 880 -0.0311591 -0.0145484 0.0350423 1 0 1 1 0 0 +EDGE2 6000 5940 -0.0558914 0.00194215 -3.10835 1 0 1 1 0 0 +EDGE2 6000 5960 0.0885957 0.0217567 0.00702819 1 0 1 1 0 0 +EDGE2 6000 5981 0.0477513 0.939243 1.57736 1 0 1 1 0 0 +EDGE2 6000 879 -1.04869 -0.0424084 0.0140659 1 0 1 1 0 0 +EDGE2 6000 5959 -0.985127 0.0296497 0.0217694 1 0 1 1 0 0 +EDGE2 6000 5979 -0.993195 -0.0214953 0.014427 1 0 1 1 0 0 +EDGE2 6000 881 -0.0302314 0.889609 1.54978 1 0 1 1 0 0 +EDGE2 6000 5941 -0.0347338 1.05587 1.58525 1 0 1 1 0 0 +EDGE2 6001 5980 -0.985501 0.00789398 1.53192 1 0 1 1 0 0 +EDGE2 6001 6000 -0.951332 0.00452475 1.55792 1 0 1 1 0 0 +EDGE2 6001 880 -1.05292 -0.0403647 1.5798 1 0 1 1 0 0 +EDGE2 6001 5940 -1.07391 -0.0284621 -1.55353 1 0 1 1 0 0 +EDGE2 6001 5960 -0.969429 0.00224222 1.56207 1 0 1 1 0 0 +EDGE2 6002 6001 -1.01192 -0.0142399 -0.0349568 1 0 1 1 0 0 +EDGE2 6003 6002 -0.938653 0.0511478 0.00967672 1 0 1 1 0 0 +EDGE2 6004 6003 -1.01395 0.00275547 0.0292429 1 0 1 1 0 0 +EDGE2 6005 6004 -1.04455 -0.0674447 0.00535435 1 0 1 1 0 0 +EDGE2 6006 6005 -1.02144 0.0622896 -1.58847 1 0 1 1 0 0 +EDGE2 6007 6006 -0.913917 -0.00121437 0.00722413 1 0 1 1 0 0 +EDGE2 6008 6007 -0.940787 0.023617 0.0126528 1 0 1 1 0 0 +EDGE2 6009 6008 -0.935458 0.0564737 0.0114751 1 0 1 1 0 0 +EDGE2 6010 6009 -1.05926 0.0584951 -0.0073357 1 0 1 1 0 0 +EDGE2 6011 6010 -1.0407 -0.0513418 -1.55194 1 0 1 1 0 0 +EDGE2 6012 6011 -1.07595 0.00410099 0.00592915 1 0 1 1 0 0 +EDGE2 6013 6012 -0.954388 0.0608095 0.0166437 1 0 1 1 0 0 +EDGE2 6014 6013 -1.00897 -0.0171936 -0.000837009 1 0 1 1 0 0 +EDGE2 6014 5915 1.0002 -0.00541043 -3.1273 1 0 1 1 0 0 +EDGE2 6014 5935 0.995073 0.0852326 -3.11712 1 0 1 1 0 0 +EDGE2 6015 6014 -1.03877 0.0505328 -0.00605887 1 0 1 1 0 0 +EDGE2 6015 5915 -0.0145104 0.0597542 -3.11367 1 0 1 1 0 0 +EDGE2 6015 5916 -0.138408 -0.991402 -1.5518 1 0 1 1 0 0 +EDGE2 6015 5935 0.0836885 0.0120897 -3.15383 1 0 1 1 0 0 +EDGE2 6015 5934 1.03044 0.0476625 -3.1525 1 0 1 1 0 0 +EDGE2 6015 5914 1.01297 -0.0535162 -3.12977 1 0 1 1 0 0 +EDGE2 6015 5936 0.0158882 0.974779 1.59322 1 0 1 1 0 0 +EDGE2 6016 5915 -1.02078 0.0499327 -1.55142 1 0 1 1 0 0 +EDGE2 6016 5917 1.08058 0.112877 -0.0196127 1 0 1 1 0 0 +EDGE2 6016 6015 -0.941235 0.00682262 1.5795 1 0 1 1 0 0 +EDGE2 6016 5916 0.0831704 -0.0752677 0.011945 1 0 1 1 0 0 +EDGE2 6016 5935 -1.10785 -0.0670025 -1.56137 1 0 1 1 0 0 +EDGE2 6017 5918 1.02543 -0.0502373 0.00235267 1 0 1 1 0 0 +EDGE2 6017 6016 -1.01172 0.0125101 0.030187 1 0 1 1 0 0 +EDGE2 6017 5917 -0.0494838 -0.0220979 -0.0168945 1 0 1 1 0 0 +EDGE2 6017 5916 -0.922181 -0.0493979 0.0158454 1 0 1 1 0 0 +EDGE2 6018 5919 0.969004 -0.0545833 -0.0326953 1 0 1 1 0 0 +EDGE2 6018 5918 0.0571227 0.035388 -0.018768 1 0 1 1 0 0 +EDGE2 6018 5917 -0.949384 -0.160306 0.00844459 1 0 1 1 0 0 +EDGE2 6018 6017 -1.05567 -0.0155429 0.0129097 1 0 1 1 0 0 +EDGE2 6019 620 1.01714 -0.0351386 -3.08948 1 0 1 1 0 0 +EDGE2 6019 5920 0.895585 -0.105987 -0.00275209 1 0 1 1 0 0 +EDGE2 6019 6018 -0.952021 -0.000910474 0.027373 1 0 1 1 0 0 +EDGE2 6019 5919 0.0428971 0.0216896 -0.0150183 1 0 1 1 0 0 +EDGE2 6019 5918 -0.977105 -0.00591356 0.00223681 1 0 1 1 0 0 +EDGE2 6020 620 -0.135885 -0.0313246 -3.10862 1 0 1 1 0 0 +EDGE2 6020 619 0.962133 -0.0546695 -3.1836 1 0 1 1 0 0 +EDGE2 6020 5920 -0.0140788 -0.0175252 -0.0222705 1 0 1 1 0 0 +EDGE2 6020 6019 -0.928958 -0.0728889 0.0228508 1 0 1 1 0 0 +EDGE2 6020 621 0.0116003 1.03816 1.6204 1 0 1 1 0 0 +EDGE2 6020 5921 -0.0712825 0.974562 1.56597 1 0 1 1 0 0 +EDGE2 6020 5919 -0.907975 0.119294 -0.0166095 1 0 1 1 0 0 +EDGE2 6021 620 -0.929474 -0.00694678 -1.55766 1 0 1 1 0 0 +EDGE2 6021 6020 -0.967914 -0.0620305 1.56061 1 0 1 1 0 0 +EDGE2 6021 5920 -1.01953 0.00999227 1.56366 1 0 1 1 0 0 +EDGE2 6022 6021 -1.03099 -0.00456802 0.00203327 1 0 1 1 0 0 +EDGE2 6023 6022 -0.968201 0.00711855 -0.00308304 1 0 1 1 0 0 +EDGE2 6024 6023 -1.1311 0.00848788 -0.0312056 1 0 1 1 0 0 +EDGE2 6025 6024 -1.02702 0.0514004 -0.0168246 1 0 1 1 0 0 +EDGE2 6026 6025 -1.03708 -0.00680539 -1.54221 1 0 1 1 0 0 +EDGE2 6027 6026 -1.09648 0.0387784 -0.00671976 1 0 1 1 0 0 +EDGE2 6028 6027 -1.03508 0.0174602 -0.0104004 1 0 1 1 0 0 +EDGE2 6029 610 0.950362 0.0116636 -3.10137 1 0 1 1 0 0 +EDGE2 6029 6028 -0.955959 0.0920388 -0.00348489 1 0 1 1 0 0 +EDGE2 6030 609 0.995329 0.0649051 -3.15066 1 0 1 1 0 0 +EDGE2 6030 610 -0.0548276 -0.00108034 -3.13596 1 0 1 1 0 0 +EDGE2 6030 6029 -0.874915 0.0178648 0.00323721 1 0 1 1 0 0 +EDGE2 6030 611 0.0832452 0.947166 1.52726 1 0 1 1 0 0 +EDGE2 6031 610 -0.963771 -0.0519213 -1.57205 1 0 1 1 0 0 +EDGE2 6031 6030 -0.959587 0.0332734 1.58606 1 0 1 1 0 0 +EDGE2 6032 6031 -0.947756 0.00229109 0.035713 1 0 1 1 0 0 +EDGE2 6033 6032 -1.06028 0.0796525 0.0180005 1 0 1 1 0 0 +EDGE2 6034 6033 -0.955627 0.00947163 0.0252185 1 0 1 1 0 0 +EDGE2 6035 6034 -1.0103 0.0202889 -0.0155631 1 0 1 1 0 0 +EDGE2 6036 6035 -0.976529 -0.0584018 -1.57758 1 0 1 1 0 0 +EDGE2 6037 6036 -0.989673 0.0517766 0.00718123 1 0 1 1 0 0 +EDGE2 6038 6037 -1.04423 0.0232485 -0.00987611 1 0 1 1 0 0 +EDGE2 6039 6038 -1.1129 0.010979 0.00814004 1 0 1 1 0 0 +EDGE2 6040 6039 -1.05523 0.0396535 0.0472323 1 0 1 1 0 0 +EDGE2 6041 6040 -0.899442 -0.000432925 -1.55127 1 0 1 1 0 0 +EDGE2 6042 6041 -0.980601 0.0285392 0.0362234 1 0 1 1 0 0 +EDGE2 6043 6042 -0.962295 0.0416615 -0.00965681 1 0 1 1 0 0 +EDGE2 6044 6043 -1.00614 0.110515 -0.00891574 1 0 1 1 0 0 +EDGE2 6044 605 1.05124 -0.047358 -3.11887 1 0 1 1 0 0 +EDGE2 6045 6044 -0.97355 -0.00199228 -0.0114506 1 0 1 1 0 0 +EDGE2 6045 605 -0.0493395 -0.0240692 -3.12954 1 0 1 1 0 0 +EDGE2 6045 604 0.939621 -0.00833829 -3.14643 1 0 1 1 0 0 +EDGE2 6045 606 0.0174444 0.997153 1.58696 1 0 1 1 0 0 +EDGE2 6046 6045 -0.90118 0.0473239 -1.59897 1 0 1 1 0 0 +EDGE2 6046 605 -1.02279 0.057017 1.5383 1 0 1 1 0 0 +EDGE2 6046 607 1.06082 -0.0485608 -0.00207108 1 0 1 1 0 0 +EDGE2 6046 606 0.080561 -0.0584921 0.00709085 1 0 1 1 0 0 +EDGE2 6047 607 -0.0100024 0.0382204 -0.0193161 1 0 1 1 0 0 +EDGE2 6047 6046 -0.944687 0.0303391 0.00213716 1 0 1 1 0 0 +EDGE2 6047 606 -1.01358 -0.0290356 -0.00689455 1 0 1 1 0 0 +EDGE2 6047 608 0.970627 0.0514844 -0.00258216 1 0 1 1 0 0 +EDGE2 6048 607 -1.0211 -0.0279257 -0.0187853 1 0 1 1 0 0 +EDGE2 6048 6047 -1.00421 0.01899 -0.0334897 1 0 1 1 0 0 +EDGE2 6048 608 0.000583235 0.0107895 0.0186014 1 0 1 1 0 0 +EDGE2 6048 609 1.04067 -0.0217815 0.0177463 1 0 1 1 0 0 +EDGE2 6049 608 -0.889144 -0.0897237 0.00685032 1 0 1 1 0 0 +EDGE2 6049 6048 -0.926196 -0.088287 0.00582824 1 0 1 1 0 0 +EDGE2 6049 609 0.0766521 -0.0417893 -0.00865715 1 0 1 1 0 0 +EDGE2 6049 610 1.04997 0.0181911 0.0195716 1 0 1 1 0 0 +EDGE2 6049 6030 1.08787 -0.0486006 -3.1186 1 0 1 1 0 0 +EDGE2 6050 6031 0.0697676 1.01651 1.58082 1 0 1 1 0 0 +EDGE2 6050 6049 -1.01958 0.0212216 -0.00559467 1 0 1 1 0 0 +EDGE2 6050 609 -1.04448 -0.0900704 0.00290964 1 0 1 1 0 0 +EDGE2 6050 610 0.0165269 -0.0975932 0.00418249 1 0 1 1 0 0 +EDGE2 6050 6030 -0.0457496 0.020776 -3.13702 1 0 1 1 0 0 +EDGE2 6050 6029 1.01642 0.0626821 -3.16411 1 0 1 1 0 0 +EDGE2 6050 611 -0.0558894 -0.955554 -1.55095 1 0 1 1 0 0 +EDGE2 6051 6032 0.951678 0.0739475 0.0292717 1 0 1 1 0 0 +EDGE2 6051 6031 0.0136108 0.1082 -0.00597391 1 0 1 1 0 0 +EDGE2 6051 6050 -0.926877 0.0580836 -1.53531 1 0 1 1 0 0 +EDGE2 6051 610 -1.03953 -0.159239 -1.56389 1 0 1 1 0 0 +EDGE2 6051 6030 -1.01881 0.00473993 1.54114 1 0 1 1 0 0 +EDGE2 6052 6032 0.0494746 0.0501923 0.00411507 1 0 1 1 0 0 +EDGE2 6052 6033 0.993275 -0.0844187 -0.00724998 1 0 1 1 0 0 +EDGE2 6052 6051 -1.0149 -0.0266627 -0.0272488 1 0 1 1 0 0 +EDGE2 6052 6031 -0.970142 0.00969309 -0.00833164 1 0 1 1 0 0 +EDGE2 6053 6032 -1.00614 -0.0360156 0.0405827 1 0 1 1 0 0 +EDGE2 6053 6034 0.954473 -0.00137778 0.0352026 1 0 1 1 0 0 +EDGE2 6053 6033 0.0159267 0.0132277 -0.0245986 1 0 1 1 0 0 +EDGE2 6053 6052 -1.07045 -0.0963915 -0.0061237 1 0 1 1 0 0 +EDGE2 6054 6035 0.970432 0.0164145 -0.0155613 1 0 1 1 0 0 +EDGE2 6054 6034 -0.000201493 -0.00344527 -0.000425148 1 0 1 1 0 0 +EDGE2 6054 6033 -1.0415 0.0226315 0.0162022 1 0 1 1 0 0 +EDGE2 6054 6053 -1.04591 0.0129012 0.0155063 1 0 1 1 0 0 +EDGE2 6055 6036 -0.0626831 1.06835 1.6018 1 0 1 1 0 0 +EDGE2 6055 6035 -0.0240579 -0.108576 0.0182245 1 0 1 1 0 0 +EDGE2 6055 6034 -1.01606 0.0514345 0.015874 1 0 1 1 0 0 +EDGE2 6055 6054 -0.984199 -0.0245173 -0.0142295 1 0 1 1 0 0 +EDGE2 6056 6037 0.986563 -0.0851031 -0.0155829 1 0 1 1 0 0 +EDGE2 6056 6036 0.00166616 0.00472799 -0.0130965 1 0 1 1 0 0 +EDGE2 6056 6035 -1.01754 0.0342103 -1.58141 1 0 1 1 0 0 +EDGE2 6056 6055 -1.02008 0.0115728 -1.53817 1 0 1 1 0 0 +EDGE2 6057 6038 1.01883 0.0298481 -0.0342893 1 0 1 1 0 0 +EDGE2 6057 6056 -0.959896 0.00366867 -0.00644125 1 0 1 1 0 0 +EDGE2 6057 6037 0.0185462 -0.0433584 -0.0146978 1 0 1 1 0 0 +EDGE2 6057 6036 -1.052 0.00378064 -0.00885285 1 0 1 1 0 0 +EDGE2 6058 6039 1.05338 0.0428974 0.0066394 1 0 1 1 0 0 +EDGE2 6058 6038 0.0303858 -0.0100884 -0.0155606 1 0 1 1 0 0 +EDGE2 6058 6037 -1.01092 0.0069953 -0.038837 1 0 1 1 0 0 +EDGE2 6058 6057 -0.95561 -0.0591065 -0.00166881 1 0 1 1 0 0 +EDGE2 6059 6040 1.03811 0.0593619 0.0191549 1 0 1 1 0 0 +EDGE2 6059 6039 -0.0915733 0.0368585 -0.0099937 1 0 1 1 0 0 +EDGE2 6059 6058 -1.01183 0.00891957 -0.00286754 1 0 1 1 0 0 +EDGE2 6059 6038 -0.994439 -0.121337 0.0346979 1 0 1 1 0 0 +EDGE2 6060 6040 0.0386651 -0.0459243 0.00574297 1 0 1 1 0 0 +EDGE2 6060 6041 -0.0772789 0.952314 1.57934 1 0 1 1 0 0 +EDGE2 6060 6059 -1.058 -0.0492426 0.0045101 1 0 1 1 0 0 +EDGE2 6060 6039 -1.07608 0.0354102 0.00984935 1 0 1 1 0 0 +EDGE2 6061 6042 0.988548 -0.031767 0.00891833 1 0 1 1 0 0 +EDGE2 6061 6040 -0.949379 0.103388 -1.58468 1 0 1 1 0 0 +EDGE2 6061 6060 -1.00598 -0.0367458 -1.57663 1 0 1 1 0 0 +EDGE2 6061 6041 0.0559733 0.00549811 0.0232323 1 0 1 1 0 0 +EDGE2 6062 6042 -0.00617691 0.0842473 0.0010846 1 0 1 1 0 0 +EDGE2 6062 6061 -1.01328 -0.114561 0.0127125 1 0 1 1 0 0 +EDGE2 6062 6041 -1.06334 -0.00738222 -0.0102028 1 0 1 1 0 0 +EDGE2 6062 6043 0.94908 -0.0886386 -0.0270096 1 0 1 1 0 0 +EDGE2 6063 6042 -1.10869 -0.0693362 -0.0435211 1 0 1 1 0 0 +EDGE2 6063 6062 -0.932264 0.00707861 0.0039009 1 0 1 1 0 0 +EDGE2 6063 6043 0.0209904 -0.0392385 0.0180314 1 0 1 1 0 0 +EDGE2 6063 6044 0.98285 -0.0277663 -0.00830757 1 0 1 1 0 0 +EDGE2 6064 6063 -1.03559 0.0568536 0.0016787 1 0 1 1 0 0 +EDGE2 6064 6043 -1.04045 -0.00703155 0.0150764 1 0 1 1 0 0 +EDGE2 6064 6044 0.165236 -0.0768536 0.00152723 1 0 1 1 0 0 +EDGE2 6064 6045 1.02189 0.00194328 0.0272219 1 0 1 1 0 0 +EDGE2 6064 605 0.967843 0.0287453 -3.14619 1 0 1 1 0 0 +EDGE2 6065 6044 -1.01306 0.0339775 0.0216076 1 0 1 1 0 0 +EDGE2 6065 6064 -1.06082 -0.0198982 0.0133855 1 0 1 1 0 0 +EDGE2 6065 6045 -0.0254329 0.0581393 -0.0243443 1 0 1 1 0 0 +EDGE2 6065 605 -0.0319218 -0.0389536 -3.14237 1 0 1 1 0 0 +EDGE2 6065 604 1.00057 -0.0149375 -3.16211 1 0 1 1 0 0 +EDGE2 6065 6046 0.0113352 0.920736 1.58182 1 0 1 1 0 0 +EDGE2 6065 606 -0.0417325 0.992501 1.55597 1 0 1 1 0 0 +EDGE2 6066 6045 -1.01137 -0.149767 -1.58091 1 0 1 1 0 0 +EDGE2 6066 6065 -0.970155 -0.0327844 -1.5217 1 0 1 1 0 0 +EDGE2 6066 605 -1.04554 -0.0513223 1.56969 1 0 1 1 0 0 +EDGE2 6066 607 1.03608 0.0509307 0.0194299 1 0 1 1 0 0 +EDGE2 6066 6046 -0.0174824 -0.0132189 0.0150086 1 0 1 1 0 0 +EDGE2 6066 606 0.0461207 -0.0165825 -0.0263098 1 0 1 1 0 0 +EDGE2 6066 6047 1.03542 -0.0073855 0.0278113 1 0 1 1 0 0 +EDGE2 6067 607 0.0621998 0.00539037 0.00668989 1 0 1 1 0 0 +EDGE2 6067 6046 -0.973475 0.0388977 -0.00846458 1 0 1 1 0 0 +EDGE2 6067 6066 -0.947062 0.0256407 0.00342203 1 0 1 1 0 0 +EDGE2 6067 606 -0.986207 -0.056998 0.000286689 1 0 1 1 0 0 +EDGE2 6067 6047 -0.00988652 0.0577671 0.0092356 1 0 1 1 0 0 +EDGE2 6067 608 0.96853 0.0173906 -0.0118379 1 0 1 1 0 0 +EDGE2 6067 6048 1.05623 -0.0347427 -0.0078374 1 0 1 1 0 0 +EDGE2 6068 607 -1.02812 0.00930931 -0.0315313 1 0 1 1 0 0 +EDGE2 6068 6067 -1.08778 -0.142951 -0.0482475 1 0 1 1 0 0 +EDGE2 6068 6047 -0.967942 -0.0217941 -0.0118564 1 0 1 1 0 0 +EDGE2 6068 608 -0.109335 -0.0475708 -0.0284858 1 0 1 1 0 0 +EDGE2 6068 6048 -0.0449739 -0.0938029 -0.00542792 1 0 1 1 0 0 +EDGE2 6068 6049 0.946159 -0.018263 -0.00686586 1 0 1 1 0 0 +EDGE2 6068 609 0.986083 0.00852785 -0.015587 1 0 1 1 0 0 +EDGE2 6069 6068 -0.995586 0.0341773 0.00787584 1 0 1 1 0 0 +EDGE2 6069 608 -1.03916 0.0642243 0.00541983 1 0 1 1 0 0 +EDGE2 6069 6048 -0.973043 0.00124316 0.00281769 1 0 1 1 0 0 +EDGE2 6069 6049 -0.000682864 -0.0245991 0.0148316 1 0 1 1 0 0 +EDGE2 6069 609 0.00144313 -0.00238004 0.00536492 1 0 1 1 0 0 +EDGE2 6069 6050 1.03591 -0.0192069 -0.000775468 1 0 1 1 0 0 +EDGE2 6069 610 1.09781 -0.0690651 -0.00445338 1 0 1 1 0 0 +EDGE2 6069 6030 1.0087 0.141932 -3.13447 1 0 1 1 0 0 +EDGE2 6070 6051 -0.103285 0.985406 1.5966 1 0 1 1 0 0 +EDGE2 6070 6031 0.0715853 1.03355 1.60501 1 0 1 1 0 0 +EDGE2 6070 6049 -0.962993 0.0180324 -0.0220381 1 0 1 1 0 0 +EDGE2 6070 6069 -1.07399 0.0280163 0.0050799 1 0 1 1 0 0 +EDGE2 6070 609 -0.97392 0.0862232 0.00285106 1 0 1 1 0 0 +EDGE2 6070 6050 0.0781741 0.0449995 -0.00569825 1 0 1 1 0 0 +EDGE2 6070 610 0.0345048 -0.0687761 -0.0229272 1 0 1 1 0 0 +EDGE2 6070 6030 -0.0232671 -0.0355417 -3.15574 1 0 1 1 0 0 +EDGE2 6070 6029 1.00134 0.0271969 -3.14282 1 0 1 1 0 0 +EDGE2 6070 611 0.106556 -0.944229 -1.56287 1 0 1 1 0 0 +EDGE2 6071 6032 1.04829 0.00680562 0.00132938 1 0 1 1 0 0 +EDGE2 6071 6052 0.969237 0.0409677 -0.00761947 1 0 1 1 0 0 +EDGE2 6071 6051 0.00803238 -0.0488852 -0.00746034 1 0 1 1 0 0 +EDGE2 6071 6031 0.0489005 0.0665708 0.0041565 1 0 1 1 0 0 +EDGE2 6071 6050 -0.97145 -0.0458853 -1.58066 1 0 1 1 0 0 +EDGE2 6071 6070 -0.969855 0.10175 -1.58626 1 0 1 1 0 0 +EDGE2 6071 610 -0.873645 -0.0529281 -1.57446 1 0 1 1 0 0 +EDGE2 6071 6030 -0.899038 -0.0548448 1.57082 1 0 1 1 0 0 +EDGE2 6072 6032 0.00804415 -0.0350019 -0.0165435 1 0 1 1 0 0 +EDGE2 6072 6033 0.917139 -0.021172 -0.0136374 1 0 1 1 0 0 +EDGE2 6072 6053 1.00167 -0.0151493 0.00284615 1 0 1 1 0 0 +EDGE2 6072 6052 0.0668931 -0.0163275 -0.0163874 1 0 1 1 0 0 +EDGE2 6072 6051 -0.956411 0.105841 -0.0184042 1 0 1 1 0 0 +EDGE2 6072 6071 -1.00103 -0.0650271 -0.0210766 1 0 1 1 0 0 +EDGE2 6072 6031 -0.98198 -0.0497178 0.0342121 1 0 1 1 0 0 +EDGE2 6073 6032 -1.02645 0.0472546 0.0210738 1 0 1 1 0 0 +EDGE2 6073 6034 0.968592 0.0545388 0.00139062 1 0 1 1 0 0 +EDGE2 6073 6054 0.973233 -0.00237523 0.00735968 1 0 1 1 0 0 +EDGE2 6073 6033 0.0267338 -0.00544605 -0.00965719 1 0 1 1 0 0 +EDGE2 6073 6053 -0.046575 0.0257586 -0.00261901 1 0 1 1 0 0 +EDGE2 6073 6072 -0.96714 -0.0176895 0.027202 1 0 1 1 0 0 +EDGE2 6073 6052 -0.866845 -0.0306541 0.0206323 1 0 1 1 0 0 +EDGE2 6074 6035 1.01159 -0.0287205 0.00369496 1 0 1 1 0 0 +EDGE2 6074 6055 1.02075 0.0368794 -0.00698419 1 0 1 1 0 0 +EDGE2 6074 6034 -0.0988661 0.0867229 0.00815615 1 0 1 1 0 0 +EDGE2 6074 6054 -0.00136922 0.00188396 0.00113609 1 0 1 1 0 0 +EDGE2 6074 6033 -1.0047 0.0521142 0.00190209 1 0 1 1 0 0 +EDGE2 6074 6053 -1.00777 0.017082 0.0042508 1 0 1 1 0 0 +EDGE2 6074 6073 -1.0335 -0.0508166 0.0306667 1 0 1 1 0 0 +EDGE2 6075 6056 -0.108893 1.00987 1.55097 1 0 1 1 0 0 +EDGE2 6075 6036 -0.118994 0.96481 1.60687 1 0 1 1 0 0 +EDGE2 6075 6035 0.0997793 -0.0378277 0.00255136 1 0 1 1 0 0 +EDGE2 6075 6055 0.00588891 0.00650003 0.00766613 1 0 1 1 0 0 +EDGE2 6075 6034 -0.999004 -0.0746109 0.0226121 1 0 1 1 0 0 +EDGE2 6075 6054 -0.944869 -0.0328339 -0.0062401 1 0 1 1 0 0 +EDGE2 6075 6074 -1.03382 -0.0644695 -0.0374084 1 0 1 1 0 0 +EDGE2 6076 6056 0.0186375 0.0273655 0.0255189 1 0 1 1 0 0 +EDGE2 6076 6037 0.933263 -0.0972666 -0.0405982 1 0 1 1 0 0 +EDGE2 6076 6057 0.956709 -0.0588107 0.00514206 1 0 1 1 0 0 +EDGE2 6076 6075 -1.01361 0.0747427 -1.59484 1 0 1 1 0 0 +EDGE2 6076 6036 -0.0635087 0.152912 -0.00131466 1 0 1 1 0 0 +EDGE2 6076 6035 -1.03684 0.00828724 -1.54255 1 0 1 1 0 0 +EDGE2 6076 6055 -1.03836 -0.00791041 -1.58662 1 0 1 1 0 0 +EDGE2 6077 6058 1.06784 0.040505 0.00491654 1 0 1 1 0 0 +EDGE2 6077 6038 0.975131 -0.0261794 0.00660216 1 0 1 1 0 0 +EDGE2 6077 6056 -1.00688 0.0121217 -0.00923968 1 0 1 1 0 0 +EDGE2 6077 6037 -0.0347099 -0.0870816 -0.0227211 1 0 1 1 0 0 +EDGE2 6077 6057 -0.0351831 -0.0267058 0.0105934 1 0 1 1 0 0 +EDGE2 6077 6076 -1.15046 0.00853446 0.0154716 1 0 1 1 0 0 +EDGE2 6077 6036 -1.02696 -0.0062164 0.00169379 1 0 1 1 0 0 +EDGE2 6078 6059 1.06287 0.0426481 0.0123621 1 0 1 1 0 0 +EDGE2 6078 6039 0.949701 -0.0343051 0.031877 1 0 1 1 0 0 +EDGE2 6078 6058 -0.00597923 -0.0210035 -0.0283304 1 0 1 1 0 0 +EDGE2 6078 6038 0.0616762 0.00127687 0.00823596 1 0 1 1 0 0 +EDGE2 6078 6037 -1.02611 0.07136 0.016688 1 0 1 1 0 0 +EDGE2 6078 6077 -1.02079 0.00959814 0.0281628 1 0 1 1 0 0 +EDGE2 6078 6057 -0.893882 -0.0685504 0.0229888 1 0 1 1 0 0 +EDGE2 6079 6040 0.973785 -0.00575511 0.0288856 1 0 1 1 0 0 +EDGE2 6079 6060 0.971836 -0.0164501 -0.0222454 1 0 1 1 0 0 +EDGE2 6079 6078 -1.03325 -0.010149 0.00512071 1 0 1 1 0 0 +EDGE2 6079 6059 0.0518426 0.039203 0.0280003 1 0 1 1 0 0 +EDGE2 6079 6039 0.0862081 -0.00765567 0.00114937 1 0 1 1 0 0 +EDGE2 6079 6058 -0.930152 0.0321582 0.00306027 1 0 1 1 0 0 +EDGE2 6079 6038 -0.957861 0.0726723 0.0188205 1 0 1 1 0 0 +EDGE2 6080 6040 0.0229621 -0.0211063 0.010947 1 0 1 1 0 0 +EDGE2 6080 6060 -0.00751205 0.0577597 -0.0102644 1 0 1 1 0 0 +EDGE2 6080 6061 0.0631018 0.922771 1.54341 1 0 1 1 0 0 +EDGE2 6080 6041 -0.116226 1.02988 1.55709 1 0 1 1 0 0 +EDGE2 6080 6059 -0.984424 -0.0639625 -0.0224353 1 0 1 1 0 0 +EDGE2 6080 6079 -1.02837 0.0952667 0.00472288 1 0 1 1 0 0 +EDGE2 6080 6039 -1.06458 0.0326778 -0.00733406 1 0 1 1 0 0 +EDGE2 6081 6042 0.919762 -0.0348998 0.000644075 1 0 1 1 0 0 +EDGE2 6081 6040 -1.04913 0.00610422 -1.55532 1 0 1 1 0 0 +EDGE2 6081 6060 -1.11889 0.0399421 -1.5628 1 0 1 1 0 0 +EDGE2 6081 6080 -1.03562 0.0270704 -1.55305 1 0 1 1 0 0 +EDGE2 6081 6061 0.0329174 -0.00648029 -0.0241419 1 0 1 1 0 0 +EDGE2 6081 6041 -0.0657303 -0.068994 0.0144584 1 0 1 1 0 0 +EDGE2 6081 6062 0.882341 -0.00650875 -0.00857913 1 0 1 1 0 0 +EDGE2 6082 6042 -0.0935713 0.0581489 0.0377641 1 0 1 1 0 0 +EDGE2 6082 6061 -0.929342 0.0612739 0.00515328 1 0 1 1 0 0 +EDGE2 6082 6081 -1.04449 -0.0254948 0.00439132 1 0 1 1 0 0 +EDGE2 6082 6041 -0.999222 -0.00827261 -0.000169978 1 0 1 1 0 0 +EDGE2 6082 6062 -0.00488645 -0.0141459 0.016547 1 0 1 1 0 0 +EDGE2 6082 6063 1.00868 0.047926 0.0236996 1 0 1 1 0 0 +EDGE2 6082 6043 0.940023 -0.0181099 0.0270199 1 0 1 1 0 0 +EDGE2 6083 6042 -0.890512 -0.0604801 0.0174611 1 0 1 1 0 0 +EDGE2 6083 6082 -1.14769 0.00646489 0.00928959 1 0 1 1 0 0 +EDGE2 6083 6062 -0.978182 -0.0261131 -0.00119395 1 0 1 1 0 0 +EDGE2 6083 6063 0.0414059 -0.0817713 -0.000388638 1 0 1 1 0 0 +EDGE2 6083 6043 -0.0707915 0.0487838 -0.00147933 1 0 1 1 0 0 +EDGE2 6083 6044 1.06468 0.0128176 0.0139975 1 0 1 1 0 0 +EDGE2 6083 6064 0.987262 -0.0378903 -0.0216368 1 0 1 1 0 0 +EDGE2 6084 6063 -0.992092 0.0351685 0.0113098 1 0 1 1 0 0 +EDGE2 6084 6083 -1.08107 0.100362 0.0222843 1 0 1 1 0 0 +EDGE2 6084 6043 -0.978478 0.0646599 -0.0055233 1 0 1 1 0 0 +EDGE2 6084 6044 0.0110312 -0.0315393 0.0357694 1 0 1 1 0 0 +EDGE2 6084 6064 -0.0183008 0.0759211 -0.00287721 1 0 1 1 0 0 +EDGE2 6084 6045 0.980684 0.0260793 -0.00559868 1 0 1 1 0 0 +EDGE2 6084 6065 0.958421 -0.0201774 -0.020073 1 0 1 1 0 0 +EDGE2 6084 605 0.965745 -0.000511181 -3.13269 1 0 1 1 0 0 +EDGE2 6085 6044 -0.987181 0.0667292 0.0137748 1 0 1 1 0 0 +EDGE2 6085 6084 -0.938321 -0.0166627 -0.000208883 1 0 1 1 0 0 +EDGE2 6085 6064 -1.0336 0.0917462 -0.0282539 1 0 1 1 0 0 +EDGE2 6085 6045 -0.0612142 -0.0878119 -0.0079722 1 0 1 1 0 0 +EDGE2 6085 6065 -0.0360486 -0.00650466 -0.033912 1 0 1 1 0 0 +EDGE2 6085 605 0.00305693 -0.0116848 -3.12965 1 0 1 1 0 0 +EDGE2 6085 604 1.01967 0.00266473 -3.15514 1 0 1 1 0 0 +EDGE2 6085 6046 0.0532358 1.03373 1.55238 1 0 1 1 0 0 +EDGE2 6085 6066 0.0378817 0.994811 1.58409 1 0 1 1 0 0 +EDGE2 6085 606 0.0102992 1.02985 1.55641 1 0 1 1 0 0 +EDGE2 6086 6045 -0.9699 -0.0549085 -1.56466 1 0 1 1 0 0 +EDGE2 6086 6065 -1.02321 0.107407 -1.59362 1 0 1 1 0 0 +EDGE2 6086 6085 -1.05989 -0.00687245 -1.56486 1 0 1 1 0 0 +EDGE2 6086 605 -1.01649 0.00641372 1.57157 1 0 1 1 0 0 +EDGE2 6086 607 0.948193 0.0252579 0.0147646 1 0 1 1 0 0 +EDGE2 6086 6067 1.00292 -0.00230829 -0.00372045 1 0 1 1 0 0 +EDGE2 6086 6046 0.00305101 0.0148354 0.0158704 1 0 1 1 0 0 +EDGE2 6086 6066 0.0912538 0.0192759 -0.000616311 1 0 1 1 0 0 +EDGE2 6086 606 -0.0591938 0.0237424 -0.00325254 1 0 1 1 0 0 +EDGE2 6086 6047 0.954928 0.0282306 -0.0125682 1 0 1 1 0 0 +EDGE2 6087 607 -0.0289416 -0.114896 0.00115142 1 0 1 1 0 0 +EDGE2 6087 6067 0.0423698 0.0365019 0.00396186 1 0 1 1 0 0 +EDGE2 6087 6046 -0.94767 0.0196853 0.0262795 1 0 1 1 0 0 +EDGE2 6087 6086 -1.04843 0.0934274 0.0069642 1 0 1 1 0 0 +EDGE2 6087 6066 -1.03239 0.0295738 0.00899388 1 0 1 1 0 0 +EDGE2 6087 606 -0.9201 0.0354133 -0.0156788 1 0 1 1 0 0 +EDGE2 6087 6047 0.113905 0.0436234 -0.01962 1 0 1 1 0 0 +EDGE2 6087 6068 0.966352 -0.0185458 -0.00670228 1 0 1 1 0 0 +EDGE2 6087 608 0.986558 -0.0578359 0.0245812 1 0 1 1 0 0 +EDGE2 6087 6048 0.97935 -0.0265214 0.0244145 1 0 1 1 0 0 +EDGE2 6088 607 -1.03721 -0.0234551 -0.0161545 1 0 1 1 0 0 +EDGE2 6088 6067 -0.971148 0.0774562 0.00559342 1 0 1 1 0 0 +EDGE2 6088 6087 -1.00407 -0.0998187 0.0118065 1 0 1 1 0 0 +EDGE2 6088 6047 -1.03634 0.0673195 -0.00787597 1 0 1 1 0 0 +EDGE2 6088 6068 -0.0594111 -0.0080667 -0.0138471 1 0 1 1 0 0 +EDGE2 6088 608 -0.0103655 -0.0630725 -0.0125274 1 0 1 1 0 0 +EDGE2 6088 6048 0.0373186 -0.144172 0.0204871 1 0 1 1 0 0 +EDGE2 6088 6049 0.975138 -0.0124565 0.0115566 1 0 1 1 0 0 +EDGE2 6088 6069 0.949938 -0.0639515 0.00339324 1 0 1 1 0 0 +EDGE2 6088 609 0.989988 0.0124816 0.0212522 1 0 1 1 0 0 +EDGE2 6089 6068 -1.02306 0.00824585 0.0112426 1 0 1 1 0 0 +EDGE2 6089 6088 -1.05277 -0.0800506 0.0171244 1 0 1 1 0 0 +EDGE2 6089 608 -1.03233 -0.05398 -0.0203628 1 0 1 1 0 0 +EDGE2 6089 6048 -1.11203 -0.0334392 0.0294349 1 0 1 1 0 0 +EDGE2 6089 6049 0.00721885 -0.0442389 0.0497468 1 0 1 1 0 0 +EDGE2 6089 6069 0.0133591 -0.0451125 0.0171677 1 0 1 1 0 0 +EDGE2 6089 609 0.0497796 -0.129623 -0.0030307 1 0 1 1 0 0 +EDGE2 6089 6050 1.04273 0.0274128 0.0178536 1 0 1 1 0 0 +EDGE2 6089 6070 1.02845 -0.0771745 -0.00509519 1 0 1 1 0 0 +EDGE2 6089 610 1.03299 -0.0444341 0.0251116 1 0 1 1 0 0 +EDGE2 6089 6030 1.00292 -0.00491566 -3.19465 1 0 1 1 0 0 +EDGE2 6090 6051 -0.0126033 1.01694 1.56673 1 0 1 1 0 0 +EDGE2 6090 6071 0.00297557 1.05125 1.54424 1 0 1 1 0 0 +EDGE2 6090 6031 -0.0574469 1.04471 1.57624 1 0 1 1 0 0 +EDGE2 6090 6089 -0.962117 -0.0824488 -0.0265726 1 0 1 1 0 0 +EDGE2 6090 6049 -0.981524 0.0322582 -0.0159879 1 0 1 1 0 0 +EDGE2 6090 6069 -0.979004 0.0316432 0.0277881 1 0 1 1 0 0 +EDGE2 6090 609 -1.00793 0.00482837 0.00999766 1 0 1 1 0 0 +EDGE2 6090 6050 0.0516434 0.0497981 0.0175725 1 0 1 1 0 0 +EDGE2 6090 6070 -0.0267627 0.0195064 0.0102723 1 0 1 1 0 0 +EDGE2 6090 610 0.083648 -0.0904157 0.000188554 1 0 1 1 0 0 +EDGE2 6090 6030 0.0104882 -0.00439951 -3.12765 1 0 1 1 0 0 +EDGE2 6090 6029 1.05772 -0.0685828 -3.14772 1 0 1 1 0 0 +EDGE2 6090 611 -0.00423991 -1.02041 -1.57506 1 0 1 1 0 0 +EDGE2 6091 6032 1.0276 0.126327 -0.0138216 1 0 1 1 0 0 +EDGE2 6091 6072 0.997917 -0.046683 0.029678 1 0 1 1 0 0 +EDGE2 6091 6052 1.01682 -0.00623141 -0.0279113 1 0 1 1 0 0 +EDGE2 6091 6051 -0.00785731 0.00314022 0.0272018 1 0 1 1 0 0 +EDGE2 6091 6071 -0.0591019 -0.00158715 0.00359122 1 0 1 1 0 0 +EDGE2 6091 6031 0.0661064 -0.0556614 0.00731891 1 0 1 1 0 0 +EDGE2 6091 6050 -0.953297 0.0247861 -1.58672 1 0 1 1 0 0 +EDGE2 6091 6090 -1.01738 -0.0283188 -1.57181 1 0 1 1 0 0 +EDGE2 6091 6070 -1.03046 0.0150249 -1.55144 1 0 1 1 0 0 +EDGE2 6091 610 -1.00703 -0.0589549 -1.54484 1 0 1 1 0 0 +EDGE2 6091 6030 -1.0095 -0.0788203 1.56247 1 0 1 1 0 0 +EDGE2 6092 6032 -0.0247904 0.00816672 0.0076291 1 0 1 1 0 0 +EDGE2 6092 6033 0.988119 -0.0464885 0.0224805 1 0 1 1 0 0 +EDGE2 6092 6053 1.0076 -0.0530325 -0.00146577 1 0 1 1 0 0 +EDGE2 6092 6073 0.954333 0.00241124 -0.022356 1 0 1 1 0 0 +EDGE2 6092 6072 -0.0590181 -0.029782 -0.0128828 1 0 1 1 0 0 +EDGE2 6092 6052 -0.00842478 0.0126246 0.0211275 1 0 1 1 0 0 +EDGE2 6092 6051 -1.04929 0.0153269 0.0259618 1 0 1 1 0 0 +EDGE2 6092 6071 -0.967601 0.0832879 -0.00113288 1 0 1 1 0 0 +EDGE2 6092 6091 -0.972919 -0.044857 0.00826511 1 0 1 1 0 0 +EDGE2 6092 6031 -1.02487 -0.0619126 0.0102737 1 0 1 1 0 0 +EDGE2 6093 6032 -0.888935 0.00926413 0.00257891 1 0 1 1 0 0 +EDGE2 6093 6034 0.988033 -0.0237696 -0.0319474 1 0 1 1 0 0 +EDGE2 6093 6054 1.04418 0.0181864 0.0103406 1 0 1 1 0 0 +EDGE2 6093 6074 1.02228 0.0173132 -0.00505527 1 0 1 1 0 0 +EDGE2 6093 6033 0.0726354 0.0992879 -0.0257755 1 0 1 1 0 0 +EDGE2 6093 6053 -0.0764553 0.00753315 -0.00816578 1 0 1 1 0 0 +EDGE2 6093 6073 -0.00681588 -0.073703 0.0114811 1 0 1 1 0 0 +EDGE2 6093 6072 -0.948956 -0.0492829 0.0321619 1 0 1 1 0 0 +EDGE2 6093 6092 -0.86366 0.0429066 -0.0370518 1 0 1 1 0 0 +EDGE2 6093 6052 -0.952386 0.0441718 -0.0101855 1 0 1 1 0 0 +EDGE2 6094 6075 1.02401 -0.0137089 0.0066424 1 0 1 1 0 0 +EDGE2 6094 6035 0.990986 -0.0864292 0.00238031 1 0 1 1 0 0 +EDGE2 6094 6055 1.06682 0.0110313 0.0138921 1 0 1 1 0 0 +EDGE2 6094 6093 -0.957009 -0.00273333 0.0304211 1 0 1 1 0 0 +EDGE2 6094 6034 0.014147 -0.0225885 0.00116389 1 0 1 1 0 0 +EDGE2 6094 6054 -0.021701 -0.0735004 0.0024759 1 0 1 1 0 0 +EDGE2 6094 6074 -0.0456484 0.0640375 -0.00797039 1 0 1 1 0 0 +EDGE2 6094 6033 -1.00997 -0.00141417 -0.00286324 1 0 1 1 0 0 +EDGE2 6094 6053 -1.01644 0.00172463 -0.000731922 1 0 1 1 0 0 +EDGE2 6094 6073 -1.02508 0.022193 -0.00922735 1 0 1 1 0 0 +EDGE2 6095 6094 -1.01664 -0.00507214 -0.00563092 1 0 1 1 0 0 +EDGE2 6095 6056 0.0411033 0.961826 1.5585 1 0 1 1 0 0 +EDGE2 6095 6076 0.0516676 0.990952 1.60389 1 0 1 1 0 0 +EDGE2 6095 6075 0.0927054 0.00933332 -0.038319 1 0 1 1 0 0 +EDGE2 6095 6036 0.0950929 1.01657 1.56697 1 0 1 1 0 0 +EDGE2 6095 6035 -0.0544311 -0.0419663 -0.0110467 1 0 1 1 0 0 +EDGE2 6095 6055 -0.100315 -0.0301302 -0.0303217 1 0 1 1 0 0 +EDGE2 6095 6034 -0.998594 0.104424 -0.00347558 1 0 1 1 0 0 +EDGE2 6095 6054 -1.01797 0.0527205 0.0255568 1 0 1 1 0 0 +EDGE2 6095 6074 -0.978247 0.0344669 0.00443788 1 0 1 1 0 0 +EDGE2 6096 6056 0.0251454 -0.00742691 -0.00769409 1 0 1 1 0 0 +EDGE2 6096 6037 1.07559 0.0251924 -0.00135111 1 0 1 1 0 0 +EDGE2 6096 6077 1.00302 0.034409 0.0314263 1 0 1 1 0 0 +EDGE2 6096 6057 0.924866 0.030187 -0.0099375 1 0 1 1 0 0 +EDGE2 6096 6076 0.0654303 -0.0514332 0.0167665 1 0 1 1 0 0 +EDGE2 6096 6075 -1.01468 -0.0447738 -1.57629 1 0 1 1 0 0 +EDGE2 6096 6036 -0.0501407 -0.0017283 -0.00782253 1 0 1 1 0 0 +EDGE2 6096 6095 -1.03003 0.0920384 -1.55715 1 0 1 1 0 0 +EDGE2 6096 6035 -1.02739 0.0357566 -1.56506 1 0 1 1 0 0 +EDGE2 6096 6055 -0.970353 -0.00445345 -1.56133 1 0 1 1 0 0 +EDGE2 6097 6078 0.943192 -0.0650351 0.00498997 1 0 1 1 0 0 +EDGE2 6097 6058 1.04495 -0.0515317 0.0137592 1 0 1 1 0 0 +EDGE2 6097 6038 0.977 0.0034245 -0.0047728 1 0 1 1 0 0 +EDGE2 6097 6056 -0.854416 -0.0415502 -0.015713 1 0 1 1 0 0 +EDGE2 6097 6037 0.0110664 -0.052664 0.0131281 1 0 1 1 0 0 +EDGE2 6097 6077 0.0220788 0.0567989 -0.00217562 1 0 1 1 0 0 +EDGE2 6097 6057 0.071624 0.0126944 -0.0174422 1 0 1 1 0 0 +EDGE2 6097 6096 -1.03203 0.0822943 0.0172555 1 0 1 1 0 0 +EDGE2 6097 6076 -1.00347 -0.00523179 0.0422517 1 0 1 1 0 0 +EDGE2 6097 6036 -0.992778 -0.105444 -0.0244358 1 0 1 1 0 0 +EDGE2 6098 6078 0.0110592 -0.00992171 0.00684472 1 0 1 1 0 0 +EDGE2 6098 6059 1.05494 -0.00899434 -0.00389345 1 0 1 1 0 0 +EDGE2 6098 6079 1.02528 -0.011829 -0.000934834 1 0 1 1 0 0 +EDGE2 6098 6039 1.12625 -0.0328519 -0.0210577 1 0 1 1 0 0 +EDGE2 6098 6058 -0.00390604 -0.0348644 -0.00345434 1 0 1 1 0 0 +EDGE2 6098 6038 -0.000992857 0.0524538 0.0304381 1 0 1 1 0 0 +EDGE2 6098 6037 -0.920054 0.030964 -0.0251355 1 0 1 1 0 0 +EDGE2 6098 6077 -0.999118 -0.0185314 0.0291107 1 0 1 1 0 0 +EDGE2 6098 6097 -1.00084 -0.0117244 0.00702964 1 0 1 1 0 0 +EDGE2 6098 6057 -0.993709 -0.0497924 -0.0213028 1 0 1 1 0 0 +EDGE2 6099 6040 1.04697 0.0427986 0.00499014 1 0 1 1 0 0 +EDGE2 6099 6060 1.05632 -0.0698364 -0.0090936 1 0 1 1 0 0 +EDGE2 6099 6080 1.02537 -0.0300162 0.0261917 1 0 1 1 0 0 +EDGE2 6099 6078 -1.01466 0.014095 0.000564112 1 0 1 1 0 0 +EDGE2 6099 6059 -0.0356877 -0.0632491 -0.00751641 1 0 1 1 0 0 +EDGE2 6099 6079 -0.00553447 -0.0187288 0.0293321 1 0 1 1 0 0 +EDGE2 6099 6039 -0.0227624 0.0395448 0.0448622 1 0 1 1 0 0 +EDGE2 6099 6098 -1.01868 0.0501386 0.0249723 1 0 1 1 0 0 +EDGE2 6099 6058 -0.966908 0.00444413 -0.0149487 1 0 1 1 0 0 +EDGE2 6099 6038 -1.04608 -0.0554222 -0.00843399 1 0 1 1 0 0 +EDGE2 6100 6040 -0.027787 -0.0752991 -0.0270645 1 0 1 1 0 0 +EDGE2 6100 6060 -0.0653333 -0.0341777 -0.0215354 1 0 1 1 0 0 +EDGE2 6100 6080 0.03259 -0.00981876 0.00960927 1 0 1 1 0 0 +EDGE2 6100 6061 -0.0155603 0.974445 1.57837 1 0 1 1 0 0 +EDGE2 6100 6081 0.0708992 1.00971 1.58092 1 0 1 1 0 0 +EDGE2 6100 6041 0.0457612 0.983402 1.59805 1 0 1 1 0 0 +EDGE2 6100 6059 -0.983207 0.023184 0.0110921 1 0 1 1 0 0 +EDGE2 6100 6099 -0.992559 -0.00107906 -0.0479902 1 0 1 1 0 0 +EDGE2 6100 6079 -1.01028 -0.0171487 0.00522792 1 0 1 1 0 0 +EDGE2 6100 6039 -0.995427 0.0955023 0.00206108 1 0 1 1 0 0 +EDGE2 6101 6100 -1.00837 0.0274971 1.56292 1 0 1 1 0 0 +EDGE2 6101 6040 -1.12602 -0.00217631 1.56853 1 0 1 1 0 0 +EDGE2 6101 6060 -1.07509 0.00575403 1.53853 1 0 1 1 0 0 +EDGE2 6101 6080 -0.945251 0.0196446 1.57879 1 0 1 1 0 0 +EDGE2 6102 6101 -0.989883 -0.0169223 0.0168082 1 0 1 1 0 0 +EDGE2 6103 6102 -1.05789 0.0409578 -0.00116741 1 0 1 1 0 0 +EDGE2 6104 6103 -1.07962 0.110624 0.0269128 1 0 1 1 0 0 +EDGE2 6105 6104 -0.97327 -0.07893 0.00469777 1 0 1 1 0 0 +EDGE2 6106 6105 -1.05606 0.0289009 -1.55457 1 0 1 1 0 0 +EDGE2 6107 6106 -0.941347 0.00717461 0.0324723 1 0 1 1 0 0 +EDGE2 6108 6107 -1.02336 -0.0982812 0.00563898 1 0 1 1 0 0 +EDGE2 6109 6108 -0.993088 0.0374829 -0.0133226 1 0 1 1 0 0 +EDGE2 6110 6109 -1.00683 0.0575327 0.0142501 1 0 1 1 0 0 +EDGE2 6111 6110 -1.07343 -0.0380083 1.55638 1 0 1 1 0 0 +EDGE2 6112 6111 -0.960453 0.015391 0.0416478 1 0 1 1 0 0 +EDGE2 6113 6112 -0.946421 0.00217077 0.0180705 1 0 1 1 0 0 +EDGE2 6114 6113 -0.974616 0.0178751 0.00650579 1 0 1 1 0 0 +EDGE2 6115 6114 -1.02794 -0.0370538 -0.0238593 1 0 1 1 0 0 +EDGE2 6116 6115 -0.952514 0.02763 -1.58028 1 0 1 1 0 0 +EDGE2 6117 6116 -1.02264 0.00544964 -0.00521542 1 0 1 1 0 0 +EDGE2 6118 6117 -0.924856 0.0184558 0.0122954 1 0 1 1 0 0 +EDGE2 6119 6118 -1.13195 -0.0334642 -0.0300777 1 0 1 1 0 0 +EDGE2 6120 6119 -1.01599 0.00489677 0.00786461 1 0 1 1 0 0 +EDGE2 6121 6120 -0.965308 -0.0185733 -1.55039 1 0 1 1 0 0 +EDGE2 6122 6121 -1.03933 -0.086664 0.0247681 1 0 1 1 0 0 +EDGE2 6123 6122 -1.05293 0.0302707 0.0432069 1 0 1 1 0 0 +EDGE2 6124 6123 -0.928541 0.0486654 0.00626891 1 0 1 1 0 0 +EDGE2 6125 6124 -1.00848 0.0165511 0.0193496 1 0 1 1 0 0 +EDGE2 6126 6125 -1.01425 -0.0855335 1.58489 1 0 1 1 0 0 +EDGE2 6127 6126 -1.03189 0.0312141 0.0155049 1 0 1 1 0 0 +EDGE2 6128 6127 -1.01809 -0.0408602 0.00184383 1 0 1 1 0 0 +EDGE2 6129 570 1.01956 -0.0730262 -3.13493 1 0 1 1 0 0 +EDGE2 6129 6128 -1.04618 -0.0068561 -0.0285917 1 0 1 1 0 0 +EDGE2 6130 570 0.0577671 0.0316071 -3.16928 1 0 1 1 0 0 +EDGE2 6130 569 1.07451 -0.0437882 -3.0985 1 0 1 1 0 0 +EDGE2 6130 571 -0.00944197 0.918289 1.57326 1 0 1 1 0 0 +EDGE2 6130 6129 -0.995264 -0.0165762 0.00348179 1 0 1 1 0 0 +EDGE2 6131 570 -0.964065 -0.0651476 -1.6114 1 0 1 1 0 0 +EDGE2 6131 6130 -0.952703 0.0603001 1.57789 1 0 1 1 0 0 +EDGE2 6132 6131 -0.96791 0.0157216 -0.0115322 1 0 1 1 0 0 +EDGE2 6133 6132 -0.931061 0.0685403 -0.00755537 1 0 1 1 0 0 +EDGE2 6134 6133 -0.924179 -0.0320642 0.0281501 1 0 1 1 0 0 +EDGE2 6135 6134 -1.02084 0.0275107 -0.0125705 1 0 1 1 0 0 +EDGE2 6136 6135 -0.943102 0.0323075 -1.58736 1 0 1 1 0 0 +EDGE2 6137 6136 -1.03601 0.0881508 0.000712304 1 0 1 1 0 0 +EDGE2 6138 6137 -0.955606 -0.063278 -0.0147561 1 0 1 1 0 0 +EDGE2 6139 560 0.98518 0.036756 -3.17256 1 0 1 1 0 0 +EDGE2 6139 6138 -0.984954 0.00957652 -0.0182967 1 0 1 1 0 0 +EDGE2 6140 561 -0.014766 0.956708 1.57172 1 0 1 1 0 0 +EDGE2 6140 560 0.0439342 -0.0443572 -3.13914 1 0 1 1 0 0 +EDGE2 6140 559 0.97798 0.0146103 -3.10901 1 0 1 1 0 0 +EDGE2 6140 6139 -1.02025 -0.0454221 0.0302454 1 0 1 1 0 0 +EDGE2 6141 561 -0.0985723 -0.0434343 -0.012299 1 0 1 1 0 0 +EDGE2 6141 560 -0.954332 -0.0106277 1.56562 1 0 1 1 0 0 +EDGE2 6141 6140 -1.03961 0.0558314 -1.5706 1 0 1 1 0 0 +EDGE2 6141 562 1.02443 0.0026548 -0.0333808 1 0 1 1 0 0 +EDGE2 6142 561 -1.04644 0.0341296 0.011806 1 0 1 1 0 0 +EDGE2 6142 6141 -0.954064 -0.025947 -0.0279748 1 0 1 1 0 0 +EDGE2 6142 562 0.0167857 -0.0030147 -0.00386933 1 0 1 1 0 0 +EDGE2 6142 563 1.05658 0.0178981 0.0176461 1 0 1 1 0 0 +EDGE2 6143 562 -1.0077 -0.00821121 0.00914652 1 0 1 1 0 0 +EDGE2 6143 6142 -1.0863 0.0163933 0.0269115 1 0 1 1 0 0 +EDGE2 6143 563 -0.00864368 0.00390436 -0.0161034 1 0 1 1 0 0 +EDGE2 6143 564 1.06142 0.0225309 0.0231858 1 0 1 1 0 0 +EDGE2 6144 6143 -0.970281 0.0293674 -0.0245118 1 0 1 1 0 0 +EDGE2 6144 563 -1.03665 -0.0438337 -0.0231191 1 0 1 1 0 0 +EDGE2 6144 564 -0.129937 0.0662374 -0.0265107 1 0 1 1 0 0 +EDGE2 6144 565 1.0272 -0.0634252 0.0295614 1 0 1 1 0 0 +EDGE2 6145 6144 -1.04272 -0.0244488 0.00669726 1 0 1 1 0 0 +EDGE2 6145 564 -1.00353 -0.0173103 -0.0119987 1 0 1 1 0 0 +EDGE2 6145 565 -0.00366035 -0.0792312 -0.0123803 1 0 1 1 0 0 +EDGE2 6145 566 0.0565112 1.00856 1.58194 1 0 1 1 0 0 +EDGE2 6146 565 -0.987297 -0.0477801 -1.55918 1 0 1 1 0 0 +EDGE2 6146 6145 -1.02209 -0.0926457 -1.57235 1 0 1 1 0 0 +EDGE2 6146 566 0.0528822 -0.0222353 -0.0301678 1 0 1 1 0 0 +EDGE2 6146 567 1.00232 0.099751 0.0138174 1 0 1 1 0 0 +EDGE2 6147 566 -1.00096 0.0257124 -0.0405171 1 0 1 1 0 0 +EDGE2 6147 6146 -1.01523 0.060772 -0.0229501 1 0 1 1 0 0 +EDGE2 6147 567 0.037304 -0.00485739 0.0150663 1 0 1 1 0 0 +EDGE2 6147 568 1.00391 0.0382825 -0.0279573 1 0 1 1 0 0 +EDGE2 6148 6147 -1.05769 0.00402686 -0.000177466 1 0 1 1 0 0 +EDGE2 6148 567 -0.973491 -0.0584776 -0.00995012 1 0 1 1 0 0 +EDGE2 6148 568 0.0114101 -0.0193678 -0.0123229 1 0 1 1 0 0 +EDGE2 6148 569 0.950234 0.0660626 -0.000552488 1 0 1 1 0 0 +EDGE2 6149 6148 -1.01624 -0.0713193 0.0156458 1 0 1 1 0 0 +EDGE2 6149 568 -0.973968 -0.0441989 -0.00184293 1 0 1 1 0 0 +EDGE2 6149 570 0.956505 -0.0363082 -0.0013322 1 0 1 1 0 0 +EDGE2 6149 569 -0.0440675 -0.0396887 0.00988775 1 0 1 1 0 0 +EDGE2 6149 6130 1.0461 0.00225025 -3.12508 1 0 1 1 0 0 +EDGE2 6150 570 -0.0199839 0.0445807 -0.0163487 1 0 1 1 0 0 +EDGE2 6150 569 -0.974346 -0.0338735 -0.0143812 1 0 1 1 0 0 +EDGE2 6150 6149 -0.941184 0.0416694 0.0530695 1 0 1 1 0 0 +EDGE2 6150 6131 -0.0724203 0.968275 1.58337 1 0 1 1 0 0 +EDGE2 6150 6130 -0.025842 0.0142908 -3.13114 1 0 1 1 0 0 +EDGE2 6150 571 0.066936 -1.05624 -1.58293 1 0 1 1 0 0 +EDGE2 6150 6129 0.926062 0.0163829 -3.11955 1 0 1 1 0 0 +EDGE2 6151 570 -0.980896 -0.00640926 1.57622 1 0 1 1 0 0 +EDGE2 6151 6150 -1.08225 -0.0595497 1.61025 1 0 1 1 0 0 +EDGE2 6151 6130 -1.02849 0.025901 -1.58964 1 0 1 1 0 0 +EDGE2 6151 572 1.01303 -0.0758506 -0.0136186 1 0 1 1 0 0 +EDGE2 6151 571 0.0739217 0.0662417 0.00323813 1 0 1 1 0 0 +EDGE2 6152 572 -0.021689 -0.0935379 0.000580981 1 0 1 1 0 0 +EDGE2 6152 571 -1.0137 0.0328784 0.0184197 1 0 1 1 0 0 +EDGE2 6152 6151 -0.970101 0.0791971 0.0308887 1 0 1 1 0 0 +EDGE2 6152 573 0.989784 0.00782968 0.00299739 1 0 1 1 0 0 +EDGE2 6153 572 -0.961553 -0.0858472 -0.00822594 1 0 1 1 0 0 +EDGE2 6153 6152 -0.978168 -0.0147594 -0.00638765 1 0 1 1 0 0 +EDGE2 6153 573 0.0567185 -0.0143836 0.00732876 1 0 1 1 0 0 +EDGE2 6153 574 0.982015 0.0245306 -0.0247715 1 0 1 1 0 0 +EDGE2 6154 573 -0.964991 -0.0401667 0.0267918 1 0 1 1 0 0 +EDGE2 6154 6153 -1.02617 -0.0323949 -0.0240397 1 0 1 1 0 0 +EDGE2 6154 574 0.039493 -0.0492772 -0.00949372 1 0 1 1 0 0 +EDGE2 6154 575 1.01397 0.00413026 -0.000495934 1 0 1 1 0 0 +EDGE2 6155 6154 -0.968431 0.00987848 -0.0217615 1 0 1 1 0 0 +EDGE2 6155 574 -0.997357 0.0304924 0.000497672 1 0 1 1 0 0 +EDGE2 6155 575 0.0250306 -0.0530761 0.0316837 1 0 1 1 0 0 +EDGE2 6155 576 -0.00730057 0.951862 1.55327 1 0 1 1 0 0 +EDGE2 6156 575 -0.976275 0.0445889 -1.57432 1 0 1 1 0 0 +EDGE2 6156 6155 -1.02012 -0.107726 -1.55909 1 0 1 1 0 0 +EDGE2 6156 576 -0.0574928 -0.0282312 0.00187538 1 0 1 1 0 0 +EDGE2 6156 577 1.02368 -0.0254718 -0.0164513 1 0 1 1 0 0 +EDGE2 6157 6156 -0.951642 0.0309739 0.0101856 1 0 1 1 0 0 +EDGE2 6157 576 -1.03918 -0.0345726 -0.000745585 1 0 1 1 0 0 +EDGE2 6157 577 0.019209 0.0115065 0.0103125 1 0 1 1 0 0 +EDGE2 6157 578 1.02344 0.0288826 0.0101521 1 0 1 1 0 0 +EDGE2 6158 577 -1.00897 0.0571317 -0.00622121 1 0 1 1 0 0 +EDGE2 6158 6157 -0.926137 0.14197 -0.0228018 1 0 1 1 0 0 +EDGE2 6158 578 -0.0836051 0.0254302 0.00622259 1 0 1 1 0 0 +EDGE2 6158 579 1.02103 0.000829176 0.0002692 1 0 1 1 0 0 +EDGE2 6159 6158 -0.976656 0.0225471 -0.00501128 1 0 1 1 0 0 +EDGE2 6159 578 -0.942136 -0.04335 0.0108236 1 0 1 1 0 0 +EDGE2 6159 579 0.0455754 0.0267488 -0.0733536 1 0 1 1 0 0 +EDGE2 6159 580 0.919589 0.00285521 0.0286248 1 0 1 1 0 0 +EDGE2 6160 579 -1.00948 -0.000967823 0.0278559 1 0 1 1 0 0 +EDGE2 6160 6159 -0.98281 -0.0768672 -0.0605407 1 0 1 1 0 0 +EDGE2 6160 581 0.00492873 -1.01706 -1.56432 1 0 1 1 0 0 +EDGE2 6160 580 -0.0315989 -0.104882 -0.00590476 1 0 1 1 0 0 +EDGE2 6161 6160 -1.01408 0.00914215 -1.55907 1 0 1 1 0 0 +EDGE2 6161 580 -1.07909 0.021925 -1.56093 1 0 1 1 0 0 +EDGE2 6162 6161 -1.0833 -0.00837414 0.00752303 1 0 1 1 0 0 +EDGE2 6163 6162 -0.953256 0.0689125 -0.00514257 1 0 1 1 0 0 +EDGE2 6164 6163 -1.00533 -0.046929 -0.0333047 1 0 1 1 0 0 +EDGE2 6164 6125 1.0362 -0.0307621 -3.14277 1 0 1 1 0 0 +EDGE2 6165 6164 -1.03442 -0.053341 -0.0366619 1 0 1 1 0 0 +EDGE2 6165 6126 0.120164 1.01853 1.59832 1 0 1 1 0 0 +EDGE2 6165 6124 0.921437 -0.0404498 -3.14987 1 0 1 1 0 0 +EDGE2 6165 6125 -0.0102776 -0.0487874 -3.1492 1 0 1 1 0 0 +EDGE2 6166 6165 -0.946453 -0.0631412 1.56954 1 0 1 1 0 0 +EDGE2 6166 6125 -0.984802 -0.0904282 -1.6006 1 0 1 1 0 0 +EDGE2 6167 6166 -1.08217 0.0733947 0.00248394 1 0 1 1 0 0 +EDGE2 6168 6167 -1.06011 0.000516623 -0.00513445 1 0 1 1 0 0 +EDGE2 6169 6168 -0.960479 0.0396915 -0.0207669 1 0 1 1 0 0 +EDGE2 6169 6110 0.992132 -0.0116144 -3.13296 1 0 1 1 0 0 +EDGE2 6170 6111 -0.0242697 0.940043 1.59884 1 0 1 1 0 0 +EDGE2 6170 6169 -0.987986 -0.00346757 -0.0158411 1 0 1 1 0 0 +EDGE2 6170 6110 0.0226598 0.040356 -3.13545 1 0 1 1 0 0 +EDGE2 6170 6109 0.965016 -0.0260531 -3.12395 1 0 1 1 0 0 +EDGE2 6171 6112 0.947114 0.0804227 0.0351337 1 0 1 1 0 0 +EDGE2 6171 6111 -0.0392084 -0.0341512 5.9754e-05 1 0 1 1 0 0 +EDGE2 6171 6110 -1.01825 0.00204771 1.56005 1 0 1 1 0 0 +EDGE2 6171 6170 -0.975244 0.126483 -1.58846 1 0 1 1 0 0 +EDGE2 6172 6113 0.957321 -0.0339783 -0.019525 1 0 1 1 0 0 +EDGE2 6172 6171 -1.06578 -0.05285 0.00339213 1 0 1 1 0 0 +EDGE2 6172 6112 -0.0099317 -0.0218875 -0.0307722 1 0 1 1 0 0 +EDGE2 6172 6111 -1.03839 -0.102173 -0.0169257 1 0 1 1 0 0 +EDGE2 6173 6114 0.914685 0.0042841 0.00755158 1 0 1 1 0 0 +EDGE2 6173 6113 0.0986554 -0.0325386 0.0100268 1 0 1 1 0 0 +EDGE2 6173 6112 -1.10138 -0.0487534 0.0278009 1 0 1 1 0 0 +EDGE2 6173 6172 -0.90391 -4.5719e-05 -0.00229429 1 0 1 1 0 0 +EDGE2 6174 6115 0.950338 -0.0137317 -0.043202 1 0 1 1 0 0 +EDGE2 6174 6114 0.105413 -0.118127 0.00366497 1 0 1 1 0 0 +EDGE2 6174 6113 -0.936227 -0.0373678 0.0034735 1 0 1 1 0 0 +EDGE2 6174 6173 -1.03323 -0.0348301 0.0097783 1 0 1 1 0 0 +EDGE2 6175 6116 0.100053 0.985359 1.58792 1 0 1 1 0 0 +EDGE2 6175 6174 -1.00602 0.110336 -0.0170949 1 0 1 1 0 0 +EDGE2 6175 6115 0.0913344 -0.0208687 0.00411293 1 0 1 1 0 0 +EDGE2 6175 6114 -1.05703 -0.0823236 0.00144093 1 0 1 1 0 0 +EDGE2 6176 6175 -1.0501 -0.0775977 -1.62482 1 0 1 1 0 0 +EDGE2 6176 6117 0.914173 0.0434089 -0.00943718 1 0 1 1 0 0 +EDGE2 6176 6116 0.0534369 0.0211859 -0.00667127 1 0 1 1 0 0 +EDGE2 6176 6115 -1.03082 -0.138639 -1.55198 1 0 1 1 0 0 +EDGE2 6177 6118 1.06139 0.102466 -0.0252934 1 0 1 1 0 0 +EDGE2 6177 6176 -1.08789 0.0278629 -0.0341772 1 0 1 1 0 0 +EDGE2 6177 6117 0.0166918 0.00769168 -0.0411705 1 0 1 1 0 0 +EDGE2 6177 6116 -0.981783 -0.0281442 0.0102982 1 0 1 1 0 0 +EDGE2 6178 6119 0.949668 0.0649231 -0.0153019 1 0 1 1 0 0 +EDGE2 6178 6118 0.0403331 -0.0127329 -0.00348532 1 0 1 1 0 0 +EDGE2 6178 6117 -0.997809 -0.0096612 0.00514339 1 0 1 1 0 0 +EDGE2 6178 6177 -0.967071 -0.0436549 -0.0264487 1 0 1 1 0 0 +EDGE2 6179 6120 1.06571 0.0148638 -0.00267715 1 0 1 1 0 0 +EDGE2 6179 6178 -1.03055 0.0288282 0.000530541 1 0 1 1 0 0 +EDGE2 6179 6119 -0.0550967 -0.0221789 -3.98796e-06 1 0 1 1 0 0 +EDGE2 6179 6118 -0.913676 0.0286636 -0.0153844 1 0 1 1 0 0 +EDGE2 6180 6121 -0.00381821 1.04796 1.56647 1 0 1 1 0 0 +EDGE2 6180 6120 -0.0795976 -0.0116847 0.0444432 1 0 1 1 0 0 +EDGE2 6180 6119 -1.05021 0.0312666 -0.00316678 1 0 1 1 0 0 +EDGE2 6180 6179 -0.979632 0.0258593 0.0123275 1 0 1 1 0 0 +EDGE2 6181 6122 0.96048 -0.0491423 -0.0047853 1 0 1 1 0 0 +EDGE2 6181 6121 -0.0721837 -0.0295054 -0.0113183 1 0 1 1 0 0 +EDGE2 6181 6180 -1.01833 0.0641478 -1.54643 1 0 1 1 0 0 +EDGE2 6181 6120 -0.988256 0.0145016 -1.57815 1 0 1 1 0 0 +EDGE2 6182 6122 -0.0358989 0.0279214 0.00146325 1 0 1 1 0 0 +EDGE2 6182 6181 -0.997136 -0.022507 -0.0482538 1 0 1 1 0 0 +EDGE2 6182 6121 -1.08403 -0.0124639 -0.0140126 1 0 1 1 0 0 +EDGE2 6182 6123 1.01175 0.0361455 -0.0115046 1 0 1 1 0 0 +EDGE2 6183 6122 -1.02575 0.010194 0.00093273 1 0 1 1 0 0 +EDGE2 6183 6182 -1.02746 0.0774743 0.00585391 1 0 1 1 0 0 +EDGE2 6183 6123 0.00890098 0.0490039 0.0341297 1 0 1 1 0 0 +EDGE2 6183 6124 0.922229 -0.021072 0.00164099 1 0 1 1 0 0 +EDGE2 6184 6165 1.00365 -0.0825542 -3.139 1 0 1 1 0 0 +EDGE2 6184 6123 -1.02546 0.0332593 -0.00649577 1 0 1 1 0 0 +EDGE2 6184 6183 -1.01022 -0.0218064 -0.012682 1 0 1 1 0 0 +EDGE2 6184 6124 0.0201005 0.0503656 -0.0199799 1 0 1 1 0 0 +EDGE2 6184 6125 0.917995 -0.0768141 -0.0152659 1 0 1 1 0 0 +EDGE2 6185 6164 1.01294 0.00147328 -3.15032 1 0 1 1 0 0 +EDGE2 6185 6165 -0.0605212 0.0453389 -3.16758 1 0 1 1 0 0 +EDGE2 6185 6126 0.0300455 -1.01118 -1.56954 1 0 1 1 0 0 +EDGE2 6185 6184 -0.937177 0.0298082 0.00702917 1 0 1 1 0 0 +EDGE2 6185 6124 -0.964898 -0.0304186 -0.0369354 1 0 1 1 0 0 +EDGE2 6185 6166 -0.016422 1.05053 1.52929 1 0 1 1 0 0 +EDGE2 6185 6125 -0.00121418 0.018043 -0.000118106 1 0 1 1 0 0 +EDGE2 6186 6165 -1.01459 0.00141535 1.57387 1 0 1 1 0 0 +EDGE2 6186 6166 0.0146486 0.115654 0.00138722 1 0 1 1 0 0 +EDGE2 6186 6125 -0.977337 0.00257589 -1.56619 1 0 1 1 0 0 +EDGE2 6186 6185 -1.0375 0.0135302 -1.55961 1 0 1 1 0 0 +EDGE2 6186 6167 1.01706 0.0179087 -0.0163799 1 0 1 1 0 0 +EDGE2 6187 6186 -0.971886 -0.0809317 -0.00965317 1 0 1 1 0 0 +EDGE2 6187 6166 -0.961171 0.0425011 -0.000735816 1 0 1 1 0 0 +EDGE2 6187 6168 0.973459 -0.000372805 -0.00277227 1 0 1 1 0 0 +EDGE2 6187 6167 0.0622032 0.104659 -0.0101247 1 0 1 1 0 0 +EDGE2 6188 6168 0.0597816 -0.0240808 0.0100342 1 0 1 1 0 0 +EDGE2 6188 6167 -1.01845 -0.00767467 -0.0290479 1 0 1 1 0 0 +EDGE2 6188 6187 -1.0054 -0.0410092 0.00449458 1 0 1 1 0 0 +EDGE2 6188 6169 0.998202 0.0275601 0.00825093 1 0 1 1 0 0 +EDGE2 6189 6168 -0.961796 0.0636095 0.016224 1 0 1 1 0 0 +EDGE2 6189 6188 -0.989841 0.0310443 -0.0272748 1 0 1 1 0 0 +EDGE2 6189 6169 0.0948806 -0.00554573 0.0113788 1 0 1 1 0 0 +EDGE2 6189 6110 0.93566 0.0298991 -3.13476 1 0 1 1 0 0 +EDGE2 6189 6170 0.967748 -0.0561021 0.0245463 1 0 1 1 0 0 +EDGE2 6190 6171 -0.000633302 0.980695 1.59361 1 0 1 1 0 0 +EDGE2 6190 6111 0.023559 0.996796 1.57359 1 0 1 1 0 0 +EDGE2 6190 6189 -1.01476 0.079965 0.0291836 1 0 1 1 0 0 +EDGE2 6190 6169 -0.922281 0.0209404 0.0129574 1 0 1 1 0 0 +EDGE2 6190 6110 0.0808817 -0.0970922 -3.12898 1 0 1 1 0 0 +EDGE2 6190 6170 0.0414082 0.0194576 -0.0242952 1 0 1 1 0 0 +EDGE2 6190 6109 0.944018 0.0872692 -3.15323 1 0 1 1 0 0 +EDGE2 6191 6110 -0.933542 0.00892502 -1.59444 1 0 1 1 0 0 +EDGE2 6191 6170 -1.00278 0.0588058 1.56695 1 0 1 1 0 0 +EDGE2 6191 6190 -1.02535 -0.0254158 1.58433 1 0 1 1 0 0 +EDGE2 6192 6191 -1.07595 -0.0298484 0.00417473 1 0 1 1 0 0 +EDGE2 6193 6192 -0.937328 -0.0900846 -0.00836023 1 0 1 1 0 0 +EDGE2 6194 6193 -0.978693 0.0129568 0.000588455 1 0 1 1 0 0 +EDGE2 6195 6194 -0.979422 -0.0239727 -0.0187786 1 0 1 1 0 0 +EDGE2 6196 6195 -0.99269 -0.0239908 -1.57271 1 0 1 1 0 0 +EDGE2 6197 6196 -0.967475 -0.0606199 0.0443389 1 0 1 1 0 0 +EDGE2 6198 6197 -1.03373 -0.0893864 -0.0367374 1 0 1 1 0 0 +EDGE2 6199 6198 -0.934249 -0.000883864 0.0186489 1 0 1 1 0 0 +EDGE2 6199 6100 0.982205 -0.00352719 -3.16819 1 0 1 1 0 0 +EDGE2 6199 6040 0.974381 0.055914 -3.17695 1 0 1 1 0 0 +EDGE2 6199 6060 1.03804 0.0785718 -3.13716 1 0 1 1 0 0 +EDGE2 6199 6080 1.0322 0.0808311 -3.14286 1 0 1 1 0 0 +EDGE2 6200 6101 0.037299 1.00504 1.56284 1 0 1 1 0 0 +EDGE2 6200 6199 -0.964773 -0.0749993 -0.00065186 1 0 1 1 0 0 +EDGE2 6200 6100 -0.0577838 -0.0487758 -3.11529 1 0 1 1 0 0 +EDGE2 6200 6040 -0.01246 0.00670523 -3.1658 1 0 1 1 0 0 +EDGE2 6200 6060 -0.0770823 0.026022 -3.1548 1 0 1 1 0 0 +EDGE2 6200 6080 0.0179863 -0.0314635 -3.12894 1 0 1 1 0 0 +EDGE2 6200 6061 0.0285617 -1.0001 -1.60426 1 0 1 1 0 0 +EDGE2 6200 6081 -0.01305 -1.02372 -1.57701 1 0 1 1 0 0 +EDGE2 6200 6041 -0.0415316 -0.914744 -1.57499 1 0 1 1 0 0 +EDGE2 6200 6059 0.909182 -0.0173883 -3.17436 1 0 1 1 0 0 +EDGE2 6200 6099 0.976473 -0.00762862 -3.15927 1 0 1 1 0 0 +EDGE2 6200 6079 1.12718 -0.0173286 -3.12703 1 0 1 1 0 0 +EDGE2 6200 6039 1.00073 0.0263315 -3.12905 1 0 1 1 0 0 +EDGE2 6201 6101 0.0326769 -0.039181 -0.0119724 1 0 1 1 0 0 +EDGE2 6201 6102 1.01091 -0.0719406 0.0118128 1 0 1 1 0 0 +EDGE2 6201 6100 -0.99325 -0.045991 1.58127 1 0 1 1 0 0 +EDGE2 6201 6200 -1.06882 -0.0217752 -1.57264 1 0 1 1 0 0 +EDGE2 6201 6040 -0.917356 0.0697803 1.62017 1 0 1 1 0 0 +EDGE2 6201 6060 -1.04183 -0.00440726 1.5566 1 0 1 1 0 0 +EDGE2 6201 6080 -1.00069 0.00906576 1.55619 1 0 1 1 0 0 +EDGE2 6202 6101 -1.02153 -0.0394022 0.00482676 1 0 1 1 0 0 +EDGE2 6202 6103 1.02648 0.0514915 0.0277317 1 0 1 1 0 0 +EDGE2 6202 6102 0.0290444 -0.0176008 -0.00398096 1 0 1 1 0 0 +EDGE2 6202 6201 -0.973668 -0.0571996 0.0288059 1 0 1 1 0 0 +EDGE2 6203 6103 -0.0314172 -0.0667286 -0.0236768 1 0 1 1 0 0 +EDGE2 6203 6104 0.950227 0.020219 -0.0218957 1 0 1 1 0 0 +EDGE2 6203 6102 -0.933695 0.0692437 0.00966029 1 0 1 1 0 0 +EDGE2 6203 6202 -1.12335 -0.0360624 0.0254423 1 0 1 1 0 0 +EDGE2 6204 6103 -1.04633 -0.0401443 -0.0140095 1 0 1 1 0 0 +EDGE2 6204 6104 -0.0821997 -0.051911 -0.0005232 1 0 1 1 0 0 +EDGE2 6204 6105 1.03034 0.0347965 0.0374837 1 0 1 1 0 0 +EDGE2 6204 6203 -0.944371 0.0427055 0.0153436 1 0 1 1 0 0 +EDGE2 6205 6106 -0.0557257 1.10198 1.59194 1 0 1 1 0 0 +EDGE2 6205 6104 -1.01806 0.0169617 0.0227611 1 0 1 1 0 0 +EDGE2 6205 6204 -1.03894 -0.0324173 0.0169962 1 0 1 1 0 0 +EDGE2 6205 6105 0.0363219 -0.0815139 -0.0134112 1 0 1 1 0 0 +EDGE2 6206 6205 -0.952472 0.0402918 -1.5673 1 0 1 1 0 0 +EDGE2 6206 6107 1.05396 0.0229934 -0.015865 1 0 1 1 0 0 +EDGE2 6206 6106 0.00421138 -0.00242885 0.0267538 1 0 1 1 0 0 +EDGE2 6206 6105 -0.99474 0.00269883 -1.56371 1 0 1 1 0 0 +EDGE2 6207 6108 1.03277 0.00486978 -0.0142056 1 0 1 1 0 0 +EDGE2 6207 6206 -1.06359 -0.017715 0.0455382 1 0 1 1 0 0 +EDGE2 6207 6107 -0.063892 -0.0409558 -0.0117914 1 0 1 1 0 0 +EDGE2 6207 6106 -0.976603 0.0636209 -0.0255568 1 0 1 1 0 0 +EDGE2 6208 6109 1.06251 -0.0518057 -0.039045 1 0 1 1 0 0 +EDGE2 6208 6108 -0.0153589 0.0949047 0.0230987 1 0 1 1 0 0 +EDGE2 6208 6107 -0.997989 -0.0513212 -0.0617254 1 0 1 1 0 0 +EDGE2 6208 6207 -1.02419 -0.0092146 -0.00799243 1 0 1 1 0 0 +EDGE2 6209 6110 0.980836 0.0806217 0.0044673 1 0 1 1 0 0 +EDGE2 6209 6170 0.983903 -0.0211396 -3.17651 1 0 1 1 0 0 +EDGE2 6209 6190 1.03319 0.0291203 -3.12385 1 0 1 1 0 0 +EDGE2 6209 6208 -0.96258 -0.0633907 -0.0121265 1 0 1 1 0 0 +EDGE2 6209 6109 0.0251187 0.0911347 0.0430249 1 0 1 1 0 0 +EDGE2 6209 6108 -1.00875 0.0498987 -0.0317428 1 0 1 1 0 0 +EDGE2 6210 6171 -0.00784066 -1.05781 -1.57861 1 0 1 1 0 0 +EDGE2 6210 6111 0.0526306 -1.10686 -1.59468 1 0 1 1 0 0 +EDGE2 6210 6189 0.979812 -0.0815198 -3.16207 1 0 1 1 0 0 +EDGE2 6210 6169 0.939657 0.0215649 -3.13192 1 0 1 1 0 0 +EDGE2 6210 6191 0.0696736 1.02407 1.6252 1 0 1 1 0 0 +EDGE2 6210 6110 0.0386162 0.0103303 -0.0294633 1 0 1 1 0 0 +EDGE2 6210 6170 0.21126 0.0140955 -3.15094 1 0 1 1 0 0 +EDGE2 6210 6190 -0.0728349 -0.0175499 -3.16868 1 0 1 1 0 0 +EDGE2 6210 6109 -1.07962 0.0561627 -0.0107038 1 0 1 1 0 0 +EDGE2 6210 6209 -1.06128 -0.026513 0.0260526 1 0 1 1 0 0 +EDGE2 6211 6210 -1.04237 0.0170623 -1.57916 1 0 1 1 0 0 +EDGE2 6211 6191 0.0549138 0.00335126 0.0181144 1 0 1 1 0 0 +EDGE2 6211 6110 -1.0203 -0.024057 -1.54855 1 0 1 1 0 0 +EDGE2 6211 6170 -1.01847 -0.00332644 1.56065 1 0 1 1 0 0 +EDGE2 6211 6190 -0.997839 -0.037784 1.52193 1 0 1 1 0 0 +EDGE2 6211 6192 0.996818 -0.00362102 -0.00401554 1 0 1 1 0 0 +EDGE2 6212 6191 -1.01304 -0.0356651 -0.0194962 1 0 1 1 0 0 +EDGE2 6212 6211 -0.943287 -0.0248588 -0.0130873 1 0 1 1 0 0 +EDGE2 6212 6193 1.01898 -0.0346589 -0.0150771 1 0 1 1 0 0 +EDGE2 6212 6192 -0.00726733 -0.0219356 0.01429 1 0 1 1 0 0 +EDGE2 6213 6212 -1.01789 0.0953381 -0.0175412 1 0 1 1 0 0 +EDGE2 6213 6194 1.07132 0.0315214 0.0401494 1 0 1 1 0 0 +EDGE2 6213 6193 -0.0626215 0.0169076 -0.0261985 1 0 1 1 0 0 +EDGE2 6213 6192 -0.938897 -0.0116123 0.0106293 1 0 1 1 0 0 +EDGE2 6214 6194 0.0025095 -0.0400978 0.00609916 1 0 1 1 0 0 +EDGE2 6214 6193 -0.890145 0.0252399 0.000575583 1 0 1 1 0 0 +EDGE2 6214 6213 -0.995425 -0.040121 0.00152447 1 0 1 1 0 0 +EDGE2 6214 6195 0.99882 -0.0258089 -0.0180827 1 0 1 1 0 0 +EDGE2 6215 6194 -0.968556 0.0690645 0.0161865 1 0 1 1 0 0 +EDGE2 6215 6214 -1.01777 0.0485091 0.00160633 1 0 1 1 0 0 +EDGE2 6215 6195 -0.00675926 0.015223 -0.0209067 1 0 1 1 0 0 +EDGE2 6215 6196 -0.0365533 0.924497 1.56591 1 0 1 1 0 0 +EDGE2 6216 6195 -0.986175 0.105508 -1.59923 1 0 1 1 0 0 +EDGE2 6216 6215 -1.00294 0.0678136 -1.57729 1 0 1 1 0 0 +EDGE2 6216 6196 0.0447927 0.0330222 -0.00487303 1 0 1 1 0 0 +EDGE2 6216 6197 0.922805 0.0094203 -0.00436457 1 0 1 1 0 0 +EDGE2 6217 6216 -0.995306 0.0118677 -0.00242594 1 0 1 1 0 0 +EDGE2 6217 6196 -1.04185 -0.0290737 0.014528 1 0 1 1 0 0 +EDGE2 6217 6198 1.08773 0.0218525 -0.00732841 1 0 1 1 0 0 +EDGE2 6217 6197 -0.0250505 0.00682697 0.00655949 1 0 1 1 0 0 +EDGE2 6218 6217 -1.00183 0.0319832 0.0211874 1 0 1 1 0 0 +EDGE2 6218 6199 1.03389 -0.0468678 0.0026732 1 0 1 1 0 0 +EDGE2 6218 6198 0.105082 0.0168096 -0.00559742 1 0 1 1 0 0 +EDGE2 6218 6197 -1.02351 -0.0520769 0.0192332 1 0 1 1 0 0 +EDGE2 6219 6199 -0.0112595 -0.110455 0.00632685 1 0 1 1 0 0 +EDGE2 6219 6198 -1.06434 -0.0795377 -0.0034506 1 0 1 1 0 0 +EDGE2 6219 6218 -1.02829 -0.0106666 -0.0305359 1 0 1 1 0 0 +EDGE2 6219 6100 1.03491 0.0523744 -3.13919 1 0 1 1 0 0 +EDGE2 6219 6200 0.95295 -0.110512 0.000240663 1 0 1 1 0 0 +EDGE2 6219 6040 0.964688 0.00624154 -3.16757 1 0 1 1 0 0 +EDGE2 6219 6060 1.04686 0.0617379 -3.15059 1 0 1 1 0 0 +EDGE2 6219 6080 1.06072 -0.0843008 -3.14731 1 0 1 1 0 0 +EDGE2 6220 6101 -0.0566141 0.994518 1.56558 1 0 1 1 0 0 +EDGE2 6220 6199 -1.00904 -0.0274706 -0.0147681 1 0 1 1 0 0 +EDGE2 6220 6219 -0.865207 -0.046897 0.00158454 1 0 1 1 0 0 +EDGE2 6220 6201 -0.0208405 0.939219 1.58585 1 0 1 1 0 0 +EDGE2 6220 6100 -0.0579951 -0.0563445 -3.11983 1 0 1 1 0 0 +EDGE2 6220 6200 -0.0338181 0.0168928 -0.0283523 1 0 1 1 0 0 +EDGE2 6220 6040 0.024028 0.0863803 -3.11739 1 0 1 1 0 0 +EDGE2 6220 6060 -0.02685 -0.0215939 -3.10709 1 0 1 1 0 0 +EDGE2 6220 6080 -0.0770883 0.0258872 -3.12397 1 0 1 1 0 0 +EDGE2 6220 6061 -0.0383476 -0.972828 -1.56841 1 0 1 1 0 0 +EDGE2 6220 6081 -0.0218816 -1.00197 -1.58774 1 0 1 1 0 0 +EDGE2 6220 6041 -0.0462061 -0.979752 -1.55015 1 0 1 1 0 0 +EDGE2 6220 6059 1.01956 0.0108953 -3.11474 1 0 1 1 0 0 +EDGE2 6220 6099 1.0465 0.0455675 -3.13216 1 0 1 1 0 0 +EDGE2 6220 6079 1.05776 -0.00319503 -3.16023 1 0 1 1 0 0 +EDGE2 6220 6039 0.945544 -0.0560004 -3.13738 1 0 1 1 0 0 +EDGE2 6221 6042 1.08057 -0.0391484 0.0204339 1 0 1 1 0 0 +EDGE2 6221 6100 -1.07002 -0.0175468 -1.61319 1 0 1 1 0 0 +EDGE2 6221 6220 -0.965819 -0.067993 1.5711 1 0 1 1 0 0 +EDGE2 6221 6200 -1.02957 0.0477071 1.57723 1 0 1 1 0 0 +EDGE2 6221 6040 -1.05116 -0.00948686 -1.58688 1 0 1 1 0 0 +EDGE2 6221 6060 -0.921798 -0.0049103 -1.59718 1 0 1 1 0 0 +EDGE2 6221 6080 -1.0667 -0.022388 -1.57702 1 0 1 1 0 0 +EDGE2 6221 6061 0.000346459 0.0411503 -0.0275183 1 0 1 1 0 0 +EDGE2 6221 6081 -0.0393105 -0.0384981 -0.0217857 1 0 1 1 0 0 +EDGE2 6221 6041 0.00144723 0.113413 -0.018101 1 0 1 1 0 0 +EDGE2 6221 6082 0.974991 0.0605798 0.0126967 1 0 1 1 0 0 +EDGE2 6221 6062 1.0519 -0.0179476 0.0302048 1 0 1 1 0 0 +EDGE2 6222 6042 0.0956844 -0.0154263 -0.00783909 1 0 1 1 0 0 +EDGE2 6222 6061 -0.971589 -0.00302629 -0.0301331 1 0 1 1 0 0 +EDGE2 6222 6081 -1.02342 -0.0766583 -0.00785621 1 0 1 1 0 0 +EDGE2 6222 6221 -0.99773 0.0269869 0.014715 1 0 1 1 0 0 +EDGE2 6222 6041 -1.01438 -0.000141616 0.00840146 1 0 1 1 0 0 +EDGE2 6222 6082 0.022275 -0.0151911 0.0246113 1 0 1 1 0 0 +EDGE2 6222 6062 0.0462349 -0.0667328 0.0106281 1 0 1 1 0 0 +EDGE2 6222 6063 0.959883 0.0474348 0.00792127 1 0 1 1 0 0 +EDGE2 6222 6083 1.01113 0.00850908 0.0122022 1 0 1 1 0 0 +EDGE2 6222 6043 1.03115 -0.0251827 0.0269509 1 0 1 1 0 0 +EDGE2 6223 6042 -1.02285 0.000628363 0.0241007 1 0 1 1 0 0 +EDGE2 6223 6082 -0.945484 -0.064469 -0.0567977 1 0 1 1 0 0 +EDGE2 6223 6222 -0.894625 0.00607945 -0.0029133 1 0 1 1 0 0 +EDGE2 6223 6062 -1.04831 0.0489522 0.00275992 1 0 1 1 0 0 +EDGE2 6223 6063 -0.0391868 -0.0827908 0.0216477 1 0 1 1 0 0 +EDGE2 6223 6083 -0.117944 0.010834 0.00238227 1 0 1 1 0 0 +EDGE2 6223 6043 0.0178115 -0.0616608 -0.0144903 1 0 1 1 0 0 +EDGE2 6223 6044 0.991222 0.0850658 -0.0160164 1 0 1 1 0 0 +EDGE2 6223 6084 1.04005 -0.00130232 -0.0235719 1 0 1 1 0 0 +EDGE2 6223 6064 0.953288 -0.0458351 0.0185018 1 0 1 1 0 0 +EDGE2 6224 6063 -0.995316 -0.0149178 -0.00974126 1 0 1 1 0 0 +EDGE2 6224 6223 -0.962469 0.0742843 0.0173695 1 0 1 1 0 0 +EDGE2 6224 6083 -0.98349 0.0515163 0.00909838 1 0 1 1 0 0 +EDGE2 6224 6043 -0.967715 0.0186814 0.00928663 1 0 1 1 0 0 +EDGE2 6224 6044 0.0688102 0.0254051 0.0208242 1 0 1 1 0 0 +EDGE2 6224 6084 -0.120617 0.0424107 0.019043 1 0 1 1 0 0 +EDGE2 6224 6064 0.047991 0.0568883 0.0067696 1 0 1 1 0 0 +EDGE2 6224 6045 0.932666 0.0581883 -0.0107597 1 0 1 1 0 0 +EDGE2 6224 6065 0.886421 -0.0436244 0.0134942 1 0 1 1 0 0 +EDGE2 6224 6085 1.00057 0.0216818 0.0214421 1 0 1 1 0 0 +EDGE2 6224 605 0.983593 -0.0404858 -3.08524 1 0 1 1 0 0 +EDGE2 6225 6044 -1.0494 0.00728612 0.00788883 1 0 1 1 0 0 +EDGE2 6225 6084 -1.03068 0.0194942 0.00963648 1 0 1 1 0 0 +EDGE2 6225 6224 -0.999209 -0.0221621 -0.0110171 1 0 1 1 0 0 +EDGE2 6225 6064 -0.985447 -0.0153921 -0.00442938 1 0 1 1 0 0 +EDGE2 6225 6045 -0.0797693 0.041111 0.00841737 1 0 1 1 0 0 +EDGE2 6225 6065 -0.00972784 -0.0525969 -0.00387183 1 0 1 1 0 0 +EDGE2 6225 6085 -0.0484169 0.0240169 0.0191462 1 0 1 1 0 0 +EDGE2 6225 605 0.0656334 0.00351231 -3.13499 1 0 1 1 0 0 +EDGE2 6225 604 0.922909 0.01326 -3.15821 1 0 1 1 0 0 +EDGE2 6225 6046 -0.0489669 0.935638 1.58266 1 0 1 1 0 0 +EDGE2 6225 6086 0.0694971 1.05475 1.59627 1 0 1 1 0 0 +EDGE2 6225 6066 -0.0403748 0.952013 1.56592 1 0 1 1 0 0 +EDGE2 6225 606 0.089272 0.947151 1.56921 1 0 1 1 0 0 +EDGE2 6226 6225 -1.08139 0.0187736 1.55941 1 0 1 1 0 0 +EDGE2 6226 6045 -0.955669 -0.0125807 1.53815 1 0 1 1 0 0 +EDGE2 6226 6065 -0.947317 -0.0171626 1.57724 1 0 1 1 0 0 +EDGE2 6226 6085 -0.987377 0.0835871 1.57826 1 0 1 1 0 0 +EDGE2 6226 605 -1.05639 0.00513714 -1.56695 1 0 1 1 0 0 +EDGE2 6227 6226 -1.0469 0.109377 0.0043111 1 0 1 1 0 0 +EDGE2 6228 6227 -0.993942 -0.0611426 0.00358397 1 0 1 1 0 0 +EDGE2 6229 590 1.00636 0.0241651 -3.13333 1 0 1 1 0 0 +EDGE2 6229 6228 -1.03694 0.0287679 -0.0153228 1 0 1 1 0 0 +EDGE2 6230 591 0.0555754 1.11797 1.58689 1 0 1 1 0 0 +EDGE2 6230 589 1.05081 0.0253556 -3.15608 1 0 1 1 0 0 +EDGE2 6230 590 0.0134008 -0.00804338 -3.16402 1 0 1 1 0 0 +EDGE2 6230 6229 -1.04922 -0.0450497 -0.0452297 1 0 1 1 0 0 +EDGE2 6231 592 1.03719 -0.0244763 -0.0308976 1 0 1 1 0 0 +EDGE2 6231 591 0.0511238 0.048886 -0.0105647 1 0 1 1 0 0 +EDGE2 6231 6230 -1.00313 -0.00347454 -1.55503 1 0 1 1 0 0 +EDGE2 6231 590 -1.00663 0.0935535 1.54637 1 0 1 1 0 0 +EDGE2 6232 592 0.0283317 0.0929326 -0.0202556 1 0 1 1 0 0 +EDGE2 6232 591 -1.02866 -0.0467519 -0.0171792 1 0 1 1 0 0 +EDGE2 6232 6231 -0.921382 0.0293341 -0.00319812 1 0 1 1 0 0 +EDGE2 6232 593 0.998007 0.082976 -0.0254211 1 0 1 1 0 0 +EDGE2 6233 592 -1.03581 -0.0197379 -0.0111766 1 0 1 1 0 0 +EDGE2 6233 6232 -0.99172 0.0110569 -0.0512668 1 0 1 1 0 0 +EDGE2 6233 594 1.03922 -0.071482 -0.0173025 1 0 1 1 0 0 +EDGE2 6233 593 0.0558602 -0.115097 0.0148655 1 0 1 1 0 0 +EDGE2 6234 6233 -1.007 -0.0539349 -0.00542879 1 0 1 1 0 0 +EDGE2 6234 594 0.00249005 0.0610418 -0.0137046 1 0 1 1 0 0 +EDGE2 6234 593 -0.959203 -0.0440049 0.000968433 1 0 1 1 0 0 +EDGE2 6234 595 0.986432 -0.0134915 -0.0105058 1 0 1 1 0 0 +EDGE2 6235 6234 -1.01502 -0.0101789 0.0292689 1 0 1 1 0 0 +EDGE2 6235 594 -1.06642 -0.0943392 -0.0299719 1 0 1 1 0 0 +EDGE2 6235 596 -0.0345781 1.06491 1.57103 1 0 1 1 0 0 +EDGE2 6235 595 0.0632805 0.0026977 -0.00495763 1 0 1 1 0 0 +EDGE2 6236 596 0.00978972 0.00806133 0.00999008 1 0 1 1 0 0 +EDGE2 6236 6235 -1.04627 0.0515057 -1.56904 1 0 1 1 0 0 +EDGE2 6236 595 -0.983513 -0.0827586 -1.58687 1 0 1 1 0 0 +EDGE2 6236 597 0.941506 -0.00720226 -0.00914487 1 0 1 1 0 0 +EDGE2 6237 596 -1.07669 -0.0389218 0.0321975 1 0 1 1 0 0 +EDGE2 6237 6236 -0.959771 -0.0270806 -0.00956929 1 0 1 1 0 0 +EDGE2 6237 597 -0.0251403 -0.112852 0.00653611 1 0 1 1 0 0 +EDGE2 6237 598 1.00086 -0.0941613 0.0103658 1 0 1 1 0 0 +EDGE2 6238 597 -0.963574 -0.0227788 -0.00686549 1 0 1 1 0 0 +EDGE2 6238 6237 -1.0568 0.0231651 0.0262274 1 0 1 1 0 0 +EDGE2 6238 598 0.0201669 -0.0114183 -0.0305886 1 0 1 1 0 0 +EDGE2 6238 599 1.09583 0.0324888 -0.0142916 1 0 1 1 0 0 +EDGE2 6239 598 -0.981718 0.0295659 0.0129181 1 0 1 1 0 0 +EDGE2 6239 6238 -1.00393 -0.019572 0.00304074 1 0 1 1 0 0 +EDGE2 6239 599 -0.0010418 0.00940618 -0.00730192 1 0 1 1 0 0 +EDGE2 6239 600 1.00716 0.0513031 0.00490922 1 0 1 1 0 0 +EDGE2 6240 6239 -1.02701 -0.0524586 -0.00544816 1 0 1 1 0 0 +EDGE2 6240 599 -0.984287 -0.0236354 -0.0187628 1 0 1 1 0 0 +EDGE2 6240 601 0.0664238 1.01677 1.55754 1 0 1 1 0 0 +EDGE2 6240 600 0.0498242 0.127715 0.0249832 1 0 1 1 0 0 +EDGE2 6241 602 0.965272 0.0381796 0.00847282 1 0 1 1 0 0 +EDGE2 6241 6240 -0.923261 0.0569678 -1.60322 1 0 1 1 0 0 +EDGE2 6241 601 -0.0565576 0.056236 0.0158298 1 0 1 1 0 0 +EDGE2 6241 600 -1.06705 -0.0857578 -1.58733 1 0 1 1 0 0 +EDGE2 6242 603 1.01308 -0.0522187 -0.04847 1 0 1 1 0 0 +EDGE2 6242 602 -0.031208 -0.0554959 -0.00460335 1 0 1 1 0 0 +EDGE2 6242 601 -0.992787 -0.0231537 -0.000818596 1 0 1 1 0 0 +EDGE2 6242 6241 -1.13564 -0.0384694 -0.00632898 1 0 1 1 0 0 +EDGE2 6243 603 0.0103267 -0.0529923 -0.0410864 1 0 1 1 0 0 +EDGE2 6243 604 1.04224 -0.0886016 -0.0150446 1 0 1 1 0 0 +EDGE2 6243 6242 -1.01058 0.00822911 -0.00208968 1 0 1 1 0 0 +EDGE2 6243 602 -0.907415 0.077232 -0.00108472 1 0 1 1 0 0 +EDGE2 6244 6225 1.04771 0.0412686 -3.11217 1 0 1 1 0 0 +EDGE2 6244 6045 0.997077 -0.0298787 -3.13087 1 0 1 1 0 0 +EDGE2 6244 6065 0.950167 -0.0603348 -3.18048 1 0 1 1 0 0 +EDGE2 6244 6085 1.04742 0.0458454 -3.17516 1 0 1 1 0 0 +EDGE2 6244 605 1.05094 0.0773669 -0.0246909 1 0 1 1 0 0 +EDGE2 6244 603 -0.910987 -0.0504683 0.0384856 1 0 1 1 0 0 +EDGE2 6244 604 -0.0148298 -0.026165 0.0284767 1 0 1 1 0 0 +EDGE2 6244 6243 -0.907825 -0.0333182 0.00837803 1 0 1 1 0 0 +EDGE2 6245 6044 1.01012 -0.0453667 -3.12418 1 0 1 1 0 0 +EDGE2 6245 6084 1.0489 0.00910942 -3.13362 1 0 1 1 0 0 +EDGE2 6245 6224 0.975559 -0.023888 -3.153 1 0 1 1 0 0 +EDGE2 6245 6064 1.12943 0.00842328 -3.1399 1 0 1 1 0 0 +EDGE2 6245 6226 -0.00342572 0.909396 1.60415 1 0 1 1 0 0 +EDGE2 6245 6225 -0.00482368 -0.0314227 -3.13197 1 0 1 1 0 0 +EDGE2 6245 6045 -0.026558 0.0361719 -3.11789 1 0 1 1 0 0 +EDGE2 6245 6065 -0.0326399 0.0570883 -3.14327 1 0 1 1 0 0 +EDGE2 6245 6085 0.0483579 -0.0235107 -3.16128 1 0 1 1 0 0 +EDGE2 6245 605 0.0132591 -0.01851 -0.00816476 1 0 1 1 0 0 +EDGE2 6245 604 -0.969878 0.0998294 0.0404261 1 0 1 1 0 0 +EDGE2 6245 6244 -1.02637 0.0182972 -0.0217629 1 0 1 1 0 0 +EDGE2 6245 6046 -0.00789238 -1.02819 -1.56449 1 0 1 1 0 0 +EDGE2 6245 6086 0.00143633 -1.01251 -1.57465 1 0 1 1 0 0 +EDGE2 6245 6066 -0.0185829 -1.05016 -1.57328 1 0 1 1 0 0 +EDGE2 6245 606 0.00195325 -1.03022 -1.57163 1 0 1 1 0 0 +EDGE2 6246 6225 -0.972753 -0.00722641 -1.54723 1 0 1 1 0 0 +EDGE2 6246 6245 -1.00893 -0.0728945 1.57905 1 0 1 1 0 0 +EDGE2 6246 6045 -1.0104 0.066103 -1.59301 1 0 1 1 0 0 +EDGE2 6246 6065 -0.970999 0.072061 -1.59078 1 0 1 1 0 0 +EDGE2 6246 6085 -0.978589 -0.0253497 -1.58378 1 0 1 1 0 0 +EDGE2 6246 605 -0.897362 -0.0293782 1.53677 1 0 1 1 0 0 +EDGE2 6246 607 1.00236 -0.133845 0.00372815 1 0 1 1 0 0 +EDGE2 6246 6067 0.921481 -0.0630922 0.00858028 1 0 1 1 0 0 +EDGE2 6246 6046 0.0307212 0.0251448 0.0105278 1 0 1 1 0 0 +EDGE2 6246 6086 0.014915 0.00805064 0.00951904 1 0 1 1 0 0 +EDGE2 6246 6066 -0.000661023 -0.0353162 -0.026101 1 0 1 1 0 0 +EDGE2 6246 606 -0.0453881 0.0108552 -0.034295 1 0 1 1 0 0 +EDGE2 6246 6087 1.02658 -0.15181 0.0265606 1 0 1 1 0 0 +EDGE2 6246 6047 1.00747 0.0442874 -0.0217869 1 0 1 1 0 0 +EDGE2 6247 607 0.0434579 0.0132598 -0.0108708 1 0 1 1 0 0 +EDGE2 6247 6067 0.0216859 -0.116382 0.0051061 1 0 1 1 0 0 +EDGE2 6247 6046 -1.09342 -0.0722452 0.00235038 1 0 1 1 0 0 +EDGE2 6247 6086 -1.02666 0.0432638 -8.41273e-05 1 0 1 1 0 0 +EDGE2 6247 6246 -0.995602 0.0686913 0.0157043 1 0 1 1 0 0 +EDGE2 6247 6066 -0.928555 0.0107809 -0.0560748 1 0 1 1 0 0 +EDGE2 6247 606 -0.982105 0.0140374 -0.0202586 1 0 1 1 0 0 +EDGE2 6247 6087 -0.0161407 0.00530687 0.0247949 1 0 1 1 0 0 +EDGE2 6247 6047 -0.0261449 0.0206312 0.00978606 1 0 1 1 0 0 +EDGE2 6247 6068 0.939231 -0.0538687 -0.00726838 1 0 1 1 0 0 +EDGE2 6247 6088 1.01127 0.0440064 -0.000265453 1 0 1 1 0 0 +EDGE2 6247 608 0.952118 0.0139652 -0.016495 1 0 1 1 0 0 +EDGE2 6247 6048 0.998613 -0.0719872 -0.00622948 1 0 1 1 0 0 +EDGE2 6248 607 -1.04122 0.0419026 -0.0115517 1 0 1 1 0 0 +EDGE2 6248 6067 -0.990295 0.0817238 -0.00749642 1 0 1 1 0 0 +EDGE2 6248 6247 -1.02055 0.0600378 0.0505705 1 0 1 1 0 0 +EDGE2 6248 6087 -1.06293 -0.0202098 -0.0268368 1 0 1 1 0 0 +EDGE2 6248 6047 -1.01968 -0.0348184 -0.00741286 1 0 1 1 0 0 +EDGE2 6248 6068 -0.0116132 -0.0344407 0.0370165 1 0 1 1 0 0 +EDGE2 6248 6088 -0.0471163 -0.00306532 -0.00320642 1 0 1 1 0 0 +EDGE2 6248 6089 1.06596 -0.0241902 0.0397194 1 0 1 1 0 0 +EDGE2 6248 608 -0.0205709 0.0558187 0.0320803 1 0 1 1 0 0 +EDGE2 6248 6048 -0.062554 -0.00333912 -0.00273477 1 0 1 1 0 0 +EDGE2 6248 6049 1.0193 0.0994073 0.017888 1 0 1 1 0 0 +EDGE2 6248 6069 0.999954 0.017458 0.0020524 1 0 1 1 0 0 +EDGE2 6248 609 0.992101 -0.0486751 -0.0233645 1 0 1 1 0 0 +EDGE2 6249 6068 -1.02282 -0.0377455 0.0282906 1 0 1 1 0 0 +EDGE2 6249 6088 -0.918987 0.000225518 0.00250411 1 0 1 1 0 0 +EDGE2 6249 6248 -0.969139 0.0687997 0.00543561 1 0 1 1 0 0 +EDGE2 6249 6089 -0.0503228 0.0533957 0.00379532 1 0 1 1 0 0 +EDGE2 6249 608 -1.03936 0.0406295 -0.00255512 1 0 1 1 0 0 +EDGE2 6249 6048 -0.994624 -0.046152 0.0266338 1 0 1 1 0 0 +EDGE2 6249 6049 -0.0641997 0.0219476 -0.0683629 1 0 1 1 0 0 +EDGE2 6249 6069 -0.0643704 0.0541384 -0.0298837 1 0 1 1 0 0 +EDGE2 6249 609 0.0859526 -0.0767743 0.0270469 1 0 1 1 0 0 +EDGE2 6249 6050 0.990133 0.0685463 -0.0171076 1 0 1 1 0 0 +EDGE2 6249 6090 0.992144 0.0389136 0.00242822 1 0 1 1 0 0 +EDGE2 6249 6070 0.965504 -0.0473655 -0.0586479 1 0 1 1 0 0 +EDGE2 6249 610 1.09663 -0.0689701 0.0149907 1 0 1 1 0 0 +EDGE2 6249 6030 0.98989 0.00544804 -3.11825 1 0 1 1 0 0 +EDGE2 6250 6051 -0.0436705 1.01688 1.58093 1 0 1 1 0 0 +EDGE2 6250 6071 -0.0742848 0.984057 1.56627 1 0 1 1 0 0 +EDGE2 6250 6091 0.0291348 0.959444 1.56896 1 0 1 1 0 0 +EDGE2 6250 6031 -0.0650965 0.938919 1.55238 1 0 1 1 0 0 +EDGE2 6250 6089 -1.02593 -0.00926699 0.00363573 1 0 1 1 0 0 +EDGE2 6250 6249 -0.955095 -0.0475018 -0.0142899 1 0 1 1 0 0 +EDGE2 6250 6049 -1.02622 -0.056355 0.0100886 1 0 1 1 0 0 +EDGE2 6250 6069 -0.988341 0.0301299 -0.00590292 1 0 1 1 0 0 +EDGE2 6250 609 -0.960745 0.0101075 -0.00321803 1 0 1 1 0 0 +EDGE2 6250 6050 0.00498554 0.0532269 -0.00705723 1 0 1 1 0 0 +EDGE2 6250 6090 -0.109013 0.0762918 0.0187772 1 0 1 1 0 0 +EDGE2 6250 6070 0.0414294 0.0237126 -0.00395431 1 0 1 1 0 0 +EDGE2 6250 610 -0.0268306 -0.0198132 -0.0105509 1 0 1 1 0 0 +EDGE2 6250 6030 -0.0694573 -0.0368711 -3.14994 1 0 1 1 0 0 +EDGE2 6250 6029 1.04613 -0.0243596 -3.15148 1 0 1 1 0 0 +EDGE2 6250 611 -0.0834962 -1.12246 -1.54379 1 0 1 1 0 0 +EDGE2 6251 6032 1.03955 0.039853 -0.0516672 1 0 1 1 0 0 +EDGE2 6251 6072 0.983728 -0.0499638 0.0161308 1 0 1 1 0 0 +EDGE2 6251 6092 1.04743 -0.00138091 -0.0490167 1 0 1 1 0 0 +EDGE2 6251 6052 1.04904 -0.019303 -0.0154973 1 0 1 1 0 0 +EDGE2 6251 6051 -0.0057998 0.0307517 0.0202229 1 0 1 1 0 0 +EDGE2 6251 6071 0.0730884 0.0874675 -0.00559189 1 0 1 1 0 0 +EDGE2 6251 6091 0.0394376 -0.0327509 0.00262722 1 0 1 1 0 0 +EDGE2 6251 6031 -0.0270545 0.0396791 -0.00744132 1 0 1 1 0 0 +EDGE2 6251 6050 -0.985323 -0.0322478 -1.59811 1 0 1 1 0 0 +EDGE2 6251 6090 -1.01321 -0.0234751 -1.57845 1 0 1 1 0 0 +EDGE2 6251 6250 -1.03804 0.0364186 -1.57597 1 0 1 1 0 0 +EDGE2 6251 6070 -0.96578 -0.0392543 -1.54923 1 0 1 1 0 0 +EDGE2 6251 610 -1.05473 0.0136887 -1.53609 1 0 1 1 0 0 +EDGE2 6251 6030 -0.928956 0.0991333 1.55626 1 0 1 1 0 0 +EDGE2 6252 6032 0.00342281 0.00816323 0.016424 1 0 1 1 0 0 +EDGE2 6252 6093 0.911522 -0.0260811 -0.0185266 1 0 1 1 0 0 +EDGE2 6252 6033 1.00285 -0.0162161 -0.0328193 1 0 1 1 0 0 +EDGE2 6252 6053 0.967524 0.0560489 0.00194191 1 0 1 1 0 0 +EDGE2 6252 6073 1.05631 0.036926 0.012668 1 0 1 1 0 0 +EDGE2 6252 6072 -0.0617508 0.0241982 0.0262605 1 0 1 1 0 0 +EDGE2 6252 6092 -0.0170738 0.0243364 -0.0153504 1 0 1 1 0 0 +EDGE2 6252 6052 -0.144613 -0.0238439 0.0153439 1 0 1 1 0 0 +EDGE2 6252 6251 -0.985219 -0.0357205 -0.00781525 1 0 1 1 0 0 +EDGE2 6252 6051 -0.962814 -0.0375178 0.00198672 1 0 1 1 0 0 +EDGE2 6252 6071 -0.971468 -0.0326465 0.0159701 1 0 1 1 0 0 +EDGE2 6252 6091 -1.00487 0.0442355 0.0241485 1 0 1 1 0 0 +EDGE2 6252 6031 -1.03146 -0.0316284 -0.0220728 1 0 1 1 0 0 +EDGE2 6253 6032 -1.00529 -0.0223152 -0.00982191 1 0 1 1 0 0 +EDGE2 6253 6094 0.98868 -0.0622737 -0.000857914 1 0 1 1 0 0 +EDGE2 6253 6093 0.118958 0.0330892 0.00304014 1 0 1 1 0 0 +EDGE2 6253 6034 0.99548 -0.0276639 -0.00564833 1 0 1 1 0 0 +EDGE2 6253 6054 1.05087 -0.0574114 -0.0105387 1 0 1 1 0 0 +EDGE2 6253 6074 0.997145 -0.0464834 0.0162166 1 0 1 1 0 0 +EDGE2 6253 6252 -0.968049 0.00201864 -0.00862206 1 0 1 1 0 0 +EDGE2 6253 6033 0.0431596 -0.11553 -0.0107029 1 0 1 1 0 0 +EDGE2 6253 6053 -0.113293 -0.0846499 -0.0292821 1 0 1 1 0 0 +EDGE2 6253 6073 0.00217098 -0.0219259 0.0288191 1 0 1 1 0 0 +EDGE2 6253 6072 -1.01595 -0.042485 -0.0284898 1 0 1 1 0 0 +EDGE2 6253 6092 -0.979064 0.0268853 -0.0103234 1 0 1 1 0 0 +EDGE2 6253 6052 -0.998762 0.00074109 -0.000744304 1 0 1 1 0 0 +EDGE2 6254 6094 0.110096 -0.0410723 -0.0460156 1 0 1 1 0 0 +EDGE2 6254 6075 1.07722 0.0574459 -0.0270913 1 0 1 1 0 0 +EDGE2 6254 6095 0.963614 -0.0615536 -0.0146986 1 0 1 1 0 0 +EDGE2 6254 6035 1.08393 -0.0334668 0.00226328 1 0 1 1 0 0 +EDGE2 6254 6055 1.08483 -0.149322 -0.0213031 1 0 1 1 0 0 +EDGE2 6254 6093 -1.0397 0.0384312 0.000345321 1 0 1 1 0 0 +EDGE2 6254 6253 -0.925072 -0.0506138 -0.00742753 1 0 1 1 0 0 +EDGE2 6254 6034 -0.0414833 0.0315324 0.0192454 1 0 1 1 0 0 +EDGE2 6254 6054 -0.00506232 0.119007 0.00767514 1 0 1 1 0 0 +EDGE2 6254 6074 -0.0988784 -0.019059 3.99657e-05 1 0 1 1 0 0 +EDGE2 6254 6033 -1.07658 -0.0722046 0.0251079 1 0 1 1 0 0 +EDGE2 6254 6053 -1.10061 0.000621614 0.0186296 1 0 1 1 0 0 +EDGE2 6254 6073 -0.979798 -0.0222115 0.0122165 1 0 1 1 0 0 +EDGE2 6255 6094 -0.988972 0.0545016 -0.0164472 1 0 1 1 0 0 +EDGE2 6255 6056 -0.017846 0.955396 1.59231 1 0 1 1 0 0 +EDGE2 6255 6096 0.0579914 0.946836 1.55683 1 0 1 1 0 0 +EDGE2 6255 6076 -0.0974706 1.03275 1.56248 1 0 1 1 0 0 +EDGE2 6255 6075 -0.052643 0.0538223 -0.0272271 1 0 1 1 0 0 +EDGE2 6255 6036 0.0653142 0.980323 1.55392 1 0 1 1 0 0 +EDGE2 6255 6095 -0.0148848 -0.0514566 -0.0315482 1 0 1 1 0 0 +EDGE2 6255 6035 -0.000724228 0.087116 0.00914471 1 0 1 1 0 0 +EDGE2 6255 6055 0.067365 0.00734781 -0.0147551 1 0 1 1 0 0 +EDGE2 6255 6254 -1.01932 0.0966537 -0.0110795 1 0 1 1 0 0 +EDGE2 6255 6034 -0.960841 0.00997917 0.00244943 1 0 1 1 0 0 +EDGE2 6255 6054 -1.06331 -0.0634903 0.0115513 1 0 1 1 0 0 +EDGE2 6255 6074 -1.00991 -0.032275 0.0100117 1 0 1 1 0 0 +EDGE2 6256 6056 -0.0596316 0.0137706 0.0129512 1 0 1 1 0 0 +EDGE2 6256 6037 0.976075 0.00574792 0.0163623 1 0 1 1 0 0 +EDGE2 6256 6077 0.969437 0.00115132 0.0275231 1 0 1 1 0 0 +EDGE2 6256 6097 0.918441 -0.0049582 -0.0556154 1 0 1 1 0 0 +EDGE2 6256 6057 1.01182 -0.034437 0.012544 1 0 1 1 0 0 +EDGE2 6256 6096 -0.0178318 -0.0123371 -0.00090678 1 0 1 1 0 0 +EDGE2 6256 6076 0.0314499 -0.00380904 0.00105947 1 0 1 1 0 0 +EDGE2 6256 6075 -0.95583 0.0824017 -1.57115 1 0 1 1 0 0 +EDGE2 6256 6255 -1.05722 -0.0176987 -1.56291 1 0 1 1 0 0 +EDGE2 6256 6036 -0.024234 -0.00442869 -0.0132573 1 0 1 1 0 0 +EDGE2 6256 6095 -0.923783 0.00618691 -1.5756 1 0 1 1 0 0 +EDGE2 6256 6035 -1.022 0.0115221 -1.54869 1 0 1 1 0 0 +EDGE2 6256 6055 -1.02501 -0.0316123 -1.56283 1 0 1 1 0 0 +EDGE2 6257 6078 1.00866 -0.0196297 0.0279008 1 0 1 1 0 0 +EDGE2 6257 6098 1.03076 -0.0707869 -0.0293693 1 0 1 1 0 0 +EDGE2 6257 6058 0.948749 0.0106732 0.0116262 1 0 1 1 0 0 +EDGE2 6257 6038 1.0056 0.0867314 0.0244206 1 0 1 1 0 0 +EDGE2 6257 6056 -0.969788 -0.0313979 -0.0313514 1 0 1 1 0 0 +EDGE2 6257 6037 0.0103468 0.0542243 0.0171475 1 0 1 1 0 0 +EDGE2 6257 6077 0.0536456 0.0167784 -0.00660292 1 0 1 1 0 0 +EDGE2 6257 6097 0.0232664 -0.0291299 -0.00683202 1 0 1 1 0 0 +EDGE2 6257 6057 -0.0167935 -0.0223354 -0.043761 1 0 1 1 0 0 +EDGE2 6257 6096 -0.999004 0.0347025 0.0265586 1 0 1 1 0 0 +EDGE2 6257 6256 -0.957946 0.000217279 0.0430583 1 0 1 1 0 0 +EDGE2 6257 6076 -0.974291 -0.0826105 -0.031459 1 0 1 1 0 0 +EDGE2 6257 6036 -0.979083 0.0154515 -0.00464521 1 0 1 1 0 0 +EDGE2 6258 6078 0.0143571 -0.107511 -0.0041719 1 0 1 1 0 0 +EDGE2 6258 6059 1.00665 -0.0669278 0.0135607 1 0 1 1 0 0 +EDGE2 6258 6099 0.965243 0.0706964 -0.0104176 1 0 1 1 0 0 +EDGE2 6258 6079 1.02491 -0.0691412 0.0105193 1 0 1 1 0 0 +EDGE2 6258 6039 1.0069 -0.121925 -0.00847591 1 0 1 1 0 0 +EDGE2 6258 6098 0.0205319 0.0451277 0.0224418 1 0 1 1 0 0 +EDGE2 6258 6058 -0.00136851 -0.0586862 0.0112424 1 0 1 1 0 0 +EDGE2 6258 6038 -0.0125488 -0.0238137 0.023515 1 0 1 1 0 0 +EDGE2 6258 6037 -1.01631 0.0203513 -0.0214411 1 0 1 1 0 0 +EDGE2 6258 6077 -0.919809 -0.104118 -0.00348778 1 0 1 1 0 0 +EDGE2 6258 6097 -0.997956 -0.00458987 0.00795065 1 0 1 1 0 0 +EDGE2 6258 6257 -1.01343 0.047063 -0.0091698 1 0 1 1 0 0 +EDGE2 6258 6057 -0.974132 -0.0851534 -0.0109082 1 0 1 1 0 0 +EDGE2 6259 6100 1.01736 0.0228302 -0.00599129 1 0 1 1 0 0 +EDGE2 6259 6220 0.975885 -0.00846837 -3.13974 1 0 1 1 0 0 +EDGE2 6259 6200 0.921656 0.0461793 -3.14948 1 0 1 1 0 0 +EDGE2 6259 6040 0.939833 -0.107133 -0.0176477 1 0 1 1 0 0 +EDGE2 6259 6060 1.03947 0.00696968 0.0295293 1 0 1 1 0 0 +EDGE2 6259 6080 1.01451 0.0550957 0.0043441 1 0 1 1 0 0 +EDGE2 6259 6078 -1.05817 0.0922491 -0.00572673 1 0 1 1 0 0 +EDGE2 6259 6059 0.0750517 -0.0620276 0.0110856 1 0 1 1 0 0 +EDGE2 6259 6099 -0.00645337 -0.00570162 0.0145456 1 0 1 1 0 0 +EDGE2 6259 6079 -0.100751 0.0456191 -0.0130919 1 0 1 1 0 0 +EDGE2 6259 6258 -1.01416 0.0747243 0.00150624 1 0 1 1 0 0 +EDGE2 6259 6039 -0.00276922 0.0342547 0.0171942 1 0 1 1 0 0 +EDGE2 6259 6098 -1.14261 -0.000102453 -0.00982534 1 0 1 1 0 0 +EDGE2 6259 6058 -0.992209 -0.0396971 -0.04285 1 0 1 1 0 0 +EDGE2 6259 6038 -0.957325 0.0607781 -0.0127837 1 0 1 1 0 0 +EDGE2 6260 6101 0.035579 -0.9709 -1.56159 1 0 1 1 0 0 +EDGE2 6260 6199 0.941025 0.0506865 -3.16379 1 0 1 1 0 0 +EDGE2 6260 6219 0.998387 0.0382229 -3.12359 1 0 1 1 0 0 +EDGE2 6260 6201 -0.00325245 -1.09439 -1.59646 1 0 1 1 0 0 +EDGE2 6260 6100 0.0637004 0.0153441 -0.0076326 1 0 1 1 0 0 +EDGE2 6260 6220 -0.0498165 0.0098357 -3.19301 1 0 1 1 0 0 +EDGE2 6260 6200 0.0570681 -0.00544024 -3.12418 1 0 1 1 0 0 +EDGE2 6260 6040 0.101244 -0.0213107 -0.0196401 1 0 1 1 0 0 +EDGE2 6260 6060 -0.0446767 -0.0750612 0.0144261 1 0 1 1 0 0 +EDGE2 6260 6080 0.0376557 -0.00143208 0.0189609 1 0 1 1 0 0 +EDGE2 6260 6061 0.051291 0.986751 1.56087 1 0 1 1 0 0 +EDGE2 6260 6081 -0.0721946 1.02895 1.54256 1 0 1 1 0 0 +EDGE2 6260 6221 0.0167215 0.926982 1.5775 1 0 1 1 0 0 +EDGE2 6260 6041 -0.0201915 0.971436 1.59895 1 0 1 1 0 0 +EDGE2 6260 6059 -1.029 -0.00249794 -0.000975677 1 0 1 1 0 0 +EDGE2 6260 6099 -1.06503 0.0796847 -0.009715 1 0 1 1 0 0 +EDGE2 6260 6259 -1.03366 -0.00604431 -0.00325624 1 0 1 1 0 0 +EDGE2 6260 6079 -0.964901 0.058376 0.00332608 1 0 1 1 0 0 +EDGE2 6260 6039 -0.979336 -0.0470153 0.0159163 1 0 1 1 0 0 +EDGE2 6261 6042 0.973221 -0.0325628 0.0312208 1 0 1 1 0 0 +EDGE2 6261 6100 -1.02366 -0.053107 -1.53887 1 0 1 1 0 0 +EDGE2 6261 6220 -0.907041 0.0591188 1.55636 1 0 1 1 0 0 +EDGE2 6261 6260 -0.983306 0.129777 -1.6093 1 0 1 1 0 0 +EDGE2 6261 6200 -0.96455 0.0438553 1.57217 1 0 1 1 0 0 +EDGE2 6261 6040 -1.05294 0.0129689 -1.57747 1 0 1 1 0 0 +EDGE2 6261 6060 -1.05441 -0.0446183 -1.56166 1 0 1 1 0 0 +EDGE2 6261 6080 -0.988558 0.0088462 -1.57509 1 0 1 1 0 0 +EDGE2 6261 6061 -0.0728373 -0.126942 -0.0188664 1 0 1 1 0 0 +EDGE2 6261 6081 0.00919225 0.0492089 -0.000518472 1 0 1 1 0 0 +EDGE2 6261 6221 0.00102333 0.0581623 -0.00351506 1 0 1 1 0 0 +EDGE2 6261 6041 -0.0310216 0.0327517 -0.00749357 1 0 1 1 0 0 +EDGE2 6261 6082 0.99768 0.0187394 -0.00741418 1 0 1 1 0 0 +EDGE2 6261 6222 1.04846 -0.00932878 -0.00264191 1 0 1 1 0 0 +EDGE2 6261 6062 0.936448 0.0750918 -0.00881051 1 0 1 1 0 0 +EDGE2 6262 6042 -0.028554 -0.0586496 -0.0078454 1 0 1 1 0 0 +EDGE2 6262 6261 -1.01559 -0.0323743 0.0055111 1 0 1 1 0 0 +EDGE2 6262 6061 -0.929215 -0.000289171 -0.036229 1 0 1 1 0 0 +EDGE2 6262 6081 -1.02317 -0.128609 -0.00320441 1 0 1 1 0 0 +EDGE2 6262 6221 -1.04814 -0.0247196 0.00947471 1 0 1 1 0 0 +EDGE2 6262 6041 -1.02181 -0.0699611 0.0161967 1 0 1 1 0 0 +EDGE2 6262 6082 0.0200563 -0.0318606 0.0134671 1 0 1 1 0 0 +EDGE2 6262 6222 0.0425891 -0.00715645 0.00401597 1 0 1 1 0 0 +EDGE2 6262 6062 -0.0297566 -0.0408548 0.000837993 1 0 1 1 0 0 +EDGE2 6262 6063 0.942248 -0.0255534 -0.0367832 1 0 1 1 0 0 +EDGE2 6262 6223 1.05304 0.0766467 0.0016731 1 0 1 1 0 0 +EDGE2 6262 6083 1.00787 -0.0573129 -0.00377388 1 0 1 1 0 0 +EDGE2 6262 6043 1.00701 -0.0739774 -0.00396257 1 0 1 1 0 0 +EDGE2 6263 6042 -1.0318 -0.0300958 0.0023969 1 0 1 1 0 0 +EDGE2 6263 6082 -1.03115 0.038973 -0.00130443 1 0 1 1 0 0 +EDGE2 6263 6222 -0.961056 -0.0297617 0.028215 1 0 1 1 0 0 +EDGE2 6263 6262 -1.0035 0.0307876 0.0218944 1 0 1 1 0 0 +EDGE2 6263 6062 -1.00952 0.0724655 -0.0324968 1 0 1 1 0 0 +EDGE2 6263 6063 -0.0357015 -0.0317336 0.0115496 1 0 1 1 0 0 +EDGE2 6263 6223 -0.11276 0.054368 -0.0188745 1 0 1 1 0 0 +EDGE2 6263 6083 0.00702346 -0.037646 0.0222389 1 0 1 1 0 0 +EDGE2 6263 6043 -0.047656 -0.0470746 0.00850178 1 0 1 1 0 0 +EDGE2 6263 6044 0.957462 -0.0265303 0.00795949 1 0 1 1 0 0 +EDGE2 6263 6084 0.994192 -0.0370506 -0.0134183 1 0 1 1 0 0 +EDGE2 6263 6224 1.03991 0.0473629 -0.00337553 1 0 1 1 0 0 +EDGE2 6263 6064 1.01242 -0.00981447 -0.00338306 1 0 1 1 0 0 +EDGE2 6264 6063 -0.963989 -0.0237177 -0.00901583 1 0 1 1 0 0 +EDGE2 6264 6223 -1.09602 0.043712 0.0135389 1 0 1 1 0 0 +EDGE2 6264 6263 -0.996168 0.00827714 0.0061729 1 0 1 1 0 0 +EDGE2 6264 6083 -1.02011 0.0021764 0.042723 1 0 1 1 0 0 +EDGE2 6264 6043 -1.0634 0.0661181 0.00312914 1 0 1 1 0 0 +EDGE2 6264 6044 0.00593616 -0.06603 -0.00179365 1 0 1 1 0 0 +EDGE2 6264 6084 0.0101727 -0.0380455 -0.0273757 1 0 1 1 0 0 +EDGE2 6264 6224 0.0298739 0.00323043 0.0131207 1 0 1 1 0 0 +EDGE2 6264 6064 -0.00696203 0.0257637 0.0182991 1 0 1 1 0 0 +EDGE2 6264 6225 1.00518 0.144054 -0.0339783 1 0 1 1 0 0 +EDGE2 6264 6245 0.990349 -0.139061 -3.13684 1 0 1 1 0 0 +EDGE2 6264 6045 0.98201 -0.145885 -0.00506874 1 0 1 1 0 0 +EDGE2 6264 6065 0.951385 0.0753529 0.0174146 1 0 1 1 0 0 +EDGE2 6264 6085 1.01527 -0.0337672 -0.00141858 1 0 1 1 0 0 +EDGE2 6264 605 0.997975 0.0475233 -3.15519 1 0 1 1 0 0 +EDGE2 6265 6044 -1.05027 -0.00621183 0.000529125 1 0 1 1 0 0 +EDGE2 6265 6084 -1.03581 0.0289188 0.0302298 1 0 1 1 0 0 +EDGE2 6265 6224 -0.950011 -0.00523713 -0.000165899 1 0 1 1 0 0 +EDGE2 6265 6264 -1.04503 -0.0206384 0.0194213 1 0 1 1 0 0 +EDGE2 6265 6064 -1.01664 0.0317532 0.0238949 1 0 1 1 0 0 +EDGE2 6265 6226 0.0750552 -0.984465 -1.55511 1 0 1 1 0 0 +EDGE2 6265 6225 -0.0344901 0.00971858 -0.0375259 1 0 1 1 0 0 +EDGE2 6265 6245 -0.04476 0.0289012 -3.14211 1 0 1 1 0 0 +EDGE2 6265 6045 -0.00594449 -0.0394636 0.0179963 1 0 1 1 0 0 +EDGE2 6265 6065 0.0474249 -0.0132865 0.00143718 1 0 1 1 0 0 +EDGE2 6265 6085 -0.0543914 0.0193536 0.0305038 1 0 1 1 0 0 +EDGE2 6265 605 -0.0393535 0.0637043 -3.15215 1 0 1 1 0 0 +EDGE2 6265 604 1.01914 -0.0509663 -3.12755 1 0 1 1 0 0 +EDGE2 6265 6244 0.985262 -0.0461675 -3.14786 1 0 1 1 0 0 +EDGE2 6265 6046 0.0612496 0.994808 1.57808 1 0 1 1 0 0 +EDGE2 6265 6086 0.00286934 0.979323 1.56488 1 0 1 1 0 0 +EDGE2 6265 6246 0.0290372 1.00951 1.54329 1 0 1 1 0 0 +EDGE2 6265 6066 -0.12437 0.991156 1.52895 1 0 1 1 0 0 +EDGE2 6265 606 -0.0802077 0.961049 1.56362 1 0 1 1 0 0 +EDGE2 6266 6227 1.0348 0.062556 0.0242057 1 0 1 1 0 0 +EDGE2 6266 6226 0.0113138 -0.00744566 0.0104183 1 0 1 1 0 0 +EDGE2 6266 6225 -0.883228 0.123033 1.55202 1 0 1 1 0 0 +EDGE2 6266 6265 -1.09743 0.0050392 1.57216 1 0 1 1 0 0 +EDGE2 6266 6245 -1.01026 -0.0653393 -1.55223 1 0 1 1 0 0 +EDGE2 6266 6045 -1.05159 -0.00395631 1.59102 1 0 1 1 0 0 +EDGE2 6266 6065 -0.948634 -0.0079963 1.58967 1 0 1 1 0 0 +EDGE2 6266 6085 -1.11122 -0.029964 1.57658 1 0 1 1 0 0 +EDGE2 6266 605 -0.982631 -0.0586863 -1.6008 1 0 1 1 0 0 +EDGE2 6267 6228 0.922129 -0.0212679 0.0132411 1 0 1 1 0 0 +EDGE2 6267 6266 -1.04152 0.0259346 -0.01314 1 0 1 1 0 0 +EDGE2 6267 6227 0.0154147 0.0548405 -0.0239497 1 0 1 1 0 0 +EDGE2 6267 6226 -1.05086 -0.0195769 0.0166606 1 0 1 1 0 0 +EDGE2 6268 6229 0.995666 0.0069811 -0.0184758 1 0 1 1 0 0 +EDGE2 6268 6267 -1.04768 -0.0498054 0.0265315 1 0 1 1 0 0 +EDGE2 6268 6228 0.0387137 0.0721989 0.0181599 1 0 1 1 0 0 +EDGE2 6268 6227 -1.02021 -0.0474221 0.00421473 1 0 1 1 0 0 +EDGE2 6269 6230 0.995904 0.0647015 -0.00586974 1 0 1 1 0 0 +EDGE2 6269 590 1.02709 0.0615323 -3.1549 1 0 1 1 0 0 +EDGE2 6269 6268 -1.02493 0.0141793 0.0066354 1 0 1 1 0 0 +EDGE2 6269 6229 0.0332579 -0.00571201 -0.0113188 1 0 1 1 0 0 +EDGE2 6269 6228 -0.971731 0.0466411 -0.00986124 1 0 1 1 0 0 +EDGE2 6270 591 0.030028 1.00241 1.55344 1 0 1 1 0 0 +EDGE2 6270 6230 0.0602702 0.0740497 0.0110342 1 0 1 1 0 0 +EDGE2 6270 589 0.936256 -0.00708468 -3.13135 1 0 1 1 0 0 +EDGE2 6270 6231 0.00115426 0.8939 1.5875 1 0 1 1 0 0 +EDGE2 6270 590 -0.0855511 -0.0633214 -3.14532 1 0 1 1 0 0 +EDGE2 6270 6229 -1.02341 0.0188652 -0.0107639 1 0 1 1 0 0 +EDGE2 6270 6269 -0.960136 0.0136522 0.0304575 1 0 1 1 0 0 +EDGE2 6271 592 0.953157 -0.0400259 -0.000401184 1 0 1 1 0 0 +EDGE2 6271 591 -0.0546644 0.0226003 0.0355217 1 0 1 1 0 0 +EDGE2 6271 6230 -0.939326 -0.0177389 -1.56843 1 0 1 1 0 0 +EDGE2 6271 6270 -1.03407 -0.0839841 -1.57018 1 0 1 1 0 0 +EDGE2 6271 6231 -0.115281 0.0508677 0.000683117 1 0 1 1 0 0 +EDGE2 6271 590 -1.01416 -0.00066278 1.54326 1 0 1 1 0 0 +EDGE2 6271 6232 0.984438 -0.0418458 0.00381356 1 0 1 1 0 0 +EDGE2 6272 592 0.0217132 0.0417126 0.014079 1 0 1 1 0 0 +EDGE2 6272 591 -1.11708 0.00897092 -0.0363722 1 0 1 1 0 0 +EDGE2 6272 6231 -1.00033 -0.0116815 -0.0404687 1 0 1 1 0 0 +EDGE2 6272 6271 -1.08393 0.0447594 -0.0180496 1 0 1 1 0 0 +EDGE2 6272 6232 0.0522934 0.0934457 -0.0140986 1 0 1 1 0 0 +EDGE2 6272 6233 1.04562 -0.0991403 0.00076121 1 0 1 1 0 0 +EDGE2 6272 593 1.09724 -0.0126322 0.00087572 1 0 1 1 0 0 +EDGE2 6273 592 -0.967903 -0.0868364 0.0123231 1 0 1 1 0 0 +EDGE2 6273 6232 -0.999489 0.0757395 -0.00841447 1 0 1 1 0 0 +EDGE2 6273 6272 -1.02312 -0.0515285 -0.000789891 1 0 1 1 0 0 +EDGE2 6273 6233 0.0452673 -0.0139048 4.61279e-05 1 0 1 1 0 0 +EDGE2 6273 6234 1.004 0.00613869 0.0308075 1 0 1 1 0 0 +EDGE2 6273 594 0.978753 -0.0421939 0.0430245 1 0 1 1 0 0 +EDGE2 6273 593 0.0186085 -0.0286567 0.0216836 1 0 1 1 0 0 +EDGE2 6274 6273 -1.04281 0.12276 0.00918327 1 0 1 1 0 0 +EDGE2 6274 6233 -1.02987 -0.040832 -0.00418304 1 0 1 1 0 0 +EDGE2 6274 6234 0.0246165 0.00838917 0.0316078 1 0 1 1 0 0 +EDGE2 6274 594 -0.0204845 0.0332539 0.00207484 1 0 1 1 0 0 +EDGE2 6274 593 -1.02737 -0.0661706 0.02985 1 0 1 1 0 0 +EDGE2 6274 6235 1.01443 0.00598134 -0.0139521 1 0 1 1 0 0 +EDGE2 6274 595 0.965712 0.0896427 -0.0131781 1 0 1 1 0 0 +EDGE2 6275 6274 -1.00791 -0.0474171 -0.0218253 1 0 1 1 0 0 +EDGE2 6275 6234 -0.986574 0.00691009 0.0317458 1 0 1 1 0 0 +EDGE2 6275 594 -1.12548 0.0274639 0.0212524 1 0 1 1 0 0 +EDGE2 6275 596 0.0177339 1.12728 1.55143 1 0 1 1 0 0 +EDGE2 6275 6235 0.00646379 0.00108226 0.0142883 1 0 1 1 0 0 +EDGE2 6275 595 0.0691691 0.0722376 0.00100045 1 0 1 1 0 0 +EDGE2 6275 6236 -0.0315189 0.974843 1.55386 1 0 1 1 0 0 +EDGE2 6276 6235 -0.930569 0.00159329 1.59279 1 0 1 1 0 0 +EDGE2 6276 6275 -0.914645 0.0761971 1.54456 1 0 1 1 0 0 +EDGE2 6276 595 -0.978883 0.041646 1.59601 1 0 1 1 0 0 +EDGE2 6277 6276 -1.01894 0.0809032 0.00577106 1 0 1 1 0 0 +EDGE2 6278 6277 -0.965834 -0.0118757 0.020605 1 0 1 1 0 0 +EDGE2 6279 6278 -0.92859 0.0439428 -0.00995145 1 0 1 1 0 0 +EDGE2 6280 6279 -1.00086 0.0576712 0.0106328 1 0 1 1 0 0 +EDGE2 6281 6280 -1.02279 -0.000902463 1.57936 1 0 1 1 0 0 +EDGE2 6282 6281 -0.984162 0.032091 -0.0016596 1 0 1 1 0 0 +EDGE2 6283 6282 -1.00292 -0.0686345 0.0461624 1 0 1 1 0 0 +EDGE2 6284 585 0.937536 -0.0438293 -3.144 1 0 1 1 0 0 +EDGE2 6284 6283 -0.912881 -0.0540886 0.014264 1 0 1 1 0 0 +EDGE2 6285 584 1.0669 0.0328003 -3.13375 1 0 1 1 0 0 +EDGE2 6285 585 0.0524196 0.001908 -3.15221 1 0 1 1 0 0 +EDGE2 6285 6284 -0.940626 0.0228685 -0.00798552 1 0 1 1 0 0 +EDGE2 6285 586 -0.0890398 -0.96594 -1.53343 1 0 1 1 0 0 +EDGE2 6286 6285 -0.881376 -0.00469098 -1.56486 1 0 1 1 0 0 +EDGE2 6286 585 -1.05661 0.0887832 1.56626 1 0 1 1 0 0 +EDGE2 6287 6286 -0.933469 -0.0743466 0.0111117 1 0 1 1 0 0 +EDGE2 6288 6287 -1.03934 0.118107 0.0117607 1 0 1 1 0 0 +EDGE2 6289 6288 -0.939755 0.034122 0.000529492 1 0 1 1 0 0 +EDGE2 6290 6289 -0.979097 0.00956718 -0.0109231 1 0 1 1 0 0 +EDGE2 6291 6290 -0.893808 0.000885768 -1.55728 1 0 1 1 0 0 +EDGE2 6292 6291 -0.978057 -0.0212416 0.0308204 1 0 1 1 0 0 +EDGE2 6293 6292 -0.960665 -0.0338108 -0.0278178 1 0 1 1 0 0 +EDGE2 6294 6293 -1.00923 0.0116356 -0.0160136 1 0 1 1 0 0 +EDGE2 6295 6294 -1.01399 0.0262937 -0.0113151 1 0 1 1 0 0 +EDGE2 6296 6295 -1.05413 -0.0100391 -1.54756 1 0 1 1 0 0 +EDGE2 6297 6296 -1.02195 0.0535976 -0.00399999 1 0 1 1 0 0 +EDGE2 6298 6297 -0.980921 -0.0263429 -0.0321651 1 0 1 1 0 0 +EDGE2 6299 6298 -1.08513 0.0157206 0.0286177 1 0 1 1 0 0 +EDGE2 6299 6280 0.94243 -0.0349953 -3.11344 1 0 1 1 0 0 +EDGE2 6300 6299 -1.03914 -0.077066 -0.000453801 1 0 1 1 0 0 +EDGE2 6300 6281 0.0531959 0.995279 1.54645 1 0 1 1 0 0 +EDGE2 6300 6279 1.12029 0.0255615 -3.12067 1 0 1 1 0 0 +EDGE2 6300 6280 -0.0822281 0.0628449 -3.13021 1 0 1 1 0 0 +EDGE2 6301 6300 -1.01518 -0.00828154 1.59345 1 0 1 1 0 0 +EDGE2 6301 6280 -0.971508 0.00623601 -1.5664 1 0 1 1 0 0 +EDGE2 6302 6301 -0.962517 0.0334232 -0.0271205 1 0 1 1 0 0 +EDGE2 6303 6302 -0.978309 0.055487 0.00579222 1 0 1 1 0 0 +EDGE2 6304 6303 -0.979782 -0.0460684 -0.000524143 1 0 1 1 0 0 +EDGE2 6305 6304 -1.05723 -0.0295265 -0.00864984 1 0 1 1 0 0 +EDGE2 6306 6305 -1.00846 0.0206872 -1.58178 1 0 1 1 0 0 +EDGE2 6307 6306 -0.979204 -0.0128417 0.0135042 1 0 1 1 0 0 +EDGE2 6308 6307 -0.949428 0.0310708 -0.0107005 1 0 1 1 0 0 +EDGE2 6309 6308 -0.889439 -0.0451413 0.00600008 1 0 1 1 0 0 +EDGE2 6310 6309 -1.03497 -0.01188 0.00242602 1 0 1 1 0 0 +EDGE2 6311 6310 -1.09797 -0.0331201 -1.56975 1 0 1 1 0 0 +EDGE2 6312 6311 -1.02365 -0.0766337 0.0260305 1 0 1 1 0 0 +EDGE2 6313 6312 -1.0033 0.0555635 0.0142763 1 0 1 1 0 0 +EDGE2 6314 6235 1.00253 0.0091537 -3.13395 1 0 1 1 0 0 +EDGE2 6314 6275 0.975974 0.0202039 -3.13352 1 0 1 1 0 0 +EDGE2 6314 595 1.06076 0.0336064 -3.14734 1 0 1 1 0 0 +EDGE2 6314 6313 -1.07331 0.0607306 -0.0232485 1 0 1 1 0 0 +EDGE2 6315 6274 1.10247 -0.08312 -3.11145 1 0 1 1 0 0 +EDGE2 6315 6234 0.994272 -0.052661 -3.16011 1 0 1 1 0 0 +EDGE2 6315 594 1.02763 0.00810335 -3.13472 1 0 1 1 0 0 +EDGE2 6315 6276 -0.0359238 0.952297 1.56877 1 0 1 1 0 0 +EDGE2 6315 596 0.0463288 -0.988943 -1.57504 1 0 1 1 0 0 +EDGE2 6315 6314 -1.07706 -0.0573345 0.00382636 1 0 1 1 0 0 +EDGE2 6315 6235 0.0520677 -0.0417569 -3.12087 1 0 1 1 0 0 +EDGE2 6315 6275 0.00832025 0.010086 -3.12161 1 0 1 1 0 0 +EDGE2 6315 595 0.0265849 -0.0499162 -3.16656 1 0 1 1 0 0 +EDGE2 6315 6236 -0.0106576 -0.951685 -1.58075 1 0 1 1 0 0 +EDGE2 6316 6277 1.0465 0.026064 -0.022652 1 0 1 1 0 0 +EDGE2 6316 6276 0.0634015 0.0200637 0.00757154 1 0 1 1 0 0 +EDGE2 6316 6315 -1.00359 0.00443446 -1.55161 1 0 1 1 0 0 +EDGE2 6316 6235 -0.889909 -0.00440453 1.57096 1 0 1 1 0 0 +EDGE2 6316 6275 -1.05288 -0.0681333 1.60509 1 0 1 1 0 0 +EDGE2 6316 595 -1.02679 -0.0175073 1.58846 1 0 1 1 0 0 +EDGE2 6317 6316 -1.07513 -0.027138 -0.00880032 1 0 1 1 0 0 +EDGE2 6317 6278 0.955606 0.00924151 0.0197068 1 0 1 1 0 0 +EDGE2 6317 6277 0.079891 0.0216162 0.0319735 1 0 1 1 0 0 +EDGE2 6317 6276 -1.01625 -0.00308512 -0.0282739 1 0 1 1 0 0 +EDGE2 6318 6279 1.00773 -0.0261114 0.00251888 1 0 1 1 0 0 +EDGE2 6318 6278 0.048141 0.00458399 -0.0117026 1 0 1 1 0 0 +EDGE2 6318 6317 -1.03161 0.0168004 -0.0170905 1 0 1 1 0 0 +EDGE2 6318 6277 -0.9676 0.0223315 -0.00468951 1 0 1 1 0 0 +EDGE2 6319 6279 -0.0360139 -0.0254039 0.0161562 1 0 1 1 0 0 +EDGE2 6319 6300 1.04196 -0.090724 -3.11849 1 0 1 1 0 0 +EDGE2 6319 6280 1.06833 0.031193 0.0206062 1 0 1 1 0 0 +EDGE2 6319 6278 -1.01433 0.0244543 -0.021472 1 0 1 1 0 0 +EDGE2 6319 6318 -1.01758 0.0587858 -0.0284536 1 0 1 1 0 0 +EDGE2 6320 6299 1.00439 -0.0338814 -3.08046 1 0 1 1 0 0 +EDGE2 6320 6281 0.0576676 -0.979881 -1.57809 1 0 1 1 0 0 +EDGE2 6320 6279 -1.1122 0.0183989 0.0234074 1 0 1 1 0 0 +EDGE2 6320 6300 -0.0203575 0.0152362 -3.17765 1 0 1 1 0 0 +EDGE2 6320 6280 -0.0777154 0.0318764 -0.0131213 1 0 1 1 0 0 +EDGE2 6320 6301 0.0104391 0.983158 1.5882 1 0 1 1 0 0 +EDGE2 6320 6319 -0.968907 -0.0009244 -0.0111553 1 0 1 1 0 0 +EDGE2 6321 6282 1.01063 -0.00983147 0.0194472 1 0 1 1 0 0 +EDGE2 6321 6281 -0.0231909 0.0251713 0.00831534 1 0 1 1 0 0 +EDGE2 6321 6300 -1.07084 0.0216017 -1.55185 1 0 1 1 0 0 +EDGE2 6321 6280 -1.0815 0.0112948 1.55812 1 0 1 1 0 0 +EDGE2 6321 6320 -0.953319 0.000144071 1.5786 1 0 1 1 0 0 +EDGE2 6322 6282 -0.0104417 0.0242955 -0.01466 1 0 1 1 0 0 +EDGE2 6322 6283 1.04651 -0.0475482 0.0183436 1 0 1 1 0 0 +EDGE2 6322 6281 -0.90391 0.0185073 -0.0186892 1 0 1 1 0 0 +EDGE2 6322 6321 -1.00482 0.0413886 -0.0193312 1 0 1 1 0 0 +EDGE2 6323 6282 -0.89927 0.0167134 0.0122557 1 0 1 1 0 0 +EDGE2 6323 6283 0.0126824 -0.0877403 -0.0270457 1 0 1 1 0 0 +EDGE2 6323 6284 0.962153 0.0447996 -0.0125302 1 0 1 1 0 0 +EDGE2 6323 6322 -1.05475 0.0161158 -0.0224053 1 0 1 1 0 0 +EDGE2 6324 6285 1.02975 -0.0626406 -0.0113663 1 0 1 1 0 0 +EDGE2 6324 585 1.1021 -0.030775 -3.1413 1 0 1 1 0 0 +EDGE2 6324 6283 -1.08868 -0.00959446 0.00675451 1 0 1 1 0 0 +EDGE2 6324 6284 -0.00418635 -0.0729086 -0.026065 1 0 1 1 0 0 +EDGE2 6324 6323 -1.04889 0.0763978 -0.00571816 1 0 1 1 0 0 +EDGE2 6325 6285 0.0810625 0.0120232 0.0284958 1 0 1 1 0 0 +EDGE2 6325 6286 0.0128251 0.981432 1.56763 1 0 1 1 0 0 +EDGE2 6325 584 0.86848 0.0661818 -3.13361 1 0 1 1 0 0 +EDGE2 6325 585 -0.0295928 -0.0154693 -3.1164 1 0 1 1 0 0 +EDGE2 6325 6324 -0.950752 -0.0114254 -0.0290823 1 0 1 1 0 0 +EDGE2 6325 6284 -0.920091 -0.0329855 0.0328679 1 0 1 1 0 0 +EDGE2 6325 586 -0.0576486 -1.01129 -1.56516 1 0 1 1 0 0 +EDGE2 6326 6287 0.980082 -0.00576741 -0.0178309 1 0 1 1 0 0 +EDGE2 6326 6325 -0.974214 -0.00707437 -1.55567 1 0 1 1 0 0 +EDGE2 6326 6285 -1.02489 0.0243006 -1.59934 1 0 1 1 0 0 +EDGE2 6326 6286 -0.0286207 0.0248632 0.00499394 1 0 1 1 0 0 +EDGE2 6326 585 -1.03092 0.00363761 1.57228 1 0 1 1 0 0 +EDGE2 6327 6288 0.977613 0.0450748 0.0147021 1 0 1 1 0 0 +EDGE2 6327 6287 0.0609604 0.0259202 0.0113752 1 0 1 1 0 0 +EDGE2 6327 6286 -0.991323 -0.0665961 0.00444737 1 0 1 1 0 0 +EDGE2 6327 6326 -1.01267 -0.00531368 0.0245932 1 0 1 1 0 0 +EDGE2 6328 6289 0.995861 -0.0126095 -0.00641737 1 0 1 1 0 0 +EDGE2 6328 6288 0.0813007 0.00261633 0.00189706 1 0 1 1 0 0 +EDGE2 6328 6287 -1.03752 -0.0236716 0.00175724 1 0 1 1 0 0 +EDGE2 6328 6327 -1.04492 -0.0139825 -0.0348609 1 0 1 1 0 0 +EDGE2 6329 6290 0.902995 0.0314206 0.0317131 1 0 1 1 0 0 +EDGE2 6329 6328 -0.997389 -0.0937098 -0.00571567 1 0 1 1 0 0 +EDGE2 6329 6289 0.0130194 -0.047486 -0.0089275 1 0 1 1 0 0 +EDGE2 6329 6288 -0.973237 -0.0428639 0.0225568 1 0 1 1 0 0 +EDGE2 6330 6291 -0.0418923 1.00273 1.56597 1 0 1 1 0 0 +EDGE2 6330 6290 0.0508136 0.0614343 0.0033591 1 0 1 1 0 0 +EDGE2 6330 6289 -0.963571 0.0769973 0.0333709 1 0 1 1 0 0 +EDGE2 6330 6329 -1.04351 0.000775381 -0.0135069 1 0 1 1 0 0 +EDGE2 6331 6290 -0.876278 -0.0535537 1.55956 1 0 1 1 0 0 +EDGE2 6331 6330 -1.08972 -0.016125 1.56593 1 0 1 1 0 0 +EDGE2 6332 6331 -0.98934 -0.0117513 -0.0136982 1 0 1 1 0 0 +EDGE2 6333 6332 -0.954104 0.00719922 0.000729645 1 0 1 1 0 0 +EDGE2 6334 6333 -1.00004 0.00449629 -0.00119313 1 0 1 1 0 0 +EDGE2 6334 575 0.996606 -0.0510414 -3.1453 1 0 1 1 0 0 +EDGE2 6334 6155 1.07428 0.0186698 -3.14175 1 0 1 1 0 0 +EDGE2 6335 6154 1.01195 0.0324339 -3.1153 1 0 1 1 0 0 +EDGE2 6335 574 0.991158 -0.0166083 -3.16257 1 0 1 1 0 0 +EDGE2 6335 6156 5.20852e-05 -0.939328 -1.55532 1 0 1 1 0 0 +EDGE2 6335 575 -0.00281165 0.039031 -3.14291 1 0 1 1 0 0 +EDGE2 6335 6155 0.0486737 -0.0273266 -3.14534 1 0 1 1 0 0 +EDGE2 6335 576 -0.0881982 -0.915165 -1.54324 1 0 1 1 0 0 +EDGE2 6335 6334 -1.01577 0.0173555 0.0404893 1 0 1 1 0 0 +EDGE2 6336 6335 -1.12494 -0.0189619 -1.58281 1 0 1 1 0 0 +EDGE2 6336 575 -1.03362 0.0127533 1.57089 1 0 1 1 0 0 +EDGE2 6336 6155 -1.01447 0.0276652 1.5845 1 0 1 1 0 0 +EDGE2 6337 6336 -0.97756 -0.0231145 0.00647012 1 0 1 1 0 0 +EDGE2 6338 6337 -1.04074 0.101017 0.00463429 1 0 1 1 0 0 +EDGE2 6339 6338 -0.999459 -0.0260707 -0.00783132 1 0 1 1 0 0 +EDGE2 6340 6339 -0.994272 -0.0102393 -0.0288288 1 0 1 1 0 0 +EDGE2 6341 6340 -1.0125 -0.043399 1.54728 1 0 1 1 0 0 +EDGE2 6342 6341 -1.00215 0.0310697 -0.00168315 1 0 1 1 0 0 +EDGE2 6343 6342 -1.04492 0.0416262 -0.0333121 1 0 1 1 0 0 +EDGE2 6344 6343 -0.993016 -0.0773324 0.00649388 1 0 1 1 0 0 +EDGE2 6344 565 0.953198 0.0873157 -3.13259 1 0 1 1 0 0 +EDGE2 6344 6145 0.984266 0.0416085 -3.12008 1 0 1 1 0 0 +EDGE2 6345 6144 0.963599 -0.0357146 -3.19849 1 0 1 1 0 0 +EDGE2 6345 564 1.02852 -0.0804869 -3.0973 1 0 1 1 0 0 +EDGE2 6345 565 0.0542598 0.105844 -3.18093 1 0 1 1 0 0 +EDGE2 6345 6145 -0.0860994 0.0302702 -3.15611 1 0 1 1 0 0 +EDGE2 6345 6344 -1.03823 0.0268954 -0.00519211 1 0 1 1 0 0 +EDGE2 6345 566 0.0670039 -1.08173 -1.59743 1 0 1 1 0 0 +EDGE2 6345 6146 0.0064455 -0.990517 -1.60954 1 0 1 1 0 0 +EDGE2 6346 565 -0.9827 0.0202287 1.57094 1 0 1 1 0 0 +EDGE2 6346 6145 -0.942844 0.0111312 1.53892 1 0 1 1 0 0 +EDGE2 6346 6345 -0.980927 -0.0965946 -1.54404 1 0 1 1 0 0 +EDGE2 6347 6346 -1.02419 -0.0609974 -0.0163613 1 0 1 1 0 0 +EDGE2 6348 6347 -1.0528 0.0560285 0.0598196 1 0 1 1 0 0 +EDGE2 6349 530 0.930638 -0.0125812 -3.16129 1 0 1 1 0 0 +EDGE2 6349 6348 -0.937366 -0.0344223 -0.00159592 1 0 1 1 0 0 +EDGE2 6350 529 0.983242 -0.0114369 -3.11887 1 0 1 1 0 0 +EDGE2 6350 531 0.0779283 -1.02845 -1.59896 1 0 1 1 0 0 +EDGE2 6350 530 0.0620053 0.00993364 -3.17152 1 0 1 1 0 0 +EDGE2 6350 6349 -1.00182 -0.0840324 -0.00650314 1 0 1 1 0 0 +EDGE2 6351 6350 -0.982873 0.0317764 -1.55508 1 0 1 1 0 0 +EDGE2 6351 530 -1.00657 -0.0558087 1.57782 1 0 1 1 0 0 +EDGE2 6352 6351 -1.10695 -0.0635737 -0.0101601 1 0 1 1 0 0 +EDGE2 6353 6352 -0.933899 -0.0328616 -0.0116363 1 0 1 1 0 0 +EDGE2 6354 6353 -1.01345 -0.03193 0.00391108 1 0 1 1 0 0 +EDGE2 6355 6354 -1.03267 -0.0508094 0.0052916 1 0 1 1 0 0 +EDGE2 6356 6355 -0.906023 -0.086875 1.57374 1 0 1 1 0 0 +EDGE2 6357 6356 -0.951909 0.0117465 0.0207108 1 0 1 1 0 0 +EDGE2 6358 6357 -0.991919 0.0491482 -0.0109558 1 0 1 1 0 0 +EDGE2 6359 6358 -1.08331 -0.069778 0.0126886 1 0 1 1 0 0 +EDGE2 6360 6359 -0.934664 0.0534545 -0.00940825 1 0 1 1 0 0 +EDGE2 6361 6360 -1.02114 -0.0173681 -1.56225 1 0 1 1 0 0 +EDGE2 6362 6361 -0.986961 -0.0771502 0.036059 1 0 1 1 0 0 +EDGE2 6363 6362 -1.00883 -0.0276127 0.00169801 1 0 1 1 0 0 +EDGE2 6364 6363 -1.02669 -0.0764372 0.00343927 1 0 1 1 0 0 +EDGE2 6365 6364 -0.95301 0.0188724 -0.0310968 1 0 1 1 0 0 +EDGE2 6366 6365 -1.1006 0.0230812 -1.57277 1 0 1 1 0 0 +EDGE2 6367 6366 -1.00879 -0.0533476 0.0141846 1 0 1 1 0 0 +EDGE2 6368 6367 -0.980716 0.030015 0.0157055 1 0 1 1 0 0 +EDGE2 6369 6368 -0.992272 -0.0748943 0.0228825 1 0 1 1 0 0 +EDGE2 6370 6369 -1.03831 0.139287 0.030957 1 0 1 1 0 0 +EDGE2 6371 6370 -1.02216 -0.0151279 -1.57106 1 0 1 1 0 0 +EDGE2 6372 6371 -0.979463 0.0759807 -0.0215179 1 0 1 1 0 0 +EDGE2 6373 6372 -0.932293 0.103897 -0.00159063 1 0 1 1 0 0 +EDGE2 6374 6355 1.02265 -0.0645135 -3.13907 1 0 1 1 0 0 +EDGE2 6374 6373 -1.05312 0.0207144 0.0161857 1 0 1 1 0 0 +EDGE2 6375 6356 -0.00373682 1.06861 1.56272 1 0 1 1 0 0 +EDGE2 6375 6354 0.965246 0.0058958 -3.1194 1 0 1 1 0 0 +EDGE2 6375 6355 -0.0290679 0.0488869 -3.15163 1 0 1 1 0 0 +EDGE2 6375 6374 -1.01277 -0.000544361 0.0288787 1 0 1 1 0 0 +EDGE2 6376 6355 -0.99058 -0.0708732 -1.57354 1 0 1 1 0 0 +EDGE2 6376 6375 -0.904383 -0.0142861 1.54906 1 0 1 1 0 0 +EDGE2 6377 6376 -1.05049 0.0380618 0.0232582 1 0 1 1 0 0 +EDGE2 6378 6377 -1.08082 0.000247627 -0.0215786 1 0 1 1 0 0 +EDGE2 6379 6378 -1.02699 -0.0986495 0.0158049 1 0 1 1 0 0 +EDGE2 6379 6340 1.00282 -0.0679502 -3.14294 1 0 1 1 0 0 +EDGE2 6380 6379 -0.938779 -0.0400169 0.00946409 1 0 1 1 0 0 +EDGE2 6380 6340 -0.00224785 0.00816364 -3.13427 1 0 1 1 0 0 +EDGE2 6380 6341 0.010708 1.04472 1.54975 1 0 1 1 0 0 +EDGE2 6380 6339 0.950758 -0.0444235 -3.12277 1 0 1 1 0 0 +EDGE2 6381 6340 -0.955898 -0.0179072 -1.56737 1 0 1 1 0 0 +EDGE2 6381 6380 -0.90214 0.0259709 1.56916 1 0 1 1 0 0 +EDGE2 6382 6381 -1.05596 0.0884455 -0.0142129 1 0 1 1 0 0 +EDGE2 6383 6382 -0.935728 -0.00416111 0.0439182 1 0 1 1 0 0 +EDGE2 6384 6383 -0.987047 0.0589802 -0.0008911 1 0 1 1 0 0 +EDGE2 6385 6384 -0.933135 -0.12945 0.021484 1 0 1 1 0 0 +EDGE2 6386 6385 -1.05834 -0.0317573 -1.59335 1 0 1 1 0 0 +EDGE2 6387 6386 -0.987865 -0.0115736 0.019149 1 0 1 1 0 0 +EDGE2 6388 6387 -1.04859 -0.0276184 0.0207567 1 0 1 1 0 0 +EDGE2 6389 6388 -1.02752 -0.0360844 0.020342 1 0 1 1 0 0 +EDGE2 6389 6290 1.0066 0.0542011 -3.13008 1 0 1 1 0 0 +EDGE2 6389 6330 1.02253 0.100534 -3.14476 1 0 1 1 0 0 +EDGE2 6390 6291 -0.0783295 -1.05189 -1.57519 1 0 1 1 0 0 +EDGE2 6390 6389 -0.990232 0.0489161 -0.00611006 1 0 1 1 0 0 +EDGE2 6390 6290 0.0444822 -0.00326697 -3.10673 1 0 1 1 0 0 +EDGE2 6390 6289 1.10239 0.0322329 -3.12064 1 0 1 1 0 0 +EDGE2 6390 6331 -0.00752801 0.974513 1.55892 1 0 1 1 0 0 +EDGE2 6390 6330 -0.0692299 -0.0224151 -3.14918 1 0 1 1 0 0 +EDGE2 6390 6329 0.952146 -0.0241021 -3.14259 1 0 1 1 0 0 +EDGE2 6391 6390 -0.966014 -0.0094629 -1.56071 1 0 1 1 0 0 +EDGE2 6391 6290 -1.01156 -0.0345581 1.56386 1 0 1 1 0 0 +EDGE2 6391 6331 0.10964 -0.0130029 0.0239133 1 0 1 1 0 0 +EDGE2 6391 6332 0.970865 0.092592 0.00475386 1 0 1 1 0 0 +EDGE2 6391 6330 -0.971244 0.0468869 1.55836 1 0 1 1 0 0 +EDGE2 6392 6333 0.930989 0.0270826 -0.0110099 1 0 1 1 0 0 +EDGE2 6392 6391 -0.991814 0.0267207 0.00041601 1 0 1 1 0 0 +EDGE2 6392 6331 -0.905542 0.0145845 -0.00257348 1 0 1 1 0 0 +EDGE2 6392 6332 0.00584638 -0.0886726 -0.0267939 1 0 1 1 0 0 +EDGE2 6393 6333 0.0684228 -0.019977 0.00966467 1 0 1 1 0 0 +EDGE2 6393 6334 0.943108 -0.0465012 0.0677367 1 0 1 1 0 0 +EDGE2 6393 6392 -0.98201 -0.00479205 -0.00424443 1 0 1 1 0 0 +EDGE2 6393 6332 -1.02733 -0.0323259 0.0273395 1 0 1 1 0 0 +EDGE2 6394 6333 -0.952172 0.039796 0.0154793 1 0 1 1 0 0 +EDGE2 6394 6335 1.11106 -0.00976794 0.00763613 1 0 1 1 0 0 +EDGE2 6394 575 1.0701 0.00138305 -3.1444 1 0 1 1 0 0 +EDGE2 6394 6155 0.976817 0.0522472 -3.11845 1 0 1 1 0 0 +EDGE2 6394 6334 0.0659192 -0.00370041 -0.0115589 1 0 1 1 0 0 +EDGE2 6394 6393 -1.00316 0.0198939 0.00324688 1 0 1 1 0 0 +EDGE2 6395 6336 -0.0224501 1.0281 1.5856 1 0 1 1 0 0 +EDGE2 6395 6154 1.08499 -0.0680774 -3.15671 1 0 1 1 0 0 +EDGE2 6395 574 0.931151 -0.0458008 -3.16 1 0 1 1 0 0 +EDGE2 6395 6156 0.0243023 -1.05511 -1.56978 1 0 1 1 0 0 +EDGE2 6395 6335 0.0544979 0.027159 0.0118985 1 0 1 1 0 0 +EDGE2 6395 575 0.0145078 -0.0530414 -3.13109 1 0 1 1 0 0 +EDGE2 6395 6155 0.0226645 0.057482 -3.15822 1 0 1 1 0 0 +EDGE2 6395 576 0.0533768 -1.03248 -1.57492 1 0 1 1 0 0 +EDGE2 6395 6334 -1.01919 0.0166216 -0.0026002 1 0 1 1 0 0 +EDGE2 6395 6394 -0.951051 -0.0261252 0.0193006 1 0 1 1 0 0 +EDGE2 6396 6395 -0.917968 -0.00460195 1.55544 1 0 1 1 0 0 +EDGE2 6396 6156 -0.00627213 0.0511407 0.000998706 1 0 1 1 0 0 +EDGE2 6396 6335 -0.995854 0.0439511 1.58163 1 0 1 1 0 0 +EDGE2 6396 575 -0.963752 -0.037118 -1.62405 1 0 1 1 0 0 +EDGE2 6396 6155 -1.06926 -0.0737484 -1.50683 1 0 1 1 0 0 +EDGE2 6396 576 -0.0798394 -0.0197791 0.00689546 1 0 1 1 0 0 +EDGE2 6396 577 1.04031 0.0515194 0.00108267 1 0 1 1 0 0 +EDGE2 6396 6157 1.02191 -0.0474739 -0.020355 1 0 1 1 0 0 +EDGE2 6397 6156 -1.04147 -0.0189231 0.00180689 1 0 1 1 0 0 +EDGE2 6397 6396 -0.993264 -0.0209315 0.0199612 1 0 1 1 0 0 +EDGE2 6397 576 -1.02913 0.0575631 -0.00693175 1 0 1 1 0 0 +EDGE2 6397 577 -0.078259 0.0129227 -0.0414343 1 0 1 1 0 0 +EDGE2 6397 6157 0.0405395 0.0734996 -0.00197107 1 0 1 1 0 0 +EDGE2 6397 6158 0.980158 -0.0360129 0.0460902 1 0 1 1 0 0 +EDGE2 6397 578 1.0538 -0.0323495 0.0035953 1 0 1 1 0 0 +EDGE2 6398 6397 -0.993896 0.0818748 -0.00564576 1 0 1 1 0 0 +EDGE2 6398 577 -0.97454 -0.0829841 -0.0165591 1 0 1 1 0 0 +EDGE2 6398 6157 -0.982461 -0.0944104 0.0242846 1 0 1 1 0 0 +EDGE2 6398 6158 0.0406666 -0.0394256 0.0369505 1 0 1 1 0 0 +EDGE2 6398 578 -0.0239495 0.0941476 -0.00671406 1 0 1 1 0 0 +EDGE2 6398 579 0.989246 0.0435763 -0.0251747 1 0 1 1 0 0 +EDGE2 6398 6159 0.969631 -0.0182474 0.0169768 1 0 1 1 0 0 +EDGE2 6399 6158 -1.00915 -0.0893292 0.00234963 1 0 1 1 0 0 +EDGE2 6399 6398 -0.991254 0.0160448 -0.00871506 1 0 1 1 0 0 +EDGE2 6399 578 -0.982823 -0.00513223 -0.041604 1 0 1 1 0 0 +EDGE2 6399 6160 0.988127 -0.0726679 -0.00719311 1 0 1 1 0 0 +EDGE2 6399 579 0.0221062 0.0302628 0.0010102 1 0 1 1 0 0 +EDGE2 6399 6159 0.0189768 -0.0682853 -0.0121612 1 0 1 1 0 0 +EDGE2 6399 580 0.95211 0.00489938 -0.00907444 1 0 1 1 0 0 +EDGE2 6400 6161 -0.0098604 1.02665 1.59898 1 0 1 1 0 0 +EDGE2 6400 6160 -0.0202772 0.0424607 -0.0341145 1 0 1 1 0 0 +EDGE2 6400 579 -0.955416 0.0187077 0.0206749 1 0 1 1 0 0 +EDGE2 6400 6159 -1.02194 -0.0272073 -0.0414203 1 0 1 1 0 0 +EDGE2 6400 6399 -0.961102 -0.00541366 0.0347238 1 0 1 1 0 0 +EDGE2 6400 581 0.053679 -1.02921 -1.58448 1 0 1 1 0 0 +EDGE2 6400 580 -0.00914669 -0.0127227 0.0017816 1 0 1 1 0 0 +EDGE2 6401 582 1.06055 0.0629278 -0.0431555 1 0 1 1 0 0 +EDGE2 6401 6160 -1.04128 -0.0138528 1.54823 1 0 1 1 0 0 +EDGE2 6401 6400 -0.979605 -0.0576644 1.58065 1 0 1 1 0 0 +EDGE2 6401 581 -0.020556 -0.0390791 -0.0203794 1 0 1 1 0 0 +EDGE2 6401 580 -1.03697 0.0889862 1.56927 1 0 1 1 0 0 +EDGE2 6402 582 -0.0603104 0.00417423 0.0105047 1 0 1 1 0 0 +EDGE2 6402 581 -0.921977 -0.152865 -0.046934 1 0 1 1 0 0 +EDGE2 6402 6401 -1.04108 -0.0343694 -0.0161673 1 0 1 1 0 0 +EDGE2 6402 583 1.04271 0.071576 0.0216855 1 0 1 1 0 0 +EDGE2 6403 582 -0.976718 -0.198086 0.0153612 1 0 1 1 0 0 +EDGE2 6403 6402 -0.957168 -0.00970335 -0.00445838 1 0 1 1 0 0 +EDGE2 6403 583 -0.0180174 0.0433281 -0.0397956 1 0 1 1 0 0 +EDGE2 6403 584 0.986966 -0.0296977 -0.00998792 1 0 1 1 0 0 +EDGE2 6404 583 -0.935696 0.060097 -0.017027 1 0 1 1 0 0 +EDGE2 6404 6403 -1.05181 0.011467 0.00405426 1 0 1 1 0 0 +EDGE2 6404 6325 0.998943 -0.0175037 -3.13248 1 0 1 1 0 0 +EDGE2 6404 6285 1.02993 -0.0417675 -3.13009 1 0 1 1 0 0 +EDGE2 6404 584 -0.0696197 0.0158754 -0.0279436 1 0 1 1 0 0 +EDGE2 6404 585 1.00589 0.0180067 0.0050973 1 0 1 1 0 0 +EDGE2 6405 6325 -0.000612351 0.034431 -3.15534 1 0 1 1 0 0 +EDGE2 6405 6285 0.000967579 -0.056248 -3.14677 1 0 1 1 0 0 +EDGE2 6405 6286 -0.0344684 -1.06546 -1.57346 1 0 1 1 0 0 +EDGE2 6405 6326 0.0366615 -1.02618 -1.59408 1 0 1 1 0 0 +EDGE2 6405 584 -1.0295 0.0229302 0.00176143 1 0 1 1 0 0 +EDGE2 6405 6404 -1.07078 0.0309242 0.00530168 1 0 1 1 0 0 +EDGE2 6405 585 0.00405017 -0.125541 0.00645396 1 0 1 1 0 0 +EDGE2 6405 6324 0.989186 -0.0203256 -3.13708 1 0 1 1 0 0 +EDGE2 6405 6284 1.00013 0.00495805 -3.13785 1 0 1 1 0 0 +EDGE2 6405 586 0.0280241 0.956064 1.53891 1 0 1 1 0 0 +EDGE2 6406 6287 0.977221 0.053021 0.01191 1 0 1 1 0 0 +EDGE2 6406 6325 -0.907292 -0.138057 -1.58711 1 0 1 1 0 0 +EDGE2 6406 6285 -1.06191 -0.0778125 -1.57193 1 0 1 1 0 0 +EDGE2 6406 6286 -0.0168909 -0.0289392 -0.0315359 1 0 1 1 0 0 +EDGE2 6406 6327 0.964242 0.00619641 -0.0193963 1 0 1 1 0 0 +EDGE2 6406 6326 0.0225723 0.00640698 0.00350837 1 0 1 1 0 0 +EDGE2 6406 6405 -0.961322 -0.0220476 1.58373 1 0 1 1 0 0 +EDGE2 6406 585 -1.11376 -0.0664356 1.58009 1 0 1 1 0 0 +EDGE2 6407 6328 0.917918 0.0980652 0.0221786 1 0 1 1 0 0 +EDGE2 6407 6288 0.992987 0.0197702 -0.0202742 1 0 1 1 0 0 +EDGE2 6407 6287 -0.047487 -0.00141967 0.0265099 1 0 1 1 0 0 +EDGE2 6407 6406 -0.966664 0.0372979 -0.00684239 1 0 1 1 0 0 +EDGE2 6407 6286 -1.0375 -0.0795338 -0.0353397 1 0 1 1 0 0 +EDGE2 6407 6327 -0.0355072 0.0296185 -0.0168521 1 0 1 1 0 0 +EDGE2 6407 6326 -1.00575 0.0790302 0.0055594 1 0 1 1 0 0 +EDGE2 6408 6407 -1.04216 -0.0100098 0.0251595 1 0 1 1 0 0 +EDGE2 6408 6328 -0.0561075 -0.0370655 -0.00680938 1 0 1 1 0 0 +EDGE2 6408 6289 1.04666 -0.0294555 -0.00484666 1 0 1 1 0 0 +EDGE2 6408 6288 0.0622165 0.0195255 -0.0467889 1 0 1 1 0 0 +EDGE2 6408 6329 0.983671 -0.0926441 -0.0102843 1 0 1 1 0 0 +EDGE2 6408 6287 -1.0115 -0.0365216 -0.00979291 1 0 1 1 0 0 +EDGE2 6408 6327 -1.02438 -0.0236388 0.00493193 1 0 1 1 0 0 +EDGE2 6409 6390 0.970162 0.0160688 -3.1441 1 0 1 1 0 0 +EDGE2 6409 6290 0.972993 0.0401895 0.00433734 1 0 1 1 0 0 +EDGE2 6409 6328 -0.918629 0.017882 0.0209007 1 0 1 1 0 0 +EDGE2 6409 6289 0.0882443 -0.0293735 0.00811061 1 0 1 1 0 0 +EDGE2 6409 6330 1.05853 -0.023445 -0.0241215 1 0 1 1 0 0 +EDGE2 6409 6288 -1.09818 0.0279868 -0.0131434 1 0 1 1 0 0 +EDGE2 6409 6329 -0.0648782 0.0226341 -0.00854848 1 0 1 1 0 0 +EDGE2 6409 6408 -1.011 0.0525822 -0.00433293 1 0 1 1 0 0 +EDGE2 6410 6291 -0.0157839 0.962048 1.55808 1 0 1 1 0 0 +EDGE2 6410 6391 0.00137477 -0.978764 -1.5643 1 0 1 1 0 0 +EDGE2 6410 6390 -0.1204 -0.069548 -3.15739 1 0 1 1 0 0 +EDGE2 6410 6389 0.940093 0.0998456 -3.1369 1 0 1 1 0 0 +EDGE2 6410 6290 0.0325964 -0.027315 -0.0223739 1 0 1 1 0 0 +EDGE2 6410 6289 -1.06804 -0.0156111 -0.0120026 1 0 1 1 0 0 +EDGE2 6410 6331 0.0133108 -0.997954 -1.60036 1 0 1 1 0 0 +EDGE2 6410 6330 0.0192288 -0.0181129 0.0435849 1 0 1 1 0 0 +EDGE2 6410 6329 -1.07195 -0.0145424 -0.0143271 1 0 1 1 0 0 +EDGE2 6410 6409 -1.02222 -0.0344198 0.00723362 1 0 1 1 0 0 +EDGE2 6411 6291 -0.00582945 -0.0148418 0.00316014 1 0 1 1 0 0 +EDGE2 6411 6390 -0.98288 -0.0182976 1.5865 1 0 1 1 0 0 +EDGE2 6411 6290 -1.02956 -0.0133775 -1.55898 1 0 1 1 0 0 +EDGE2 6411 6410 -0.977483 0.00391806 -1.58267 1 0 1 1 0 0 +EDGE2 6411 6330 -0.971056 -0.0485604 -1.5275 1 0 1 1 0 0 +EDGE2 6411 6292 1.02764 -0.0628184 0.0202035 1 0 1 1 0 0 +EDGE2 6412 6291 -0.98916 -0.0125789 0.0257958 1 0 1 1 0 0 +EDGE2 6412 6293 1.05074 0.0403038 0.0336238 1 0 1 1 0 0 +EDGE2 6412 6292 -0.0803887 0.0750043 0.0100664 1 0 1 1 0 0 +EDGE2 6412 6411 -1.03909 -0.0602613 -0.0166959 1 0 1 1 0 0 +EDGE2 6413 6412 -0.943366 0.0594171 -0.0377779 1 0 1 1 0 0 +EDGE2 6413 6294 0.914503 -0.0012005 0.00343851 1 0 1 1 0 0 +EDGE2 6413 6293 0.0498612 0.0973935 -0.0276539 1 0 1 1 0 0 +EDGE2 6413 6292 -1.01302 -0.0710833 0.000202589 1 0 1 1 0 0 +EDGE2 6414 6294 -0.0136215 0.088741 0.00790516 1 0 1 1 0 0 +EDGE2 6414 6293 -1.03483 -0.00494541 0.0294715 1 0 1 1 0 0 +EDGE2 6414 6413 -1.04344 -0.0400249 -0.0278204 1 0 1 1 0 0 +EDGE2 6414 6295 1.05568 0.0381545 0.0122219 1 0 1 1 0 0 +EDGE2 6415 6294 -1.09721 0.0115319 0.000240999 1 0 1 1 0 0 +EDGE2 6415 6414 -0.973965 0.0736807 -0.00359314 1 0 1 1 0 0 +EDGE2 6415 6295 0.0421588 -0.106752 0.00505119 1 0 1 1 0 0 +EDGE2 6415 6296 -0.0150501 1.01884 1.53597 1 0 1 1 0 0 +EDGE2 6416 6295 -1.046 -0.0165709 1.6069 1 0 1 1 0 0 +EDGE2 6416 6415 -0.997775 -0.0404267 1.54618 1 0 1 1 0 0 +EDGE2 6417 6416 -1.01701 0.00221982 -0.0434177 1 0 1 1 0 0 +EDGE2 6418 6417 -0.977114 -0.0372988 -0.0164627 1 0 1 1 0 0 +EDGE2 6419 6418 -0.9479 -0.136972 0.00277111 1 0 1 1 0 0 +EDGE2 6420 6419 -0.958923 -0.011587 -0.00928668 1 0 1 1 0 0 +EDGE2 6421 6420 -1.08706 0.0589066 -1.58242 1 0 1 1 0 0 +EDGE2 6422 6421 -0.903927 0.0220186 0.0203602 1 0 1 1 0 0 +EDGE2 6423 6422 -0.959419 -0.0213562 -0.0206226 1 0 1 1 0 0 +EDGE2 6424 6423 -1.00911 -0.0469713 0.00847195 1 0 1 1 0 0 +EDGE2 6425 6424 -0.962816 -0.0429088 -0.0338076 1 0 1 1 0 0 +EDGE2 6426 6425 -1.03283 -0.111118 -1.53982 1 0 1 1 0 0 +EDGE2 6427 6426 -1.06492 -0.0150677 -0.0188483 1 0 1 1 0 0 +EDGE2 6428 6427 -0.969021 0.0634817 -0.0256095 1 0 1 1 0 0 +EDGE2 6429 6428 -0.977441 -0.010259 -0.00793714 1 0 1 1 0 0 +EDGE2 6430 6429 -1.01358 0.0461651 -0.000767816 1 0 1 1 0 0 +EDGE2 6431 6430 -0.993359 -0.0210551 -1.56339 1 0 1 1 0 0 +EDGE2 6432 6431 -1.00183 0.00899543 -0.0413052 1 0 1 1 0 0 +EDGE2 6433 6432 -0.944299 0.0286149 0.0160187 1 0 1 1 0 0 +EDGE2 6434 6295 0.934927 0.0227054 -3.11304 1 0 1 1 0 0 +EDGE2 6434 6433 -0.940588 0.0177207 0.0236926 1 0 1 1 0 0 +EDGE2 6434 6415 0.854812 0.0711213 -3.11201 1 0 1 1 0 0 +EDGE2 6435 6294 1.06302 -0.0125828 -3.16818 1 0 1 1 0 0 +EDGE2 6435 6414 0.955892 -0.011327 -3.14442 1 0 1 1 0 0 +EDGE2 6435 6416 -0.0228515 0.983179 1.5492 1 0 1 1 0 0 +EDGE2 6435 6295 0.0545401 0.0134343 -3.15311 1 0 1 1 0 0 +EDGE2 6435 6434 -1.08385 0.0843459 0.0162761 1 0 1 1 0 0 +EDGE2 6435 6296 0.0540541 -0.997688 -1.53884 1 0 1 1 0 0 +EDGE2 6435 6415 0.0102475 -0.116999 -3.15871 1 0 1 1 0 0 +EDGE2 6436 6417 1.04573 0.00567772 0.0238728 1 0 1 1 0 0 +EDGE2 6436 6435 -0.982637 -0.01339 -1.54061 1 0 1 1 0 0 +EDGE2 6436 6416 -0.0166431 -0.115886 -0.00665285 1 0 1 1 0 0 +EDGE2 6436 6295 -1.0533 -0.0154894 1.54608 1 0 1 1 0 0 +EDGE2 6436 6415 -0.991397 -0.0158579 1.54782 1 0 1 1 0 0 +EDGE2 6437 6418 1.00047 -0.0512708 0.032605 1 0 1 1 0 0 +EDGE2 6437 6436 -1.03575 -0.0717289 0.0137534 1 0 1 1 0 0 +EDGE2 6437 6417 -0.00365966 0.0298525 -0.0387293 1 0 1 1 0 0 +EDGE2 6437 6416 -1.00873 0.0693041 -0.00516691 1 0 1 1 0 0 +EDGE2 6438 6418 -0.0180848 -0.0123542 -0.00157993 1 0 1 1 0 0 +EDGE2 6438 6419 0.94944 0.00870537 0.0228712 1 0 1 1 0 0 +EDGE2 6438 6417 -0.950321 0.0549947 -0.00635847 1 0 1 1 0 0 +EDGE2 6438 6437 -1.03426 0.0509825 -0.0268768 1 0 1 1 0 0 +EDGE2 6439 6418 -0.955752 -0.0166762 -0.0308551 1 0 1 1 0 0 +EDGE2 6439 6420 0.947736 0.0693713 -0.00957044 1 0 1 1 0 0 +EDGE2 6439 6419 -0.0286742 0.0365242 0.0146235 1 0 1 1 0 0 +EDGE2 6439 6438 -0.922847 0.0248285 0.0125009 1 0 1 1 0 0 +EDGE2 6440 6420 0.0755416 -0.019982 0.00433039 1 0 1 1 0 0 +EDGE2 6440 6421 -0.0315353 1.03374 1.60027 1 0 1 1 0 0 +EDGE2 6440 6419 -1.03437 0.00800773 -0.0163157 1 0 1 1 0 0 +EDGE2 6440 6439 -1.0058 -0.0544083 -0.0113818 1 0 1 1 0 0 +EDGE2 6441 6422 1.02111 -0.0244479 -0.0410103 1 0 1 1 0 0 +EDGE2 6441 6440 -0.964206 0.0541625 -1.56799 1 0 1 1 0 0 +EDGE2 6441 6420 -0.977115 -0.0173841 -1.5661 1 0 1 1 0 0 +EDGE2 6441 6421 0.0312865 0.00907525 0.0121674 1 0 1 1 0 0 +EDGE2 6442 6422 -0.0123273 -0.0283631 0.00435477 1 0 1 1 0 0 +EDGE2 6442 6421 -1.0532 -0.0761706 0.0227628 1 0 1 1 0 0 +EDGE2 6442 6441 -1.02014 0.0475912 0.0202137 1 0 1 1 0 0 +EDGE2 6442 6423 1.09212 0.0324288 0.0192916 1 0 1 1 0 0 +EDGE2 6443 6422 -0.989861 -0.0323482 0.00272518 1 0 1 1 0 0 +EDGE2 6443 6442 -0.96519 0.0901061 -0.0130952 1 0 1 1 0 0 +EDGE2 6443 6423 0.0479709 0.0640223 0.00722568 1 0 1 1 0 0 +EDGE2 6443 6424 1.07951 -0.0135989 0.0100484 1 0 1 1 0 0 +EDGE2 6444 6443 -1.04297 0.0121331 0.0191103 1 0 1 1 0 0 +EDGE2 6444 6423 -0.977688 0.058518 0.00266813 1 0 1 1 0 0 +EDGE2 6444 6424 -0.0639299 -0.0801655 -0.0122113 1 0 1 1 0 0 +EDGE2 6444 6425 1.05059 -0.0230639 0.0298417 1 0 1 1 0 0 +EDGE2 6445 6444 -1.00361 0.0487253 0.0100749 1 0 1 1 0 0 +EDGE2 6445 6424 -1.03938 -0.0260151 0.0129282 1 0 1 1 0 0 +EDGE2 6445 6426 0.0505199 1.00522 1.57778 1 0 1 1 0 0 +EDGE2 6445 6425 0.00792897 -0.0490029 0.00860707 1 0 1 1 0 0 +EDGE2 6446 6426 -0.0393648 0.0643326 -0.0282184 1 0 1 1 0 0 +EDGE2 6446 6425 -0.947749 -0.0713132 -1.55466 1 0 1 1 0 0 +EDGE2 6446 6445 -1.02344 -0.0138639 -1.57742 1 0 1 1 0 0 +EDGE2 6446 6427 1.06582 0.118653 -0.00904984 1 0 1 1 0 0 +EDGE2 6447 6426 -0.962169 0.0181327 -0.0147945 1 0 1 1 0 0 +EDGE2 6447 6446 -0.997643 -0.0479809 0.0163694 1 0 1 1 0 0 +EDGE2 6447 6427 0.00596747 -0.0556834 0.0169507 1 0 1 1 0 0 +EDGE2 6447 6428 1.01644 -0.0100988 -0.0128121 1 0 1 1 0 0 +EDGE2 6448 6447 -1.08415 0.0857467 0.00626719 1 0 1 1 0 0 +EDGE2 6448 6427 -1.01784 -0.0207522 0.0121122 1 0 1 1 0 0 +EDGE2 6448 6428 -0.0813179 0.00977965 -0.0108912 1 0 1 1 0 0 +EDGE2 6448 6429 1.0038 -0.00536819 0.0258361 1 0 1 1 0 0 +EDGE2 6449 6428 -0.931978 0.0433078 -0.0278988 1 0 1 1 0 0 +EDGE2 6449 6448 -1.02469 -0.0080221 0.011664 1 0 1 1 0 0 +EDGE2 6449 6429 0.0537626 0.00719764 0.0331362 1 0 1 1 0 0 +EDGE2 6449 6430 1.02248 -0.0130097 0.0284972 1 0 1 1 0 0 +EDGE2 6450 6449 -0.95216 0.0416121 -0.0133758 1 0 1 1 0 0 +EDGE2 6450 6429 -1.06373 0.0190256 -0.0221375 1 0 1 1 0 0 +EDGE2 6450 6431 -0.108884 1.00625 1.57969 1 0 1 1 0 0 +EDGE2 6450 6430 -0.0393903 0.033228 0.00473785 1 0 1 1 0 0 +EDGE2 6451 6431 0.0638952 -0.0271232 -0.0119976 1 0 1 1 0 0 +EDGE2 6451 6432 1.13184 -0.0161308 0.00321124 1 0 1 1 0 0 +EDGE2 6451 6430 -0.952815 -0.0121214 -1.57469 1 0 1 1 0 0 +EDGE2 6451 6450 -0.96322 -0.00929541 -1.5574 1 0 1 1 0 0 +EDGE2 6452 6433 1.01726 -0.00524924 0.00922794 1 0 1 1 0 0 +EDGE2 6452 6431 -0.957932 0.0166703 0.0138578 1 0 1 1 0 0 +EDGE2 6452 6451 -0.970693 -0.0315534 0.00193279 1 0 1 1 0 0 +EDGE2 6452 6432 0.0515787 0.0261536 -0.00530363 1 0 1 1 0 0 +EDGE2 6453 6452 -1.06312 -0.0359914 -0.00707771 1 0 1 1 0 0 +EDGE2 6453 6434 0.979842 -0.0299009 -0.0238326 1 0 1 1 0 0 +EDGE2 6453 6433 -0.023648 0.0525166 -0.00387437 1 0 1 1 0 0 +EDGE2 6453 6432 -1.0128 -0.0615644 -0.00476322 1 0 1 1 0 0 +EDGE2 6454 6435 0.925483 0.0158163 -0.0413164 1 0 1 1 0 0 +EDGE2 6454 6295 0.941682 -0.0124093 -3.13306 1 0 1 1 0 0 +EDGE2 6454 6453 -1.09914 -0.109268 0.0115371 1 0 1 1 0 0 +EDGE2 6454 6434 0.0134844 0.0182618 0.010213 1 0 1 1 0 0 +EDGE2 6454 6433 -1.00077 -0.0582837 0.0082033 1 0 1 1 0 0 +EDGE2 6454 6415 1.00959 0.0425615 -3.15433 1 0 1 1 0 0 +EDGE2 6455 6294 1.02441 -0.00920279 -3.12834 1 0 1 1 0 0 +EDGE2 6455 6414 1.05499 0.0237273 -3.15574 1 0 1 1 0 0 +EDGE2 6455 6454 -1.04619 0.0288878 -0.0176821 1 0 1 1 0 0 +EDGE2 6455 6436 -0.0136168 0.963987 1.56603 1 0 1 1 0 0 +EDGE2 6455 6435 -0.0655059 -0.0416678 -0.022671 1 0 1 1 0 0 +EDGE2 6455 6416 -0.0485013 0.993031 1.55518 1 0 1 1 0 0 +EDGE2 6455 6295 0.0464413 -0.00198088 -3.1434 1 0 1 1 0 0 +EDGE2 6455 6434 -1.00593 0.0270119 0.00729557 1 0 1 1 0 0 +EDGE2 6455 6296 0.0920354 -1.02472 -1.60397 1 0 1 1 0 0 +EDGE2 6455 6415 -0.0456406 0.182972 -3.1773 1 0 1 1 0 0 +EDGE2 6456 6436 0.0141671 0.00660599 0.00543354 1 0 1 1 0 0 +EDGE2 6456 6417 0.941723 -0.0341914 0.0531632 1 0 1 1 0 0 +EDGE2 6456 6437 1.0442 0.045604 0.00587701 1 0 1 1 0 0 +EDGE2 6456 6435 -0.938361 -0.0250362 -1.56294 1 0 1 1 0 0 +EDGE2 6456 6455 -1.01788 0.0475405 -1.53306 1 0 1 1 0 0 +EDGE2 6456 6416 0.00738268 -0.0559195 0.028118 1 0 1 1 0 0 +EDGE2 6456 6295 -0.948474 0.162229 1.59144 1 0 1 1 0 0 +EDGE2 6456 6415 -0.955243 -0.0675786 1.52577 1 0 1 1 0 0 +EDGE2 6457 6418 1.10655 0.0785072 -0.00931178 1 0 1 1 0 0 +EDGE2 6457 6438 1.01351 -0.0187002 -0.00877639 1 0 1 1 0 0 +EDGE2 6457 6436 -0.959904 -0.0691439 0.0203473 1 0 1 1 0 0 +EDGE2 6457 6417 0.0500544 0.0122909 0.00350588 1 0 1 1 0 0 +EDGE2 6457 6437 0.0351761 -0.0536919 0.0261492 1 0 1 1 0 0 +EDGE2 6457 6456 -1.07307 -0.0295591 0.022329 1 0 1 1 0 0 +EDGE2 6457 6416 -1.00254 0.0172111 0.0394727 1 0 1 1 0 0 +EDGE2 6458 6418 -0.0169233 -0.0340685 0.0155469 1 0 1 1 0 0 +EDGE2 6458 6419 0.982738 -0.0453774 -0.0482832 1 0 1 1 0 0 +EDGE2 6458 6439 0.944879 0.0538577 0.0034865 1 0 1 1 0 0 +EDGE2 6458 6438 0.053213 -0.016586 -0.0146426 1 0 1 1 0 0 +EDGE2 6458 6417 -0.931214 -0.0830813 0.0107718 1 0 1 1 0 0 +EDGE2 6458 6437 -1.01664 0.00189617 0.00146254 1 0 1 1 0 0 +EDGE2 6458 6457 -1.09194 -0.06393 -0.0015617 1 0 1 1 0 0 +EDGE2 6459 6418 -0.901727 0.0603112 -0.0180821 1 0 1 1 0 0 +EDGE2 6459 6440 1.01886 0.025541 0.00367258 1 0 1 1 0 0 +EDGE2 6459 6420 0.99235 -0.0858071 0.0321059 1 0 1 1 0 0 +EDGE2 6459 6458 -0.936867 0.00237126 0.00879332 1 0 1 1 0 0 +EDGE2 6459 6419 0.0198549 -0.0229486 -0.00665656 1 0 1 1 0 0 +EDGE2 6459 6439 -0.0193421 -0.00563437 0.00340722 1 0 1 1 0 0 +EDGE2 6459 6438 -1.01591 0.0537376 -0.0364221 1 0 1 1 0 0 +EDGE2 6460 6440 -0.0866047 -0.0461133 0.00954747 1 0 1 1 0 0 +EDGE2 6460 6420 0.133406 -0.0307905 0.0149164 1 0 1 1 0 0 +EDGE2 6460 6421 -0.0435289 1.00861 1.56823 1 0 1 1 0 0 +EDGE2 6460 6441 0.00551253 1.15064 1.59723 1 0 1 1 0 0 +EDGE2 6460 6459 -1.10581 0.0711123 -0.0324692 1 0 1 1 0 0 +EDGE2 6460 6419 -0.947419 0.109094 0.010964 1 0 1 1 0 0 +EDGE2 6460 6439 -0.937123 0.067551 0.01388 1 0 1 1 0 0 +EDGE2 6461 6460 -0.952088 -0.00437353 -1.58728 1 0 1 1 0 0 +EDGE2 6461 6422 1.0951 -0.0552122 -0.0308932 1 0 1 1 0 0 +EDGE2 6461 6440 -0.915211 0.0409528 -1.55496 1 0 1 1 0 0 +EDGE2 6461 6420 -1.01864 -0.0292218 -1.52558 1 0 1 1 0 0 +EDGE2 6461 6421 -0.126151 0.0763698 0.0481801 1 0 1 1 0 0 +EDGE2 6461 6441 -0.0567782 -0.067848 -0.00252549 1 0 1 1 0 0 +EDGE2 6461 6442 1.04941 0.116022 -0.00811061 1 0 1 1 0 0 +EDGE2 6462 6443 0.970869 -0.0679824 -0.0326871 1 0 1 1 0 0 +EDGE2 6462 6422 -0.0260324 0.0117161 -0.0280437 1 0 1 1 0 0 +EDGE2 6462 6461 -1.0094 0.0137986 0.00319111 1 0 1 1 0 0 +EDGE2 6462 6421 -1.00344 -0.00152932 -0.00676086 1 0 1 1 0 0 +EDGE2 6462 6441 -0.962916 -0.00705257 0.0267005 1 0 1 1 0 0 +EDGE2 6462 6442 0.00232674 -0.0381324 -0.0158234 1 0 1 1 0 0 +EDGE2 6462 6423 0.944006 -0.0205935 0.0310155 1 0 1 1 0 0 +EDGE2 6463 6443 -0.0278652 -0.072631 0.0175699 1 0 1 1 0 0 +EDGE2 6463 6422 -0.909871 0.0300915 -0.0240364 1 0 1 1 0 0 +EDGE2 6463 6462 -1.06426 0.0485688 -0.00554645 1 0 1 1 0 0 +EDGE2 6463 6442 -1.0982 -0.0392716 -0.0167627 1 0 1 1 0 0 +EDGE2 6463 6444 1.01749 0.0325248 0.0386368 1 0 1 1 0 0 +EDGE2 6463 6423 -0.014689 -0.016762 -0.00643586 1 0 1 1 0 0 +EDGE2 6463 6424 1.00359 0.024556 -0.0117046 1 0 1 1 0 0 +EDGE2 6464 6443 -0.998579 -0.0692748 -0.00173166 1 0 1 1 0 0 +EDGE2 6464 6463 -0.932261 0.0129686 0.00628314 1 0 1 1 0 0 +EDGE2 6464 6444 0.0460997 -0.0216729 -0.00211136 1 0 1 1 0 0 +EDGE2 6464 6423 -1.10144 0.01413 -0.0233701 1 0 1 1 0 0 +EDGE2 6464 6424 -0.0374717 0.0447938 0.0102123 1 0 1 1 0 0 +EDGE2 6464 6425 0.996553 0.0424031 -0.00799359 1 0 1 1 0 0 +EDGE2 6464 6445 0.965957 -0.00141469 0.00969802 1 0 1 1 0 0 +EDGE2 6465 6444 -1.02502 -0.0308838 -0.0129677 1 0 1 1 0 0 +EDGE2 6465 6464 -0.9923 -0.00331097 0.0173864 1 0 1 1 0 0 +EDGE2 6465 6424 -0.992266 -0.0290676 0.0224795 1 0 1 1 0 0 +EDGE2 6465 6426 0.0262968 1.01816 1.57831 1 0 1 1 0 0 +EDGE2 6465 6425 0.0284247 -0.0131511 0.030583 1 0 1 1 0 0 +EDGE2 6465 6445 0.00309763 -0.100698 0.00218138 1 0 1 1 0 0 +EDGE2 6465 6446 0.0209167 0.96038 1.54345 1 0 1 1 0 0 +EDGE2 6466 6465 -1.06405 0.0291077 -1.5398 1 0 1 1 0 0 +EDGE2 6466 6426 -0.0523679 0.0391414 -0.0113628 1 0 1 1 0 0 +EDGE2 6466 6425 -1.0232 0.0435223 -1.55804 1 0 1 1 0 0 +EDGE2 6466 6445 -0.91644 -0.0293727 -1.57515 1 0 1 1 0 0 +EDGE2 6466 6446 -0.0133622 -0.0153561 0.00616466 1 0 1 1 0 0 +EDGE2 6466 6447 0.918217 -0.0531843 0.0193162 1 0 1 1 0 0 +EDGE2 6466 6427 1.02415 -0.0303205 0.00220514 1 0 1 1 0 0 +EDGE2 6467 6426 -0.985489 -0.106292 0.0191138 1 0 1 1 0 0 +EDGE2 6467 6466 -0.979291 -0.0454561 0.0189751 1 0 1 1 0 0 +EDGE2 6467 6446 -0.948815 -0.0344118 0.0301454 1 0 1 1 0 0 +EDGE2 6467 6447 -0.0220882 -0.0239401 -0.00252078 1 0 1 1 0 0 +EDGE2 6467 6427 -0.0249456 0.0109874 -0.00446126 1 0 1 1 0 0 +EDGE2 6467 6428 0.972684 -0.0333656 -0.00896722 1 0 1 1 0 0 +EDGE2 6467 6448 0.945415 -0.0134943 0.0230889 1 0 1 1 0 0 +EDGE2 6468 6447 -0.977753 -0.0961592 0.0273782 1 0 1 1 0 0 +EDGE2 6468 6467 -0.927881 0.0285022 -0.0102136 1 0 1 1 0 0 +EDGE2 6468 6427 -0.928874 -0.0954104 -0.000699728 1 0 1 1 0 0 +EDGE2 6468 6449 1.01516 0.0324396 -0.0331455 1 0 1 1 0 0 +EDGE2 6468 6428 0.0810271 -0.0323371 0.000581236 1 0 1 1 0 0 +EDGE2 6468 6448 0.092663 -0.032636 -0.0223153 1 0 1 1 0 0 +EDGE2 6468 6429 1.03234 -0.106172 -0.0447073 1 0 1 1 0 0 +EDGE2 6469 6449 -0.00834029 -0.0790401 -0.00558227 1 0 1 1 0 0 +EDGE2 6469 6428 -1.03344 0.0105018 0.010276 1 0 1 1 0 0 +EDGE2 6469 6448 -1.07358 0.0065158 -0.00193735 1 0 1 1 0 0 +EDGE2 6469 6468 -1.07538 0.00806873 0.0165961 1 0 1 1 0 0 +EDGE2 6469 6429 -0.00592678 0.0497773 0.0167618 1 0 1 1 0 0 +EDGE2 6469 6430 0.963986 -0.0762775 -0.00856175 1 0 1 1 0 0 +EDGE2 6469 6450 1.00363 -0.0327153 -0.0322034 1 0 1 1 0 0 +EDGE2 6470 6449 -0.995161 -0.061202 0.0328272 1 0 1 1 0 0 +EDGE2 6470 6469 -1.02879 -0.0909219 -0.014023 1 0 1 1 0 0 +EDGE2 6470 6429 -0.945989 0.123825 -0.0171182 1 0 1 1 0 0 +EDGE2 6470 6431 0.0362442 0.961839 1.60955 1 0 1 1 0 0 +EDGE2 6470 6451 0.0629077 1.03853 1.58764 1 0 1 1 0 0 +EDGE2 6470 6430 -0.0337209 0.0481459 -0.00678487 1 0 1 1 0 0 +EDGE2 6470 6450 -0.0821537 -0.115203 -0.00137037 1 0 1 1 0 0 +EDGE2 6471 6470 -1.0444 -0.0552565 1.58193 1 0 1 1 0 0 +EDGE2 6471 6430 -0.983407 -0.0658081 1.51456 1 0 1 1 0 0 +EDGE2 6471 6450 -1.0508 0.100156 1.57329 1 0 1 1 0 0 +EDGE2 6472 6471 -1.07967 -0.0225864 0.0264478 1 0 1 1 0 0 +EDGE2 6473 6472 -0.93005 0.00733754 -0.041604 1 0 1 1 0 0 +EDGE2 6474 6473 -1.00551 -0.0245083 -6.20648e-05 1 0 1 1 0 0 +EDGE2 6475 6474 -1.05014 0.0460021 -0.0257857 1 0 1 1 0 0 +EDGE2 6476 6475 -0.95343 -0.00795432 -1.552 1 0 1 1 0 0 +EDGE2 6477 6476 -1.05585 -0.0581938 0.0271529 1 0 1 1 0 0 +EDGE2 6478 6477 -1.0349 -0.135903 -0.0132525 1 0 1 1 0 0 +EDGE2 6479 6478 -0.899318 -0.0982773 0.0171633 1 0 1 1 0 0 +EDGE2 6480 6479 -1.06617 0.00383263 -0.0171552 1 0 1 1 0 0 +EDGE2 6481 6480 -0.938234 0.00809921 -1.55697 1 0 1 1 0 0 +EDGE2 6482 6481 -0.866104 0.048882 -0.00356941 1 0 1 1 0 0 +EDGE2 6483 6482 -1.01845 -0.0564921 -0.0314355 1 0 1 1 0 0 +EDGE2 6484 6305 1.02727 0.0498215 -3.15222 1 0 1 1 0 0 +EDGE2 6484 6483 -0.991235 -0.017459 0.0172641 1 0 1 1 0 0 +EDGE2 6485 6304 1.00719 -0.0244531 -3.13364 1 0 1 1 0 0 +EDGE2 6485 6305 0.137273 -0.0192672 -3.11508 1 0 1 1 0 0 +EDGE2 6485 6306 0.046792 -1.01581 -1.58913 1 0 1 1 0 0 +EDGE2 6485 6484 -0.992702 -0.0197948 0.00459888 1 0 1 1 0 0 +EDGE2 6486 6485 -0.980862 -0.00122474 -1.60089 1 0 1 1 0 0 +EDGE2 6486 6305 -1.03239 0.0735014 1.57203 1 0 1 1 0 0 +EDGE2 6487 6486 -0.960119 0.0835404 -0.0221673 1 0 1 1 0 0 +EDGE2 6488 6487 -0.982256 -0.079014 -0.0238643 1 0 1 1 0 0 +EDGE2 6489 6470 0.929884 -0.0839492 -3.15685 1 0 1 1 0 0 +EDGE2 6489 6430 1.01217 -0.00297074 -3.13242 1 0 1 1 0 0 +EDGE2 6489 6450 0.993519 -0.0594184 -3.13436 1 0 1 1 0 0 +EDGE2 6489 6488 -1.00865 0.0256163 -0.002689 1 0 1 1 0 0 +EDGE2 6490 6449 1.0216 -0.0403913 -3.1605 1 0 1 1 0 0 +EDGE2 6490 6469 1.00871 0.0422693 -3.1168 1 0 1 1 0 0 +EDGE2 6490 6429 1.04231 -0.0674844 -3.12159 1 0 1 1 0 0 +EDGE2 6490 6470 -0.0584899 -0.0333424 -3.12586 1 0 1 1 0 0 +EDGE2 6490 6431 -0.0341227 -0.958957 -1.56975 1 0 1 1 0 0 +EDGE2 6490 6451 0.0466463 -0.973817 -1.57279 1 0 1 1 0 0 +EDGE2 6490 6430 0.0451107 -0.0495126 -3.152 1 0 1 1 0 0 +EDGE2 6490 6450 -0.0163935 -0.0308043 -3.13914 1 0 1 1 0 0 +EDGE2 6490 6489 -0.923792 -0.0245675 0.0318297 1 0 1 1 0 0 +EDGE2 6490 6471 0.0882305 0.964294 1.55686 1 0 1 1 0 0 +EDGE2 6491 6470 -1.013 -0.00983221 1.5703 1 0 1 1 0 0 +EDGE2 6491 6490 -0.931016 -0.0102229 -1.57678 1 0 1 1 0 0 +EDGE2 6491 6430 -1.01816 0.00637632 1.53946 1 0 1 1 0 0 +EDGE2 6491 6450 -0.916951 -0.0287952 1.55372 1 0 1 1 0 0 +EDGE2 6491 6471 -0.0461394 0.0471161 -0.0054127 1 0 1 1 0 0 +EDGE2 6491 6472 1.04837 -0.0243104 0.00623268 1 0 1 1 0 0 +EDGE2 6492 6491 -0.991873 0.0523849 -0.00377134 1 0 1 1 0 0 +EDGE2 6492 6471 -0.954515 0.0447486 -0.021566 1 0 1 1 0 0 +EDGE2 6492 6472 -0.00939897 0.0969295 -0.000661315 1 0 1 1 0 0 +EDGE2 6492 6473 1.11542 0.0430807 -0.000427665 1 0 1 1 0 0 +EDGE2 6493 6474 0.987731 -0.0178394 -0.0227273 1 0 1 1 0 0 +EDGE2 6493 6492 -1.07315 0.0251378 -0.0231214 1 0 1 1 0 0 +EDGE2 6493 6472 -1.03625 -0.0109654 0.0071764 1 0 1 1 0 0 +EDGE2 6493 6473 0.00483057 -0.0796141 0.0136399 1 0 1 1 0 0 +EDGE2 6494 6474 -0.00728285 -0.044018 -0.0128322 1 0 1 1 0 0 +EDGE2 6494 6473 -1.03966 -0.0414637 -0.0351763 1 0 1 1 0 0 +EDGE2 6494 6493 -1.01441 -0.0737667 -0.00196566 1 0 1 1 0 0 +EDGE2 6494 6475 1.01065 -0.0214524 -0.0138496 1 0 1 1 0 0 +EDGE2 6495 6474 -1.05039 -0.00271642 0.0153844 1 0 1 1 0 0 +EDGE2 6495 6494 -0.996815 0.0364847 -0.00631731 1 0 1 1 0 0 +EDGE2 6495 6475 0.0338508 -0.0225554 0.00938927 1 0 1 1 0 0 +EDGE2 6495 6476 0.0347881 1.02143 1.62776 1 0 1 1 0 0 +EDGE2 6496 6495 -0.982559 0.0201267 -1.5667 1 0 1 1 0 0 +EDGE2 6496 6475 -0.933533 -0.0338686 -1.56955 1 0 1 1 0 0 +EDGE2 6496 6476 0.00472722 -0.039175 0.00964223 1 0 1 1 0 0 +EDGE2 6496 6477 1.03048 -0.037222 -0.00226082 1 0 1 1 0 0 +EDGE2 6497 6478 1.03959 0.0356088 0.00914404 1 0 1 1 0 0 +EDGE2 6497 6476 -0.968145 0.0572946 -0.00156387 1 0 1 1 0 0 +EDGE2 6497 6496 -0.951046 0.0499999 -0.0184489 1 0 1 1 0 0 +EDGE2 6497 6477 -0.0360546 0.00295672 0.00473834 1 0 1 1 0 0 +EDGE2 6498 6478 0.0169801 -0.0135801 0.0161289 1 0 1 1 0 0 +EDGE2 6498 6497 -0.975796 0.0155194 0.0142382 1 0 1 1 0 0 +EDGE2 6498 6477 -1.14072 -0.03925 -0.0117796 1 0 1 1 0 0 +EDGE2 6498 6479 1.10106 -0.0850721 0.00151985 1 0 1 1 0 0 +EDGE2 6499 6478 -1.01023 0.0379823 0.0178155 1 0 1 1 0 0 +EDGE2 6499 6498 -0.982199 0.0624788 -0.0105131 1 0 1 1 0 0 +EDGE2 6499 6479 -0.0258456 -0.022777 -0.00628859 1 0 1 1 0 0 +EDGE2 6499 6480 1.0929 0.0860748 0.0139342 1 0 1 1 0 0 +EDGE2 6500 6479 -0.960573 0.0488909 -0.0364961 1 0 1 1 0 0 +EDGE2 6500 6499 -0.983321 -0.0254654 0.0103416 1 0 1 1 0 0 +EDGE2 6500 6480 0.0897585 0.0631998 0.0334648 1 0 1 1 0 0 +EDGE2 6500 6481 -0.0147013 1.0482 1.57242 1 0 1 1 0 0 +EDGE2 6501 6480 -1.00832 0.0175441 -1.54261 1 0 1 1 0 0 +EDGE2 6501 6482 1.04812 -0.0121319 0.020359 1 0 1 1 0 0 +EDGE2 6501 6481 0.0253403 0.0384019 0.0247949 1 0 1 1 0 0 +EDGE2 6501 6500 -1.02863 0.00659577 -1.6145 1 0 1 1 0 0 +EDGE2 6502 6501 -1.01804 -0.100314 0.0180276 1 0 1 1 0 0 +EDGE2 6502 6483 1.06597 -0.0175462 -0.0164323 1 0 1 1 0 0 +EDGE2 6502 6482 0.00586132 0.00475863 0.0106922 1 0 1 1 0 0 +EDGE2 6502 6481 -1.03336 0.0596592 0.0118088 1 0 1 1 0 0 +EDGE2 6503 6484 1.09142 -0.0356127 0.0048495 1 0 1 1 0 0 +EDGE2 6503 6502 -0.953466 -0.00912508 -0.00824372 1 0 1 1 0 0 +EDGE2 6503 6483 0.0620364 -0.00381018 -0.00961812 1 0 1 1 0 0 +EDGE2 6503 6482 -1.00617 -0.062392 0.010761 1 0 1 1 0 0 +EDGE2 6504 6485 1.05653 -0.048862 -0.00731684 1 0 1 1 0 0 +EDGE2 6504 6305 1.01436 0.059352 -3.1451 1 0 1 1 0 0 +EDGE2 6504 6484 0.0206548 -0.0168571 0.00336473 1 0 1 1 0 0 +EDGE2 6504 6483 -1.00899 -0.00498242 0.0103412 1 0 1 1 0 0 +EDGE2 6504 6503 -0.866791 0.046556 0.0215585 1 0 1 1 0 0 +EDGE2 6505 6486 -0.0365247 0.973051 1.57419 1 0 1 1 0 0 +EDGE2 6505 6485 -0.0517982 0.0219832 -0.041258 1 0 1 1 0 0 +EDGE2 6505 6304 1.07434 0.0837509 -3.16331 1 0 1 1 0 0 +EDGE2 6505 6305 -0.0538075 -0.0408298 -3.1298 1 0 1 1 0 0 +EDGE2 6505 6306 -0.0432563 -0.958611 -1.57746 1 0 1 1 0 0 +EDGE2 6505 6484 -1.00634 0.0658537 0.00210394 1 0 1 1 0 0 +EDGE2 6505 6504 -1.01479 0.0150094 0.0218118 1 0 1 1 0 0 +EDGE2 6506 6487 0.995638 0.0558844 0.00178623 1 0 1 1 0 0 +EDGE2 6506 6505 -0.993349 0.003359 -1.58842 1 0 1 1 0 0 +EDGE2 6506 6486 0.0924011 0.00124969 0.025554 1 0 1 1 0 0 +EDGE2 6506 6485 -1.06234 0.0555086 -1.56505 1 0 1 1 0 0 +EDGE2 6506 6305 -1.04899 -0.0398383 1.60881 1 0 1 1 0 0 +EDGE2 6507 6488 0.928535 -0.0405983 0.0142523 1 0 1 1 0 0 +EDGE2 6507 6487 -0.0151767 -0.0305554 0.00366422 1 0 1 1 0 0 +EDGE2 6507 6486 -1.12885 -0.0126587 -0.0256325 1 0 1 1 0 0 +EDGE2 6507 6506 -1.03775 -0.0794085 -0.0405723 1 0 1 1 0 0 +EDGE2 6508 6489 1.0989 0.0175344 -0.0145437 1 0 1 1 0 0 +EDGE2 6508 6507 -0.944736 0.0639676 -0.00660132 1 0 1 1 0 0 +EDGE2 6508 6488 -0.0395962 -0.0376984 0.0451469 1 0 1 1 0 0 +EDGE2 6508 6487 -1.02363 0.0126469 0.00793936 1 0 1 1 0 0 +EDGE2 6509 6470 0.95708 0.135417 -3.16797 1 0 1 1 0 0 +EDGE2 6509 6490 0.95781 0.022253 0.0060193 1 0 1 1 0 0 +EDGE2 6509 6508 -1.00804 0.0627663 -0.0185789 1 0 1 1 0 0 +EDGE2 6509 6430 1.03194 -0.0277902 -3.13097 1 0 1 1 0 0 +EDGE2 6509 6450 1.02625 0.0044282 -3.14257 1 0 1 1 0 0 +EDGE2 6509 6489 0.0226871 0.00446727 -0.0282705 1 0 1 1 0 0 +EDGE2 6509 6488 -0.953269 -0.031686 -0.0321346 1 0 1 1 0 0 +EDGE2 6510 6449 1.05306 -0.02297 -3.1445 1 0 1 1 0 0 +EDGE2 6510 6469 1.02964 -0.0475466 -3.1362 1 0 1 1 0 0 +EDGE2 6510 6429 1.07926 0.00786263 -3.14153 1 0 1 1 0 0 +EDGE2 6510 6470 -0.00993863 -0.0201057 -3.11424 1 0 1 1 0 0 +EDGE2 6510 6490 -0.0357904 -0.0481598 -0.0170489 1 0 1 1 0 0 +EDGE2 6510 6431 -0.0667233 -0.980618 -1.56807 1 0 1 1 0 0 +EDGE2 6510 6451 -0.0881231 -0.937844 -1.56061 1 0 1 1 0 0 +EDGE2 6510 6509 -1.0637 0.0211326 -0.0240593 1 0 1 1 0 0 +EDGE2 6510 6430 0.0421468 0.0134483 -3.13314 1 0 1 1 0 0 +EDGE2 6510 6450 -0.0703601 0.0023569 -3.13024 1 0 1 1 0 0 +EDGE2 6510 6489 -1.0136 0.0124404 0.000592339 1 0 1 1 0 0 +EDGE2 6510 6491 0.0357701 1.04941 1.5915 1 0 1 1 0 0 +EDGE2 6510 6471 0.0629663 1.00672 1.56416 1 0 1 1 0 0 +EDGE2 6511 6470 -1.0446 0.000383542 1.576 1 0 1 1 0 0 +EDGE2 6511 6490 -1.05021 0.0346934 -1.57286 1 0 1 1 0 0 +EDGE2 6511 6510 -1.01424 0.026041 -1.59623 1 0 1 1 0 0 +EDGE2 6511 6430 -0.986347 0.00612925 1.54749 1 0 1 1 0 0 +EDGE2 6511 6450 -0.943834 -0.0587673 1.54739 1 0 1 1 0 0 +EDGE2 6511 6491 0.0336105 -0.0283895 -0.0285141 1 0 1 1 0 0 +EDGE2 6511 6492 0.994039 -0.0594698 0.00899837 1 0 1 1 0 0 +EDGE2 6511 6471 0.0136599 -0.0415878 -0.00317971 1 0 1 1 0 0 +EDGE2 6511 6472 1.0383 0.0400801 -0.0213243 1 0 1 1 0 0 +EDGE2 6512 6491 -0.876578 0.0485493 -0.00600031 1 0 1 1 0 0 +EDGE2 6512 6511 -0.937391 0.00370642 -0.0113868 1 0 1 1 0 0 +EDGE2 6512 6492 0.00828571 0.0590049 0.0184987 1 0 1 1 0 0 +EDGE2 6512 6471 -0.991365 0.0628902 -0.0100339 1 0 1 1 0 0 +EDGE2 6512 6472 -0.0112567 -0.0480332 0.00815486 1 0 1 1 0 0 +EDGE2 6512 6473 0.968775 0.0498599 -0.0423017 1 0 1 1 0 0 +EDGE2 6512 6493 0.924751 0.102908 0.010013 1 0 1 1 0 0 +EDGE2 6513 6474 0.949596 -0.0638547 -0.00431504 1 0 1 1 0 0 +EDGE2 6513 6492 -0.921309 0.00591398 0.00228515 1 0 1 1 0 0 +EDGE2 6513 6512 -1.09546 -0.0204726 0.00406273 1 0 1 1 0 0 +EDGE2 6513 6472 -0.997767 -0.024738 -0.0276793 1 0 1 1 0 0 +EDGE2 6513 6473 -0.0401416 0.0293982 -0.00723068 1 0 1 1 0 0 +EDGE2 6513 6493 -0.0328967 -0.0268121 0.00818134 1 0 1 1 0 0 +EDGE2 6513 6494 1.09676 0.0409655 0.0276499 1 0 1 1 0 0 +EDGE2 6514 6474 0.00803133 -0.0315378 0.00542581 1 0 1 1 0 0 +EDGE2 6514 6513 -1.01906 0.0376016 0.0227188 1 0 1 1 0 0 +EDGE2 6514 6473 -1.00144 -0.0652723 -0.0156265 1 0 1 1 0 0 +EDGE2 6514 6493 -1.02107 0.0192857 0.00862902 1 0 1 1 0 0 +EDGE2 6514 6494 -0.0800573 -0.0530148 0.0327334 1 0 1 1 0 0 +EDGE2 6514 6495 0.995164 -0.0930571 -0.013335 1 0 1 1 0 0 +EDGE2 6514 6475 0.954168 0.0294467 -0.00960611 1 0 1 1 0 0 +EDGE2 6515 6474 -0.974431 -0.0928451 0.0154738 1 0 1 1 0 0 +EDGE2 6515 6514 -0.953664 -0.0529776 0.00842349 1 0 1 1 0 0 +EDGE2 6515 6494 -0.977851 -0.0768283 0.017585 1 0 1 1 0 0 +EDGE2 6515 6495 -0.0199847 -0.020669 -0.0269923 1 0 1 1 0 0 +EDGE2 6515 6475 0.103642 -0.0611493 -0.0124082 1 0 1 1 0 0 +EDGE2 6515 6476 0.00442771 1.01652 1.53317 1 0 1 1 0 0 +EDGE2 6515 6496 -0.00742338 1.09908 1.55297 1 0 1 1 0 0 +EDGE2 6516 6495 -0.999605 0.0788821 1.58398 1 0 1 1 0 0 +EDGE2 6516 6515 -0.938676 0.0134526 1.57057 1 0 1 1 0 0 +EDGE2 6516 6475 -1.06416 -0.0566797 1.6261 1 0 1 1 0 0 +EDGE2 6517 6516 -1.01756 -0.0271169 0.0277592 1 0 1 1 0 0 +EDGE2 6518 6517 -0.992041 -0.0722267 -0.0132867 1 0 1 1 0 0 +EDGE2 6519 6518 -0.928467 0.0187319 0.0217523 1 0 1 1 0 0 +EDGE2 6520 6519 -1.01285 -0.0262238 -0.0270387 1 0 1 1 0 0 +EDGE2 6521 6520 -0.995293 0.0388407 -1.54818 1 0 1 1 0 0 +EDGE2 6522 6521 -1.04556 -0.0131044 0.0169813 1 0 1 1 0 0 +EDGE2 6523 6522 -0.955391 -0.016226 0.0140141 1 0 1 1 0 0 +EDGE2 6524 6523 -1.04124 -0.0744847 0.00664248 1 0 1 1 0 0 +EDGE2 6525 6524 -0.973004 -0.0128388 -0.00774248 1 0 1 1 0 0 +EDGE2 6526 6525 -1.02719 -0.0304877 1.56897 1 0 1 1 0 0 +EDGE2 6527 6526 -1.04196 -0.0660197 -0.0357296 1 0 1 1 0 0 +EDGE2 6528 6527 -1.05951 0.0259455 0.0102039 1 0 1 1 0 0 +EDGE2 6529 6528 -1.00925 0.0426084 0.0457933 1 0 1 1 0 0 +EDGE2 6530 6529 -0.915593 -0.0614415 -0.00871425 1 0 1 1 0 0 +EDGE2 6531 6530 -0.971531 0.0305969 -1.5747 1 0 1 1 0 0 +EDGE2 6532 6531 -0.959772 -0.0714341 -0.0291275 1 0 1 1 0 0 +EDGE2 6533 6532 -1.07511 0.032212 -0.00881406 1 0 1 1 0 0 +EDGE2 6534 6533 -1.02813 0.109376 0.0258584 1 0 1 1 0 0 +EDGE2 6535 6534 -0.99139 0.00278093 0.0491324 1 0 1 1 0 0 +EDGE2 6536 6535 -1.02348 0.0394468 -1.57387 1 0 1 1 0 0 +EDGE2 6537 6536 -0.975512 0.0098951 -0.0348001 1 0 1 1 0 0 +EDGE2 6538 6537 -1.05129 -0.0797918 -0.00538254 1 0 1 1 0 0 +EDGE2 6539 6538 -0.922865 -0.0343839 0.0146701 1 0 1 1 0 0 +EDGE2 6540 6539 -1.04049 0.00308531 -0.00780777 1 0 1 1 0 0 +EDGE2 6541 6540 -1.13859 0.0327753 1.5559 1 0 1 1 0 0 +EDGE2 6542 6541 -0.968878 0.0214732 -0.0232122 1 0 1 1 0 0 +EDGE2 6543 6542 -1.01211 -0.0248112 -0.0133146 1 0 1 1 0 0 +EDGE2 6544 6543 -1.06572 -0.0252322 0.00724076 1 0 1 1 0 0 +EDGE2 6545 6544 -1.0575 0.0173484 -0.0134029 1 0 1 1 0 0 +EDGE2 6546 6545 -1.0333 0.153061 1.56244 1 0 1 1 0 0 +EDGE2 6547 6546 -1.04182 0.0143582 0.0230068 1 0 1 1 0 0 +EDGE2 6548 6547 -1.05018 0.0446442 -0.00992655 1 0 1 1 0 0 +EDGE2 6549 6548 -0.998091 0.014299 0.00582534 1 0 1 1 0 0 +EDGE2 6550 6549 -0.983608 0.0075052 0.00732095 1 0 1 1 0 0 +EDGE2 6551 6550 -0.976403 -0.0249456 -1.57527 1 0 1 1 0 0 +EDGE2 6552 6551 -1.03519 0.0344778 -0.0193579 1 0 1 1 0 0 +EDGE2 6553 6552 -0.88564 0.0348825 -0.0214867 1 0 1 1 0 0 +EDGE2 6554 6553 -0.93633 -0.0806563 0.0182745 1 0 1 1 0 0 +EDGE2 6555 6554 -0.979935 0.0703755 -0.000442551 1 0 1 1 0 0 +EDGE2 6556 6555 -1.00988 0.0224117 -1.56585 1 0 1 1 0 0 +EDGE2 6557 6556 -1.01354 -0.0249994 -0.0209873 1 0 1 1 0 0 +EDGE2 6558 6557 -1.02041 -0.0160219 0.00011529 1 0 1 1 0 0 +EDGE2 6559 6558 -1.07953 -0.0626671 -0.000478568 1 0 1 1 0 0 +EDGE2 6560 6559 -1.02251 0.0356972 -0.0270716 1 0 1 1 0 0 +EDGE2 6561 6560 -1.05155 -0.0465229 -1.59062 1 0 1 1 0 0 +EDGE2 6562 6561 -0.986253 -0.0750576 0.00238726 1 0 1 1 0 0 +EDGE2 6563 6562 -0.931721 -0.0864482 -0.00551096 1 0 1 1 0 0 +EDGE2 6564 6545 1.01314 0.0500829 -3.09671 1 0 1 1 0 0 +EDGE2 6564 6563 -1.02782 -0.0669074 -0.0175221 1 0 1 1 0 0 +EDGE2 6565 6545 0.0509271 -0.027728 -3.15339 1 0 1 1 0 0 +EDGE2 6565 6546 -0.0544505 1.01132 1.58048 1 0 1 1 0 0 +EDGE2 6565 6544 1.02863 -0.0178658 -3.12783 1 0 1 1 0 0 +EDGE2 6565 6564 -0.959833 0.00764922 0.00403706 1 0 1 1 0 0 +EDGE2 6566 6545 -0.93035 -0.00337164 1.58151 1 0 1 1 0 0 +EDGE2 6566 6547 0.9576 0.00125288 -0.00497345 1 0 1 1 0 0 +EDGE2 6566 6546 0.0356184 -0.00688192 0.0151629 1 0 1 1 0 0 +EDGE2 6566 6565 -1.04413 0.0040907 -1.57778 1 0 1 1 0 0 +EDGE2 6567 6548 1.01454 0.0482063 0.0102512 1 0 1 1 0 0 +EDGE2 6567 6566 -1.02257 0.0211766 -0.00535061 1 0 1 1 0 0 +EDGE2 6567 6547 0.03707 0.0084498 0.0251187 1 0 1 1 0 0 +EDGE2 6567 6546 -1.00968 0.0286322 0.0247821 1 0 1 1 0 0 +EDGE2 6568 6549 0.957261 -0.0219817 -0.0113986 1 0 1 1 0 0 +EDGE2 6568 6548 -0.0444714 0.017665 0.0158978 1 0 1 1 0 0 +EDGE2 6568 6547 -1.00746 0.100071 -0.0130574 1 0 1 1 0 0 +EDGE2 6568 6567 -0.979215 0.0664599 0.013511 1 0 1 1 0 0 +EDGE2 6569 6550 1.04836 -0.0112824 0.00176623 1 0 1 1 0 0 +EDGE2 6569 6549 -0.0180551 -0.0218788 -1.24607e-05 1 0 1 1 0 0 +EDGE2 6569 6548 -0.911142 0.00144936 0.00756167 1 0 1 1 0 0 +EDGE2 6569 6568 -1.01292 -0.000324022 -0.00913599 1 0 1 1 0 0 +EDGE2 6570 6550 0.0220633 0.0318155 -0.0199068 1 0 1 1 0 0 +EDGE2 6570 6551 -0.0081112 0.984271 1.53247 1 0 1 1 0 0 +EDGE2 6570 6549 -0.999527 -0.0234459 -0.0373143 1 0 1 1 0 0 +EDGE2 6570 6569 -0.961533 0.00185616 0.0127886 1 0 1 1 0 0 +EDGE2 6571 6550 -1.04039 -0.0521991 -1.5291 1 0 1 1 0 0 +EDGE2 6571 6570 -1.05926 -0.0911648 -1.59291 1 0 1 1 0 0 +EDGE2 6571 6551 0.0491248 0.0607193 -0.00560591 1 0 1 1 0 0 +EDGE2 6571 6552 0.977977 -0.0290401 -0.0157585 1 0 1 1 0 0 +EDGE2 6572 6571 -1.01216 0.0800945 -0.0161749 1 0 1 1 0 0 +EDGE2 6572 6551 -1.01344 0.0264036 0.00429655 1 0 1 1 0 0 +EDGE2 6572 6552 -0.0648206 -0.0336731 -0.00538754 1 0 1 1 0 0 +EDGE2 6572 6553 0.915455 -0.0555201 -0.00544291 1 0 1 1 0 0 +EDGE2 6573 6554 0.999157 -0.0105637 0.0307762 1 0 1 1 0 0 +EDGE2 6573 6572 -0.948137 0.0015001 -0.0341185 1 0 1 1 0 0 +EDGE2 6573 6552 -1.04838 -0.0510051 0.036092 1 0 1 1 0 0 +EDGE2 6573 6553 -0.0135074 0.0328306 -0.00530985 1 0 1 1 0 0 +EDGE2 6574 6554 0.0220782 0.0307425 0.0189462 1 0 1 1 0 0 +EDGE2 6574 6553 -0.971982 -0.0151086 -0.00195431 1 0 1 1 0 0 +EDGE2 6574 6573 -0.969649 0.037785 -0.0139834 1 0 1 1 0 0 +EDGE2 6574 6555 1.05279 -0.0113278 -0.00848698 1 0 1 1 0 0 +EDGE2 6575 6554 -1.04444 0.0603389 0.0411724 1 0 1 1 0 0 +EDGE2 6575 6574 -0.970289 0.0308217 0.0432798 1 0 1 1 0 0 +EDGE2 6575 6555 -0.0781302 0.0809938 0.0238886 1 0 1 1 0 0 +EDGE2 6575 6556 0.0563774 1.05318 1.60737 1 0 1 1 0 0 +EDGE2 6576 6557 1.00799 -0.0298971 0.0351475 1 0 1 1 0 0 +EDGE2 6576 6555 -1.00918 -0.0984071 -1.58921 1 0 1 1 0 0 +EDGE2 6576 6575 -0.981564 0.0378344 -1.59161 1 0 1 1 0 0 +EDGE2 6576 6556 -0.127282 -0.0338008 -0.00884516 1 0 1 1 0 0 +EDGE2 6577 6557 -0.0358468 0.0232706 0.00312719 1 0 1 1 0 0 +EDGE2 6577 6556 -1.03111 -0.0674857 -0.0134105 1 0 1 1 0 0 +EDGE2 6577 6576 -0.987315 0.0311552 -0.00951154 1 0 1 1 0 0 +EDGE2 6577 6558 0.977302 0.0322736 -0.0107138 1 0 1 1 0 0 +EDGE2 6578 6557 -0.906823 -0.00293199 -0.00319549 1 0 1 1 0 0 +EDGE2 6578 6577 -0.973162 0.0433261 -0.0112695 1 0 1 1 0 0 +EDGE2 6578 6558 0.00119744 0.0292426 -0.0132273 1 0 1 1 0 0 +EDGE2 6578 6559 0.961224 -0.0447821 -0.0234196 1 0 1 1 0 0 +EDGE2 6579 6558 -0.96286 -0.0037175 0.0222982 1 0 1 1 0 0 +EDGE2 6579 6578 -0.917267 0.0404599 0.000153266 1 0 1 1 0 0 +EDGE2 6579 6559 -0.0266826 0.0158908 -0.0259036 1 0 1 1 0 0 +EDGE2 6579 6560 0.983994 -0.0742794 0.00522375 1 0 1 1 0 0 +EDGE2 6580 6579 -0.951196 -0.131975 0.0248327 1 0 1 1 0 0 +EDGE2 6580 6559 -0.981266 0.0726768 -0.00145825 1 0 1 1 0 0 +EDGE2 6580 6560 0.0419377 0.0245187 0.0233851 1 0 1 1 0 0 +EDGE2 6580 6561 0.033529 1.05087 1.55731 1 0 1 1 0 0 +EDGE2 6581 6562 0.919346 0.0248146 0.00807502 1 0 1 1 0 0 +EDGE2 6581 6560 -1.05726 -0.0604825 -1.57523 1 0 1 1 0 0 +EDGE2 6581 6561 -0.00606321 -0.0506104 -0.000616621 1 0 1 1 0 0 +EDGE2 6581 6580 -1.0439 0.0387642 -1.54761 1 0 1 1 0 0 +EDGE2 6582 6562 0.00171311 0.0171267 -0.00836722 1 0 1 1 0 0 +EDGE2 6582 6563 1.00436 0.0807755 -0.00845166 1 0 1 1 0 0 +EDGE2 6582 6561 -0.9323 -0.0554863 -0.00960151 1 0 1 1 0 0 +EDGE2 6582 6581 -1.0258 -0.0114532 -0.00679024 1 0 1 1 0 0 +EDGE2 6583 6562 -0.971936 -0.0690546 -0.0169729 1 0 1 1 0 0 +EDGE2 6583 6563 -0.0243883 -0.0696999 -0.0275858 1 0 1 1 0 0 +EDGE2 6583 6564 1.02976 -0.119834 -0.0431094 1 0 1 1 0 0 +EDGE2 6583 6582 -0.99427 0.0597421 -0.014474 1 0 1 1 0 0 +EDGE2 6584 6545 1.01492 -0.02271 -3.12463 1 0 1 1 0 0 +EDGE2 6584 6565 0.976112 0.061086 0.0227826 1 0 1 1 0 0 +EDGE2 6584 6563 -0.995759 -0.016074 0.00259962 1 0 1 1 0 0 +EDGE2 6584 6583 -0.984119 -0.0550455 0.00781259 1 0 1 1 0 0 +EDGE2 6584 6564 0.0236754 -0.0113518 0.00530793 1 0 1 1 0 0 +EDGE2 6585 6545 0.0088084 0.0795093 -3.16827 1 0 1 1 0 0 +EDGE2 6585 6566 -0.0311075 1.03414 1.55658 1 0 1 1 0 0 +EDGE2 6585 6546 -0.0278951 0.991727 1.57146 1 0 1 1 0 0 +EDGE2 6585 6544 1.05792 0.0610371 -3.17183 1 0 1 1 0 0 +EDGE2 6585 6565 0.0874322 0.0585635 -0.00463226 1 0 1 1 0 0 +EDGE2 6585 6584 -0.999225 0.0531246 -0.0288277 1 0 1 1 0 0 +EDGE2 6585 6564 -0.99226 0.0606292 -0.0242436 1 0 1 1 0 0 +EDGE2 6586 6545 -1.03349 -0.104725 1.58829 1 0 1 1 0 0 +EDGE2 6586 6566 -0.0404274 0.0552245 0.00351911 1 0 1 1 0 0 +EDGE2 6586 6547 0.983155 -0.046655 -0.0149918 1 0 1 1 0 0 +EDGE2 6586 6567 1.08075 -0.00336486 0.0169676 1 0 1 1 0 0 +EDGE2 6586 6585 -1.088 0.00342871 -1.58309 1 0 1 1 0 0 +EDGE2 6586 6546 -0.0522191 0.0679792 0.0209865 1 0 1 1 0 0 +EDGE2 6586 6565 -1.02833 -0.0471281 -1.57078 1 0 1 1 0 0 +EDGE2 6587 6548 0.995971 -0.0259772 -0.0110482 1 0 1 1 0 0 +EDGE2 6587 6568 0.986853 -0.0155258 0.0268433 1 0 1 1 0 0 +EDGE2 6587 6566 -1.00653 0.0231842 -0.0183666 1 0 1 1 0 0 +EDGE2 6587 6547 -0.0971772 -0.00566436 0.00432754 1 0 1 1 0 0 +EDGE2 6587 6567 0.0288757 -0.0140737 -0.0290888 1 0 1 1 0 0 +EDGE2 6587 6586 -1.01766 0.0203493 -0.0064118 1 0 1 1 0 0 +EDGE2 6587 6546 -0.940562 0.0012898 -0.00855487 1 0 1 1 0 0 +EDGE2 6588 6549 1.02282 0.0194218 0.0166563 1 0 1 1 0 0 +EDGE2 6588 6569 1.08431 0.0133818 0.0350939 1 0 1 1 0 0 +EDGE2 6588 6548 0.00853966 -0.0148996 0.0192457 1 0 1 1 0 0 +EDGE2 6588 6568 0.0789936 0.00150995 0.0396196 1 0 1 1 0 0 +EDGE2 6588 6547 -1.03719 0.0384421 0.0198479 1 0 1 1 0 0 +EDGE2 6588 6567 -0.961292 0.00195106 0.0156524 1 0 1 1 0 0 +EDGE2 6588 6587 -0.96074 -0.0611346 -0.0130109 1 0 1 1 0 0 +EDGE2 6589 6550 0.926371 0.0397117 -0.0207536 1 0 1 1 0 0 +EDGE2 6589 6570 0.974088 0.0358648 0.00788682 1 0 1 1 0 0 +EDGE2 6589 6549 -0.150025 -0.0407578 -0.0442043 1 0 1 1 0 0 +EDGE2 6589 6569 0.0508495 -0.00476656 -0.00302583 1 0 1 1 0 0 +EDGE2 6589 6548 -0.966472 0.0472483 0.0171398 1 0 1 1 0 0 +EDGE2 6589 6568 -0.986158 0.0215646 -0.00589508 1 0 1 1 0 0 +EDGE2 6589 6588 -0.97436 0.0163665 -0.0339936 1 0 1 1 0 0 +EDGE2 6590 6571 -0.000765013 1.03777 1.55531 1 0 1 1 0 0 +EDGE2 6590 6550 -0.0140388 -0.0964293 0.0258969 1 0 1 1 0 0 +EDGE2 6590 6570 -0.0460851 -0.0192802 0.0124364 1 0 1 1 0 0 +EDGE2 6590 6551 0.0301564 1.05712 1.55091 1 0 1 1 0 0 +EDGE2 6590 6549 -1.00755 -0.0209161 -0.00821053 1 0 1 1 0 0 +EDGE2 6590 6569 -1.0619 -0.0176796 -0.018091 1 0 1 1 0 0 +EDGE2 6590 6589 -1.05888 -0.0750174 -0.0412171 1 0 1 1 0 0 +EDGE2 6591 6550 -0.973328 0.0180909 1.5586 1 0 1 1 0 0 +EDGE2 6591 6590 -1.03247 -0.00106542 1.60613 1 0 1 1 0 0 +EDGE2 6591 6570 -1.03498 0.00628797 1.57384 1 0 1 1 0 0 +EDGE2 6592 6591 -0.972465 0.0479156 -0.0432633 1 0 1 1 0 0 +EDGE2 6593 6592 -1.00214 0.0144915 -0.0139048 1 0 1 1 0 0 +EDGE2 6594 6535 1.04088 0.0970332 -3.13502 1 0 1 1 0 0 +EDGE2 6594 6593 -0.967278 -0.00441965 -0.00575924 1 0 1 1 0 0 +EDGE2 6595 6535 -0.0253305 0.04292 -3.14063 1 0 1 1 0 0 +EDGE2 6595 6534 1.087 0.0655362 -3.1329 1 0 1 1 0 0 +EDGE2 6595 6536 0.0489449 -1.0108 -1.57302 1 0 1 1 0 0 +EDGE2 6595 6594 -1.03406 0.0592612 -0.00943936 1 0 1 1 0 0 +EDGE2 6596 6535 -1.10278 -0.0453553 1.60171 1 0 1 1 0 0 +EDGE2 6596 6595 -0.973836 -0.113681 -1.56009 1 0 1 1 0 0 +EDGE2 6597 6596 -0.99366 -0.0178803 -0.0194912 1 0 1 1 0 0 +EDGE2 6598 6597 -0.907312 0.0466274 -0.0129963 1 0 1 1 0 0 +EDGE2 6599 6598 -1.08457 0.00360315 -0.00374097 1 0 1 1 0 0 +EDGE2 6600 6599 -0.933642 0.0770799 -0.00720569 1 0 1 1 0 0 +EDGE2 6601 6600 -0.947559 0.0081954 1.57192 1 0 1 1 0 0 +EDGE2 6602 6601 -0.950578 -0.0576719 0.015422 1 0 1 1 0 0 +EDGE2 6603 6602 -0.989556 0.05563 0.0076224 1 0 1 1 0 0 +EDGE2 6604 6603 -0.96889 0.0109389 -0.021986 1 0 1 1 0 0 +EDGE2 6605 6604 -1.05593 0.0592428 0.0251174 1 0 1 1 0 0 +EDGE2 6606 6605 -0.924653 -0.0100723 -1.59263 1 0 1 1 0 0 +EDGE2 6607 6606 -1.06833 0.00875984 -0.028929 1 0 1 1 0 0 +EDGE2 6608 6607 -1.07119 -0.0188534 -0.0116049 1 0 1 1 0 0 +EDGE2 6609 6608 -1.01072 0.0674371 0.00565652 1 0 1 1 0 0 +EDGE2 6610 6609 -1.07683 -0.00364314 0.0138469 1 0 1 1 0 0 +EDGE2 6611 6610 -1.03558 0.010353 -1.57281 1 0 1 1 0 0 +EDGE2 6612 6611 -1.03225 0.0823569 0.0108139 1 0 1 1 0 0 +EDGE2 6613 6612 -0.97938 -0.0502496 0.0299294 1 0 1 1 0 0 +EDGE2 6614 6613 -1.00876 0.021502 0.0121987 1 0 1 1 0 0 +EDGE2 6615 6614 -1.01676 -0.0441957 -0.0150352 1 0 1 1 0 0 +EDGE2 6616 6615 -0.984523 0.113123 -1.57605 1 0 1 1 0 0 +EDGE2 6617 6616 -1.05026 -0.0966355 -0.047681 1 0 1 1 0 0 +EDGE2 6618 6617 -0.969816 0.0695585 -0.0103821 1 0 1 1 0 0 +EDGE2 6619 6618 -0.906596 0.056958 0.0208139 1 0 1 1 0 0 +EDGE2 6619 6600 0.918018 -0.0254604 -3.12862 1 0 1 1 0 0 +EDGE2 6620 6619 -0.94743 0.0436417 0.0221973 1 0 1 1 0 0 +EDGE2 6620 6601 0.00357069 1.01364 1.56732 1 0 1 1 0 0 +EDGE2 6620 6600 -0.0588528 -0.0373115 -3.12989 1 0 1 1 0 0 +EDGE2 6620 6599 0.943709 0.0115559 -3.17461 1 0 1 1 0 0 +EDGE2 6621 6600 -1.0145 -0.0506938 -1.56791 1 0 1 1 0 0 +EDGE2 6621 6620 -0.98071 0.0049138 1.56926 1 0 1 1 0 0 +EDGE2 6622 6621 -1.02969 -0.00566899 -0.00696818 1 0 1 1 0 0 +EDGE2 6623 6622 -0.985533 0.0159731 0.00446203 1 0 1 1 0 0 +EDGE2 6624 6623 -1.04402 -0.0503096 0.017675 1 0 1 1 0 0 +EDGE2 6625 6624 -0.910242 -0.0797237 -0.0088239 1 0 1 1 0 0 +EDGE2 6626 6625 -0.940047 0.0883563 -1.54024 1 0 1 1 0 0 +EDGE2 6627 6626 -0.996419 -0.0355729 0.0173275 1 0 1 1 0 0 +EDGE2 6628 6627 -1.04541 -0.019244 0.0192914 1 0 1 1 0 0 +EDGE2 6629 6628 -0.981241 0.0168214 0.0025986 1 0 1 1 0 0 +EDGE2 6629 6550 0.978845 0.0573501 -3.14698 1 0 1 1 0 0 +EDGE2 6629 6590 0.967512 -0.0218039 -3.14417 1 0 1 1 0 0 +EDGE2 6629 6570 0.967776 -0.0314518 -3.16607 1 0 1 1 0 0 +EDGE2 6630 6571 -0.0780404 -0.955234 -1.59579 1 0 1 1 0 0 +EDGE2 6630 6550 0.00737668 -0.00917816 -3.15154 1 0 1 1 0 0 +EDGE2 6630 6629 -0.924486 -0.0397665 -0.0227528 1 0 1 1 0 0 +EDGE2 6630 6591 0.0492961 1.0301 1.59846 1 0 1 1 0 0 +EDGE2 6630 6590 0.000894318 0.0267566 -3.14119 1 0 1 1 0 0 +EDGE2 6630 6570 0.0635925 -0.0316774 -3.1484 1 0 1 1 0 0 +EDGE2 6630 6551 0.0383501 -0.942751 -1.5667 1 0 1 1 0 0 +EDGE2 6630 6549 1.0814 -0.0299761 -3.11957 1 0 1 1 0 0 +EDGE2 6630 6569 0.922531 -0.0948638 -3.18103 1 0 1 1 0 0 +EDGE2 6630 6589 1.00697 0.00598512 -3.12861 1 0 1 1 0 0 +EDGE2 6631 6592 0.980305 -0.100507 -0.00788868 1 0 1 1 0 0 +EDGE2 6631 6550 -1.02131 -0.0590186 1.57339 1 0 1 1 0 0 +EDGE2 6631 6591 0.011195 -0.0300841 0.0163477 1 0 1 1 0 0 +EDGE2 6631 6590 -1.00141 -0.0926367 1.58513 1 0 1 1 0 0 +EDGE2 6631 6630 -1.03804 0.00863474 -1.58626 1 0 1 1 0 0 +EDGE2 6631 6570 -1.00874 0.10468 1.53546 1 0 1 1 0 0 +EDGE2 6632 6631 -1.04776 -0.00413801 0.0260473 1 0 1 1 0 0 +EDGE2 6632 6593 1.05811 0.0104006 0.0100761 1 0 1 1 0 0 +EDGE2 6632 6592 -0.00931845 -0.0256584 0.00424446 1 0 1 1 0 0 +EDGE2 6632 6591 -1.05135 0.0274697 -0.0167428 1 0 1 1 0 0 +EDGE2 6633 6593 0.0586025 -0.107287 -0.00111661 1 0 1 1 0 0 +EDGE2 6633 6594 0.945347 0.0467719 -0.0112683 1 0 1 1 0 0 +EDGE2 6633 6592 -0.998111 -0.00521006 0.0097815 1 0 1 1 0 0 +EDGE2 6633 6632 -0.910366 0.0191962 0.0137671 1 0 1 1 0 0 +EDGE2 6634 6535 0.922409 -0.0674123 -3.13758 1 0 1 1 0 0 +EDGE2 6634 6595 1.00665 0.0180753 -0.0155796 1 0 1 1 0 0 +EDGE2 6634 6593 -1.07533 0.0701649 0.0360179 1 0 1 1 0 0 +EDGE2 6634 6594 -0.0466921 -0.0645149 -0.0402564 1 0 1 1 0 0 +EDGE2 6634 6633 -1.03334 -0.0746025 -0.0176037 1 0 1 1 0 0 +EDGE2 6635 6535 -0.016095 -0.0699329 -3.12655 1 0 1 1 0 0 +EDGE2 6635 6534 1.04479 -0.0523531 -3.16446 1 0 1 1 0 0 +EDGE2 6635 6596 -0.0811747 0.969815 1.53452 1 0 1 1 0 0 +EDGE2 6635 6595 -0.0123615 0.0902266 0.0287313 1 0 1 1 0 0 +EDGE2 6635 6536 0.00984833 -1.06843 -1.58247 1 0 1 1 0 0 +EDGE2 6635 6594 -0.980129 0.0489598 -0.0260127 1 0 1 1 0 0 +EDGE2 6635 6634 -1.07431 -0.00681136 0.0251898 1 0 1 1 0 0 +EDGE2 6636 6535 -0.976099 -0.076689 1.58611 1 0 1 1 0 0 +EDGE2 6636 6597 1.0937 0.0294498 -0.00813483 1 0 1 1 0 0 +EDGE2 6636 6596 0.0194729 -0.0879517 0.026263 1 0 1 1 0 0 +EDGE2 6636 6635 -1.00217 -0.00981469 -1.57187 1 0 1 1 0 0 +EDGE2 6636 6595 -0.957581 -0.0596988 -1.57932 1 0 1 1 0 0 +EDGE2 6637 6636 -1.01548 0.0321426 0.00808654 1 0 1 1 0 0 +EDGE2 6637 6598 1.06251 0.0211402 0.013245 1 0 1 1 0 0 +EDGE2 6637 6597 -0.0212588 -0.0148345 -0.0042155 1 0 1 1 0 0 +EDGE2 6637 6596 -1.1021 -0.0109273 0.0018782 1 0 1 1 0 0 +EDGE2 6638 6599 0.960506 -0.0152155 -0.00652886 1 0 1 1 0 0 +EDGE2 6638 6598 -0.0780696 -0.068046 -0.00404642 1 0 1 1 0 0 +EDGE2 6638 6597 -0.980315 0.130521 -0.0121661 1 0 1 1 0 0 +EDGE2 6638 6637 -0.974007 0.0335369 -0.0164299 1 0 1 1 0 0 +EDGE2 6639 6600 0.974902 0.0212011 0.0395035 1 0 1 1 0 0 +EDGE2 6639 6620 1.04313 -0.00986147 -3.11694 1 0 1 1 0 0 +EDGE2 6639 6599 0.032134 0.0472168 -0.0201606 1 0 1 1 0 0 +EDGE2 6639 6598 -1.07143 -0.0146729 0.0111273 1 0 1 1 0 0 +EDGE2 6639 6638 -0.988276 -0.0178465 -0.000676091 1 0 1 1 0 0 +EDGE2 6640 6619 0.899986 -0.00711284 -3.14644 1 0 1 1 0 0 +EDGE2 6640 6601 0.00992015 -1.01416 -1.56741 1 0 1 1 0 0 +EDGE2 6640 6600 -0.0267667 0.0256143 -0.0333457 1 0 1 1 0 0 +EDGE2 6640 6620 0.00556844 -0.00200222 -3.17411 1 0 1 1 0 0 +EDGE2 6640 6621 -0.0269145 1.02258 1.55459 1 0 1 1 0 0 +EDGE2 6640 6639 -1.04137 0.0213301 -0.0118833 1 0 1 1 0 0 +EDGE2 6640 6599 -1.00023 -0.0516739 -0.0261146 1 0 1 1 0 0 +EDGE2 6641 6600 -0.915417 0.038048 -1.59223 1 0 1 1 0 0 +EDGE2 6641 6620 -0.974877 -0.040698 1.57669 1 0 1 1 0 0 +EDGE2 6641 6640 -0.917026 0.0181139 -1.54629 1 0 1 1 0 0 +EDGE2 6641 6621 0.0347618 -0.026543 -0.00460718 1 0 1 1 0 0 +EDGE2 6641 6622 0.986746 -0.00621384 0.0162456 1 0 1 1 0 0 +EDGE2 6642 6621 -0.926389 -0.071556 -0.0504693 1 0 1 1 0 0 +EDGE2 6642 6641 -1.05446 0.00481811 -0.0203211 1 0 1 1 0 0 +EDGE2 6642 6622 -0.0176407 0.0930319 -0.00476136 1 0 1 1 0 0 +EDGE2 6642 6623 0.947765 -0.0406063 0.00734838 1 0 1 1 0 0 +EDGE2 6643 6642 -1.06453 -0.0279573 -0.0164084 1 0 1 1 0 0 +EDGE2 6643 6622 -1.00752 0.00529588 -0.0201979 1 0 1 1 0 0 +EDGE2 6643 6624 1.05457 -0.097211 0.00352968 1 0 1 1 0 0 +EDGE2 6643 6623 0.0146418 0.0662273 0.00411689 1 0 1 1 0 0 +EDGE2 6644 6643 -0.975644 -0.110736 0.0222569 1 0 1 1 0 0 +EDGE2 6644 6624 0.0715151 0.0227838 -0.0265524 1 0 1 1 0 0 +EDGE2 6644 6623 -1.09042 0.0050962 0.00116734 1 0 1 1 0 0 +EDGE2 6644 6625 1.02572 0.0215507 0.0189869 1 0 1 1 0 0 +EDGE2 6645 6624 -1.05362 0.0123778 -0.0308371 1 0 1 1 0 0 +EDGE2 6645 6644 -1.04425 -0.0328692 -0.0127904 1 0 1 1 0 0 +EDGE2 6645 6625 -0.0300435 -0.00394115 -0.0011499 1 0 1 1 0 0 +EDGE2 6645 6626 -0.0214633 1.03061 1.59833 1 0 1 1 0 0 +EDGE2 6646 6645 -1.04358 -0.0173067 -1.57493 1 0 1 1 0 0 +EDGE2 6646 6625 -0.993095 0.0210453 -1.55817 1 0 1 1 0 0 +EDGE2 6646 6626 -0.0862392 -0.040553 -0.0140593 1 0 1 1 0 0 +EDGE2 6646 6627 0.99172 -0.043792 -8.43026e-05 1 0 1 1 0 0 +EDGE2 6647 6626 -0.988188 -0.0169995 0.0209608 1 0 1 1 0 0 +EDGE2 6647 6646 -1.01694 -0.0736932 -0.00107977 1 0 1 1 0 0 +EDGE2 6647 6627 -0.0226258 -0.0742432 0.0170677 1 0 1 1 0 0 +EDGE2 6647 6628 1.01678 -0.030036 0.0264391 1 0 1 1 0 0 +EDGE2 6648 6627 -1.00316 0.025955 0.0318728 1 0 1 1 0 0 +EDGE2 6648 6647 -1.02869 0.0525164 0.00640451 1 0 1 1 0 0 +EDGE2 6648 6628 0.133965 -0.0675038 -0.00124343 1 0 1 1 0 0 +EDGE2 6648 6629 0.917721 0.0334392 -0.0565769 1 0 1 1 0 0 +EDGE2 6649 6628 -1.02092 -0.066508 -0.00802884 1 0 1 1 0 0 +EDGE2 6649 6648 -0.98447 -0.0490488 -0.0130645 1 0 1 1 0 0 +EDGE2 6649 6550 0.991513 -0.00754119 -3.14354 1 0 1 1 0 0 +EDGE2 6649 6629 0.00703106 -0.0395142 0.00200093 1 0 1 1 0 0 +EDGE2 6649 6590 0.906461 0.0664798 -3.14447 1 0 1 1 0 0 +EDGE2 6649 6630 1.04527 0.128903 0.0126512 1 0 1 1 0 0 +EDGE2 6649 6570 0.941086 0.0891783 -3.17119 1 0 1 1 0 0 +EDGE2 6650 6631 -0.0468885 1.06671 1.56806 1 0 1 1 0 0 +EDGE2 6650 6571 0.0145085 -1.021 -1.59602 1 0 1 1 0 0 +EDGE2 6650 6550 -0.0183812 -0.00788028 -3.1736 1 0 1 1 0 0 +EDGE2 6650 6629 -1.00943 0.0108335 -0.0159432 1 0 1 1 0 0 +EDGE2 6650 6649 -1.03219 0.0283491 0.00318209 1 0 1 1 0 0 +EDGE2 6650 6591 0.101691 1.05077 1.58778 1 0 1 1 0 0 +EDGE2 6650 6590 -0.0595533 -0.0906367 -3.1628 1 0 1 1 0 0 +EDGE2 6650 6630 0.0460979 -0.0657108 -0.0214564 1 0 1 1 0 0 +EDGE2 6650 6570 -0.0670233 0.045455 -3.14973 1 0 1 1 0 0 +EDGE2 6650 6551 0.0488709 -1.05477 -1.56293 1 0 1 1 0 0 +EDGE2 6650 6549 1.0373 0.0375923 -3.12563 1 0 1 1 0 0 +EDGE2 6650 6569 1.01038 -0.111816 -3.13867 1 0 1 1 0 0 +EDGE2 6650 6589 0.992982 0.0115855 -3.12832 1 0 1 1 0 0 +EDGE2 6651 6631 0.0155345 -0.00956115 -0.00687832 1 0 1 1 0 0 +EDGE2 6651 6592 1.00956 0.0453997 0.0289024 1 0 1 1 0 0 +EDGE2 6651 6632 0.988928 0.0224848 -0.0231779 1 0 1 1 0 0 +EDGE2 6651 6550 -1.01697 -0.0234783 1.62921 1 0 1 1 0 0 +EDGE2 6651 6591 -0.00607035 -0.0122487 -0.000438058 1 0 1 1 0 0 +EDGE2 6651 6590 -1.10186 -0.028142 1.52774 1 0 1 1 0 0 +EDGE2 6651 6630 -0.96948 -0.0449447 -1.57982 1 0 1 1 0 0 +EDGE2 6651 6650 -1.0236 0.0107333 -1.59891 1 0 1 1 0 0 +EDGE2 6651 6570 -1.04545 -0.0136439 1.53888 1 0 1 1 0 0 +EDGE2 6652 6631 -0.960851 0.0513165 -0.0491939 1 0 1 1 0 0 +EDGE2 6652 6593 0.974054 0.0656672 0.0144073 1 0 1 1 0 0 +EDGE2 6652 6633 1.03607 0.0376673 -0.0234665 1 0 1 1 0 0 +EDGE2 6652 6592 -0.0438335 0.00175296 0.0224135 1 0 1 1 0 0 +EDGE2 6652 6632 0.0431116 -0.00215281 -0.0467406 1 0 1 1 0 0 +EDGE2 6652 6651 -0.993186 -0.00532766 -0.0035589 1 0 1 1 0 0 +EDGE2 6652 6591 -0.938631 -0.00177786 0.014697 1 0 1 1 0 0 +EDGE2 6653 6593 -0.0260913 0.0480731 -0.0116727 1 0 1 1 0 0 +EDGE2 6653 6594 1.01496 -0.0369012 0.0158227 1 0 1 1 0 0 +EDGE2 6653 6634 0.945615 -0.0251674 0.0126191 1 0 1 1 0 0 +EDGE2 6653 6633 -0.0608497 -0.0134266 -0.00643937 1 0 1 1 0 0 +EDGE2 6653 6592 -0.925735 0.0595684 -0.00387705 1 0 1 1 0 0 +EDGE2 6653 6632 -0.907134 0.0916693 0.0147001 1 0 1 1 0 0 +EDGE2 6653 6652 -1.02005 0.0735843 0.0318886 1 0 1 1 0 0 +EDGE2 6654 6535 0.993079 -0.00410881 -3.1405 1 0 1 1 0 0 +EDGE2 6654 6635 1.06097 0.0412517 0.0391796 1 0 1 1 0 0 +EDGE2 6654 6595 0.940687 0.00269835 0.00789619 1 0 1 1 0 0 +EDGE2 6654 6593 -0.957691 0.00760842 0.0119923 1 0 1 1 0 0 +EDGE2 6654 6653 -0.945961 0.0344367 0.00960489 1 0 1 1 0 0 +EDGE2 6654 6594 0.0128763 0.0198383 0.0158374 1 0 1 1 0 0 +EDGE2 6654 6634 -0.0120489 -0.0760712 -0.00501185 1 0 1 1 0 0 +EDGE2 6654 6633 -1.00077 0.0323712 0.020653 1 0 1 1 0 0 +EDGE2 6655 6535 0.0316515 -0.0465498 -3.11856 1 0 1 1 0 0 +EDGE2 6655 6636 -0.017778 0.991019 1.59357 1 0 1 1 0 0 +EDGE2 6655 6534 0.951413 0.0236679 -3.12692 1 0 1 1 0 0 +EDGE2 6655 6596 0.0541815 1.03819 1.61052 1 0 1 1 0 0 +EDGE2 6655 6635 -0.0327251 0.0241345 0.0221311 1 0 1 1 0 0 +EDGE2 6655 6595 -0.0594327 0.00483012 0.00527062 1 0 1 1 0 0 +EDGE2 6655 6654 -1.01663 0.0212064 -0.00494953 1 0 1 1 0 0 +EDGE2 6655 6536 0.0364945 -0.971714 -1.57199 1 0 1 1 0 0 +EDGE2 6655 6594 -0.921112 0.0573418 -0.0142067 1 0 1 1 0 0 +EDGE2 6655 6634 -0.88369 -0.0112562 -0.023032 1 0 1 1 0 0 +EDGE2 6656 6535 -1.11706 0.00736301 -1.57352 1 0 1 1 0 0 +EDGE2 6656 6635 -1.05294 0.0855192 1.55146 1 0 1 1 0 0 +EDGE2 6656 6655 -0.969344 0.0445106 1.57879 1 0 1 1 0 0 +EDGE2 6656 6595 -0.977845 -0.0474626 1.5856 1 0 1 1 0 0 +EDGE2 6656 6536 -0.0756198 -0.0975523 0.0210961 1 0 1 1 0 0 +EDGE2 6656 6537 1.01973 0.0319187 -0.00685805 1 0 1 1 0 0 +EDGE2 6657 6536 -1.00776 -0.0406206 -0.00825625 1 0 1 1 0 0 +EDGE2 6657 6656 -1.01786 -0.00237839 0.00411987 1 0 1 1 0 0 +EDGE2 6657 6537 -0.0215597 0.0967995 -0.0198016 1 0 1 1 0 0 +EDGE2 6657 6538 0.877883 -0.0225896 0.00424602 1 0 1 1 0 0 +EDGE2 6658 6657 -0.957706 -0.0384737 0.031923 1 0 1 1 0 0 +EDGE2 6658 6537 -0.996126 -0.00472398 0.00770729 1 0 1 1 0 0 +EDGE2 6658 6539 0.957792 0.00667415 -0.0226576 1 0 1 1 0 0 +EDGE2 6658 6538 -0.0598504 -0.0898373 0.0239762 1 0 1 1 0 0 +EDGE2 6659 6658 -0.997578 -0.0426802 -0.0164318 1 0 1 1 0 0 +EDGE2 6659 6539 0.0351033 0.0345803 0.0110266 1 0 1 1 0 0 +EDGE2 6659 6538 -0.997085 -0.0165867 0.000787994 1 0 1 1 0 0 +EDGE2 6659 6540 1.00252 -0.0328636 0.0265489 1 0 1 1 0 0 +EDGE2 6660 6539 -1.04261 -0.0268927 -0.0180882 1 0 1 1 0 0 +EDGE2 6660 6659 -1.0672 0.0615721 -0.00596394 1 0 1 1 0 0 +EDGE2 6660 6541 -0.0222584 -0.98995 -1.56354 1 0 1 1 0 0 +EDGE2 6660 6540 -0.0313683 0.0141046 -0.0231824 1 0 1 1 0 0 +EDGE2 6661 6660 -1.04406 -0.022857 -1.56174 1 0 1 1 0 0 +EDGE2 6661 6540 -1.01053 0.0477141 -1.58581 1 0 1 1 0 0 +EDGE2 6662 6661 -1.1149 0.088455 -0.0231548 1 0 1 1 0 0 +EDGE2 6663 6662 -1.03249 0.0522187 -0.000616116 1 0 1 1 0 0 +EDGE2 6664 6525 1.01562 -0.0154202 -3.13545 1 0 1 1 0 0 +EDGE2 6664 6663 -0.960444 -0.0592867 0.00819708 1 0 1 1 0 0 +EDGE2 6665 6526 0.0139684 0.971375 1.57345 1 0 1 1 0 0 +EDGE2 6665 6524 0.98608 -0.00711419 -3.12444 1 0 1 1 0 0 +EDGE2 6665 6525 -0.110121 -0.00335072 -3.1716 1 0 1 1 0 0 +EDGE2 6665 6664 -1.00608 0.0532793 0.0165848 1 0 1 1 0 0 +EDGE2 6666 6527 0.882524 -0.0276056 -0.0203211 1 0 1 1 0 0 +EDGE2 6666 6526 0.00143192 -0.0294845 -0.0156515 1 0 1 1 0 0 +EDGE2 6666 6525 -1.00221 0.0262414 1.60661 1 0 1 1 0 0 +EDGE2 6666 6665 -1.00658 -0.0848684 -1.5715 1 0 1 1 0 0 +EDGE2 6667 6528 0.89986 0.102594 -0.0619839 1 0 1 1 0 0 +EDGE2 6667 6666 -0.950455 0.00287799 -0.0225472 1 0 1 1 0 0 +EDGE2 6667 6527 0.00483471 0.0283992 -0.0309321 1 0 1 1 0 0 +EDGE2 6667 6526 -1.00123 -0.0222031 -0.0234553 1 0 1 1 0 0 +EDGE2 6668 6529 1.03234 -0.0519215 -0.00327863 1 0 1 1 0 0 +EDGE2 6668 6667 -0.980772 -0.0137036 -0.0124044 1 0 1 1 0 0 +EDGE2 6668 6528 -0.0596689 -0.000672338 -0.0318773 1 0 1 1 0 0 +EDGE2 6668 6527 -1.00228 -0.0151394 -0.0229544 1 0 1 1 0 0 +EDGE2 6669 6529 0.030681 0.106965 0.00170818 1 0 1 1 0 0 +EDGE2 6669 6530 1.00713 -0.0109459 0.0254267 1 0 1 1 0 0 +EDGE2 6669 6528 -0.914898 0.0420547 0.0184613 1 0 1 1 0 0 +EDGE2 6669 6668 -0.96519 -0.00801216 -0.0502577 1 0 1 1 0 0 +EDGE2 6670 6529 -0.925398 -0.00818008 -0.00189121 1 0 1 1 0 0 +EDGE2 6670 6669 -0.995097 -0.0192149 -0.00905692 1 0 1 1 0 0 +EDGE2 6670 6530 0.0926632 0.0991458 0.00992262 1 0 1 1 0 0 +EDGE2 6670 6531 0.0471445 0.947489 1.55703 1 0 1 1 0 0 +EDGE2 6671 6530 -0.986423 0.0835033 -1.55077 1 0 1 1 0 0 +EDGE2 6671 6670 -0.972099 -0.0180996 -1.5965 1 0 1 1 0 0 +EDGE2 6671 6531 -0.0406669 -0.026958 -0.0130543 1 0 1 1 0 0 +EDGE2 6671 6532 1.04693 -0.0806634 -0.00999368 1 0 1 1 0 0 +EDGE2 6672 6531 -0.992785 -0.0591209 -4.81702e-05 1 0 1 1 0 0 +EDGE2 6672 6671 -0.972976 0.047665 0.0039614 1 0 1 1 0 0 +EDGE2 6672 6532 -0.0327672 -0.0249713 -0.0343947 1 0 1 1 0 0 +EDGE2 6672 6533 1.06301 0.0534394 -0.00309145 1 0 1 1 0 0 +EDGE2 6673 6672 -1.03086 -0.0245329 -0.0270202 1 0 1 1 0 0 +EDGE2 6673 6532 -0.96043 0.0390682 -0.00263988 1 0 1 1 0 0 +EDGE2 6673 6533 -0.0427404 0.0252925 -0.00494374 1 0 1 1 0 0 +EDGE2 6673 6534 0.976371 0.0584413 0.00945253 1 0 1 1 0 0 +EDGE2 6674 6535 0.987852 0.0022803 -0.000411492 1 0 1 1 0 0 +EDGE2 6674 6673 -1.01513 0.00170503 -0.00737735 1 0 1 1 0 0 +EDGE2 6674 6533 -1.02823 -0.0371842 0.0318998 1 0 1 1 0 0 +EDGE2 6674 6534 0.0608405 -0.0988646 0.00364419 1 0 1 1 0 0 +EDGE2 6674 6635 1.05922 -0.0122011 -3.13739 1 0 1 1 0 0 +EDGE2 6674 6655 0.99951 -0.0200148 -3.14233 1 0 1 1 0 0 +EDGE2 6674 6595 1.02845 -0.000744979 -3.14974 1 0 1 1 0 0 +EDGE2 6675 6535 -0.000845077 -0.0502816 -0.019543 1 0 1 1 0 0 +EDGE2 6675 6636 0.0926551 -1.07433 -1.5737 1 0 1 1 0 0 +EDGE2 6675 6534 -0.948426 0.0158898 -0.0132447 1 0 1 1 0 0 +EDGE2 6675 6596 -0.00416862 -1.0446 -1.55534 1 0 1 1 0 0 +EDGE2 6675 6674 -1.06343 0.0187668 -0.00395432 1 0 1 1 0 0 +EDGE2 6675 6635 0.0817647 0.00146117 -3.19716 1 0 1 1 0 0 +EDGE2 6675 6655 -0.0591612 -0.0258204 -3.15884 1 0 1 1 0 0 +EDGE2 6675 6595 0.133962 -0.0848205 -3.14394 1 0 1 1 0 0 +EDGE2 6675 6654 0.908963 0.105718 -3.12832 1 0 1 1 0 0 +EDGE2 6675 6536 0.0678927 1.04867 1.60722 1 0 1 1 0 0 +EDGE2 6675 6656 -0.0431336 1.04776 1.57624 1 0 1 1 0 0 +EDGE2 6675 6594 1.0186 0.00320009 -3.14553 1 0 1 1 0 0 +EDGE2 6675 6634 0.997842 -0.033024 -3.15539 1 0 1 1 0 0 +EDGE2 6676 6535 -1.01095 -0.0404402 1.5817 1 0 1 1 0 0 +EDGE2 6676 6636 -0.0250491 -0.0328067 -0.0506481 1 0 1 1 0 0 +EDGE2 6676 6597 1.02148 -0.0289353 -0.0304612 1 0 1 1 0 0 +EDGE2 6676 6637 0.97304 0.0321491 -0.035161 1 0 1 1 0 0 +EDGE2 6676 6675 -1.01793 -0.020203 1.53365 1 0 1 1 0 0 +EDGE2 6676 6596 0.000300893 0.00804072 -0.0232178 1 0 1 1 0 0 +EDGE2 6676 6635 -0.884582 0.0102212 -1.55368 1 0 1 1 0 0 +EDGE2 6676 6655 -0.96622 0.0922364 -1.58498 1 0 1 1 0 0 +EDGE2 6676 6595 -0.95959 -0.0548006 -1.58225 1 0 1 1 0 0 +EDGE2 6677 6636 -1.00024 0.130425 0.00069498 1 0 1 1 0 0 +EDGE2 6677 6598 1.0111 -0.0283735 -0.0125745 1 0 1 1 0 0 +EDGE2 6677 6638 0.958815 0.031502 -0.0267898 1 0 1 1 0 0 +EDGE2 6677 6597 0.0138103 -0.00070952 0.00179242 1 0 1 1 0 0 +EDGE2 6677 6637 0.0206614 -0.0673232 0.0147165 1 0 1 1 0 0 +EDGE2 6677 6676 -1.10287 -0.0668214 0.00589571 1 0 1 1 0 0 +EDGE2 6677 6596 -0.931598 -0.015584 -0.0161255 1 0 1 1 0 0 +EDGE2 6678 6677 -0.96902 -0.041381 -0.00552908 1 0 1 1 0 0 +EDGE2 6678 6639 1.05551 0.0117386 -0.0157955 1 0 1 1 0 0 +EDGE2 6678 6599 1.0332 0.0194188 -0.0219183 1 0 1 1 0 0 +EDGE2 6678 6598 -0.0452131 -0.0711266 0.0015502 1 0 1 1 0 0 +EDGE2 6678 6638 0.0465618 -0.069051 0.012888 1 0 1 1 0 0 +EDGE2 6678 6597 -1.0289 0.0630792 -0.000945068 1 0 1 1 0 0 +EDGE2 6678 6637 -0.995235 0.0300157 -0.00505784 1 0 1 1 0 0 +EDGE2 6679 6600 0.98051 0.0247647 0.00178606 1 0 1 1 0 0 +EDGE2 6679 6620 0.909418 -0.00990768 -3.13637 1 0 1 1 0 0 +EDGE2 6679 6640 0.940766 0.00265377 -0.00520943 1 0 1 1 0 0 +EDGE2 6679 6639 -0.0299491 -0.0485188 0.0190759 1 0 1 1 0 0 +EDGE2 6679 6599 -0.0145439 -0.0359097 0.029327 1 0 1 1 0 0 +EDGE2 6679 6598 -1.04419 -0.0717614 -0.00968958 1 0 1 1 0 0 +EDGE2 6679 6638 -0.943385 0.0729391 0.00684357 1 0 1 1 0 0 +EDGE2 6679 6678 -0.984507 0.0501838 -0.0114971 1 0 1 1 0 0 +EDGE2 6680 6619 1.02179 0.0567919 -3.1375 1 0 1 1 0 0 +EDGE2 6680 6601 -0.0909282 -0.987394 -1.56899 1 0 1 1 0 0 +EDGE2 6680 6600 -0.0182977 0.0207944 -0.00365422 1 0 1 1 0 0 +EDGE2 6680 6620 -0.0281657 -0.0794652 -3.20512 1 0 1 1 0 0 +EDGE2 6680 6640 -0.0126129 0.0307395 -0.00815112 1 0 1 1 0 0 +EDGE2 6680 6621 0.0526816 0.956118 1.56392 1 0 1 1 0 0 +EDGE2 6680 6641 0.0253878 1.00754 1.56889 1 0 1 1 0 0 +EDGE2 6680 6639 -0.926938 0.00892926 0.019782 1 0 1 1 0 0 +EDGE2 6680 6679 -0.996632 -0.00849558 -0.0122099 1 0 1 1 0 0 +EDGE2 6680 6599 -0.983804 0.0128721 0.00658694 1 0 1 1 0 0 +EDGE2 6681 6680 -1.0367 -0.0046709 -1.56568 1 0 1 1 0 0 +EDGE2 6681 6600 -0.975727 -0.0423837 -1.54234 1 0 1 1 0 0 +EDGE2 6681 6620 -1.00124 0.0513827 1.55719 1 0 1 1 0 0 +EDGE2 6681 6640 -1.10454 0.127116 -1.58017 1 0 1 1 0 0 +EDGE2 6681 6642 0.924387 -0.0891103 0.0112549 1 0 1 1 0 0 +EDGE2 6681 6621 -0.0526482 0.0238324 -0.00169233 1 0 1 1 0 0 +EDGE2 6681 6641 -0.00955494 -0.0497574 -0.0245423 1 0 1 1 0 0 +EDGE2 6681 6622 1.04223 0.0890111 -0.0363438 1 0 1 1 0 0 +EDGE2 6682 6643 0.933006 0.0222862 0.0222254 1 0 1 1 0 0 +EDGE2 6682 6681 -1.07814 0.011458 0.0312368 1 0 1 1 0 0 +EDGE2 6682 6642 -0.0425306 -0.00310774 -0.0102892 1 0 1 1 0 0 +EDGE2 6682 6621 -1.01036 -0.0674759 -0.0379549 1 0 1 1 0 0 +EDGE2 6682 6641 -0.945467 0.0314326 -0.0148284 1 0 1 1 0 0 +EDGE2 6682 6622 -0.133182 0.0459612 0.00802228 1 0 1 1 0 0 +EDGE2 6682 6623 1.00906 -0.0158771 0.00795669 1 0 1 1 0 0 +EDGE2 6683 6643 -0.00500982 -0.00353806 0.00613307 1 0 1 1 0 0 +EDGE2 6683 6642 -1.00832 0.000997108 -0.0300776 1 0 1 1 0 0 +EDGE2 6683 6682 -0.928192 -0.0386227 -0.011246 1 0 1 1 0 0 +EDGE2 6683 6622 -1.04244 0.0634946 0.00330208 1 0 1 1 0 0 +EDGE2 6683 6624 1.0298 -0.0613226 -0.00081856 1 0 1 1 0 0 +EDGE2 6683 6623 0.0530585 0.0122329 -0.00175619 1 0 1 1 0 0 +EDGE2 6683 6644 0.89835 -0.0392132 -0.0370661 1 0 1 1 0 0 +EDGE2 6684 6643 -0.951594 -0.0403665 0.00359168 1 0 1 1 0 0 +EDGE2 6684 6683 -0.901793 0.0181669 0.0222886 1 0 1 1 0 0 +EDGE2 6684 6624 0.0481188 0.0522075 -0.00697717 1 0 1 1 0 0 +EDGE2 6684 6623 -0.980656 0.00422627 0.0104128 1 0 1 1 0 0 +EDGE2 6684 6644 0.0463156 -0.0124986 -0.00632417 1 0 1 1 0 0 +EDGE2 6684 6645 1.04451 -0.0326724 0.0239682 1 0 1 1 0 0 +EDGE2 6684 6625 0.994871 0.0957732 0.0380526 1 0 1 1 0 0 +EDGE2 6685 6624 -0.963735 -0.00546382 0.0330214 1 0 1 1 0 0 +EDGE2 6685 6684 -1.06625 0.0255384 0.00618837 1 0 1 1 0 0 +EDGE2 6685 6644 -1.03984 0.0658865 0.0301641 1 0 1 1 0 0 +EDGE2 6685 6645 0.0254772 -0.0138583 0.0025183 1 0 1 1 0 0 +EDGE2 6685 6625 0.00350108 0.0303267 -0.0171998 1 0 1 1 0 0 +EDGE2 6685 6626 -0.0652147 0.993995 1.55671 1 0 1 1 0 0 +EDGE2 6685 6646 -0.0297673 0.979601 1.57255 1 0 1 1 0 0 +EDGE2 6686 6645 -0.88706 0.0421254 -1.58138 1 0 1 1 0 0 +EDGE2 6686 6685 -1.06853 -0.0599196 -1.58217 1 0 1 1 0 0 +EDGE2 6686 6625 -0.981532 -0.00402304 -1.55581 1 0 1 1 0 0 +EDGE2 6686 6626 -0.0141398 -0.00814049 0.00740882 1 0 1 1 0 0 +EDGE2 6686 6646 -0.0573897 -0.0521141 0.0258747 1 0 1 1 0 0 +EDGE2 6686 6627 1.02621 -0.0577586 -0.0108921 1 0 1 1 0 0 +EDGE2 6686 6647 1.0023 -0.0816292 -0.000304717 1 0 1 1 0 0 +EDGE2 6687 6686 -1.0538 -0.0134302 -0.0124664 1 0 1 1 0 0 +EDGE2 6687 6626 -1.04521 -0.108572 0.00707498 1 0 1 1 0 0 +EDGE2 6687 6646 -1.02275 -0.0423805 -0.0200218 1 0 1 1 0 0 +EDGE2 6687 6627 -0.0430882 -0.023753 7.07981e-05 1 0 1 1 0 0 +EDGE2 6687 6647 0.00694346 -0.0752338 0.0252234 1 0 1 1 0 0 +EDGE2 6687 6628 0.991093 -0.0387592 0.0010423 1 0 1 1 0 0 +EDGE2 6687 6648 1.01519 0.0293266 -0.00331039 1 0 1 1 0 0 +EDGE2 6688 6627 -0.984217 -0.0769248 0.0188517 1 0 1 1 0 0 +EDGE2 6688 6647 -1.02098 0.0426806 -0.0116989 1 0 1 1 0 0 +EDGE2 6688 6687 -1.00079 -0.0333847 0.0413022 1 0 1 1 0 0 +EDGE2 6688 6628 0.0363344 -0.0445355 -0.0195469 1 0 1 1 0 0 +EDGE2 6688 6648 0.0693854 -0.0606473 -0.0168323 1 0 1 1 0 0 +EDGE2 6688 6629 1.02847 0.0528812 -0.0141779 1 0 1 1 0 0 +EDGE2 6688 6649 0.991341 -0.0543164 -0.020509 1 0 1 1 0 0 +EDGE2 6689 6628 -0.971484 -0.0424393 -0.0302669 1 0 1 1 0 0 +EDGE2 6689 6648 -0.902502 0.0366962 0.0132323 1 0 1 1 0 0 +EDGE2 6689 6688 -1.02711 0.0326856 0.0106183 1 0 1 1 0 0 +EDGE2 6689 6550 1.04268 0.00824892 -3.12189 1 0 1 1 0 0 +EDGE2 6689 6629 0.0138518 0.0587292 -0.00831957 1 0 1 1 0 0 +EDGE2 6689 6649 -0.0131195 -0.0485166 -0.0143054 1 0 1 1 0 0 +EDGE2 6689 6590 0.973205 -0.0287235 -3.14092 1 0 1 1 0 0 +EDGE2 6689 6630 0.922879 0.0437737 -0.0185097 1 0 1 1 0 0 +EDGE2 6689 6650 1.02714 -0.0372916 -0.0194267 1 0 1 1 0 0 +EDGE2 6689 6570 1.00768 0.00826765 -3.15508 1 0 1 1 0 0 +EDGE2 6690 6631 -0.0499398 1.09942 1.59096 1 0 1 1 0 0 +EDGE2 6690 6651 -0.031867 1.00841 1.55675 1 0 1 1 0 0 +EDGE2 6690 6571 -0.00293494 -0.960077 -1.58954 1 0 1 1 0 0 +EDGE2 6690 6550 0.0320027 0.0383274 -3.14138 1 0 1 1 0 0 +EDGE2 6690 6629 -0.90684 0.0384348 0.0244436 1 0 1 1 0 0 +EDGE2 6690 6649 -0.990212 0.0221589 -0.0184219 1 0 1 1 0 0 +EDGE2 6690 6689 -1.01325 0.0656376 -0.0251676 1 0 1 1 0 0 +EDGE2 6690 6591 0.0868872 0.991918 1.54664 1 0 1 1 0 0 +EDGE2 6690 6590 0.0212939 -0.05311 -3.13102 1 0 1 1 0 0 +EDGE2 6690 6630 -0.00840943 0.0554375 -0.0506672 1 0 1 1 0 0 +EDGE2 6690 6650 0.0961076 0.000152303 -0.021773 1 0 1 1 0 0 +EDGE2 6690 6570 -0.00818313 -0.00281522 -3.14655 1 0 1 1 0 0 +EDGE2 6690 6551 0.0355251 -0.871445 -1.57491 1 0 1 1 0 0 +EDGE2 6690 6549 0.987306 0.0105266 -3.17312 1 0 1 1 0 0 +EDGE2 6690 6569 0.991274 0.0121075 -3.13628 1 0 1 1 0 0 +EDGE2 6690 6589 1.07353 -0.00227959 -3.1186 1 0 1 1 0 0 +EDGE2 6691 6571 0.0665441 -0.0147761 0.0111764 1 0 1 1 0 0 +EDGE2 6691 6550 -0.955364 0.0749361 -1.58352 1 0 1 1 0 0 +EDGE2 6691 6690 -1.01531 0.0643547 1.5671 1 0 1 1 0 0 +EDGE2 6691 6590 -0.977623 0.00863741 -1.525 1 0 1 1 0 0 +EDGE2 6691 6630 -0.942724 0.0392182 1.54441 1 0 1 1 0 0 +EDGE2 6691 6650 -0.958931 0.0605814 1.56722 1 0 1 1 0 0 +EDGE2 6691 6570 -0.94527 -0.0115975 -1.54532 1 0 1 1 0 0 +EDGE2 6691 6572 1.00599 -0.00341486 0.00814413 1 0 1 1 0 0 +EDGE2 6691 6551 0.0169399 0.0520155 0.0175049 1 0 1 1 0 0 +EDGE2 6691 6552 1.07846 0.030998 -0.0169619 1 0 1 1 0 0 +EDGE2 6692 6571 -0.98703 -0.0540537 0.0105544 1 0 1 1 0 0 +EDGE2 6692 6691 -0.970995 0.0373696 -0.0358129 1 0 1 1 0 0 +EDGE2 6692 6572 0.0483864 0.0757531 0.000919219 1 0 1 1 0 0 +EDGE2 6692 6551 -0.9795 -0.0208941 0.0091874 1 0 1 1 0 0 +EDGE2 6692 6552 -0.0349682 -0.0721254 0.00954717 1 0 1 1 0 0 +EDGE2 6692 6553 0.979699 0.0830284 -0.012088 1 0 1 1 0 0 +EDGE2 6692 6573 0.993067 -0.0248925 -0.0277461 1 0 1 1 0 0 +EDGE2 6693 6554 1.10825 -0.0195267 0.00888601 1 0 1 1 0 0 +EDGE2 6693 6572 -0.996804 -0.001665 0.0048807 1 0 1 1 0 0 +EDGE2 6693 6692 -1.00917 -0.0326617 0.0159987 1 0 1 1 0 0 +EDGE2 6693 6552 -0.981763 -0.0204121 0.0232771 1 0 1 1 0 0 +EDGE2 6693 6553 -0.0357649 -0.0125204 0.00448599 1 0 1 1 0 0 +EDGE2 6693 6573 0.112547 0.0103087 -0.0192006 1 0 1 1 0 0 +EDGE2 6693 6574 1.02943 0.118652 0.0261405 1 0 1 1 0 0 +EDGE2 6694 6554 -0.0398397 0.0213405 0.0278892 1 0 1 1 0 0 +EDGE2 6694 6693 -0.98583 0.0408119 -0.00731576 1 0 1 1 0 0 +EDGE2 6694 6553 -0.968224 -0.00383578 0.0257316 1 0 1 1 0 0 +EDGE2 6694 6573 -1.01415 0.0457325 -0.00576254 1 0 1 1 0 0 +EDGE2 6694 6574 0.0102821 0.0547644 0.0230596 1 0 1 1 0 0 +EDGE2 6694 6555 1.08091 0.0517055 0.0212313 1 0 1 1 0 0 +EDGE2 6694 6575 0.981164 -0.0296319 -0.00462633 1 0 1 1 0 0 +EDGE2 6695 6554 -0.933485 -0.0532611 -0.0176347 1 0 1 1 0 0 +EDGE2 6695 6694 -1.00645 7.33011e-05 -0.0207081 1 0 1 1 0 0 +EDGE2 6695 6574 -0.986706 -0.0292318 -0.0126711 1 0 1 1 0 0 +EDGE2 6695 6555 0.0318857 -0.0386887 -0.00889606 1 0 1 1 0 0 +EDGE2 6695 6575 0.0172138 -0.028064 0.013809 1 0 1 1 0 0 +EDGE2 6695 6556 -0.034962 1.04402 1.54473 1 0 1 1 0 0 +EDGE2 6695 6576 0.0417397 0.945506 1.57117 1 0 1 1 0 0 +EDGE2 6696 6555 -0.958479 0.0550978 1.56234 1 0 1 1 0 0 +EDGE2 6696 6575 -1.0811 0.0657432 1.57643 1 0 1 1 0 0 +EDGE2 6696 6695 -0.985812 -0.0360146 1.59933 1 0 1 1 0 0 +EDGE2 6697 6696 -0.966965 0.00850442 0.000402099 1 0 1 1 0 0 +EDGE2 6698 6697 -1.06662 0.0029468 -0.025819 1 0 1 1 0 0 +EDGE2 6699 6698 -1.00746 0.00919402 0.0265569 1 0 1 1 0 0 +EDGE2 6700 6699 -0.975617 -0.00522565 0.00829747 1 0 1 1 0 0 +EDGE2 6701 6700 -1.00921 0.0791421 -1.626 1 0 1 1 0 0 +EDGE2 6702 6701 -0.883786 0.00773717 0.0431122 1 0 1 1 0 0 +EDGE2 6703 6702 -1.08052 0.0297723 -0.00880178 1 0 1 1 0 0 +EDGE2 6704 6703 -0.989235 -0.0772525 0.0240014 1 0 1 1 0 0 +EDGE2 6705 6704 -1.00432 0.0819087 -0.00376948 1 0 1 1 0 0 +EDGE2 6706 6705 -0.970821 0.0803442 -1.59186 1 0 1 1 0 0 +EDGE2 6707 6706 -1.09361 -0.0397151 0.0056825 1 0 1 1 0 0 +EDGE2 6708 6707 -1.02094 0.0213852 -0.0214025 1 0 1 1 0 0 +EDGE2 6709 6708 -0.90961 0.06859 -0.00990609 1 0 1 1 0 0 +EDGE2 6710 6709 -0.931248 0.00848462 -0.00876746 1 0 1 1 0 0 +EDGE2 6711 6710 -0.978718 -0.0262586 1.56515 1 0 1 1 0 0 +EDGE2 6712 6711 -1.01395 0.0297799 0.028936 1 0 1 1 0 0 +EDGE2 6713 6712 -1.03127 -0.00159609 -0.000862688 1 0 1 1 0 0 +EDGE2 6714 6713 -1.01065 0.0531632 -0.0150101 1 0 1 1 0 0 +EDGE2 6715 6714 -0.960276 0.0231712 -0.00795016 1 0 1 1 0 0 +EDGE2 6716 6715 -1.01093 0.0274791 1.6205 1 0 1 1 0 0 +EDGE2 6717 6716 -0.986625 -0.0159063 0.00748882 1 0 1 1 0 0 +EDGE2 6718 6717 -1.02349 0.0746753 -0.0395513 1 0 1 1 0 0 +EDGE2 6719 6718 -0.928937 0.0143078 -0.00490033 1 0 1 1 0 0 +EDGE2 6720 6719 -0.975427 -0.0670375 -0.0178961 1 0 1 1 0 0 +EDGE2 6721 6720 -1.07659 -0.0473814 -1.54225 1 0 1 1 0 0 +EDGE2 6722 6721 -0.986237 0.031996 0.00375894 1 0 1 1 0 0 +EDGE2 6723 6722 -1.01425 -0.0571399 -0.00500602 1 0 1 1 0 0 +EDGE2 6724 6723 -0.941113 0.0699007 -0.0443872 1 0 1 1 0 0 +EDGE2 6725 6724 -1.01504 0.0407064 -0.00547503 1 0 1 1 0 0 +EDGE2 6726 6725 -0.989671 0.0343744 -1.54467 1 0 1 1 0 0 +EDGE2 6727 6726 -1.01526 -0.0104078 -0.0144867 1 0 1 1 0 0 +EDGE2 6728 6727 -1.00411 -0.0533612 0.0149912 1 0 1 1 0 0 +EDGE2 6729 6728 -1.06895 0.054604 0.0285778 1 0 1 1 0 0 +EDGE2 6730 6729 -0.936162 -0.0731721 -0.0223986 1 0 1 1 0 0 +EDGE2 6731 6730 -1.05299 0.00632549 -1.56696 1 0 1 1 0 0 +EDGE2 6732 6731 -0.955663 0.0201099 -0.0243012 1 0 1 1 0 0 +EDGE2 6733 6732 -1.00616 -0.143889 0.017524 1 0 1 1 0 0 +EDGE2 6734 6715 1.03662 0.0528415 -3.1412 1 0 1 1 0 0 +EDGE2 6734 6733 -0.992296 0.0477707 0.0086754 1 0 1 1 0 0 +EDGE2 6735 6716 0.0216741 0.934078 1.57603 1 0 1 1 0 0 +EDGE2 6735 6715 -0.010603 0.0619426 -3.14902 1 0 1 1 0 0 +EDGE2 6735 6714 1.02439 -0.0733113 -3.17207 1 0 1 1 0 0 +EDGE2 6735 6734 -1.01844 -0.0181994 0.0124582 1 0 1 1 0 0 +EDGE2 6736 6717 0.888012 -0.0485045 -0.0114461 1 0 1 1 0 0 +EDGE2 6736 6716 -0.0102489 -0.0195971 -0.000529096 1 0 1 1 0 0 +EDGE2 6736 6715 -0.88303 -0.062312 1.55369 1 0 1 1 0 0 +EDGE2 6736 6735 -0.959315 0.0441898 -1.56491 1 0 1 1 0 0 +EDGE2 6737 6718 0.976911 -0.0713401 0.0305547 1 0 1 1 0 0 +EDGE2 6737 6717 -0.00711288 0.00358894 -0.0234282 1 0 1 1 0 0 +EDGE2 6737 6716 -1.03418 0.0693507 -0.0289356 1 0 1 1 0 0 +EDGE2 6737 6736 -0.935248 -0.0390683 -0.00450633 1 0 1 1 0 0 +EDGE2 6738 6718 0.0748083 0.0314791 0.0569239 1 0 1 1 0 0 +EDGE2 6738 6719 1.00493 0.0634779 0.0447538 1 0 1 1 0 0 +EDGE2 6738 6737 -1.03338 -0.0738105 0.0173875 1 0 1 1 0 0 +EDGE2 6738 6717 -0.954097 -0.000304527 0.0110672 1 0 1 1 0 0 +EDGE2 6739 6720 1.0668 -0.0595358 -0.0137165 1 0 1 1 0 0 +EDGE2 6739 6718 -0.969011 -0.0463664 0.00725562 1 0 1 1 0 0 +EDGE2 6739 6719 -0.0534692 0.0258367 0.00133419 1 0 1 1 0 0 +EDGE2 6739 6738 -1.06175 0.0357262 -0.00638838 1 0 1 1 0 0 +EDGE2 6740 6739 -1.0841 0.0308638 -0.0394113 1 0 1 1 0 0 +EDGE2 6740 6720 -0.0291201 -0.0378244 0.0193313 1 0 1 1 0 0 +EDGE2 6740 6721 -0.0320788 1.04476 1.55021 1 0 1 1 0 0 +EDGE2 6740 6719 -0.916261 -0.0789059 -0.0191056 1 0 1 1 0 0 +EDGE2 6741 6720 -1.03303 -0.0320341 1.5869 1 0 1 1 0 0 +EDGE2 6741 6740 -1.00447 -0.00407224 1.57074 1 0 1 1 0 0 +EDGE2 6742 6741 -0.982463 -0.00534417 0.00749437 1 0 1 1 0 0 +EDGE2 6743 6742 -1.0922 0.0546597 -0.00922289 1 0 1 1 0 0 +EDGE2 6744 6705 0.958444 -0.0452485 -3.15307 1 0 1 1 0 0 +EDGE2 6744 6743 -1.04203 -0.0243695 0.000133019 1 0 1 1 0 0 +EDGE2 6745 6704 1.06841 -0.0115788 -3.08691 1 0 1 1 0 0 +EDGE2 6745 6705 0.0324048 -0.024554 -3.1575 1 0 1 1 0 0 +EDGE2 6745 6744 -0.971317 0.0559842 0.012211 1 0 1 1 0 0 +EDGE2 6745 6706 -0.0523206 -1.06478 -1.55071 1 0 1 1 0 0 +EDGE2 6746 6705 -1.08007 0.0476965 1.57481 1 0 1 1 0 0 +EDGE2 6746 6745 -1.06244 0.020436 -1.60128 1 0 1 1 0 0 +EDGE2 6747 6746 -1.00224 0.0112748 0.0102402 1 0 1 1 0 0 +EDGE2 6748 6747 -0.98818 0.0498613 -0.0299997 1 0 1 1 0 0 +EDGE2 6749 6748 -0.940301 0.0561956 -0.0147279 1 0 1 1 0 0 +EDGE2 6750 6749 -0.986611 -0.00812655 -0.00953656 1 0 1 1 0 0 +EDGE2 6751 6750 -0.980455 0.0286109 1.53972 1 0 1 1 0 0 +EDGE2 6752 6751 -0.975539 -0.010705 -0.0181944 1 0 1 1 0 0 +EDGE2 6753 6752 -0.928189 -0.00912683 0.0083042 1 0 1 1 0 0 +EDGE2 6754 6753 -1.031 -0.0216435 -0.019688 1 0 1 1 0 0 +EDGE2 6755 6754 -0.973496 0.0609743 -0.0042924 1 0 1 1 0 0 +EDGE2 6756 6755 -0.984005 0.0438784 -1.55743 1 0 1 1 0 0 +EDGE2 6757 6756 -0.970677 -0.0584154 0.00172556 1 0 1 1 0 0 +EDGE2 6758 6757 -1.01841 -0.0774321 0.00503884 1 0 1 1 0 0 +EDGE2 6759 6758 -0.999978 0.027914 0.0169283 1 0 1 1 0 0 +EDGE2 6760 6759 -0.95092 0.0189056 -0.00659301 1 0 1 1 0 0 +EDGE2 6761 6760 -1.05462 -0.0563588 -1.60805 1 0 1 1 0 0 +EDGE2 6762 6761 -0.931189 0.00203352 -0.00572225 1 0 1 1 0 0 +EDGE2 6763 6762 -0.974431 0.0645465 0.030365 1 0 1 1 0 0 +EDGE2 6764 6763 -1.0323 0.0201501 0.00871601 1 0 1 1 0 0 +EDGE2 6765 6764 -0.993507 -0.0141769 -0.000989896 1 0 1 1 0 0 +EDGE2 6766 6765 -0.909564 -0.0422909 1.57727 1 0 1 1 0 0 +EDGE2 6767 6766 -1.04132 -0.0158413 -0.0201887 1 0 1 1 0 0 +EDGE2 6768 6767 -1.07844 0.0475554 -0.0373954 1 0 1 1 0 0 +EDGE2 6769 6768 -0.971435 0.0607018 0.0261701 1 0 1 1 0 0 +EDGE2 6770 6769 -0.986607 -0.0552595 -0.0167 1 0 1 1 0 0 +EDGE2 6771 6770 -0.942964 -0.00526883 -1.58093 1 0 1 1 0 0 +EDGE2 6772 6771 -1.03231 0.0141757 -0.00949484 1 0 1 1 0 0 +EDGE2 6773 6772 -0.9949 -0.0371795 0.0294803 1 0 1 1 0 0 +EDGE2 6774 6773 -1.01361 -0.0406845 0.0507202 1 0 1 1 0 0 +EDGE2 6775 6774 -0.888008 -0.0799015 0.0248196 1 0 1 1 0 0 +EDGE2 6776 6775 -1.00295 -0.0995987 -1.55432 1 0 1 1 0 0 +EDGE2 6777 6776 -0.95001 0.020308 -0.00272148 1 0 1 1 0 0 +EDGE2 6778 6777 -0.981897 0.00311459 0.015056 1 0 1 1 0 0 +EDGE2 6779 6778 -0.984105 -0.104822 -0.0119397 1 0 1 1 0 0 +EDGE2 6780 6779 -1.03448 -0.0104511 0.021987 1 0 1 1 0 0 +EDGE2 6781 6780 -1.01202 -0.0850321 -1.56259 1 0 1 1 0 0 +EDGE2 6782 6781 -0.945339 -0.0297623 -0.0270994 1 0 1 1 0 0 +EDGE2 6783 6782 -1.03705 -0.0414108 0.0191185 1 0 1 1 0 0 +EDGE2 6784 6765 0.917689 0.132895 -3.11033 1 0 1 1 0 0 +EDGE2 6784 6783 -1.05974 -0.0336866 -0.0317236 1 0 1 1 0 0 +EDGE2 6785 6784 -0.96017 0.0431722 0.00823527 1 0 1 1 0 0 +EDGE2 6785 6764 0.962481 -0.0043806 -3.14384 1 0 1 1 0 0 +EDGE2 6785 6766 0.0162967 0.891226 1.52975 1 0 1 1 0 0 +EDGE2 6785 6765 -0.0404317 -0.154118 -3.12719 1 0 1 1 0 0 +EDGE2 6786 6767 1.01084 -0.0171149 -0.0237734 1 0 1 1 0 0 +EDGE2 6786 6766 -0.0589826 0.0586789 -0.0354403 1 0 1 1 0 0 +EDGE2 6786 6785 -0.999715 -0.0182449 -1.56629 1 0 1 1 0 0 +EDGE2 6786 6765 -0.982144 0.00636906 1.56466 1 0 1 1 0 0 +EDGE2 6787 6768 0.994643 -0.0262892 0.00447556 1 0 1 1 0 0 +EDGE2 6787 6767 0.0237141 -0.0066608 -0.0367732 1 0 1 1 0 0 +EDGE2 6787 6766 -1.0534 0.0312993 0.0139107 1 0 1 1 0 0 +EDGE2 6787 6786 -1.02467 -0.00248338 -0.0108509 1 0 1 1 0 0 +EDGE2 6788 6769 0.994682 -0.0591828 -0.00162364 1 0 1 1 0 0 +EDGE2 6788 6787 -1.01883 -0.0357506 0.00270128 1 0 1 1 0 0 +EDGE2 6788 6768 0.0153915 -0.0739928 -0.00648704 1 0 1 1 0 0 +EDGE2 6788 6767 -1.00995 -0.0221263 0.0227261 1 0 1 1 0 0 +EDGE2 6789 6770 0.94054 0.0437079 0.0247061 1 0 1 1 0 0 +EDGE2 6789 6788 -0.977537 0.0309278 -0.039807 1 0 1 1 0 0 +EDGE2 6789 6769 -0.0143305 0.0518444 -0.0396772 1 0 1 1 0 0 +EDGE2 6789 6768 -1.00954 -0.0836389 -0.01037 1 0 1 1 0 0 +EDGE2 6790 6770 -0.0294256 -0.00266928 0.0305031 1 0 1 1 0 0 +EDGE2 6790 6771 -0.0669285 0.966329 1.57345 1 0 1 1 0 0 +EDGE2 6790 6769 -0.914908 -0.0476787 -0.0333522 1 0 1 1 0 0 +EDGE2 6790 6789 -1.02642 0.0119244 0.00798956 1 0 1 1 0 0 +EDGE2 6791 6770 -0.948009 0.00158288 -1.57741 1 0 1 1 0 0 +EDGE2 6791 6790 -1.0018 0.0330733 -1.5461 1 0 1 1 0 0 +EDGE2 6791 6771 -0.0300764 0.0559716 0.00693068 1 0 1 1 0 0 +EDGE2 6791 6772 0.949711 -0.0723239 -0.0116256 1 0 1 1 0 0 +EDGE2 6792 6791 -1.02893 0.027157 -0.011635 1 0 1 1 0 0 +EDGE2 6792 6771 -0.990002 -0.00161995 -0.020441 1 0 1 1 0 0 +EDGE2 6792 6773 1.0125 0.0671397 0.0374561 1 0 1 1 0 0 +EDGE2 6792 6772 0.0342958 0.0236563 0.0140982 1 0 1 1 0 0 +EDGE2 6793 6774 1.02835 -0.0392816 0.0235569 1 0 1 1 0 0 +EDGE2 6793 6792 -1.0386 0.0553877 -0.00202178 1 0 1 1 0 0 +EDGE2 6793 6773 -0.021201 -0.0219131 -0.0167038 1 0 1 1 0 0 +EDGE2 6793 6772 -0.991869 0.0503149 -0.00694513 1 0 1 1 0 0 +EDGE2 6794 6774 0.051442 -0.0312729 0.0022193 1 0 1 1 0 0 +EDGE2 6794 6773 -1.04029 -0.0558018 -0.00212183 1 0 1 1 0 0 +EDGE2 6794 6793 -1.00502 -0.0377534 0.0309526 1 0 1 1 0 0 +EDGE2 6794 6775 1.01445 -0.00800621 0.0166979 1 0 1 1 0 0 +EDGE2 6795 6774 -1.04318 -0.0377135 0.0129452 1 0 1 1 0 0 +EDGE2 6795 6794 -1.04214 -0.0470186 -0.0312906 1 0 1 1 0 0 +EDGE2 6795 6775 0.137446 0.0471087 0.00533628 1 0 1 1 0 0 +EDGE2 6795 6776 0.0227608 1.01379 1.52587 1 0 1 1 0 0 +EDGE2 6796 6795 -0.905605 0.0141908 -1.55612 1 0 1 1 0 0 +EDGE2 6796 6775 -1.00596 0.0377277 -1.57555 1 0 1 1 0 0 +EDGE2 6796 6777 0.894996 -0.0687088 0.0174851 1 0 1 1 0 0 +EDGE2 6796 6776 0.0160788 0.072439 -0.0137539 1 0 1 1 0 0 +EDGE2 6797 6777 0.0155633 -0.0372525 0.0110563 1 0 1 1 0 0 +EDGE2 6797 6796 -1.00022 0.00587718 -0.00591678 1 0 1 1 0 0 +EDGE2 6797 6776 -0.94022 -0.0178751 -0.00968125 1 0 1 1 0 0 +EDGE2 6797 6778 1.08331 0.0426647 0.010972 1 0 1 1 0 0 +EDGE2 6798 6777 -0.992075 -0.00338887 -0.0251918 1 0 1 1 0 0 +EDGE2 6798 6797 -1.11201 -0.032943 -0.027471 1 0 1 1 0 0 +EDGE2 6798 6778 0.0587886 -0.0517441 0.00707234 1 0 1 1 0 0 +EDGE2 6798 6779 1.00861 0.137723 -0.00171756 1 0 1 1 0 0 +EDGE2 6799 6778 -0.984376 2.71171e-06 -0.0110234 1 0 1 1 0 0 +EDGE2 6799 6798 -0.943201 0.0461196 0.0289955 1 0 1 1 0 0 +EDGE2 6799 6779 -0.00226844 0.0672526 -0.0221911 1 0 1 1 0 0 +EDGE2 6799 6780 1.06378 0.0456727 0.00666656 1 0 1 1 0 0 +EDGE2 6800 6799 -0.918085 0.0844833 0.0206558 1 0 1 1 0 0 +EDGE2 6800 6779 -1.01181 0.00429471 0.0234624 1 0 1 1 0 0 +EDGE2 6800 6781 -0.0833433 1.10566 1.5741 1 0 1 1 0 0 +EDGE2 6800 6780 0.0559523 -0.000232581 -0.0220104 1 0 1 1 0 0 +EDGE2 6801 6780 -1.04922 -0.00586348 1.57185 1 0 1 1 0 0 +EDGE2 6801 6800 -0.980281 0.0072517 1.55334 1 0 1 1 0 0 +EDGE2 6802 6801 -0.93132 -0.0295247 0.0200097 1 0 1 1 0 0 +EDGE2 6803 6802 -1.03692 -0.00543982 0.00804957 1 0 1 1 0 0 +EDGE2 6804 6803 -0.962045 0.0163574 -0.0239175 1 0 1 1 0 0 +EDGE2 6805 6804 -1.03365 -0.023386 0.00485597 1 0 1 1 0 0 +EDGE2 6806 6805 -0.981923 -0.00461987 -1.58175 1 0 1 1 0 0 +EDGE2 6807 6806 -1.00886 0.0294674 0.00423974 1 0 1 1 0 0 +EDGE2 6808 6807 -1.02842 -0.0533322 -0.00500681 1 0 1 1 0 0 +EDGE2 6809 6808 -1.01305 -0.0273015 0.000463718 1 0 1 1 0 0 +EDGE2 6810 6809 -0.933181 0.0172611 -0.00711977 1 0 1 1 0 0 +EDGE2 6811 6810 -1.04629 0.0863601 -1.60265 1 0 1 1 0 0 +EDGE2 6812 6811 -1.00391 0.00270128 0.00512399 1 0 1 1 0 0 +EDGE2 6813 6812 -0.981086 -0.104371 -0.0356402 1 0 1 1 0 0 +EDGE2 6814 6813 -0.963419 0.00846839 0.00989465 1 0 1 1 0 0 +EDGE2 6815 6814 -0.949039 0.00194526 0.0109431 1 0 1 1 0 0 +EDGE2 6816 6815 -0.999993 -0.0258195 -1.54693 1 0 1 1 0 0 +EDGE2 6817 6816 -1.03891 0.00449283 -0.00723911 1 0 1 1 0 0 +EDGE2 6818 6817 -1.0919 -0.00250936 0.0135443 1 0 1 1 0 0 +EDGE2 6819 6780 1.01103 0.000537977 -3.1549 1 0 1 1 0 0 +EDGE2 6819 6800 0.993548 0.0338247 -3.15455 1 0 1 1 0 0 +EDGE2 6819 6818 -1.04373 0.0680495 -0.00664147 1 0 1 1 0 0 +EDGE2 6820 6799 1.06196 0.0217646 -3.1302 1 0 1 1 0 0 +EDGE2 6820 6779 0.93718 0.057054 -3.1628 1 0 1 1 0 0 +EDGE2 6820 6801 0.0411648 0.96927 1.5699 1 0 1 1 0 0 +EDGE2 6820 6781 0.0526231 -1.01333 -1.60427 1 0 1 1 0 0 +EDGE2 6820 6780 0.0561846 0.0306492 -3.15215 1 0 1 1 0 0 +EDGE2 6820 6800 0.0203873 0.00626322 -3.11188 1 0 1 1 0 0 +EDGE2 6820 6819 -1.0017 0.0503009 -0.00520818 1 0 1 1 0 0 +EDGE2 6821 6801 0.0525588 -0.0203645 0.0159912 1 0 1 1 0 0 +EDGE2 6821 6820 -1.00201 -0.0130248 -1.61226 1 0 1 1 0 0 +EDGE2 6821 6780 -0.95503 0.0411414 1.56845 1 0 1 1 0 0 +EDGE2 6821 6800 -1.05836 -0.0248984 1.57427 1 0 1 1 0 0 +EDGE2 6821 6802 1.09782 -0.0164973 0.0232876 1 0 1 1 0 0 +EDGE2 6822 6801 -0.937782 0.0484649 0.0329778 1 0 1 1 0 0 +EDGE2 6822 6821 -0.945437 0.0210384 0.0124156 1 0 1 1 0 0 +EDGE2 6822 6802 -0.0078111 0.0618253 0.00334136 1 0 1 1 0 0 +EDGE2 6822 6803 1.02086 0.0345551 -0.0245779 1 0 1 1 0 0 +EDGE2 6823 6802 -0.980686 0.0449546 -0.00629811 1 0 1 1 0 0 +EDGE2 6823 6822 -0.948916 0.0115379 -0.0184596 1 0 1 1 0 0 +EDGE2 6823 6803 0.0437273 0.0378546 0.00642072 1 0 1 1 0 0 +EDGE2 6823 6804 1.02949 0.0143004 0.0202966 1 0 1 1 0 0 +EDGE2 6824 6823 -0.931947 0.0730576 -0.0205315 1 0 1 1 0 0 +EDGE2 6824 6803 -1.01735 0.00756533 0.0326327 1 0 1 1 0 0 +EDGE2 6824 6804 0.0979879 0.0159681 0.00436428 1 0 1 1 0 0 +EDGE2 6824 6805 0.989731 0.115894 -0.031172 1 0 1 1 0 0 +EDGE2 6825 6824 -0.919339 -0.0420517 -0.00392792 1 0 1 1 0 0 +EDGE2 6825 6804 -0.93219 -0.00972348 0.0297219 1 0 1 1 0 0 +EDGE2 6825 6805 0.115121 0.0419425 0.015261 1 0 1 1 0 0 +EDGE2 6825 6806 0.0169622 0.974223 1.59909 1 0 1 1 0 0 +EDGE2 6826 6825 -1.11125 0.0491745 -1.56889 1 0 1 1 0 0 +EDGE2 6826 6805 -0.964167 -0.0314865 -1.58129 1 0 1 1 0 0 +EDGE2 6826 6806 0.0298149 -0.0990601 0.0182513 1 0 1 1 0 0 +EDGE2 6826 6807 1.13019 -0.0612864 0.0575526 1 0 1 1 0 0 +EDGE2 6827 6826 -1.00422 0.0678633 0.0241736 1 0 1 1 0 0 +EDGE2 6827 6806 -0.989281 0.0200613 -0.0142917 1 0 1 1 0 0 +EDGE2 6827 6807 -0.0648461 0.0840006 0.0130315 1 0 1 1 0 0 +EDGE2 6827 6808 0.948702 0.0415332 0.0285227 1 0 1 1 0 0 +EDGE2 6828 6827 -0.944092 -0.0322496 0.0061815 1 0 1 1 0 0 +EDGE2 6828 6807 -1.02347 -0.0551614 -0.00349634 1 0 1 1 0 0 +EDGE2 6828 6808 0.043314 0.0151315 0.0140837 1 0 1 1 0 0 +EDGE2 6828 6809 1.00512 0.0610541 -0.0311674 1 0 1 1 0 0 +EDGE2 6829 6808 -1.01947 0.0400476 0.00456559 1 0 1 1 0 0 +EDGE2 6829 6828 -0.988123 0.0445474 0.0113933 1 0 1 1 0 0 +EDGE2 6829 6809 0.0374363 -0.0257168 0.055312 1 0 1 1 0 0 +EDGE2 6829 6810 0.928035 -0.0485503 0.0201953 1 0 1 1 0 0 +EDGE2 6830 6809 -1.01152 0.0380757 0.00566309 1 0 1 1 0 0 +EDGE2 6830 6829 -1.06226 -0.0330902 0.0291336 1 0 1 1 0 0 +EDGE2 6830 6810 0.00695118 -0.0594344 0.0169156 1 0 1 1 0 0 +EDGE2 6830 6811 0.00971501 0.931034 1.55932 1 0 1 1 0 0 +EDGE2 6831 6810 -1.04078 -0.0251926 -1.57636 1 0 1 1 0 0 +EDGE2 6831 6811 0.0389445 -0.0331163 0.000868163 1 0 1 1 0 0 +EDGE2 6831 6812 1.05502 -0.0469148 0.00388532 1 0 1 1 0 0 +EDGE2 6831 6830 -1.02801 0.0397636 -1.56992 1 0 1 1 0 0 +EDGE2 6832 6813 1.10231 -0.00287067 0.00491314 1 0 1 1 0 0 +EDGE2 6832 6811 -0.985089 0.0171506 0.0345777 1 0 1 1 0 0 +EDGE2 6832 6831 -1.02768 0.0540982 0.0318757 1 0 1 1 0 0 +EDGE2 6832 6812 0.0325169 -0.0464705 0.0203023 1 0 1 1 0 0 +EDGE2 6833 6832 -0.966341 0.0157541 -0.0128612 1 0 1 1 0 0 +EDGE2 6833 6814 1.01602 0.0509924 -0.0188738 1 0 1 1 0 0 +EDGE2 6833 6813 0.102299 0.126742 -0.0142453 1 0 1 1 0 0 +EDGE2 6833 6812 -0.960914 0.00237585 0.0229124 1 0 1 1 0 0 +EDGE2 6834 6815 0.930079 -0.0919635 0.0206659 1 0 1 1 0 0 +EDGE2 6834 6833 -0.996591 -0.024651 0.0091057 1 0 1 1 0 0 +EDGE2 6834 6814 0.0799797 0.0290584 0.0184281 1 0 1 1 0 0 +EDGE2 6834 6813 -0.994456 -0.0252325 0.00283939 1 0 1 1 0 0 +EDGE2 6835 6815 0.00696717 -0.0153221 -0.0116085 1 0 1 1 0 0 +EDGE2 6835 6816 0.0607963 0.967487 1.50755 1 0 1 1 0 0 +EDGE2 6835 6814 -0.933892 0.00866748 0.0236875 1 0 1 1 0 0 +EDGE2 6835 6834 -1.12874 0.0393619 0.000471286 1 0 1 1 0 0 +EDGE2 6836 6815 -1.0067 0.0387772 1.57699 1 0 1 1 0 0 +EDGE2 6836 6835 -1.04672 0.0123876 1.58702 1 0 1 1 0 0 +EDGE2 6837 6836 -0.985634 -0.032528 0.0138191 1 0 1 1 0 0 +EDGE2 6838 6837 -0.979203 -0.0476319 -0.00796542 1 0 1 1 0 0 +EDGE2 6839 6838 -0.970732 -0.0348185 0.00657318 1 0 1 1 0 0 +EDGE2 6839 6720 1.05012 -0.00991784 -3.14808 1 0 1 1 0 0 +EDGE2 6839 6740 0.857043 0.0570915 -3.11292 1 0 1 1 0 0 +EDGE2 6840 6839 -0.999362 0.00484435 -0.0351661 1 0 1 1 0 0 +EDGE2 6840 6739 0.937869 -0.0172457 -3.13345 1 0 1 1 0 0 +EDGE2 6840 6741 -0.035469 0.916999 1.54523 1 0 1 1 0 0 +EDGE2 6840 6720 -0.0652341 -0.0011329 -3.15027 1 0 1 1 0 0 +EDGE2 6840 6740 0.0234412 -0.0241196 -3.13073 1 0 1 1 0 0 +EDGE2 6840 6721 -0.0282563 -1.08491 -1.5657 1 0 1 1 0 0 +EDGE2 6840 6719 0.984968 -0.00798022 -3.13314 1 0 1 1 0 0 +EDGE2 6841 6741 -0.090141 0.0606514 0.00816836 1 0 1 1 0 0 +EDGE2 6841 6742 0.988926 -0.0401582 -0.00793874 1 0 1 1 0 0 +EDGE2 6841 6720 -1.09212 0.00480845 1.57305 1 0 1 1 0 0 +EDGE2 6841 6740 -1.04404 -0.0286516 1.56501 1 0 1 1 0 0 +EDGE2 6841 6840 -1.02362 -0.042468 -1.55361 1 0 1 1 0 0 +EDGE2 6842 6741 -1.11552 0.0225282 -0.0121417 1 0 1 1 0 0 +EDGE2 6842 6742 0.00658429 -0.0309279 -0.00314407 1 0 1 1 0 0 +EDGE2 6842 6743 0.970446 -0.0175227 0.0391254 1 0 1 1 0 0 +EDGE2 6842 6841 -0.939379 -0.120448 0.0036293 1 0 1 1 0 0 +EDGE2 6843 6744 0.974152 -0.0990446 0.00577737 1 0 1 1 0 0 +EDGE2 6843 6742 -1.06346 -0.0348043 0.00917845 1 0 1 1 0 0 +EDGE2 6843 6842 -1.0683 -0.00261044 0.0297618 1 0 1 1 0 0 +EDGE2 6843 6743 -0.0288881 0.00726848 -0.0160872 1 0 1 1 0 0 +EDGE2 6844 6843 -1.10335 -0.0558394 -0.042432 1 0 1 1 0 0 +EDGE2 6844 6705 1.01628 0.0295424 -3.20006 1 0 1 1 0 0 +EDGE2 6844 6745 1.11051 0.063579 0.0156669 1 0 1 1 0 0 +EDGE2 6844 6744 0.0018074 -0.00239935 -0.0401891 1 0 1 1 0 0 +EDGE2 6844 6743 -0.88404 0.0570399 -0.031614 1 0 1 1 0 0 +EDGE2 6845 6746 0.0283748 1.0651 1.57997 1 0 1 1 0 0 +EDGE2 6845 6704 1.03852 -0.0387648 -3.13571 1 0 1 1 0 0 +EDGE2 6845 6844 -0.921495 -0.0575706 -0.00564813 1 0 1 1 0 0 +EDGE2 6845 6705 0.0406032 0.00179415 -3.16561 1 0 1 1 0 0 +EDGE2 6845 6745 -0.0102646 -0.0613378 1.97156e-05 1 0 1 1 0 0 +EDGE2 6845 6744 -0.987547 -0.0571748 -0.0144867 1 0 1 1 0 0 +EDGE2 6845 6706 -0.0846739 -1.01649 -1.56648 1 0 1 1 0 0 +EDGE2 6846 6747 1.12778 0.0292852 0.00868205 1 0 1 1 0 0 +EDGE2 6846 6746 0.00257129 -0.0197682 0.00588922 1 0 1 1 0 0 +EDGE2 6846 6845 -1.02353 -0.0893108 -1.568 1 0 1 1 0 0 +EDGE2 6846 6705 -1.05953 0.00020146 1.5998 1 0 1 1 0 0 +EDGE2 6846 6745 -1.08422 -0.0477048 -1.59492 1 0 1 1 0 0 +EDGE2 6847 6748 0.960908 -0.0671744 -0.00636131 1 0 1 1 0 0 +EDGE2 6847 6846 -0.994098 -0.010363 0.0120806 1 0 1 1 0 0 +EDGE2 6847 6747 -0.0171643 -0.0069563 0.0331568 1 0 1 1 0 0 +EDGE2 6847 6746 -0.970065 0.0139533 0.00533023 1 0 1 1 0 0 +EDGE2 6848 6748 -0.0515815 -0.0145143 0.0377549 1 0 1 1 0 0 +EDGE2 6848 6749 0.975213 -0.0989821 0.00804656 1 0 1 1 0 0 +EDGE2 6848 6747 -1.05546 -0.0192296 -0.0255782 1 0 1 1 0 0 +EDGE2 6848 6847 -1.01499 -0.00867653 0.0184766 1 0 1 1 0 0 +EDGE2 6849 6750 0.949274 0.0215583 -0.0122387 1 0 1 1 0 0 +EDGE2 6849 6748 -0.924547 0.0369966 -0.0224542 1 0 1 1 0 0 +EDGE2 6849 6749 -0.0100945 0.0123748 0.00270511 1 0 1 1 0 0 +EDGE2 6849 6848 -1.04699 -0.0369128 0.0320331 1 0 1 1 0 0 +EDGE2 6850 6751 0.0121518 -1.09745 -1.56975 1 0 1 1 0 0 +EDGE2 6850 6750 -0.0153018 -0.00350928 0.00269315 1 0 1 1 0 0 +EDGE2 6850 6749 -1.05328 -0.0718928 0.0309367 1 0 1 1 0 0 +EDGE2 6850 6849 -0.925411 -0.0210357 -0.00850407 1 0 1 1 0 0 +EDGE2 6851 6750 -0.99972 -0.0594599 -1.55575 1 0 1 1 0 0 +EDGE2 6851 6850 -0.988041 -0.052997 -1.5697 1 0 1 1 0 0 +EDGE2 6852 6851 -0.99876 0.0736965 -0.00936694 1 0 1 1 0 0 +EDGE2 6853 6852 -1.00806 0.00208828 0.00467342 1 0 1 1 0 0 +EDGE2 6854 6815 0.952633 -0.0799291 -3.16471 1 0 1 1 0 0 +EDGE2 6854 6853 -0.97275 -0.089914 -0.0264553 1 0 1 1 0 0 +EDGE2 6854 6835 1.0128 0.00350961 -3.11602 1 0 1 1 0 0 +EDGE2 6855 6815 -0.0160579 0.108338 -3.15056 1 0 1 1 0 0 +EDGE2 6855 6816 -0.0470629 -0.889093 -1.55737 1 0 1 1 0 0 +EDGE2 6855 6854 -0.950793 0.0193594 -0.000256718 1 0 1 1 0 0 +EDGE2 6855 6835 0.0353318 -0.0248803 -3.15792 1 0 1 1 0 0 +EDGE2 6855 6814 1.10547 -0.00229643 -3.13278 1 0 1 1 0 0 +EDGE2 6855 6834 1.02142 0.0612551 -3.14395 1 0 1 1 0 0 +EDGE2 6855 6836 -0.0516063 0.961298 1.59174 1 0 1 1 0 0 +EDGE2 6856 6815 -0.981995 -0.00201066 -1.59106 1 0 1 1 0 0 +EDGE2 6856 6817 0.949148 -0.0210543 -0.040848 1 0 1 1 0 0 +EDGE2 6856 6816 -0.0428505 -0.0406079 -0.00347467 1 0 1 1 0 0 +EDGE2 6856 6855 -0.964782 -0.00539098 1.58274 1 0 1 1 0 0 +EDGE2 6856 6835 -1.01395 0.0229753 -1.56488 1 0 1 1 0 0 +EDGE2 6857 6818 0.960285 -0.0133121 0.00272651 1 0 1 1 0 0 +EDGE2 6857 6817 -0.015943 0.0291053 -0.0192037 1 0 1 1 0 0 +EDGE2 6857 6856 -0.983705 0.131281 0.0259658 1 0 1 1 0 0 +EDGE2 6857 6816 -0.993442 0.000710841 -0.00600105 1 0 1 1 0 0 +EDGE2 6858 6819 1.01591 -0.0202011 -0.00858875 1 0 1 1 0 0 +EDGE2 6858 6818 -0.0859789 0.0392384 -0.00607804 1 0 1 1 0 0 +EDGE2 6858 6857 -1.01483 -0.0518763 0.0204404 1 0 1 1 0 0 +EDGE2 6858 6817 -0.924844 0.00269148 0.00323179 1 0 1 1 0 0 +EDGE2 6859 6820 1.06846 0.0362023 9.49287e-05 1 0 1 1 0 0 +EDGE2 6859 6780 0.957624 -0.0335772 -3.1429 1 0 1 1 0 0 +EDGE2 6859 6800 0.970025 0.0107991 -3.14113 1 0 1 1 0 0 +EDGE2 6859 6819 -0.0161274 0.0282041 -0.0160755 1 0 1 1 0 0 +EDGE2 6859 6858 -0.981167 -0.00603729 -0.0195429 1 0 1 1 0 0 +EDGE2 6859 6818 -1.04421 0.0975724 0.0126784 1 0 1 1 0 0 +EDGE2 6860 6799 1.02418 0.0968033 -3.13849 1 0 1 1 0 0 +EDGE2 6860 6779 0.986953 0.041098 -3.15745 1 0 1 1 0 0 +EDGE2 6860 6801 -0.0135281 0.929892 1.59661 1 0 1 1 0 0 +EDGE2 6860 6820 -0.0083792 0.0335491 0.00934679 1 0 1 1 0 0 +EDGE2 6860 6781 0.00449929 -0.982661 -1.57125 1 0 1 1 0 0 +EDGE2 6860 6780 -0.125799 0.00813849 -3.12749 1 0 1 1 0 0 +EDGE2 6860 6800 0.016109 -0.0741146 -3.11105 1 0 1 1 0 0 +EDGE2 6860 6821 0.012216 0.983401 1.55532 1 0 1 1 0 0 +EDGE2 6860 6819 -1.08237 0.0763045 0.0115594 1 0 1 1 0 0 +EDGE2 6860 6859 -1.02781 -0.0508974 0.0119432 1 0 1 1 0 0 +EDGE2 6861 6801 0.00261022 -0.0512334 -0.0016877 1 0 1 1 0 0 +EDGE2 6861 6820 -0.921448 -0.0455046 -1.60567 1 0 1 1 0 0 +EDGE2 6861 6860 -1.00479 0.0328174 -1.56287 1 0 1 1 0 0 +EDGE2 6861 6780 -1.0189 0.0252194 1.55748 1 0 1 1 0 0 +EDGE2 6861 6800 -1.01846 0.0041146 1.59446 1 0 1 1 0 0 +EDGE2 6861 6821 -0.00627654 0.068237 -0.0254314 1 0 1 1 0 0 +EDGE2 6861 6802 1.00257 -0.0176705 -0.0535784 1 0 1 1 0 0 +EDGE2 6861 6822 1.1074 -0.0218145 0.00600754 1 0 1 1 0 0 +EDGE2 6862 6801 -1.00317 0.0266748 0.000296658 1 0 1 1 0 0 +EDGE2 6862 6861 -1.0401 0.0172019 -0.00251786 1 0 1 1 0 0 +EDGE2 6862 6821 -0.99782 -0.00693539 0.0148949 1 0 1 1 0 0 +EDGE2 6862 6823 0.953663 0.0530626 0.0106766 1 0 1 1 0 0 +EDGE2 6862 6802 0.00343705 -0.0285516 -0.00259394 1 0 1 1 0 0 +EDGE2 6862 6822 -0.00588645 0.0476545 0.00154472 1 0 1 1 0 0 +EDGE2 6862 6803 1.04134 -0.127961 0.0213323 1 0 1 1 0 0 +EDGE2 6863 6823 0.0935086 0.0232853 0.00251282 1 0 1 1 0 0 +EDGE2 6863 6802 -1.08095 0.0224027 0.000369779 1 0 1 1 0 0 +EDGE2 6863 6822 -0.953669 0.0570673 -0.0114912 1 0 1 1 0 0 +EDGE2 6863 6862 -1.07611 -0.0352006 -0.0042181 1 0 1 1 0 0 +EDGE2 6863 6824 1.03675 0.0300403 -0.034834 1 0 1 1 0 0 +EDGE2 6863 6803 -0.0105355 0.00144868 -0.0130538 1 0 1 1 0 0 +EDGE2 6863 6804 0.93179 -0.0729399 -0.0422087 1 0 1 1 0 0 +EDGE2 6864 6823 -0.968044 0.00815531 -0.0277743 1 0 1 1 0 0 +EDGE2 6864 6863 -1.07272 0.0717249 0.00390552 1 0 1 1 0 0 +EDGE2 6864 6824 -0.0362361 0.100122 0.0251213 1 0 1 1 0 0 +EDGE2 6864 6803 -0.914622 0.0414687 0.0194069 1 0 1 1 0 0 +EDGE2 6864 6804 0.0618166 -0.0418601 0.0233371 1 0 1 1 0 0 +EDGE2 6864 6825 1.01794 -0.017669 -0.0039913 1 0 1 1 0 0 +EDGE2 6864 6805 0.905591 0.0521834 -0.0115111 1 0 1 1 0 0 +EDGE2 6865 6824 -1.0128 -0.0356571 -0.0319603 1 0 1 1 0 0 +EDGE2 6865 6864 -1.03137 0.050991 0.0178788 1 0 1 1 0 0 +EDGE2 6865 6804 -1.00133 -0.0346178 -0.00960754 1 0 1 1 0 0 +EDGE2 6865 6825 0.0635757 0.0611282 -0.0138805 1 0 1 1 0 0 +EDGE2 6865 6826 0.0266675 0.882744 1.57301 1 0 1 1 0 0 +EDGE2 6865 6805 0.0717161 0.016189 -0.00940362 1 0 1 1 0 0 +EDGE2 6865 6806 -0.0509761 0.950667 1.55473 1 0 1 1 0 0 +EDGE2 6866 6825 -1.07352 0.0363724 1.56641 1 0 1 1 0 0 +EDGE2 6866 6865 -1.04081 0.045748 1.56609 1 0 1 1 0 0 +EDGE2 6866 6805 -0.956166 0.0162927 1.55478 1 0 1 1 0 0 +EDGE2 6867 6866 -0.997276 -0.0375496 -0.0134193 1 0 1 1 0 0 +EDGE2 6868 6867 -0.958497 0.0142009 0.00513234 1 0 1 1 0 0 +EDGE2 6869 6868 -1.01223 -0.00843349 0.00144482 1 0 1 1 0 0 +EDGE2 6870 6869 -1.05563 0.0211424 0.0233939 1 0 1 1 0 0 +EDGE2 6871 6870 -0.957324 -0.00638914 1.59169 1 0 1 1 0 0 +EDGE2 6872 6871 -0.957708 -0.0370894 -0.0164441 1 0 1 1 0 0 +EDGE2 6873 6872 -0.929793 0.0259883 -0.000558517 1 0 1 1 0 0 +EDGE2 6874 6795 0.987122 -0.0245372 -3.15003 1 0 1 1 0 0 +EDGE2 6874 6775 1.09686 -0.000482872 -3.13982 1 0 1 1 0 0 +EDGE2 6874 6873 -0.963327 -0.0145053 0.0202848 1 0 1 1 0 0 +EDGE2 6875 6774 0.941039 0.0040625 -3.14906 1 0 1 1 0 0 +EDGE2 6875 6794 0.947728 -0.0124406 -3.14884 1 0 1 1 0 0 +EDGE2 6875 6795 -0.0456869 0.0449999 -3.12047 1 0 1 1 0 0 +EDGE2 6875 6775 0.0788011 -0.058839 -3.1201 1 0 1 1 0 0 +EDGE2 6875 6874 -1.05192 -0.0396968 -0.0146023 1 0 1 1 0 0 +EDGE2 6875 6796 0.0509422 -0.965353 -1.5653 1 0 1 1 0 0 +EDGE2 6875 6776 -0.112919 -0.970646 -1.58012 1 0 1 1 0 0 +EDGE2 6876 6795 -1.02702 -0.0322221 1.52976 1 0 1 1 0 0 +EDGE2 6876 6875 -0.952618 -0.046872 -1.57351 1 0 1 1 0 0 +EDGE2 6876 6775 -0.973258 0.0619354 1.5754 1 0 1 1 0 0 +EDGE2 6877 6876 -1.06667 0.00584901 0.0390915 1 0 1 1 0 0 +EDGE2 6878 6877 -1.13407 0.131624 -0.021543 1 0 1 1 0 0 +EDGE2 6879 6878 -0.98917 -0.0533997 -0.00634692 1 0 1 1 0 0 +EDGE2 6880 6879 -1.01956 -0.0614095 -0.00542501 1 0 1 1 0 0 +EDGE2 6881 6880 -0.903028 -0.0760885 -1.53096 1 0 1 1 0 0 +EDGE2 6882 6881 -1.01127 0.0782721 0.035259 1 0 1 1 0 0 +EDGE2 6883 6882 -0.997052 -0.0223484 -0.0383921 1 0 1 1 0 0 +EDGE2 6884 6883 -1.05692 0.00345356 0.0263296 1 0 1 1 0 0 +EDGE2 6885 6884 -0.954236 -0.0666464 0.00728909 1 0 1 1 0 0 +EDGE2 6886 6885 -0.971764 -0.031858 -1.55973 1 0 1 1 0 0 +EDGE2 6887 6886 -0.897301 0.0214844 -0.0445588 1 0 1 1 0 0 +EDGE2 6888 6887 -0.938269 0.0398342 0.0132413 1 0 1 1 0 0 +EDGE2 6889 6888 -0.997242 -0.00086546 -0.0101877 1 0 1 1 0 0 +EDGE2 6889 6870 0.936165 -0.0391536 -3.12889 1 0 1 1 0 0 +EDGE2 6890 6889 -1.00405 0.0131946 -0.0118519 1 0 1 1 0 0 +EDGE2 6890 6871 -0.0196035 1.02439 1.57102 1 0 1 1 0 0 +EDGE2 6890 6870 -0.00985075 -0.0248935 -3.17114 1 0 1 1 0 0 +EDGE2 6890 6869 1.06352 0.0258585 -3.15032 1 0 1 1 0 0 +EDGE2 6891 6870 -1.13482 -0.0011195 -1.58019 1 0 1 1 0 0 +EDGE2 6891 6890 -1.01076 -0.0814897 1.55194 1 0 1 1 0 0 +EDGE2 6892 6891 -0.993942 0.081642 0.0318979 1 0 1 1 0 0 +EDGE2 6893 6892 -1.10378 0.0329814 0.0299208 1 0 1 1 0 0 +EDGE2 6894 6893 -1.03187 0.00956308 0.0110965 1 0 1 1 0 0 +EDGE2 6895 6894 -1.0442 0.0525595 0.0154567 1 0 1 1 0 0 +EDGE2 6896 6895 -1.04987 0.0111467 -1.54853 1 0 1 1 0 0 +EDGE2 6897 6896 -1.0662 0.0453219 -0.0194329 1 0 1 1 0 0 +EDGE2 6898 6897 -1.02594 -0.0974939 0.00506386 1 0 1 1 0 0 +EDGE2 6899 6898 -1.05413 -0.0552295 -0.00542424 1 0 1 1 0 0 +EDGE2 6900 6899 -1.02733 -0.101665 0.0073567 1 0 1 1 0 0 +EDGE2 6901 6900 -0.986991 -0.0175976 -1.58429 1 0 1 1 0 0 +EDGE2 6902 6901 -1.02784 0.044122 0.00651014 1 0 1 1 0 0 +EDGE2 6903 6902 -0.991784 -0.00719414 -0.016161 1 0 1 1 0 0 +EDGE2 6904 6825 0.963081 -0.046269 -3.12825 1 0 1 1 0 0 +EDGE2 6904 6865 0.939978 0.0226603 -3.16135 1 0 1 1 0 0 +EDGE2 6904 6903 -1.02082 -0.00835852 0.00861313 1 0 1 1 0 0 +EDGE2 6904 6805 0.960422 -0.052493 -3.14176 1 0 1 1 0 0 +EDGE2 6905 6866 -0.0502149 1.10632 1.58181 1 0 1 1 0 0 +EDGE2 6905 6824 1.00701 0.0449068 -3.14765 1 0 1 1 0 0 +EDGE2 6905 6864 0.939714 -0.00905088 -3.13313 1 0 1 1 0 0 +EDGE2 6905 6804 0.972512 0.023286 -3.12856 1 0 1 1 0 0 +EDGE2 6905 6825 -0.0418413 -0.0608514 -3.10147 1 0 1 1 0 0 +EDGE2 6905 6865 -0.0451647 -0.0495143 -3.15433 1 0 1 1 0 0 +EDGE2 6905 6826 0.113931 -1.05316 -1.55391 1 0 1 1 0 0 +EDGE2 6905 6904 -0.995816 -0.0336468 0.0153168 1 0 1 1 0 0 +EDGE2 6905 6805 0.0870933 -0.0190117 -3.14067 1 0 1 1 0 0 +EDGE2 6905 6806 0.00474511 -1.0518 -1.55804 1 0 1 1 0 0 +EDGE2 6906 6867 1.00588 -0.118691 0.0110609 1 0 1 1 0 0 +EDGE2 6906 6866 0.0298964 0.00222588 0.0331043 1 0 1 1 0 0 +EDGE2 6906 6905 -1.00968 -0.00183525 -1.57668 1 0 1 1 0 0 +EDGE2 6906 6825 -0.93748 0.0540464 1.58188 1 0 1 1 0 0 +EDGE2 6906 6865 -0.984381 0.0729517 1.54424 1 0 1 1 0 0 +EDGE2 6906 6805 -1.01503 -0.013199 1.5929 1 0 1 1 0 0 +EDGE2 6907 6867 0.00939407 0.0859091 0.0150836 1 0 1 1 0 0 +EDGE2 6907 6868 0.905308 -0.00725458 -0.0218211 1 0 1 1 0 0 +EDGE2 6907 6906 -0.999253 0.00153356 -0.000765435 1 0 1 1 0 0 +EDGE2 6907 6866 -0.911826 -0.023025 -0.021163 1 0 1 1 0 0 +EDGE2 6908 6867 -0.95906 0.0102414 0.0216748 1 0 1 1 0 0 +EDGE2 6908 6869 0.966651 -0.00423162 -0.0011751 1 0 1 1 0 0 +EDGE2 6908 6868 0.0674951 -0.0137834 0.00373227 1 0 1 1 0 0 +EDGE2 6908 6907 -1.0559 0.0339459 -0.0117738 1 0 1 1 0 0 +EDGE2 6909 6870 0.90076 0.0454038 0.017885 1 0 1 1 0 0 +EDGE2 6909 6890 0.924222 -0.0693674 -3.13591 1 0 1 1 0 0 +EDGE2 6909 6908 -1.04448 0.0723519 -0.0123014 1 0 1 1 0 0 +EDGE2 6909 6869 0.0420613 0.0586343 0.0186817 1 0 1 1 0 0 +EDGE2 6909 6868 -0.962044 -0.0503496 -0.0192244 1 0 1 1 0 0 +EDGE2 6910 6889 0.932106 0.0123981 -3.14838 1 0 1 1 0 0 +EDGE2 6910 6871 -0.033261 -1.06481 -1.59854 1 0 1 1 0 0 +EDGE2 6910 6870 0.0120851 0.0649761 0.0100655 1 0 1 1 0 0 +EDGE2 6910 6890 0.027949 0.00721076 -3.12252 1 0 1 1 0 0 +EDGE2 6910 6891 0.00105171 1.00854 1.58459 1 0 1 1 0 0 +EDGE2 6910 6909 -0.956425 -0.0265627 -0.0101108 1 0 1 1 0 0 +EDGE2 6910 6869 -1.05191 0.00179817 -0.0203516 1 0 1 1 0 0 +EDGE2 6911 6870 -0.997041 0.0406115 -1.52639 1 0 1 1 0 0 +EDGE2 6911 6890 -0.961108 -0.0346585 1.5913 1 0 1 1 0 0 +EDGE2 6911 6910 -1.00485 0.00136826 -1.56192 1 0 1 1 0 0 +EDGE2 6911 6892 0.917788 0.0725733 0.00961355 1 0 1 1 0 0 +EDGE2 6911 6891 -0.0179029 0.0421208 0.0388086 1 0 1 1 0 0 +EDGE2 6912 6911 -1.10697 0.0305918 -0.0115082 1 0 1 1 0 0 +EDGE2 6912 6892 -0.0277522 0.0283035 0.0208156 1 0 1 1 0 0 +EDGE2 6912 6891 -1.04496 0.0328163 -0.00467387 1 0 1 1 0 0 +EDGE2 6912 6893 0.956813 0.00781727 -0.0187226 1 0 1 1 0 0 +EDGE2 6913 6892 -1.03434 -0.00628339 0.006259 1 0 1 1 0 0 +EDGE2 6913 6912 -1.02835 -0.0267184 -0.00779457 1 0 1 1 0 0 +EDGE2 6913 6893 -0.0103137 0.0168309 0.0140962 1 0 1 1 0 0 +EDGE2 6913 6894 0.980829 -0.0576524 -0.00461909 1 0 1 1 0 0 +EDGE2 6914 6913 -0.975363 -0.0254536 0.00479712 1 0 1 1 0 0 +EDGE2 6914 6893 -0.979302 0.0712472 -0.0286643 1 0 1 1 0 0 +EDGE2 6914 6894 -0.0339341 0.0394061 0.0170527 1 0 1 1 0 0 +EDGE2 6914 6895 1.01369 0.0503772 -0.0368324 1 0 1 1 0 0 +EDGE2 6915 6894 -1.04851 -0.0105153 0.0210187 1 0 1 1 0 0 +EDGE2 6915 6914 -1.01459 -0.0104504 0.00793546 1 0 1 1 0 0 +EDGE2 6915 6895 -0.0328933 0.0701217 0.00924976 1 0 1 1 0 0 +EDGE2 6915 6896 -0.138372 0.955693 1.58126 1 0 1 1 0 0 +EDGE2 6916 6915 -0.978983 0.0648811 1.53558 1 0 1 1 0 0 +EDGE2 6916 6895 -0.921253 0.0487397 1.54096 1 0 1 1 0 0 +EDGE2 6917 6916 -1.00847 -0.0621948 0.0119389 1 0 1 1 0 0 +EDGE2 6918 6917 -1.0853 0.0376139 -0.0490891 1 0 1 1 0 0 +EDGE2 6919 6918 -1.01461 0.0390694 -0.0210409 1 0 1 1 0 0 +EDGE2 6920 6919 -1.07235 0.0858061 -0.0176153 1 0 1 1 0 0 +EDGE2 6921 6920 -1.07944 -0.0169158 -1.53255 1 0 1 1 0 0 +EDGE2 6922 6921 -0.954019 0.0358978 0.00494623 1 0 1 1 0 0 +EDGE2 6923 6922 -0.982753 0.0272373 0.0353044 1 0 1 1 0 0 +EDGE2 6924 6923 -0.941289 0.00806442 0.00623541 1 0 1 1 0 0 +EDGE2 6925 6924 -0.932992 0.0170983 -0.0200314 1 0 1 1 0 0 +EDGE2 6926 6925 -1.01718 0.0175469 -1.5786 1 0 1 1 0 0 +EDGE2 6927 6926 -1.02936 0.033602 -0.018634 1 0 1 1 0 0 +EDGE2 6928 6927 -1.00488 -0.0210106 0.00686654 1 0 1 1 0 0 +EDGE2 6929 6928 -1.03209 0.101198 -0.0268513 1 0 1 1 0 0 +EDGE2 6930 6929 -1.06975 0.0559025 -0.0105756 1 0 1 1 0 0 +EDGE2 6931 6930 -1.00995 0.03624 1.58338 1 0 1 1 0 0 +EDGE2 6932 6931 -0.987275 -0.0285565 -0.0163829 1 0 1 1 0 0 +EDGE2 6933 6932 -1.04179 -0.0349524 -0.00932975 1 0 1 1 0 0 +EDGE2 6934 6933 -0.986053 -0.0114849 0.0227618 1 0 1 1 0 0 +EDGE2 6935 6934 -1.00548 0.122881 0.0122585 1 0 1 1 0 0 +EDGE2 6936 6935 -1.15143 0.0551845 -1.55077 1 0 1 1 0 0 +EDGE2 6937 6936 -1.10673 -0.0328587 0.00700038 1 0 1 1 0 0 +EDGE2 6938 6937 -0.97124 -0.060463 -0.0273382 1 0 1 1 0 0 +EDGE2 6939 6938 -0.950743 0.0551085 -0.0124507 1 0 1 1 0 0 +EDGE2 6940 6939 -1.08106 0.00164804 0.012963 1 0 1 1 0 0 +EDGE2 6941 6940 -0.964415 0.0494283 -1.59315 1 0 1 1 0 0 +EDGE2 6942 6941 -0.947998 -0.0370224 0.00512268 1 0 1 1 0 0 +EDGE2 6943 6942 -1.09225 0.0577206 -0.0298611 1 0 1 1 0 0 +EDGE2 6944 6943 -1.02413 0.0617899 0.00576126 1 0 1 1 0 0 +EDGE2 6945 6944 -0.995572 0.10168 0.0331821 1 0 1 1 0 0 +EDGE2 6946 6945 -1.00856 -0.00902503 -1.55316 1 0 1 1 0 0 +EDGE2 6947 6946 -0.934982 0.0667726 0.00446471 1 0 1 1 0 0 +EDGE2 6948 6947 -0.98676 -0.0389927 0.0223597 1 0 1 1 0 0 +EDGE2 6949 6930 1.01274 -0.0151204 -3.14687 1 0 1 1 0 0 +EDGE2 6949 6948 -0.994197 -0.00744961 0.010373 1 0 1 1 0 0 +EDGE2 6950 6929 1.08381 -0.0150034 -3.11987 1 0 1 1 0 0 +EDGE2 6950 6931 -0.00789217 0.991726 1.56392 1 0 1 1 0 0 +EDGE2 6950 6930 -0.0409806 -0.0116146 -3.17421 1 0 1 1 0 0 +EDGE2 6950 6949 -1.05515 -0.0254275 -0.0228311 1 0 1 1 0 0 +EDGE2 6951 6930 -0.97482 -0.0569359 -1.59527 1 0 1 1 0 0 +EDGE2 6951 6950 -0.959188 0.0135209 1.51914 1 0 1 1 0 0 +EDGE2 6952 6951 -0.911717 -0.116452 0.0439353 1 0 1 1 0 0 +EDGE2 6953 6952 -1.02067 -0.0373452 0.00348226 1 0 1 1 0 0 +EDGE2 6954 6915 1.08955 -0.0327682 -3.17786 1 0 1 1 0 0 +EDGE2 6954 6895 0.90658 -0.0783993 -3.1493 1 0 1 1 0 0 +EDGE2 6954 6953 -1.02861 0.0421554 -0.0254398 1 0 1 1 0 0 +EDGE2 6955 6916 -0.0168712 1.09224 1.55385 1 0 1 1 0 0 +EDGE2 6955 6894 1.042 0.0413011 -3.12714 1 0 1 1 0 0 +EDGE2 6955 6914 0.956523 -0.0504939 -3.13733 1 0 1 1 0 0 +EDGE2 6955 6954 -1.05017 -0.0139464 0.0081905 1 0 1 1 0 0 +EDGE2 6955 6915 -0.0236148 -0.0636217 -3.16592 1 0 1 1 0 0 +EDGE2 6955 6895 0.0863861 0.0042761 -3.10185 1 0 1 1 0 0 +EDGE2 6955 6896 0.017795 -0.990818 -1.58148 1 0 1 1 0 0 +EDGE2 6956 6916 -0.0194274 -0.0415026 -0.0466619 1 0 1 1 0 0 +EDGE2 6956 6917 0.923482 -0.0267518 -0.0438423 1 0 1 1 0 0 +EDGE2 6956 6915 -1.01003 -0.0139037 1.56583 1 0 1 1 0 0 +EDGE2 6956 6955 -0.982035 -0.018302 -1.5912 1 0 1 1 0 0 +EDGE2 6956 6895 -1.05299 -0.0875589 1.60165 1 0 1 1 0 0 +EDGE2 6957 6916 -1.02513 -0.0212257 0.00232191 1 0 1 1 0 0 +EDGE2 6957 6918 0.990661 0.0487719 -0.00383611 1 0 1 1 0 0 +EDGE2 6957 6917 -0.132987 0.00646111 0.0213389 1 0 1 1 0 0 +EDGE2 6957 6956 -0.972501 -0.0740021 -0.0119581 1 0 1 1 0 0 +EDGE2 6958 6919 1.00336 0.0506341 -0.000700256 1 0 1 1 0 0 +EDGE2 6958 6918 0.0434969 0.0456221 -0.00660056 1 0 1 1 0 0 +EDGE2 6958 6917 -0.942225 -0.0183191 -0.0393286 1 0 1 1 0 0 +EDGE2 6958 6957 -1.05224 -4.73274e-05 0.0319667 1 0 1 1 0 0 +EDGE2 6959 6920 0.950667 0.0115272 -0.00923274 1 0 1 1 0 0 +EDGE2 6959 6958 -1.05014 0.0963642 0.0035494 1 0 1 1 0 0 +EDGE2 6959 6919 -0.041807 -0.0788188 0.0469483 1 0 1 1 0 0 +EDGE2 6959 6918 -0.985788 -0.0483949 -0.0044002 1 0 1 1 0 0 +EDGE2 6960 6920 0.022525 0.028986 0.00540751 1 0 1 1 0 0 +EDGE2 6960 6921 0.0463122 0.951895 1.56039 1 0 1 1 0 0 +EDGE2 6960 6959 -0.982569 -0.0419775 0.00599727 1 0 1 1 0 0 +EDGE2 6960 6919 -0.962033 -0.0316939 -0.00914566 1 0 1 1 0 0 +EDGE2 6961 6920 -0.955157 0.048739 1.54812 1 0 1 1 0 0 +EDGE2 6961 6960 -0.996311 -0.00767818 1.55094 1 0 1 1 0 0 +EDGE2 6962 6961 -0.930528 -0.0657597 -0.0299545 1 0 1 1 0 0 +EDGE2 6963 6962 -0.934161 0.0394567 0.0163969 1 0 1 1 0 0 +EDGE2 6964 6885 0.95823 -0.0760211 -3.10764 1 0 1 1 0 0 +EDGE2 6964 6963 -1.02145 -0.0990096 0.00626732 1 0 1 1 0 0 +EDGE2 6965 6886 -0.00899489 -1.04406 -1.57706 1 0 1 1 0 0 +EDGE2 6965 6885 0.0990768 -0.0671428 -3.14806 1 0 1 1 0 0 +EDGE2 6965 6884 1.09006 0.0136079 -3.14709 1 0 1 1 0 0 +EDGE2 6965 6964 -1.00082 0.0089012 -0.00172605 1 0 1 1 0 0 +EDGE2 6966 6886 0.114655 0.02182 0.00597172 1 0 1 1 0 0 +EDGE2 6966 6885 -1.0529 -0.0508118 -1.61452 1 0 1 1 0 0 +EDGE2 6966 6965 -0.975081 -0.0154167 1.51161 1 0 1 1 0 0 +EDGE2 6966 6887 0.982556 -0.0262254 0.061171 1 0 1 1 0 0 +EDGE2 6967 6886 -1.08194 -0.0152566 0.00161622 1 0 1 1 0 0 +EDGE2 6967 6966 -0.972643 -0.0561214 0.00176329 1 0 1 1 0 0 +EDGE2 6967 6887 -0.0835133 0.023732 0.011041 1 0 1 1 0 0 +EDGE2 6967 6888 1.05384 0.0125706 0.0610611 1 0 1 1 0 0 +EDGE2 6968 6887 -1.04803 -0.0369573 -0.0273297 1 0 1 1 0 0 +EDGE2 6968 6967 -0.937498 -0.051215 -0.0213978 1 0 1 1 0 0 +EDGE2 6968 6888 0.0761195 -0.0190373 -0.02276 1 0 1 1 0 0 +EDGE2 6968 6889 1.04076 0.0377347 0.0476341 1 0 1 1 0 0 +EDGE2 6969 6968 -1.05676 0.0176437 -0.000851924 1 0 1 1 0 0 +EDGE2 6969 6888 -1.00357 -0.0211146 -0.0251897 1 0 1 1 0 0 +EDGE2 6969 6889 -0.049376 -0.00544391 0.0167081 1 0 1 1 0 0 +EDGE2 6969 6870 0.930052 -0.0278288 -3.1063 1 0 1 1 0 0 +EDGE2 6969 6890 0.938357 -0.0662462 -0.0132786 1 0 1 1 0 0 +EDGE2 6969 6910 1.01767 -0.000252734 -3.14581 1 0 1 1 0 0 +EDGE2 6970 6969 -1.05339 0.00473708 -0.0219263 1 0 1 1 0 0 +EDGE2 6970 6889 -0.952854 -0.0278205 -0.025499 1 0 1 1 0 0 +EDGE2 6970 6911 0.00990752 -0.969869 -1.57176 1 0 1 1 0 0 +EDGE2 6970 6871 -0.00672785 0.986411 1.59874 1 0 1 1 0 0 +EDGE2 6970 6870 -0.0160265 -0.0432258 -3.16433 1 0 1 1 0 0 +EDGE2 6970 6890 -0.0869737 0.093625 -0.0212972 1 0 1 1 0 0 +EDGE2 6970 6910 0.0336213 0.0362396 -3.13897 1 0 1 1 0 0 +EDGE2 6970 6891 -0.0209072 -0.907912 -1.55709 1 0 1 1 0 0 +EDGE2 6970 6909 1.01097 0.0394012 -3.13284 1 0 1 1 0 0 +EDGE2 6970 6869 0.990673 0.0691995 -3.15038 1 0 1 1 0 0 +EDGE2 6971 6970 -0.967659 -0.0584338 -1.60404 1 0 1 1 0 0 +EDGE2 6971 6871 0.0191256 -0.00234505 0.000896945 1 0 1 1 0 0 +EDGE2 6971 6872 1.03612 0.0446069 0.0289803 1 0 1 1 0 0 +EDGE2 6971 6870 -0.943386 -0.04285 1.5668 1 0 1 1 0 0 +EDGE2 6971 6890 -1.04335 0.0485914 -1.58386 1 0 1 1 0 0 +EDGE2 6971 6910 -1.104 0.0163954 1.58318 1 0 1 1 0 0 +EDGE2 6972 6873 0.940279 0.0794562 -0.0208323 1 0 1 1 0 0 +EDGE2 6972 6871 -0.991975 -0.0218445 0.00940249 1 0 1 1 0 0 +EDGE2 6972 6971 -0.902808 0.00943607 0.0227446 1 0 1 1 0 0 +EDGE2 6972 6872 -0.00390764 -0.105845 0.0165459 1 0 1 1 0 0 +EDGE2 6973 6972 -0.948528 -0.0523376 0.0011077 1 0 1 1 0 0 +EDGE2 6973 6874 1.02414 -0.0670635 -0.0164608 1 0 1 1 0 0 +EDGE2 6973 6873 -0.0499112 -0.0350436 0.0508711 1 0 1 1 0 0 +EDGE2 6973 6872 -1.01256 0.0150181 0.00469656 1 0 1 1 0 0 +EDGE2 6974 6795 1.01233 0.00258474 -3.10259 1 0 1 1 0 0 +EDGE2 6974 6875 1.00424 0.0384398 -0.00472157 1 0 1 1 0 0 +EDGE2 6974 6775 1.0554 -0.0191295 -3.1224 1 0 1 1 0 0 +EDGE2 6974 6973 -0.951471 0.00764858 0.0273859 1 0 1 1 0 0 +EDGE2 6974 6874 0.0429466 0.0764161 -0.000723374 1 0 1 1 0 0 +EDGE2 6974 6873 -0.948379 0.00714287 -0.0147601 1 0 1 1 0 0 +EDGE2 6975 6876 0.0790115 0.991018 1.54258 1 0 1 1 0 0 +EDGE2 6975 6774 0.894354 -0.0361815 -3.1627 1 0 1 1 0 0 +EDGE2 6975 6794 1.00025 -0.0336657 -3.14498 1 0 1 1 0 0 +EDGE2 6975 6974 -0.972767 -0.0405851 -0.010467 1 0 1 1 0 0 +EDGE2 6975 6795 -0.0101914 -0.0229248 -3.13602 1 0 1 1 0 0 +EDGE2 6975 6875 -0.0749341 0.131595 0.0271251 1 0 1 1 0 0 +EDGE2 6975 6775 -0.155458 0.010329 -3.14848 1 0 1 1 0 0 +EDGE2 6975 6874 -1.02635 -0.0352742 0.0077111 1 0 1 1 0 0 +EDGE2 6975 6796 -0.0586358 -0.955269 -1.62467 1 0 1 1 0 0 +EDGE2 6975 6776 -0.0508443 -1.08242 -1.5724 1 0 1 1 0 0 +EDGE2 6976 6876 -0.0362608 0.0589895 -0.0345991 1 0 1 1 0 0 +EDGE2 6976 6877 0.862158 0.0452457 -0.0179051 1 0 1 1 0 0 +EDGE2 6976 6795 -0.92237 0.0208932 1.56061 1 0 1 1 0 0 +EDGE2 6976 6875 -1.00848 -0.059328 -1.5769 1 0 1 1 0 0 +EDGE2 6976 6975 -1.07447 -0.0777886 -1.59523 1 0 1 1 0 0 +EDGE2 6976 6775 -1.01917 0.0876562 1.59348 1 0 1 1 0 0 +EDGE2 6977 6876 -0.946765 0.0217088 -0.0116873 1 0 1 1 0 0 +EDGE2 6977 6877 0.00355422 -0.0562922 -0.0394499 1 0 1 1 0 0 +EDGE2 6977 6878 0.994979 -0.00589075 -0.00703312 1 0 1 1 0 0 +EDGE2 6977 6976 -0.886266 0.0566184 -0.029221 1 0 1 1 0 0 +EDGE2 6978 6879 1.04021 0.0149055 -0.0524564 1 0 1 1 0 0 +EDGE2 6978 6877 -1.11099 -0.0440776 0.0486665 1 0 1 1 0 0 +EDGE2 6978 6977 -0.974521 0.0259881 -0.010915 1 0 1 1 0 0 +EDGE2 6978 6878 -0.1141 -0.0151166 0.00260762 1 0 1 1 0 0 +EDGE2 6979 6880 0.987494 -0.0206474 -0.0105586 1 0 1 1 0 0 +EDGE2 6979 6978 -0.910168 0.0584337 -0.0242356 1 0 1 1 0 0 +EDGE2 6979 6879 0.0266649 0.064902 -0.0220454 1 0 1 1 0 0 +EDGE2 6979 6878 -0.951562 -0.00319754 0.000807522 1 0 1 1 0 0 +EDGE2 6980 6979 -0.970412 0.026267 0.0142408 1 0 1 1 0 0 +EDGE2 6980 6880 0.0133618 0.0130998 -0.00562269 1 0 1 1 0 0 +EDGE2 6980 6881 -0.0477025 0.977215 1.55599 1 0 1 1 0 0 +EDGE2 6980 6879 -0.950788 0.0119113 -0.0301853 1 0 1 1 0 0 +EDGE2 6981 6980 -0.93582 -0.00804575 1.57607 1 0 1 1 0 0 +EDGE2 6981 6880 -0.956188 0.0257014 1.56215 1 0 1 1 0 0 +EDGE2 6982 6981 -1.0426 0.0556854 0.024232 1 0 1 1 0 0 +EDGE2 6983 6982 -1.03624 -0.148047 -0.00411867 1 0 1 1 0 0 +EDGE2 6984 6983 -0.945301 -0.0144487 -0.0273141 1 0 1 1 0 0 +EDGE2 6985 6984 -1.09829 -0.0138132 0.00131831 1 0 1 1 0 0 +EDGE2 6986 6985 -0.926014 -0.127794 -1.57424 1 0 1 1 0 0 +EDGE2 6987 6986 -1.00277 -0.0585382 -0.0327707 1 0 1 1 0 0 +EDGE2 6988 6987 -0.936724 -0.0291748 -0.00178617 1 0 1 1 0 0 +EDGE2 6989 6988 -1.06684 -0.00675619 0.0184785 1 0 1 1 0 0 +EDGE2 6990 6989 -1.01116 -0.0312504 -0.0139623 1 0 1 1 0 0 +EDGE2 6991 6990 -0.938435 0.0486486 1.55754 1 0 1 1 0 0 +EDGE2 6992 6991 -1.0484 0.0153691 -0.0248302 1 0 1 1 0 0 +EDGE2 6993 6992 -1.09986 0.116696 -0.0432903 1 0 1 1 0 0 +EDGE2 6994 6993 -1.0663 -0.000125288 0.033188 1 0 1 1 0 0 +EDGE2 6995 6994 -1.01673 0.000700922 -0.00365712 1 0 1 1 0 0 +EDGE2 6996 6995 -1.03261 -0.00865619 1.55457 1 0 1 1 0 0 +EDGE2 6997 6996 -0.966386 0.090622 -0.0139471 1 0 1 1 0 0 +EDGE2 6998 6997 -1.03967 -0.11272 -0.0109436 1 0 1 1 0 0 +EDGE2 6999 6998 -0.991499 0.0039702 0.0221677 1 0 1 1 0 0 +EDGE2 7000 6999 -0.914988 0.00103078 -0.0261417 1 0 1 1 0 0 +EDGE2 7001 7000 -0.950272 -0.00518723 -1.55852 1 0 1 1 0 0 +EDGE2 7002 7001 -1.07639 0.0409521 -0.00872493 1 0 1 1 0 0 +EDGE2 7003 7002 -1.05868 0.00508698 0.00301099 1 0 1 1 0 0 +EDGE2 7004 7003 -1.02477 -0.0251036 -0.00359483 1 0 1 1 0 0 +EDGE2 7005 7004 -0.945891 -0.0186505 0.0120892 1 0 1 1 0 0 +EDGE2 7006 7005 -1.07276 -0.00274022 -1.57025 1 0 1 1 0 0 +EDGE2 7007 7006 -0.951148 0.0762679 -0.0321807 1 0 1 1 0 0 +EDGE2 7008 7007 -0.98095 0.0357657 0.0194568 1 0 1 1 0 0 +EDGE2 7009 7008 -1.00038 -0.00157911 0.0183403 1 0 1 1 0 0 +EDGE2 7010 7009 -1.02714 0.014737 -0.045947 1 0 1 1 0 0 +EDGE2 7011 7010 -1.03682 0.0696201 -1.58988 1 0 1 1 0 0 +EDGE2 7012 7011 -0.964927 0.0589713 -0.0179124 1 0 1 1 0 0 +EDGE2 7013 7012 -0.986912 -0.00922319 0.0148571 1 0 1 1 0 0 +EDGE2 7014 7013 -0.955428 -0.0280854 -0.00906926 1 0 1 1 0 0 +EDGE2 7014 6995 1.03314 -0.0129244 -3.15434 1 0 1 1 0 0 +EDGE2 7015 7014 -1.01786 -0.0146477 0.00754803 1 0 1 1 0 0 +EDGE2 7015 6995 0.0134603 0.0171705 -3.16338 1 0 1 1 0 0 +EDGE2 7015 6994 0.87866 -0.105129 -3.12427 1 0 1 1 0 0 +EDGE2 7015 6996 0.0123327 1.09302 1.60368 1 0 1 1 0 0 +EDGE2 7016 6995 -0.952294 -0.0669765 1.55678 1 0 1 1 0 0 +EDGE2 7016 7015 -1.02196 -0.0139802 -1.56584 1 0 1 1 0 0 +EDGE2 7016 6996 -0.0231409 0.00354893 -0.00272493 1 0 1 1 0 0 +EDGE2 7016 6997 1.09967 -0.113014 -0.00062182 1 0 1 1 0 0 +EDGE2 7017 7016 -1.03351 -0.0853158 0.0127197 1 0 1 1 0 0 +EDGE2 7017 6996 -0.909947 0.0253406 0.0546282 1 0 1 1 0 0 +EDGE2 7017 6997 -0.0547322 0.000950229 -0.00525911 1 0 1 1 0 0 +EDGE2 7017 6998 0.939655 0.0146546 -0.0094084 1 0 1 1 0 0 +EDGE2 7018 6999 1.05048 0.0324266 -0.0356358 1 0 1 1 0 0 +EDGE2 7018 6997 -1.03997 0.0436196 -0.00321932 1 0 1 1 0 0 +EDGE2 7018 7017 -1.09904 -0.0117234 -0.0379539 1 0 1 1 0 0 +EDGE2 7018 6998 -0.067109 -0.0999598 0.0279734 1 0 1 1 0 0 +EDGE2 7019 6999 -0.0226695 0.0200412 0.0249448 1 0 1 1 0 0 +EDGE2 7019 6998 -0.934674 0.0611244 0.0117649 1 0 1 1 0 0 +EDGE2 7019 7018 -1.00754 0.0342003 -0.0491771 1 0 1 1 0 0 +EDGE2 7019 7000 1.03722 0.00354997 -0.0301011 1 0 1 1 0 0 +EDGE2 7020 6999 -1.10765 0.0415665 -0.0400265 1 0 1 1 0 0 +EDGE2 7020 7019 -0.978168 0.035688 -0.0101602 1 0 1 1 0 0 +EDGE2 7020 7001 -0.0416706 0.936014 1.57737 1 0 1 1 0 0 +EDGE2 7020 7000 -0.0616798 0.0958192 0.0101824 1 0 1 1 0 0 +EDGE2 7021 7002 1.04456 -0.0502528 0.0234708 1 0 1 1 0 0 +EDGE2 7021 7001 -0.0278578 0.0181399 -0.0252894 1 0 1 1 0 0 +EDGE2 7021 7000 -1.00305 -0.0084154 -1.56961 1 0 1 1 0 0 +EDGE2 7021 7020 -0.963921 0.0546116 -1.56786 1 0 1 1 0 0 +EDGE2 7022 7003 0.981626 -0.0338009 -0.0248117 1 0 1 1 0 0 +EDGE2 7022 7002 3.2498e-05 -0.0557268 -0.0128317 1 0 1 1 0 0 +EDGE2 7022 7001 -1.05612 -0.0677512 0.0111273 1 0 1 1 0 0 +EDGE2 7022 7021 -1.03654 -0.0393655 0.0200353 1 0 1 1 0 0 +EDGE2 7023 7004 1.00756 -0.0267876 0.0181647 1 0 1 1 0 0 +EDGE2 7023 7003 0.11843 -0.00957694 0.0020945 1 0 1 1 0 0 +EDGE2 7023 7002 -1.04373 -0.0202556 -0.0219689 1 0 1 1 0 0 +EDGE2 7023 7022 -0.948803 -0.091817 0.0142932 1 0 1 1 0 0 +EDGE2 7024 7005 0.985773 0.117165 0.0122524 1 0 1 1 0 0 +EDGE2 7024 7004 0.0224069 0.0298507 -0.0473253 1 0 1 1 0 0 +EDGE2 7024 7003 -1.07627 0.0152124 -0.016945 1 0 1 1 0 0 +EDGE2 7024 7023 -1.11883 0.0287378 0.0258994 1 0 1 1 0 0 +EDGE2 7025 7006 0.0360419 0.998705 1.56593 1 0 1 1 0 0 +EDGE2 7025 7005 -0.0589325 0.105563 -0.000489971 1 0 1 1 0 0 +EDGE2 7025 7024 -1.05513 -0.0599366 -0.0271211 1 0 1 1 0 0 +EDGE2 7025 7004 -0.894224 0.00873133 0.0161941 1 0 1 1 0 0 +EDGE2 7026 7007 1.00625 -0.0185908 -0.0282592 1 0 1 1 0 0 +EDGE2 7026 7006 0.00758216 -0.0178949 -0.0296164 1 0 1 1 0 0 +EDGE2 7026 7005 -1.04729 0.0538348 -1.55089 1 0 1 1 0 0 +EDGE2 7026 7025 -1.07972 0.0601829 -1.55217 1 0 1 1 0 0 +EDGE2 7027 7007 0.0530114 -0.0427271 -0.0180721 1 0 1 1 0 0 +EDGE2 7027 7008 0.91194 -0.0151285 0.0467291 1 0 1 1 0 0 +EDGE2 7027 7006 -0.969219 0.0403771 0.0134545 1 0 1 1 0 0 +EDGE2 7027 7026 -1.01864 0.012722 -0.0237802 1 0 1 1 0 0 +EDGE2 7028 7009 0.940739 0.100249 0.000257463 1 0 1 1 0 0 +EDGE2 7028 7007 -0.892764 -0.0880242 0.00344668 1 0 1 1 0 0 +EDGE2 7028 7008 0.0476444 -0.0652052 -0.00716779 1 0 1 1 0 0 +EDGE2 7028 7027 -0.997993 -0.0549394 -0.00564057 1 0 1 1 0 0 +EDGE2 7029 7010 1.05569 -0.00280078 -0.0119773 1 0 1 1 0 0 +EDGE2 7029 7009 -0.00940892 0.00989657 0.0199197 1 0 1 1 0 0 +EDGE2 7029 7008 -0.970307 -0.115171 0.0166359 1 0 1 1 0 0 +EDGE2 7029 7028 -1.04551 -0.0392029 -0.0132269 1 0 1 1 0 0 +EDGE2 7030 7010 0.0346682 -0.0236963 0.014801 1 0 1 1 0 0 +EDGE2 7030 7029 -0.962175 -0.0648995 0.0133102 1 0 1 1 0 0 +EDGE2 7030 7009 -0.998014 0.0495257 0.00721129 1 0 1 1 0 0 +EDGE2 7030 7011 0.0962617 1.10538 1.54226 1 0 1 1 0 0 +EDGE2 7031 7010 -0.962863 0.0525767 -1.59196 1 0 1 1 0 0 +EDGE2 7031 7030 -0.956118 0.0221651 -1.57816 1 0 1 1 0 0 +EDGE2 7031 7011 0.0325244 0.0692526 -0.0385646 1 0 1 1 0 0 +EDGE2 7031 7012 0.901834 -0.0188481 -0.0194489 1 0 1 1 0 0 +EDGE2 7032 7031 -0.982543 -0.0367615 0.00308206 1 0 1 1 0 0 +EDGE2 7032 7011 -1.05361 -0.0309877 -0.0091966 1 0 1 1 0 0 +EDGE2 7032 7012 -0.0431692 0.0369125 0.0159452 1 0 1 1 0 0 +EDGE2 7032 7013 1.06945 0.0419306 0.0188081 1 0 1 1 0 0 +EDGE2 7033 7032 -0.999467 0.00272759 0.0151957 1 0 1 1 0 0 +EDGE2 7033 7012 -1.01567 -0.0147209 -0.00205898 1 0 1 1 0 0 +EDGE2 7033 7013 -0.029485 -0.0560148 -0.0279074 1 0 1 1 0 0 +EDGE2 7033 7014 1.01255 -0.0399575 0.0131004 1 0 1 1 0 0 +EDGE2 7034 7033 -1.01974 0.0256619 7.09278e-05 1 0 1 1 0 0 +EDGE2 7034 7013 -1.01465 0.0157345 0.0370394 1 0 1 1 0 0 +EDGE2 7034 7014 0.0398409 0.0938111 0.0284202 1 0 1 1 0 0 +EDGE2 7034 6995 1.04102 0.0515553 -3.17342 1 0 1 1 0 0 +EDGE2 7034 7015 1.00177 0.0491272 -0.00359788 1 0 1 1 0 0 +EDGE2 7035 7034 -0.932579 -0.0286213 0.00215579 1 0 1 1 0 0 +EDGE2 7035 7014 -1.02739 0.00583328 0.014333 1 0 1 1 0 0 +EDGE2 7035 6995 -0.0345716 -0.0279692 -3.13609 1 0 1 1 0 0 +EDGE2 7035 7015 -0.0084447 0.0100923 -0.0356186 1 0 1 1 0 0 +EDGE2 7035 6994 1.02221 -0.0466942 -3.13626 1 0 1 1 0 0 +EDGE2 7035 7016 -0.0161103 1.01266 1.59044 1 0 1 1 0 0 +EDGE2 7035 6996 -0.0422568 1.01162 1.60549 1 0 1 1 0 0 +EDGE2 7036 6995 -0.936317 0.136652 1.57906 1 0 1 1 0 0 +EDGE2 7036 7035 -1.03927 0.00439543 -1.55069 1 0 1 1 0 0 +EDGE2 7036 7015 -0.99588 -0.0801551 -1.56817 1 0 1 1 0 0 +EDGE2 7036 7016 0.0106259 -0.0820522 0.0116202 1 0 1 1 0 0 +EDGE2 7036 6996 0.0355111 0.00330937 0.0109423 1 0 1 1 0 0 +EDGE2 7036 6997 0.985413 -0.00694777 0.00793887 1 0 1 1 0 0 +EDGE2 7036 7017 1.09477 0.0259391 -0.00802999 1 0 1 1 0 0 +EDGE2 7037 7016 -0.991082 -0.0401732 0.00735747 1 0 1 1 0 0 +EDGE2 7037 7036 -0.984259 0.0315389 -0.00598296 1 0 1 1 0 0 +EDGE2 7037 6996 -1.00933 0.000494837 -0.0201897 1 0 1 1 0 0 +EDGE2 7037 6997 -0.017128 0.00898281 0.00572613 1 0 1 1 0 0 +EDGE2 7037 7017 0.00889602 -0.00855952 0.0325142 1 0 1 1 0 0 +EDGE2 7037 6998 0.960783 -0.0217917 -0.00341991 1 0 1 1 0 0 +EDGE2 7037 7018 1.0072 -0.0320667 -0.0207058 1 0 1 1 0 0 +EDGE2 7038 6999 0.952535 0.0208972 -0.017558 1 0 1 1 0 0 +EDGE2 7038 6997 -1.0314 0.00638167 0.0128683 1 0 1 1 0 0 +EDGE2 7038 7017 -1.02659 -0.0557733 -0.0258501 1 0 1 1 0 0 +EDGE2 7038 7037 -0.964897 -0.0620593 -0.0328329 1 0 1 1 0 0 +EDGE2 7038 6998 -0.0689573 0.0378398 0.0117538 1 0 1 1 0 0 +EDGE2 7038 7018 -0.0549851 -0.00518071 0.0148754 1 0 1 1 0 0 +EDGE2 7038 7019 0.888269 -0.0353096 -0.00364041 1 0 1 1 0 0 +EDGE2 7039 6999 0.0630443 0.0263792 0.0269015 1 0 1 1 0 0 +EDGE2 7039 7038 -1.05737 -0.0539368 0.0026365 1 0 1 1 0 0 +EDGE2 7039 6998 -1.13393 -0.049352 -0.013715 1 0 1 1 0 0 +EDGE2 7039 7018 -1.06812 0.0458174 0.00687499 1 0 1 1 0 0 +EDGE2 7039 7019 -0.0274487 0.0677148 -0.00811188 1 0 1 1 0 0 +EDGE2 7039 7000 1.08091 -0.120021 0.00621844 1 0 1 1 0 0 +EDGE2 7039 7020 1.0216 0.0762403 -0.031044 1 0 1 1 0 0 +EDGE2 7040 6999 -0.974377 0.0944643 -0.011542 1 0 1 1 0 0 +EDGE2 7040 7039 -0.980689 -0.000792005 -0.00169851 1 0 1 1 0 0 +EDGE2 7040 7019 -0.989811 -0.07826 -0.0117817 1 0 1 1 0 0 +EDGE2 7040 7001 0.0438465 0.967002 1.59771 1 0 1 1 0 0 +EDGE2 7040 7021 0.0497231 1.00857 1.5602 1 0 1 1 0 0 +EDGE2 7040 7000 0.0569685 0.0419562 0.00739392 1 0 1 1 0 0 +EDGE2 7040 7020 -0.0998601 -0.0953646 0.00838418 1 0 1 1 0 0 +EDGE2 7041 7040 -1.00603 0.0516753 -1.59957 1 0 1 1 0 0 +EDGE2 7041 7002 1.01203 -0.00444887 0.0220222 1 0 1 1 0 0 +EDGE2 7041 7022 0.988646 0.0728271 0.0118759 1 0 1 1 0 0 +EDGE2 7041 7001 -0.0373645 0.0449095 -0.0180975 1 0 1 1 0 0 +EDGE2 7041 7021 0.0547992 -0.0316375 0.032437 1 0 1 1 0 0 +EDGE2 7041 7000 -1.01983 0.0399107 -1.54643 1 0 1 1 0 0 +EDGE2 7041 7020 -1.07047 0.0598504 -1.57772 1 0 1 1 0 0 +EDGE2 7042 7003 1.04358 0.0336287 -0.0332733 1 0 1 1 0 0 +EDGE2 7042 7023 1.02516 -0.0336943 0.0115339 1 0 1 1 0 0 +EDGE2 7042 7041 -1.03382 0.0485624 0.0102266 1 0 1 1 0 0 +EDGE2 7042 7002 -0.0102915 -0.0219641 0.0190982 1 0 1 1 0 0 +EDGE2 7042 7022 0.0687893 -0.0414534 0.0117556 1 0 1 1 0 0 +EDGE2 7042 7001 -1.03901 0.0494572 -0.00620533 1 0 1 1 0 0 +EDGE2 7042 7021 -0.920147 0.0406242 -0.0171067 1 0 1 1 0 0 +EDGE2 7043 7042 -1.11722 -0.0438089 0.00808642 1 0 1 1 0 0 +EDGE2 7043 7024 0.963789 -0.0832891 0.0285143 1 0 1 1 0 0 +EDGE2 7043 7004 0.934068 -0.0534436 0.0123226 1 0 1 1 0 0 +EDGE2 7043 7003 0.0254213 0.0354446 0.0265269 1 0 1 1 0 0 +EDGE2 7043 7023 0.0758894 0.0790106 0.043647 1 0 1 1 0 0 +EDGE2 7043 7002 -0.988091 -0.0170247 0.0116835 1 0 1 1 0 0 +EDGE2 7043 7022 -1.03703 0.00471421 -0.00735059 1 0 1 1 0 0 +EDGE2 7044 7005 0.956915 -0.0191611 -0.0366539 1 0 1 1 0 0 +EDGE2 7044 7025 0.985859 0.0235654 0.016717 1 0 1 1 0 0 +EDGE2 7044 7024 0.0645046 -0.0285044 0.0135817 1 0 1 1 0 0 +EDGE2 7044 7004 0.0523933 -0.0172829 0.0377199 1 0 1 1 0 0 +EDGE2 7044 7003 -0.98308 0.0258906 -0.0130387 1 0 1 1 0 0 +EDGE2 7044 7023 -1.05072 -0.00539995 0.0245981 1 0 1 1 0 0 +EDGE2 7044 7043 -0.932015 -0.012488 0.0179002 1 0 1 1 0 0 +EDGE2 7045 7006 -0.0755958 1.02512 1.56953 1 0 1 1 0 0 +EDGE2 7045 7026 0.0179276 1.01157 1.56554 1 0 1 1 0 0 +EDGE2 7045 7005 0.0164941 0.0858951 -0.0045191 1 0 1 1 0 0 +EDGE2 7045 7025 0.0370961 0.00908194 0.0306979 1 0 1 1 0 0 +EDGE2 7045 7024 -1.00356 0.0193651 0.00776604 1 0 1 1 0 0 +EDGE2 7045 7044 -0.966775 -0.024804 0.00053947 1 0 1 1 0 0 +EDGE2 7045 7004 -0.943771 0.0621829 0.00360109 1 0 1 1 0 0 +EDGE2 7046 7007 1.00915 -0.0818107 -0.0273852 1 0 1 1 0 0 +EDGE2 7046 7027 1.07089 -0.119078 0.00331392 1 0 1 1 0 0 +EDGE2 7046 7006 0.0002024 0.132122 0.029956 1 0 1 1 0 0 +EDGE2 7046 7026 0.0663261 0.0195692 -0.0263244 1 0 1 1 0 0 +EDGE2 7046 7045 -0.978477 -0.0191082 -1.57166 1 0 1 1 0 0 +EDGE2 7046 7005 -0.998144 0.0029976 -1.58476 1 0 1 1 0 0 +EDGE2 7046 7025 -0.956514 0.0261657 -1.57632 1 0 1 1 0 0 +EDGE2 7047 7007 -0.0600513 -0.0118591 0.0101457 1 0 1 1 0 0 +EDGE2 7047 7008 1.03587 0.003765 -0.0102643 1 0 1 1 0 0 +EDGE2 7047 7028 0.984635 0.0960461 0.00864139 1 0 1 1 0 0 +EDGE2 7047 7027 0.0400901 -0.0601919 0.0197285 1 0 1 1 0 0 +EDGE2 7047 7046 -0.982821 0.00179192 0.0228327 1 0 1 1 0 0 +EDGE2 7047 7006 -1.06612 -0.0105621 -0.00636232 1 0 1 1 0 0 +EDGE2 7047 7026 -1.0439 0.0130195 0.00737761 1 0 1 1 0 0 +EDGE2 7048 7029 1.00105 0.0159559 -0.00690135 1 0 1 1 0 0 +EDGE2 7048 7009 0.950447 -0.0914653 0.013997 1 0 1 1 0 0 +EDGE2 7048 7007 -0.936129 -0.0194207 0.0148588 1 0 1 1 0 0 +EDGE2 7048 7008 -0.0207953 0.0104824 -0.0102619 1 0 1 1 0 0 +EDGE2 7048 7028 0.0307686 -0.0493614 0.0308292 1 0 1 1 0 0 +EDGE2 7048 7047 -0.975924 0.0918703 0.029391 1 0 1 1 0 0 +EDGE2 7048 7027 -1.02886 0.00189403 -0.00246953 1 0 1 1 0 0 +EDGE2 7049 7010 1.03511 -0.0217056 0.0256495 1 0 1 1 0 0 +EDGE2 7049 7030 0.958387 0.0968641 -0.0174663 1 0 1 1 0 0 +EDGE2 7049 7029 0.0115795 -0.0641076 0.0116112 1 0 1 1 0 0 +EDGE2 7049 7009 0.0252876 -0.0205049 0.0112154 1 0 1 1 0 0 +EDGE2 7049 7008 -0.972366 0.0406718 0.00541473 1 0 1 1 0 0 +EDGE2 7049 7048 -1.08791 -0.0344093 0.000426394 1 0 1 1 0 0 +EDGE2 7049 7028 -1.00064 -0.0664063 -0.00225665 1 0 1 1 0 0 +EDGE2 7050 7010 -0.0507689 0.0248234 0.00281938 1 0 1 1 0 0 +EDGE2 7050 7030 0.02352 0.018998 -0.00345042 1 0 1 1 0 0 +EDGE2 7050 7029 -1.00277 -0.0699864 -0.00656657 1 0 1 1 0 0 +EDGE2 7050 7049 -1.01192 0.0135597 0.00630239 1 0 1 1 0 0 +EDGE2 7050 7009 -0.971777 -0.000484891 0.0296137 1 0 1 1 0 0 +EDGE2 7050 7031 -0.0164233 0.98283 1.56258 1 0 1 1 0 0 +EDGE2 7050 7011 0.0737987 1.03934 1.57356 1 0 1 1 0 0 +EDGE2 7051 7010 -0.955487 0.0251672 1.54709 1 0 1 1 0 0 +EDGE2 7051 7030 -0.909364 -0.0155877 1.54338 1 0 1 1 0 0 +EDGE2 7051 7050 -0.944947 0.0148333 1.59555 1 0 1 1 0 0 +EDGE2 7052 7051 -0.994873 -0.0533539 -0.0125996 1 0 1 1 0 0 +EDGE2 7053 7052 -1.05161 0.0525351 0.0028005 1 0 1 1 0 0 +EDGE2 7054 7053 -0.88305 -0.0304953 -0.0336005 1 0 1 1 0 0 +EDGE2 7055 7054 -1.00006 -0.0825916 -0.00656092 1 0 1 1 0 0 +EDGE2 7056 7055 -0.952817 0.102661 -1.57333 1 0 1 1 0 0 +EDGE2 7057 7056 -1.01426 -0.0567163 0.0321449 1 0 1 1 0 0 +EDGE2 7058 7057 -1.06666 0.0327283 -0.0122784 1 0 1 1 0 0 +EDGE2 7059 7058 -1.01289 0.0387172 -0.00275712 1 0 1 1 0 0 +EDGE2 7060 7059 -0.929211 -0.0643779 -0.02047 1 0 1 1 0 0 +EDGE2 7061 7060 -0.935811 0.00723887 1.55034 1 0 1 1 0 0 +EDGE2 7062 7061 -1.02893 -0.0227661 0.0411737 1 0 1 1 0 0 +EDGE2 7063 7062 -0.954809 0.0955492 -0.0230957 1 0 1 1 0 0 +EDGE2 7064 7063 -1.03804 0.0554712 -0.0273523 1 0 1 1 0 0 +EDGE2 7065 7064 -0.942011 0.0206858 -0.0129971 1 0 1 1 0 0 +EDGE2 7066 7065 -0.979609 -0.00500152 -1.57101 1 0 1 1 0 0 +EDGE2 7067 7066 -1.0097 0.129693 0.0114845 1 0 1 1 0 0 +EDGE2 7068 7067 -0.959849 0.0466977 0.0108799 1 0 1 1 0 0 +EDGE2 7069 7068 -0.966476 -0.0682674 -0.0195541 1 0 1 1 0 0 +EDGE2 7070 7069 -1.05802 0.0718155 0.00739604 1 0 1 1 0 0 +EDGE2 7071 7070 -1.03659 -0.0255258 1.59557 1 0 1 1 0 0 +EDGE2 7072 7071 -0.980316 -0.0387479 -0.00666681 1 0 1 1 0 0 +EDGE2 7073 7072 -0.947477 -0.0179162 0.0282717 1 0 1 1 0 0 +EDGE2 7074 7073 -0.996457 0.0941157 -0.0224208 1 0 1 1 0 0 +EDGE2 7075 7074 -0.977471 -0.0342715 0.0168456 1 0 1 1 0 0 +EDGE2 7076 7075 -1.01214 0.0525396 -1.58068 1 0 1 1 0 0 +EDGE2 7077 7076 -1.00056 -0.0480342 0.0259562 1 0 1 1 0 0 +EDGE2 7078 7077 -1.02061 0.0681274 0.0383438 1 0 1 1 0 0 +EDGE2 7079 7078 -1.04935 0.00477107 -0.00732897 1 0 1 1 0 0 +EDGE2 7080 7079 -0.96832 -0.0259811 -0.0107211 1 0 1 1 0 0 +EDGE2 7081 7080 -0.966281 0.0577646 -1.52323 1 0 1 1 0 0 +EDGE2 7082 7081 -0.996225 -0.040226 0.00644288 1 0 1 1 0 0 +EDGE2 7083 7082 -1.0306 0.0110329 0.00533254 1 0 1 1 0 0 +EDGE2 7084 7083 -1.14818 -0.00440583 0.0151688 1 0 1 1 0 0 +EDGE2 7085 7084 -1.01202 -0.0600914 0.0252353 1 0 1 1 0 0 +EDGE2 7086 7085 -1.08752 0.0016655 -1.55647 1 0 1 1 0 0 +EDGE2 7087 7086 -0.974996 -0.0244532 -0.00239806 1 0 1 1 0 0 +EDGE2 7088 7087 -0.983807 0.0232354 0.00530222 1 0 1 1 0 0 +EDGE2 7089 7088 -0.976539 0.0548557 -0.0268706 1 0 1 1 0 0 +EDGE2 7089 7070 1.09971 -0.0433012 -3.10353 1 0 1 1 0 0 +EDGE2 7090 7089 -0.988133 0.0297909 0.040632 1 0 1 1 0 0 +EDGE2 7090 7071 0.0153756 0.987664 1.58971 1 0 1 1 0 0 +EDGE2 7090 7069 1.02766 0.0238015 -3.11038 1 0 1 1 0 0 +EDGE2 7090 7070 -0.0238568 -0.0113939 -3.17663 1 0 1 1 0 0 +EDGE2 7091 7090 -0.944945 0.056685 1.56888 1 0 1 1 0 0 +EDGE2 7091 7070 -1.01712 0.0220569 -1.54229 1 0 1 1 0 0 +EDGE2 7092 7091 -0.960147 0.0197118 -6.47259e-05 1 0 1 1 0 0 +EDGE2 7093 7092 -1.09922 0.0680964 0.022117 1 0 1 1 0 0 +EDGE2 7094 7093 -0.948307 0.0602438 0.000961113 1 0 1 1 0 0 +EDGE2 7095 7094 -0.934286 0.0108381 -0.0241759 1 0 1 1 0 0 +EDGE2 7096 7095 -0.990123 -0.0963352 -1.56892 1 0 1 1 0 0 +EDGE2 7097 7096 -0.963349 0.065122 0.0250317 1 0 1 1 0 0 +EDGE2 7098 7097 -0.961924 0.0360329 -0.0144598 1 0 1 1 0 0 +EDGE2 7099 7098 -0.994745 0.0193915 0.0240541 1 0 1 1 0 0 +EDGE2 7099 7060 0.985803 -0.0528702 -3.11719 1 0 1 1 0 0 +EDGE2 7100 7099 -1.0314 -0.00538007 -0.00227009 1 0 1 1 0 0 +EDGE2 7100 7061 0.0878383 0.987849 1.57985 1 0 1 1 0 0 +EDGE2 7100 7060 0.0377871 0.0348997 -3.14841 1 0 1 1 0 0 +EDGE2 7100 7059 0.982654 0.0403983 -3.17107 1 0 1 1 0 0 +EDGE2 7101 7061 -0.0460121 -0.00396435 0.00884475 1 0 1 1 0 0 +EDGE2 7101 7062 1.03926 0.0849314 -0.0343931 1 0 1 1 0 0 +EDGE2 7101 7060 -1.02828 0.000486798 1.58024 1 0 1 1 0 0 +EDGE2 7101 7100 -0.968555 0.044054 -1.5425 1 0 1 1 0 0 +EDGE2 7102 7061 -0.955989 -0.00230805 0.0331307 1 0 1 1 0 0 +EDGE2 7102 7062 0.0404033 0.053511 0.00125611 1 0 1 1 0 0 +EDGE2 7102 7063 0.954977 -0.0259595 -0.0202095 1 0 1 1 0 0 +EDGE2 7102 7101 -1.0878 0.0285441 0.0095216 1 0 1 1 0 0 +EDGE2 7103 7064 1.00031 0.138673 0.0288167 1 0 1 1 0 0 +EDGE2 7103 7062 -0.953812 -0.0655928 -0.0092508 1 0 1 1 0 0 +EDGE2 7103 7102 -1.01453 -0.0358436 0.0309215 1 0 1 1 0 0 +EDGE2 7103 7063 -0.0175188 -0.110743 -0.0122744 1 0 1 1 0 0 +EDGE2 7104 7103 -0.954925 0.0437347 -0.0295068 1 0 1 1 0 0 +EDGE2 7104 7065 0.989577 -0.0960804 0.00488675 1 0 1 1 0 0 +EDGE2 7104 7064 -0.00885257 0.0476065 -0.0291864 1 0 1 1 0 0 +EDGE2 7104 7063 -0.968392 0.0179584 -0.0433938 1 0 1 1 0 0 +EDGE2 7105 7066 -0.0157386 0.989066 1.5771 1 0 1 1 0 0 +EDGE2 7105 7104 -0.934266 0.006404 -0.0374043 1 0 1 1 0 0 +EDGE2 7105 7065 -0.154646 0.0484811 0.000878416 1 0 1 1 0 0 +EDGE2 7105 7064 -0.975742 -0.0569545 -0.0264631 1 0 1 1 0 0 +EDGE2 7106 7065 -1.10657 -0.00976506 1.56059 1 0 1 1 0 0 +EDGE2 7106 7105 -1.004 -0.0195966 1.59353 1 0 1 1 0 0 +EDGE2 7107 7106 -1.09031 -0.00531866 -0.0155316 1 0 1 1 0 0 +EDGE2 7108 7107 -1.01896 -0.076426 -0.00315929 1 0 1 1 0 0 +EDGE2 7109 7108 -0.871735 -0.0522213 -0.00107269 1 0 1 1 0 0 +EDGE2 7110 7109 -0.898777 -0.0550958 0.00495672 1 0 1 1 0 0 +EDGE2 7111 7110 -0.955709 0.0313805 -1.61838 1 0 1 1 0 0 +EDGE2 7112 7111 -1.03245 -0.0482623 -0.00616785 1 0 1 1 0 0 +EDGE2 7113 7112 -1.05111 0.00473091 0.0309623 1 0 1 1 0 0 +EDGE2 7114 7113 -0.96256 -0.0425437 -0.0114741 1 0 1 1 0 0 +EDGE2 7115 7114 -0.894361 0.0206866 0.0347694 1 0 1 1 0 0 +EDGE2 7116 7115 -1.02048 0.0535648 -1.58276 1 0 1 1 0 0 +EDGE2 7117 7116 -0.963461 0.0454374 -0.00916764 1 0 1 1 0 0 +EDGE2 7118 7117 -0.925301 -0.0194276 0.0252992 1 0 1 1 0 0 +EDGE2 7119 7118 -0.96389 0.122044 0.0260503 1 0 1 1 0 0 +EDGE2 7120 7119 -1.06307 0.0163544 0.0108771 1 0 1 1 0 0 +EDGE2 7121 7120 -0.940173 -0.0555594 -1.60635 1 0 1 1 0 0 +EDGE2 7122 7121 -1.03078 -0.0283724 0.00824713 1 0 1 1 0 0 +EDGE2 7123 7122 -1.00302 -0.044961 -0.00742833 1 0 1 1 0 0 +EDGE2 7124 7123 -1.03074 -0.0187789 -0.0408291 1 0 1 1 0 0 +EDGE2 7124 7065 0.980669 0.0160049 -3.13888 1 0 1 1 0 0 +EDGE2 7124 7105 1.05304 -0.0725473 -3.14294 1 0 1 1 0 0 +EDGE2 7125 7124 -1.0071 0.0266005 0.00888019 1 0 1 1 0 0 +EDGE2 7125 7066 0.00481671 -1.00309 -1.58131 1 0 1 1 0 0 +EDGE2 7125 7104 0.999872 -0.0701337 -3.1486 1 0 1 1 0 0 +EDGE2 7125 7065 -0.0018724 0.0719555 -3.11597 1 0 1 1 0 0 +EDGE2 7125 7105 0.0707817 0.0359906 -3.15233 1 0 1 1 0 0 +EDGE2 7125 7064 0.983672 0.00491053 -3.09837 1 0 1 1 0 0 +EDGE2 7125 7106 0.00165187 0.887338 1.56772 1 0 1 1 0 0 +EDGE2 7126 7125 -1.10524 0.048255 -1.56863 1 0 1 1 0 0 +EDGE2 7126 7065 -1.09949 0.0235269 1.53822 1 0 1 1 0 0 +EDGE2 7126 7105 -1.01437 -0.0531492 1.58818 1 0 1 1 0 0 +EDGE2 7126 7106 0.000584436 -0.00840985 -0.000166214 1 0 1 1 0 0 +EDGE2 7126 7107 1.03867 -0.0424697 0.00771318 1 0 1 1 0 0 +EDGE2 7127 7126 -1.05396 -0.0270526 -0.0108227 1 0 1 1 0 0 +EDGE2 7127 7106 -0.883368 0.00501981 0.0126031 1 0 1 1 0 0 +EDGE2 7127 7107 0.0837869 -0.0501792 0.0268775 1 0 1 1 0 0 +EDGE2 7127 7108 1.01316 0.125707 0.000675964 1 0 1 1 0 0 +EDGE2 7128 7107 -0.966707 0.000301571 -0.0215894 1 0 1 1 0 0 +EDGE2 7128 7127 -1.0378 0.0486278 -0.0108492 1 0 1 1 0 0 +EDGE2 7128 7108 -0.0332699 -0.0135694 -0.0458677 1 0 1 1 0 0 +EDGE2 7128 7109 1.00565 0.127765 0.00130752 1 0 1 1 0 0 +EDGE2 7129 7128 -0.976661 -0.00119905 -0.0302825 1 0 1 1 0 0 +EDGE2 7129 7108 -0.953931 -0.0805898 0.0326916 1 0 1 1 0 0 +EDGE2 7129 7109 0.038708 0.0786992 0.0278416 1 0 1 1 0 0 +EDGE2 7129 7110 0.978272 0.0269554 -0.0327086 1 0 1 1 0 0 +EDGE2 7130 7111 -0.00289849 1.09761 1.61029 1 0 1 1 0 0 +EDGE2 7130 7129 -1.00967 -0.0687412 -0.00368575 1 0 1 1 0 0 +EDGE2 7130 7109 -0.934513 0.0181807 -0.0284629 1 0 1 1 0 0 +EDGE2 7130 7110 -0.0250586 -0.00262547 -0.0141172 1 0 1 1 0 0 +EDGE2 7131 7112 0.925641 -0.0606036 -0.011332 1 0 1 1 0 0 +EDGE2 7131 7111 -0.0439827 -0.0115723 0.0167713 1 0 1 1 0 0 +EDGE2 7131 7110 -1.07068 -0.0136522 -1.60037 1 0 1 1 0 0 +EDGE2 7131 7130 -1.03533 -0.0563652 -1.59704 1 0 1 1 0 0 +EDGE2 7132 7113 0.963814 0.0644797 -0.0186077 1 0 1 1 0 0 +EDGE2 7132 7131 -0.9668 -0.0799058 -0.0155967 1 0 1 1 0 0 +EDGE2 7132 7112 0.0526683 0.13289 0.0166927 1 0 1 1 0 0 +EDGE2 7132 7111 -1.01442 -0.0262468 -0.00674286 1 0 1 1 0 0 +EDGE2 7133 7132 -1.10972 0.0314701 -0.0146193 1 0 1 1 0 0 +EDGE2 7133 7114 1.02361 0.0199574 -0.0394679 1 0 1 1 0 0 +EDGE2 7133 7113 -0.0574545 0.0117987 0.0376447 1 0 1 1 0 0 +EDGE2 7133 7112 -0.948829 0.0862376 -0.00555424 1 0 1 1 0 0 +EDGE2 7134 7115 0.994219 0.0261012 0.00460256 1 0 1 1 0 0 +EDGE2 7134 7133 -0.96136 0.0512045 -0.0017216 1 0 1 1 0 0 +EDGE2 7134 7114 -0.0393887 0.0319465 -0.0154991 1 0 1 1 0 0 +EDGE2 7134 7113 -0.92498 -0.00226702 -0.00598881 1 0 1 1 0 0 +EDGE2 7135 7116 0.056873 1.0173 1.57341 1 0 1 1 0 0 +EDGE2 7135 7134 -0.924639 -0.0336489 0.0665315 1 0 1 1 0 0 +EDGE2 7135 7115 0.0143237 -0.0573401 -0.00174092 1 0 1 1 0 0 +EDGE2 7135 7114 -0.997486 0.11559 0.0104137 1 0 1 1 0 0 +EDGE2 7136 7117 1.04186 -0.0199464 0.0266419 1 0 1 1 0 0 +EDGE2 7136 7116 0.0222785 -0.0394044 0.00802211 1 0 1 1 0 0 +EDGE2 7136 7135 -0.932581 -0.0282679 -1.57563 1 0 1 1 0 0 +EDGE2 7136 7115 -0.980379 0.0796039 -1.54361 1 0 1 1 0 0 +EDGE2 7137 7118 0.927389 0.00330762 0.00170608 1 0 1 1 0 0 +EDGE2 7137 7117 0.010771 -0.0878107 -0.0104426 1 0 1 1 0 0 +EDGE2 7137 7136 -0.977155 0.0323531 -0.00740019 1 0 1 1 0 0 +EDGE2 7137 7116 -1.03709 -0.0190124 0.00981013 1 0 1 1 0 0 +EDGE2 7138 7119 0.956807 -0.00317384 0.0167815 1 0 1 1 0 0 +EDGE2 7138 7118 -0.00860517 0.048979 0.0144528 1 0 1 1 0 0 +EDGE2 7138 7117 -0.968615 0.0227722 0.00554323 1 0 1 1 0 0 +EDGE2 7138 7137 -1.03975 -0.0159891 0.00649101 1 0 1 1 0 0 +EDGE2 7139 7120 0.969856 0.0148156 0.00145693 1 0 1 1 0 0 +EDGE2 7139 7119 -0.0757307 -0.03544 0.00313489 1 0 1 1 0 0 +EDGE2 7139 7138 -1.0673 0.0102094 -0.0165092 1 0 1 1 0 0 +EDGE2 7139 7118 -1.09581 0.0326865 0.0237804 1 0 1 1 0 0 +EDGE2 7140 7120 0.104543 -0.0530209 -0.00255174 1 0 1 1 0 0 +EDGE2 7140 7119 -1.07641 -0.00931954 -0.00788615 1 0 1 1 0 0 +EDGE2 7140 7121 -0.0336747 1.00326 1.57376 1 0 1 1 0 0 +EDGE2 7140 7139 -0.971324 -0.030427 -0.0332131 1 0 1 1 0 0 +EDGE2 7141 7120 -0.939308 -0.0133445 1.55742 1 0 1 1 0 0 +EDGE2 7141 7140 -0.94293 0.0650145 1.58683 1 0 1 1 0 0 +EDGE2 7142 7141 -1.04765 0.049056 -0.0123797 1 0 1 1 0 0 +EDGE2 7143 7142 -0.939798 -0.0909788 -0.00306385 1 0 1 1 0 0 +EDGE2 7144 7143 -0.998303 -0.0215675 -0.0155812 1 0 1 1 0 0 +EDGE2 7145 7144 -0.974991 0.0533777 -0.0453314 1 0 1 1 0 0 +EDGE2 7146 7145 -0.984447 -0.0489638 -1.57838 1 0 1 1 0 0 +EDGE2 7147 7146 -0.979819 -0.0263289 -0.00578839 1 0 1 1 0 0 +EDGE2 7148 7147 -0.97456 -0.0177353 -0.0119187 1 0 1 1 0 0 +EDGE2 7149 7148 -0.953519 0.0146358 -0.000540615 1 0 1 1 0 0 +EDGE2 7150 7149 -0.928508 0.0284495 0.0418891 1 0 1 1 0 0 +EDGE2 7151 7150 -0.991495 -0.0643542 -1.57038 1 0 1 1 0 0 +EDGE2 7152 7151 -1.018 -0.102966 -0.0208778 1 0 1 1 0 0 +EDGE2 7153 7152 -1.02951 -0.00735843 -0.0101583 1 0 1 1 0 0 +EDGE2 7154 7153 -1.03316 -0.00308946 0.0106826 1 0 1 1 0 0 +EDGE2 7154 7075 1.02768 0.031567 -3.15564 1 0 1 1 0 0 +EDGE2 7155 7076 -0.112518 -1.03397 -1.58615 1 0 1 1 0 0 +EDGE2 7155 7075 -0.0215981 -0.0567757 -3.13735 1 0 1 1 0 0 +EDGE2 7155 7154 -0.990596 0.00221 0.0216954 1 0 1 1 0 0 +EDGE2 7155 7074 1.03009 0.00227913 -3.17937 1 0 1 1 0 0 +EDGE2 7156 7075 -0.967478 0.00974306 1.61533 1 0 1 1 0 0 +EDGE2 7156 7155 -0.90594 0.0515279 -1.54743 1 0 1 1 0 0 +EDGE2 7157 7156 -0.956991 0.0121011 -0.0160946 1 0 1 1 0 0 +EDGE2 7158 7157 -1.0421 0.0447001 0.0208 1 0 1 1 0 0 +EDGE2 7159 7158 -1.06617 -0.0544833 0.0110296 1 0 1 1 0 0 +EDGE2 7159 7120 1.03057 0.0135296 -3.13665 1 0 1 1 0 0 +EDGE2 7159 7140 0.973926 0.0100732 -3.12674 1 0 1 1 0 0 +EDGE2 7160 7159 -1.10534 -0.0231051 -0.00650166 1 0 1 1 0 0 +EDGE2 7160 7141 0.0261018 1.05138 1.58595 1 0 1 1 0 0 +EDGE2 7160 7120 -0.0756429 -0.0303968 -3.15088 1 0 1 1 0 0 +EDGE2 7160 7140 -0.158635 -0.00683926 -3.13485 1 0 1 1 0 0 +EDGE2 7160 7119 0.941841 -0.0219725 -3.1475 1 0 1 1 0 0 +EDGE2 7160 7121 0.0437372 -0.937389 -1.5535 1 0 1 1 0 0 +EDGE2 7160 7139 1.09031 0.0849902 -3.16866 1 0 1 1 0 0 +EDGE2 7161 7142 0.989862 -0.0563464 -0.0163663 1 0 1 1 0 0 +EDGE2 7161 7141 0.0101432 0.0297565 0.0160243 1 0 1 1 0 0 +EDGE2 7161 7120 -0.921507 -0.0674213 1.5667 1 0 1 1 0 0 +EDGE2 7161 7140 -0.999113 -0.0441292 1.55897 1 0 1 1 0 0 +EDGE2 7161 7160 -0.95633 0.00813246 -1.58204 1 0 1 1 0 0 +EDGE2 7162 7143 1.0491 -0.0625159 0.00574082 1 0 1 1 0 0 +EDGE2 7162 7142 0.0298718 -0.0339702 -0.0105622 1 0 1 1 0 0 +EDGE2 7162 7141 -0.916245 0.0393704 -0.0130224 1 0 1 1 0 0 +EDGE2 7162 7161 -0.986271 0.0448661 0.0176539 1 0 1 1 0 0 +EDGE2 7163 7144 0.943376 0.0248955 -0.00449702 1 0 1 1 0 0 +EDGE2 7163 7162 -1.02755 -0.00485006 -0.00545967 1 0 1 1 0 0 +EDGE2 7163 7143 0.0289258 -0.0360573 -0.00483443 1 0 1 1 0 0 +EDGE2 7163 7142 -1.01748 0.0325586 0.0149113 1 0 1 1 0 0 +EDGE2 7164 7145 1.06755 0.0250642 0.00519382 1 0 1 1 0 0 +EDGE2 7164 7163 -1.03372 -0.112688 0.027164 1 0 1 1 0 0 +EDGE2 7164 7144 0.0622494 0.0334666 -0.0027985 1 0 1 1 0 0 +EDGE2 7164 7143 -0.947449 0.0208568 -0.025391 1 0 1 1 0 0 +EDGE2 7165 7146 0.0318544 1.01416 1.58551 1 0 1 1 0 0 +EDGE2 7165 7145 0.0752851 -0.00902927 0.00654448 1 0 1 1 0 0 +EDGE2 7165 7144 -0.941289 -0.0153944 0.00900824 1 0 1 1 0 0 +EDGE2 7165 7164 -0.949052 -0.0236966 -0.010418 1 0 1 1 0 0 +EDGE2 7166 7145 -0.976389 -0.0318437 1.6011 1 0 1 1 0 0 +EDGE2 7166 7165 -1.03306 0.0344037 1.56238 1 0 1 1 0 0 +EDGE2 7167 7166 -1.01301 -0.0471061 0.0479374 1 0 1 1 0 0 +EDGE2 7168 7167 -0.98137 -0.00521051 -0.001267 1 0 1 1 0 0 +EDGE2 7169 7168 -0.939186 -0.0142067 0.00364695 1 0 1 1 0 0 +EDGE2 7170 7169 -1.02195 -0.00354443 0.00085936 1 0 1 1 0 0 +EDGE2 7171 7170 -1.01315 -0.0849247 1.56455 1 0 1 1 0 0 +EDGE2 7172 7171 -0.983072 0.084532 0.0010368 1 0 1 1 0 0 +EDGE2 7173 7172 -0.980506 -0.0389689 0.0188213 1 0 1 1 0 0 +EDGE2 7174 7173 -1.12225 -0.0030487 -2.96491e-05 1 0 1 1 0 0 +EDGE2 7174 7135 0.939784 -0.00284316 -3.13909 1 0 1 1 0 0 +EDGE2 7174 7115 0.988444 -0.0344955 -3.13864 1 0 1 1 0 0 +EDGE2 7175 7136 0.00361475 -0.986401 -1.56203 1 0 1 1 0 0 +EDGE2 7175 7116 -0.0501497 -0.977386 -1.55265 1 0 1 1 0 0 +EDGE2 7175 7174 -0.999987 -0.107782 -0.0206478 1 0 1 1 0 0 +EDGE2 7175 7134 0.94321 0.00567769 -3.13784 1 0 1 1 0 0 +EDGE2 7175 7135 -0.0607927 -0.0506305 -3.15467 1 0 1 1 0 0 +EDGE2 7175 7115 0.0566321 -0.0895683 -3.15696 1 0 1 1 0 0 +EDGE2 7175 7114 1.01257 -0.0575455 -3.14672 1 0 1 1 0 0 +EDGE2 7176 7135 -0.952463 0.0515361 1.5697 1 0 1 1 0 0 +EDGE2 7176 7175 -1.02498 -0.0146699 -1.54032 1 0 1 1 0 0 +EDGE2 7176 7115 -1.00923 -0.0384823 1.54714 1 0 1 1 0 0 +EDGE2 7177 7176 -0.975252 -0.124013 -0.0046591 1 0 1 1 0 0 +EDGE2 7178 7177 -1.0464 -0.0432733 3.86746e-06 1 0 1 1 0 0 +EDGE2 7179 7178 -0.974769 0.0348052 0.0440564 1 0 1 1 0 0 +EDGE2 7180 7179 -1.00969 0.00782081 -0.0120096 1 0 1 1 0 0 +EDGE2 7181 7180 -0.942842 -0.115123 -1.57154 1 0 1 1 0 0 +EDGE2 7182 7181 -0.876036 -0.0144857 0.0269939 1 0 1 1 0 0 +EDGE2 7183 7182 -0.941692 0.000689227 -0.0330903 1 0 1 1 0 0 +EDGE2 7184 7183 -1.01999 -0.0221475 0.0138198 1 0 1 1 0 0 +EDGE2 7185 7184 -1.06182 0.0703342 -0.0299223 1 0 1 1 0 0 +EDGE2 7186 7185 -1.00283 -0.0456402 1.55986 1 0 1 1 0 0 +EDGE2 7187 7186 -1.05365 -0.0181409 0.0210679 1 0 1 1 0 0 +EDGE2 7188 7187 -0.940035 -0.0793007 -0.026813 1 0 1 1 0 0 +EDGE2 7189 7188 -0.992856 0.0432113 0.0318251 1 0 1 1 0 0 +EDGE2 7190 7189 -0.930221 0.067951 -0.000182849 1 0 1 1 0 0 +EDGE2 7191 7190 -1.00527 -0.0118595 1.54532 1 0 1 1 0 0 +EDGE2 7192 7191 -0.96864 -0.0103669 -0.00814984 1 0 1 1 0 0 +EDGE2 7193 7192 -0.964521 -0.0856727 -0.0316949 1 0 1 1 0 0 +EDGE2 7194 7193 -0.990911 -0.0196622 -0.0178749 1 0 1 1 0 0 +EDGE2 7195 7194 -0.991188 -0.0183609 -0.0177378 1 0 1 1 0 0 +EDGE2 7196 7195 -1.06083 0.0835484 -1.52376 1 0 1 1 0 0 +EDGE2 7197 7196 -0.934262 -0.0117585 0.00505612 1 0 1 1 0 0 +EDGE2 7198 7197 -0.974598 0.0414163 0.00757285 1 0 1 1 0 0 +EDGE2 7199 7198 -1.0633 0.0279699 0.0236764 1 0 1 1 0 0 +EDGE2 7200 7199 -1.0315 -0.00363884 0.002535 1 0 1 1 0 0 +EDGE2 7201 7200 -1.06181 -0.0390564 1.57846 1 0 1 1 0 0 +EDGE2 7202 7201 -0.947787 0.107251 -0.0382757 1 0 1 1 0 0 +EDGE2 7203 7202 -1.04134 0.00771679 -0.0229657 1 0 1 1 0 0 +EDGE2 7204 7203 -1.07713 -0.0314633 -0.0137719 1 0 1 1 0 0 +EDGE2 7205 7204 -1.02246 -0.0753176 0.0277824 1 0 1 1 0 0 +EDGE2 7206 7205 -0.950915 -0.0561191 -1.58227 1 0 1 1 0 0 +EDGE2 7207 7206 -0.972931 0.0280959 -0.0156205 1 0 1 1 0 0 +EDGE2 7208 7207 -1.02549 -0.098047 -0.0117213 1 0 1 1 0 0 +EDGE2 7209 7208 -1.021 0.0413069 0.0167686 1 0 1 1 0 0 +EDGE2 7209 6610 0.87361 0.0224125 -3.17696 1 0 1 1 0 0 +EDGE2 7210 7209 -1.01192 0.0240972 -0.00327566 1 0 1 1 0 0 +EDGE2 7210 6610 0.0347218 0.00654532 -3.17361 1 0 1 1 0 0 +EDGE2 7210 6611 -0.0308753 -0.930479 -1.5799 1 0 1 1 0 0 +EDGE2 7210 6609 0.910989 -0.0125727 -3.12984 1 0 1 1 0 0 +EDGE2 7211 6610 -1.0358 0.013834 1.56287 1 0 1 1 0 0 +EDGE2 7211 7210 -0.913927 0.0729544 -1.5493 1 0 1 1 0 0 +EDGE2 7212 7211 -1.058 0.0363029 0.0100019 1 0 1 1 0 0 +EDGE2 7213 7212 -0.995981 0.0301385 -0.00197951 1 0 1 1 0 0 +EDGE2 7214 7213 -1.00714 -0.000978134 0.0155174 1 0 1 1 0 0 +EDGE2 7215 7214 -1.06112 0.0652321 0.0170567 1 0 1 1 0 0 +EDGE2 7216 7215 -0.999453 0.0303593 -1.58523 1 0 1 1 0 0 +EDGE2 7217 7216 -1.00746 -0.00101042 -0.00705639 1 0 1 1 0 0 +EDGE2 7218 7217 -0.97754 0.0901492 0.0279503 1 0 1 1 0 0 +EDGE2 7219 7200 1.05417 0.0288152 -3.15219 1 0 1 1 0 0 +EDGE2 7219 7218 -0.988664 -0.0888766 -0.0387257 1 0 1 1 0 0 +EDGE2 7220 7199 1.03637 0.0225649 -3.14554 1 0 1 1 0 0 +EDGE2 7220 7201 0.0168734 0.980832 1.57968 1 0 1 1 0 0 +EDGE2 7220 7200 -0.00793474 -0.0103311 -3.13994 1 0 1 1 0 0 +EDGE2 7220 7219 -1.13394 0.024828 -0.000526726 1 0 1 1 0 0 +EDGE2 7221 7201 0.0108965 0.0482556 -0.017232 1 0 1 1 0 0 +EDGE2 7221 7200 -1.02922 0.0283733 1.56949 1 0 1 1 0 0 +EDGE2 7221 7220 -0.968861 -0.0278122 -1.5631 1 0 1 1 0 0 +EDGE2 7221 7202 0.943656 0.0160991 0.0187866 1 0 1 1 0 0 +EDGE2 7222 7201 -0.891245 -0.046006 -0.00711653 1 0 1 1 0 0 +EDGE2 7222 7221 -1.00074 0.0577311 -0.0280953 1 0 1 1 0 0 +EDGE2 7222 7202 -0.0165687 -0.0363748 -0.0379941 1 0 1 1 0 0 +EDGE2 7222 7203 0.861298 0.0337176 0.0205768 1 0 1 1 0 0 +EDGE2 7223 7204 0.971273 0.00573821 0.00641021 1 0 1 1 0 0 +EDGE2 7223 7202 -1.02212 0.150088 -0.0341564 1 0 1 1 0 0 +EDGE2 7223 7222 -1.01008 -0.00259361 -0.0157119 1 0 1 1 0 0 +EDGE2 7223 7203 -0.0367754 0.0474999 0.011955 1 0 1 1 0 0 +EDGE2 7224 7204 -0.00131235 -0.0710275 -0.0152585 1 0 1 1 0 0 +EDGE2 7224 7223 -1.03802 -0.00901497 0.0162669 1 0 1 1 0 0 +EDGE2 7224 7203 -0.952489 0.0233562 0.00795483 1 0 1 1 0 0 +EDGE2 7224 7205 0.97199 -0.000401481 -0.0184503 1 0 1 1 0 0 +EDGE2 7225 7204 -1.05153 -0.0273053 0.00200627 1 0 1 1 0 0 +EDGE2 7225 7224 -1.04051 -0.00285092 0.00948351 1 0 1 1 0 0 +EDGE2 7225 7205 0.0630286 -0.0104056 0.0376926 1 0 1 1 0 0 +EDGE2 7225 7206 0.0011779 0.993406 1.5541 1 0 1 1 0 0 +EDGE2 7226 7205 -1.07106 0.0121188 1.58992 1 0 1 1 0 0 +EDGE2 7226 7225 -0.95279 0.0139737 1.53975 1 0 1 1 0 0 +EDGE2 7227 7226 -0.951925 0.00291963 0.0164414 1 0 1 1 0 0 +EDGE2 7228 7227 -0.988107 0.0606862 0.00948748 1 0 1 1 0 0 +EDGE2 7229 7228 -1.01111 -0.0504851 0.0117575 1 0 1 1 0 0 +EDGE2 7230 7229 -0.984439 -0.0415118 -0.00752068 1 0 1 1 0 0 +EDGE2 7231 7230 -0.886678 0.0154316 -1.54474 1 0 1 1 0 0 +EDGE2 7232 7231 -1.04747 0.012407 -0.0113691 1 0 1 1 0 0 +EDGE2 7233 7232 -1.03999 0.0518016 0.00891913 1 0 1 1 0 0 +EDGE2 7234 7233 -0.971767 -0.0717425 0.015672 1 0 1 1 0 0 +EDGE2 7235 7234 -1.0079 -0.0163183 0.0354902 1 0 1 1 0 0 +EDGE2 7236 7235 -1.02609 0.0564565 1.57279 1 0 1 1 0 0 +EDGE2 7237 7236 -1.02035 -0.0563788 0.00889517 1 0 1 1 0 0 +EDGE2 7238 7237 -1.02731 0.0106105 -0.0218737 1 0 1 1 0 0 +EDGE2 7239 7238 -0.984498 -0.04758 -0.00592793 1 0 1 1 0 0 +EDGE2 7240 7239 -1.02918 -0.0340546 -0.0131084 1 0 1 1 0 0 +EDGE2 7241 7240 -1.0146 -0.129974 1.57684 1 0 1 1 0 0 +EDGE2 7242 7241 -1.01932 -0.0161921 0.0120723 1 0 1 1 0 0 +EDGE2 7243 7242 -0.942123 0.0299237 -0.0112929 1 0 1 1 0 0 +EDGE2 7244 7243 -0.952337 -0.0700389 0.00299373 1 0 1 1 0 0 +EDGE2 7245 7244 -1.0157 -0.00618578 -0.0153147 1 0 1 1 0 0 +EDGE2 7246 7245 -1.01624 -0.0319471 -1.53772 1 0 1 1 0 0 +EDGE2 7247 7246 -0.997022 -0.0595595 -0.0401918 1 0 1 1 0 0 +EDGE2 7248 7247 -0.986443 0.0538859 0.0218645 1 0 1 1 0 0 +EDGE2 7249 7110 0.963438 0.0800669 -3.15031 1 0 1 1 0 0 +EDGE2 7249 7130 0.995558 0.0375157 -3.09581 1 0 1 1 0 0 +EDGE2 7249 7248 -1.00081 -0.0918423 0.015871 1 0 1 1 0 0 +EDGE2 7250 7131 -0.0372444 -0.993146 -1.58885 1 0 1 1 0 0 +EDGE2 7250 7111 0.0108061 -1.06896 -1.61079 1 0 1 1 0 0 +EDGE2 7250 7129 1.01395 -0.0202755 -3.12403 1 0 1 1 0 0 +EDGE2 7250 7109 1.00942 -0.0365622 -3.16232 1 0 1 1 0 0 +EDGE2 7250 7110 -0.0100407 0.00223981 -3.1579 1 0 1 1 0 0 +EDGE2 7250 7130 0.00500335 -0.0229361 -3.13169 1 0 1 1 0 0 +EDGE2 7250 7249 -1.02776 0.0525537 0.0534465 1 0 1 1 0 0 +EDGE2 7251 7132 1.02449 0.0333262 -0.0158532 1 0 1 1 0 0 +EDGE2 7251 7131 0.0355363 0.00464424 0.00344849 1 0 1 1 0 0 +EDGE2 7251 7112 0.960493 -0.0338399 0.0189375 1 0 1 1 0 0 +EDGE2 7251 7111 0.00412179 0.0704303 0.0217589 1 0 1 1 0 0 +EDGE2 7251 7250 -0.932724 0.0042601 1.53631 1 0 1 1 0 0 +EDGE2 7251 7110 -0.993637 0.00526113 -1.58192 1 0 1 1 0 0 +EDGE2 7251 7130 -0.993528 -0.0555349 -1.56517 1 0 1 1 0 0 +EDGE2 7252 7132 0.0189352 0.00350804 -0.0201036 1 0 1 1 0 0 +EDGE2 7252 7133 1.04408 0.117019 0.0175444 1 0 1 1 0 0 +EDGE2 7252 7113 1.09042 0.0488241 -0.0261951 1 0 1 1 0 0 +EDGE2 7252 7131 -1.07741 -0.0638231 -0.014064 1 0 1 1 0 0 +EDGE2 7252 7112 0.0663381 0.00233643 0.0170011 1 0 1 1 0 0 +EDGE2 7252 7251 -1.08167 0.00451102 -0.0272685 1 0 1 1 0 0 +EDGE2 7252 7111 -1.02168 -0.0142404 0.000436984 1 0 1 1 0 0 +EDGE2 7253 7132 -0.880124 0.0432328 -0.00577439 1 0 1 1 0 0 +EDGE2 7253 7134 0.948407 -0.0340149 0.00768637 1 0 1 1 0 0 +EDGE2 7253 7133 -0.0298915 -0.0222576 0.00796883 1 0 1 1 0 0 +EDGE2 7253 7114 1.01416 -0.0637589 -0.0234723 1 0 1 1 0 0 +EDGE2 7253 7113 0.0973252 -0.00258976 0.0276626 1 0 1 1 0 0 +EDGE2 7253 7252 -1.08022 -0.0537992 -0.00885205 1 0 1 1 0 0 +EDGE2 7253 7112 -0.963173 -0.0117627 0.000386841 1 0 1 1 0 0 +EDGE2 7254 7134 0.000130938 -0.0235903 -0.0041853 1 0 1 1 0 0 +EDGE2 7254 7135 1.05552 -0.00835348 -0.0100311 1 0 1 1 0 0 +EDGE2 7254 7175 1.05969 0.00631371 -3.15109 1 0 1 1 0 0 +EDGE2 7254 7115 0.926655 0.0360906 0.0243441 1 0 1 1 0 0 +EDGE2 7254 7133 -1.01367 0.164858 -0.0460146 1 0 1 1 0 0 +EDGE2 7254 7114 -0.056485 -0.0176523 -0.0114803 1 0 1 1 0 0 +EDGE2 7254 7253 -1.01143 -0.056905 5.98246e-05 1 0 1 1 0 0 +EDGE2 7254 7113 -1.0167 0.0386379 -0.0263791 1 0 1 1 0 0 +EDGE2 7255 7136 -0.0326555 0.885173 1.54083 1 0 1 1 0 0 +EDGE2 7255 7116 -0.0518906 0.981365 1.58443 1 0 1 1 0 0 +EDGE2 7255 7174 1.02733 -0.0567889 -3.14153 1 0 1 1 0 0 +EDGE2 7255 7134 -0.971879 -0.0385153 -0.0236073 1 0 1 1 0 0 +EDGE2 7255 7135 0.0165974 -0.0383239 0.00681541 1 0 1 1 0 0 +EDGE2 7255 7175 -0.00272546 0.003418 -3.16922 1 0 1 1 0 0 +EDGE2 7255 7115 0.0751117 0.00391271 0.0229737 1 0 1 1 0 0 +EDGE2 7255 7254 -0.916845 -0.0758158 0.016434 1 0 1 1 0 0 +EDGE2 7255 7114 -1.05559 0.101295 -0.00184027 1 0 1 1 0 0 +EDGE2 7255 7176 -0.022991 -0.972764 -1.57008 1 0 1 1 0 0 +EDGE2 7256 7117 1.00371 0.0284819 0.00832786 1 0 1 1 0 0 +EDGE2 7256 7137 1.05979 -0.00248139 0.00411657 1 0 1 1 0 0 +EDGE2 7256 7136 0.0141678 -0.0197337 -0.0453335 1 0 1 1 0 0 +EDGE2 7256 7116 0.0333682 0.0908711 -0.00950663 1 0 1 1 0 0 +EDGE2 7256 7135 -1.06867 -0.00440555 -1.57828 1 0 1 1 0 0 +EDGE2 7256 7255 -0.98918 -0.0471604 -1.56392 1 0 1 1 0 0 +EDGE2 7256 7175 -0.993544 0.0246381 1.59289 1 0 1 1 0 0 +EDGE2 7256 7115 -0.889616 -0.0300137 -1.57174 1 0 1 1 0 0 +EDGE2 7257 7138 1.01284 -0.0696081 -0.000117117 1 0 1 1 0 0 +EDGE2 7257 7118 0.93216 0.00837919 0.0411534 1 0 1 1 0 0 +EDGE2 7257 7117 0.00804146 -0.032143 0.0247279 1 0 1 1 0 0 +EDGE2 7257 7137 -0.0226495 -0.00394088 0.0261425 1 0 1 1 0 0 +EDGE2 7257 7136 -1.02483 -0.0919845 0.00438867 1 0 1 1 0 0 +EDGE2 7257 7256 -0.964386 -0.0123319 -0.0171936 1 0 1 1 0 0 +EDGE2 7257 7116 -1.00494 0.064553 0.00909312 1 0 1 1 0 0 +EDGE2 7258 7119 1.01379 0.0439546 -0.0330817 1 0 1 1 0 0 +EDGE2 7258 7139 0.990309 0.0257105 -0.0026663 1 0 1 1 0 0 +EDGE2 7258 7138 0.033514 0.0194616 -0.0242721 1 0 1 1 0 0 +EDGE2 7258 7118 -0.0188943 -0.0161884 -0.0478141 1 0 1 1 0 0 +EDGE2 7258 7117 -0.936769 -0.0306253 0.0440826 1 0 1 1 0 0 +EDGE2 7258 7137 -1.06509 -0.076165 0.00156632 1 0 1 1 0 0 +EDGE2 7258 7257 -1.04962 0.0327886 -0.0402375 1 0 1 1 0 0 +EDGE2 7259 7120 0.939083 0.00632241 0.00420498 1 0 1 1 0 0 +EDGE2 7259 7140 1.05648 -0.0389695 0.00247612 1 0 1 1 0 0 +EDGE2 7259 7160 1.03077 -0.0360292 -3.16435 1 0 1 1 0 0 +EDGE2 7259 7119 0.0541662 -0.0602192 -0.0143197 1 0 1 1 0 0 +EDGE2 7259 7139 -0.00972945 -0.0168664 0.00912405 1 0 1 1 0 0 +EDGE2 7259 7138 -0.971735 -0.0374594 -0.0227204 1 0 1 1 0 0 +EDGE2 7259 7258 -0.976914 -0.0201307 0.000345329 1 0 1 1 0 0 +EDGE2 7259 7118 -1.0301 -0.0285569 -0.00111772 1 0 1 1 0 0 +EDGE2 7260 7159 1.03421 0.0836384 -3.11993 1 0 1 1 0 0 +EDGE2 7260 7141 -0.0400781 -1.0603 -1.5795 1 0 1 1 0 0 +EDGE2 7260 7161 -0.0675539 -0.998092 -1.60334 1 0 1 1 0 0 +EDGE2 7260 7120 0.0344135 0.0547316 -0.0150494 1 0 1 1 0 0 +EDGE2 7260 7140 0.128983 0.0270755 -0.0132372 1 0 1 1 0 0 +EDGE2 7260 7160 0.0247857 0.022788 -3.15995 1 0 1 1 0 0 +EDGE2 7260 7119 -0.981171 0.071433 -0.0177763 1 0 1 1 0 0 +EDGE2 7260 7259 -1.01936 0.00935501 0.00952813 1 0 1 1 0 0 +EDGE2 7260 7121 -0.025532 0.984317 1.59247 1 0 1 1 0 0 +EDGE2 7260 7139 -1.03482 -0.027505 -0.0358867 1 0 1 1 0 0 +EDGE2 7261 7260 -1.05128 0.020819 -1.53287 1 0 1 1 0 0 +EDGE2 7261 7120 -1.03298 0.0278082 -1.53906 1 0 1 1 0 0 +EDGE2 7261 7140 -1.06977 -0.00209425 -1.57209 1 0 1 1 0 0 +EDGE2 7261 7160 -1.01311 0.056493 1.59115 1 0 1 1 0 0 +EDGE2 7261 7121 -0.0102166 0.00504672 0.023197 1 0 1 1 0 0 +EDGE2 7261 7122 1.01068 0.0628986 -0.00213302 1 0 1 1 0 0 +EDGE2 7262 7261 -0.938955 0.0531934 -0.00472962 1 0 1 1 0 0 +EDGE2 7262 7121 -1.01588 0.0686224 0.0372394 1 0 1 1 0 0 +EDGE2 7262 7123 1.0193 -0.0974633 0.00838533 1 0 1 1 0 0 +EDGE2 7262 7122 0.0393038 0.0249602 -0.034625 1 0 1 1 0 0 +EDGE2 7263 7123 0.107152 -0.0135242 -0.00584488 1 0 1 1 0 0 +EDGE2 7263 7122 -1.02983 -0.00922848 0.00163538 1 0 1 1 0 0 +EDGE2 7263 7262 -0.963596 -0.0286991 -0.0070185 1 0 1 1 0 0 +EDGE2 7263 7124 0.928422 0.0885521 -0.0243031 1 0 1 1 0 0 +EDGE2 7264 7123 -1.01246 -0.00665396 0.0277267 1 0 1 1 0 0 +EDGE2 7264 7263 -1.02951 -0.0227425 -0.0113871 1 0 1 1 0 0 +EDGE2 7264 7124 0.0385363 0.0384758 0.00947324 1 0 1 1 0 0 +EDGE2 7264 7125 1.04934 -0.0497449 0.0213838 1 0 1 1 0 0 +EDGE2 7264 7065 1.06408 0.047349 -3.15869 1 0 1 1 0 0 +EDGE2 7264 7105 1.01729 -0.00249645 -3.14998 1 0 1 1 0 0 +EDGE2 7265 7264 -0.999518 -0.00692784 0.00470083 1 0 1 1 0 0 +EDGE2 7265 7124 -1.08851 0.0209422 0.00121743 1 0 1 1 0 0 +EDGE2 7265 7125 -0.0321167 -0.0296994 -0.0125439 1 0 1 1 0 0 +EDGE2 7265 7066 -0.116847 -1.09623 -1.55521 1 0 1 1 0 0 +EDGE2 7265 7104 1.03066 -0.0525257 -3.18014 1 0 1 1 0 0 +EDGE2 7265 7065 0.0205339 0.00204708 -3.11268 1 0 1 1 0 0 +EDGE2 7265 7105 0.0278002 0.114702 -3.13083 1 0 1 1 0 0 +EDGE2 7265 7064 1.05183 0.0409461 -3.10874 1 0 1 1 0 0 +EDGE2 7265 7126 -0.0390635 1.07387 1.55505 1 0 1 1 0 0 +EDGE2 7265 7106 0.116216 1.02178 1.55026 1 0 1 1 0 0 +EDGE2 7266 7125 -1.04246 0.0314287 -1.58183 1 0 1 1 0 0 +EDGE2 7266 7265 -1.01204 0.0488044 -1.60539 1 0 1 1 0 0 +EDGE2 7266 7065 -0.977436 -0.00357736 1.5811 1 0 1 1 0 0 +EDGE2 7266 7105 -1.00711 -0.028178 1.57557 1 0 1 1 0 0 +EDGE2 7266 7126 0.0202989 0.0321934 0.0429233 1 0 1 1 0 0 +EDGE2 7266 7106 -0.066991 -0.00330255 0.0114532 1 0 1 1 0 0 +EDGE2 7266 7107 1.08511 -0.0447035 -0.00595189 1 0 1 1 0 0 +EDGE2 7266 7127 1.06629 0.0362945 0.0160125 1 0 1 1 0 0 +EDGE2 7267 7126 -0.981176 -0.034655 -0.0112853 1 0 1 1 0 0 +EDGE2 7267 7266 -0.948616 -0.0208779 -0.0181906 1 0 1 1 0 0 +EDGE2 7267 7106 -1.06088 -0.012134 -0.000714802 1 0 1 1 0 0 +EDGE2 7267 7107 0.0473095 0.023625 -0.00344752 1 0 1 1 0 0 +EDGE2 7267 7127 -0.0415799 -0.0276119 0.00745142 1 0 1 1 0 0 +EDGE2 7267 7128 1.05962 -0.0149867 -0.0287297 1 0 1 1 0 0 +EDGE2 7267 7108 0.993076 -0.0718359 0.00696313 1 0 1 1 0 0 +EDGE2 7268 7267 -1.01539 0.084116 -0.0303041 1 0 1 1 0 0 +EDGE2 7268 7107 -1.01193 -0.0336702 0.000557031 1 0 1 1 0 0 +EDGE2 7268 7127 -0.982558 -0.0277702 0.00184186 1 0 1 1 0 0 +EDGE2 7268 7128 -0.0201024 0.0241276 0.00997088 1 0 1 1 0 0 +EDGE2 7268 7108 -0.0107619 0.00200711 -0.00503501 1 0 1 1 0 0 +EDGE2 7268 7129 0.988905 -0.0425334 -0.0228643 1 0 1 1 0 0 +EDGE2 7268 7109 0.951904 0.103856 0.0260522 1 0 1 1 0 0 +EDGE2 7269 7128 -0.922736 -0.0103813 0.00480828 1 0 1 1 0 0 +EDGE2 7269 7268 -1.07937 -0.0312643 0.0120776 1 0 1 1 0 0 +EDGE2 7269 7108 -0.949373 0.00957107 -0.000194402 1 0 1 1 0 0 +EDGE2 7269 7129 -0.0897328 1.09125e-05 -0.0179896 1 0 1 1 0 0 +EDGE2 7269 7109 0.0126589 -0.034668 0.00928043 1 0 1 1 0 0 +EDGE2 7269 7250 0.937532 -0.0132115 -3.12857 1 0 1 1 0 0 +EDGE2 7269 7110 0.990972 0.0185228 -0.00458354 1 0 1 1 0 0 +EDGE2 7269 7130 0.968093 0.0741643 0.0190115 1 0 1 1 0 0 +EDGE2 7270 7131 -0.0536239 0.996728 1.57405 1 0 1 1 0 0 +EDGE2 7270 7251 -0.0323511 0.988424 1.52641 1 0 1 1 0 0 +EDGE2 7270 7111 0.0853947 0.990127 1.60303 1 0 1 1 0 0 +EDGE2 7270 7129 -1.06859 -0.0990343 0.0147237 1 0 1 1 0 0 +EDGE2 7270 7269 -0.992632 -0.0678224 0.000475653 1 0 1 1 0 0 +EDGE2 7270 7109 -0.942042 0.046648 0.00680486 1 0 1 1 0 0 +EDGE2 7270 7250 -0.10249 0.0525221 -3.15203 1 0 1 1 0 0 +EDGE2 7270 7110 -0.0164071 0.0077666 -0.000966022 1 0 1 1 0 0 +EDGE2 7270 7130 0.0319541 0.0267578 -0.00851452 1 0 1 1 0 0 +EDGE2 7270 7249 0.960631 0.0586341 -3.17771 1 0 1 1 0 0 +EDGE2 7271 7132 1.0123 -0.00446459 0.0120014 1 0 1 1 0 0 +EDGE2 7271 7252 0.932479 -0.00719726 0.0186875 1 0 1 1 0 0 +EDGE2 7271 7131 0.00916115 0.125583 -0.0040231 1 0 1 1 0 0 +EDGE2 7271 7112 1.04366 -0.0295918 -0.0139246 1 0 1 1 0 0 +EDGE2 7271 7251 -0.11183 0.0060813 0.00319187 1 0 1 1 0 0 +EDGE2 7271 7111 -0.0190587 0.06261 0.0287181 1 0 1 1 0 0 +EDGE2 7271 7250 -1.00701 0.0740994 1.57123 1 0 1 1 0 0 +EDGE2 7271 7270 -0.965678 0.107913 -1.56914 1 0 1 1 0 0 +EDGE2 7271 7110 -0.953506 0.0191586 -1.55421 1 0 1 1 0 0 +EDGE2 7271 7130 -0.905215 -0.0514114 -1.53664 1 0 1 1 0 0 +EDGE2 7272 7132 0.0378618 -0.0465686 0.000618747 1 0 1 1 0 0 +EDGE2 7272 7133 1.0125 0.00773397 -0.0365984 1 0 1 1 0 0 +EDGE2 7272 7253 0.985105 -0.0184987 0.00610694 1 0 1 1 0 0 +EDGE2 7272 7113 1.00135 0.0144976 -0.0201767 1 0 1 1 0 0 +EDGE2 7272 7252 0.0512243 -0.02616 0.0102656 1 0 1 1 0 0 +EDGE2 7272 7131 -1.07158 -0.0376881 0.0246799 1 0 1 1 0 0 +EDGE2 7272 7271 -0.936792 0.0135817 0.0337348 1 0 1 1 0 0 +EDGE2 7272 7112 -0.00818436 0.00901373 -0.0220624 1 0 1 1 0 0 +EDGE2 7272 7251 -0.983904 0.0205079 -0.0114556 1 0 1 1 0 0 +EDGE2 7272 7111 -1.09433 -0.0912009 0.00701309 1 0 1 1 0 0 +EDGE2 7273 7132 -0.989749 0.075317 0.0193004 1 0 1 1 0 0 +EDGE2 7273 7134 0.960023 -0.0558804 0.0175326 1 0 1 1 0 0 +EDGE2 7273 7254 0.98196 -0.0144315 -0.00144447 1 0 1 1 0 0 +EDGE2 7273 7133 0.0224221 0.0366981 0.00977201 1 0 1 1 0 0 +EDGE2 7273 7114 0.964111 0.0423008 0.0104355 1 0 1 1 0 0 +EDGE2 7273 7253 0.00273279 -0.0314633 -0.0130187 1 0 1 1 0 0 +EDGE2 7273 7272 -0.980706 0.0202648 -0.011947 1 0 1 1 0 0 +EDGE2 7273 7113 0.00369812 0.0541627 0.0281672 1 0 1 1 0 0 +EDGE2 7273 7252 -1.00475 -0.0420383 0.000879116 1 0 1 1 0 0 +EDGE2 7273 7112 -0.951464 0.0702986 -0.00728389 1 0 1 1 0 0 +EDGE2 7274 7134 -0.0940889 -0.0487028 0.0112214 1 0 1 1 0 0 +EDGE2 7274 7135 1.00713 0.0233086 0.0112274 1 0 1 1 0 0 +EDGE2 7274 7255 0.928681 0.0560118 0.0144981 1 0 1 1 0 0 +EDGE2 7274 7175 1.00679 -0.0111031 -3.16263 1 0 1 1 0 0 +EDGE2 7274 7115 0.988373 -0.0545026 0.0188789 1 0 1 1 0 0 +EDGE2 7274 7254 0.0236163 -0.0325791 -0.00399371 1 0 1 1 0 0 +EDGE2 7274 7133 -0.932552 -0.0221034 -0.000971458 1 0 1 1 0 0 +EDGE2 7274 7273 -0.966169 -0.028896 0.0305067 1 0 1 1 0 0 +EDGE2 7274 7114 -0.0819027 -0.0554208 -0.00269708 1 0 1 1 0 0 +EDGE2 7274 7253 -1.01523 0.0488917 -0.000325381 1 0 1 1 0 0 +EDGE2 7274 7113 -0.971918 0.035123 0.000708154 1 0 1 1 0 0 +EDGE2 7275 7136 0.0123225 0.972376 1.57204 1 0 1 1 0 0 +EDGE2 7275 7256 7.41335e-05 1.07343 1.58473 1 0 1 1 0 0 +EDGE2 7275 7116 -0.0340043 1.02049 1.56595 1 0 1 1 0 0 +EDGE2 7275 7174 1.00276 0.00959119 -3.16807 1 0 1 1 0 0 +EDGE2 7275 7134 -0.984422 -0.0832096 -0.00328639 1 0 1 1 0 0 +EDGE2 7275 7135 -0.129051 0.0507272 -0.00413453 1 0 1 1 0 0 +EDGE2 7275 7255 0.0219135 -0.0745678 -0.0089715 1 0 1 1 0 0 +EDGE2 7275 7175 0.0133673 -0.0112954 -3.13926 1 0 1 1 0 0 +EDGE2 7275 7274 -0.961326 -0.0449403 0.0369116 1 0 1 1 0 0 +EDGE2 7275 7115 -0.0649412 0.0232015 -0.0257242 1 0 1 1 0 0 +EDGE2 7275 7254 -1.04293 -0.0639727 0.0126372 1 0 1 1 0 0 +EDGE2 7275 7114 -0.926026 0.0553744 0.025843 1 0 1 1 0 0 +EDGE2 7275 7176 0.0118748 -0.897536 -1.56803 1 0 1 1 0 0 +EDGE2 7276 7135 -0.976091 0.155891 1.59861 1 0 1 1 0 0 +EDGE2 7276 7255 -0.974087 0.014201 1.57335 1 0 1 1 0 0 +EDGE2 7276 7275 -1.09578 0.00757835 1.5752 1 0 1 1 0 0 +EDGE2 7276 7175 -0.917539 -0.0181797 -1.56901 1 0 1 1 0 0 +EDGE2 7276 7115 -0.944695 -0.027349 1.57338 1 0 1 1 0 0 +EDGE2 7276 7176 0.0275859 0.0296663 -0.0169051 1 0 1 1 0 0 +EDGE2 7276 7177 1.06704 -0.0553136 0.00354709 1 0 1 1 0 0 +EDGE2 7277 7176 -1.05198 -0.0460754 0.00499156 1 0 1 1 0 0 +EDGE2 7277 7276 -0.972857 0.00507687 -0.00087016 1 0 1 1 0 0 +EDGE2 7277 7177 -0.0792187 0.0322334 -0.000256417 1 0 1 1 0 0 +EDGE2 7277 7178 0.950253 0.0625466 -0.00270024 1 0 1 1 0 0 +EDGE2 7278 7277 -0.954685 -0.0279349 -0.00597403 1 0 1 1 0 0 +EDGE2 7278 7177 -0.994159 -0.0368521 -0.00523795 1 0 1 1 0 0 +EDGE2 7278 7178 -0.0134376 0.0854195 0.000416417 1 0 1 1 0 0 +EDGE2 7278 7179 1.00149 -0.0294315 -0.00621563 1 0 1 1 0 0 +EDGE2 7279 7178 -0.993142 0.0441167 0.0196765 1 0 1 1 0 0 +EDGE2 7279 7278 -0.990992 -0.0910716 -0.0191034 1 0 1 1 0 0 +EDGE2 7279 7179 -0.0623216 -0.0171558 -0.0114935 1 0 1 1 0 0 +EDGE2 7279 7180 0.922314 -0.0540253 0.00883385 1 0 1 1 0 0 +EDGE2 7280 7279 -0.947602 0.0621086 0.00152276 1 0 1 1 0 0 +EDGE2 7280 7179 -1.0964 -0.028535 -0.0131159 1 0 1 1 0 0 +EDGE2 7280 7181 -0.0569685 0.924714 1.56272 1 0 1 1 0 0 +EDGE2 7280 7180 0.0364644 -0.0285857 0.0528046 1 0 1 1 0 0 +EDGE2 7281 7182 0.967822 -0.0160509 -0.019574 1 0 1 1 0 0 +EDGE2 7281 7181 -0.0270411 0.0361855 0.0171846 1 0 1 1 0 0 +EDGE2 7281 7180 -0.941856 0.0198949 -1.56662 1 0 1 1 0 0 +EDGE2 7281 7280 -1.07913 -0.0655138 -1.54725 1 0 1 1 0 0 +EDGE2 7282 7183 0.964802 0.103748 0.0227367 1 0 1 1 0 0 +EDGE2 7282 7182 -0.00444341 -0.0430399 -0.000129939 1 0 1 1 0 0 +EDGE2 7282 7281 -0.977339 -0.0363614 -0.0164172 1 0 1 1 0 0 +EDGE2 7282 7181 -1.00523 0.0450765 0.00314408 1 0 1 1 0 0 +EDGE2 7283 7184 0.979764 0.0434539 -0.0120086 1 0 1 1 0 0 +EDGE2 7283 7183 0.0548491 -0.00351951 -0.0173696 1 0 1 1 0 0 +EDGE2 7283 7282 -1.0786 0.0260099 0.00608998 1 0 1 1 0 0 +EDGE2 7283 7182 -0.940846 -0.0358563 -0.000570037 1 0 1 1 0 0 +EDGE2 7284 7185 0.945177 0.015278 0.0324966 1 0 1 1 0 0 +EDGE2 7284 7184 0.135529 0.0870966 0.0198111 1 0 1 1 0 0 +EDGE2 7284 7283 -0.971166 0.00656428 -0.016393 1 0 1 1 0 0 +EDGE2 7284 7183 -1.0422 0.0177533 0.00680215 1 0 1 1 0 0 +EDGE2 7285 7185 -0.0192138 0.0134041 0.012038 1 0 1 1 0 0 +EDGE2 7285 7186 -0.00341472 -0.973888 -1.57858 1 0 1 1 0 0 +EDGE2 7285 7184 -1.0684 -0.0311854 -0.0412178 1 0 1 1 0 0 +EDGE2 7285 7284 -0.99117 0.056652 0.00956342 1 0 1 1 0 0 +EDGE2 7286 7285 -1.04235 -0.0518288 -1.53224 1 0 1 1 0 0 +EDGE2 7286 7185 -0.967556 -0.0610111 -1.60626 1 0 1 1 0 0 +EDGE2 7287 7286 -0.981913 0.00989455 -0.00493349 1 0 1 1 0 0 +EDGE2 7288 7287 -0.968537 -0.00671822 0.00446102 1 0 1 1 0 0 +EDGE2 7289 7170 0.983837 -0.0280074 -3.13491 1 0 1 1 0 0 +EDGE2 7289 7288 -1.04538 0.019313 0.0232834 1 0 1 1 0 0 +EDGE2 7290 7169 0.965047 -0.0240579 -3.12837 1 0 1 1 0 0 +EDGE2 7290 7170 0.0813205 0.00467651 -3.1211 1 0 1 1 0 0 +EDGE2 7290 7289 -0.950897 0.0671127 0.0303131 1 0 1 1 0 0 +EDGE2 7290 7171 0.0837626 0.993741 1.60457 1 0 1 1 0 0 +EDGE2 7291 7170 -1.06434 -0.0177042 1.56459 1 0 1 1 0 0 +EDGE2 7291 7290 -1.03405 -0.0697803 -1.56479 1 0 1 1 0 0 +EDGE2 7291 7171 0.00204739 -0.0569242 0.012777 1 0 1 1 0 0 +EDGE2 7291 7172 1.07117 -0.00579045 -0.00560374 1 0 1 1 0 0 +EDGE2 7292 7291 -1.02661 0.0677262 -0.000701786 1 0 1 1 0 0 +EDGE2 7292 7171 -0.996702 0.0377867 -0.0223413 1 0 1 1 0 0 +EDGE2 7292 7172 0.0984388 0.0220126 0.00516788 1 0 1 1 0 0 +EDGE2 7292 7173 1.0097 0.0444495 0.0210774 1 0 1 1 0 0 +EDGE2 7293 7172 -1.03851 -0.0986714 0.0117127 1 0 1 1 0 0 +EDGE2 7293 7292 -0.982061 0.00554217 -0.0059665 1 0 1 1 0 0 +EDGE2 7293 7173 -0.0086069 0.0450548 0.0244766 1 0 1 1 0 0 +EDGE2 7293 7174 0.993836 0.106511 0.0153165 1 0 1 1 0 0 +EDGE2 7294 7173 -0.990759 0.0557452 0.00856986 1 0 1 1 0 0 +EDGE2 7294 7293 -1.0907 -0.0854625 -0.0060735 1 0 1 1 0 0 +EDGE2 7294 7174 -0.0367812 0.00208319 -0.0173808 1 0 1 1 0 0 +EDGE2 7294 7135 0.965437 -0.0237857 -3.15243 1 0 1 1 0 0 +EDGE2 7294 7255 0.97128 -0.00951325 -3.1519 1 0 1 1 0 0 +EDGE2 7294 7275 1.00929 0.0537848 -3.15143 1 0 1 1 0 0 +EDGE2 7294 7175 1.0005 -0.000900149 -0.000278538 1 0 1 1 0 0 +EDGE2 7294 7115 0.961451 0.0537371 -3.14902 1 0 1 1 0 0 +EDGE2 7295 7136 0.0458138 -1.02383 -1.57117 1 0 1 1 0 0 +EDGE2 7295 7256 0.0444229 -1.04511 -1.55261 1 0 1 1 0 0 +EDGE2 7295 7116 0.00965943 -0.98847 -1.57027 1 0 1 1 0 0 +EDGE2 7295 7294 -1.19985 0.0898148 0.0212783 1 0 1 1 0 0 +EDGE2 7295 7174 -0.986246 -0.0699931 0.0214972 1 0 1 1 0 0 +EDGE2 7295 7134 0.969453 0.0597752 -3.1345 1 0 1 1 0 0 +EDGE2 7295 7135 0.0151479 0.02252 -3.15777 1 0 1 1 0 0 +EDGE2 7295 7255 0.0424163 0.0242444 -3.16573 1 0 1 1 0 0 +EDGE2 7295 7275 -0.037725 -0.00800932 -3.11208 1 0 1 1 0 0 +EDGE2 7295 7175 0.0689713 -0.0131381 0.0152494 1 0 1 1 0 0 +EDGE2 7295 7274 0.914602 0.028168 -3.15269 1 0 1 1 0 0 +EDGE2 7295 7115 -0.0627902 0.0407557 -3.13974 1 0 1 1 0 0 +EDGE2 7295 7254 0.892691 0.00145127 -3.14903 1 0 1 1 0 0 +EDGE2 7295 7114 1.00537 0.00239168 -3.11394 1 0 1 1 0 0 +EDGE2 7295 7176 -0.000104863 0.958251 1.55524 1 0 1 1 0 0 +EDGE2 7295 7276 -0.0421046 1.00335 1.54752 1 0 1 1 0 0 +EDGE2 7296 7277 1.0602 0.0271819 -0.0259021 1 0 1 1 0 0 +EDGE2 7296 7135 -1.00055 0.000690024 1.57186 1 0 1 1 0 0 +EDGE2 7296 7255 -1.02167 -0.0137253 1.62597 1 0 1 1 0 0 +EDGE2 7296 7275 -0.943783 -0.0422738 1.57798 1 0 1 1 0 0 +EDGE2 7296 7295 -0.968187 0.00391853 -1.60475 1 0 1 1 0 0 +EDGE2 7296 7175 -1.06468 -0.0476372 -1.57936 1 0 1 1 0 0 +EDGE2 7296 7115 -0.890256 -0.0130099 1.55514 1 0 1 1 0 0 +EDGE2 7296 7176 0.0875524 -0.0515363 0.0152878 1 0 1 1 0 0 +EDGE2 7296 7276 0.0595431 -0.00698616 -0.0331859 1 0 1 1 0 0 +EDGE2 7296 7177 0.99895 -0.0230168 0.00800502 1 0 1 1 0 0 +EDGE2 7297 7277 -0.0643521 0.030836 -0.0165171 1 0 1 1 0 0 +EDGE2 7297 7296 -0.966257 -0.129931 0.00178378 1 0 1 1 0 0 +EDGE2 7297 7176 -0.965222 0.0158256 -0.0145532 1 0 1 1 0 0 +EDGE2 7297 7276 -1.05295 0.0323729 0.0134983 1 0 1 1 0 0 +EDGE2 7297 7177 0.00960333 -0.0065617 0.0105354 1 0 1 1 0 0 +EDGE2 7297 7178 0.997345 -0.0383846 0.0303598 1 0 1 1 0 0 +EDGE2 7297 7278 1.01314 -0.00772242 -0.0216789 1 0 1 1 0 0 +EDGE2 7298 7277 -0.927106 -0.0482982 0.0441924 1 0 1 1 0 0 +EDGE2 7298 7297 -1.02708 -0.0190067 -0.0120382 1 0 1 1 0 0 +EDGE2 7298 7177 -0.998387 -0.0228504 -0.0203833 1 0 1 1 0 0 +EDGE2 7298 7178 0.0228698 -0.0115872 0.0590438 1 0 1 1 0 0 +EDGE2 7298 7278 0.0114986 0.0481207 -0.0176458 1 0 1 1 0 0 +EDGE2 7298 7279 0.969095 -0.0252373 -0.00460895 1 0 1 1 0 0 +EDGE2 7298 7179 0.954448 -0.00987721 0.0180292 1 0 1 1 0 0 +EDGE2 7299 7298 -1.01798 0.000400951 -0.0104203 1 0 1 1 0 0 +EDGE2 7299 7178 -0.987177 -0.0123495 0.00211672 1 0 1 1 0 0 +EDGE2 7299 7278 -0.95337 0.0238003 -0.000795917 1 0 1 1 0 0 +EDGE2 7299 7279 0.00990547 -0.0312823 -0.00171658 1 0 1 1 0 0 +EDGE2 7299 7179 0.0321124 0.0326288 -0.00510738 1 0 1 1 0 0 +EDGE2 7299 7180 0.986312 -0.000211819 0.00686452 1 0 1 1 0 0 +EDGE2 7299 7280 1.04033 -0.0470001 -0.00125407 1 0 1 1 0 0 +EDGE2 7300 7279 -1.00988 0.000627653 -0.00693985 1 0 1 1 0 0 +EDGE2 7300 7299 -0.996364 0.0314166 -0.0018572 1 0 1 1 0 0 +EDGE2 7300 7179 -0.993398 0.0989714 0.00176127 1 0 1 1 0 0 +EDGE2 7300 7281 -0.0818934 1.05448 1.56082 1 0 1 1 0 0 +EDGE2 7300 7181 0.0759404 1.00331 1.59487 1 0 1 1 0 0 +EDGE2 7300 7180 0.036245 -0.0322417 -0.0129183 1 0 1 1 0 0 +EDGE2 7300 7280 -0.0211952 -0.023515 -0.0189907 1 0 1 1 0 0 +EDGE2 7301 7282 1.07173 0.0598291 0.0026855 1 0 1 1 0 0 +EDGE2 7301 7182 0.913759 -0.0316244 -0.0177883 1 0 1 1 0 0 +EDGE2 7301 7281 -0.0114465 0.0889088 -0.00201503 1 0 1 1 0 0 +EDGE2 7301 7181 0.0675097 -0.0282572 0.0163099 1 0 1 1 0 0 +EDGE2 7301 7180 -1.01858 -0.0225949 -1.59101 1 0 1 1 0 0 +EDGE2 7301 7280 -0.895116 0.010475 -1.58079 1 0 1 1 0 0 +EDGE2 7301 7300 -1.0453 -0.0412807 -1.52793 1 0 1 1 0 0 +EDGE2 7302 7283 1.00082 0.0707723 0.00740535 1 0 1 1 0 0 +EDGE2 7302 7183 0.971059 0.0473443 0.035973 1 0 1 1 0 0 +EDGE2 7302 7282 0.0493927 -0.0373729 0.0124209 1 0 1 1 0 0 +EDGE2 7302 7182 -0.0845276 0.0117507 0.00882735 1 0 1 1 0 0 +EDGE2 7302 7281 -1.03681 0.0515496 -0.00494539 1 0 1 1 0 0 +EDGE2 7302 7301 -0.959336 -0.0500558 -0.0127382 1 0 1 1 0 0 +EDGE2 7302 7181 -1.05102 -0.00241671 -0.0210549 1 0 1 1 0 0 +EDGE2 7303 7184 1.01911 0.0275837 0.0054889 1 0 1 1 0 0 +EDGE2 7303 7284 1.10415 0.116254 0.0286109 1 0 1 1 0 0 +EDGE2 7303 7283 0.0521816 0.0311492 -0.0122991 1 0 1 1 0 0 +EDGE2 7303 7183 -0.0475973 -0.0421033 -0.0263897 1 0 1 1 0 0 +EDGE2 7303 7282 -0.984345 -0.0183354 -0.0193065 1 0 1 1 0 0 +EDGE2 7303 7302 -1.0403 0.0205902 -0.0348688 1 0 1 1 0 0 +EDGE2 7303 7182 -0.980633 0.0283442 0.0431186 1 0 1 1 0 0 +EDGE2 7304 7285 1.00187 0.0273638 0.0103405 1 0 1 1 0 0 +EDGE2 7304 7185 1.0159 0.00301087 0.00755705 1 0 1 1 0 0 +EDGE2 7304 7184 -0.0644928 0.0170074 0.00730312 1 0 1 1 0 0 +EDGE2 7304 7284 -0.0323208 0.0237101 0.0179071 1 0 1 1 0 0 +EDGE2 7304 7283 -0.988356 -0.0236883 -0.00175863 1 0 1 1 0 0 +EDGE2 7304 7303 -1.0293 -0.0173141 -0.0403494 1 0 1 1 0 0 +EDGE2 7304 7183 -1.02995 0.066789 0.0379845 1 0 1 1 0 0 +EDGE2 7305 7286 0.130674 1.01344 1.58738 1 0 1 1 0 0 +EDGE2 7305 7285 -0.0335455 0.0245259 -0.0105323 1 0 1 1 0 0 +EDGE2 7305 7185 -0.00492619 0.0157072 -0.00161299 1 0 1 1 0 0 +EDGE2 7305 7186 -0.0015397 -1.09751 -1.56049 1 0 1 1 0 0 +EDGE2 7305 7304 -0.987211 -0.0651465 -0.00830581 1 0 1 1 0 0 +EDGE2 7305 7184 -1.02033 0.0466871 -0.00451749 1 0 1 1 0 0 +EDGE2 7305 7284 -1.03608 -0.0348647 0.00274765 1 0 1 1 0 0 +EDGE2 7306 7287 0.993442 0.0240259 0.00904154 1 0 1 1 0 0 +EDGE2 7306 7286 0.0666326 0.0671266 -0.013427 1 0 1 1 0 0 +EDGE2 7306 7285 -1.01679 -0.0267978 -1.57986 1 0 1 1 0 0 +EDGE2 7306 7305 -0.919011 0.012083 -1.54783 1 0 1 1 0 0 +EDGE2 7306 7185 -1.03397 -0.0381723 -1.61711 1 0 1 1 0 0 +EDGE2 7307 7288 0.943912 0.00998225 0.00446899 1 0 1 1 0 0 +EDGE2 7307 7287 -0.020411 -0.0781678 0.0369979 1 0 1 1 0 0 +EDGE2 7307 7286 -1.02124 0.0879103 -0.00651623 1 0 1 1 0 0 +EDGE2 7307 7306 -1.02387 0.0849415 -0.0193851 1 0 1 1 0 0 +EDGE2 7308 7289 1.02039 0.0193911 -0.0536688 1 0 1 1 0 0 +EDGE2 7308 7288 0.0124442 0.0503533 -0.0106004 1 0 1 1 0 0 +EDGE2 7308 7307 -0.956203 0.034598 0.00228291 1 0 1 1 0 0 +EDGE2 7308 7287 -0.942516 0.02008 -0.0224902 1 0 1 1 0 0 +EDGE2 7309 7170 1.03014 0.0641012 -3.14089 1 0 1 1 0 0 +EDGE2 7309 7290 0.964648 -0.060995 0.0725537 1 0 1 1 0 0 +EDGE2 7309 7289 0.0522753 0.00168143 -0.00869527 1 0 1 1 0 0 +EDGE2 7309 7308 -0.98355 0.0584471 -0.0346613 1 0 1 1 0 0 +EDGE2 7309 7288 -1.01245 0.0357046 0.0277267 1 0 1 1 0 0 +EDGE2 7310 7169 1.14644 -0.018407 -3.1596 1 0 1 1 0 0 +EDGE2 7310 7170 0.0508234 -0.038256 -3.17455 1 0 1 1 0 0 +EDGE2 7310 7290 -0.036536 0.0269013 -0.0534767 1 0 1 1 0 0 +EDGE2 7310 7289 -1.03088 -0.0877408 0.0193733 1 0 1 1 0 0 +EDGE2 7310 7309 -0.983553 0.0639783 0.0232895 1 0 1 1 0 0 +EDGE2 7310 7291 0.00386576 0.984856 1.54463 1 0 1 1 0 0 +EDGE2 7310 7171 -0.0633112 1.05205 1.56032 1 0 1 1 0 0 +EDGE2 7311 7310 -1.00069 -0.033143 -1.58364 1 0 1 1 0 0 +EDGE2 7311 7170 -1.09026 0.0387137 1.56682 1 0 1 1 0 0 +EDGE2 7311 7290 -0.993339 -0.05896 -1.55213 1 0 1 1 0 0 +EDGE2 7311 7291 0.0154999 -0.148059 0.0156585 1 0 1 1 0 0 +EDGE2 7311 7171 0.0919464 0.021045 0.0197385 1 0 1 1 0 0 +EDGE2 7311 7172 0.986209 0.0140196 0.011652 1 0 1 1 0 0 +EDGE2 7311 7292 1.08958 -0.0106887 0.0223221 1 0 1 1 0 0 +EDGE2 7312 7291 -1.0829 0.0490251 -0.014094 1 0 1 1 0 0 +EDGE2 7312 7311 -0.966847 0.0137415 0.00383174 1 0 1 1 0 0 +EDGE2 7312 7171 -0.936797 0.0080538 0.00542228 1 0 1 1 0 0 +EDGE2 7312 7172 -0.0787698 -0.00915168 0.00874795 1 0 1 1 0 0 +EDGE2 7312 7292 -0.0518772 -0.085828 0.0226681 1 0 1 1 0 0 +EDGE2 7312 7173 1.07609 0.00334749 -0.00766162 1 0 1 1 0 0 +EDGE2 7312 7293 1.04191 0.00183681 0.0181492 1 0 1 1 0 0 +EDGE2 7313 7312 -0.953337 0.0630582 0.00746404 1 0 1 1 0 0 +EDGE2 7313 7172 -1.01402 0.0632292 0.021136 1 0 1 1 0 0 +EDGE2 7313 7292 -0.918386 0.0243038 0.00666447 1 0 1 1 0 0 +EDGE2 7313 7173 0.00787224 0.0386014 0.0144302 1 0 1 1 0 0 +EDGE2 7313 7293 -0.0111502 -0.024723 -0.0238737 1 0 1 1 0 0 +EDGE2 7313 7294 0.98457 -0.0314324 0.0247503 1 0 1 1 0 0 +EDGE2 7313 7174 1.0171 -0.0627059 -0.0450254 1 0 1 1 0 0 +EDGE2 7314 7173 -1.04565 0.0457908 0.00727743 1 0 1 1 0 0 +EDGE2 7314 7293 -1.07911 0.0310705 -0.0269772 1 0 1 1 0 0 +EDGE2 7314 7313 -1.01578 0.00675738 0.0398975 1 0 1 1 0 0 +EDGE2 7314 7294 -0.0103207 0.0700443 0.00281383 1 0 1 1 0 0 +EDGE2 7314 7174 -0.00755537 -0.0658599 -0.0108411 1 0 1 1 0 0 +EDGE2 7314 7135 1.03044 0.0482812 -3.15712 1 0 1 1 0 0 +EDGE2 7314 7255 0.954725 0.0784922 -3.13002 1 0 1 1 0 0 +EDGE2 7314 7275 1.01549 0.0466703 -3.17872 1 0 1 1 0 0 +EDGE2 7314 7295 0.97231 -0.0096503 -0.00613905 1 0 1 1 0 0 +EDGE2 7314 7175 1.0375 0.0538469 -0.0200528 1 0 1 1 0 0 +EDGE2 7314 7115 1.07561 0.0857973 -3.11711 1 0 1 1 0 0 +EDGE2 7315 7136 0.0394269 -0.953651 -1.59295 1 0 1 1 0 0 +EDGE2 7315 7256 0.019107 -1.04771 -1.56502 1 0 1 1 0 0 +EDGE2 7315 7116 0.0169355 -1.0654 -1.58068 1 0 1 1 0 0 +EDGE2 7315 7294 -0.995028 0.0235392 -0.00560724 1 0 1 1 0 0 +EDGE2 7315 7314 -1.00461 -0.0198626 0.0409844 1 0 1 1 0 0 +EDGE2 7315 7174 -0.979508 0.022577 0.0121165 1 0 1 1 0 0 +EDGE2 7315 7134 0.99281 -0.0824781 -3.12555 1 0 1 1 0 0 +EDGE2 7315 7135 0.0650169 -0.0659747 -3.18047 1 0 1 1 0 0 +EDGE2 7315 7255 0.0292203 -0.113578 -3.16756 1 0 1 1 0 0 +EDGE2 7315 7275 -0.029024 0.0873603 -3.11202 1 0 1 1 0 0 +EDGE2 7315 7295 0.0311039 -0.00623414 0.0101517 1 0 1 1 0 0 +EDGE2 7315 7175 -0.0497983 -0.0118161 0.00176209 1 0 1 1 0 0 +EDGE2 7315 7274 1.06212 -0.0172682 -3.15012 1 0 1 1 0 0 +EDGE2 7315 7115 -0.00648613 0.0821977 -3.16228 1 0 1 1 0 0 +EDGE2 7315 7254 1.13065 -0.00195811 -3.11181 1 0 1 1 0 0 +EDGE2 7315 7114 0.920507 -0.00218987 -3.15225 1 0 1 1 0 0 +EDGE2 7315 7296 -0.0462335 0.994957 1.56714 1 0 1 1 0 0 +EDGE2 7315 7176 -0.0722548 0.944275 1.57897 1 0 1 1 0 0 +EDGE2 7315 7276 0.00575923 0.958194 1.55436 1 0 1 1 0 0 +EDGE2 7316 7277 1.09696 -0.0942419 5.9476e-05 1 0 1 1 0 0 +EDGE2 7316 7315 -1.05294 -0.00566255 -1.56874 1 0 1 1 0 0 +EDGE2 7316 7135 -1.08041 0.0194847 1.55936 1 0 1 1 0 0 +EDGE2 7316 7255 -1.03558 0.0564329 1.61167 1 0 1 1 0 0 +EDGE2 7316 7275 -0.951868 -0.0161589 1.62407 1 0 1 1 0 0 +EDGE2 7316 7295 -0.971766 0.0646575 -1.58442 1 0 1 1 0 0 +EDGE2 7316 7175 -0.903387 0.0236903 -1.5569 1 0 1 1 0 0 +EDGE2 7316 7115 -1.03415 -0.00893022 1.58079 1 0 1 1 0 0 +EDGE2 7316 7296 0.0222799 -0.000328019 0.0140092 1 0 1 1 0 0 +EDGE2 7316 7176 0.10723 -0.0409835 0.0195106 1 0 1 1 0 0 +EDGE2 7316 7276 0.0204766 0.00913243 -0.00357625 1 0 1 1 0 0 +EDGE2 7316 7297 0.981547 -0.0202143 -0.0249374 1 0 1 1 0 0 +EDGE2 7316 7177 0.982503 0.0708037 0.020536 1 0 1 1 0 0 +EDGE2 7317 7277 0.0378399 0.0292046 -0.00112491 1 0 1 1 0 0 +EDGE2 7317 7296 -0.964632 0.0192922 0.0392266 1 0 1 1 0 0 +EDGE2 7317 7316 -1.03644 -0.00286109 0.0069098 1 0 1 1 0 0 +EDGE2 7317 7176 -0.930069 0.00208465 0.0254758 1 0 1 1 0 0 +EDGE2 7317 7276 -1.07131 0.0218172 -0.00290442 1 0 1 1 0 0 +EDGE2 7317 7297 -0.104723 -0.115219 -0.0113261 1 0 1 1 0 0 +EDGE2 7317 7298 1.00296 -0.0316934 -0.0261321 1 0 1 1 0 0 +EDGE2 7317 7177 0.0188708 -0.0180094 0.00209368 1 0 1 1 0 0 +EDGE2 7317 7178 0.931214 -0.0490096 0.0103656 1 0 1 1 0 0 +EDGE2 7317 7278 1.01672 0.136028 -0.0120395 1 0 1 1 0 0 +EDGE2 7318 7277 -0.975544 -0.114549 0.0178663 1 0 1 1 0 0 +EDGE2 7318 7317 -0.968332 -0.0186148 0.0273233 1 0 1 1 0 0 +EDGE2 7318 7297 -1.08911 0.0129778 0.0217927 1 0 1 1 0 0 +EDGE2 7318 7298 0.0444373 0.0138906 0.000805396 1 0 1 1 0 0 +EDGE2 7318 7177 -0.848933 -0.00163615 -0.0580437 1 0 1 1 0 0 +EDGE2 7318 7178 0.107593 0.0168552 -0.00551514 1 0 1 1 0 0 +EDGE2 7318 7278 -0.0342314 0.0205367 -0.0141722 1 0 1 1 0 0 +EDGE2 7318 7279 0.998089 0.0425492 -0.0155437 1 0 1 1 0 0 +EDGE2 7318 7299 0.993882 -0.0182237 0.00898525 1 0 1 1 0 0 +EDGE2 7318 7179 0.981756 -0.00421741 -0.000474219 1 0 1 1 0 0 +EDGE2 7319 7298 -0.981616 0.125579 -0.0108788 1 0 1 1 0 0 +EDGE2 7319 7318 -1.07137 -0.0555021 0.0337405 1 0 1 1 0 0 +EDGE2 7319 7178 -1.09297 0.00970986 0.011519 1 0 1 1 0 0 +EDGE2 7319 7278 -1.00568 -0.0417703 0.0132593 1 0 1 1 0 0 +EDGE2 7319 7279 -0.0348647 0.0192553 0.0126718 1 0 1 1 0 0 +EDGE2 7319 7299 0.0507857 0.0113384 -0.00468366 1 0 1 1 0 0 +EDGE2 7319 7179 0.0022546 -0.0737948 0.0151956 1 0 1 1 0 0 +EDGE2 7319 7180 0.954141 -0.0991937 0.000604857 1 0 1 1 0 0 +EDGE2 7319 7280 0.979074 -0.0179112 0.00610324 1 0 1 1 0 0 +EDGE2 7319 7300 1.04199 -0.0601929 -0.0235228 1 0 1 1 0 0 +EDGE2 7320 7279 -1.0211 0.0177534 -0.0226043 1 0 1 1 0 0 +EDGE2 7320 7299 -0.983124 0.0231522 -0.0124687 1 0 1 1 0 0 +EDGE2 7320 7319 -1.08762 -0.0156298 0.0391478 1 0 1 1 0 0 +EDGE2 7320 7179 -1.04658 -0.0259703 0.0100989 1 0 1 1 0 0 +EDGE2 7320 7281 -0.0309084 0.933755 1.62041 1 0 1 1 0 0 +EDGE2 7320 7301 0.0334557 1.01325 1.56448 1 0 1 1 0 0 +EDGE2 7320 7181 -0.0263881 0.987481 1.59078 1 0 1 1 0 0 +EDGE2 7320 7180 0.0169055 -0.0079358 -0.0201168 1 0 1 1 0 0 +EDGE2 7320 7280 0.0354773 0.0480119 -0.00860852 1 0 1 1 0 0 +EDGE2 7320 7300 -0.0274493 -0.0708239 -0.00162729 1 0 1 1 0 0 +EDGE2 7321 7282 0.987219 -0.103221 0.0216341 1 0 1 1 0 0 +EDGE2 7321 7302 1.00646 0.0575049 -0.0197853 1 0 1 1 0 0 +EDGE2 7321 7182 1.0185 0.00825258 -0.0228808 1 0 1 1 0 0 +EDGE2 7321 7320 -0.93961 -0.0744285 -1.60255 1 0 1 1 0 0 +EDGE2 7321 7281 0.00289439 0.051722 0.00381003 1 0 1 1 0 0 +EDGE2 7321 7301 0.00487038 0.0251103 -0.00946825 1 0 1 1 0 0 +EDGE2 7321 7181 -0.00419983 0.00757052 -0.00868327 1 0 1 1 0 0 +EDGE2 7321 7180 -1.03396 -0.00415682 -1.56886 1 0 1 1 0 0 +EDGE2 7321 7280 -0.98011 0.0549055 -1.5851 1 0 1 1 0 0 +EDGE2 7321 7300 -0.941635 -0.00184031 -1.562 1 0 1 1 0 0 +EDGE2 7322 7283 0.908725 0.00678392 0.00714437 1 0 1 1 0 0 +EDGE2 7322 7303 1.04065 0.00992848 0.00612445 1 0 1 1 0 0 +EDGE2 7322 7183 0.973993 -0.00307356 0.0101718 1 0 1 1 0 0 +EDGE2 7322 7282 -0.0613419 -0.036762 0.00354086 1 0 1 1 0 0 +EDGE2 7322 7302 0.000177315 -0.0184251 -0.00664487 1 0 1 1 0 0 +EDGE2 7322 7182 -0.0348723 -0.0369561 0.00962396 1 0 1 1 0 0 +EDGE2 7322 7281 -1.08439 0.0700477 -0.00297083 1 0 1 1 0 0 +EDGE2 7322 7301 -1.07766 -0.0563008 0.0023828 1 0 1 1 0 0 +EDGE2 7322 7321 -0.966381 0.0453929 0.0177495 1 0 1 1 0 0 +EDGE2 7322 7181 -1.04016 0.00870631 0.0107805 1 0 1 1 0 0 +EDGE2 7323 7304 0.987888 -0.0128371 -0.0133916 1 0 1 1 0 0 +EDGE2 7323 7184 0.922809 0.0167854 0.0231969 1 0 1 1 0 0 +EDGE2 7323 7284 1.06121 0.0704489 -0.00781152 1 0 1 1 0 0 +EDGE2 7323 7283 0.0432894 0.0243407 -0.0126161 1 0 1 1 0 0 +EDGE2 7323 7303 0.0644287 0.000118975 0.0245689 1 0 1 1 0 0 +EDGE2 7323 7183 0.0273382 0.079131 -0.00595754 1 0 1 1 0 0 +EDGE2 7323 7282 -1.0138 -0.0116684 0.0364422 1 0 1 1 0 0 +EDGE2 7323 7322 -0.977635 -0.0142629 -0.0167684 1 0 1 1 0 0 +EDGE2 7323 7302 -1.02228 -0.0255971 0.0478488 1 0 1 1 0 0 +EDGE2 7323 7182 -1.01719 -0.0340747 -0.016467 1 0 1 1 0 0 +EDGE2 7324 7285 0.95402 0.0378771 -0.0246033 1 0 1 1 0 0 +EDGE2 7324 7305 0.983749 -0.0663427 0.00870997 1 0 1 1 0 0 +EDGE2 7324 7185 0.988693 0.0266058 0.0374624 1 0 1 1 0 0 +EDGE2 7324 7304 -0.0281097 -0.0643046 0.0400778 1 0 1 1 0 0 +EDGE2 7324 7184 0.00620647 0.088616 0.00346551 1 0 1 1 0 0 +EDGE2 7324 7284 0.0283007 -0.0271894 -0.0285178 1 0 1 1 0 0 +EDGE2 7324 7283 -1.04136 0.0225126 -0.00399147 1 0 1 1 0 0 +EDGE2 7324 7303 -0.944114 0.00420086 -0.0145561 1 0 1 1 0 0 +EDGE2 7324 7323 -0.981559 -0.0102165 0.00812816 1 0 1 1 0 0 +EDGE2 7324 7183 -1.04712 -0.0894773 0.000164247 1 0 1 1 0 0 +EDGE2 7325 7286 0.0254588 0.942189 1.56217 1 0 1 1 0 0 +EDGE2 7325 7306 0.0364882 1.0321 1.57269 1 0 1 1 0 0 +EDGE2 7325 7285 -0.0215899 0.0157492 -0.00338748 1 0 1 1 0 0 +EDGE2 7325 7305 0.0196226 -0.0658722 -0.0121237 1 0 1 1 0 0 +EDGE2 7325 7185 0.0606031 0.018124 0.032046 1 0 1 1 0 0 +EDGE2 7325 7186 0.0226434 -1.04515 -1.58553 1 0 1 1 0 0 +EDGE2 7325 7304 -0.972951 0.117994 -0.00675369 1 0 1 1 0 0 +EDGE2 7325 7324 -0.9931 0.0110802 0.0168244 1 0 1 1 0 0 +EDGE2 7325 7184 -1.06599 0.0500037 -0.0061865 1 0 1 1 0 0 +EDGE2 7325 7284 -1.01524 0.0493844 0.00748028 1 0 1 1 0 0 +EDGE2 7326 7307 0.953665 -0.101951 -0.0157341 1 0 1 1 0 0 +EDGE2 7326 7287 0.993388 0.115784 -0.0305694 1 0 1 1 0 0 +EDGE2 7326 7286 -0.00464118 0.00142094 -0.0415101 1 0 1 1 0 0 +EDGE2 7326 7306 -0.000583973 -0.0921534 -0.00971626 1 0 1 1 0 0 +EDGE2 7326 7285 -0.98731 0.0324444 -1.54616 1 0 1 1 0 0 +EDGE2 7326 7325 -0.998232 -0.0398876 -1.58128 1 0 1 1 0 0 +EDGE2 7326 7305 -1.02135 0.023262 -1.58001 1 0 1 1 0 0 +EDGE2 7326 7185 -1.00138 0.0159834 -1.55712 1 0 1 1 0 0 +EDGE2 7327 7326 -0.974514 -0.00324164 -0.0102437 1 0 1 1 0 0 +EDGE2 7327 7308 1.05828 -0.0398068 0.0121243 1 0 1 1 0 0 +EDGE2 7327 7288 0.932083 0.0609248 0.00543869 1 0 1 1 0 0 +EDGE2 7327 7307 0.0203018 -0.0424235 -0.0225793 1 0 1 1 0 0 +EDGE2 7327 7287 -0.0305243 -0.0420604 0.0235209 1 0 1 1 0 0 +EDGE2 7327 7286 -1.02836 0.0105513 -0.0298572 1 0 1 1 0 0 +EDGE2 7327 7306 -1.08794 -0.0456013 -0.00352389 1 0 1 1 0 0 +EDGE2 7328 7289 1.03431 -0.062081 0.0173624 1 0 1 1 0 0 +EDGE2 7328 7309 1.01884 -0.0280463 0.0046127 1 0 1 1 0 0 +EDGE2 7328 7308 -0.0493394 -0.0324718 0.0013097 1 0 1 1 0 0 +EDGE2 7328 7288 0.0851133 -0.0583426 -0.0119055 1 0 1 1 0 0 +EDGE2 7328 7307 -0.989345 -0.0880563 0.0364789 1 0 1 1 0 0 +EDGE2 7328 7327 -0.96161 0.0606893 -0.00435807 1 0 1 1 0 0 +EDGE2 7328 7287 -0.964969 0.016258 -0.0154643 1 0 1 1 0 0 +EDGE2 7329 7310 1.07168 0.0283721 -0.0034722 1 0 1 1 0 0 +EDGE2 7329 7170 0.909826 0.021868 -3.13786 1 0 1 1 0 0 +EDGE2 7329 7290 0.97292 -0.0491464 -0.014589 1 0 1 1 0 0 +EDGE2 7329 7289 0.0782168 0.0144556 0.0186897 1 0 1 1 0 0 +EDGE2 7329 7309 0.0138237 -0.139658 -0.0447286 1 0 1 1 0 0 +EDGE2 7329 7308 -0.953936 0.042948 -0.0165379 1 0 1 1 0 0 +EDGE2 7329 7328 -0.945957 -0.0289137 0.00180758 1 0 1 1 0 0 +EDGE2 7329 7288 -0.985124 -0.0310616 0.00562644 1 0 1 1 0 0 +EDGE2 7330 7169 1.07893 0.000603319 -3.11964 1 0 1 1 0 0 +EDGE2 7330 7310 0.0595512 -0.0337337 0.000467145 1 0 1 1 0 0 +EDGE2 7330 7170 0.0472516 0.0339845 -3.13661 1 0 1 1 0 0 +EDGE2 7330 7290 -0.0247967 -0.037533 0.0269759 1 0 1 1 0 0 +EDGE2 7330 7329 -0.963289 0.0361287 0.0127574 1 0 1 1 0 0 +EDGE2 7330 7289 -0.953851 0.0543882 0.00781443 1 0 1 1 0 0 +EDGE2 7330 7309 -0.994517 -0.00148237 0.00270653 1 0 1 1 0 0 +EDGE2 7330 7291 -0.0299489 1.11579 1.56816 1 0 1 1 0 0 +EDGE2 7330 7311 0.0194116 1.07925 1.57354 1 0 1 1 0 0 +EDGE2 7330 7171 0.0187804 1.01171 1.59642 1 0 1 1 0 0 +EDGE2 7331 7310 -0.959821 -0.0303143 -1.5907 1 0 1 1 0 0 +EDGE2 7331 7330 -1.07712 0.0409167 -1.53932 1 0 1 1 0 0 +EDGE2 7331 7170 -1.0701 0.0405184 1.54857 1 0 1 1 0 0 +EDGE2 7331 7290 -1.00432 0.0503242 -1.58493 1 0 1 1 0 0 +EDGE2 7331 7312 0.920715 0.00630024 -0.00600266 1 0 1 1 0 0 +EDGE2 7331 7291 -0.123119 -0.135156 -0.0165265 1 0 1 1 0 0 +EDGE2 7331 7311 0.0228903 0.0208539 -0.0160006 1 0 1 1 0 0 +EDGE2 7331 7171 0.0434666 0.0195748 0.018034 1 0 1 1 0 0 +EDGE2 7331 7172 0.989336 -0.087031 -0.0109683 1 0 1 1 0 0 +EDGE2 7331 7292 1.04304 -0.0407684 0.00151012 1 0 1 1 0 0 +EDGE2 7332 7312 -0.0473399 0.00801082 -0.00782518 1 0 1 1 0 0 +EDGE2 7332 7291 -1.01698 -0.0651059 -0.00482877 1 0 1 1 0 0 +EDGE2 7332 7331 -1.02706 0.129819 0.0318166 1 0 1 1 0 0 +EDGE2 7332 7311 -0.99633 -0.0431136 -0.00116747 1 0 1 1 0 0 +EDGE2 7332 7171 -1.00437 -0.0617731 0.00421504 1 0 1 1 0 0 +EDGE2 7332 7172 0.0808556 -0.0613182 -0.00731054 1 0 1 1 0 0 +EDGE2 7332 7292 -0.034341 -0.0585865 0.0227436 1 0 1 1 0 0 +EDGE2 7332 7173 0.937671 -0.12571 -0.0228148 1 0 1 1 0 0 +EDGE2 7332 7293 1.07237 -0.0702496 0.00159392 1 0 1 1 0 0 +EDGE2 7332 7313 0.991079 -0.0421066 0.00888916 1 0 1 1 0 0 +EDGE2 7333 7312 -1.03928 -0.0388959 0.0132067 1 0 1 1 0 0 +EDGE2 7333 7332 -0.95247 0.0547166 -0.00915155 1 0 1 1 0 0 +EDGE2 7333 7172 -0.909822 0.0662434 -0.0129634 1 0 1 1 0 0 +EDGE2 7333 7292 -1.04326 0.0998344 0.00120862 1 0 1 1 0 0 +EDGE2 7333 7173 0.0320179 0.0254255 0.00943173 1 0 1 1 0 0 +EDGE2 7333 7293 -0.0384737 0.0947182 0.0129235 1 0 1 1 0 0 +EDGE2 7333 7313 0.0346859 0.0478693 -0.0106069 1 0 1 1 0 0 +EDGE2 7333 7294 1.04475 -0.0081967 -0.029274 1 0 1 1 0 0 +EDGE2 7333 7314 0.954011 -0.0280286 -0.0276662 1 0 1 1 0 0 +EDGE2 7333 7174 1.01894 -0.0568195 0.0218735 1 0 1 1 0 0 +EDGE2 7334 7315 1.04925 -0.0834586 -0.0169357 1 0 1 1 0 0 +EDGE2 7334 7333 -1.00388 -0.00965746 -0.0321148 1 0 1 1 0 0 +EDGE2 7334 7173 -1.0118 -0.0932322 0.0246079 1 0 1 1 0 0 +EDGE2 7334 7293 -0.962275 0.047423 0.019639 1 0 1 1 0 0 +EDGE2 7334 7313 -1.08349 0.0490761 -0.00872698 1 0 1 1 0 0 +EDGE2 7334 7294 -0.0190896 0.0134889 -0.0208281 1 0 1 1 0 0 +EDGE2 7334 7314 -0.0604135 -0.0283969 0.0185486 1 0 1 1 0 0 +EDGE2 7334 7174 0.0472303 -0.0370424 -0.018467 1 0 1 1 0 0 +EDGE2 7334 7135 0.917042 0.0557804 -3.17414 1 0 1 1 0 0 +EDGE2 7334 7255 0.943512 0.0456985 -3.12387 1 0 1 1 0 0 +EDGE2 7334 7275 0.913199 -0.0468765 -3.11782 1 0 1 1 0 0 +EDGE2 7334 7295 1.02036 0.0477103 0.0314286 1 0 1 1 0 0 +EDGE2 7334 7175 0.988236 -0.00431309 -0.0289501 1 0 1 1 0 0 +EDGE2 7334 7115 0.99475 0.0327186 -3.18659 1 0 1 1 0 0 +EDGE2 7335 7315 -0.0796185 0.0417478 0.00678025 1 0 1 1 0 0 +EDGE2 7335 7136 0.0930087 -1.01714 -1.56966 1 0 1 1 0 0 +EDGE2 7335 7256 0.0284826 -1.0639 -1.54572 1 0 1 1 0 0 +EDGE2 7335 7116 -0.0993733 -0.954344 -1.58198 1 0 1 1 0 0 +EDGE2 7335 7294 -0.863557 0.03456 -0.0335989 1 0 1 1 0 0 +EDGE2 7335 7314 -1.06623 0.0129421 -0.00651271 1 0 1 1 0 0 +EDGE2 7335 7334 -1.04037 0.0224309 -0.0178697 1 0 1 1 0 0 +EDGE2 7335 7174 -1.00908 -0.0355858 0.0262768 1 0 1 1 0 0 +EDGE2 7335 7134 0.993514 -0.0029626 -3.09544 1 0 1 1 0 0 +EDGE2 7335 7135 0.0115061 -0.0772825 -3.14558 1 0 1 1 0 0 +EDGE2 7335 7255 -0.0408872 0.0654296 -3.12198 1 0 1 1 0 0 +EDGE2 7335 7275 0.0544705 -0.0203012 -3.1277 1 0 1 1 0 0 +EDGE2 7335 7295 0.0101043 0.084126 0.0121809 1 0 1 1 0 0 +EDGE2 7335 7175 -0.0303028 -0.0212589 0.0070899 1 0 1 1 0 0 +EDGE2 7335 7274 1.01145 -0.0173235 -3.12034 1 0 1 1 0 0 +EDGE2 7335 7115 -0.0365731 -0.0360779 -3.14102 1 0 1 1 0 0 +EDGE2 7335 7254 1.0542 -0.0259066 -3.16226 1 0 1 1 0 0 +EDGE2 7335 7114 0.98972 0.0266652 -3.16432 1 0 1 1 0 0 +EDGE2 7335 7296 -0.0697997 0.974943 1.5712 1 0 1 1 0 0 +EDGE2 7335 7316 -0.0194991 1.0796 1.56441 1 0 1 1 0 0 +EDGE2 7335 7176 -0.0153124 0.994844 1.56612 1 0 1 1 0 0 +EDGE2 7335 7276 -0.019446 0.96052 1.57646 1 0 1 1 0 0 +EDGE2 7336 7277 0.98695 0.0260155 0.0432283 1 0 1 1 0 0 +EDGE2 7336 7315 -1.00401 0.0580156 -1.57582 1 0 1 1 0 0 +EDGE2 7336 7335 -1.02358 0.0435817 -1.60564 1 0 1 1 0 0 +EDGE2 7336 7135 -0.905951 -0.0303553 1.56961 1 0 1 1 0 0 +EDGE2 7336 7255 -1.01089 -0.0442844 1.57196 1 0 1 1 0 0 +EDGE2 7336 7275 -1.07914 -0.0275186 1.58259 1 0 1 1 0 0 +EDGE2 7336 7295 -1.07446 0.0351928 -1.55186 1 0 1 1 0 0 +EDGE2 7336 7175 -1.08004 0.0417568 -1.5707 1 0 1 1 0 0 +EDGE2 7336 7115 -1.06306 0.0149925 1.58683 1 0 1 1 0 0 +EDGE2 7336 7296 -0.0642318 0.0434573 0.00322603 1 0 1 1 0 0 +EDGE2 7336 7316 -0.0363367 -0.00827911 -0.0113657 1 0 1 1 0 0 +EDGE2 7336 7176 0.0175509 0.0368003 0.0163525 1 0 1 1 0 0 +EDGE2 7336 7276 -0.0589753 0.0115288 -0.0139873 1 0 1 1 0 0 +EDGE2 7336 7317 0.980902 -0.0221989 0.00111617 1 0 1 1 0 0 +EDGE2 7336 7297 1.0622 -0.0318284 0.00560073 1 0 1 1 0 0 +EDGE2 7336 7177 0.990124 -0.0835102 -0.0368624 1 0 1 1 0 0 +EDGE2 7337 7277 -0.00774427 0.10821 0.00379832 1 0 1 1 0 0 +EDGE2 7337 7296 -0.903175 -0.00747151 0.00976973 1 0 1 1 0 0 +EDGE2 7337 7336 -1.04433 0.00215781 -0.00232033 1 0 1 1 0 0 +EDGE2 7337 7316 -0.994343 0.0365402 -0.00305511 1 0 1 1 0 0 +EDGE2 7337 7176 -0.977207 -0.0376348 0.0294798 1 0 1 1 0 0 +EDGE2 7337 7276 -1.00451 -0.0608681 -0.0660493 1 0 1 1 0 0 +EDGE2 7337 7317 -0.0214576 -0.0286819 -0.0145939 1 0 1 1 0 0 +EDGE2 7337 7297 0.0117777 0.00411719 0.0568098 1 0 1 1 0 0 +EDGE2 7337 7298 1.07671 -0.0635761 0.0295956 1 0 1 1 0 0 +EDGE2 7337 7318 1.05357 -0.0247107 -0.0118191 1 0 1 1 0 0 +EDGE2 7337 7177 -0.0296528 0.0305983 0.0314799 1 0 1 1 0 0 +EDGE2 7337 7178 1.02449 -0.0576773 0.00771565 1 0 1 1 0 0 +EDGE2 7337 7278 1.02837 -0.0168375 0.00829917 1 0 1 1 0 0 +EDGE2 7338 7277 -1.04514 -0.0155222 0.0139759 1 0 1 1 0 0 +EDGE2 7338 7337 -1.13506 0.07098 -0.000429777 1 0 1 1 0 0 +EDGE2 7338 7317 -1.02214 0.093179 0.0212298 1 0 1 1 0 0 +EDGE2 7338 7297 -0.945336 0.0626475 0.00264978 1 0 1 1 0 0 +EDGE2 7338 7298 0.013681 0.0665444 0.00844851 1 0 1 1 0 0 +EDGE2 7338 7318 -0.0758667 0.0616637 0.0166825 1 0 1 1 0 0 +EDGE2 7338 7177 -0.974594 0.0279807 0.0116537 1 0 1 1 0 0 +EDGE2 7338 7178 -0.0287847 -0.0491436 -0.00457203 1 0 1 1 0 0 +EDGE2 7338 7278 -0.0253248 -0.0625158 0.00238621 1 0 1 1 0 0 +EDGE2 7338 7279 1.06364 0.0291928 0.000949015 1 0 1 1 0 0 +EDGE2 7338 7299 0.98448 0.0235141 -0.0146179 1 0 1 1 0 0 +EDGE2 7338 7319 0.944713 -0.0317649 -0.0117386 1 0 1 1 0 0 +EDGE2 7338 7179 0.979678 0.0221734 0.034928 1 0 1 1 0 0 +EDGE2 7339 7298 -0.926306 0.113819 0.00446711 1 0 1 1 0 0 +EDGE2 7339 7318 -1.02584 0.044912 0.0498683 1 0 1 1 0 0 +EDGE2 7339 7338 -1.04023 0.0219943 0.0520861 1 0 1 1 0 0 +EDGE2 7339 7178 -1.1244 -0.0687054 -0.0114744 1 0 1 1 0 0 +EDGE2 7339 7278 -1.00744 -0.0796148 -0.0235793 1 0 1 1 0 0 +EDGE2 7339 7279 -0.0343468 0.0396604 -0.0246376 1 0 1 1 0 0 +EDGE2 7339 7299 -0.00492952 -0.0296116 0.00989458 1 0 1 1 0 0 +EDGE2 7339 7319 0.0296631 -0.0015173 0.0179188 1 0 1 1 0 0 +EDGE2 7339 7179 0.0417062 0.0683997 -0.00620956 1 0 1 1 0 0 +EDGE2 7339 7320 0.971948 -0.0324238 0.00589709 1 0 1 1 0 0 +EDGE2 7339 7180 0.965687 -0.0476864 -0.0193233 1 0 1 1 0 0 +EDGE2 7339 7280 0.954469 -0.0999142 -0.00775442 1 0 1 1 0 0 +EDGE2 7339 7300 1.0272 0.0151973 0.0323562 1 0 1 1 0 0 +EDGE2 7340 7339 -1.01253 0.0283444 0.000545843 1 0 1 1 0 0 +EDGE2 7340 7279 -1.00788 -0.0698331 0.00983988 1 0 1 1 0 0 +EDGE2 7340 7299 -1.04594 0.0637397 0.0343218 1 0 1 1 0 0 +EDGE2 7340 7319 -1.08373 0.0707571 -0.00360667 1 0 1 1 0 0 +EDGE2 7340 7179 -1.0356 -0.126765 -0.0431332 1 0 1 1 0 0 +EDGE2 7340 7320 -0.0653779 -0.0102119 0.024716 1 0 1 1 0 0 +EDGE2 7340 7281 -0.0529438 0.946679 1.58991 1 0 1 1 0 0 +EDGE2 7340 7301 -0.0188341 1.06408 1.58682 1 0 1 1 0 0 +EDGE2 7340 7321 0.0559149 0.923098 1.57716 1 0 1 1 0 0 +EDGE2 7340 7181 0.0162913 1.0521 1.60067 1 0 1 1 0 0 +EDGE2 7340 7180 0.00744662 -0.10664 0.0141428 1 0 1 1 0 0 +EDGE2 7340 7280 0.000887269 -0.0655555 0.0054445 1 0 1 1 0 0 +EDGE2 7340 7300 0.00171526 0.0439325 -0.0109394 1 0 1 1 0 0 +EDGE2 7341 7282 1.00953 -0.0312166 0.0150614 1 0 1 1 0 0 +EDGE2 7341 7322 0.984062 0.0433545 -0.0128849 1 0 1 1 0 0 +EDGE2 7341 7302 1.02108 0.128681 0.0142912 1 0 1 1 0 0 +EDGE2 7341 7182 1.02526 0.00543122 0.016458 1 0 1 1 0 0 +EDGE2 7341 7320 -0.954746 0.013251 -1.5686 1 0 1 1 0 0 +EDGE2 7341 7281 0.0531497 0.0412576 0.00462941 1 0 1 1 0 0 +EDGE2 7341 7301 -0.0457044 -0.0194221 0.00456384 1 0 1 1 0 0 +EDGE2 7341 7321 -0.0258289 0.0942987 -0.00037073 1 0 1 1 0 0 +EDGE2 7341 7181 0.0768773 -0.0111987 -0.0127241 1 0 1 1 0 0 +EDGE2 7341 7340 -0.983411 -0.0858371 -1.5635 1 0 1 1 0 0 +EDGE2 7341 7180 -0.982298 -0.00375384 -1.59022 1 0 1 1 0 0 +EDGE2 7341 7280 -0.994603 -0.0391052 -1.57778 1 0 1 1 0 0 +EDGE2 7341 7300 -0.974754 0.0704583 -1.61579 1 0 1 1 0 0 +EDGE2 7342 7341 -0.987299 -0.0355662 0.0109235 1 0 1 1 0 0 +EDGE2 7342 7283 0.902492 -0.0414819 -0.0223926 1 0 1 1 0 0 +EDGE2 7342 7303 0.996623 0.00731434 0.0372041 1 0 1 1 0 0 +EDGE2 7342 7323 0.986595 -0.0209126 0.00740642 1 0 1 1 0 0 +EDGE2 7342 7183 1.00623 -0.0322432 0.0173974 1 0 1 1 0 0 +EDGE2 7342 7282 0.0295847 0.0100665 0.0156547 1 0 1 1 0 0 +EDGE2 7342 7322 0.0118078 -0.0460345 -0.0145081 1 0 1 1 0 0 +EDGE2 7342 7302 -0.0994865 -0.0435646 0.0306669 1 0 1 1 0 0 +EDGE2 7342 7182 -0.058094 -0.0199172 -0.0109161 1 0 1 1 0 0 +EDGE2 7342 7281 -0.966016 0.0657904 0.0455526 1 0 1 1 0 0 +EDGE2 7342 7301 -1.11572 0.00409905 0.0143417 1 0 1 1 0 0 +EDGE2 7342 7321 -1.03593 -0.0105058 0.0267995 1 0 1 1 0 0 +EDGE2 7342 7181 -0.976554 -0.0429522 0.0201302 1 0 1 1 0 0 +EDGE2 7343 7304 1.02224 0.0354497 -0.0364773 1 0 1 1 0 0 +EDGE2 7343 7324 0.907531 0.0197862 0.0176389 1 0 1 1 0 0 +EDGE2 7343 7184 0.973409 -0.0449983 -0.055175 1 0 1 1 0 0 +EDGE2 7343 7284 1.08163 0.0334911 -0.0143643 1 0 1 1 0 0 +EDGE2 7343 7283 -0.0180588 0.0295289 -0.00487064 1 0 1 1 0 0 +EDGE2 7343 7303 -0.0386264 0.0186535 9.70352e-05 1 0 1 1 0 0 +EDGE2 7343 7323 -0.0103175 0.0243393 -0.00988022 1 0 1 1 0 0 +EDGE2 7343 7183 0.0419072 -0.000759671 -0.0138025 1 0 1 1 0 0 +EDGE2 7343 7282 -0.933232 -0.0417576 0.0320399 1 0 1 1 0 0 +EDGE2 7343 7322 -1.01584 0.0839981 -0.00651465 1 0 1 1 0 0 +EDGE2 7343 7342 -0.999326 -0.0125239 0.0155367 1 0 1 1 0 0 +EDGE2 7343 7302 -1.00663 -0.0176077 -0.000757469 1 0 1 1 0 0 +EDGE2 7343 7182 -1.10248 0.0820024 0.0276898 1 0 1 1 0 0 +EDGE2 7344 7285 0.998062 0.076745 -0.00340588 1 0 1 1 0 0 +EDGE2 7344 7325 1.0418 0.0582246 0.00601801 1 0 1 1 0 0 +EDGE2 7344 7305 1.04189 -0.0408389 0.00806611 1 0 1 1 0 0 +EDGE2 7344 7185 1.04578 -0.0500211 -0.00752591 1 0 1 1 0 0 +EDGE2 7344 7304 0.0409436 -0.0334959 -0.0099031 1 0 1 1 0 0 +EDGE2 7344 7324 -0.074065 -0.00976608 0.0179335 1 0 1 1 0 0 +EDGE2 7344 7343 -1.00485 -0.0141838 0.0278413 1 0 1 1 0 0 +EDGE2 7344 7184 -0.024886 -0.116628 0.0307625 1 0 1 1 0 0 +EDGE2 7344 7284 -0.0211858 0.0266528 -0.0139615 1 0 1 1 0 0 +EDGE2 7344 7283 -1.06386 0.060836 -0.0169226 1 0 1 1 0 0 +EDGE2 7344 7303 -0.996213 -0.0141051 -0.0115602 1 0 1 1 0 0 +EDGE2 7344 7323 -0.996166 0.02277 0.0030295 1 0 1 1 0 0 +EDGE2 7344 7183 -1.12473 -0.0191811 -0.0240471 1 0 1 1 0 0 +EDGE2 7345 7326 0.0403753 1.07334 1.56161 1 0 1 1 0 0 +EDGE2 7345 7286 -0.0585752 0.999989 1.54468 1 0 1 1 0 0 +EDGE2 7345 7306 -0.0126468 1.01367 1.55614 1 0 1 1 0 0 +EDGE2 7345 7285 0.0315643 0.0208868 0.0153431 1 0 1 1 0 0 +EDGE2 7345 7325 -0.0106481 0.0490726 -0.0076021 1 0 1 1 0 0 +EDGE2 7345 7305 -0.010338 0.0473494 0.0192477 1 0 1 1 0 0 +EDGE2 7345 7185 -0.000852531 -0.0997747 0.00874585 1 0 1 1 0 0 +EDGE2 7345 7186 0.0417058 -0.975931 -1.59702 1 0 1 1 0 0 +EDGE2 7345 7304 -1.01768 0.0469823 -0.00189479 1 0 1 1 0 0 +EDGE2 7345 7344 -0.952727 0.0100515 0.013031 1 0 1 1 0 0 +EDGE2 7345 7324 -1.07155 0.0251637 -0.00931198 1 0 1 1 0 0 +EDGE2 7345 7184 -1.07739 0.0701321 0.00952396 1 0 1 1 0 0 +EDGE2 7345 7284 -1.02061 -0.0577405 -0.00378083 1 0 1 1 0 0 +EDGE2 7346 7326 -0.0320058 0.000715254 0.00429387 1 0 1 1 0 0 +EDGE2 7346 7307 1.02808 0.0482851 -0.00526751 1 0 1 1 0 0 +EDGE2 7346 7327 0.967998 0.0837016 0.0398804 1 0 1 1 0 0 +EDGE2 7346 7287 1.06724 -0.0848501 -0.00364352 1 0 1 1 0 0 +EDGE2 7346 7286 -0.0829112 0.0145256 0.0056449 1 0 1 1 0 0 +EDGE2 7346 7306 0.0339751 -0.0645859 0.0030572 1 0 1 1 0 0 +EDGE2 7346 7285 -1.0377 -0.0692824 -1.55434 1 0 1 1 0 0 +EDGE2 7346 7325 -1.04798 0.0972931 -1.6005 1 0 1 1 0 0 +EDGE2 7346 7345 -0.94916 0.0330688 -1.54465 1 0 1 1 0 0 +EDGE2 7346 7305 -0.999504 -0.084821 -1.58524 1 0 1 1 0 0 +EDGE2 7346 7185 -1.06535 -0.0371846 -1.56884 1 0 1 1 0 0 +EDGE2 7347 7326 -0.993759 -0.0810324 -0.0408505 1 0 1 1 0 0 +EDGE2 7347 7308 0.962142 0.0493245 0.0147549 1 0 1 1 0 0 +EDGE2 7347 7328 1.07689 -0.0246632 0.0160909 1 0 1 1 0 0 +EDGE2 7347 7288 1.04111 0.0508692 0.0335299 1 0 1 1 0 0 +EDGE2 7347 7307 0.0476165 -0.00682095 0.0361299 1 0 1 1 0 0 +EDGE2 7347 7327 -0.0692193 -0.00803762 0.0218669 1 0 1 1 0 0 +EDGE2 7347 7287 0.0764396 0.0839033 0.017636 1 0 1 1 0 0 +EDGE2 7347 7346 -1.06255 -0.0490545 -0.0210135 1 0 1 1 0 0 +EDGE2 7347 7286 -1.04644 0.0366609 -0.00978886 1 0 1 1 0 0 +EDGE2 7347 7306 -0.912999 -0.0122427 -0.0110453 1 0 1 1 0 0 +EDGE2 7348 7329 1.02618 0.00133077 0.00197585 1 0 1 1 0 0 +EDGE2 7348 7289 0.984674 -0.0295869 -0.00337116 1 0 1 1 0 0 +EDGE2 7348 7309 1.00221 0.0840356 -0.021842 1 0 1 1 0 0 +EDGE2 7348 7308 0.0215707 0.0601693 0.0192853 1 0 1 1 0 0 +EDGE2 7348 7328 -0.0215273 -0.0109722 -0.01449 1 0 1 1 0 0 +EDGE2 7348 7288 -0.00592889 0.0498868 -0.0083454 1 0 1 1 0 0 +EDGE2 7348 7307 -1.03515 -0.144243 -0.00946616 1 0 1 1 0 0 +EDGE2 7348 7327 -1.03291 0.0679344 -0.0016875 1 0 1 1 0 0 +EDGE2 7348 7347 -1.0883 0.01142 0.0120886 1 0 1 1 0 0 +EDGE2 7348 7287 -0.979885 -0.0842831 -0.00115132 1 0 1 1 0 0 +EDGE2 7349 7310 0.928194 0.028823 -0.0129801 1 0 1 1 0 0 +EDGE2 7349 7330 0.955332 0.0518461 -0.000948862 1 0 1 1 0 0 +EDGE2 7349 7170 1.07421 -0.0431632 -3.13305 1 0 1 1 0 0 +EDGE2 7349 7290 0.953794 -0.0273767 0.0053205 1 0 1 1 0 0 +EDGE2 7349 7329 -0.0358618 -0.0363704 0.0226439 1 0 1 1 0 0 +EDGE2 7349 7289 0.0584024 0.00414144 0.0225777 1 0 1 1 0 0 +EDGE2 7349 7309 -0.0436332 -0.0537161 -0.00993498 1 0 1 1 0 0 +EDGE2 7349 7308 -0.960529 0.0192461 0.0194097 1 0 1 1 0 0 +EDGE2 7349 7348 -0.894889 0.0888914 -0.0104823 1 0 1 1 0 0 +EDGE2 7349 7328 -1.02992 0.0718864 -0.0162741 1 0 1 1 0 0 +EDGE2 7349 7288 -1.02681 -0.0746882 -0.0130241 1 0 1 1 0 0 +EDGE2 7350 7169 1.01219 0.0180161 -3.13621 1 0 1 1 0 0 +EDGE2 7350 7310 -0.0465289 0.0896875 0.00835304 1 0 1 1 0 0 +EDGE2 7350 7330 0.083654 0.00420381 0.0265194 1 0 1 1 0 0 +EDGE2 7350 7170 0.0216644 -0.0194822 -3.14228 1 0 1 1 0 0 +EDGE2 7350 7290 -0.0461414 -0.0556252 -0.0381663 1 0 1 1 0 0 +EDGE2 7350 7329 -0.956246 0.00835961 -0.0167245 1 0 1 1 0 0 +EDGE2 7350 7349 -0.983745 0.0657499 0.0212614 1 0 1 1 0 0 +EDGE2 7350 7289 -1.0777 -0.0804758 0.0397896 1 0 1 1 0 0 +EDGE2 7350 7309 -1.06571 0.0110377 -0.0334698 1 0 1 1 0 0 +EDGE2 7350 7291 -0.0138296 0.959807 1.59689 1 0 1 1 0 0 +EDGE2 7350 7331 0.00764311 1.03544 1.55531 1 0 1 1 0 0 +EDGE2 7350 7311 0.0252374 0.910827 1.5757 1 0 1 1 0 0 +EDGE2 7350 7171 0.0257746 0.944094 1.58594 1 0 1 1 0 0 +EDGE2 7351 7310 -0.867603 0.0922037 -1.55661 1 0 1 1 0 0 +EDGE2 7351 7350 -1.02115 -0.0256595 -1.57523 1 0 1 1 0 0 +EDGE2 7351 7330 -1.01851 0.00185402 -1.57957 1 0 1 1 0 0 +EDGE2 7351 7170 -1.03546 0.0805187 1.56889 1 0 1 1 0 0 +EDGE2 7351 7290 -1.03274 0.00385559 -1.56352 1 0 1 1 0 0 +EDGE2 7351 7312 1.03272 -0.10782 0.0246766 1 0 1 1 0 0 +EDGE2 7351 7291 -0.0149337 0.0823339 -0.0187708 1 0 1 1 0 0 +EDGE2 7351 7331 -0.0278565 -0.0237201 -0.0399835 1 0 1 1 0 0 +EDGE2 7351 7311 -0.0693894 0.026395 0.0151872 1 0 1 1 0 0 +EDGE2 7351 7171 0.060676 0.0229785 0.00645944 1 0 1 1 0 0 +EDGE2 7351 7332 1.01525 -0.0383817 -0.00687314 1 0 1 1 0 0 +EDGE2 7351 7172 0.892119 -0.0254211 0.0128538 1 0 1 1 0 0 +EDGE2 7351 7292 1.01561 9.83414e-05 0.00868767 1 0 1 1 0 0 +EDGE2 7352 7312 -0.0763731 0.105928 -0.0126833 1 0 1 1 0 0 +EDGE2 7352 7291 -0.906867 0.0446863 0.00296621 1 0 1 1 0 0 +EDGE2 7352 7331 -1.01964 -0.0491984 -0.00845484 1 0 1 1 0 0 +EDGE2 7352 7351 -0.976956 -0.0146389 0.0505411 1 0 1 1 0 0 +EDGE2 7352 7311 -0.921429 0.0281088 -0.000284931 1 0 1 1 0 0 +EDGE2 7352 7171 -0.994633 -0.0109266 -0.0130466 1 0 1 1 0 0 +EDGE2 7352 7332 0.0551196 0.0338154 -0.0271999 1 0 1 1 0 0 +EDGE2 7352 7333 0.970246 -0.0840537 -0.021273 1 0 1 1 0 0 +EDGE2 7352 7172 -0.033589 -0.108437 0.00864715 1 0 1 1 0 0 +EDGE2 7352 7292 -0.106691 -0.0504437 0.0183783 1 0 1 1 0 0 +EDGE2 7352 7173 1.03684 0.0720993 -0.00873682 1 0 1 1 0 0 +EDGE2 7352 7293 0.99967 0.0495731 -0.00369825 1 0 1 1 0 0 +EDGE2 7352 7313 0.937821 0.0169127 0.000406836 1 0 1 1 0 0 +EDGE2 7353 7312 -1.06802 -0.0878978 -0.0193046 1 0 1 1 0 0 +EDGE2 7353 7352 -1.01184 0.0961913 0.0113461 1 0 1 1 0 0 +EDGE2 7353 7332 -0.973664 0.0329634 -0.013091 1 0 1 1 0 0 +EDGE2 7353 7333 -0.0446126 -0.00268822 -0.00947467 1 0 1 1 0 0 +EDGE2 7353 7172 -0.918868 -0.00887961 -0.0444338 1 0 1 1 0 0 +EDGE2 7353 7292 -1.02256 -0.0155865 -0.0214909 1 0 1 1 0 0 +EDGE2 7353 7173 0.108126 -0.00210117 0.00560176 1 0 1 1 0 0 +EDGE2 7353 7293 -0.00734482 -0.0266409 0.0118162 1 0 1 1 0 0 +EDGE2 7353 7313 -0.0295202 -0.00155979 0.00734542 1 0 1 1 0 0 +EDGE2 7353 7294 0.975624 -0.131272 -0.00238612 1 0 1 1 0 0 +EDGE2 7353 7314 1.1023 0.00513011 0.0188021 1 0 1 1 0 0 +EDGE2 7353 7334 0.978274 -0.0533014 0.00887886 1 0 1 1 0 0 +EDGE2 7353 7174 0.981958 0.0580442 0.0143792 1 0 1 1 0 0 +EDGE2 7354 7315 1.01268 0.00814355 0.00301451 1 0 1 1 0 0 +EDGE2 7354 7333 -0.946074 6.17021e-06 -0.0216035 1 0 1 1 0 0 +EDGE2 7354 7353 -1.06167 -0.0472261 0.0159697 1 0 1 1 0 0 +EDGE2 7354 7173 -0.959504 0.00925092 0.0153051 1 0 1 1 0 0 +EDGE2 7354 7293 -0.993073 -0.0611243 0.0199559 1 0 1 1 0 0 +EDGE2 7354 7313 -0.994248 0.0130258 0.0168184 1 0 1 1 0 0 +EDGE2 7354 7294 -0.00747273 -0.0371891 0.00191603 1 0 1 1 0 0 +EDGE2 7354 7314 -0.0717072 0.021988 0.0162003 1 0 1 1 0 0 +EDGE2 7354 7334 0.0427546 0.00742206 0.0206098 1 0 1 1 0 0 +EDGE2 7354 7174 -0.0181274 -0.0582782 -0.0145592 1 0 1 1 0 0 +EDGE2 7354 7335 1.03505 -0.0108941 0.0111159 1 0 1 1 0 0 +EDGE2 7354 7135 1.07649 0.0399605 -3.16274 1 0 1 1 0 0 +EDGE2 7354 7255 1.03319 -0.0680412 -3.15808 1 0 1 1 0 0 +EDGE2 7354 7275 0.991912 -0.094863 -3.13583 1 0 1 1 0 0 +EDGE2 7354 7295 1.04522 0.0110011 -0.0159916 1 0 1 1 0 0 +EDGE2 7354 7175 0.968444 -0.0598561 0.0190321 1 0 1 1 0 0 +EDGE2 7354 7115 1.01051 0.0303389 -3.15821 1 0 1 1 0 0 +EDGE2 7355 7315 -0.0363856 0.000176088 0.00597379 1 0 1 1 0 0 +EDGE2 7355 7136 0.0267289 -0.936198 -1.55661 1 0 1 1 0 0 +EDGE2 7355 7256 0.0262316 -1.04111 -1.58012 1 0 1 1 0 0 +EDGE2 7355 7116 0.00182354 -1.04812 -1.60424 1 0 1 1 0 0 +EDGE2 7355 7354 -1.01404 0.0136149 0.011901 1 0 1 1 0 0 +EDGE2 7355 7294 -0.970116 0.0271157 0.0148275 1 0 1 1 0 0 +EDGE2 7355 7314 -0.98 0.0352995 0.0181365 1 0 1 1 0 0 +EDGE2 7355 7334 -1.08087 0.00531601 -0.0095898 1 0 1 1 0 0 +EDGE2 7355 7174 -0.951817 0.0378429 -0.00173031 1 0 1 1 0 0 +EDGE2 7355 7335 -0.0212324 0.0382487 -0.0258508 1 0 1 1 0 0 +EDGE2 7355 7134 0.971776 -0.0678022 -3.12831 1 0 1 1 0 0 +EDGE2 7355 7135 -0.0230324 0.019073 -3.1534 1 0 1 1 0 0 +EDGE2 7355 7255 -0.0488386 0.0228733 -3.14238 1 0 1 1 0 0 +EDGE2 7355 7275 0.0920585 0.044677 -3.1443 1 0 1 1 0 0 +EDGE2 7355 7295 -0.0495735 0.0227258 0.0155302 1 0 1 1 0 0 +EDGE2 7355 7175 -0.0401575 -0.0166701 -0.0402381 1 0 1 1 0 0 +EDGE2 7355 7274 1.01982 0.0115748 -3.16918 1 0 1 1 0 0 +EDGE2 7355 7115 0.0254723 -0.0283687 -3.11417 1 0 1 1 0 0 +EDGE2 7355 7254 0.964397 -0.0235151 -3.15236 1 0 1 1 0 0 +EDGE2 7355 7114 1.00187 0.0638782 -3.15361 1 0 1 1 0 0 +EDGE2 7355 7296 -0.0820603 0.895789 1.5606 1 0 1 1 0 0 +EDGE2 7355 7336 -0.00221517 0.998082 1.57495 1 0 1 1 0 0 +EDGE2 7355 7316 -0.0752909 1.03104 1.58388 1 0 1 1 0 0 +EDGE2 7355 7176 -0.0351127 1.00638 1.52772 1 0 1 1 0 0 +EDGE2 7355 7276 0.0299853 1.00752 1.60641 1 0 1 1 0 0 +EDGE2 7356 7277 1.029 -0.0550369 0.0257409 1 0 1 1 0 0 +EDGE2 7356 7315 -1.02479 -0.00741316 -1.59133 1 0 1 1 0 0 +EDGE2 7356 7355 -1.01723 -0.0968104 -1.56739 1 0 1 1 0 0 +EDGE2 7356 7335 -0.927633 0.0047543 -1.57149 1 0 1 1 0 0 +EDGE2 7356 7135 -1.02853 0.0106141 1.5821 1 0 1 1 0 0 +EDGE2 7356 7255 -0.963502 0.018934 1.57714 1 0 1 1 0 0 +EDGE2 7356 7275 -1.01736 -0.00748492 1.60587 1 0 1 1 0 0 +EDGE2 7356 7295 -0.970221 -0.0481365 -1.58972 1 0 1 1 0 0 +EDGE2 7356 7175 -1.03819 -0.0946633 -1.54957 1 0 1 1 0 0 +EDGE2 7356 7115 -0.962734 0.0748012 1.55773 1 0 1 1 0 0 +EDGE2 7356 7337 1.02182 -0.0243078 0.0152075 1 0 1 1 0 0 +EDGE2 7356 7296 -0.0101566 -0.0650143 -0.00670735 1 0 1 1 0 0 +EDGE2 7356 7336 -0.023394 0.0293727 0.0323712 1 0 1 1 0 0 +EDGE2 7356 7316 0.0746389 -0.0278952 0.00717583 1 0 1 1 0 0 +EDGE2 7356 7176 -0.0223059 0.00348736 -0.029135 1 0 1 1 0 0 +EDGE2 7356 7276 0.0194409 0.01117 0.0197387 1 0 1 1 0 0 +EDGE2 7356 7317 1.00764 0.0380723 -0.00113714 1 0 1 1 0 0 +EDGE2 7356 7297 0.974148 -0.082694 -0.0230099 1 0 1 1 0 0 +EDGE2 7356 7177 1.02244 0.0120668 -0.0292576 1 0 1 1 0 0 +EDGE2 7357 7277 -0.0862765 0.00595251 -0.00625393 1 0 1 1 0 0 +EDGE2 7357 7337 -0.0262715 0.000809319 -0.00226667 1 0 1 1 0 0 +EDGE2 7357 7296 -1.01611 0.000751186 0.0137593 1 0 1 1 0 0 +EDGE2 7357 7336 -0.997312 -0.0214383 -0.00814898 1 0 1 1 0 0 +EDGE2 7357 7356 -0.995057 -0.035459 -0.0171034 1 0 1 1 0 0 +EDGE2 7357 7316 -0.970941 -0.0927249 -0.00408964 1 0 1 1 0 0 +EDGE2 7357 7176 -0.964984 -0.0582784 -0.0366063 1 0 1 1 0 0 +EDGE2 7357 7276 -1.03868 0.00422713 -0.00730326 1 0 1 1 0 0 +EDGE2 7357 7317 -0.0282372 -0.0240008 0.0263596 1 0 1 1 0 0 +EDGE2 7357 7297 0.011817 0.108345 0.0140106 1 0 1 1 0 0 +EDGE2 7357 7298 0.987405 0.0416159 0.0211351 1 0 1 1 0 0 +EDGE2 7357 7318 0.937954 0.00526006 -0.0110017 1 0 1 1 0 0 +EDGE2 7357 7177 0.0220537 -0.0121792 -0.0277452 1 0 1 1 0 0 +EDGE2 7357 7338 1.03517 0.0104485 -0.0129541 1 0 1 1 0 0 +EDGE2 7357 7178 1.00856 0.0562913 -0.00911366 1 0 1 1 0 0 +EDGE2 7357 7278 1.01045 0.00604789 0.0218751 1 0 1 1 0 0 +EDGE2 7358 7277 -1.09034 -0.0491133 0.0377331 1 0 1 1 0 0 +EDGE2 7358 7337 -1.0317 0.0106773 -0.00936404 1 0 1 1 0 0 +EDGE2 7358 7357 -0.945497 0.00302304 -0.0243974 1 0 1 1 0 0 +EDGE2 7358 7317 -1.04005 0.000552368 -0.0185694 1 0 1 1 0 0 +EDGE2 7358 7297 -1.04533 -0.0173555 -0.000402104 1 0 1 1 0 0 +EDGE2 7358 7298 0.00428103 -0.0329081 -0.00254416 1 0 1 1 0 0 +EDGE2 7358 7318 -0.0383855 0.0632254 -0.00833389 1 0 1 1 0 0 +EDGE2 7358 7177 -0.960116 -0.0107465 -0.0353155 1 0 1 1 0 0 +EDGE2 7358 7338 0.062688 -0.0139314 -0.0279295 1 0 1 1 0 0 +EDGE2 7358 7339 0.871277 0.0117301 -0.0321523 1 0 1 1 0 0 +EDGE2 7358 7178 -0.0302538 -0.047693 0.0132193 1 0 1 1 0 0 +EDGE2 7358 7278 0.0230321 -0.00626055 0.0475826 1 0 1 1 0 0 +EDGE2 7358 7279 1.00749 -0.0333718 -0.0168715 1 0 1 1 0 0 +EDGE2 7358 7299 1.05389 -0.0135606 0.0184986 1 0 1 1 0 0 +EDGE2 7358 7319 0.974966 0.0344248 -0.0128413 1 0 1 1 0 0 +EDGE2 7358 7179 0.934429 0.0162718 0.029174 1 0 1 1 0 0 +EDGE2 7359 7298 -1.05143 -0.027525 0.000233839 1 0 1 1 0 0 +EDGE2 7359 7318 -1.00132 -0.090668 0.00616908 1 0 1 1 0 0 +EDGE2 7359 7358 -0.955237 -0.115768 0.00851454 1 0 1 1 0 0 +EDGE2 7359 7338 -0.895298 0.117617 -0.0200311 1 0 1 1 0 0 +EDGE2 7359 7339 -0.0699505 -0.0224349 0.00265725 1 0 1 1 0 0 +EDGE2 7359 7178 -1.03584 -0.0172127 -0.00895811 1 0 1 1 0 0 +EDGE2 7359 7278 -0.987573 0.0011668 0.0327613 1 0 1 1 0 0 +EDGE2 7359 7279 0.097219 -0.046841 0.0312536 1 0 1 1 0 0 +EDGE2 7359 7299 -0.0442709 -0.0265035 0.0253164 1 0 1 1 0 0 +EDGE2 7359 7319 -0.0382014 -0.0915416 -0.0143761 1 0 1 1 0 0 +EDGE2 7359 7179 0.0111526 -0.00304861 0.0136185 1 0 1 1 0 0 +EDGE2 7359 7320 0.908391 -0.00146648 -0.0159557 1 0 1 1 0 0 +EDGE2 7359 7340 0.965784 -0.0324953 0.0090656 1 0 1 1 0 0 +EDGE2 7359 7180 0.969375 0.00762098 -0.0244361 1 0 1 1 0 0 +EDGE2 7359 7280 1.00159 -0.0352649 -0.0086622 1 0 1 1 0 0 +EDGE2 7359 7300 0.99172 0.022676 0.00474252 1 0 1 1 0 0 +EDGE2 7360 7341 -0.00170725 1.06076 1.58566 1 0 1 1 0 0 +EDGE2 7360 7339 -0.868351 -0.0232337 0.039756 1 0 1 1 0 0 +EDGE2 7360 7359 -1.00078 0.0914926 0.000299336 1 0 1 1 0 0 +EDGE2 7360 7279 -0.924405 -0.050564 -0.0236952 1 0 1 1 0 0 +EDGE2 7360 7299 -0.973929 -0.0481229 -0.00582341 1 0 1 1 0 0 +EDGE2 7360 7319 -0.918949 -0.108169 -0.00626922 1 0 1 1 0 0 +EDGE2 7360 7179 -1.01951 0.0465789 0.0159472 1 0 1 1 0 0 +EDGE2 7360 7320 0.0339931 0.00322314 -0.009118 1 0 1 1 0 0 +EDGE2 7360 7281 0.0728842 0.98125 1.55128 1 0 1 1 0 0 +EDGE2 7360 7301 0.0964499 1.01986 1.60834 1 0 1 1 0 0 +EDGE2 7360 7321 0.00478881 1.03716 1.56664 1 0 1 1 0 0 +EDGE2 7360 7181 0.104878 1.09879 1.53218 1 0 1 1 0 0 +EDGE2 7360 7340 0.00401757 0.139611 -0.0448108 1 0 1 1 0 0 +EDGE2 7360 7180 0.0406737 0.0396976 -0.0208796 1 0 1 1 0 0 +EDGE2 7360 7280 -0.057909 -0.0386286 0.0378922 1 0 1 1 0 0 +EDGE2 7360 7300 -0.0179248 -0.01706 0.0200157 1 0 1 1 0 0 +EDGE2 7361 7341 -0.00730955 -0.067533 0.00469686 1 0 1 1 0 0 +EDGE2 7361 7282 1.07267 0.0154111 -0.0327392 1 0 1 1 0 0 +EDGE2 7361 7322 0.983741 0.0136614 0.00655898 1 0 1 1 0 0 +EDGE2 7361 7342 1.07533 0.0361039 -0.00552051 1 0 1 1 0 0 +EDGE2 7361 7302 1.00321 0.0356227 -0.0119825 1 0 1 1 0 0 +EDGE2 7361 7182 1.03093 -0.013643 -0.00238182 1 0 1 1 0 0 +EDGE2 7361 7320 -0.994207 0.0723062 -1.55147 1 0 1 1 0 0 +EDGE2 7361 7281 0.0274953 0.00784777 0.0104552 1 0 1 1 0 0 +EDGE2 7361 7301 -0.0479164 -0.0774463 0.00508234 1 0 1 1 0 0 +EDGE2 7361 7321 -0.0657296 0.00540092 0.0231134 1 0 1 1 0 0 +EDGE2 7361 7181 -0.0164804 -0.0023081 0.0132156 1 0 1 1 0 0 +EDGE2 7361 7360 -1.0006 0.00630857 -1.59965 1 0 1 1 0 0 +EDGE2 7361 7340 -1.00606 -0.0134832 -1.58404 1 0 1 1 0 0 +EDGE2 7361 7180 -1.01907 0.00227983 -1.60288 1 0 1 1 0 0 +EDGE2 7361 7280 -0.989347 0.0720287 -1.56033 1 0 1 1 0 0 +EDGE2 7361 7300 -0.93892 0.0364308 -1.55541 1 0 1 1 0 0 +EDGE2 7362 7341 -1.00358 -0.029511 -0.016562 1 0 1 1 0 0 +EDGE2 7362 7343 0.945876 0.0590644 0.0666752 1 0 1 1 0 0 +EDGE2 7362 7283 1.04355 0.108492 -0.0153989 1 0 1 1 0 0 +EDGE2 7362 7303 1.06418 -0.113098 0.0170151 1 0 1 1 0 0 +EDGE2 7362 7323 0.938775 -0.0455991 0.0199077 1 0 1 1 0 0 +EDGE2 7362 7183 0.951258 -0.0442188 0.0216787 1 0 1 1 0 0 +EDGE2 7362 7282 -0.00886991 -0.0109727 0.00305109 1 0 1 1 0 0 +EDGE2 7362 7322 0.031344 -0.0447522 -0.0285947 1 0 1 1 0 0 +EDGE2 7362 7342 -0.0609804 0.00887612 0.0281448 1 0 1 1 0 0 +EDGE2 7362 7302 -0.018749 -0.0542538 -0.0102513 1 0 1 1 0 0 +EDGE2 7362 7182 0.0597103 0.0950848 -0.0368129 1 0 1 1 0 0 +EDGE2 7362 7361 -1.01772 0.01034 0.0173714 1 0 1 1 0 0 +EDGE2 7362 7281 -1.03659 0.0579968 -0.0080321 1 0 1 1 0 0 +EDGE2 7362 7301 -1.06575 -0.112791 0.00294273 1 0 1 1 0 0 +EDGE2 7362 7321 -1.05524 -0.0553984 0.00102592 1 0 1 1 0 0 +EDGE2 7362 7181 -1.07641 -0.0494588 0.0196367 1 0 1 1 0 0 +EDGE2 7363 7304 1.04512 -0.020222 0.0131488 1 0 1 1 0 0 +EDGE2 7363 7344 0.986967 -0.0182699 0.00148064 1 0 1 1 0 0 +EDGE2 7363 7324 0.95172 0.0756227 -0.0278643 1 0 1 1 0 0 +EDGE2 7363 7343 -0.0384159 0.0462554 -0.0148179 1 0 1 1 0 0 +EDGE2 7363 7184 1.03862 -0.0400733 -0.0576732 1 0 1 1 0 0 +EDGE2 7363 7284 1.05237 0.0504344 0.00610244 1 0 1 1 0 0 +EDGE2 7363 7283 -0.00455039 0.0332229 -0.00213894 1 0 1 1 0 0 +EDGE2 7363 7303 -0.021474 -0.0813039 -0.0197415 1 0 1 1 0 0 +EDGE2 7363 7323 0.0348149 -0.0599714 -0.00457408 1 0 1 1 0 0 +EDGE2 7363 7183 0.0600972 0.0521559 0.0315527 1 0 1 1 0 0 +EDGE2 7363 7282 -1.07965 -0.0839726 0.00782806 1 0 1 1 0 0 +EDGE2 7363 7322 -1.0396 -0.019508 0.00372438 1 0 1 1 0 0 +EDGE2 7363 7342 -1.06662 0.0337932 -0.0390161 1 0 1 1 0 0 +EDGE2 7363 7362 -1.04666 0.0507772 0.0169072 1 0 1 1 0 0 +EDGE2 7363 7302 -0.934557 -0.0163176 0.00573116 1 0 1 1 0 0 +EDGE2 7363 7182 -0.965731 0.026401 0.0235546 1 0 1 1 0 0 +EDGE2 7364 7285 1.02876 -0.0196651 0.0505761 1 0 1 1 0 0 +EDGE2 7364 7325 0.990981 -0.0260993 -0.0192537 1 0 1 1 0 0 +EDGE2 7364 7345 1.0199 0.0835343 0.0209155 1 0 1 1 0 0 +EDGE2 7364 7305 1.03929 -0.0376838 -0.00150156 1 0 1 1 0 0 +EDGE2 7364 7185 1.03821 -0.0263172 -0.0109337 1 0 1 1 0 0 +EDGE2 7364 7304 0.0272455 -0.133593 -0.0057928 1 0 1 1 0 0 +EDGE2 7364 7344 0.0330946 0.0548658 -0.0167558 1 0 1 1 0 0 +EDGE2 7364 7324 -0.0225195 -0.0429643 0.00439005 1 0 1 1 0 0 +EDGE2 7364 7343 -0.983393 0.00626065 -0.0162562 1 0 1 1 0 0 +EDGE2 7364 7184 -0.0756806 0.0404411 -0.0147675 1 0 1 1 0 0 +EDGE2 7364 7284 0.0115446 0.0708078 0.0202594 1 0 1 1 0 0 +EDGE2 7364 7363 -1.02445 -0.0468826 -0.0290139 1 0 1 1 0 0 +EDGE2 7364 7283 -0.903536 -0.0836196 0.0178355 1 0 1 1 0 0 +EDGE2 7364 7303 -0.981045 -0.010609 -0.00451264 1 0 1 1 0 0 +EDGE2 7364 7323 -1.07769 0.0198844 0.00375456 1 0 1 1 0 0 +EDGE2 7364 7183 -0.950293 -0.0744158 0.0250179 1 0 1 1 0 0 +EDGE2 7365 7326 -0.0510605 1.00823 1.56488 1 0 1 1 0 0 +EDGE2 7365 7346 -0.00724053 0.97103 1.56732 1 0 1 1 0 0 +EDGE2 7365 7286 -0.0477264 0.937055 1.59507 1 0 1 1 0 0 +EDGE2 7365 7306 0.0522125 1.01885 1.59846 1 0 1 1 0 0 +EDGE2 7365 7285 0.0392745 0.0251384 0.00319773 1 0 1 1 0 0 +EDGE2 7365 7325 -0.0148857 -0.0671532 0.0186754 1 0 1 1 0 0 +EDGE2 7365 7345 -0.074927 -0.00261045 0.0389403 1 0 1 1 0 0 +EDGE2 7365 7305 -0.0046629 0.0282925 -0.0490449 1 0 1 1 0 0 +EDGE2 7365 7185 -0.0450698 -0.029258 -0.0183797 1 0 1 1 0 0 +EDGE2 7365 7186 -0.0945521 -0.910313 -1.57211 1 0 1 1 0 0 +EDGE2 7365 7304 -0.894379 -0.0725391 -0.00856381 1 0 1 1 0 0 +EDGE2 7365 7344 -0.97115 0.0672654 -0.0127258 1 0 1 1 0 0 +EDGE2 7365 7364 -0.940697 0.0457477 -0.0390055 1 0 1 1 0 0 +EDGE2 7365 7324 -1.01848 0.000516027 0.0127261 1 0 1 1 0 0 +EDGE2 7365 7184 -1.04359 0.00200339 -0.00240692 1 0 1 1 0 0 +EDGE2 7365 7284 -0.992041 -0.0501945 -0.000729874 1 0 1 1 0 0 +EDGE2 7366 7285 -0.976742 -0.0240812 1.59251 1 0 1 1 0 0 +EDGE2 7366 7325 -0.957144 -0.0855996 1.63715 1 0 1 1 0 0 +EDGE2 7366 7345 -0.923728 -0.0581034 1.55014 1 0 1 1 0 0 +EDGE2 7366 7365 -1.02336 0.0043809 1.56289 1 0 1 1 0 0 +EDGE2 7366 7305 -1.06931 0.0640815 1.54 1 0 1 1 0 0 +EDGE2 7366 7185 -0.947568 -0.0632093 1.57801 1 0 1 1 0 0 +EDGE2 7366 7186 -0.0070304 0.0401302 0.0192936 1 0 1 1 0 0 +EDGE2 7366 7187 1.01566 -0.0201433 0.00390818 1 0 1 1 0 0 +EDGE2 7367 7366 -1.04724 -0.053407 -0.0162798 1 0 1 1 0 0 +EDGE2 7367 7186 -1.01702 -0.0071347 0.0053293 1 0 1 1 0 0 +EDGE2 7367 7188 1.07684 -0.0755124 -0.0169889 1 0 1 1 0 0 +EDGE2 7367 7187 -0.0673777 -0.0473209 -0.0230387 1 0 1 1 0 0 +EDGE2 7368 7188 0.0763561 0.0490831 0.0119423 1 0 1 1 0 0 +EDGE2 7368 7187 -1.02652 0.0418913 -0.0280523 1 0 1 1 0 0 +EDGE2 7368 7367 -1.0713 0.0326685 -0.0291385 1 0 1 1 0 0 +EDGE2 7368 7189 1.03799 0.0401624 -0.0142336 1 0 1 1 0 0 +EDGE2 7369 7188 -0.953149 0.0220723 0.00378842 1 0 1 1 0 0 +EDGE2 7369 7368 -0.966464 -0.0455113 -0.00907248 1 0 1 1 0 0 +EDGE2 7369 7189 -0.0268552 0.0532679 0.00118631 1 0 1 1 0 0 +EDGE2 7369 7190 0.966115 0.0364939 0.00653818 1 0 1 1 0 0 +EDGE2 7370 7369 -0.957636 -0.0667733 0.0355038 1 0 1 1 0 0 +EDGE2 7370 7189 -1.02264 -0.0434302 -0.0184153 1 0 1 1 0 0 +EDGE2 7370 7190 0.0104968 -0.0496784 -0.000660842 1 0 1 1 0 0 +EDGE2 7370 7191 0.0193284 -0.983268 -1.5673 1 0 1 1 0 0 +EDGE2 7371 7370 -0.969224 -0.0189921 -1.59202 1 0 1 1 0 0 +EDGE2 7371 7190 -1.0398 -0.0405903 -1.55368 1 0 1 1 0 0 +EDGE2 7372 7371 -1.02626 0.0866482 -0.00733489 1 0 1 1 0 0 +EDGE2 7373 7372 -0.93541 0.0501011 -0.00921515 1 0 1 1 0 0 +EDGE2 7374 7373 -0.965073 0.01477 0.021602 1 0 1 1 0 0 +EDGE2 7375 7374 -0.966643 -0.0318757 0.0522973 1 0 1 1 0 0 +EDGE2 7376 7375 -1.00237 0.023227 -1.56637 1 0 1 1 0 0 +EDGE2 7377 7376 -1.00433 0.0317478 0.034024 1 0 1 1 0 0 +EDGE2 7378 7377 -0.939082 -0.0700903 0.00873321 1 0 1 1 0 0 +EDGE2 7379 7378 -1.03257 -0.0281195 -0.0297692 1 0 1 1 0 0 +EDGE2 7380 7379 -1.00856 -0.0229313 -0.0208595 1 0 1 1 0 0 +EDGE2 7381 7380 -1.00516 0.0143993 1.55183 1 0 1 1 0 0 +EDGE2 7382 7381 -0.968232 0.0284278 -0.00640147 1 0 1 1 0 0 +EDGE2 7383 7382 -1.06232 0.0503573 0.0176687 1 0 1 1 0 0 +EDGE2 7384 7383 -1.04608 0.0397262 0.00216835 1 0 1 1 0 0 +EDGE2 7385 7384 -0.950615 -0.0618271 0.00315023 1 0 1 1 0 0 +EDGE2 7386 7385 -0.914358 -0.0805344 -1.57673 1 0 1 1 0 0 +EDGE2 7387 7386 -0.994975 -0.0340819 0.0338766 1 0 1 1 0 0 +EDGE2 7388 7387 -1.01891 -0.0546239 -0.0143113 1 0 1 1 0 0 +EDGE2 7389 7388 -1.01286 -0.000640674 0.0137569 1 0 1 1 0 0 +EDGE2 7390 7389 -1.06014 0.125797 -0.00490775 1 0 1 1 0 0 +EDGE2 7391 7390 -0.975578 0.0741016 -1.63667 1 0 1 1 0 0 +EDGE2 7392 7391 -0.916468 0.0530878 -0.0205939 1 0 1 1 0 0 +EDGE2 7393 7392 -1.06736 0.0050808 0.0304091 1 0 1 1 0 0 +EDGE2 7394 7393 -0.994766 -0.0627294 -0.0178386 1 0 1 1 0 0 +EDGE2 7395 7394 -0.954041 -0.00628278 -0.000288014 1 0 1 1 0 0 +EDGE2 7396 7395 -0.96795 -0.0205946 1.54513 1 0 1 1 0 0 +EDGE2 7397 7396 -1.02942 -0.034051 0.0182068 1 0 1 1 0 0 +EDGE2 7398 7397 -0.994182 0.0121436 -0.0358304 1 0 1 1 0 0 +EDGE2 7399 7398 -1.00809 0.00971919 0.0440094 1 0 1 1 0 0 +EDGE2 7400 7399 -0.965961 0.103117 0.00469553 1 0 1 1 0 0 +EDGE2 7401 7400 -0.931037 0.0533331 -1.5564 1 0 1 1 0 0 +EDGE2 7402 7401 -0.896107 0.0494113 -0.0100615 1 0 1 1 0 0 +EDGE2 7403 7402 -0.952957 -0.0657768 -0.00810686 1 0 1 1 0 0 +EDGE2 7404 7403 -0.891881 0.0554116 0.00931895 1 0 1 1 0 0 +EDGE2 7404 7145 1.04675 -0.0379913 -3.11853 1 0 1 1 0 0 +EDGE2 7404 7165 1.00028 0.0340179 -3.14244 1 0 1 1 0 0 +EDGE2 7405 7404 -1.02496 -0.0584943 0.0129525 1 0 1 1 0 0 +EDGE2 7405 7146 0.0362897 -1.12057 -1.534 1 0 1 1 0 0 +EDGE2 7405 7145 -0.0444959 -0.0125451 -3.14221 1 0 1 1 0 0 +EDGE2 7405 7165 0.0781544 0.0279027 -3.1352 1 0 1 1 0 0 +EDGE2 7405 7166 -0.013659 1.01944 1.5568 1 0 1 1 0 0 +EDGE2 7405 7144 1.01761 0.00607026 -3.1293 1 0 1 1 0 0 +EDGE2 7405 7164 0.966703 -0.0467115 -3.15677 1 0 1 1 0 0 +EDGE2 7406 7146 0.0235958 -0.117408 -0.00513641 1 0 1 1 0 0 +EDGE2 7406 7147 0.997425 -0.00789478 0.000941948 1 0 1 1 0 0 +EDGE2 7406 7145 -0.939472 0.0961563 -1.59231 1 0 1 1 0 0 +EDGE2 7406 7165 -1.0379 0.0520543 -1.57849 1 0 1 1 0 0 +EDGE2 7406 7405 -0.995003 0.0384766 1.62431 1 0 1 1 0 0 +EDGE2 7407 7148 0.968909 -0.00372891 -0.0245595 1 0 1 1 0 0 +EDGE2 7407 7146 -1.03835 -0.00650595 -0.0221437 1 0 1 1 0 0 +EDGE2 7407 7406 -1.04559 0.00715536 0.00289969 1 0 1 1 0 0 +EDGE2 7407 7147 -0.0020745 -0.0557608 -0.0110196 1 0 1 1 0 0 +EDGE2 7408 7407 -1.05255 -0.0315297 -0.0166981 1 0 1 1 0 0 +EDGE2 7408 7149 1.04732 0.0469695 0.0266534 1 0 1 1 0 0 +EDGE2 7408 7148 0.0341954 -0.0502776 0.0213455 1 0 1 1 0 0 +EDGE2 7408 7147 -1.00777 0.0104962 -0.015589 1 0 1 1 0 0 +EDGE2 7409 7150 1.01884 -0.026044 -0.00999982 1 0 1 1 0 0 +EDGE2 7409 7408 -1.08738 -0.00183421 0.00507725 1 0 1 1 0 0 +EDGE2 7409 7149 0.0192003 0.0200507 -0.00353678 1 0 1 1 0 0 +EDGE2 7409 7148 -1.03952 -0.135928 0.0397844 1 0 1 1 0 0 +EDGE2 7410 7150 -0.0048642 -0.0508019 0.03063 1 0 1 1 0 0 +EDGE2 7410 7149 -1.07431 -0.0226572 -0.0311677 1 0 1 1 0 0 +EDGE2 7410 7409 -0.973439 -0.0270293 0.0307287 1 0 1 1 0 0 +EDGE2 7410 7151 -0.0077174 0.954786 1.60739 1 0 1 1 0 0 +EDGE2 7411 7150 -1.02391 -0.0155957 -1.54287 1 0 1 1 0 0 +EDGE2 7411 7410 -1.02552 0.00633584 -1.59887 1 0 1 1 0 0 +EDGE2 7411 7152 0.966449 0.0704943 0.010444 1 0 1 1 0 0 +EDGE2 7411 7151 -0.0164909 -0.0079009 -0.00545531 1 0 1 1 0 0 +EDGE2 7412 7153 0.921307 -0.0253183 -0.0308656 1 0 1 1 0 0 +EDGE2 7412 7411 -1.0511 0.0147771 -0.0130287 1 0 1 1 0 0 +EDGE2 7412 7152 0.0433739 -0.00158724 -0.0128285 1 0 1 1 0 0 +EDGE2 7412 7151 -0.966464 0.00627583 -0.00334682 1 0 1 1 0 0 +EDGE2 7413 7153 -0.0369802 -0.0779486 -0.00622643 1 0 1 1 0 0 +EDGE2 7413 7152 -0.999642 0.0251101 -0.0123436 1 0 1 1 0 0 +EDGE2 7413 7412 -0.963538 0.0163642 -0.00141329 1 0 1 1 0 0 +EDGE2 7413 7154 1.02882 -0.031686 0.0144299 1 0 1 1 0 0 +EDGE2 7414 7153 -0.940501 0.0358815 0.0226055 1 0 1 1 0 0 +EDGE2 7414 7413 -1.03146 0.0550636 -0.00419306 1 0 1 1 0 0 +EDGE2 7414 7075 0.958667 0.0522387 -3.1336 1 0 1 1 0 0 +EDGE2 7414 7154 -0.0904658 -0.0278806 0.00338015 1 0 1 1 0 0 +EDGE2 7414 7155 1.01679 0.048353 0.00817511 1 0 1 1 0 0 +EDGE2 7415 7076 -0.0154946 -1.00645 -1.57323 1 0 1 1 0 0 +EDGE2 7415 7075 0.0507705 -0.0657639 -3.14184 1 0 1 1 0 0 +EDGE2 7415 7154 -0.969439 -0.0980396 -0.0514268 1 0 1 1 0 0 +EDGE2 7415 7414 -0.942976 -0.00176073 0.0055007 1 0 1 1 0 0 +EDGE2 7415 7155 -0.00836603 0.00642244 -0.0210889 1 0 1 1 0 0 +EDGE2 7415 7156 0.0198355 0.932511 1.55862 1 0 1 1 0 0 +EDGE2 7415 7074 0.924574 -0.0562248 -3.18113 1 0 1 1 0 0 +EDGE2 7416 7075 -0.987829 0.0119014 1.57106 1 0 1 1 0 0 +EDGE2 7416 7415 -1.00431 0.00304788 -1.58555 1 0 1 1 0 0 +EDGE2 7416 7155 -1.05362 -0.0188105 -1.59485 1 0 1 1 0 0 +EDGE2 7416 7156 -0.0332655 0.0551643 -0.0319537 1 0 1 1 0 0 +EDGE2 7416 7157 0.957416 -0.0114896 0.0068386 1 0 1 1 0 0 +EDGE2 7417 7156 -1.12908 -0.0150569 0.0316051 1 0 1 1 0 0 +EDGE2 7417 7416 -0.992543 -0.00552953 0.019254 1 0 1 1 0 0 +EDGE2 7417 7157 -0.0675044 0.0702519 0.0032594 1 0 1 1 0 0 +EDGE2 7417 7158 1.00021 -0.070713 0.0125661 1 0 1 1 0 0 +EDGE2 7418 7159 1.02423 -0.00614827 0.00929342 1 0 1 1 0 0 +EDGE2 7418 7417 -1.01099 -0.14176 0.0119598 1 0 1 1 0 0 +EDGE2 7418 7157 -0.938734 0.101718 -0.00147701 1 0 1 1 0 0 +EDGE2 7418 7158 -0.0536138 0.0387886 0.00193382 1 0 1 1 0 0 +EDGE2 7419 7159 -0.0746057 -0.0274029 -0.00156855 1 0 1 1 0 0 +EDGE2 7419 7418 -1.05529 0.0390842 0.0155958 1 0 1 1 0 0 +EDGE2 7419 7158 -1.0081 -0.0372157 0.0248533 1 0 1 1 0 0 +EDGE2 7419 7260 0.944173 0.0722477 -3.14801 1 0 1 1 0 0 +EDGE2 7419 7120 1.14567 -0.0186372 -3.1314 1 0 1 1 0 0 +EDGE2 7419 7140 1.02456 0.0221988 -3.11952 1 0 1 1 0 0 +EDGE2 7419 7160 0.962392 -0.127559 0.00680355 1 0 1 1 0 0 +EDGE2 7420 7159 -0.918282 -0.0071444 0.00731787 1 0 1 1 0 0 +EDGE2 7420 7419 -1.02184 -0.0128542 0.0528582 1 0 1 1 0 0 +EDGE2 7420 7261 -0.0491904 -0.946578 -1.5915 1 0 1 1 0 0 +EDGE2 7420 7260 -0.01852 -0.122755 -3.16945 1 0 1 1 0 0 +EDGE2 7420 7141 0.0493408 1.0118 1.55266 1 0 1 1 0 0 +EDGE2 7420 7161 0.0578199 1.018 1.57478 1 0 1 1 0 0 +EDGE2 7420 7120 0.0321326 0.0239608 -3.11017 1 0 1 1 0 0 +EDGE2 7420 7140 -0.0702728 0.0389657 -3.10901 1 0 1 1 0 0 +EDGE2 7420 7160 0.0285755 0.00669165 0.00560855 1 0 1 1 0 0 +EDGE2 7420 7119 0.986891 -0.0273851 -3.11458 1 0 1 1 0 0 +EDGE2 7420 7259 0.976389 0.0233222 -3.10861 1 0 1 1 0 0 +EDGE2 7420 7121 -0.0273219 -1.02132 -1.5591 1 0 1 1 0 0 +EDGE2 7420 7139 1.02903 -0.0174524 -3.12817 1 0 1 1 0 0 +EDGE2 7421 7261 0.0279092 -0.015875 0.014447 1 0 1 1 0 0 +EDGE2 7421 7260 -0.99343 -0.00249677 -1.56904 1 0 1 1 0 0 +EDGE2 7421 7420 -1.03288 -0.0100972 1.58324 1 0 1 1 0 0 +EDGE2 7421 7120 -1.07934 -0.00912064 -1.58581 1 0 1 1 0 0 +EDGE2 7421 7140 -1.04113 0.0315863 -1.55338 1 0 1 1 0 0 +EDGE2 7421 7160 -0.996385 -0.00838609 1.57779 1 0 1 1 0 0 +EDGE2 7421 7121 -0.0223982 -0.00468885 0.000191207 1 0 1 1 0 0 +EDGE2 7421 7122 1.01734 -0.0734547 0.0140291 1 0 1 1 0 0 +EDGE2 7421 7262 1.04425 0.0828878 -0.0398251 1 0 1 1 0 0 +EDGE2 7422 7261 -1.01585 -0.0172444 0.0276653 1 0 1 1 0 0 +EDGE2 7422 7421 -0.935273 -0.0835041 0.026775 1 0 1 1 0 0 +EDGE2 7422 7121 -1.09112 -0.00833157 -0.00162304 1 0 1 1 0 0 +EDGE2 7422 7123 1.03828 -0.0699348 0.0188112 1 0 1 1 0 0 +EDGE2 7422 7122 -0.029268 -0.0118781 0.0102229 1 0 1 1 0 0 +EDGE2 7422 7262 0.0806196 0.000315182 0.0159337 1 0 1 1 0 0 +EDGE2 7422 7263 1.0058 -0.0395058 0.00891935 1 0 1 1 0 0 +EDGE2 7423 7422 -0.908909 0.00984342 -0.0459431 1 0 1 1 0 0 +EDGE2 7423 7123 0.062308 -0.0643111 0.00110287 1 0 1 1 0 0 +EDGE2 7423 7122 -0.968292 0.0399693 -0.0184309 1 0 1 1 0 0 +EDGE2 7423 7262 -1.03364 0.00602732 0.0238698 1 0 1 1 0 0 +EDGE2 7423 7263 0.0627804 -0.0567171 -0.00621282 1 0 1 1 0 0 +EDGE2 7423 7264 0.948642 -0.0304915 0.00704344 1 0 1 1 0 0 +EDGE2 7423 7124 1.03128 0.0313181 0.00872199 1 0 1 1 0 0 +EDGE2 7424 7123 -1.01806 0.0438877 0.0166176 1 0 1 1 0 0 +EDGE2 7424 7423 -1.02281 -0.0779496 0.027056 1 0 1 1 0 0 +EDGE2 7424 7263 -0.966716 0.0279161 -0.00981213 1 0 1 1 0 0 +EDGE2 7424 7264 -0.0283999 0.0998008 0.00140004 1 0 1 1 0 0 +EDGE2 7424 7124 -0.0202103 -0.0406662 0.0324762 1 0 1 1 0 0 +EDGE2 7424 7125 0.973114 0.0020752 0.000165498 1 0 1 1 0 0 +EDGE2 7424 7265 0.954757 0.00821994 -0.00680846 1 0 1 1 0 0 +EDGE2 7424 7065 1.04669 -0.0080362 -3.13492 1 0 1 1 0 0 +EDGE2 7424 7105 1.01353 -0.0524473 -3.10965 1 0 1 1 0 0 +EDGE2 7425 7264 -1.01442 -0.0178245 -0.00772415 1 0 1 1 0 0 +EDGE2 7425 7424 -0.954715 -0.032648 0.0117029 1 0 1 1 0 0 +EDGE2 7425 7124 -0.988444 0.0387108 -0.00713438 1 0 1 1 0 0 +EDGE2 7425 7125 -0.0340732 0.0542537 0.00479043 1 0 1 1 0 0 +EDGE2 7425 7066 -0.0237008 -1.04297 -1.56707 1 0 1 1 0 0 +EDGE2 7425 7265 -0.0833001 0.0639772 -0.0151007 1 0 1 1 0 0 +EDGE2 7425 7104 1.03889 0.0179302 -3.14257 1 0 1 1 0 0 +EDGE2 7425 7065 0.0424531 -0.0190765 -3.16289 1 0 1 1 0 0 +EDGE2 7425 7105 0.0279892 -0.0597728 -3.16574 1 0 1 1 0 0 +EDGE2 7425 7064 1.01724 0.0571146 -3.14201 1 0 1 1 0 0 +EDGE2 7425 7126 -0.0398049 1.03653 1.58733 1 0 1 1 0 0 +EDGE2 7425 7266 -0.122993 1.08543 1.56856 1 0 1 1 0 0 +EDGE2 7425 7106 0.0436787 0.991616 1.54734 1 0 1 1 0 0 +EDGE2 7426 7125 -1.02762 -0.0036347 -1.58807 1 0 1 1 0 0 +EDGE2 7426 7425 -1.03795 -0.0634043 -1.56891 1 0 1 1 0 0 +EDGE2 7426 7265 -1.09309 -0.0133704 -1.57805 1 0 1 1 0 0 +EDGE2 7426 7065 -1.06732 0.0772391 1.56345 1 0 1 1 0 0 +EDGE2 7426 7105 -0.98575 0.0270963 1.55559 1 0 1 1 0 0 +EDGE2 7426 7126 0.05187 -0.0337359 0.0256518 1 0 1 1 0 0 +EDGE2 7426 7266 -0.0325985 0.117412 -0.0119 1 0 1 1 0 0 +EDGE2 7426 7106 -0.0532684 0.0253604 -0.0294404 1 0 1 1 0 0 +EDGE2 7426 7267 1.01425 -0.0861959 0.010085 1 0 1 1 0 0 +EDGE2 7426 7107 1.09379 0.0963456 -0.0176829 1 0 1 1 0 0 +EDGE2 7426 7127 1.0349 -0.00341703 0.0434773 1 0 1 1 0 0 +EDGE2 7427 7126 -0.904642 0.015386 0.0286176 1 0 1 1 0 0 +EDGE2 7427 7266 -0.963553 -0.0296649 0.031216 1 0 1 1 0 0 +EDGE2 7427 7426 -1.03825 -0.0825992 0.00186043 1 0 1 1 0 0 +EDGE2 7427 7106 -0.985331 -0.10254 0.0128567 1 0 1 1 0 0 +EDGE2 7427 7267 0.0223277 -0.00149294 0.00964807 1 0 1 1 0 0 +EDGE2 7427 7107 0.089607 0.0301383 -0.0178239 1 0 1 1 0 0 +EDGE2 7427 7127 -0.0293248 0.00927099 0.0184741 1 0 1 1 0 0 +EDGE2 7427 7128 0.922507 -0.0339189 0.0196954 1 0 1 1 0 0 +EDGE2 7427 7268 0.990312 -0.0756491 0.0107017 1 0 1 1 0 0 +EDGE2 7427 7108 0.942335 0.00590627 0.0162345 1 0 1 1 0 0 +EDGE2 7428 7267 -1.10001 0.0186103 0.0217332 1 0 1 1 0 0 +EDGE2 7428 7427 -1.06511 -0.000359547 0.0203391 1 0 1 1 0 0 +EDGE2 7428 7107 -1.0043 0.0157177 -0.0150844 1 0 1 1 0 0 +EDGE2 7428 7127 -0.970819 -0.0138428 0.0271851 1 0 1 1 0 0 +EDGE2 7428 7128 -0.0266776 0.0144376 0.00958687 1 0 1 1 0 0 +EDGE2 7428 7268 0.0154452 0.0753163 0.0215431 1 0 1 1 0 0 +EDGE2 7428 7108 0.0333727 0.0590458 0.00766534 1 0 1 1 0 0 +EDGE2 7428 7129 1.02095 -0.0868455 -0.027026 1 0 1 1 0 0 +EDGE2 7428 7269 1.01212 -0.0270219 -0.00570882 1 0 1 1 0 0 +EDGE2 7428 7109 1.05219 0.0266642 0.0115949 1 0 1 1 0 0 +EDGE2 7429 7128 -0.962099 -0.00902607 0.0148201 1 0 1 1 0 0 +EDGE2 7429 7268 -0.930679 0.0264002 0.00919747 1 0 1 1 0 0 +EDGE2 7429 7428 -1.05367 -0.00555982 -0.0191707 1 0 1 1 0 0 +EDGE2 7429 7108 -1.01359 0.0230277 0.0186426 1 0 1 1 0 0 +EDGE2 7429 7129 -0.0730437 -0.0173372 -0.0317809 1 0 1 1 0 0 +EDGE2 7429 7269 0.0384321 -0.0574053 -0.0138454 1 0 1 1 0 0 +EDGE2 7429 7109 0.035995 -0.0358102 0.00721262 1 0 1 1 0 0 +EDGE2 7429 7250 0.94117 0.0137412 -3.14562 1 0 1 1 0 0 +EDGE2 7429 7270 0.997664 0.039821 -0.0100802 1 0 1 1 0 0 +EDGE2 7429 7110 0.951962 -0.0112979 -0.0189228 1 0 1 1 0 0 +EDGE2 7429 7130 0.97382 0.0729709 -0.0356381 1 0 1 1 0 0 +EDGE2 7430 7131 -0.0204053 1.00121 1.5784 1 0 1 1 0 0 +EDGE2 7430 7271 0.0547973 0.98109 1.57117 1 0 1 1 0 0 +EDGE2 7430 7251 0.0358793 0.980206 1.61142 1 0 1 1 0 0 +EDGE2 7430 7111 0.0432118 1.05933 1.5626 1 0 1 1 0 0 +EDGE2 7430 7129 -0.985113 -0.0592524 -0.00575149 1 0 1 1 0 0 +EDGE2 7430 7269 -1.07851 -0.0363644 0.0247429 1 0 1 1 0 0 +EDGE2 7430 7429 -1.00417 0.046147 0.00899993 1 0 1 1 0 0 +EDGE2 7430 7109 -0.90754 0.0208616 0.0141183 1 0 1 1 0 0 +EDGE2 7430 7250 -0.0415147 -0.058269 -3.14376 1 0 1 1 0 0 +EDGE2 7430 7270 0.0322392 0.00299285 0.0376894 1 0 1 1 0 0 +EDGE2 7430 7110 -0.0133755 -8.80546e-05 -0.0155833 1 0 1 1 0 0 +EDGE2 7430 7130 0.0598326 -0.00327908 0.017201 1 0 1 1 0 0 +EDGE2 7430 7249 1.01613 0.0531524 -3.12571 1 0 1 1 0 0 +EDGE2 7431 7132 1.00231 0.0145889 7.71719e-06 1 0 1 1 0 0 +EDGE2 7431 7272 1.02023 0.0981502 0.00553748 1 0 1 1 0 0 +EDGE2 7431 7252 1.03084 0.067313 0.0178092 1 0 1 1 0 0 +EDGE2 7431 7131 0.0730546 0.0949485 0.00142199 1 0 1 1 0 0 +EDGE2 7431 7271 0.0226786 -0.00588895 0.0184624 1 0 1 1 0 0 +EDGE2 7431 7112 1.02863 -0.0465993 -0.0230646 1 0 1 1 0 0 +EDGE2 7431 7251 0.0763353 -0.0348076 0.0160465 1 0 1 1 0 0 +EDGE2 7431 7111 -0.00704324 0.0162991 -0.0195903 1 0 1 1 0 0 +EDGE2 7431 7250 -1.01854 0.00273238 1.55688 1 0 1 1 0 0 +EDGE2 7431 7430 -1.02829 -0.0107232 -1.60166 1 0 1 1 0 0 +EDGE2 7431 7270 -0.964238 0.0224239 -1.58367 1 0 1 1 0 0 +EDGE2 7431 7110 -0.959795 -0.0314101 -1.58341 1 0 1 1 0 0 +EDGE2 7431 7130 -0.942517 0.0724717 -1.60457 1 0 1 1 0 0 +EDGE2 7432 7132 -0.0733171 0.0564054 0.0270298 1 0 1 1 0 0 +EDGE2 7432 7133 1.05133 -0.0323119 0.00397063 1 0 1 1 0 0 +EDGE2 7432 7273 1.02068 -0.00065265 0.0135674 1 0 1 1 0 0 +EDGE2 7432 7253 0.904216 -0.0535148 0.0303554 1 0 1 1 0 0 +EDGE2 7432 7272 0.01711 0.0825283 0.00848554 1 0 1 1 0 0 +EDGE2 7432 7113 0.95834 -0.070422 -0.0265302 1 0 1 1 0 0 +EDGE2 7432 7252 -0.0372657 0.0553336 0.00225873 1 0 1 1 0 0 +EDGE2 7432 7131 -1.01163 0.0933388 -0.0279562 1 0 1 1 0 0 +EDGE2 7432 7271 -1.04191 -0.0418431 -0.0169462 1 0 1 1 0 0 +EDGE2 7432 7431 -0.961576 -0.0543093 -0.0168845 1 0 1 1 0 0 +EDGE2 7432 7112 0.0318678 -0.0422283 0.0358479 1 0 1 1 0 0 +EDGE2 7432 7251 -1.03072 0.0144103 0.00702621 1 0 1 1 0 0 +EDGE2 7432 7111 -0.92811 -0.0344016 0.0409291 1 0 1 1 0 0 +EDGE2 7433 7132 -1.06623 -0.0923476 -0.0124493 1 0 1 1 0 0 +EDGE2 7433 7134 1.06364 0.0406144 -0.00139981 1 0 1 1 0 0 +EDGE2 7433 7274 1.0166 -0.00826142 0.0147835 1 0 1 1 0 0 +EDGE2 7433 7254 0.946321 -0.0427066 -0.0339328 1 0 1 1 0 0 +EDGE2 7433 7133 -0.0187597 -0.0097062 -0.000152738 1 0 1 1 0 0 +EDGE2 7433 7273 0.0388196 0.0487114 0.0333092 1 0 1 1 0 0 +EDGE2 7433 7114 0.998961 -0.0329663 0.00690023 1 0 1 1 0 0 +EDGE2 7433 7253 0.00335608 0.057839 -0.0276221 1 0 1 1 0 0 +EDGE2 7433 7272 -1.00605 0.0348073 0.00241528 1 0 1 1 0 0 +EDGE2 7433 7432 -0.957142 -0.00897804 -0.0150746 1 0 1 1 0 0 +EDGE2 7433 7113 -0.00383226 -0.0108078 0.030695 1 0 1 1 0 0 +EDGE2 7433 7252 -0.944494 0.0511712 0.0132821 1 0 1 1 0 0 +EDGE2 7433 7112 -1.00104 -0.0929063 0.0150195 1 0 1 1 0 0 +EDGE2 7434 7315 1.03016 0.021135 -3.1281 1 0 1 1 0 0 +EDGE2 7434 7355 0.94671 -0.110336 -3.12639 1 0 1 1 0 0 +EDGE2 7434 7335 1.02246 -0.0512413 -3.12547 1 0 1 1 0 0 +EDGE2 7434 7134 0.0412147 -0.0797763 -0.0202103 1 0 1 1 0 0 +EDGE2 7434 7135 0.995476 0.0118635 -0.00309561 1 0 1 1 0 0 +EDGE2 7434 7255 0.987454 0.0431212 0.0260515 1 0 1 1 0 0 +EDGE2 7434 7275 1.03244 -0.0100487 -0.0150567 1 0 1 1 0 0 +EDGE2 7434 7295 0.933428 -0.0719278 -3.14692 1 0 1 1 0 0 +EDGE2 7434 7175 0.923478 0.0189277 -3.15594 1 0 1 1 0 0 +EDGE2 7434 7274 0.0131589 -0.0267897 -0.033485 1 0 1 1 0 0 +EDGE2 7434 7115 0.983388 -0.0352295 0.0235387 1 0 1 1 0 0 +EDGE2 7434 7254 -0.00744165 0.0695954 -0.0045531 1 0 1 1 0 0 +EDGE2 7434 7133 -0.977896 -0.0246253 0.0121295 1 0 1 1 0 0 +EDGE2 7434 7273 -0.989073 0.0183242 0.00281785 1 0 1 1 0 0 +EDGE2 7434 7433 -1.04654 -0.0635005 0.00329895 1 0 1 1 0 0 +EDGE2 7434 7114 -0.0312904 -0.0622277 0.0327751 1 0 1 1 0 0 +EDGE2 7434 7253 -0.967179 -0.0768722 0.00260356 1 0 1 1 0 0 +EDGE2 7434 7113 -0.999044 -0.0478358 -0.0362585 1 0 1 1 0 0 +EDGE2 7435 7315 0.0522407 0.00143772 -3.1144 1 0 1 1 0 0 +EDGE2 7435 7136 -0.033454 0.983475 1.56815 1 0 1 1 0 0 +EDGE2 7435 7256 -0.0281671 1.0163 1.54705 1 0 1 1 0 0 +EDGE2 7435 7116 -0.0399259 0.969646 1.55936 1 0 1 1 0 0 +EDGE2 7435 7354 1.07698 -0.0132533 -3.12431 1 0 1 1 0 0 +EDGE2 7435 7294 0.924454 0.161195 -3.15676 1 0 1 1 0 0 +EDGE2 7435 7314 0.996568 0.0696316 -3.11978 1 0 1 1 0 0 +EDGE2 7435 7334 1.12692 -0.0295472 -3.11992 1 0 1 1 0 0 +EDGE2 7435 7174 0.958143 -0.0825985 -3.13265 1 0 1 1 0 0 +EDGE2 7435 7355 -0.0179218 -0.0360897 -3.13991 1 0 1 1 0 0 +EDGE2 7435 7335 -0.0128029 0.00842095 -3.15969 1 0 1 1 0 0 +EDGE2 7435 7134 -1.03271 -0.00177163 -0.00725798 1 0 1 1 0 0 +EDGE2 7435 7135 -0.0580055 0.000748602 -0.0139144 1 0 1 1 0 0 +EDGE2 7435 7255 -0.0341357 -0.0288022 -0.00642174 1 0 1 1 0 0 +EDGE2 7435 7275 0.069162 0.0183235 -0.00100603 1 0 1 1 0 0 +EDGE2 7435 7295 0.0200322 0.0271338 -3.15293 1 0 1 1 0 0 +EDGE2 7435 7175 0.0177364 0.00131124 -3.15606 1 0 1 1 0 0 +EDGE2 7435 7274 -0.963456 -0.0374925 0.0365649 1 0 1 1 0 0 +EDGE2 7435 7434 -1.11555 0.067551 0.0123879 1 0 1 1 0 0 +EDGE2 7435 7115 -0.0404624 0.0033451 0.00450493 1 0 1 1 0 0 +EDGE2 7435 7254 -0.970028 -0.0467936 -0.00457765 1 0 1 1 0 0 +EDGE2 7435 7114 -0.905624 -0.0179432 0.0422072 1 0 1 1 0 0 +EDGE2 7435 7296 0.106722 -0.976126 -1.57838 1 0 1 1 0 0 +EDGE2 7435 7336 0.0628796 -0.957246 -1.57495 1 0 1 1 0 0 +EDGE2 7435 7356 0.0681049 -1.02454 -1.57806 1 0 1 1 0 0 +EDGE2 7435 7316 -0.0439917 -1.02282 -1.56801 1 0 1 1 0 0 +EDGE2 7435 7176 -0.019058 -0.954685 -1.55687 1 0 1 1 0 0 +EDGE2 7435 7276 0.0628751 -1.02221 -1.54721 1 0 1 1 0 0 +EDGE2 7436 7315 -0.955848 0.0316058 1.53075 1 0 1 1 0 0 +EDGE2 7436 7117 1.02423 -0.1125 -0.0066427 1 0 1 1 0 0 +EDGE2 7436 7137 1.04794 -0.00954762 -0.0253432 1 0 1 1 0 0 +EDGE2 7436 7257 0.933237 0.0905449 0.0023301 1 0 1 1 0 0 +EDGE2 7436 7136 0.0280783 -0.0571146 0.000492027 1 0 1 1 0 0 +EDGE2 7436 7256 -0.109159 0.024187 0.0150708 1 0 1 1 0 0 +EDGE2 7436 7116 0.0489105 0.0315347 0.00664924 1 0 1 1 0 0 +EDGE2 7436 7355 -1.05241 -0.0778225 1.55616 1 0 1 1 0 0 +EDGE2 7436 7435 -0.98941 0.0548522 -1.56959 1 0 1 1 0 0 +EDGE2 7436 7335 -1.04565 -0.0320408 1.61272 1 0 1 1 0 0 +EDGE2 7436 7135 -0.989587 -0.0636225 -1.54162 1 0 1 1 0 0 +EDGE2 7436 7255 -1.02233 0.0041971 -1.58565 1 0 1 1 0 0 +EDGE2 7436 7275 -0.984385 -0.0192005 -1.52717 1 0 1 1 0 0 +EDGE2 7436 7295 -1.10963 -0.0701958 1.57222 1 0 1 1 0 0 +EDGE2 7436 7175 -1.00655 0.0275163 1.54291 1 0 1 1 0 0 +EDGE2 7436 7115 -1.02798 -0.0311439 -1.57779 1 0 1 1 0 0 +EDGE2 7437 7138 0.941502 -0.103871 -0.010806 1 0 1 1 0 0 +EDGE2 7437 7258 1.05575 -0.0453483 0.000110192 1 0 1 1 0 0 +EDGE2 7437 7118 0.952548 -0.122171 -0.001726 1 0 1 1 0 0 +EDGE2 7437 7117 -0.0169001 -0.0440389 -0.0167683 1 0 1 1 0 0 +EDGE2 7437 7137 0.0601251 0.00183038 -0.00479681 1 0 1 1 0 0 +EDGE2 7437 7257 -0.0188129 0.0814195 -0.011979 1 0 1 1 0 0 +EDGE2 7437 7136 -0.952444 -0.0188692 0.00560397 1 0 1 1 0 0 +EDGE2 7437 7256 -0.995994 0.0894792 0.0354787 1 0 1 1 0 0 +EDGE2 7437 7436 -0.871875 -0.0323652 -0.0065384 1 0 1 1 0 0 +EDGE2 7437 7116 -0.998569 0.0906266 0.00561174 1 0 1 1 0 0 +EDGE2 7438 7119 1.04017 -0.0391823 0.0025306 1 0 1 1 0 0 +EDGE2 7438 7259 1.07426 0.0302574 0.00316806 1 0 1 1 0 0 +EDGE2 7438 7139 0.986692 0.0603947 -0.0193887 1 0 1 1 0 0 +EDGE2 7438 7138 -0.0126901 0.0301499 -0.00921273 1 0 1 1 0 0 +EDGE2 7438 7258 -0.058858 0.0281715 0.0125287 1 0 1 1 0 0 +EDGE2 7438 7118 0.0439439 0.0170457 -0.00368436 1 0 1 1 0 0 +EDGE2 7438 7437 -1.00615 -0.00354667 -0.0222237 1 0 1 1 0 0 +EDGE2 7438 7117 -1.01126 -0.02523 -0.035732 1 0 1 1 0 0 +EDGE2 7438 7137 -1.00014 0.0308332 -0.0138913 1 0 1 1 0 0 +EDGE2 7438 7257 -0.946406 0.0478981 -0.0161169 1 0 1 1 0 0 +EDGE2 7439 7260 1.03807 -0.0441526 0.000940124 1 0 1 1 0 0 +EDGE2 7439 7420 0.909673 0.0374233 -3.16232 1 0 1 1 0 0 +EDGE2 7439 7120 1.07684 0.00299453 -0.0060164 1 0 1 1 0 0 +EDGE2 7439 7140 1.07445 -0.0515521 0.00651834 1 0 1 1 0 0 +EDGE2 7439 7160 0.932447 -0.0276342 -3.14328 1 0 1 1 0 0 +EDGE2 7439 7119 0.0130482 -0.0109509 -0.0041419 1 0 1 1 0 0 +EDGE2 7439 7259 0.00274862 -0.0489414 -0.0195742 1 0 1 1 0 0 +EDGE2 7439 7139 -0.0677525 0.0564311 -0.0201543 1 0 1 1 0 0 +EDGE2 7439 7138 -1.02759 0.0649115 -0.0126215 1 0 1 1 0 0 +EDGE2 7439 7258 -1.02805 0.0542151 -0.00732147 1 0 1 1 0 0 +EDGE2 7439 7438 -1.00229 0.0932718 -0.0206057 1 0 1 1 0 0 +EDGE2 7439 7118 -1.05311 0.0753564 -0.0145595 1 0 1 1 0 0 +EDGE2 7440 7159 1.05083 0.00856309 -3.13253 1 0 1 1 0 0 +EDGE2 7440 7419 0.926471 0.00962137 -3.115 1 0 1 1 0 0 +EDGE2 7440 7261 0.00565837 0.993344 1.58457 1 0 1 1 0 0 +EDGE2 7440 7260 -0.0447423 0.0119562 -0.0248396 1 0 1 1 0 0 +EDGE2 7440 7141 -0.0957766 -1.04099 -1.54051 1 0 1 1 0 0 +EDGE2 7440 7161 0.0490846 -0.965739 -1.55473 1 0 1 1 0 0 +EDGE2 7440 7420 -0.0417349 0.0191361 -3.17249 1 0 1 1 0 0 +EDGE2 7440 7120 0.00348544 -0.0208874 0.00970087 1 0 1 1 0 0 +EDGE2 7440 7140 0.0202385 0.0539232 0.0025427 1 0 1 1 0 0 +EDGE2 7440 7160 0.0399033 0.0319975 -3.13172 1 0 1 1 0 0 +EDGE2 7440 7421 -0.0366805 1.04716 1.55138 1 0 1 1 0 0 +EDGE2 7440 7119 -0.9848 -0.0606307 0.00213861 1 0 1 1 0 0 +EDGE2 7440 7259 -0.970181 0.0473771 0.0133712 1 0 1 1 0 0 +EDGE2 7440 7121 -0.0656128 0.995853 1.56518 1 0 1 1 0 0 +EDGE2 7440 7439 -0.99563 0.115816 0.00675941 1 0 1 1 0 0 +EDGE2 7440 7139 -0.968842 0.0020204 -0.0222781 1 0 1 1 0 0 +EDGE2 7441 7162 0.892626 0.00669559 -0.022802 1 0 1 1 0 0 +EDGE2 7441 7142 0.978492 0.0226512 0.00420895 1 0 1 1 0 0 +EDGE2 7441 7260 -0.974858 0.0631254 1.58043 1 0 1 1 0 0 +EDGE2 7441 7440 -0.986579 -0.0116125 1.59145 1 0 1 1 0 0 +EDGE2 7441 7141 0.0153081 0.00866858 -0.0341234 1 0 1 1 0 0 +EDGE2 7441 7161 0.025619 0.0790459 0.0199856 1 0 1 1 0 0 +EDGE2 7441 7420 -1.02979 0.0243813 -1.57705 1 0 1 1 0 0 +EDGE2 7441 7120 -1.06606 0.0205004 1.53937 1 0 1 1 0 0 +EDGE2 7441 7140 -0.922685 0.0542454 1.59935 1 0 1 1 0 0 +EDGE2 7441 7160 -0.965459 -0.00470146 -1.60752 1 0 1 1 0 0 +EDGE2 7442 7441 -0.921075 -0.00117158 0.00766186 1 0 1 1 0 0 +EDGE2 7442 7163 1.1191 0.0313604 0.0102932 1 0 1 1 0 0 +EDGE2 7442 7162 0.0768882 -0.0727126 0.0113542 1 0 1 1 0 0 +EDGE2 7442 7143 1.06858 0.0760561 0.0186999 1 0 1 1 0 0 +EDGE2 7442 7142 0.0525477 -0.0638345 -0.00738935 1 0 1 1 0 0 +EDGE2 7442 7141 -1.03601 0.00113933 -0.0179556 1 0 1 1 0 0 +EDGE2 7442 7161 -1.00639 0.0200988 -0.0192006 1 0 1 1 0 0 +EDGE2 7443 7163 0.0705049 0.0657046 0.00833776 1 0 1 1 0 0 +EDGE2 7443 7144 0.910608 -0.00153622 0.0430833 1 0 1 1 0 0 +EDGE2 7443 7164 0.952787 0.0561901 -0.0240165 1 0 1 1 0 0 +EDGE2 7443 7162 -0.926874 -0.0237545 -0.0107282 1 0 1 1 0 0 +EDGE2 7443 7442 -1.0784 0.0116599 0.010603 1 0 1 1 0 0 +EDGE2 7443 7143 -0.0268537 -0.126827 -0.00784089 1 0 1 1 0 0 +EDGE2 7443 7142 -1.08879 -0.0103298 -2.81163e-05 1 0 1 1 0 0 +EDGE2 7444 7145 1.05551 0.0110665 -0.0166567 1 0 1 1 0 0 +EDGE2 7444 7165 1.0041 -0.0249464 0.00314795 1 0 1 1 0 0 +EDGE2 7444 7405 1.0219 0.00354954 -3.18393 1 0 1 1 0 0 +EDGE2 7444 7163 -1.03273 0.0704119 0.0217265 1 0 1 1 0 0 +EDGE2 7444 7144 0.0172369 -0.0492935 0.00912893 1 0 1 1 0 0 +EDGE2 7444 7164 -0.136984 -0.0163424 0.0349616 1 0 1 1 0 0 +EDGE2 7444 7443 -0.964317 -0.0146682 -0.00728085 1 0 1 1 0 0 +EDGE2 7444 7143 -0.984082 0.0663831 0.0166791 1 0 1 1 0 0 +EDGE2 7445 7404 1.03606 -0.014295 -3.14916 1 0 1 1 0 0 +EDGE2 7445 7146 0.00590267 0.912218 1.5678 1 0 1 1 0 0 +EDGE2 7445 7406 -0.0248743 1.13243 1.5719 1 0 1 1 0 0 +EDGE2 7445 7145 0.0793248 -0.070602 0.00844494 1 0 1 1 0 0 +EDGE2 7445 7165 -0.125076 0.00920826 0.00458132 1 0 1 1 0 0 +EDGE2 7445 7405 0.00794143 -0.0289163 -3.16477 1 0 1 1 0 0 +EDGE2 7445 7166 0.0475467 -0.915921 -1.5786 1 0 1 1 0 0 +EDGE2 7445 7144 -0.97843 0.0496169 0.0312379 1 0 1 1 0 0 +EDGE2 7445 7164 -0.989021 -0.0240053 -0.0160609 1 0 1 1 0 0 +EDGE2 7445 7444 -1.03137 -0.049672 -0.00394957 1 0 1 1 0 0 +EDGE2 7446 7445 -1.11361 0.0103665 1.57158 1 0 1 1 0 0 +EDGE2 7446 7145 -0.946707 -0.0214743 1.58448 1 0 1 1 0 0 +EDGE2 7446 7165 -1.02661 -0.0667953 1.58074 1 0 1 1 0 0 +EDGE2 7446 7405 -0.929461 0.0362364 -1.57416 1 0 1 1 0 0 +EDGE2 7446 7166 -0.0211487 0.0323555 0.0260266 1 0 1 1 0 0 +EDGE2 7446 7167 1.00659 0.0305543 -0.035064 1 0 1 1 0 0 +EDGE2 7447 7446 -0.94644 -0.0296929 0.0122918 1 0 1 1 0 0 +EDGE2 7447 7166 -1.04763 0.0827637 -0.040855 1 0 1 1 0 0 +EDGE2 7447 7168 0.967081 -0.0290668 -0.0283989 1 0 1 1 0 0 +EDGE2 7447 7167 0.00704877 0.0548014 -0.0189432 1 0 1 1 0 0 +EDGE2 7448 7168 -0.049346 0.0229741 0.00389532 1 0 1 1 0 0 +EDGE2 7448 7167 -1.00557 0.0264302 -0.0375026 1 0 1 1 0 0 +EDGE2 7448 7447 -0.946549 0.0241255 -0.0199212 1 0 1 1 0 0 +EDGE2 7448 7169 0.979045 0.00690863 0.010776 1 0 1 1 0 0 +EDGE2 7449 7168 -0.994453 0.0576868 -0.0163134 1 0 1 1 0 0 +EDGE2 7449 7448 -1.06444 -0.0517258 -0.0313889 1 0 1 1 0 0 +EDGE2 7449 7169 0.000822457 -0.0512069 0.017229 1 0 1 1 0 0 +EDGE2 7449 7310 1.05284 0.104407 -3.11826 1 0 1 1 0 0 +EDGE2 7449 7350 1.03403 -0.0323671 -3.1167 1 0 1 1 0 0 +EDGE2 7449 7330 0.943464 0.0371789 -3.1787 1 0 1 1 0 0 +EDGE2 7449 7170 1.08465 -0.0156517 -0.0212099 1 0 1 1 0 0 +EDGE2 7449 7290 1.04321 -0.0537707 -3.17241 1 0 1 1 0 0 +EDGE2 7450 7449 -0.956075 0.041605 -0.0105322 1 0 1 1 0 0 +EDGE2 7450 7169 -0.900165 -0.0377876 -0.00117628 1 0 1 1 0 0 +EDGE2 7450 7310 0.0167863 0.0109142 -3.13755 1 0 1 1 0 0 +EDGE2 7450 7350 -0.0618434 0.00744953 -3.11603 1 0 1 1 0 0 +EDGE2 7450 7330 -0.0636279 0.0105647 -3.14341 1 0 1 1 0 0 +EDGE2 7450 7170 -0.0247145 0.0457035 -0.0143504 1 0 1 1 0 0 +EDGE2 7450 7290 0.00764321 0.00524513 -3.1436 1 0 1 1 0 0 +EDGE2 7450 7329 1.09558 -0.0181138 -3.10652 1 0 1 1 0 0 +EDGE2 7450 7349 0.967365 -0.0966254 -3.12277 1 0 1 1 0 0 +EDGE2 7450 7289 1.03652 -0.0319274 -3.13615 1 0 1 1 0 0 +EDGE2 7450 7309 0.96918 0.0495058 -3.13164 1 0 1 1 0 0 +EDGE2 7450 7291 0.0763601 -0.951591 -1.55088 1 0 1 1 0 0 +EDGE2 7450 7331 -0.0669547 -1.0511 -1.5834 1 0 1 1 0 0 +EDGE2 7450 7351 -0.00587 -1.09912 -1.56994 1 0 1 1 0 0 +EDGE2 7450 7311 0.0145646 -0.902307 -1.5577 1 0 1 1 0 0 +EDGE2 7450 7171 0.0183122 -1.00904 -1.53074 1 0 1 1 0 0 +EDGE2 7451 7310 -0.966338 -0.079898 1.59019 1 0 1 1 0 0 +EDGE2 7451 7350 -1.04664 0.0663261 1.56996 1 0 1 1 0 0 +EDGE2 7451 7450 -0.969881 -0.00875351 -1.52214 1 0 1 1 0 0 +EDGE2 7451 7330 -0.995774 0.0212381 1.52818 1 0 1 1 0 0 +EDGE2 7451 7170 -0.951458 -0.0856998 -1.58727 1 0 1 1 0 0 +EDGE2 7451 7290 -1.00085 0.0524276 1.58768 1 0 1 1 0 0 +EDGE2 7452 7451 -1.02906 -0.0681868 0.000306266 1 0 1 1 0 0 +EDGE2 7453 7452 -0.977269 -0.0533609 -0.0149381 1 0 1 1 0 0 +EDGE2 7454 7395 1.0547 0.0867507 -3.11714 1 0 1 1 0 0 +EDGE2 7454 7453 -1.05494 0.0991136 -0.0127836 1 0 1 1 0 0 +EDGE2 7455 7396 0.0664604 0.964875 1.55627 1 0 1 1 0 0 +EDGE2 7455 7394 1.00763 0.0431185 -3.15233 1 0 1 1 0 0 +EDGE2 7455 7395 -0.00979179 -0.0177197 -3.09706 1 0 1 1 0 0 +EDGE2 7455 7454 -0.987491 0.0210078 0.0582346 1 0 1 1 0 0 +EDGE2 7456 7455 -0.965921 -0.0214963 1.5859 1 0 1 1 0 0 +EDGE2 7456 7395 -0.975658 0.0538684 -1.58879 1 0 1 1 0 0 +EDGE2 7457 7456 -0.97379 -0.0411745 0.0528769 1 0 1 1 0 0 +EDGE2 7458 7457 -0.953919 -0.0602428 -0.054226 1 0 1 1 0 0 +EDGE2 7459 7458 -1.01179 -0.0302505 0.0373182 1 0 1 1 0 0 +EDGE2 7459 7380 0.9611 0.00898085 -3.12994 1 0 1 1 0 0 +EDGE2 7460 7459 -1.05369 -0.0639529 0.00434863 1 0 1 1 0 0 +EDGE2 7460 7381 -0.0733851 1.0085 1.541 1 0 1 1 0 0 +EDGE2 7460 7380 -0.0686482 0.0473336 -3.17732 1 0 1 1 0 0 +EDGE2 7460 7379 0.913368 -0.0379641 -3.15324 1 0 1 1 0 0 +EDGE2 7461 7382 1.08036 -0.0682246 0.0110046 1 0 1 1 0 0 +EDGE2 7461 7381 -0.0687174 -0.0153453 0.00270995 1 0 1 1 0 0 +EDGE2 7461 7380 -1.049 0.0657216 1.5906 1 0 1 1 0 0 +EDGE2 7461 7460 -0.954937 -0.0458118 -1.57995 1 0 1 1 0 0 +EDGE2 7462 7383 1.04761 -0.00293686 -0.0411596 1 0 1 1 0 0 +EDGE2 7462 7382 0.00814577 0.0191568 -0.026645 1 0 1 1 0 0 +EDGE2 7462 7381 -0.998504 0.152248 0.0106713 1 0 1 1 0 0 +EDGE2 7462 7461 -1.04647 -0.0258676 0.0080027 1 0 1 1 0 0 +EDGE2 7463 7384 0.945757 0.0687539 -0.00855474 1 0 1 1 0 0 +EDGE2 7463 7383 -0.0353124 -0.0186902 -0.0422089 1 0 1 1 0 0 +EDGE2 7463 7382 -0.948151 -0.0243451 -0.00647452 1 0 1 1 0 0 +EDGE2 7463 7462 -1.03054 0.0353668 -0.00733536 1 0 1 1 0 0 +EDGE2 7464 7463 -0.946103 -0.0202346 -0.0203339 1 0 1 1 0 0 +EDGE2 7464 7385 1.07519 -0.0372002 -0.0316113 1 0 1 1 0 0 +EDGE2 7464 7384 -0.0270245 -0.0748217 0.0164193 1 0 1 1 0 0 +EDGE2 7464 7383 -0.942434 0.0342703 -0.00918491 1 0 1 1 0 0 +EDGE2 7465 7386 -0.0263442 1.02556 1.55571 1 0 1 1 0 0 +EDGE2 7465 7385 0.0210062 -0.0523626 0.00899165 1 0 1 1 0 0 +EDGE2 7465 7464 -1.0155 -0.0209041 -0.0108506 1 0 1 1 0 0 +EDGE2 7465 7384 -0.97008 -0.0919302 -0.0466448 1 0 1 1 0 0 +EDGE2 7466 7387 1.02319 0.0709182 -0.00714315 1 0 1 1 0 0 +EDGE2 7466 7386 -0.0478835 -0.0136054 -0.0191939 1 0 1 1 0 0 +EDGE2 7466 7465 -0.99393 0.0523465 -1.59024 1 0 1 1 0 0 +EDGE2 7466 7385 -0.965597 -0.0156977 -1.5724 1 0 1 1 0 0 +EDGE2 7467 7388 0.998748 -0.0189407 0.00690877 1 0 1 1 0 0 +EDGE2 7467 7387 0.0696015 0.0565272 0.0208335 1 0 1 1 0 0 +EDGE2 7467 7466 -0.978206 -0.00432133 -0.0219215 1 0 1 1 0 0 +EDGE2 7467 7386 -0.935624 0.0413951 0.00806127 1 0 1 1 0 0 +EDGE2 7468 7389 1.04068 0.07997 -0.00417719 1 0 1 1 0 0 +EDGE2 7468 7388 0.0393477 0.028377 0.00882799 1 0 1 1 0 0 +EDGE2 7468 7467 -0.952912 0.102248 -0.00904702 1 0 1 1 0 0 +EDGE2 7468 7387 -1.01427 -0.0119695 -0.00299492 1 0 1 1 0 0 +EDGE2 7469 7390 1.04408 0.00802684 0.0346075 1 0 1 1 0 0 +EDGE2 7469 7389 0.0470846 -0.000175758 -0.00782122 1 0 1 1 0 0 +EDGE2 7469 7468 -1.0427 -0.0815141 -0.00449701 1 0 1 1 0 0 +EDGE2 7469 7388 -1.04247 0.00258009 0.0110986 1 0 1 1 0 0 +EDGE2 7470 7390 -0.01199 -0.0395744 0.00214002 1 0 1 1 0 0 +EDGE2 7470 7391 0.0357707 1.01396 1.59792 1 0 1 1 0 0 +EDGE2 7470 7389 -1.09241 0.0590142 -0.0034752 1 0 1 1 0 0 +EDGE2 7470 7469 -0.995424 -0.0226159 0.000214252 1 0 1 1 0 0 +EDGE2 7471 7470 -0.879988 -0.048985 -1.63093 1 0 1 1 0 0 +EDGE2 7471 7390 -0.971202 0.0448676 -1.54474 1 0 1 1 0 0 +EDGE2 7471 7391 -0.0415496 0.0866812 -0.00690879 1 0 1 1 0 0 +EDGE2 7471 7392 1.02672 0.0132117 0.00310716 1 0 1 1 0 0 +EDGE2 7472 7391 -1.00316 -0.0688357 -0.00871657 1 0 1 1 0 0 +EDGE2 7472 7471 -1.02743 0.0594405 0.00629077 1 0 1 1 0 0 +EDGE2 7472 7392 -0.00353846 -0.0175718 0.0124385 1 0 1 1 0 0 +EDGE2 7472 7393 0.918409 -0.08007 0.000182474 1 0 1 1 0 0 +EDGE2 7473 7394 1.00817 0.0394819 0.00781956 1 0 1 1 0 0 +EDGE2 7473 7392 -1.04211 -0.0178519 0.000854905 1 0 1 1 0 0 +EDGE2 7473 7472 -1.06646 0.0440706 0.0073232 1 0 1 1 0 0 +EDGE2 7473 7393 -0.0732348 0.0254951 0.00173727 1 0 1 1 0 0 +EDGE2 7474 7394 0.0456586 0.0341448 -0.0383593 1 0 1 1 0 0 +EDGE2 7474 7473 -1.0178 -0.00105021 0.0231489 1 0 1 1 0 0 +EDGE2 7474 7393 -0.987386 -0.0426821 0.00138474 1 0 1 1 0 0 +EDGE2 7474 7455 1.0649 0.0178862 -3.16414 1 0 1 1 0 0 +EDGE2 7474 7395 0.984393 -0.0169633 -0.0338751 1 0 1 1 0 0 +EDGE2 7475 7396 0.0424576 -1.03225 -1.56823 1 0 1 1 0 0 +EDGE2 7475 7394 -1.02292 0.0696445 -0.029233 1 0 1 1 0 0 +EDGE2 7475 7474 -1.03481 -0.0116582 -0.00595327 1 0 1 1 0 0 +EDGE2 7475 7455 -0.0221586 -0.0231285 -3.17185 1 0 1 1 0 0 +EDGE2 7475 7395 0.024701 0.0176134 0.00820369 1 0 1 1 0 0 +EDGE2 7475 7456 0.0518399 0.989142 1.57189 1 0 1 1 0 0 +EDGE2 7475 7454 1.03511 0.0653758 -3.13853 1 0 1 1 0 0 +EDGE2 7476 7397 1.01449 -0.0123165 -0.0110832 1 0 1 1 0 0 +EDGE2 7476 7396 -0.0392035 0.0159933 -0.0142035 1 0 1 1 0 0 +EDGE2 7476 7455 -1.0223 -0.0186667 -1.53151 1 0 1 1 0 0 +EDGE2 7476 7475 -0.96737 0.0782176 1.51591 1 0 1 1 0 0 +EDGE2 7476 7395 -1.00895 0.0107555 1.52267 1 0 1 1 0 0 +EDGE2 7477 7398 0.993643 0.0845375 0.0490019 1 0 1 1 0 0 +EDGE2 7477 7476 -0.931641 0.0523809 0.0350699 1 0 1 1 0 0 +EDGE2 7477 7397 -0.0307311 0.0319805 0.0385912 1 0 1 1 0 0 +EDGE2 7477 7396 -0.971751 -0.0344756 0.00381128 1 0 1 1 0 0 +EDGE2 7478 7398 0.0202891 0.00100349 0.0414789 1 0 1 1 0 0 +EDGE2 7478 7399 1.02009 -0.0297906 0.00899015 1 0 1 1 0 0 +EDGE2 7478 7397 -0.961953 -0.0322701 -0.0241832 1 0 1 1 0 0 +EDGE2 7478 7477 -0.961082 -0.0771178 -0.0102098 1 0 1 1 0 0 +EDGE2 7479 7398 -0.968617 0.0621051 -0.00891432 1 0 1 1 0 0 +EDGE2 7479 7399 -0.0475688 0.0497637 0.000399489 1 0 1 1 0 0 +EDGE2 7479 7400 1.02447 0.0192241 0.0075364 1 0 1 1 0 0 +EDGE2 7479 7478 -0.950832 -0.12189 -0.0123148 1 0 1 1 0 0 +EDGE2 7480 7399 -0.989007 -0.0412495 0.0147024 1 0 1 1 0 0 +EDGE2 7480 7479 -0.986577 0.0429507 0.0104761 1 0 1 1 0 0 +EDGE2 7480 7400 -0.035906 0.0220304 0.00990777 1 0 1 1 0 0 +EDGE2 7480 7401 0.0867966 1.01655 1.55654 1 0 1 1 0 0 +EDGE2 7481 7480 -1.00752 -0.0160873 1.59545 1 0 1 1 0 0 +EDGE2 7481 7400 -1.03408 0.108723 1.53544 1 0 1 1 0 0 +EDGE2 7482 7481 -1.03849 -0.0946011 -0.0345964 1 0 1 1 0 0 +EDGE2 7483 7482 -0.950334 -0.00567495 0.00448987 1 0 1 1 0 0 +EDGE2 7484 7483 -0.957905 0.0163563 0.000951694 1 0 1 1 0 0 +EDGE2 7485 7484 -0.994488 0.0569463 -0.00638143 1 0 1 1 0 0 +EDGE2 7486 7485 -1.02642 -0.0867701 -1.56679 1 0 1 1 0 0 +EDGE2 7487 7486 -1.06919 -0.0582844 -0.0306085 1 0 1 1 0 0 +EDGE2 7488 7487 -0.941999 0.0150404 -0.0107826 1 0 1 1 0 0 +EDGE2 7489 7488 -0.992502 0.0204833 -0.0360616 1 0 1 1 0 0 +EDGE2 7490 7489 -0.978241 -0.00231465 -0.0286815 1 0 1 1 0 0 +EDGE2 7491 7490 -1.00664 -0.0351887 -1.5427 1 0 1 1 0 0 +EDGE2 7492 7491 -1.0056 -0.101319 0.0226446 1 0 1 1 0 0 +EDGE2 7493 7492 -1.01452 -0.00728301 0.0204567 1 0 1 1 0 0 +EDGE2 7494 7493 -0.961737 -0.0592969 -0.0176537 1 0 1 1 0 0 +EDGE2 7495 7494 -1.01988 0.0972053 -0.0117443 1 0 1 1 0 0 +EDGE2 7496 7495 -1.01743 0.0691294 -1.5962 1 0 1 1 0 0 +EDGE2 7497 7496 -1.09216 0.0471523 0.00444813 1 0 1 1 0 0 +EDGE2 7498 7497 -0.984911 -0.025936 0.00769833 1 0 1 1 0 0 +EDGE2 7499 7498 -1.09348 0.028005 -0.019144 1 0 1 1 0 0 +EDGE2 7499 7480 0.888145 0.0459484 -3.12544 1 0 1 1 0 0 +EDGE2 7499 7400 1.00731 -0.0454239 -3.13397 1 0 1 1 0 0 +EDGE2 7500 7499 -0.992034 -0.0164651 0.0406901 1 0 1 1 0 0 +EDGE2 7500 7481 -0.0925081 0.910227 1.59092 1 0 1 1 0 0 +EDGE2 7500 7480 -0.0526267 0.0613021 -3.1166 1 0 1 1 0 0 +EDGE2 7500 7399 1.00907 -0.0362161 -3.12165 1 0 1 1 0 0 +EDGE2 7500 7479 0.986986 -0.0267 -3.14858 1 0 1 1 0 0 +EDGE2 7500 7400 -0.0131441 0.0707499 -3.13617 1 0 1 1 0 0 +EDGE2 7500 7401 0.0585679 -1.01458 -1.59155 1 0 1 1 0 0 +EDGE2 7501 7500 -0.92391 -0.0349436 1.5539 1 0 1 1 0 0 +EDGE2 7501 7480 -0.99403 -0.0816586 -1.53233 1 0 1 1 0 0 +EDGE2 7501 7400 -0.99526 -0.00201295 -1.56593 1 0 1 1 0 0 +EDGE2 7501 7402 1.00537 0.0191708 0.00254712 1 0 1 1 0 0 +EDGE2 7501 7401 -0.0158173 0.0495104 -0.010355 1 0 1 1 0 0 +EDGE2 7502 7402 -0.0259221 0.0122315 -0.0211161 1 0 1 1 0 0 +EDGE2 7502 7401 -0.995505 0.0120555 0.00199435 1 0 1 1 0 0 +EDGE2 7502 7501 -1.02867 0.0129018 0.0011452 1 0 1 1 0 0 +EDGE2 7502 7403 0.97946 -0.0114744 0.00237922 1 0 1 1 0 0 +EDGE2 7503 7402 -0.95037 -0.0821666 -0.0316804 1 0 1 1 0 0 +EDGE2 7503 7502 -0.944255 0.033699 0.0337335 1 0 1 1 0 0 +EDGE2 7503 7403 -0.00508676 -0.042032 -0.0202973 1 0 1 1 0 0 +EDGE2 7503 7404 0.986256 -0.0204832 -0.0243136 1 0 1 1 0 0 +EDGE2 7504 7445 1.01346 0.00879294 -3.14335 1 0 1 1 0 0 +EDGE2 7504 7403 -0.969179 -0.0186424 0.000356951 1 0 1 1 0 0 +EDGE2 7504 7503 -1.04018 0.0167378 0.00747468 1 0 1 1 0 0 +EDGE2 7504 7404 0.0488559 0.0293897 0.00937557 1 0 1 1 0 0 +EDGE2 7504 7145 0.931586 0.0458079 -3.10576 1 0 1 1 0 0 +EDGE2 7504 7165 0.969415 -0.00920746 -3.16044 1 0 1 1 0 0 +EDGE2 7504 7405 0.975849 -0.0473039 0.0331237 1 0 1 1 0 0 +EDGE2 7505 7445 -0.0388957 -0.0157358 -3.1296 1 0 1 1 0 0 +EDGE2 7505 7504 -0.987952 0.0367501 0.0452985 1 0 1 1 0 0 +EDGE2 7505 7404 -1.00314 -0.0449715 0.00819838 1 0 1 1 0 0 +EDGE2 7505 7146 0.0327377 -0.969918 -1.57624 1 0 1 1 0 0 +EDGE2 7505 7406 -0.00438048 -0.996235 -1.57377 1 0 1 1 0 0 +EDGE2 7505 7446 -0.0356612 1.09049 1.59962 1 0 1 1 0 0 +EDGE2 7505 7145 0.0120665 -0.051472 -3.16494 1 0 1 1 0 0 +EDGE2 7505 7165 0.0663644 0.0693997 -3.11473 1 0 1 1 0 0 +EDGE2 7505 7405 -0.0344019 0.00387243 0.0203436 1 0 1 1 0 0 +EDGE2 7505 7166 0.0233504 1.01205 1.60773 1 0 1 1 0 0 +EDGE2 7505 7144 0.963078 0.00568695 -3.15284 1 0 1 1 0 0 +EDGE2 7505 7164 1.00145 0.00876694 -3.14519 1 0 1 1 0 0 +EDGE2 7505 7444 0.872334 -0.0138701 -3.13541 1 0 1 1 0 0 +EDGE2 7506 7445 -1.0255 0.0871399 1.5783 1 0 1 1 0 0 +EDGE2 7506 7505 -1.00742 -0.006013 -1.59303 1 0 1 1 0 0 +EDGE2 7506 7446 -0.0436181 -0.0306831 -0.0103852 1 0 1 1 0 0 +EDGE2 7506 7145 -0.949027 -0.0717467 1.56592 1 0 1 1 0 0 +EDGE2 7506 7165 -0.982799 0.0158358 1.53385 1 0 1 1 0 0 +EDGE2 7506 7405 -0.972288 -0.0107573 -1.55346 1 0 1 1 0 0 +EDGE2 7506 7166 -0.055493 0.051171 0.0346747 1 0 1 1 0 0 +EDGE2 7506 7167 1.06693 0.0537062 0.0193024 1 0 1 1 0 0 +EDGE2 7506 7447 1.02895 -0.0269556 -0.0209448 1 0 1 1 0 0 +EDGE2 7507 7446 -1.02586 -0.0434247 0.00208351 1 0 1 1 0 0 +EDGE2 7507 7506 -0.95342 0.0419936 0.0311192 1 0 1 1 0 0 +EDGE2 7507 7166 -0.998211 0.0273174 0.00865536 1 0 1 1 0 0 +EDGE2 7507 7168 0.951148 -0.0337716 0.00426068 1 0 1 1 0 0 +EDGE2 7507 7167 -0.0900185 -0.0409052 -0.000355587 1 0 1 1 0 0 +EDGE2 7507 7447 -0.0147489 -0.0693304 -0.00974085 1 0 1 1 0 0 +EDGE2 7507 7448 0.983321 0.00174528 -0.00415529 1 0 1 1 0 0 +EDGE2 7508 7507 -0.956659 0.051613 0.0244712 1 0 1 1 0 0 +EDGE2 7508 7168 0.0254952 0.0550575 -0.0142784 1 0 1 1 0 0 +EDGE2 7508 7167 -0.955202 -0.0399902 0.0220127 1 0 1 1 0 0 +EDGE2 7508 7447 -1.00551 -0.0146312 0.000520934 1 0 1 1 0 0 +EDGE2 7508 7448 -0.0174297 0.0617579 0.0216993 1 0 1 1 0 0 +EDGE2 7508 7449 0.978296 0.0115243 0.0207949 1 0 1 1 0 0 +EDGE2 7508 7169 1.06345 0.00844552 -0.0130593 1 0 1 1 0 0 +EDGE2 7509 7168 -0.991519 0.0448214 0.0263783 1 0 1 1 0 0 +EDGE2 7509 7508 -1.03776 -0.072817 -0.00836656 1 0 1 1 0 0 +EDGE2 7509 7448 -0.989641 -0.0260582 -0.0146577 1 0 1 1 0 0 +EDGE2 7509 7449 0.0262164 0.0515858 0.0294117 1 0 1 1 0 0 +EDGE2 7509 7169 -0.0195795 -0.0111182 0.018681 1 0 1 1 0 0 +EDGE2 7509 7310 1.01905 0.0371216 -3.13666 1 0 1 1 0 0 +EDGE2 7509 7350 0.994946 -0.111709 -3.13647 1 0 1 1 0 0 +EDGE2 7509 7450 0.961573 -0.0115245 -0.0407687 1 0 1 1 0 0 +EDGE2 7509 7330 1.03696 -0.00757731 -3.15118 1 0 1 1 0 0 +EDGE2 7509 7170 1.04745 -0.0424867 0.0142472 1 0 1 1 0 0 +EDGE2 7509 7290 1.0505 -0.0254909 -3.16532 1 0 1 1 0 0 +EDGE2 7510 7449 -0.93656 -0.113489 0.0391749 1 0 1 1 0 0 +EDGE2 7510 7509 -0.990957 -0.0269642 0.00583412 1 0 1 1 0 0 +EDGE2 7510 7169 -0.961843 -0.0133568 -0.00670547 1 0 1 1 0 0 +EDGE2 7510 7451 -0.0286041 0.968973 1.57808 1 0 1 1 0 0 +EDGE2 7510 7310 -0.0238157 0.0747547 -3.13844 1 0 1 1 0 0 +EDGE2 7510 7350 -0.0143485 0.0738663 -3.17111 1 0 1 1 0 0 +EDGE2 7510 7450 -0.0276213 -0.11177 -0.0148553 1 0 1 1 0 0 +EDGE2 7510 7330 -0.0253135 -0.00962008 -3.1594 1 0 1 1 0 0 +EDGE2 7510 7170 0.0588121 0.0589987 -0.0200544 1 0 1 1 0 0 +EDGE2 7510 7290 -0.0133133 -0.00436642 -3.16925 1 0 1 1 0 0 +EDGE2 7510 7329 1.0605 -0.00181682 -3.14285 1 0 1 1 0 0 +EDGE2 7510 7349 1.02196 0.0139533 -3.14649 1 0 1 1 0 0 +EDGE2 7510 7289 1.00466 0.0307892 -3.14199 1 0 1 1 0 0 +EDGE2 7510 7309 0.966447 -0.00987421 -3.09937 1 0 1 1 0 0 +EDGE2 7510 7291 0.0505494 -0.985363 -1.56088 1 0 1 1 0 0 +EDGE2 7510 7331 -0.0623827 -1.02524 -1.61056 1 0 1 1 0 0 +EDGE2 7510 7351 -0.0107456 -1.08177 -1.58015 1 0 1 1 0 0 +EDGE2 7510 7311 -0.112689 -1.00542 -1.53033 1 0 1 1 0 0 +EDGE2 7510 7171 0.0138536 -0.939999 -1.55774 1 0 1 1 0 0 +EDGE2 7511 7452 1.06151 -0.0184284 0.0264356 1 0 1 1 0 0 +EDGE2 7511 7451 -0.0535045 -0.0666057 -0.0204022 1 0 1 1 0 0 +EDGE2 7511 7310 -0.971611 -0.0121371 1.5837 1 0 1 1 0 0 +EDGE2 7511 7350 -0.919885 -0.00538666 1.56213 1 0 1 1 0 0 +EDGE2 7511 7450 -0.878372 0.0159173 -1.51493 1 0 1 1 0 0 +EDGE2 7511 7510 -0.881668 -0.0248215 -1.57128 1 0 1 1 0 0 +EDGE2 7511 7330 -1.00642 0.148144 1.58183 1 0 1 1 0 0 +EDGE2 7511 7170 -0.988214 -0.0243061 -1.5717 1 0 1 1 0 0 +EDGE2 7511 7290 -0.980837 -0.052738 1.55633 1 0 1 1 0 0 +EDGE2 7512 7453 0.952374 0.0859917 -0.0323092 1 0 1 1 0 0 +EDGE2 7512 7511 -0.971246 0.0514573 0.00565273 1 0 1 1 0 0 +EDGE2 7512 7452 0.0422901 0.0425713 -0.020051 1 0 1 1 0 0 +EDGE2 7512 7451 -1.02953 0.0608414 0.0108199 1 0 1 1 0 0 +EDGE2 7513 7512 -1.01445 -0.0432412 0.0023343 1 0 1 1 0 0 +EDGE2 7513 7454 0.933146 -0.0336292 0.00575684 1 0 1 1 0 0 +EDGE2 7513 7453 0.0592127 0.0163712 -0.00712681 1 0 1 1 0 0 +EDGE2 7513 7452 -0.928791 0.019553 -0.0340241 1 0 1 1 0 0 +EDGE2 7514 7455 0.978721 0.0134438 -0.0260029 1 0 1 1 0 0 +EDGE2 7514 7475 0.90039 0.0628391 -3.1627 1 0 1 1 0 0 +EDGE2 7514 7395 0.994016 -0.0072506 -3.14124 1 0 1 1 0 0 +EDGE2 7514 7513 -0.943708 0.0469866 0.00585935 1 0 1 1 0 0 +EDGE2 7514 7454 -0.0136342 0.00991731 0.00721725 1 0 1 1 0 0 +EDGE2 7514 7453 -0.992864 0.048709 0.0138742 1 0 1 1 0 0 +EDGE2 7515 7476 -0.0265096 0.975769 1.57812 1 0 1 1 0 0 +EDGE2 7515 7396 0.0758858 0.945507 1.57522 1 0 1 1 0 0 +EDGE2 7515 7394 1.06955 -0.0184934 -3.1481 1 0 1 1 0 0 +EDGE2 7515 7474 1.01932 0.0427979 -3.13982 1 0 1 1 0 0 +EDGE2 7515 7455 0.031972 -0.00349462 -0.000126587 1 0 1 1 0 0 +EDGE2 7515 7475 -0.0234919 0.00520804 -3.1419 1 0 1 1 0 0 +EDGE2 7515 7395 0.0306861 0.0296467 -3.12026 1 0 1 1 0 0 +EDGE2 7515 7456 -0.0485369 -1.02465 -1.55417 1 0 1 1 0 0 +EDGE2 7515 7514 -0.926324 0.0508372 -0.0417517 1 0 1 1 0 0 +EDGE2 7515 7454 -0.947556 0.0244947 0.025917 1 0 1 1 0 0 +EDGE2 7516 7455 -1.01647 -0.0785223 1.59891 1 0 1 1 0 0 +EDGE2 7516 7475 -0.98224 -0.0534717 -1.54962 1 0 1 1 0 0 +EDGE2 7516 7515 -0.979376 -0.0263597 1.59187 1 0 1 1 0 0 +EDGE2 7516 7395 -1.08134 -0.0225746 -1.60372 1 0 1 1 0 0 +EDGE2 7516 7456 -0.0338075 -0.0614552 0.00124579 1 0 1 1 0 0 +EDGE2 7516 7457 0.971947 0.0763262 0.0140424 1 0 1 1 0 0 +EDGE2 7517 7516 -0.99237 0.0134622 0.00232874 1 0 1 1 0 0 +EDGE2 7517 7456 -1.04231 -0.00808362 0.011447 1 0 1 1 0 0 +EDGE2 7517 7457 0.00873099 -0.0545762 0.0257896 1 0 1 1 0 0 +EDGE2 7517 7458 1.05027 -0.0558424 0.0133974 1 0 1 1 0 0 +EDGE2 7518 7517 -0.988587 0.0604829 -0.0182364 1 0 1 1 0 0 +EDGE2 7518 7457 -0.93719 -0.0156585 0.0341771 1 0 1 1 0 0 +EDGE2 7518 7458 -0.0330132 0.0552932 0.00446106 1 0 1 1 0 0 +EDGE2 7518 7459 1.06748 -0.0340094 0.023228 1 0 1 1 0 0 +EDGE2 7519 7458 -1.03953 -0.0472802 -0.00612641 1 0 1 1 0 0 +EDGE2 7519 7518 -0.9332 -0.0747384 0.00527888 1 0 1 1 0 0 +EDGE2 7519 7459 -0.0317088 -0.0108 -0.00601067 1 0 1 1 0 0 +EDGE2 7519 7380 0.971562 0.0935714 -3.12689 1 0 1 1 0 0 +EDGE2 7519 7460 0.939712 -0.0421886 0.0226109 1 0 1 1 0 0 +EDGE2 7520 7459 -1.05701 0.0734269 -0.0046076 1 0 1 1 0 0 +EDGE2 7520 7519 -0.931292 -0.0623992 -0.015994 1 0 1 1 0 0 +EDGE2 7520 7381 0.043431 1.08111 1.52816 1 0 1 1 0 0 +EDGE2 7520 7461 -0.0281861 0.973682 1.58945 1 0 1 1 0 0 +EDGE2 7520 7380 0.0223979 -0.0381856 -3.11009 1 0 1 1 0 0 +EDGE2 7520 7460 0.0210724 0.0276414 -0.0331039 1 0 1 1 0 0 +EDGE2 7520 7379 1.07004 0.0498515 -3.11687 1 0 1 1 0 0 +EDGE2 7521 7520 -1.01395 -0.00462724 1.57486 1 0 1 1 0 0 +EDGE2 7521 7380 -0.896126 0.0100728 -1.61178 1 0 1 1 0 0 +EDGE2 7521 7460 -1.00074 -0.0180664 1.55856 1 0 1 1 0 0 +EDGE2 7522 7521 -0.986785 0.0304751 -0.00360129 1 0 1 1 0 0 +EDGE2 7523 7522 -1.14276 0.0193496 0.00974776 1 0 1 1 0 0 +EDGE2 7524 7523 -0.918127 -0.0428916 -0.0161206 1 0 1 1 0 0 +EDGE2 7524 7285 1.00219 0.00735451 -3.1339 1 0 1 1 0 0 +EDGE2 7524 7325 0.98191 0.0118974 -3.14391 1 0 1 1 0 0 +EDGE2 7524 7345 1.02212 0.0657386 -3.1224 1 0 1 1 0 0 +EDGE2 7524 7365 1.03944 -0.0788038 -3.12079 1 0 1 1 0 0 +EDGE2 7524 7305 0.948129 0.0299217 -3.1401 1 0 1 1 0 0 +EDGE2 7524 7185 0.881981 -0.0111134 -3.15317 1 0 1 1 0 0 +EDGE2 7525 7326 -0.00224048 -1.04456 -1.55778 1 0 1 1 0 0 +EDGE2 7525 7346 0.0143432 -1.036 -1.56354 1 0 1 1 0 0 +EDGE2 7525 7286 -0.00368185 -0.939245 -1.58894 1 0 1 1 0 0 +EDGE2 7525 7306 0.0642671 -0.97257 -1.51417 1 0 1 1 0 0 +EDGE2 7525 7524 -0.998689 -0.00420738 0.00567713 1 0 1 1 0 0 +EDGE2 7525 7285 0.0958542 -0.00982548 -3.12817 1 0 1 1 0 0 +EDGE2 7525 7325 -0.0556585 0.0592284 -3.11102 1 0 1 1 0 0 +EDGE2 7525 7345 -0.0291952 -0.0522557 -3.14827 1 0 1 1 0 0 +EDGE2 7525 7365 0.0162307 -0.0377949 -3.1227 1 0 1 1 0 0 +EDGE2 7525 7305 0.103623 -0.0222759 -3.15322 1 0 1 1 0 0 +EDGE2 7525 7366 0.0479685 0.957195 1.54963 1 0 1 1 0 0 +EDGE2 7525 7185 0.00438547 0.0718195 -3.13821 1 0 1 1 0 0 +EDGE2 7525 7186 0.0315647 0.979586 1.58703 1 0 1 1 0 0 +EDGE2 7525 7304 0.976106 0.00559103 -3.13377 1 0 1 1 0 0 +EDGE2 7525 7344 1.00326 -0.0219122 -3.14266 1 0 1 1 0 0 +EDGE2 7525 7364 0.926802 -0.0936412 -3.17359 1 0 1 1 0 0 +EDGE2 7525 7324 1.01914 0.0571174 -3.13821 1 0 1 1 0 0 +EDGE2 7525 7184 1.05488 0.0783584 -3.13546 1 0 1 1 0 0 +EDGE2 7525 7284 1.03802 0.133023 -3.137 1 0 1 1 0 0 +EDGE2 7526 7326 0.0880386 0.00393889 0.00682829 1 0 1 1 0 0 +EDGE2 7526 7307 1.05663 0.0473242 -0.0496966 1 0 1 1 0 0 +EDGE2 7526 7327 1.06832 0.136772 0.0170952 1 0 1 1 0 0 +EDGE2 7526 7347 1.03641 0.0536129 -0.00474478 1 0 1 1 0 0 +EDGE2 7526 7287 0.926506 -0.00547919 -0.0340863 1 0 1 1 0 0 +EDGE2 7526 7346 -0.000910386 -0.0122248 0.00846389 1 0 1 1 0 0 +EDGE2 7526 7286 0.0179162 0.0579766 0.00653499 1 0 1 1 0 0 +EDGE2 7526 7306 0.045188 -0.0382234 0.0083242 1 0 1 1 0 0 +EDGE2 7526 7525 -0.994961 -0.0560913 1.53228 1 0 1 1 0 0 +EDGE2 7526 7285 -0.948069 -0.00795642 -1.57218 1 0 1 1 0 0 +EDGE2 7526 7325 -0.939998 -0.0998412 -1.61692 1 0 1 1 0 0 +EDGE2 7526 7345 -0.985671 0.00677871 -1.59024 1 0 1 1 0 0 +EDGE2 7526 7365 -1.03602 -0.00547154 -1.5689 1 0 1 1 0 0 +EDGE2 7526 7305 -0.994015 0.0247924 -1.56365 1 0 1 1 0 0 +EDGE2 7526 7185 -0.972421 0.0632478 -1.5437 1 0 1 1 0 0 +EDGE2 7527 7326 -1.03771 -0.0401413 0.00322834 1 0 1 1 0 0 +EDGE2 7527 7308 0.988806 0.068938 -0.00563363 1 0 1 1 0 0 +EDGE2 7527 7348 1.0926 -0.0250385 -0.0139457 1 0 1 1 0 0 +EDGE2 7527 7328 0.960546 -0.0226587 0.0138995 1 0 1 1 0 0 +EDGE2 7527 7288 1.00176 -0.0201612 0.0225778 1 0 1 1 0 0 +EDGE2 7527 7307 -0.0375463 0.0321874 0.0221125 1 0 1 1 0 0 +EDGE2 7527 7327 -0.0253263 -0.0198735 0.0148754 1 0 1 1 0 0 +EDGE2 7527 7347 -0.0132872 0.0632888 0.00714094 1 0 1 1 0 0 +EDGE2 7527 7287 -0.0331798 0.0496906 0.0152938 1 0 1 1 0 0 +EDGE2 7527 7526 -1.04055 0.0629669 -0.0135346 1 0 1 1 0 0 +EDGE2 7527 7346 -0.993645 0.0164959 0.0256713 1 0 1 1 0 0 +EDGE2 7527 7286 -1.00402 0.0205522 -0.00488914 1 0 1 1 0 0 +EDGE2 7527 7306 -1.02471 -0.0256046 -0.0275561 1 0 1 1 0 0 +EDGE2 7528 7329 0.996602 0.00366603 0.00231994 1 0 1 1 0 0 +EDGE2 7528 7349 0.966885 0.0687393 0.000554028 1 0 1 1 0 0 +EDGE2 7528 7289 0.954981 0.0458477 -0.0131978 1 0 1 1 0 0 +EDGE2 7528 7309 0.909459 -0.0440378 -0.00147829 1 0 1 1 0 0 +EDGE2 7528 7527 -1.01477 0.0132542 0.000516446 1 0 1 1 0 0 +EDGE2 7528 7308 -0.0909658 -0.0295186 -0.00192113 1 0 1 1 0 0 +EDGE2 7528 7348 0.145511 -0.0526553 -0.00487056 1 0 1 1 0 0 +EDGE2 7528 7328 -0.0711012 0.0527255 -0.00632991 1 0 1 1 0 0 +EDGE2 7528 7288 0.0906228 0.0581758 0.025706 1 0 1 1 0 0 +EDGE2 7528 7307 -1.03289 0.0200045 0.0275358 1 0 1 1 0 0 +EDGE2 7528 7327 -1.00432 -0.0627746 0.0122488 1 0 1 1 0 0 +EDGE2 7528 7347 -0.98629 0.00842132 -0.0269798 1 0 1 1 0 0 +EDGE2 7528 7287 -1.12534 0.0925738 -0.0121875 1 0 1 1 0 0 +EDGE2 7529 7310 1.05847 0.0425121 -0.000283454 1 0 1 1 0 0 +EDGE2 7529 7350 1.00254 0.0210185 0.00653459 1 0 1 1 0 0 +EDGE2 7529 7450 0.948486 -0.0391122 -3.14751 1 0 1 1 0 0 +EDGE2 7529 7510 1.04411 0.020219 -3.1503 1 0 1 1 0 0 +EDGE2 7529 7330 0.985175 0.00296562 -0.0154184 1 0 1 1 0 0 +EDGE2 7529 7170 0.989863 0.0269121 -3.12964 1 0 1 1 0 0 +EDGE2 7529 7290 1.05763 -0.0015695 0.00291121 1 0 1 1 0 0 +EDGE2 7529 7329 0.0478069 -0.0568585 -0.00577229 1 0 1 1 0 0 +EDGE2 7529 7349 -0.00604862 0.0284556 -0.00831967 1 0 1 1 0 0 +EDGE2 7529 7289 0.00591457 0.00779623 -0.00240152 1 0 1 1 0 0 +EDGE2 7529 7309 0.0497912 -0.0310739 0.0162368 1 0 1 1 0 0 +EDGE2 7529 7308 -1.0013 -0.0288492 0.0135176 1 0 1 1 0 0 +EDGE2 7529 7348 -0.938551 -0.0400112 -0.0116668 1 0 1 1 0 0 +EDGE2 7529 7528 -0.930683 0.045537 0.00374512 1 0 1 1 0 0 +EDGE2 7529 7328 -0.963692 -0.043851 -0.0245965 1 0 1 1 0 0 +EDGE2 7529 7288 -1.02117 0.0479365 -0.0282741 1 0 1 1 0 0 +EDGE2 7530 7449 0.926847 0.0361105 -3.13961 1 0 1 1 0 0 +EDGE2 7530 7509 1.07307 -0.0208055 -3.14269 1 0 1 1 0 0 +EDGE2 7530 7169 1.02979 -0.0214056 -3.10308 1 0 1 1 0 0 +EDGE2 7530 7511 0.0921941 -1.0081 -1.59392 1 0 1 1 0 0 +EDGE2 7530 7451 0.051991 -0.981818 -1.58134 1 0 1 1 0 0 +EDGE2 7530 7310 -0.0130148 0.00560438 -0.0091501 1 0 1 1 0 0 +EDGE2 7530 7350 -0.103028 -0.0425104 0.0174715 1 0 1 1 0 0 +EDGE2 7530 7450 -0.0362129 0.0190036 -3.14884 1 0 1 1 0 0 +EDGE2 7530 7510 0.0215275 0.0842346 -3.13713 1 0 1 1 0 0 +EDGE2 7530 7330 -0.00103504 0.0204421 0.0526532 1 0 1 1 0 0 +EDGE2 7530 7170 -0.0931613 -0.0328105 -3.12857 1 0 1 1 0 0 +EDGE2 7530 7290 -0.057429 0.00745822 0.0284524 1 0 1 1 0 0 +EDGE2 7530 7329 -0.943633 0.0232586 -0.0394014 1 0 1 1 0 0 +EDGE2 7530 7529 -1.05891 -0.0127056 -0.00407667 1 0 1 1 0 0 +EDGE2 7530 7349 -0.973731 -0.0238916 -0.00304013 1 0 1 1 0 0 +EDGE2 7530 7289 -1.03886 -0.0350367 0.0328565 1 0 1 1 0 0 +EDGE2 7530 7309 -0.989927 -0.111798 0.0144922 1 0 1 1 0 0 +EDGE2 7530 7291 -0.0211893 0.99469 1.57265 1 0 1 1 0 0 +EDGE2 7530 7331 -0.0489715 0.945088 1.57882 1 0 1 1 0 0 +EDGE2 7530 7351 0.00538673 1.04765 1.57824 1 0 1 1 0 0 +EDGE2 7530 7311 -0.0556848 0.947373 1.54004 1 0 1 1 0 0 +EDGE2 7530 7171 -0.0317799 0.93301 1.57236 1 0 1 1 0 0 +EDGE2 7531 7530 -1.10633 0.0405008 1.55832 1 0 1 1 0 0 +EDGE2 7531 7512 0.987158 0.0107816 0.00668034 1 0 1 1 0 0 +EDGE2 7531 7511 0.0566333 -0.0242658 -0.0154429 1 0 1 1 0 0 +EDGE2 7531 7452 0.977234 0.0418672 -0.00537546 1 0 1 1 0 0 +EDGE2 7531 7451 0.0108552 -0.0173075 -0.00247681 1 0 1 1 0 0 +EDGE2 7531 7310 -0.964967 -0.0191919 1.56521 1 0 1 1 0 0 +EDGE2 7531 7350 -1.01441 0.0802902 1.57567 1 0 1 1 0 0 +EDGE2 7531 7450 -1.0622 -0.00449229 -1.58163 1 0 1 1 0 0 +EDGE2 7531 7510 -0.97983 -0.0617341 -1.57719 1 0 1 1 0 0 +EDGE2 7531 7330 -1.02691 0.042254 1.5657 1 0 1 1 0 0 +EDGE2 7531 7170 -0.997668 -0.00535552 -1.60888 1 0 1 1 0 0 +EDGE2 7531 7290 -0.904001 -0.0243027 1.56543 1 0 1 1 0 0 +EDGE2 7532 7512 0.0153778 -0.0107614 0.00292912 1 0 1 1 0 0 +EDGE2 7532 7513 1.0309 0.0401574 0.0262606 1 0 1 1 0 0 +EDGE2 7532 7453 0.932833 -0.00522989 -0.00790505 1 0 1 1 0 0 +EDGE2 7532 7511 -0.96626 -0.00707997 0.0260076 1 0 1 1 0 0 +EDGE2 7532 7452 0.0112429 -0.0108293 -0.0104558 1 0 1 1 0 0 +EDGE2 7532 7531 -1.04675 0.0726516 0.000490324 1 0 1 1 0 0 +EDGE2 7532 7451 -0.884988 0.0772615 0.00596012 1 0 1 1 0 0 +EDGE2 7533 7514 0.955369 -0.0234291 0.000361965 1 0 1 1 0 0 +EDGE2 7533 7512 -0.929244 -0.0109896 0.0165982 1 0 1 1 0 0 +EDGE2 7533 7513 0.0170219 0.00404703 0.002768 1 0 1 1 0 0 +EDGE2 7533 7454 0.957025 -0.0844574 -0.00618406 1 0 1 1 0 0 +EDGE2 7533 7453 -0.0550629 -0.0197615 -0.029387 1 0 1 1 0 0 +EDGE2 7533 7532 -0.94819 -0.0763883 0.0295898 1 0 1 1 0 0 +EDGE2 7533 7452 -1.05486 0.0470772 0.00570041 1 0 1 1 0 0 +EDGE2 7534 7455 0.989424 -0.0388033 -0.0042629 1 0 1 1 0 0 +EDGE2 7534 7475 1.03211 -0.110929 -3.11039 1 0 1 1 0 0 +EDGE2 7534 7515 1.01936 7.87221e-05 -0.00607792 1 0 1 1 0 0 +EDGE2 7534 7395 1.0462 0.0503453 -3.12681 1 0 1 1 0 0 +EDGE2 7534 7514 0.000356844 0.0160199 0.0251896 1 0 1 1 0 0 +EDGE2 7534 7513 -1.00482 -0.0365471 0.0219159 1 0 1 1 0 0 +EDGE2 7534 7454 -0.000601621 0.0358651 -0.0178755 1 0 1 1 0 0 +EDGE2 7534 7533 -0.929766 -0.0200371 0.0262362 1 0 1 1 0 0 +EDGE2 7534 7453 -0.94004 -0.00092174 0.0469088 1 0 1 1 0 0 +EDGE2 7535 7476 -0.0976892 1.04041 1.55842 1 0 1 1 0 0 +EDGE2 7535 7396 -0.0940928 1.00322 1.61484 1 0 1 1 0 0 +EDGE2 7535 7394 1.06897 0.0787003 -3.15702 1 0 1 1 0 0 +EDGE2 7535 7474 1.02438 -0.0679988 -3.18094 1 0 1 1 0 0 +EDGE2 7535 7455 -0.0378985 0.0393383 -0.0130778 1 0 1 1 0 0 +EDGE2 7535 7475 0.0110767 -0.0897728 -3.14078 1 0 1 1 0 0 +EDGE2 7535 7515 0.0666646 0.0556962 0.0192866 1 0 1 1 0 0 +EDGE2 7535 7395 -0.0108874 0.094968 -3.14036 1 0 1 1 0 0 +EDGE2 7535 7516 0.00540912 -1.01222 -1.5648 1 0 1 1 0 0 +EDGE2 7535 7456 0.0728016 -1.05117 -1.57828 1 0 1 1 0 0 +EDGE2 7535 7514 -0.998512 0.0891118 0.00251809 1 0 1 1 0 0 +EDGE2 7535 7534 -1.03805 0.0707604 0.00708209 1 0 1 1 0 0 +EDGE2 7535 7454 -1.00299 0.0048631 -0.0138979 1 0 1 1 0 0 +EDGE2 7536 7535 -0.938758 0.0125085 1.57096 1 0 1 1 0 0 +EDGE2 7536 7455 -1.08662 -0.0536868 1.53725 1 0 1 1 0 0 +EDGE2 7536 7475 -0.94879 0.017465 -1.5663 1 0 1 1 0 0 +EDGE2 7536 7515 -1.0789 -0.0264715 1.57834 1 0 1 1 0 0 +EDGE2 7536 7395 -0.981172 0.0494329 -1.58005 1 0 1 1 0 0 +EDGE2 7536 7516 0.0436717 -0.0159179 0.0254776 1 0 1 1 0 0 +EDGE2 7536 7456 -0.050754 -0.0313855 -0.00580897 1 0 1 1 0 0 +EDGE2 7536 7517 0.997312 0.0516001 0.0147028 1 0 1 1 0 0 +EDGE2 7536 7457 0.959294 0.0067466 0.0140573 1 0 1 1 0 0 +EDGE2 7537 7516 -0.97033 0.00110466 0.0198659 1 0 1 1 0 0 +EDGE2 7537 7536 -0.942456 0.00332047 0.00683525 1 0 1 1 0 0 +EDGE2 7537 7456 -1.06792 0.0199003 -0.0101691 1 0 1 1 0 0 +EDGE2 7537 7517 0.050711 -0.0515519 -0.0202018 1 0 1 1 0 0 +EDGE2 7537 7457 0.0337144 0.00394251 0.0143853 1 0 1 1 0 0 +EDGE2 7537 7458 1.08333 -0.0187239 -0.00322492 1 0 1 1 0 0 +EDGE2 7537 7518 1.04333 0.0056962 -0.00904569 1 0 1 1 0 0 +EDGE2 7538 7537 -1.00526 -0.0541947 0.00516356 1 0 1 1 0 0 +EDGE2 7538 7517 -1.02076 -0.0235385 -0.0117278 1 0 1 1 0 0 +EDGE2 7538 7457 -0.993295 0.0470638 -0.0184694 1 0 1 1 0 0 +EDGE2 7538 7458 0.0224837 0.0137903 -0.0216465 1 0 1 1 0 0 +EDGE2 7538 7518 0.0367338 0.0660984 0.00131469 1 0 1 1 0 0 +EDGE2 7538 7459 0.983636 0.0264369 -0.00561561 1 0 1 1 0 0 +EDGE2 7538 7519 0.96785 0.0586821 0.0136681 1 0 1 1 0 0 +EDGE2 7539 7520 1.00523 0.0433738 0.0173702 1 0 1 1 0 0 +EDGE2 7539 7458 -1.06444 -0.0508146 -0.00565565 1 0 1 1 0 0 +EDGE2 7539 7538 -0.985089 0.0829127 -0.010893 1 0 1 1 0 0 +EDGE2 7539 7518 -1.00514 0.0209195 -0.0223043 1 0 1 1 0 0 +EDGE2 7539 7459 -0.0100294 -0.0128004 0.0053174 1 0 1 1 0 0 +EDGE2 7539 7519 -0.0459515 0.106704 -0.0233203 1 0 1 1 0 0 +EDGE2 7539 7380 0.932144 0.0155782 -3.09292 1 0 1 1 0 0 +EDGE2 7539 7460 0.952504 -0.0621438 -0.0050626 1 0 1 1 0 0 +EDGE2 7540 7520 -0.0603819 -0.0459101 0.0134051 1 0 1 1 0 0 +EDGE2 7540 7539 -1.00225 -0.0545959 0.0260224 1 0 1 1 0 0 +EDGE2 7540 7459 -1.03225 -0.00581453 -0.00712915 1 0 1 1 0 0 +EDGE2 7540 7519 -1.01137 0.0199513 0.00512559 1 0 1 1 0 0 +EDGE2 7540 7381 0.0477221 1.07842 1.55413 1 0 1 1 0 0 +EDGE2 7540 7461 0.0463606 0.942716 1.58093 1 0 1 1 0 0 +EDGE2 7540 7380 -0.0317214 0.0590612 -3.14849 1 0 1 1 0 0 +EDGE2 7540 7460 0.0303684 -0.0363591 0.0192192 1 0 1 1 0 0 +EDGE2 7540 7521 -0.0393543 -1.03636 -1.58426 1 0 1 1 0 0 +EDGE2 7540 7379 1.05052 -0.0134315 -3.14576 1 0 1 1 0 0 +EDGE2 7541 7520 -1.01671 0.0325525 -1.56426 1 0 1 1 0 0 +EDGE2 7541 7540 -1.04227 0.0399156 -1.60619 1 0 1 1 0 0 +EDGE2 7541 7382 0.979797 0.00420611 -0.00860207 1 0 1 1 0 0 +EDGE2 7541 7462 1.02308 -0.00655222 -0.00286137 1 0 1 1 0 0 +EDGE2 7541 7381 0.0387916 0.0351095 0.00491785 1 0 1 1 0 0 +EDGE2 7541 7461 -0.00580812 -0.052351 -0.0246796 1 0 1 1 0 0 +EDGE2 7541 7380 -1.01057 -0.0525706 1.58269 1 0 1 1 0 0 +EDGE2 7541 7460 -1.03082 -0.048815 -1.55527 1 0 1 1 0 0 +EDGE2 7542 7463 0.978586 -0.0305002 -0.000449039 1 0 1 1 0 0 +EDGE2 7542 7383 1.05927 0.00610992 -0.0433116 1 0 1 1 0 0 +EDGE2 7542 7382 -0.0144815 0.00691979 -0.0161778 1 0 1 1 0 0 +EDGE2 7542 7462 -0.0133057 -0.113306 0.0222945 1 0 1 1 0 0 +EDGE2 7542 7381 -0.976715 -0.0543245 0.0102063 1 0 1 1 0 0 +EDGE2 7542 7461 -0.982732 -0.0891692 -0.00440198 1 0 1 1 0 0 +EDGE2 7542 7541 -1.12299 -0.0323359 -0.00623987 1 0 1 1 0 0 +EDGE2 7543 7463 -0.0367809 -0.0627843 0.00629722 1 0 1 1 0 0 +EDGE2 7543 7464 0.981149 -0.0142469 0.0233463 1 0 1 1 0 0 +EDGE2 7543 7384 0.96836 -0.0242017 -0.0240294 1 0 1 1 0 0 +EDGE2 7543 7542 -1.01775 -0.0218361 -0.0213835 1 0 1 1 0 0 +EDGE2 7543 7383 0.0485078 0.0347956 -0.0160996 1 0 1 1 0 0 +EDGE2 7543 7382 -1.00849 -0.0632791 0.00593092 1 0 1 1 0 0 +EDGE2 7543 7462 -0.978414 0.0152962 -0.0114758 1 0 1 1 0 0 +EDGE2 7544 7463 -0.983531 -0.0649999 0.0195318 1 0 1 1 0 0 +EDGE2 7544 7465 1.07969 0.0751406 -0.0255103 1 0 1 1 0 0 +EDGE2 7544 7385 1.00251 0.0259959 0.0171164 1 0 1 1 0 0 +EDGE2 7544 7464 0.0866582 0.00656348 -0.00040222 1 0 1 1 0 0 +EDGE2 7544 7384 -0.0490457 0.065789 -0.000930316 1 0 1 1 0 0 +EDGE2 7544 7543 -0.911544 0.0443391 -0.0176232 1 0 1 1 0 0 +EDGE2 7544 7383 -1.03203 0.00667719 0.0018449 1 0 1 1 0 0 +EDGE2 7545 7466 -0.0286662 0.995041 1.62548 1 0 1 1 0 0 +EDGE2 7545 7386 0.0415255 0.911054 1.58668 1 0 1 1 0 0 +EDGE2 7545 7544 -0.983025 0.00138737 -0.0112843 1 0 1 1 0 0 +EDGE2 7545 7465 -0.0451767 0.040349 -0.00978302 1 0 1 1 0 0 +EDGE2 7545 7385 0.0205095 -0.0107534 -0.0197089 1 0 1 1 0 0 +EDGE2 7545 7464 -0.881167 0.0570981 0.00319788 1 0 1 1 0 0 +EDGE2 7545 7384 -0.928983 0.0475561 0.00482836 1 0 1 1 0 0 +EDGE2 7546 7467 0.995451 -0.00944718 0.0133258 1 0 1 1 0 0 +EDGE2 7546 7387 0.950437 -0.0258716 0.00578964 1 0 1 1 0 0 +EDGE2 7546 7466 -0.0200092 -0.0589683 0.00107113 1 0 1 1 0 0 +EDGE2 7546 7386 -0.0420755 0.0638181 -0.0168322 1 0 1 1 0 0 +EDGE2 7546 7465 -0.97828 0.0538481 -1.56723 1 0 1 1 0 0 +EDGE2 7546 7545 -1.0046 -0.13882 -1.5676 1 0 1 1 0 0 +EDGE2 7546 7385 -1.00969 0.0572464 -1.5947 1 0 1 1 0 0 +EDGE2 7547 7468 1.06037 -0.00207434 -0.0271841 1 0 1 1 0 0 +EDGE2 7547 7388 0.987866 -0.0270903 -0.0188472 1 0 1 1 0 0 +EDGE2 7547 7467 -0.0193661 -0.0612986 -0.0155096 1 0 1 1 0 0 +EDGE2 7547 7387 -0.0106079 0.0386547 0.0152323 1 0 1 1 0 0 +EDGE2 7547 7466 -0.95786 0.0427955 0.00718026 1 0 1 1 0 0 +EDGE2 7547 7546 -1.00634 -0.116262 0.0188784 1 0 1 1 0 0 +EDGE2 7547 7386 -1.05507 -0.0127067 -0.0358023 1 0 1 1 0 0 +EDGE2 7548 7389 0.986623 0.00638004 0.0326392 1 0 1 1 0 0 +EDGE2 7548 7469 1.02268 0.0664867 -0.0118941 1 0 1 1 0 0 +EDGE2 7548 7468 -0.0954885 0.0523971 -0.0148553 1 0 1 1 0 0 +EDGE2 7548 7388 0.0479126 -0.0129459 -0.0123155 1 0 1 1 0 0 +EDGE2 7548 7467 -1.02096 0.0740396 0.0168848 1 0 1 1 0 0 +EDGE2 7548 7547 -0.957832 0.0818547 -0.0223269 1 0 1 1 0 0 +EDGE2 7548 7387 -1.00149 -0.0532244 -0.0132286 1 0 1 1 0 0 +EDGE2 7549 7470 0.971969 0.013677 -0.0147917 1 0 1 1 0 0 +EDGE2 7549 7390 0.969516 0.0352989 0.00295014 1 0 1 1 0 0 +EDGE2 7549 7389 0.0551335 -0.0514971 -0.039569 1 0 1 1 0 0 +EDGE2 7549 7469 -0.00128929 -0.0474233 -0.021039 1 0 1 1 0 0 +EDGE2 7549 7468 -0.9481 -0.0014114 0.011451 1 0 1 1 0 0 +EDGE2 7549 7548 -0.963388 -0.00954504 0.00245908 1 0 1 1 0 0 +EDGE2 7549 7388 -1.06588 -0.0688972 -0.0241517 1 0 1 1 0 0 +EDGE2 7550 7470 -0.0331232 0.126647 0.00395742 1 0 1 1 0 0 +EDGE2 7550 7390 0.0207269 -0.069138 -0.00810426 1 0 1 1 0 0 +EDGE2 7550 7391 0.0711128 0.965321 1.55072 1 0 1 1 0 0 +EDGE2 7550 7471 -0.00488135 1.03391 1.58166 1 0 1 1 0 0 +EDGE2 7550 7389 -0.928761 0.0017381 -0.00723988 1 0 1 1 0 0 +EDGE2 7550 7469 -1.02592 0.0768249 0.0216419 1 0 1 1 0 0 +EDGE2 7550 7549 -1.10209 -0.0472629 0.00749526 1 0 1 1 0 0 +EDGE2 7551 7470 -1.03848 0.0159899 -1.61818 1 0 1 1 0 0 +EDGE2 7551 7550 -1.05701 -0.0129566 -1.58342 1 0 1 1 0 0 +EDGE2 7551 7390 -0.948347 -0.00459994 -1.58098 1 0 1 1 0 0 +EDGE2 7551 7391 0.035239 0.0419812 -0.00815496 1 0 1 1 0 0 +EDGE2 7551 7471 0.0525773 -0.0768354 -0.0184097 1 0 1 1 0 0 +EDGE2 7551 7392 0.95954 0.0371814 0.0171009 1 0 1 1 0 0 +EDGE2 7551 7472 0.976183 -0.0210679 -0.00884503 1 0 1 1 0 0 +EDGE2 7552 7391 -1.00767 0.0320106 0.00472879 1 0 1 1 0 0 +EDGE2 7552 7471 -1.00728 -0.0132194 0.00324335 1 0 1 1 0 0 +EDGE2 7552 7551 -0.97998 -0.00959085 0.060866 1 0 1 1 0 0 +EDGE2 7552 7473 0.994562 0.00946255 0.021266 1 0 1 1 0 0 +EDGE2 7552 7392 -0.00473298 0.0243899 -0.01019 1 0 1 1 0 0 +EDGE2 7552 7472 -0.0774774 -0.125177 0.0024759 1 0 1 1 0 0 +EDGE2 7552 7393 0.987953 -0.0244552 0.00526269 1 0 1 1 0 0 +EDGE2 7553 7552 -0.962358 0.0352813 -0.0165943 1 0 1 1 0 0 +EDGE2 7553 7394 1.00897 -0.0443755 0.0120079 1 0 1 1 0 0 +EDGE2 7553 7473 -0.00675905 -0.0507044 -0.0029251 1 0 1 1 0 0 +EDGE2 7553 7392 -1.07424 -0.0138141 0.00531169 1 0 1 1 0 0 +EDGE2 7553 7472 -1.01339 0.0272337 -0.0132342 1 0 1 1 0 0 +EDGE2 7553 7393 0.0726515 0.070066 0.00103608 1 0 1 1 0 0 +EDGE2 7553 7474 0.947437 -0.0294014 0.0227385 1 0 1 1 0 0 +EDGE2 7554 7394 0.00278699 -0.0519648 0.00839229 1 0 1 1 0 0 +EDGE2 7554 7473 -1.06939 0.113693 -0.000521094 1 0 1 1 0 0 +EDGE2 7554 7553 -0.938854 -0.00469219 -0.00811776 1 0 1 1 0 0 +EDGE2 7554 7393 -0.902607 -0.0865505 -0.0352358 1 0 1 1 0 0 +EDGE2 7554 7474 -0.0647404 -0.00566872 0.0263989 1 0 1 1 0 0 +EDGE2 7554 7535 0.995128 0.00841284 -3.12953 1 0 1 1 0 0 +EDGE2 7554 7455 0.97132 -0.0163659 -3.18307 1 0 1 1 0 0 +EDGE2 7554 7475 1.05895 0.0512306 -0.00767867 1 0 1 1 0 0 +EDGE2 7554 7515 0.957605 0.105115 -3.13975 1 0 1 1 0 0 +EDGE2 7554 7395 1.05289 -0.0205677 0.0259092 1 0 1 1 0 0 +EDGE2 7555 7476 -0.0469674 -1.0929 -1.56561 1 0 1 1 0 0 +EDGE2 7555 7396 0.0515554 -1.00174 -1.59629 1 0 1 1 0 0 +EDGE2 7555 7394 -0.94423 0.0312175 -0.014954 1 0 1 1 0 0 +EDGE2 7555 7554 -0.94944 0.0380694 -0.0179061 1 0 1 1 0 0 +EDGE2 7555 7474 -0.942999 -0.0567402 -0.00409055 1 0 1 1 0 0 +EDGE2 7555 7535 0.0645165 0.00350791 -3.16074 1 0 1 1 0 0 +EDGE2 7555 7455 0.0963503 0.010091 -3.15064 1 0 1 1 0 0 +EDGE2 7555 7475 0.0164755 0.0515849 -0.0123746 1 0 1 1 0 0 +EDGE2 7555 7515 -0.0315621 -0.0208294 -3.13582 1 0 1 1 0 0 +EDGE2 7555 7395 -0.0291743 0.0540753 -0.0139349 1 0 1 1 0 0 +EDGE2 7555 7516 -0.0537535 1.00872 1.53756 1 0 1 1 0 0 +EDGE2 7555 7536 -0.0101414 0.969928 1.57132 1 0 1 1 0 0 +EDGE2 7555 7456 -0.0554497 1.02495 1.5593 1 0 1 1 0 0 +EDGE2 7555 7514 0.993301 0.0166824 -3.14241 1 0 1 1 0 0 +EDGE2 7555 7534 0.973903 0.00667301 -3.1638 1 0 1 1 0 0 +EDGE2 7555 7454 0.997322 -0.00985812 -3.10652 1 0 1 1 0 0 +EDGE2 7556 7537 0.980707 -0.0252271 0.0141546 1 0 1 1 0 0 +EDGE2 7556 7535 -0.91137 -0.0109 1.57381 1 0 1 1 0 0 +EDGE2 7556 7555 -0.94014 -0.0834771 -1.57875 1 0 1 1 0 0 +EDGE2 7556 7455 -0.992592 0.0478991 1.60919 1 0 1 1 0 0 +EDGE2 7556 7475 -1.07623 0.0711315 -1.58075 1 0 1 1 0 0 +EDGE2 7556 7515 -1.11552 -0.0418876 1.587 1 0 1 1 0 0 +EDGE2 7556 7395 -1.01122 0.0195595 -1.56169 1 0 1 1 0 0 +EDGE2 7556 7516 0.0401419 -0.0184553 -0.00638819 1 0 1 1 0 0 +EDGE2 7556 7536 -0.0788302 -0.137977 -0.0333742 1 0 1 1 0 0 +EDGE2 7556 7456 0.0369286 -0.0536165 0.0292803 1 0 1 1 0 0 +EDGE2 7556 7517 0.8982 0.0647863 -0.0300738 1 0 1 1 0 0 +EDGE2 7556 7457 1.03569 0.00907948 0.0256038 1 0 1 1 0 0 +EDGE2 7557 7537 -0.00724845 0.00435332 -0.0156731 1 0 1 1 0 0 +EDGE2 7557 7516 -0.982566 0.0293209 -0.0265368 1 0 1 1 0 0 +EDGE2 7557 7536 -0.970961 0.00691281 9.29118e-05 1 0 1 1 0 0 +EDGE2 7557 7556 -0.967315 0.010392 0.00309709 1 0 1 1 0 0 +EDGE2 7557 7456 -1.00993 0.0404322 0.00432938 1 0 1 1 0 0 +EDGE2 7557 7517 0.108959 -0.00673389 -0.00981089 1 0 1 1 0 0 +EDGE2 7557 7457 0.0787924 -0.0653127 0.0266171 1 0 1 1 0 0 +EDGE2 7557 7458 0.947074 0.0124552 -0.000712867 1 0 1 1 0 0 +EDGE2 7557 7538 1.01891 0.0194074 0.0269338 1 0 1 1 0 0 +EDGE2 7557 7518 1.08508 -0.0155049 0.0186762 1 0 1 1 0 0 +EDGE2 7558 7537 -1.02007 0.0210939 -0.00373424 1 0 1 1 0 0 +EDGE2 7558 7557 -0.951085 -0.00373434 0.0221032 1 0 1 1 0 0 +EDGE2 7558 7517 -0.984348 0.0283307 -0.00229461 1 0 1 1 0 0 +EDGE2 7558 7457 -1.00058 -0.017053 -0.00298744 1 0 1 1 0 0 +EDGE2 7558 7539 1.01037 -0.050363 -0.00304692 1 0 1 1 0 0 +EDGE2 7558 7458 0.0391881 -0.0161777 0.0174449 1 0 1 1 0 0 +EDGE2 7558 7538 -0.0150291 0.0353032 -0.0210289 1 0 1 1 0 0 +EDGE2 7558 7518 0.0444762 0.0368733 0.0178404 1 0 1 1 0 0 +EDGE2 7558 7459 0.962358 0.0680608 0.0252547 1 0 1 1 0 0 +EDGE2 7558 7519 1.08165 -0.0185434 0.0068936 1 0 1 1 0 0 +EDGE2 7559 7520 0.996554 0.00222509 0.0252919 1 0 1 1 0 0 +EDGE2 7559 7539 0.0366358 0.0333422 -0.0381759 1 0 1 1 0 0 +EDGE2 7559 7458 -1.05374 0.0299071 -3.4767e-05 1 0 1 1 0 0 +EDGE2 7559 7538 -1.08346 0.0117249 -0.00268606 1 0 1 1 0 0 +EDGE2 7559 7558 -0.897711 0.0261689 -0.0101715 1 0 1 1 0 0 +EDGE2 7559 7518 -1.05092 -0.0748629 0.00829883 1 0 1 1 0 0 +EDGE2 7559 7459 -0.041008 0.0223063 -0.0213112 1 0 1 1 0 0 +EDGE2 7559 7519 0.0193261 0.0181395 0.00493665 1 0 1 1 0 0 +EDGE2 7559 7540 0.945245 -0.0222421 0.00317239 1 0 1 1 0 0 +EDGE2 7559 7380 1.00945 0.0404802 -3.15117 1 0 1 1 0 0 +EDGE2 7559 7460 1.15149 0.0260896 -0.000340934 1 0 1 1 0 0 +EDGE2 7560 7520 0.0195118 0.0818529 -0.00322098 1 0 1 1 0 0 +EDGE2 7560 7539 -0.971508 -0.000715809 0.0271969 1 0 1 1 0 0 +EDGE2 7560 7559 -0.925665 -0.024249 -0.00133782 1 0 1 1 0 0 +EDGE2 7560 7459 -0.948784 0.0601527 -0.0108545 1 0 1 1 0 0 +EDGE2 7560 7519 -1.04926 0.0227946 -0.0201698 1 0 1 1 0 0 +EDGE2 7560 7540 -0.0112316 0.0220232 -0.0100158 1 0 1 1 0 0 +EDGE2 7560 7381 0.00160594 0.981912 1.60346 1 0 1 1 0 0 +EDGE2 7560 7461 0.0347019 1.08817 1.59441 1 0 1 1 0 0 +EDGE2 7560 7541 -0.0646574 1.0283 1.58583 1 0 1 1 0 0 +EDGE2 7560 7380 -0.0560777 -0.0180182 -3.12279 1 0 1 1 0 0 +EDGE2 7560 7460 -0.0091141 0.00789537 -0.0328085 1 0 1 1 0 0 +EDGE2 7560 7521 -0.0586111 -0.964511 -1.60997 1 0 1 1 0 0 +EDGE2 7560 7379 0.95949 -0.0198794 -3.13365 1 0 1 1 0 0 +EDGE2 7561 7520 -0.986909 -0.00635328 -1.59375 1 0 1 1 0 0 +EDGE2 7561 7540 -1.0567 -0.0241067 -1.55413 1 0 1 1 0 0 +EDGE2 7561 7542 1.09825 0.0074845 0.0298726 1 0 1 1 0 0 +EDGE2 7561 7382 0.98668 0.0256656 0.0252376 1 0 1 1 0 0 +EDGE2 7561 7462 1.03319 0.0540032 0.0136505 1 0 1 1 0 0 +EDGE2 7561 7381 0.0528345 -0.0344926 -0.0104991 1 0 1 1 0 0 +EDGE2 7561 7461 -0.014152 -0.0442279 0.0292868 1 0 1 1 0 0 +EDGE2 7561 7541 -0.0296811 -0.00324864 0.000835849 1 0 1 1 0 0 +EDGE2 7561 7560 -1.06509 0.0461697 -1.57987 1 0 1 1 0 0 +EDGE2 7561 7380 -1.00589 -0.0769352 1.56707 1 0 1 1 0 0 +EDGE2 7561 7460 -0.973244 -0.0637769 -1.53264 1 0 1 1 0 0 +EDGE2 7562 7463 0.945929 -0.0282625 0.026934 1 0 1 1 0 0 +EDGE2 7562 7543 1.0771 0.0275736 0.0147807 1 0 1 1 0 0 +EDGE2 7562 7561 -1.01002 -0.137541 0.0156302 1 0 1 1 0 0 +EDGE2 7562 7542 0.0325908 0.0333818 -0.0106369 1 0 1 1 0 0 +EDGE2 7562 7383 0.906625 0.00185344 -0.0183265 1 0 1 1 0 0 +EDGE2 7562 7382 0.0348518 0.0139581 -0.00223202 1 0 1 1 0 0 +EDGE2 7562 7462 -0.0579945 -0.0184896 0.0136455 1 0 1 1 0 0 +EDGE2 7562 7381 -0.980797 -0.0133776 0.00897377 1 0 1 1 0 0 +EDGE2 7562 7461 -1.02191 -0.0491875 -0.0416732 1 0 1 1 0 0 +EDGE2 7562 7541 -0.940278 0.0660987 -0.0289924 1 0 1 1 0 0 +EDGE2 7563 7463 -0.0100186 -0.0126575 -0.00316733 1 0 1 1 0 0 +EDGE2 7563 7544 0.838365 0.057234 0.0596094 1 0 1 1 0 0 +EDGE2 7563 7464 0.964375 -0.0494355 0.00742629 1 0 1 1 0 0 +EDGE2 7563 7384 1.04633 0.00274815 0.00521209 1 0 1 1 0 0 +EDGE2 7563 7543 0.0241643 -0.0732569 -0.015667 1 0 1 1 0 0 +EDGE2 7563 7542 -0.952383 -0.00312754 -0.00174701 1 0 1 1 0 0 +EDGE2 7563 7383 0.0225777 0.0153736 0.0229928 1 0 1 1 0 0 +EDGE2 7563 7562 -0.984139 -0.0325658 0.01972 1 0 1 1 0 0 +EDGE2 7563 7382 -1.01509 -0.0340919 0.00194784 1 0 1 1 0 0 +EDGE2 7563 7462 -1.07685 0.0383044 0.0108843 1 0 1 1 0 0 +EDGE2 7564 7463 -0.954713 0.0294569 0.0100302 1 0 1 1 0 0 +EDGE2 7564 7544 -0.102423 0.0941851 0.00356432 1 0 1 1 0 0 +EDGE2 7564 7465 0.956224 0.00593118 0.0321411 1 0 1 1 0 0 +EDGE2 7564 7545 1.03388 -0.0401484 -0.00197047 1 0 1 1 0 0 +EDGE2 7564 7385 1.065 -0.0286649 -0.0276818 1 0 1 1 0 0 +EDGE2 7564 7464 -0.0725298 -0.0278675 -0.0442188 1 0 1 1 0 0 +EDGE2 7564 7384 -0.0352843 -0.0446474 0.0257602 1 0 1 1 0 0 +EDGE2 7564 7563 -1.01125 -0.0197638 0.00386137 1 0 1 1 0 0 +EDGE2 7564 7543 -0.997987 -0.0817589 -0.00681918 1 0 1 1 0 0 +EDGE2 7564 7383 -0.930711 0.0105039 0.0217063 1 0 1 1 0 0 +EDGE2 7565 7466 -0.0356829 0.936337 1.57472 1 0 1 1 0 0 +EDGE2 7565 7546 -0.00682374 0.988007 1.59096 1 0 1 1 0 0 +EDGE2 7565 7386 -0.00927964 0.952752 1.53931 1 0 1 1 0 0 +EDGE2 7565 7544 -0.955687 0.0444857 -0.0216927 1 0 1 1 0 0 +EDGE2 7565 7465 -0.0174868 -0.0282627 0.000179069 1 0 1 1 0 0 +EDGE2 7565 7545 0.0742481 -0.0281805 0.00229023 1 0 1 1 0 0 +EDGE2 7565 7385 7.76058e-05 0.0704123 -0.00352883 1 0 1 1 0 0 +EDGE2 7565 7564 -1.02058 0.00357892 -0.00520687 1 0 1 1 0 0 +EDGE2 7565 7464 -1.01751 0.0728724 -0.00288039 1 0 1 1 0 0 +EDGE2 7565 7384 -1.04188 -0.0243056 -0.00835209 1 0 1 1 0 0 +EDGE2 7566 7467 1.05726 0.0390714 0.0193396 1 0 1 1 0 0 +EDGE2 7566 7547 1.01937 0.0114605 -0.00614423 1 0 1 1 0 0 +EDGE2 7566 7387 0.93399 -0.0440787 -0.0169005 1 0 1 1 0 0 +EDGE2 7566 7466 -0.0560235 -0.0032838 -0.00191176 1 0 1 1 0 0 +EDGE2 7566 7546 -0.0274251 0.000109549 0.0241502 1 0 1 1 0 0 +EDGE2 7566 7386 -0.00389202 0.0114376 -0.0194565 1 0 1 1 0 0 +EDGE2 7566 7465 -1.00067 -0.0797709 -1.57211 1 0 1 1 0 0 +EDGE2 7566 7565 -0.994863 0.0108216 -1.58069 1 0 1 1 0 0 +EDGE2 7566 7545 -1.0486 -0.13068 -1.57105 1 0 1 1 0 0 +EDGE2 7566 7385 -0.9972 0.0254903 -1.56901 1 0 1 1 0 0 +EDGE2 7567 7468 0.938054 0.0641004 -0.0332485 1 0 1 1 0 0 +EDGE2 7567 7548 0.984706 -0.0773277 0.00594254 1 0 1 1 0 0 +EDGE2 7567 7388 1.01817 0.0209387 -0.0452736 1 0 1 1 0 0 +EDGE2 7567 7467 0.0443268 0.00998353 0.0316775 1 0 1 1 0 0 +EDGE2 7567 7547 -0.0140324 0.039811 -0.0641186 1 0 1 1 0 0 +EDGE2 7567 7387 -0.00245698 -0.0223403 -0.0192535 1 0 1 1 0 0 +EDGE2 7567 7466 -0.99997 -0.0657534 0.020999 1 0 1 1 0 0 +EDGE2 7567 7546 -1.05752 0.00665585 -0.00236582 1 0 1 1 0 0 +EDGE2 7567 7566 -0.987014 -0.0340844 -0.00218322 1 0 1 1 0 0 +EDGE2 7567 7386 -1.00922 -0.0556859 0.00424987 1 0 1 1 0 0 +EDGE2 7568 7389 0.983927 0.0339845 -0.0182124 1 0 1 1 0 0 +EDGE2 7568 7469 0.951985 -0.0632899 0.0251033 1 0 1 1 0 0 +EDGE2 7568 7549 0.942212 0.0213713 -0.0071616 1 0 1 1 0 0 +EDGE2 7568 7468 -0.0196296 -0.143523 0.0602515 1 0 1 1 0 0 +EDGE2 7568 7548 -0.0121771 -0.0699967 -0.00780514 1 0 1 1 0 0 +EDGE2 7568 7388 0.0455798 -0.0324488 0.00579368 1 0 1 1 0 0 +EDGE2 7568 7467 -1.01907 0.0304433 -0.000427117 1 0 1 1 0 0 +EDGE2 7568 7547 -0.935822 0.0221634 0.000587113 1 0 1 1 0 0 +EDGE2 7568 7567 -1.01157 -0.012949 -0.0352953 1 0 1 1 0 0 +EDGE2 7568 7387 -1.03676 0.0225158 0.0098105 1 0 1 1 0 0 +EDGE2 7569 7470 0.983144 0.00949048 -0.0162106 1 0 1 1 0 0 +EDGE2 7569 7550 1.06412 -0.00344942 -0.00133574 1 0 1 1 0 0 +EDGE2 7569 7390 0.984442 -0.023354 0.00754278 1 0 1 1 0 0 +EDGE2 7569 7389 0.0249201 0.0378252 -0.0109148 1 0 1 1 0 0 +EDGE2 7569 7469 -0.0013513 0.0131991 0.00117092 1 0 1 1 0 0 +EDGE2 7569 7549 0.0516238 0.0240797 0.0051326 1 0 1 1 0 0 +EDGE2 7569 7468 -0.914322 -0.0359106 0.0102139 1 0 1 1 0 0 +EDGE2 7569 7548 -0.942105 -0.0294055 0.00382699 1 0 1 1 0 0 +EDGE2 7569 7568 -1.04294 -0.0672908 0.00516051 1 0 1 1 0 0 +EDGE2 7569 7388 -0.94976 -0.0210334 -0.00538547 1 0 1 1 0 0 +EDGE2 7570 7470 0.0286405 -0.0183238 0.0263731 1 0 1 1 0 0 +EDGE2 7570 7550 0.00482844 -0.0406669 0.000483426 1 0 1 1 0 0 +EDGE2 7570 7390 -0.0781592 -0.0423919 -0.0106968 1 0 1 1 0 0 +EDGE2 7570 7391 0.0145445 1.02907 1.55683 1 0 1 1 0 0 +EDGE2 7570 7471 -0.033955 0.983525 1.56456 1 0 1 1 0 0 +EDGE2 7570 7551 -0.0949595 1.00089 1.60036 1 0 1 1 0 0 +EDGE2 7570 7569 -0.986634 -0.00108226 0.00617797 1 0 1 1 0 0 +EDGE2 7570 7389 -0.935889 -0.0387156 0.0306973 1 0 1 1 0 0 +EDGE2 7570 7469 -1.01264 -0.0526726 -0.00564556 1 0 1 1 0 0 +EDGE2 7570 7549 -0.937484 -0.00984769 0.0142266 1 0 1 1 0 0 +EDGE2 7571 7552 1.03102 -0.0897148 -0.0174074 1 0 1 1 0 0 +EDGE2 7571 7470 -0.992655 0.0522216 -1.57644 1 0 1 1 0 0 +EDGE2 7571 7550 -1.05972 0.0188409 -1.59356 1 0 1 1 0 0 +EDGE2 7571 7570 -1.02449 -0.0528541 -1.56982 1 0 1 1 0 0 +EDGE2 7571 7390 -1.00628 0.0319134 -1.57551 1 0 1 1 0 0 +EDGE2 7571 7391 -0.044729 -0.0348677 0.020101 1 0 1 1 0 0 +EDGE2 7571 7471 -0.00885537 -0.0284562 0.00774547 1 0 1 1 0 0 +EDGE2 7571 7551 0.0274679 -0.0344994 0.00267929 1 0 1 1 0 0 +EDGE2 7571 7392 0.957683 0.0381605 0.0248752 1 0 1 1 0 0 +EDGE2 7571 7472 1.14667 -0.0257784 -0.0145457 1 0 1 1 0 0 +EDGE2 7572 7552 -0.0512127 -0.0369518 -0.00759026 1 0 1 1 0 0 +EDGE2 7572 7571 -0.964354 0.0379272 0.00342442 1 0 1 1 0 0 +EDGE2 7572 7391 -1.06736 -0.0460888 -0.00703552 1 0 1 1 0 0 +EDGE2 7572 7471 -0.942678 -0.0205833 -0.00612549 1 0 1 1 0 0 +EDGE2 7572 7551 -0.951416 -0.0207428 -0.0210849 1 0 1 1 0 0 +EDGE2 7572 7473 1.04955 0.00677515 -0.012325 1 0 1 1 0 0 +EDGE2 7572 7392 0.00947813 -0.0799994 0.00473177 1 0 1 1 0 0 +EDGE2 7572 7472 -0.0203903 0.00575568 -0.0435554 1 0 1 1 0 0 +EDGE2 7572 7553 0.915763 -0.0225097 -0.0253295 1 0 1 1 0 0 +EDGE2 7572 7393 0.954921 -0.0172114 0.00291096 1 0 1 1 0 0 +EDGE2 7573 7552 -1.00491 -0.0324764 -0.0391587 1 0 1 1 0 0 +EDGE2 7573 7572 -1.00316 -0.0309164 -0.0127797 1 0 1 1 0 0 +EDGE2 7573 7394 0.950692 0.0367083 0.0215978 1 0 1 1 0 0 +EDGE2 7573 7473 0.0235918 0.043767 -0.0343413 1 0 1 1 0 0 +EDGE2 7573 7392 -0.996237 0.00694754 0.00351788 1 0 1 1 0 0 +EDGE2 7573 7472 -0.959988 -0.0406125 -0.0232258 1 0 1 1 0 0 +EDGE2 7573 7553 -0.0420673 0.0226787 0.00551462 1 0 1 1 0 0 +EDGE2 7573 7554 1.00042 0.0457926 0.0123912 1 0 1 1 0 0 +EDGE2 7573 7393 -0.039304 0.0118184 0.0177136 1 0 1 1 0 0 +EDGE2 7573 7474 1.0197 -0.0146788 -0.0208871 1 0 1 1 0 0 +EDGE2 7574 7394 0.00541664 0.00983925 -0.0305671 1 0 1 1 0 0 +EDGE2 7574 7473 -0.964781 0.0234482 -0.0172703 1 0 1 1 0 0 +EDGE2 7574 7573 -0.877018 0.0538792 -0.00782226 1 0 1 1 0 0 +EDGE2 7574 7553 -0.953533 -0.0416838 0.00186656 1 0 1 1 0 0 +EDGE2 7574 7554 0.0279729 -0.0594081 -0.0195505 1 0 1 1 0 0 +EDGE2 7574 7393 -1.05905 0.0572622 0.019426 1 0 1 1 0 0 +EDGE2 7574 7474 -0.0578462 0.0619154 0.00557964 1 0 1 1 0 0 +EDGE2 7574 7535 0.949082 0.00854716 -3.18841 1 0 1 1 0 0 +EDGE2 7574 7555 1.04045 -0.0159632 -0.00489951 1 0 1 1 0 0 +EDGE2 7574 7455 0.906948 0.0411883 -3.13797 1 0 1 1 0 0 +EDGE2 7574 7475 1.00708 -0.037226 -0.000502868 1 0 1 1 0 0 +EDGE2 7574 7515 0.978693 0.0338711 -3.15699 1 0 1 1 0 0 +EDGE2 7574 7395 0.918573 -0.0299207 -0.0155647 1 0 1 1 0 0 +EDGE2 7575 7476 0.0072452 -0.980574 -1.58481 1 0 1 1 0 0 +EDGE2 7575 7396 0.0322494 -0.956043 -1.59232 1 0 1 1 0 0 +EDGE2 7575 7394 -1.01641 0.017352 0.032631 1 0 1 1 0 0 +EDGE2 7575 7554 -0.987305 0.0312887 -0.0322161 1 0 1 1 0 0 +EDGE2 7575 7574 -1.06407 -0.00123119 -0.0154164 1 0 1 1 0 0 +EDGE2 7575 7474 -1.04555 0.0894969 0.00607353 1 0 1 1 0 0 +EDGE2 7575 7535 -0.0351923 0.00204465 -3.11975 1 0 1 1 0 0 +EDGE2 7575 7555 0.0593129 -0.0523347 -0.0177111 1 0 1 1 0 0 +EDGE2 7575 7455 0.0438961 -0.00803822 -3.15511 1 0 1 1 0 0 +EDGE2 7575 7475 0.00908491 -0.0660473 0.00323039 1 0 1 1 0 0 +EDGE2 7575 7515 0.0200778 -0.0111108 -3.15884 1 0 1 1 0 0 +EDGE2 7575 7395 0.0504909 0.0403455 0.00283295 1 0 1 1 0 0 +EDGE2 7575 7516 -0.00226489 0.98276 1.61384 1 0 1 1 0 0 +EDGE2 7575 7536 0.00546074 0.982992 1.54837 1 0 1 1 0 0 +EDGE2 7575 7556 0.0707774 0.99328 1.54525 1 0 1 1 0 0 +EDGE2 7575 7456 -0.0564602 1.04682 1.57194 1 0 1 1 0 0 +EDGE2 7575 7514 0.953391 -0.0173349 -3.11699 1 0 1 1 0 0 +EDGE2 7575 7534 0.962129 -0.0387381 -3.18342 1 0 1 1 0 0 +EDGE2 7575 7454 1.01747 -0.0574334 -3.14172 1 0 1 1 0 0 +EDGE2 7576 7537 1.10026 -0.041901 0.00697004 1 0 1 1 0 0 +EDGE2 7576 7535 -1.01162 0.0235791 1.52242 1 0 1 1 0 0 +EDGE2 7576 7575 -0.99602 0.0274392 -1.53925 1 0 1 1 0 0 +EDGE2 7576 7555 -0.95274 -0.0909787 -1.58506 1 0 1 1 0 0 +EDGE2 7576 7455 -0.934707 -0.00919292 1.59394 1 0 1 1 0 0 +EDGE2 7576 7475 -0.965155 -0.0176589 -1.54928 1 0 1 1 0 0 +EDGE2 7576 7515 -1.03691 0.0127559 1.56282 1 0 1 1 0 0 +EDGE2 7576 7395 -1.09477 0.0730458 -1.5598 1 0 1 1 0 0 +EDGE2 7576 7516 -0.0475554 0.00184305 -0.000121199 1 0 1 1 0 0 +EDGE2 7576 7536 -0.0449644 -0.00777844 0.0158757 1 0 1 1 0 0 +EDGE2 7576 7556 0.0592987 -0.0178205 0.00865866 1 0 1 1 0 0 +EDGE2 7576 7456 0.00464389 -0.0349938 -0.0169856 1 0 1 1 0 0 +EDGE2 7576 7557 0.990111 -0.062389 0.0243108 1 0 1 1 0 0 +EDGE2 7576 7517 0.987508 0.0185345 -0.0194294 1 0 1 1 0 0 +EDGE2 7576 7457 1.0095 0.0437922 -0.0189798 1 0 1 1 0 0 +EDGE2 7577 7537 -0.0648939 0.0537278 0.004947 1 0 1 1 0 0 +EDGE2 7577 7576 -0.953052 0.0296923 0.0105577 1 0 1 1 0 0 +EDGE2 7577 7516 -0.980732 0.0282872 -0.016377 1 0 1 1 0 0 +EDGE2 7577 7536 -0.982445 0.0336453 0.011524 1 0 1 1 0 0 +EDGE2 7577 7556 -0.957193 -0.0305205 -0.0350662 1 0 1 1 0 0 +EDGE2 7577 7456 -1.06356 -0.0679999 0.00288016 1 0 1 1 0 0 +EDGE2 7577 7557 -0.00658731 0.0501665 0.0370923 1 0 1 1 0 0 +EDGE2 7577 7517 0.0272201 -0.0195637 -0.0102854 1 0 1 1 0 0 +EDGE2 7577 7457 0.0405453 0.0480519 0.0133151 1 0 1 1 0 0 +EDGE2 7577 7458 0.949989 0.0609511 -0.00914433 1 0 1 1 0 0 +EDGE2 7577 7538 0.909162 0.0758457 0.0291126 1 0 1 1 0 0 +EDGE2 7577 7558 0.96377 0.0334859 -0.046223 1 0 1 1 0 0 +EDGE2 7577 7518 1.02305 -0.0270408 0.00883771 1 0 1 1 0 0 +EDGE2 7578 7537 -1.05128 -0.120059 -0.0187878 1 0 1 1 0 0 +EDGE2 7578 7577 -0.935181 -0.00174016 0.00794676 1 0 1 1 0 0 +EDGE2 7578 7557 -0.882926 0.0421069 0.00103761 1 0 1 1 0 0 +EDGE2 7578 7517 -1.03139 0.0479995 0.00246552 1 0 1 1 0 0 +EDGE2 7578 7457 -0.93115 0.0113175 0.01243 1 0 1 1 0 0 +EDGE2 7578 7539 1.01008 -0.0235547 -0.0243529 1 0 1 1 0 0 +EDGE2 7578 7458 0.0256329 -0.00056635 -0.0143508 1 0 1 1 0 0 +EDGE2 7578 7538 -0.0536575 -0.00136702 -0.0181702 1 0 1 1 0 0 +EDGE2 7578 7558 -0.0726595 -0.0104017 -0.032785 1 0 1 1 0 0 +EDGE2 7578 7518 -0.0970702 -0.00280766 0.0146728 1 0 1 1 0 0 +EDGE2 7578 7559 1.04683 0.045135 -0.0105221 1 0 1 1 0 0 +EDGE2 7578 7459 0.961015 -0.0343655 -0.0152038 1 0 1 1 0 0 +EDGE2 7578 7519 0.945992 0.0379223 -0.0256612 1 0 1 1 0 0 +EDGE2 7579 7520 0.947424 -0.0141112 -0.0461045 1 0 1 1 0 0 +EDGE2 7579 7539 0.0289773 0.0117177 0.0226545 1 0 1 1 0 0 +EDGE2 7579 7458 -0.977726 -0.106211 -0.0382438 1 0 1 1 0 0 +EDGE2 7579 7538 -0.974345 -0.026275 0.0263011 1 0 1 1 0 0 +EDGE2 7579 7558 -1.00454 0.0731588 0.00644825 1 0 1 1 0 0 +EDGE2 7579 7578 -0.980539 0.0573045 0.00330117 1 0 1 1 0 0 +EDGE2 7579 7518 -0.913159 0.028126 0.0118746 1 0 1 1 0 0 +EDGE2 7579 7559 0.0496286 -0.0329686 -0.00799336 1 0 1 1 0 0 +EDGE2 7579 7459 0.0241313 0.0177849 -0.0185241 1 0 1 1 0 0 +EDGE2 7579 7519 0.00465941 -0.0802001 0.0262243 1 0 1 1 0 0 +EDGE2 7579 7540 1.05776 0.0318245 -0.0087433 1 0 1 1 0 0 +EDGE2 7579 7560 1.04109 -0.0263002 -0.00287152 1 0 1 1 0 0 +EDGE2 7579 7380 0.96718 -0.0891265 -3.19822 1 0 1 1 0 0 +EDGE2 7579 7460 1.03149 0.0422937 0.0122284 1 0 1 1 0 0 +EDGE2 7580 7520 0.11029 0.0673769 -0.00772661 1 0 1 1 0 0 +EDGE2 7580 7539 -1.02853 0.0300899 0.0131053 1 0 1 1 0 0 +EDGE2 7580 7579 -0.99204 -0.00772884 0.0340034 1 0 1 1 0 0 +EDGE2 7580 7559 -0.941471 0.0730958 0.0114039 1 0 1 1 0 0 +EDGE2 7580 7459 -1.01245 -0.0378355 0.0432279 1 0 1 1 0 0 +EDGE2 7580 7519 -1.00204 -0.0910616 0.00399065 1 0 1 1 0 0 +EDGE2 7580 7540 -0.0815236 -0.0756726 -0.00936554 1 0 1 1 0 0 +EDGE2 7580 7561 0.0207196 1.00667 1.52983 1 0 1 1 0 0 +EDGE2 7580 7381 0.0182266 0.965128 1.55405 1 0 1 1 0 0 +EDGE2 7580 7461 -0.0188317 0.882702 1.54822 1 0 1 1 0 0 +EDGE2 7580 7541 0.0376506 0.939513 1.5645 1 0 1 1 0 0 +EDGE2 7580 7560 -0.081344 0.0414675 0.0102804 1 0 1 1 0 0 +EDGE2 7580 7380 -0.0207224 -0.0333912 -3.14947 1 0 1 1 0 0 +EDGE2 7580 7460 0.0702202 -0.0385131 -0.0181774 1 0 1 1 0 0 +EDGE2 7580 7521 0.0609619 -0.987015 -1.54969 1 0 1 1 0 0 +EDGE2 7580 7379 1.07873 0.0444332 -3.12384 1 0 1 1 0 0 +EDGE2 7581 7520 -1.144 -0.00683667 -1.57089 1 0 1 1 0 0 +EDGE2 7581 7540 -1.00313 -0.0806737 -1.55445 1 0 1 1 0 0 +EDGE2 7581 7561 0.0161513 -0.125768 -0.00546935 1 0 1 1 0 0 +EDGE2 7581 7542 1.02691 0.0739786 0.00781492 1 0 1 1 0 0 +EDGE2 7581 7562 1.01932 0.0399965 -0.0176577 1 0 1 1 0 0 +EDGE2 7581 7382 0.971899 0.0990161 0.0167837 1 0 1 1 0 0 +EDGE2 7581 7462 1.0486 -0.0508303 -0.00919719 1 0 1 1 0 0 +EDGE2 7581 7381 -0.0320595 -0.0101104 -0.00339325 1 0 1 1 0 0 +EDGE2 7581 7461 0.0260022 0.0166171 0.0395594 1 0 1 1 0 0 +EDGE2 7581 7541 0.0390226 -0.0542289 0.0180106 1 0 1 1 0 0 +EDGE2 7581 7580 -1.00916 -0.0247362 -1.54439 1 0 1 1 0 0 +EDGE2 7581 7560 -0.985652 -0.115635 -1.57239 1 0 1 1 0 0 +EDGE2 7581 7380 -1.01142 -0.0292725 1.60663 1 0 1 1 0 0 +EDGE2 7581 7460 -0.984681 -0.0165221 -1.56104 1 0 1 1 0 0 +EDGE2 7582 7463 0.96236 -0.0382375 0.00997084 1 0 1 1 0 0 +EDGE2 7582 7563 0.895633 -0.0372199 -0.0217862 1 0 1 1 0 0 +EDGE2 7582 7543 1.04096 -0.0248668 -0.0407837 1 0 1 1 0 0 +EDGE2 7582 7561 -1.10406 0.0788693 0.0114506 1 0 1 1 0 0 +EDGE2 7582 7542 0.0112261 0.0600715 -0.00692115 1 0 1 1 0 0 +EDGE2 7582 7383 1.03178 0.00436385 0.0126333 1 0 1 1 0 0 +EDGE2 7582 7562 -0.0569273 0.0183358 -0.0162776 1 0 1 1 0 0 +EDGE2 7582 7382 0.0184435 0.0323071 -0.025091 1 0 1 1 0 0 +EDGE2 7582 7462 -0.0324288 -0.109356 0.0179452 1 0 1 1 0 0 +EDGE2 7582 7581 -1.06964 0.0153612 -0.0138258 1 0 1 1 0 0 +EDGE2 7582 7381 -1.0401 -0.0501003 0.0122375 1 0 1 1 0 0 +EDGE2 7582 7461 -0.934999 0.00997443 -0.0165666 1 0 1 1 0 0 +EDGE2 7582 7541 -1.00375 -0.109676 0.0172715 1 0 1 1 0 0 +EDGE2 7583 7463 0.055368 0.0338113 -0.00621102 1 0 1 1 0 0 +EDGE2 7583 7544 0.976455 0.000118671 0.000418732 1 0 1 1 0 0 +EDGE2 7583 7564 1.04094 0.0469465 -4.41607e-05 1 0 1 1 0 0 +EDGE2 7583 7464 1.08302 0.0270164 0.00413721 1 0 1 1 0 0 +EDGE2 7583 7384 1.06146 -0.0296877 0.0248454 1 0 1 1 0 0 +EDGE2 7583 7563 -0.0898731 -0.0106986 -0.0233264 1 0 1 1 0 0 +EDGE2 7583 7543 -0.0109393 0.0412241 0.0143351 1 0 1 1 0 0 +EDGE2 7583 7542 -1.06703 0.0297771 0.00289905 1 0 1 1 0 0 +EDGE2 7583 7582 -0.929709 0.00804752 -0.00735113 1 0 1 1 0 0 +EDGE2 7583 7383 -0.0216976 -0.046693 -0.0161094 1 0 1 1 0 0 +EDGE2 7583 7562 -0.972234 0.0130737 -0.0169295 1 0 1 1 0 0 +EDGE2 7583 7382 -1.01704 0.0464533 0.0208388 1 0 1 1 0 0 +EDGE2 7583 7462 -1.02078 0.0495945 -0.00503633 1 0 1 1 0 0 +EDGE2 7584 7463 -1.07626 0.102143 -0.0158738 1 0 1 1 0 0 +EDGE2 7584 7544 0.0380368 -0.0260053 0.00933289 1 0 1 1 0 0 +EDGE2 7584 7465 1.01174 0.0417361 0.0184579 1 0 1 1 0 0 +EDGE2 7584 7565 0.998353 0.015324 0.013643 1 0 1 1 0 0 +EDGE2 7584 7545 1.00117 -0.0312917 0.0384667 1 0 1 1 0 0 +EDGE2 7584 7385 1.03317 -0.0410124 -0.0395004 1 0 1 1 0 0 +EDGE2 7584 7564 -0.0144814 -0.0662246 0.025872 1 0 1 1 0 0 +EDGE2 7584 7464 0.0516884 0.0122636 0.00544122 1 0 1 1 0 0 +EDGE2 7584 7384 -0.065687 0.0918326 -0.0324841 1 0 1 1 0 0 +EDGE2 7584 7563 -0.987969 -0.0297698 -0.0237698 1 0 1 1 0 0 +EDGE2 7584 7583 -0.895988 -0.00285092 -0.0306827 1 0 1 1 0 0 +EDGE2 7584 7543 -1.01757 0.00950242 -0.0534528 1 0 1 1 0 0 +EDGE2 7584 7383 -0.916126 0.0263342 -0.0137987 1 0 1 1 0 0 +EDGE2 7585 7466 -0.0196484 0.970181 1.61798 1 0 1 1 0 0 +EDGE2 7585 7546 0.0149112 0.976997 1.53545 1 0 1 1 0 0 +EDGE2 7585 7566 -0.0372487 0.984447 1.54669 1 0 1 1 0 0 +EDGE2 7585 7386 0.0523953 1.02278 1.56492 1 0 1 1 0 0 +EDGE2 7585 7544 -0.990349 0.0179012 0.0043605 1 0 1 1 0 0 +EDGE2 7585 7465 0.0275088 -0.00322384 -0.0135534 1 0 1 1 0 0 +EDGE2 7585 7565 0.0135905 -0.0568229 -0.0109616 1 0 1 1 0 0 +EDGE2 7585 7545 0.00701411 0.0568203 0.00222683 1 0 1 1 0 0 +EDGE2 7585 7584 -1.06468 0.0264386 -0.00353895 1 0 1 1 0 0 +EDGE2 7585 7385 0.00239595 0.0512802 -0.0341753 1 0 1 1 0 0 +EDGE2 7585 7564 -1.01099 0.0601972 0.0107919 1 0 1 1 0 0 +EDGE2 7585 7464 -0.99313 0.0776841 -0.00280732 1 0 1 1 0 0 +EDGE2 7585 7384 -0.900735 0.0206392 -0.0228644 1 0 1 1 0 0 +EDGE2 7586 7465 -0.931518 0.014323 1.53413 1 0 1 1 0 0 +EDGE2 7586 7565 -1.08781 0.0765272 1.55224 1 0 1 1 0 0 +EDGE2 7586 7585 -1.05772 0.000715728 1.60419 1 0 1 1 0 0 +EDGE2 7586 7545 -1.05117 -0.0488454 1.60324 1 0 1 1 0 0 +EDGE2 7586 7385 -1.05122 0.0305385 1.53379 1 0 1 1 0 0 +EDGE2 7587 7586 -1.03628 0.0363064 -0.0186518 1 0 1 1 0 0 +EDGE2 7588 7587 -1.02098 -0.0252845 0.0215373 1 0 1 1 0 0 +EDGE2 7589 7588 -1.02429 -0.0397623 -0.0146604 1 0 1 1 0 0 +EDGE2 7590 7589 -0.975246 0.0226202 -0.0151543 1 0 1 1 0 0 +EDGE2 7591 7590 -1.045 0.0478534 1.54433 1 0 1 1 0 0 +EDGE2 7592 7591 -1.07723 -0.00162497 0.00592065 1 0 1 1 0 0 +EDGE2 7593 7592 -0.942063 0.0193527 0.00898162 1 0 1 1 0 0 +EDGE2 7594 7593 -1.03708 0.119584 -0.0251247 1 0 1 1 0 0 +EDGE2 7594 7375 0.995297 -0.0182929 -3.11228 1 0 1 1 0 0 +EDGE2 7595 7594 -0.970894 0.0083259 -0.00924911 1 0 1 1 0 0 +EDGE2 7595 7376 0.033146 -0.860462 -1.56048 1 0 1 1 0 0 +EDGE2 7595 7375 0.0546432 -0.0591645 -3.13715 1 0 1 1 0 0 +EDGE2 7595 7374 0.990864 -0.130096 -3.12679 1 0 1 1 0 0 +EDGE2 7596 7375 -1.04543 0.0156891 1.55722 1 0 1 1 0 0 +EDGE2 7596 7595 -1.07504 0.0535042 -1.55561 1 0 1 1 0 0 +EDGE2 7597 7596 -1.06914 -0.00245347 0.00757112 1 0 1 1 0 0 +EDGE2 7598 7597 -1.05441 -0.0202695 -0.00213967 1 0 1 1 0 0 +EDGE2 7599 7598 -1.02363 -0.0558849 -0.0207737 1 0 1 1 0 0 +EDGE2 7600 7599 -0.965334 0.00943863 -0.0120095 1 0 1 1 0 0 +EDGE2 7601 7600 -1.06624 0.00145115 1.54363 1 0 1 1 0 0 +EDGE2 7602 7601 -0.984018 0.0601472 -0.0062585 1 0 1 1 0 0 +EDGE2 7603 7602 -0.935763 0.0161399 -0.0305676 1 0 1 1 0 0 +EDGE2 7604 7603 -0.957182 0.0490393 0.00304448 1 0 1 1 0 0 +EDGE2 7605 7604 -0.961744 0.0670812 -0.0438224 1 0 1 1 0 0 +EDGE2 7606 7605 -1.07485 -0.0231511 -1.5675 1 0 1 1 0 0 +EDGE2 7607 7606 -0.993916 -0.0461874 -0.00979683 1 0 1 1 0 0 +EDGE2 7608 7607 -0.967559 0.0296598 -0.026852 1 0 1 1 0 0 +EDGE2 7609 7608 -0.979864 -0.0196866 0.0427352 1 0 1 1 0 0 +EDGE2 7610 7609 -0.978988 0.0344291 -0.0134732 1 0 1 1 0 0 +EDGE2 7611 7610 -1.00958 -0.066355 -1.56247 1 0 1 1 0 0 +EDGE2 7612 7611 -0.903064 -0.00572682 -0.0166644 1 0 1 1 0 0 +EDGE2 7613 7612 -0.935669 -0.0403932 -0.0190786 1 0 1 1 0 0 +EDGE2 7614 7613 -1.0644 -0.083218 -0.0256736 1 0 1 1 0 0 +EDGE2 7615 7614 -0.95278 -0.00756039 -0.000742325 1 0 1 1 0 0 +EDGE2 7616 7615 -0.970445 -0.043688 -1.56726 1 0 1 1 0 0 +EDGE2 7617 7616 -0.949312 0.0529364 -0.00333922 1 0 1 1 0 0 +EDGE2 7618 7617 -0.98301 0.0569665 0.0350629 1 0 1 1 0 0 +EDGE2 7619 7600 0.980742 0.00533061 -3.1412 1 0 1 1 0 0 +EDGE2 7619 7618 -0.973446 0.0284806 -0.00716511 1 0 1 1 0 0 +EDGE2 7620 7599 0.943879 -0.00446807 -3.13753 1 0 1 1 0 0 +EDGE2 7620 7600 -0.0872049 -0.0217757 -3.1462 1 0 1 1 0 0 +EDGE2 7620 7619 -1.0213 -0.0307399 0.0456589 1 0 1 1 0 0 +EDGE2 7620 7601 -0.0267523 0.985478 1.61708 1 0 1 1 0 0 +EDGE2 7621 7600 -1.00835 0.00151336 1.55737 1 0 1 1 0 0 +EDGE2 7621 7620 -1.02127 -0.0204576 -1.56237 1 0 1 1 0 0 +EDGE2 7621 7602 0.956056 -0.0278823 0.0149401 1 0 1 1 0 0 +EDGE2 7621 7601 -0.0297732 -0.0624316 0.00899577 1 0 1 1 0 0 +EDGE2 7622 7602 -0.00109041 -0.0502857 -0.0215782 1 0 1 1 0 0 +EDGE2 7622 7601 -0.999902 -0.00168592 0.0012047 1 0 1 1 0 0 +EDGE2 7622 7621 -0.915226 -0.0163552 0.000854006 1 0 1 1 0 0 +EDGE2 7622 7603 0.975486 -0.0220251 0.0014637 1 0 1 1 0 0 +EDGE2 7623 7602 -1.00403 0.0272156 -0.02383 1 0 1 1 0 0 +EDGE2 7623 7622 -1.08303 -0.0349042 0.00741458 1 0 1 1 0 0 +EDGE2 7623 7603 -0.0810158 -0.00127992 0.0259797 1 0 1 1 0 0 +EDGE2 7623 7604 1.01985 -0.00522136 -0.0335072 1 0 1 1 0 0 +EDGE2 7624 7603 -0.936693 0.0597055 0.020784 1 0 1 1 0 0 +EDGE2 7624 7623 -0.944971 0.0454887 0.00928967 1 0 1 1 0 0 +EDGE2 7624 7604 -0.0460448 -0.0102741 -0.000783927 1 0 1 1 0 0 +EDGE2 7624 7605 0.952136 0.0121521 0.000716217 1 0 1 1 0 0 +EDGE2 7625 7624 -0.973134 -0.0502048 -0.0107801 1 0 1 1 0 0 +EDGE2 7625 7604 -1.01258 0.0274258 -0.00430572 1 0 1 1 0 0 +EDGE2 7625 7606 -0.0630983 1.05709 1.59414 1 0 1 1 0 0 +EDGE2 7625 7605 -0.0268452 -0.0135761 -0.00935063 1 0 1 1 0 0 +EDGE2 7626 7625 -0.913883 -0.0494957 1.56705 1 0 1 1 0 0 +EDGE2 7626 7605 -0.99951 -0.0842192 1.57875 1 0 1 1 0 0 +EDGE2 7627 7626 -1.01482 -0.101998 -0.00294362 1 0 1 1 0 0 +EDGE2 7628 7627 -1.01187 0.0268844 0.0300085 1 0 1 1 0 0 +EDGE2 7629 7370 0.97863 0.0134016 -3.1226 1 0 1 1 0 0 +EDGE2 7629 7190 0.97651 -0.0433074 -3.16516 1 0 1 1 0 0 +EDGE2 7629 7628 -0.994583 0.00258724 -0.00162698 1 0 1 1 0 0 +EDGE2 7630 7369 1.02168 -0.000787164 -3.18276 1 0 1 1 0 0 +EDGE2 7630 7189 0.937679 0.0825449 -3.12992 1 0 1 1 0 0 +EDGE2 7630 7370 -0.043238 -0.0521915 -3.16691 1 0 1 1 0 0 +EDGE2 7630 7371 0.0133106 -0.946467 -1.59694 1 0 1 1 0 0 +EDGE2 7630 7190 0.0525038 -0.0045742 -3.15895 1 0 1 1 0 0 +EDGE2 7630 7629 -1.11606 -0.0111418 0.0267348 1 0 1 1 0 0 +EDGE2 7630 7191 0.0176589 1.05181 1.55298 1 0 1 1 0 0 +EDGE2 7631 7370 -1.04209 0.0209783 -1.56003 1 0 1 1 0 0 +EDGE2 7631 7372 0.976747 -0.0327184 -0.0182908 1 0 1 1 0 0 +EDGE2 7631 7371 0.0314501 -0.0638881 0.017786 1 0 1 1 0 0 +EDGE2 7631 7630 -1.02808 0.00148422 1.61501 1 0 1 1 0 0 +EDGE2 7631 7190 -0.88134 -0.0301445 -1.58791 1 0 1 1 0 0 +EDGE2 7632 7373 1.01527 -0.0132033 -0.00510325 1 0 1 1 0 0 +EDGE2 7632 7631 -1.07778 -0.056485 0.0383488 1 0 1 1 0 0 +EDGE2 7632 7372 -0.000791947 -0.0309149 0.00587743 1 0 1 1 0 0 +EDGE2 7632 7371 -0.937763 -0.0755957 0.00131517 1 0 1 1 0 0 +EDGE2 7633 7374 0.923891 -0.0224906 0.0451883 1 0 1 1 0 0 +EDGE2 7633 7373 -0.0112613 -0.00246759 0.0282748 1 0 1 1 0 0 +EDGE2 7633 7372 -0.971176 0.00935412 -0.0101783 1 0 1 1 0 0 +EDGE2 7633 7632 -1.05177 0.0534933 -0.00388629 1 0 1 1 0 0 +EDGE2 7634 7375 1.01491 0.0196326 0.0156671 1 0 1 1 0 0 +EDGE2 7634 7595 1.00041 0.0227413 -3.13552 1 0 1 1 0 0 +EDGE2 7634 7374 -0.0844636 -0.0156494 -0.0105146 1 0 1 1 0 0 +EDGE2 7634 7373 -0.993036 -0.0165646 0.00665774 1 0 1 1 0 0 +EDGE2 7634 7633 -0.940714 0.0264179 0.0268777 1 0 1 1 0 0 +EDGE2 7635 7594 0.968211 0.00395031 -3.14195 1 0 1 1 0 0 +EDGE2 7635 7376 -0.0467803 0.99187 1.5657 1 0 1 1 0 0 +EDGE2 7635 7596 -0.0869019 -0.989841 -1.56529 1 0 1 1 0 0 +EDGE2 7635 7375 -0.0192977 0.053506 -0.00619238 1 0 1 1 0 0 +EDGE2 7635 7595 0.0548123 0.0193611 -3.14113 1 0 1 1 0 0 +EDGE2 7635 7634 -0.954111 -0.052202 -0.00424214 1 0 1 1 0 0 +EDGE2 7635 7374 -1.03494 0.0120742 0.021427 1 0 1 1 0 0 +EDGE2 7636 7596 -0.00237743 0.0395097 -0.0263112 1 0 1 1 0 0 +EDGE2 7636 7375 -1.02914 -0.112468 1.5612 1 0 1 1 0 0 +EDGE2 7636 7595 -1.05872 0.078294 -1.56704 1 0 1 1 0 0 +EDGE2 7636 7635 -1.08679 0.0198616 1.56627 1 0 1 1 0 0 +EDGE2 7636 7597 0.938833 -0.026741 0.00229021 1 0 1 1 0 0 +EDGE2 7637 7596 -0.953147 -0.027022 0.0257012 1 0 1 1 0 0 +EDGE2 7637 7636 -0.952641 -0.0231422 -0.0015416 1 0 1 1 0 0 +EDGE2 7637 7597 0.012731 0.0946443 -0.0130114 1 0 1 1 0 0 +EDGE2 7637 7598 1.04621 -0.0249052 0.0136427 1 0 1 1 0 0 +EDGE2 7638 7597 -0.98854 -0.0267542 -0.0317157 1 0 1 1 0 0 +EDGE2 7638 7637 -0.972718 0.0749373 -0.0244425 1 0 1 1 0 0 +EDGE2 7638 7598 -0.0328039 0.0735137 0.0229188 1 0 1 1 0 0 +EDGE2 7638 7599 0.969346 -0.0189583 -0.0103997 1 0 1 1 0 0 +EDGE2 7639 7638 -0.992004 0.0114358 0.0226311 1 0 1 1 0 0 +EDGE2 7639 7598 -0.933326 -0.0288549 0.0207104 1 0 1 1 0 0 +EDGE2 7639 7599 -0.0199287 0.0609845 0.0199497 1 0 1 1 0 0 +EDGE2 7639 7600 0.941648 -0.0241324 0.011455 1 0 1 1 0 0 +EDGE2 7639 7620 1.02268 -0.0602966 -3.1661 1 0 1 1 0 0 +EDGE2 7640 7639 -0.941271 0.0295078 0.00942691 1 0 1 1 0 0 +EDGE2 7640 7599 -0.928726 0.0260937 -0.0169057 1 0 1 1 0 0 +EDGE2 7640 7600 0.111947 -0.0214875 0.0320076 1 0 1 1 0 0 +EDGE2 7640 7620 0.0927497 0.0208246 -3.11819 1 0 1 1 0 0 +EDGE2 7640 7619 1.11024 0.0176599 -3.14103 1 0 1 1 0 0 +EDGE2 7640 7601 0.023197 -0.958692 -1.58661 1 0 1 1 0 0 +EDGE2 7640 7621 -0.0331252 -1.02721 -1.54691 1 0 1 1 0 0 +EDGE2 7641 7600 -1.00865 0.10994 -1.60736 1 0 1 1 0 0 +EDGE2 7641 7640 -0.955965 -0.0481801 -1.55121 1 0 1 1 0 0 +EDGE2 7641 7620 -1.01159 -0.00399136 1.56692 1 0 1 1 0 0 +EDGE2 7642 7641 -0.9876 0.00144366 -0.0160954 1 0 1 1 0 0 +EDGE2 7643 7642 -0.980482 -0.0498906 0.028872 1 0 1 1 0 0 +EDGE2 7644 7643 -0.958591 -0.0234323 0.0136217 1 0 1 1 0 0 +EDGE2 7645 7644 -1.00076 -0.0466427 -0.014135 1 0 1 1 0 0 +EDGE2 7646 7645 -1.01029 0.0579536 1.55587 1 0 1 1 0 0 +EDGE2 7647 7646 -0.995185 -0.0249348 0.0304577 1 0 1 1 0 0 +EDGE2 7648 7647 -0.95813 -0.0492409 -0.0337741 1 0 1 1 0 0 +EDGE2 7649 7648 -0.989923 0.052787 0.0136476 1 0 1 1 0 0 +EDGE2 7650 7649 -0.993747 0.0964339 -0.0208617 1 0 1 1 0 0 +EDGE2 7651 7650 -0.992979 -1.15577e-05 -1.56121 1 0 1 1 0 0 +EDGE2 7652 7651 -0.974913 -0.0292856 -0.00968415 1 0 1 1 0 0 +EDGE2 7653 7652 -1.0195 0.0113618 -0.00254018 1 0 1 1 0 0 +EDGE2 7654 7653 -0.992604 0.0150698 -0.0331273 1 0 1 1 0 0 +EDGE2 7655 7654 -1.0545 -0.000241092 -0.0196502 1 0 1 1 0 0 +EDGE2 7656 7655 -0.945166 -0.0448567 1.57737 1 0 1 1 0 0 +EDGE2 7657 7656 -1.02491 -0.0360306 0.0160194 1 0 1 1 0 0 +EDGE2 7658 7657 -1.06196 -0.0310257 -0.00141744 1 0 1 1 0 0 +EDGE2 7659 7658 -0.991953 0.0579358 -0.0062787 1 0 1 1 0 0 +EDGE2 7659 6360 0.985226 0.032002 -3.1203 1 0 1 1 0 0 +EDGE2 7660 7659 -1.05566 0.0515491 0.0254965 1 0 1 1 0 0 +EDGE2 7660 6360 0.0308701 0.0784035 -3.14962 1 0 1 1 0 0 +EDGE2 7660 6359 1.13685 0.0165921 -3.16416 1 0 1 1 0 0 +EDGE2 7660 6361 -0.0234362 -0.989149 -1.56595 1 0 1 1 0 0 +EDGE2 7661 7660 -0.980598 -0.0307955 1.52553 1 0 1 1 0 0 +EDGE2 7661 6360 -0.972569 -0.0797293 -1.56134 1 0 1 1 0 0 +EDGE2 7661 6361 -0.0407203 0.0528141 0.0385949 1 0 1 1 0 0 +EDGE2 7661 6362 1.0315 0.0213683 -0.0112574 1 0 1 1 0 0 +EDGE2 7662 6361 -1.08142 -0.0286581 0.00206391 1 0 1 1 0 0 +EDGE2 7662 7661 -1.03371 -0.0412713 -0.00843649 1 0 1 1 0 0 +EDGE2 7662 6362 -0.0119714 0.0643592 0.0192241 1 0 1 1 0 0 +EDGE2 7662 6363 1.05379 -0.100134 -0.040896 1 0 1 1 0 0 +EDGE2 7663 6362 -1.05646 0.0450209 0.0177328 1 0 1 1 0 0 +EDGE2 7663 7662 -0.993158 0.0118097 -0.0117039 1 0 1 1 0 0 +EDGE2 7663 6363 -0.0357642 0.0382168 0.0138973 1 0 1 1 0 0 +EDGE2 7663 6364 1.03555 -0.0632013 -0.0129444 1 0 1 1 0 0 +EDGE2 7664 6363 -0.98651 -0.0576213 0.00502702 1 0 1 1 0 0 +EDGE2 7664 7663 -0.951235 -0.0410956 0.00898705 1 0 1 1 0 0 +EDGE2 7664 6364 0.0993514 0.06506 -0.0263602 1 0 1 1 0 0 +EDGE2 7664 6365 0.999912 0.0122441 -0.00896125 1 0 1 1 0 0 +EDGE2 7665 6364 -0.965618 0.0371847 -0.0104658 1 0 1 1 0 0 +EDGE2 7665 7664 -0.999048 0.0491001 -0.00957413 1 0 1 1 0 0 +EDGE2 7665 6366 -0.0126367 0.897136 1.55871 1 0 1 1 0 0 +EDGE2 7665 6365 0.0100363 0.0824185 0.0143681 1 0 1 1 0 0 +EDGE2 7666 7665 -1.04945 -0.0107858 -1.58596 1 0 1 1 0 0 +EDGE2 7666 6366 -0.00449757 -0.043045 0.0209419 1 0 1 1 0 0 +EDGE2 7666 6365 -0.979981 -0.096106 -1.56866 1 0 1 1 0 0 +EDGE2 7666 6367 1.07593 0.0418714 0.0396145 1 0 1 1 0 0 +EDGE2 7667 6366 -0.969359 0.0236495 -0.00994078 1 0 1 1 0 0 +EDGE2 7667 7666 -1.02062 0.0233829 -0.0138951 1 0 1 1 0 0 +EDGE2 7667 6367 0.0835166 -0.0213415 0.00924918 1 0 1 1 0 0 +EDGE2 7667 6368 1.05256 0.000956416 -0.0101103 1 0 1 1 0 0 +EDGE2 7668 7667 -1.00376 0.00400519 -0.000718252 1 0 1 1 0 0 +EDGE2 7668 6367 -0.987059 -0.0777795 0.0196086 1 0 1 1 0 0 +EDGE2 7668 6368 -0.00938106 -0.041528 0.00490261 1 0 1 1 0 0 +EDGE2 7668 6369 1.02443 0.105418 -0.0171777 1 0 1 1 0 0 +EDGE2 7669 7668 -0.980991 -0.0883509 -0.00948099 1 0 1 1 0 0 +EDGE2 7669 6368 -0.918264 -0.033825 0.00580037 1 0 1 1 0 0 +EDGE2 7669 6369 -0.0133251 0.0537659 0.00125743 1 0 1 1 0 0 +EDGE2 7669 6370 0.988764 0.0835904 -0.000262444 1 0 1 1 0 0 +EDGE2 7670 7669 -0.981912 0.0302391 -0.00758617 1 0 1 1 0 0 +EDGE2 7670 6369 -0.95629 -0.0454539 0.00523079 1 0 1 1 0 0 +EDGE2 7670 6371 -0.00368345 1.07143 1.53976 1 0 1 1 0 0 +EDGE2 7670 6370 -0.0407601 0.0098845 0.0400333 1 0 1 1 0 0 +EDGE2 7671 6371 -0.0193988 -0.0108727 0.0153235 1 0 1 1 0 0 +EDGE2 7671 6372 1.08067 0.0953129 0.0322219 1 0 1 1 0 0 +EDGE2 7671 6370 -0.990129 -0.0385948 -1.56825 1 0 1 1 0 0 +EDGE2 7671 7670 -0.982446 -0.020322 -1.51754 1 0 1 1 0 0 +EDGE2 7672 6373 0.961239 -0.0195557 -0.0229182 1 0 1 1 0 0 +EDGE2 7672 6371 -0.995222 -0.0218693 0.0247019 1 0 1 1 0 0 +EDGE2 7672 7671 -0.963137 -0.0297736 -0.00389556 1 0 1 1 0 0 +EDGE2 7672 6372 0.0218556 0.0748671 0.00299517 1 0 1 1 0 0 +EDGE2 7673 6374 0.953599 -0.0533542 0.0561734 1 0 1 1 0 0 +EDGE2 7673 6373 -0.00867881 -0.0182445 0.00567389 1 0 1 1 0 0 +EDGE2 7673 7672 -1.06773 -0.00638071 0.0178145 1 0 1 1 0 0 +EDGE2 7673 6372 -1.00588 0.054324 0.00819567 1 0 1 1 0 0 +EDGE2 7674 7673 -1.02568 -0.00554773 -0.0165824 1 0 1 1 0 0 +EDGE2 7674 6355 0.964984 -0.0913254 -3.14658 1 0 1 1 0 0 +EDGE2 7674 6375 1.07006 0.0201353 -0.00747602 1 0 1 1 0 0 +EDGE2 7674 6374 0.0387774 -0.0977528 0.0114374 1 0 1 1 0 0 +EDGE2 7674 6373 -0.973877 0.00411248 -0.0181154 1 0 1 1 0 0 +EDGE2 7675 6356 0.0579849 0.960723 1.56 1 0 1 1 0 0 +EDGE2 7675 6354 0.942408 0.0165488 -3.18496 1 0 1 1 0 0 +EDGE2 7675 7674 -1.03907 0.0312761 0.00360374 1 0 1 1 0 0 +EDGE2 7675 6355 0.0332574 -0.123886 -3.12179 1 0 1 1 0 0 +EDGE2 7675 6375 -0.0273091 -0.00348535 -0.0263966 1 0 1 1 0 0 +EDGE2 7675 6374 -0.963766 0.0111125 0.040317 1 0 1 1 0 0 +EDGE2 7675 6376 0.0347 -1.00537 -1.57412 1 0 1 1 0 0 +EDGE2 7676 6357 1.00742 -0.034892 0.0402414 1 0 1 1 0 0 +EDGE2 7676 6356 0.0741676 -0.0159846 -0.00613883 1 0 1 1 0 0 +EDGE2 7676 7675 -0.930929 0.000611964 -1.59639 1 0 1 1 0 0 +EDGE2 7676 6355 -1.00987 0.00763241 1.6034 1 0 1 1 0 0 +EDGE2 7676 6375 -0.954837 0.012686 -1.56861 1 0 1 1 0 0 +EDGE2 7677 6358 1.07871 -0.0754313 0.00218542 1 0 1 1 0 0 +EDGE2 7677 7676 -0.982999 0.00154815 -0.023683 1 0 1 1 0 0 +EDGE2 7677 6357 -0.0211799 0.0161365 0.0248255 1 0 1 1 0 0 +EDGE2 7677 6356 -1.03084 -0.00136337 -0.0219177 1 0 1 1 0 0 +EDGE2 7678 6359 0.987483 -0.103009 0.0117953 1 0 1 1 0 0 +EDGE2 7678 6358 0.00276803 0.04139 -0.0315898 1 0 1 1 0 0 +EDGE2 7678 6357 -0.976595 -0.00493014 -0.0162391 1 0 1 1 0 0 +EDGE2 7678 7677 -0.985669 -0.125237 0.0227941 1 0 1 1 0 0 +EDGE2 7679 7660 0.996397 -0.0454923 -3.13717 1 0 1 1 0 0 +EDGE2 7679 6360 0.99691 -0.0207649 0.0154067 1 0 1 1 0 0 +EDGE2 7679 7678 -1.01351 0.0262103 0.00939231 1 0 1 1 0 0 +EDGE2 7679 6359 0.0515067 0.0226564 -0.01181 1 0 1 1 0 0 +EDGE2 7679 6358 -1.03567 0.023201 0.0249186 1 0 1 1 0 0 +EDGE2 7680 7659 1.04011 0.00485439 -3.14677 1 0 1 1 0 0 +EDGE2 7680 7660 0.0299882 -0.103938 -3.10033 1 0 1 1 0 0 +EDGE2 7680 6360 -0.107115 0.0676865 0.00157856 1 0 1 1 0 0 +EDGE2 7680 6359 -0.95811 -0.0294868 0.0272448 1 0 1 1 0 0 +EDGE2 7680 7679 -1.00918 -0.0204691 -0.0210449 1 0 1 1 0 0 +EDGE2 7680 6361 -0.0451564 0.98404 1.5902 1 0 1 1 0 0 +EDGE2 7680 7661 -0.015895 0.943938 1.55259 1 0 1 1 0 0 +EDGE2 7681 7660 -1.05574 -0.0104648 1.58961 1 0 1 1 0 0 +EDGE2 7681 7680 -1.01016 -0.0843102 -1.53708 1 0 1 1 0 0 +EDGE2 7681 6360 -1.02579 0.0570816 -1.55613 1 0 1 1 0 0 +EDGE2 7681 6361 -0.0432807 0.0138409 0.00954591 1 0 1 1 0 0 +EDGE2 7681 7661 -0.0289971 0.0419658 0.0480319 1 0 1 1 0 0 +EDGE2 7681 6362 1.00804 -0.00823969 0.00438268 1 0 1 1 0 0 +EDGE2 7681 7662 1.00603 -0.0458894 0.0155747 1 0 1 1 0 0 +EDGE2 7682 6361 -1.01438 -0.0271905 0.0355105 1 0 1 1 0 0 +EDGE2 7682 7661 -1.00889 0.0274545 -0.0149072 1 0 1 1 0 0 +EDGE2 7682 7681 -1.00811 -0.0145986 0.0135016 1 0 1 1 0 0 +EDGE2 7682 6362 0.0428098 0.07283 -0.00729966 1 0 1 1 0 0 +EDGE2 7682 7662 0.0111272 -0.00180128 -0.0380192 1 0 1 1 0 0 +EDGE2 7682 6363 1.0607 -0.0983399 -0.0144315 1 0 1 1 0 0 +EDGE2 7682 7663 1.01084 0.0747451 -0.0076305 1 0 1 1 0 0 +EDGE2 7683 7682 -0.933521 -0.000308358 -0.0128479 1 0 1 1 0 0 +EDGE2 7683 6362 -0.959404 -0.0438282 0.0189871 1 0 1 1 0 0 +EDGE2 7683 7662 -0.913392 -0.0255219 0.0167599 1 0 1 1 0 0 +EDGE2 7683 6363 -0.0726682 0.00729486 -0.0155845 1 0 1 1 0 0 +EDGE2 7683 7663 0.0273994 0.0647864 -0.00624262 1 0 1 1 0 0 +EDGE2 7683 6364 0.976768 0.0232358 -0.013518 1 0 1 1 0 0 +EDGE2 7683 7664 0.964805 -0.0135065 -0.00961703 1 0 1 1 0 0 +EDGE2 7684 7665 0.969316 -0.00882832 0.0315065 1 0 1 1 0 0 +EDGE2 7684 6363 -1.05133 0.102654 0.0436152 1 0 1 1 0 0 +EDGE2 7684 7663 -1.07459 -0.0125376 -0.00404754 1 0 1 1 0 0 +EDGE2 7684 7683 -1.00843 0.0451912 0.00971697 1 0 1 1 0 0 +EDGE2 7684 6364 0.0198466 0.0719925 0.001284 1 0 1 1 0 0 +EDGE2 7684 7664 0.0211975 -0.0372998 0.0099568 1 0 1 1 0 0 +EDGE2 7684 6365 0.944219 0.0205086 -0.0222298 1 0 1 1 0 0 +EDGE2 7685 7665 0.0585163 0.00221211 0.00998142 1 0 1 1 0 0 +EDGE2 7685 7684 -1.01837 0.0393665 0.00276375 1 0 1 1 0 0 +EDGE2 7685 6364 -1.04027 0.0446287 -0.0212856 1 0 1 1 0 0 +EDGE2 7685 7664 -0.964297 -0.000528228 -0.00801613 1 0 1 1 0 0 +EDGE2 7685 6366 -0.0546536 0.965508 1.58322 1 0 1 1 0 0 +EDGE2 7685 6365 0.0439759 0.0629759 0.0163422 1 0 1 1 0 0 +EDGE2 7685 7666 -0.0555528 0.967008 1.59225 1 0 1 1 0 0 +EDGE2 7686 7665 -0.983366 0.0621989 -1.56646 1 0 1 1 0 0 +EDGE2 7686 7685 -1.06006 -0.0441083 -1.56419 1 0 1 1 0 0 +EDGE2 7686 6366 -0.0557462 0.00482818 0.00924836 1 0 1 1 0 0 +EDGE2 7686 6365 -1.02883 -0.0649534 -1.5605 1 0 1 1 0 0 +EDGE2 7686 7666 0.0155806 0.0176677 -0.0333804 1 0 1 1 0 0 +EDGE2 7686 7667 1.00074 0.0784865 -0.000658326 1 0 1 1 0 0 +EDGE2 7686 6367 1.02006 -0.0900361 -0.00730677 1 0 1 1 0 0 +EDGE2 7687 6366 -0.989373 -0.00570785 -0.0139701 1 0 1 1 0 0 +EDGE2 7687 7686 -0.955741 0.0537647 0.0411806 1 0 1 1 0 0 +EDGE2 7687 7666 -0.914778 0.00602185 0.0158099 1 0 1 1 0 0 +EDGE2 7687 7667 0.0429445 -0.0617533 -0.0165091 1 0 1 1 0 0 +EDGE2 7687 6367 -0.035099 0.0413063 -0.00268889 1 0 1 1 0 0 +EDGE2 7687 7668 0.925563 -0.0575024 0.00843365 1 0 1 1 0 0 +EDGE2 7687 6368 0.964986 -0.106605 0.0291853 1 0 1 1 0 0 +EDGE2 7688 7667 -0.999661 0.0246457 -0.00290509 1 0 1 1 0 0 +EDGE2 7688 7687 -0.986869 -0.0501935 0.00476245 1 0 1 1 0 0 +EDGE2 7688 6367 -0.94819 0.0674125 -0.00281064 1 0 1 1 0 0 +EDGE2 7688 7668 0.0222647 0.110607 -0.00411282 1 0 1 1 0 0 +EDGE2 7688 6368 -0.0240368 -0.0529897 -0.00452819 1 0 1 1 0 0 +EDGE2 7688 7669 0.922415 -0.0580651 0.0123523 1 0 1 1 0 0 +EDGE2 7688 6369 1.03153 0.0416782 0.0179379 1 0 1 1 0 0 +EDGE2 7689 7668 -1.00055 0.00106939 -0.00217872 1 0 1 1 0 0 +EDGE2 7689 7688 -1.10961 -0.0596616 0.0264862 1 0 1 1 0 0 +EDGE2 7689 6368 -1.07646 -0.0140805 0.0196083 1 0 1 1 0 0 +EDGE2 7689 7669 -0.00310439 -0.0993548 -0.00360926 1 0 1 1 0 0 +EDGE2 7689 6369 0.00346019 -0.00790744 0.00650462 1 0 1 1 0 0 +EDGE2 7689 6370 1.02655 0.0119099 -0.00122454 1 0 1 1 0 0 +EDGE2 7689 7670 1.00953 0.0227439 0.0171554 1 0 1 1 0 0 +EDGE2 7690 7669 -1.00475 0.0510629 -0.0198558 1 0 1 1 0 0 +EDGE2 7690 7689 -0.912486 -0.0399989 0.004968 1 0 1 1 0 0 +EDGE2 7690 6369 -0.953007 -0.00353515 0.00508696 1 0 1 1 0 0 +EDGE2 7690 6371 0.0434239 1.04884 1.53427 1 0 1 1 0 0 +EDGE2 7690 7671 0.0900413 1.00727 1.58213 1 0 1 1 0 0 +EDGE2 7690 6370 -0.0292116 0.0715546 0.010875 1 0 1 1 0 0 +EDGE2 7690 7670 0.00675786 0.000504513 -0.0047329 1 0 1 1 0 0 +EDGE2 7691 7690 -0.984702 0.0279231 1.58279 1 0 1 1 0 0 +EDGE2 7691 6370 -1.03279 0.0190335 1.59452 1 0 1 1 0 0 +EDGE2 7691 7670 -1.02291 -0.0372868 1.6072 1 0 1 1 0 0 +EDGE2 7692 7691 -1.06197 0.0155334 -0.0300349 1 0 1 1 0 0 +EDGE2 7693 7692 -0.955655 0.00377879 -0.0134242 1 0 1 1 0 0 +EDGE2 7694 7693 -1.03767 0.0280007 -0.0165078 1 0 1 1 0 0 +EDGE2 7695 7694 -0.88587 0.0310084 -0.0360798 1 0 1 1 0 0 +EDGE2 7696 7695 -1.03027 -0.0365373 1.56066 1 0 1 1 0 0 +EDGE2 7697 7696 -0.99418 0.0228172 -0.018529 1 0 1 1 0 0 +EDGE2 7698 7697 -0.916859 -0.0138569 0.00300929 1 0 1 1 0 0 +EDGE2 7699 7698 -0.993921 0.0325946 0.0301985 1 0 1 1 0 0 +EDGE2 7700 7699 -1.01525 0.0944166 0.0251476 1 0 1 1 0 0 +EDGE2 7701 7700 -1.0319 -0.0229553 -1.54533 1 0 1 1 0 0 +EDGE2 7702 7701 -1.02639 0.0403098 -0.00171555 1 0 1 1 0 0 +EDGE2 7703 7702 -0.970983 0.0505588 -0.0118202 1 0 1 1 0 0 +EDGE2 7704 7703 -0.991119 -0.0667184 -0.00810596 1 0 1 1 0 0 +EDGE2 7705 7704 -0.945882 -0.0020353 -0.00776999 1 0 1 1 0 0 +EDGE2 7706 7705 -1.00213 -0.0389188 -1.57685 1 0 1 1 0 0 +EDGE2 7707 7706 -1.00341 0.0607614 -0.0497035 1 0 1 1 0 0 +EDGE2 7708 7707 -1.01238 -0.0248675 0.0230084 1 0 1 1 0 0 +EDGE2 7709 7708 -1.00758 -0.0779934 -0.0443584 1 0 1 1 0 0 +EDGE2 7710 7709 -0.949949 0.0287772 0.0045069 1 0 1 1 0 0 +EDGE2 7711 7710 -1.09539 -0.0227572 -1.56335 1 0 1 1 0 0 +EDGE2 7712 7711 -0.956806 -0.0264431 0.0279557 1 0 1 1 0 0 +EDGE2 7713 7712 -0.983791 -0.0349029 0.023819 1 0 1 1 0 0 +EDGE2 7714 7695 1.05932 -0.00497213 -3.18116 1 0 1 1 0 0 +EDGE2 7714 7713 -0.961091 -0.0375419 -0.0446809 1 0 1 1 0 0 +EDGE2 7715 7696 -0.0238839 1.10093 1.57658 1 0 1 1 0 0 +EDGE2 7715 7694 1.02372 -0.00847375 -3.16412 1 0 1 1 0 0 +EDGE2 7715 7695 0.0490205 0.038591 -3.09272 1 0 1 1 0 0 +EDGE2 7715 7714 -1.05388 0.0199619 0.0283446 1 0 1 1 0 0 +EDGE2 7716 7697 1.07226 -0.124803 0.00952979 1 0 1 1 0 0 +EDGE2 7716 7696 -0.0168861 0.033335 0.019796 1 0 1 1 0 0 +EDGE2 7716 7715 -1.00151 -0.145851 -1.58403 1 0 1 1 0 0 +EDGE2 7716 7695 -0.962289 -0.0562409 1.57007 1 0 1 1 0 0 +EDGE2 7717 7698 0.978549 0.0441708 0.0173657 1 0 1 1 0 0 +EDGE2 7717 7716 -1.0371 0.0362353 -0.0353315 1 0 1 1 0 0 +EDGE2 7717 7697 -0.00369624 -0.037809 0.029486 1 0 1 1 0 0 +EDGE2 7717 7696 -0.99603 0.0422716 0.0130943 1 0 1 1 0 0 +EDGE2 7718 7717 -1.05121 0.102619 -0.00346472 1 0 1 1 0 0 +EDGE2 7718 7699 1.00223 -0.021274 -0.0351447 1 0 1 1 0 0 +EDGE2 7718 7698 -0.0169237 0.040875 0.0195516 1 0 1 1 0 0 +EDGE2 7718 7697 -0.931201 0.0148515 0.00931934 1 0 1 1 0 0 +EDGE2 7719 7699 -0.0775633 0.0337426 -0.00128249 1 0 1 1 0 0 +EDGE2 7719 7700 0.999192 -0.00328989 0.0257461 1 0 1 1 0 0 +EDGE2 7719 7698 -0.909602 -0.0854403 0.0420149 1 0 1 1 0 0 +EDGE2 7719 7718 -0.982383 -0.0742514 0.0138171 1 0 1 1 0 0 +EDGE2 7720 7699 -1.10176 0.0538208 -0.0353182 1 0 1 1 0 0 +EDGE2 7720 7719 -1.09122 0.031901 0.0234186 1 0 1 1 0 0 +EDGE2 7720 7700 -0.0784618 -0.033398 0.00729803 1 0 1 1 0 0 +EDGE2 7720 7701 -0.0519729 0.925 1.55598 1 0 1 1 0 0 +EDGE2 7721 7700 -1.0256 0.00353755 -1.57584 1 0 1 1 0 0 +EDGE2 7721 7720 -0.948627 -0.0703135 -1.56539 1 0 1 1 0 0 +EDGE2 7721 7701 -0.0550409 -0.0172577 0.00984836 1 0 1 1 0 0 +EDGE2 7721 7702 0.937858 -0.0248423 0.0106359 1 0 1 1 0 0 +EDGE2 7722 7701 -0.979609 -0.0662361 0.0214442 1 0 1 1 0 0 +EDGE2 7722 7721 -0.951266 -0.0803201 -0.0293335 1 0 1 1 0 0 +EDGE2 7722 7702 0.0628464 -0.0250796 -0.0148206 1 0 1 1 0 0 +EDGE2 7722 7703 1.08239 -0.0567825 0.0191401 1 0 1 1 0 0 +EDGE2 7723 7722 -1.09971 0.00856957 0.0183698 1 0 1 1 0 0 +EDGE2 7723 7702 -1.01349 -0.0361411 -0.0150056 1 0 1 1 0 0 +EDGE2 7723 7703 0.0284006 0.0061784 -0.00450005 1 0 1 1 0 0 +EDGE2 7723 7704 1.06993 -0.0170924 0.0466194 1 0 1 1 0 0 +EDGE2 7724 7723 -0.937211 0.00429828 -0.0101078 1 0 1 1 0 0 +EDGE2 7724 7703 -1.03373 -0.0391965 0.0343907 1 0 1 1 0 0 +EDGE2 7724 7704 0.0699759 -0.00517051 0.0592447 1 0 1 1 0 0 +EDGE2 7724 7705 1.08829 0.0317709 -0.00771436 1 0 1 1 0 0 +EDGE2 7725 7724 -0.993457 0.00120231 -0.000409947 1 0 1 1 0 0 +EDGE2 7725 7704 -0.985995 0.0732838 -0.0241066 1 0 1 1 0 0 +EDGE2 7725 7705 0.00167922 -0.000764892 -0.015754 1 0 1 1 0 0 +EDGE2 7725 7706 -0.0537273 0.987524 1.51779 1 0 1 1 0 0 +EDGE2 7726 7725 -1.0475 0.102268 1.55696 1 0 1 1 0 0 +EDGE2 7726 7705 -1.01776 -0.0291204 1.58549 1 0 1 1 0 0 +EDGE2 7727 7726 -0.959152 0.0546254 -0.0276064 1 0 1 1 0 0 +EDGE2 7728 7727 -0.967219 0.00455292 0.0328368 1 0 1 1 0 0 +EDGE2 7729 7610 0.975891 0.016299 -3.13707 1 0 1 1 0 0 +EDGE2 7729 7728 -1.0352 -0.0163356 0.00350086 1 0 1 1 0 0 +EDGE2 7730 7611 -0.0129366 -1.00535 -1.58004 1 0 1 1 0 0 +EDGE2 7730 7610 -0.00421042 -0.0479463 -3.12006 1 0 1 1 0 0 +EDGE2 7730 7609 0.904467 -0.0441601 -3.14275 1 0 1 1 0 0 +EDGE2 7730 7729 -1.06409 0.0445207 0.0076089 1 0 1 1 0 0 +EDGE2 7731 7610 -0.985296 0.0160408 1.55532 1 0 1 1 0 0 +EDGE2 7731 7730 -1.00639 -0.0653786 -1.55277 1 0 1 1 0 0 +EDGE2 7732 7731 -0.935674 -0.0394103 -0.0107518 1 0 1 1 0 0 +EDGE2 7733 7732 -1.03238 0.00619497 -0.009304 1 0 1 1 0 0 +EDGE2 7734 7215 0.955476 -0.00902426 -3.14038 1 0 1 1 0 0 +EDGE2 7734 7733 -0.981087 0.0186684 -0.00315327 1 0 1 1 0 0 +EDGE2 7735 7216 0.0425802 -1.0773 -1.59591 1 0 1 1 0 0 +EDGE2 7735 7215 0.0669729 -0.0456 -3.17777 1 0 1 1 0 0 +EDGE2 7735 7734 -0.980683 0.0035927 -0.00579215 1 0 1 1 0 0 +EDGE2 7735 7214 0.97001 0.0188712 -3.16335 1 0 1 1 0 0 +EDGE2 7736 7217 1.02393 0.00758785 0.0114362 1 0 1 1 0 0 +EDGE2 7736 7216 0.000800753 -0.0754476 -0.0304733 1 0 1 1 0 0 +EDGE2 7736 7215 -0.980516 0.0105909 -1.57349 1 0 1 1 0 0 +EDGE2 7736 7735 -0.980438 0.0508008 1.58424 1 0 1 1 0 0 +EDGE2 7737 7217 0.0277366 0.0328534 -0.000651868 1 0 1 1 0 0 +EDGE2 7737 7218 0.964526 0.0166904 -0.02137 1 0 1 1 0 0 +EDGE2 7737 7736 -0.985288 0.00881557 0.0231264 1 0 1 1 0 0 +EDGE2 7737 7216 -0.945628 -0.0601294 0.0079292 1 0 1 1 0 0 +EDGE2 7738 7217 -1.02414 0.114711 0.0510178 1 0 1 1 0 0 +EDGE2 7738 7219 1.05739 -0.0213698 0.00457014 1 0 1 1 0 0 +EDGE2 7738 7737 -1.00679 0.0156731 0.020059 1 0 1 1 0 0 +EDGE2 7738 7218 0.0232126 -0.0820727 0.00497777 1 0 1 1 0 0 +EDGE2 7739 7200 1.03478 -0.0568142 -3.12963 1 0 1 1 0 0 +EDGE2 7739 7220 0.973854 -0.0440149 -0.0261187 1 0 1 1 0 0 +EDGE2 7739 7738 -1.05264 0.0567116 0.0173465 1 0 1 1 0 0 +EDGE2 7739 7219 0.0128699 0.117129 0.00345343 1 0 1 1 0 0 +EDGE2 7739 7218 -0.938747 0.0701328 -0.00766208 1 0 1 1 0 0 +EDGE2 7740 7199 0.945126 0.00235151 -3.12982 1 0 1 1 0 0 +EDGE2 7740 7201 -0.0244965 1.05556 1.5791 1 0 1 1 0 0 +EDGE2 7740 7200 -0.0847867 0.0216112 -3.14034 1 0 1 1 0 0 +EDGE2 7740 7220 -0.0659394 0.0296598 -0.00132334 1 0 1 1 0 0 +EDGE2 7740 7221 -0.0432255 1.01615 1.59727 1 0 1 1 0 0 +EDGE2 7740 7219 -1.09963 0.0306576 0.0173654 1 0 1 1 0 0 +EDGE2 7740 7739 -0.999663 0.085454 -0.0626825 1 0 1 1 0 0 +EDGE2 7741 7201 -0.0349662 0.0525651 0.000380953 1 0 1 1 0 0 +EDGE2 7741 7740 -1.04891 0.0524447 -1.57062 1 0 1 1 0 0 +EDGE2 7741 7200 -1.07853 -0.0210448 1.57815 1 0 1 1 0 0 +EDGE2 7741 7220 -0.889485 -0.021965 -1.56004 1 0 1 1 0 0 +EDGE2 7741 7221 -0.0618782 0.0308517 -0.00437057 1 0 1 1 0 0 +EDGE2 7741 7202 1.09516 0.0270459 0.0162273 1 0 1 1 0 0 +EDGE2 7741 7222 0.955953 0.000879261 0.00387727 1 0 1 1 0 0 +EDGE2 7742 7201 -0.993697 -0.0146225 0.0190616 1 0 1 1 0 0 +EDGE2 7742 7741 -1.02999 -0.0572696 0.00259787 1 0 1 1 0 0 +EDGE2 7742 7221 -0.991922 0.0151276 0.00291763 1 0 1 1 0 0 +EDGE2 7742 7223 1.01818 -0.00806057 -0.0197844 1 0 1 1 0 0 +EDGE2 7742 7202 0.0539103 -0.0399589 0.00333092 1 0 1 1 0 0 +EDGE2 7742 7222 -0.0466987 -0.0185184 -0.0152743 1 0 1 1 0 0 +EDGE2 7742 7203 0.933076 0.0354277 0.00794984 1 0 1 1 0 0 +EDGE2 7743 7204 0.986412 -0.00722769 -0.00738695 1 0 1 1 0 0 +EDGE2 7743 7223 0.119456 0.0468883 -0.0257671 1 0 1 1 0 0 +EDGE2 7743 7202 -0.924437 -0.0293654 0.017961 1 0 1 1 0 0 +EDGE2 7743 7222 -1.0425 0.0164533 0.0225324 1 0 1 1 0 0 +EDGE2 7743 7742 -0.940872 -0.0684073 -0.00920322 1 0 1 1 0 0 +EDGE2 7743 7203 -0.0151527 -0.0574545 0.00457596 1 0 1 1 0 0 +EDGE2 7743 7224 0.971163 0.000386594 -0.000477482 1 0 1 1 0 0 +EDGE2 7744 7204 0.0710053 -0.00639429 -0.00269791 1 0 1 1 0 0 +EDGE2 7744 7223 -1.08053 -0.0375292 0.00358103 1 0 1 1 0 0 +EDGE2 7744 7743 -0.922644 0.106677 0.00315133 1 0 1 1 0 0 +EDGE2 7744 7203 -1.04052 -0.0216436 0.0133596 1 0 1 1 0 0 +EDGE2 7744 7224 0.0496963 0.0510349 -0.00272914 1 0 1 1 0 0 +EDGE2 7744 7205 1.02121 0.0681416 -0.0471002 1 0 1 1 0 0 +EDGE2 7744 7225 0.976381 -0.047598 -0.00920144 1 0 1 1 0 0 +EDGE2 7745 7204 -0.896662 -0.0151732 0.0442462 1 0 1 1 0 0 +EDGE2 7745 7226 -0.0166159 -0.938049 -1.56082 1 0 1 1 0 0 +EDGE2 7745 7744 -1.00667 -0.0403914 0.040984 1 0 1 1 0 0 +EDGE2 7745 7224 -0.980864 0.0625577 -0.000687648 1 0 1 1 0 0 +EDGE2 7745 7205 -0.0330799 -0.0114834 -0.0302124 1 0 1 1 0 0 +EDGE2 7745 7225 0.0562921 0.0782872 -0.0214169 1 0 1 1 0 0 +EDGE2 7745 7206 -0.0675562 1.04301 1.57213 1 0 1 1 0 0 +EDGE2 7746 7227 0.956448 0.00392678 -0.00523105 1 0 1 1 0 0 +EDGE2 7746 7226 -0.0848328 -0.0226848 -0.0239305 1 0 1 1 0 0 +EDGE2 7746 7205 -1.06405 -0.0200186 1.57161 1 0 1 1 0 0 +EDGE2 7746 7225 -0.939512 0.033638 1.56017 1 0 1 1 0 0 +EDGE2 7746 7745 -0.93994 -0.138758 1.56992 1 0 1 1 0 0 +EDGE2 7747 7228 1.00765 0.011649 0.00933032 1 0 1 1 0 0 +EDGE2 7747 7746 -1.02411 -0.0682539 -0.0266673 1 0 1 1 0 0 +EDGE2 7747 7227 -0.030726 0.0206646 0.0235646 1 0 1 1 0 0 +EDGE2 7747 7226 -1.01295 -0.0180274 0.0313005 1 0 1 1 0 0 +EDGE2 7748 7228 -0.0346699 -0.030565 0.0112516 1 0 1 1 0 0 +EDGE2 7748 7229 0.969346 0.0404487 -0.0150337 1 0 1 1 0 0 +EDGE2 7748 7227 -1.00465 0.0652594 0.0187614 1 0 1 1 0 0 +EDGE2 7748 7747 -0.975971 0.0584359 -0.050659 1 0 1 1 0 0 +EDGE2 7749 7228 -0.992449 0.0817644 -0.00564479 1 0 1 1 0 0 +EDGE2 7749 7229 -0.126153 0.00604955 -0.00591708 1 0 1 1 0 0 +EDGE2 7749 7230 0.888431 0.00136279 -0.0180197 1 0 1 1 0 0 +EDGE2 7749 7748 -0.997453 -0.0333757 0.0160575 1 0 1 1 0 0 +EDGE2 7750 7229 -1.06259 -0.0301909 0.0100613 1 0 1 1 0 0 +EDGE2 7750 7749 -1.02765 -0.100769 -0.0188811 1 0 1 1 0 0 +EDGE2 7750 7230 -0.055337 -0.0131728 -0.00908036 1 0 1 1 0 0 +EDGE2 7750 7231 0.00105493 0.978444 1.55693 1 0 1 1 0 0 +EDGE2 7751 7750 -0.995726 0.0525134 -1.58391 1 0 1 1 0 0 +EDGE2 7751 7230 -1.03447 -0.0655615 -1.582 1 0 1 1 0 0 +EDGE2 7751 7231 0.00491112 -0.0390968 0.0154086 1 0 1 1 0 0 +EDGE2 7751 7232 0.997555 -0.0188548 0.00220348 1 0 1 1 0 0 +EDGE2 7752 7233 0.92352 0.0670989 0.00615636 1 0 1 1 0 0 +EDGE2 7752 7231 -0.973577 -0.0329476 -0.00234274 1 0 1 1 0 0 +EDGE2 7752 7751 -1.01351 -0.0884208 -0.025526 1 0 1 1 0 0 +EDGE2 7752 7232 -0.0414516 -0.00435277 0.00865002 1 0 1 1 0 0 +EDGE2 7753 7233 0.0235931 0.0230281 0.0334732 1 0 1 1 0 0 +EDGE2 7753 7752 -0.993544 0.0273405 -0.0326039 1 0 1 1 0 0 +EDGE2 7753 7232 -0.981086 0.0648098 0.0270957 1 0 1 1 0 0 +EDGE2 7753 7234 0.948994 -0.0106095 -0.00259029 1 0 1 1 0 0 +EDGE2 7754 7233 -1.04818 -0.0366526 0.008173 1 0 1 1 0 0 +EDGE2 7754 7753 -0.98207 -0.0225474 -0.0271853 1 0 1 1 0 0 +EDGE2 7754 7234 0.0320033 0.00578054 -0.00627631 1 0 1 1 0 0 +EDGE2 7754 7235 1.00035 0.040384 -0.0398973 1 0 1 1 0 0 +EDGE2 7755 7236 0.00289515 -0.99118 -1.58177 1 0 1 1 0 0 +EDGE2 7755 7234 -1.00423 0.0740581 -0.0169417 1 0 1 1 0 0 +EDGE2 7755 7754 -0.976171 0.0828631 -0.00276979 1 0 1 1 0 0 +EDGE2 7755 7235 -0.0285734 0.0124359 0.012083 1 0 1 1 0 0 +EDGE2 7756 7237 1.00957 -0.0210893 0.00162537 1 0 1 1 0 0 +EDGE2 7756 7236 0.0116677 0.0702848 0.0123585 1 0 1 1 0 0 +EDGE2 7756 7755 -1.10748 0.0818742 1.60451 1 0 1 1 0 0 +EDGE2 7756 7235 -0.920918 0.0252927 1.56663 1 0 1 1 0 0 +EDGE2 7757 7238 1.01188 0.0204669 0.0145711 1 0 1 1 0 0 +EDGE2 7757 7756 -1.00976 -0.0101547 -0.00423232 1 0 1 1 0 0 +EDGE2 7757 7237 -0.0899523 0.0877021 -0.0195091 1 0 1 1 0 0 +EDGE2 7757 7236 -1.10481 -0.0131407 0.0264288 1 0 1 1 0 0 +EDGE2 7758 7239 1.0236 0.0040112 -0.023296 1 0 1 1 0 0 +EDGE2 7758 7757 -0.978133 -0.00325833 0.030209 1 0 1 1 0 0 +EDGE2 7758 7238 -0.0473564 -0.0933543 0.0124448 1 0 1 1 0 0 +EDGE2 7758 7237 -1.01244 0.0613932 0.0394028 1 0 1 1 0 0 +EDGE2 7759 7240 0.955692 -0.00561711 -0.0274491 1 0 1 1 0 0 +EDGE2 7759 7239 -0.04751 -0.030636 0.00351017 1 0 1 1 0 0 +EDGE2 7759 7758 -1.10756 0.104087 0.00252072 1 0 1 1 0 0 +EDGE2 7759 7238 -1.02756 -0.03578 -0.0141186 1 0 1 1 0 0 +EDGE2 7760 7241 0.00578645 -1.02026 -1.57357 1 0 1 1 0 0 +EDGE2 7760 7240 -0.0445502 0.0134599 0.0145591 1 0 1 1 0 0 +EDGE2 7760 7239 -0.982606 -0.00322809 0.00512832 1 0 1 1 0 0 +EDGE2 7760 7759 -1.02736 -0.0323561 -0.0005747 1 0 1 1 0 0 +EDGE2 7761 7240 -1.02957 0.0127637 -1.62007 1 0 1 1 0 0 +EDGE2 7761 7760 -1.00195 -0.0116793 -1.55022 1 0 1 1 0 0 +EDGE2 7762 7761 -1.05057 0.0261924 0.0334135 1 0 1 1 0 0 +EDGE2 7763 7762 -0.99369 0.0909911 -0.0120339 1 0 1 1 0 0 +EDGE2 7764 7045 1.03474 0.0647598 -3.12744 1 0 1 1 0 0 +EDGE2 7764 7763 -0.94981 -0.0199584 -0.0136275 1 0 1 1 0 0 +EDGE2 7764 7005 1.08539 0.00364128 -3.15288 1 0 1 1 0 0 +EDGE2 7764 7025 0.998742 0.02782 -3.18424 1 0 1 1 0 0 +EDGE2 7765 7046 -0.0189703 -1.09811 -1.53849 1 0 1 1 0 0 +EDGE2 7765 7006 -0.0498204 -0.940322 -1.58096 1 0 1 1 0 0 +EDGE2 7765 7026 0.0476848 -0.949726 -1.58117 1 0 1 1 0 0 +EDGE2 7765 7045 0.0516814 -0.0448403 -3.09426 1 0 1 1 0 0 +EDGE2 7765 7764 -0.938869 -0.0337022 -0.00229252 1 0 1 1 0 0 +EDGE2 7765 7005 -0.0750938 0.0100824 -3.14304 1 0 1 1 0 0 +EDGE2 7765 7025 0.0638372 -0.0742635 -3.15068 1 0 1 1 0 0 +EDGE2 7765 7024 1.0739 0.021282 -3.15282 1 0 1 1 0 0 +EDGE2 7765 7044 0.932333 0.0237736 -3.11304 1 0 1 1 0 0 +EDGE2 7765 7004 0.963881 -0.0835246 -3.15214 1 0 1 1 0 0 +EDGE2 7766 7007 0.949243 0.000608188 -0.000469459 1 0 1 1 0 0 +EDGE2 7766 7047 0.972147 -0.0378778 0.0168693 1 0 1 1 0 0 +EDGE2 7766 7027 1.04315 -0.0422815 0.0172078 1 0 1 1 0 0 +EDGE2 7766 7046 0.0232317 -0.0417432 0.002229 1 0 1 1 0 0 +EDGE2 7766 7006 0.113601 -0.000331322 -0.0170637 1 0 1 1 0 0 +EDGE2 7766 7026 -0.0301514 -0.0130236 -0.0166972 1 0 1 1 0 0 +EDGE2 7766 7045 -0.850848 0.0435267 -1.58431 1 0 1 1 0 0 +EDGE2 7766 7765 -1.05484 -0.0200228 1.60069 1 0 1 1 0 0 +EDGE2 7766 7005 -1.03595 -0.0358971 -1.58474 1 0 1 1 0 0 +EDGE2 7766 7025 -0.994368 -0.00482994 -1.53751 1 0 1 1 0 0 +EDGE2 7767 7007 -0.00766829 0.0420644 0.0214322 1 0 1 1 0 0 +EDGE2 7767 7008 0.96356 -0.0595196 0.0173935 1 0 1 1 0 0 +EDGE2 7767 7048 1.08318 0.0440408 -0.0207988 1 0 1 1 0 0 +EDGE2 7767 7028 1.06863 -0.121595 -0.0288489 1 0 1 1 0 0 +EDGE2 7767 7047 -0.0817757 0.00408474 -0.0352551 1 0 1 1 0 0 +EDGE2 7767 7027 0.0525361 0.0342867 -0.0114043 1 0 1 1 0 0 +EDGE2 7767 7046 -0.934889 0.0630175 -0.0150678 1 0 1 1 0 0 +EDGE2 7767 7766 -0.982858 -0.0520928 0.000598126 1 0 1 1 0 0 +EDGE2 7767 7006 -0.982378 -0.0120134 -0.0561229 1 0 1 1 0 0 +EDGE2 7767 7026 -0.959401 -0.0732746 0.0197785 1 0 1 1 0 0 +EDGE2 7768 7029 0.895515 -0.112255 -0.00108563 1 0 1 1 0 0 +EDGE2 7768 7049 0.980887 0.0676785 -0.0219307 1 0 1 1 0 0 +EDGE2 7768 7009 1.01223 0.00120159 0.000556375 1 0 1 1 0 0 +EDGE2 7768 7007 -0.966104 -0.0114445 0.00829719 1 0 1 1 0 0 +EDGE2 7768 7008 -0.0032766 0.0300091 -0.0318609 1 0 1 1 0 0 +EDGE2 7768 7048 0.0815678 -0.00427694 -0.0411117 1 0 1 1 0 0 +EDGE2 7768 7028 0.00571376 -0.0229692 0.0392331 1 0 1 1 0 0 +EDGE2 7768 7047 -0.99334 0.0631764 -0.0113515 1 0 1 1 0 0 +EDGE2 7768 7767 -0.9761 0.0564811 0.00785938 1 0 1 1 0 0 +EDGE2 7768 7027 -1.00991 0.0502743 -0.0266543 1 0 1 1 0 0 +EDGE2 7769 7010 0.97548 -0.0757705 -0.0224789 1 0 1 1 0 0 +EDGE2 7769 7030 1.09252 0.0809022 0.0253823 1 0 1 1 0 0 +EDGE2 7769 7050 1.03205 0.0265955 -0.00536715 1 0 1 1 0 0 +EDGE2 7769 7029 -0.0545991 0.0161147 0.0074823 1 0 1 1 0 0 +EDGE2 7769 7049 0.0018661 0.00643996 0.00695096 1 0 1 1 0 0 +EDGE2 7769 7009 -0.0244514 -0.0547182 -0.03132 1 0 1 1 0 0 +EDGE2 7769 7008 -0.941094 0.0444207 0.0268734 1 0 1 1 0 0 +EDGE2 7769 7048 -0.976364 0.0508619 -0.0143335 1 0 1 1 0 0 +EDGE2 7769 7768 -0.975473 -0.00621882 -0.0153178 1 0 1 1 0 0 +EDGE2 7769 7028 -0.978684 -0.0174953 -0.00779437 1 0 1 1 0 0 +EDGE2 7770 7051 0.0726011 -0.972444 -1.59718 1 0 1 1 0 0 +EDGE2 7770 7769 -0.95253 -0.0198479 0.00729929 1 0 1 1 0 0 +EDGE2 7770 7010 0.0106013 0.0494372 0.00307436 1 0 1 1 0 0 +EDGE2 7770 7030 -0.0950921 -0.0612331 0.00611745 1 0 1 1 0 0 +EDGE2 7770 7050 -0.0368033 0.0336684 0.00260256 1 0 1 1 0 0 +EDGE2 7770 7029 -0.973869 -0.00645839 -0.00139454 1 0 1 1 0 0 +EDGE2 7770 7049 -1.03268 0.0322421 0.013073 1 0 1 1 0 0 +EDGE2 7770 7009 -0.922072 0.0286204 -0.0169427 1 0 1 1 0 0 +EDGE2 7770 7031 0.00895925 1.00733 1.58173 1 0 1 1 0 0 +EDGE2 7770 7011 0.027958 1.02948 1.56777 1 0 1 1 0 0 +EDGE2 7771 7770 -1.02884 -0.0563881 -1.5728 1 0 1 1 0 0 +EDGE2 7771 7010 -1.00909 0.127035 -1.57332 1 0 1 1 0 0 +EDGE2 7771 7030 -1.03124 -0.0103364 -1.5709 1 0 1 1 0 0 +EDGE2 7771 7050 -1.08195 0.0275775 -1.55435 1 0 1 1 0 0 +EDGE2 7771 7031 -0.0942636 0.0138406 0.0284468 1 0 1 1 0 0 +EDGE2 7771 7011 -0.0475366 -0.099364 0.0148145 1 0 1 1 0 0 +EDGE2 7771 7032 1.06454 0.0288082 0.00262934 1 0 1 1 0 0 +EDGE2 7771 7012 1.01127 -0.116041 0.00499919 1 0 1 1 0 0 +EDGE2 7772 7031 -0.922823 -0.0810916 0.011296 1 0 1 1 0 0 +EDGE2 7772 7771 -0.904704 -0.101119 0.0139749 1 0 1 1 0 0 +EDGE2 7772 7011 -0.970437 -0.0484001 -0.00267814 1 0 1 1 0 0 +EDGE2 7772 7032 0.000694438 -0.027535 0.00207789 1 0 1 1 0 0 +EDGE2 7772 7012 0.0179419 -0.0464236 -0.0183123 1 0 1 1 0 0 +EDGE2 7772 7033 0.994121 -0.0794284 0.0149081 1 0 1 1 0 0 +EDGE2 7772 7013 1.02944 0.0573121 -0.031791 1 0 1 1 0 0 +EDGE2 7773 7032 -1.02191 0.108772 -0.00515878 1 0 1 1 0 0 +EDGE2 7773 7772 -0.961898 0.0693623 0.0256317 1 0 1 1 0 0 +EDGE2 7773 7012 -0.978356 0.0132606 -0.00197207 1 0 1 1 0 0 +EDGE2 7773 7033 0.0639632 -0.0369047 0.005243 1 0 1 1 0 0 +EDGE2 7773 7013 -0.00895248 -0.102097 0.0227025 1 0 1 1 0 0 +EDGE2 7773 7034 1.02955 -0.0181079 -0.00938953 1 0 1 1 0 0 +EDGE2 7773 7014 1.04008 0.0331367 0.0108206 1 0 1 1 0 0 +EDGE2 7774 7033 -0.96119 -0.0316708 0.0154491 1 0 1 1 0 0 +EDGE2 7774 7773 -1.09 -0.0226323 -0.0358774 1 0 1 1 0 0 +EDGE2 7774 7013 -0.999868 -0.0301206 -0.00423228 1 0 1 1 0 0 +EDGE2 7774 7034 -0.0155473 0.0208524 0.0265412 1 0 1 1 0 0 +EDGE2 7774 7014 -0.00827015 -0.0134035 0.0310593 1 0 1 1 0 0 +EDGE2 7774 6995 0.903619 -0.00590881 -3.16769 1 0 1 1 0 0 +EDGE2 7774 7035 1.07315 -0.0188064 -0.00749697 1 0 1 1 0 0 +EDGE2 7774 7015 1.13625 -0.0459506 0.0164493 1 0 1 1 0 0 +EDGE2 7775 7034 -1.05485 -0.0197187 -0.0126556 1 0 1 1 0 0 +EDGE2 7775 7774 -0.945301 0.0447678 -0.0084093 1 0 1 1 0 0 +EDGE2 7775 7014 -1.05028 -0.0416523 -0.00995793 1 0 1 1 0 0 +EDGE2 7775 6995 -0.00595475 0.0290348 -3.14066 1 0 1 1 0 0 +EDGE2 7775 7035 0.00975229 -0.0618943 0.0298374 1 0 1 1 0 0 +EDGE2 7775 7015 0.000202856 -0.0526624 0.0457651 1 0 1 1 0 0 +EDGE2 7775 6994 1.06814 -0.0570817 -3.12134 1 0 1 1 0 0 +EDGE2 7775 7016 -0.0387658 0.937747 1.56425 1 0 1 1 0 0 +EDGE2 7775 7036 0.0249127 0.997709 1.61623 1 0 1 1 0 0 +EDGE2 7775 6996 -0.00551508 1.00296 1.56049 1 0 1 1 0 0 +EDGE2 7776 6995 -0.973255 -0.00991875 1.58041 1 0 1 1 0 0 +EDGE2 7776 7035 -0.986906 0.0329392 -1.5773 1 0 1 1 0 0 +EDGE2 7776 7775 -0.920188 0.0362262 -1.57822 1 0 1 1 0 0 +EDGE2 7776 7015 -0.992564 -0.0186686 -1.55355 1 0 1 1 0 0 +EDGE2 7776 7016 0.0472233 0.0067073 -0.0211021 1 0 1 1 0 0 +EDGE2 7776 7036 -0.0713343 0.0627893 -0.0217716 1 0 1 1 0 0 +EDGE2 7776 6996 -0.0921159 -0.00105161 -0.0229165 1 0 1 1 0 0 +EDGE2 7776 6997 1.05 -0.0272538 0.0344217 1 0 1 1 0 0 +EDGE2 7776 7017 1.00287 -0.0505118 -0.0158263 1 0 1 1 0 0 +EDGE2 7776 7037 1.03394 0.0598933 -0.0238649 1 0 1 1 0 0 +EDGE2 7777 7038 1.04676 0.00295939 -0.0105103 1 0 1 1 0 0 +EDGE2 7777 7016 -0.979262 0.049763 0.0282854 1 0 1 1 0 0 +EDGE2 7777 7036 -0.957428 0.0493426 -0.0167063 1 0 1 1 0 0 +EDGE2 7777 7776 -1.01359 0.0694727 -0.0291 1 0 1 1 0 0 +EDGE2 7777 6996 -1.01875 -0.0409462 0.0289921 1 0 1 1 0 0 +EDGE2 7777 6997 0.0304652 0.0240586 -0.0040408 1 0 1 1 0 0 +EDGE2 7777 7017 -0.0112983 0.0109015 0.04315 1 0 1 1 0 0 +EDGE2 7777 7037 -0.0114037 0.087999 0.0251383 1 0 1 1 0 0 +EDGE2 7777 6998 0.985344 -0.0311645 -0.0282937 1 0 1 1 0 0 +EDGE2 7777 7018 0.930217 0.0078531 0.0189437 1 0 1 1 0 0 +EDGE2 7778 6999 0.938318 0.076671 -0.0200874 1 0 1 1 0 0 +EDGE2 7778 7038 -0.0142059 -0.0130585 -0.0322463 1 0 1 1 0 0 +EDGE2 7778 7777 -1.06131 -0.00677595 -0.025019 1 0 1 1 0 0 +EDGE2 7778 6997 -1.06912 0.108276 0.0293274 1 0 1 1 0 0 +EDGE2 7778 7017 -1.00095 -0.0205889 0.0203743 1 0 1 1 0 0 +EDGE2 7778 7037 -1.07507 0.000294257 -0.00296304 1 0 1 1 0 0 +EDGE2 7778 6998 0.0127841 -0.0130487 -0.018503 1 0 1 1 0 0 +EDGE2 7778 7018 -0.0826197 -0.0861341 -0.012465 1 0 1 1 0 0 +EDGE2 7778 7039 1.03042 0.105231 -0.00186583 1 0 1 1 0 0 +EDGE2 7778 7019 0.973061 0.0307113 0.0248272 1 0 1 1 0 0 +EDGE2 7779 7040 0.984488 -0.0359965 -0.0224024 1 0 1 1 0 0 +EDGE2 7779 6999 0.0444935 -0.0102576 0.0146048 1 0 1 1 0 0 +EDGE2 7779 7038 -0.999023 -0.00244955 0.00295088 1 0 1 1 0 0 +EDGE2 7779 7778 -0.91175 0.0069327 0.010731 1 0 1 1 0 0 +EDGE2 7779 6998 -1.03381 0.0683834 0.00986732 1 0 1 1 0 0 +EDGE2 7779 7018 -1.06831 0.0523535 0.0253107 1 0 1 1 0 0 +EDGE2 7779 7039 0.0112436 0.0363412 -0.018092 1 0 1 1 0 0 +EDGE2 7779 7019 0.0593389 0.0162296 0.0350463 1 0 1 1 0 0 +EDGE2 7779 7000 0.98115 0.0567888 0.0280052 1 0 1 1 0 0 +EDGE2 7779 7020 1.07026 -0.0180709 -0.0139779 1 0 1 1 0 0 +EDGE2 7780 7040 -0.0110935 -0.0713303 -0.0229025 1 0 1 1 0 0 +EDGE2 7780 6999 -1.02687 -0.0196402 -0.033243 1 0 1 1 0 0 +EDGE2 7780 7039 -0.998291 -0.0272073 0.0160118 1 0 1 1 0 0 +EDGE2 7780 7779 -1.04085 -0.025923 -0.0163047 1 0 1 1 0 0 +EDGE2 7780 7019 -0.995526 -0.0340481 -0.0286229 1 0 1 1 0 0 +EDGE2 7780 7041 0.0697932 1.00308 1.55664 1 0 1 1 0 0 +EDGE2 7780 7001 0.0738178 0.939786 1.52753 1 0 1 1 0 0 +EDGE2 7780 7021 -0.00756481 0.916083 1.53765 1 0 1 1 0 0 +EDGE2 7780 7000 -0.0393065 0.0186028 0.00207559 1 0 1 1 0 0 +EDGE2 7780 7020 -0.124014 0.0270847 0.0150487 1 0 1 1 0 0 +EDGE2 7781 7040 -0.93825 -0.00485196 -1.55641 1 0 1 1 0 0 +EDGE2 7781 7042 0.98472 0.0627224 0.0192579 1 0 1 1 0 0 +EDGE2 7781 7041 0.0364132 0.0660144 -0.0153362 1 0 1 1 0 0 +EDGE2 7781 7002 0.967347 0.0420376 0.0127163 1 0 1 1 0 0 +EDGE2 7781 7022 1.06455 0.0723682 -0.0266464 1 0 1 1 0 0 +EDGE2 7781 7001 0.0294903 -0.0670298 -0.012712 1 0 1 1 0 0 +EDGE2 7781 7021 0.0773994 0.00892761 0.0345238 1 0 1 1 0 0 +EDGE2 7781 7780 -1.02735 -0.0133829 -1.59081 1 0 1 1 0 0 +EDGE2 7781 7000 -0.960812 -0.0012774 -1.55412 1 0 1 1 0 0 +EDGE2 7781 7020 -0.940811 -0.00387089 -1.57039 1 0 1 1 0 0 +EDGE2 7782 7042 0.0733826 0.0103221 -0.00218159 1 0 1 1 0 0 +EDGE2 7782 7003 1.03269 -0.00486461 -0.00915445 1 0 1 1 0 0 +EDGE2 7782 7023 1.04743 0.0565201 -0.0108236 1 0 1 1 0 0 +EDGE2 7782 7043 0.866916 0.0268334 0.00396006 1 0 1 1 0 0 +EDGE2 7782 7041 -1.00002 0.0359258 0.00386229 1 0 1 1 0 0 +EDGE2 7782 7002 -0.0431174 -0.0222495 0.0258569 1 0 1 1 0 0 +EDGE2 7782 7022 -0.0682452 0.0394496 0.0186422 1 0 1 1 0 0 +EDGE2 7782 7781 -0.946667 -0.118887 0.0291199 1 0 1 1 0 0 +EDGE2 7782 7001 -0.93957 -0.0117791 -0.0279644 1 0 1 1 0 0 +EDGE2 7782 7021 -1.00966 0.0623016 0.0280637 1 0 1 1 0 0 +EDGE2 7783 7042 -0.964306 0.0717127 -0.00136356 1 0 1 1 0 0 +EDGE2 7783 7024 1.07439 -0.0782876 0.0198856 1 0 1 1 0 0 +EDGE2 7783 7044 1.03394 -0.0668896 -0.0173315 1 0 1 1 0 0 +EDGE2 7783 7004 1.04438 -0.0390794 -0.0099091 1 0 1 1 0 0 +EDGE2 7783 7003 -0.0334687 0.021785 -0.0245288 1 0 1 1 0 0 +EDGE2 7783 7023 0.0601997 0.0091072 -0.0359299 1 0 1 1 0 0 +EDGE2 7783 7043 0.019197 -0.0662845 -0.0194957 1 0 1 1 0 0 +EDGE2 7783 7782 -0.976546 -0.00615407 0.00623023 1 0 1 1 0 0 +EDGE2 7783 7002 -0.963474 -0.00760614 -0.029923 1 0 1 1 0 0 +EDGE2 7783 7022 -0.984672 0.0154591 0.0129429 1 0 1 1 0 0 +EDGE2 7784 7045 1.06136 -0.0476952 -0.0314718 1 0 1 1 0 0 +EDGE2 7784 7765 0.899641 -0.0736346 -3.13447 1 0 1 1 0 0 +EDGE2 7784 7005 1.02974 0.00404281 -0.0119922 1 0 1 1 0 0 +EDGE2 7784 7025 1.00934 0.0120906 0.00507183 1 0 1 1 0 0 +EDGE2 7784 7783 -1.0501 0.10145 -0.00884727 1 0 1 1 0 0 +EDGE2 7784 7024 0.0376786 0.0605878 0.0287416 1 0 1 1 0 0 +EDGE2 7784 7044 -0.00368094 -0.060399 0.0225149 1 0 1 1 0 0 +EDGE2 7784 7004 -0.017705 -0.0709693 0.0268346 1 0 1 1 0 0 +EDGE2 7784 7003 -1.03562 -0.0542322 0.0169134 1 0 1 1 0 0 +EDGE2 7784 7023 -1.11945 -0.0809346 -0.00909926 1 0 1 1 0 0 +EDGE2 7784 7043 -1.05186 0.00219944 0.00544433 1 0 1 1 0 0 +EDGE2 7785 7046 -0.045806 1.05182 1.58802 1 0 1 1 0 0 +EDGE2 7785 7766 0.0205924 0.957062 1.5396 1 0 1 1 0 0 +EDGE2 7785 7006 0.0504304 0.975992 1.57038 1 0 1 1 0 0 +EDGE2 7785 7026 -0.0137714 0.945495 1.59555 1 0 1 1 0 0 +EDGE2 7785 7045 -0.00483795 -0.021418 -0.0222838 1 0 1 1 0 0 +EDGE2 7785 7764 1.09847 0.0625906 -3.191 1 0 1 1 0 0 +EDGE2 7785 7765 0.0593955 0.033576 -3.14062 1 0 1 1 0 0 +EDGE2 7785 7005 0.0569442 0.197812 -0.0112146 1 0 1 1 0 0 +EDGE2 7785 7025 -0.107409 0.00619365 -0.0138564 1 0 1 1 0 0 +EDGE2 7785 7024 -1.00088 -0.0354819 0.0182869 1 0 1 1 0 0 +EDGE2 7785 7044 -0.915017 -0.0432334 -0.00364764 1 0 1 1 0 0 +EDGE2 7785 7784 -1.05339 0.00966987 0.0310721 1 0 1 1 0 0 +EDGE2 7785 7004 -0.963199 0.164508 -0.00490813 1 0 1 1 0 0 +EDGE2 7786 7007 0.98614 0.0148882 0.0319348 1 0 1 1 0 0 +EDGE2 7786 7047 0.985682 -0.0895062 0.0302567 1 0 1 1 0 0 +EDGE2 7786 7767 1.08603 0.046123 0.0203047 1 0 1 1 0 0 +EDGE2 7786 7027 1.04137 -0.0138932 0.00162548 1 0 1 1 0 0 +EDGE2 7786 7046 -0.0742944 0.0229794 0.00473945 1 0 1 1 0 0 +EDGE2 7786 7766 0.0125086 -0.0334411 -0.0280038 1 0 1 1 0 0 +EDGE2 7786 7006 0.0113585 -0.0437563 -0.00882366 1 0 1 1 0 0 +EDGE2 7786 7026 0.00575582 0.0470784 -0.0270233 1 0 1 1 0 0 +EDGE2 7786 7045 -1.00175 -0.0363158 -1.58007 1 0 1 1 0 0 +EDGE2 7786 7785 -0.99433 -0.0601844 -1.53482 1 0 1 1 0 0 +EDGE2 7786 7765 -0.970394 -0.0459171 1.56104 1 0 1 1 0 0 +EDGE2 7786 7005 -0.8494 -0.0180818 -1.55839 1 0 1 1 0 0 +EDGE2 7786 7025 -0.881504 0.0269637 -1.57757 1 0 1 1 0 0 +EDGE2 7787 7007 -0.0161592 0.0430476 -0.0128625 1 0 1 1 0 0 +EDGE2 7787 7008 1.01749 0.0167299 0.0343171 1 0 1 1 0 0 +EDGE2 7787 7048 1.10406 -0.0753834 -0.00519398 1 0 1 1 0 0 +EDGE2 7787 7768 1.02084 0.0537431 0.0193571 1 0 1 1 0 0 +EDGE2 7787 7028 1.10266 -0.0299237 -0.00190666 1 0 1 1 0 0 +EDGE2 7787 7047 0.0284758 0.059674 -0.0148699 1 0 1 1 0 0 +EDGE2 7787 7767 -0.04947 -0.0488176 0.0226902 1 0 1 1 0 0 +EDGE2 7787 7027 -0.00215332 0.00665769 0.00255377 1 0 1 1 0 0 +EDGE2 7787 7046 -0.956036 -0.0284406 -0.0139382 1 0 1 1 0 0 +EDGE2 7787 7786 -1.01086 -0.0860246 0.0218397 1 0 1 1 0 0 +EDGE2 7787 7766 -0.898928 -0.00331438 0.023292 1 0 1 1 0 0 +EDGE2 7787 7006 -0.982545 0.0821917 -0.000266187 1 0 1 1 0 0 +EDGE2 7787 7026 -0.972527 0.00256443 -0.000617097 1 0 1 1 0 0 +EDGE2 7788 7769 1.07631 -0.0931246 0.0178164 1 0 1 1 0 0 +EDGE2 7788 7029 0.979186 0.0443971 0.00420121 1 0 1 1 0 0 +EDGE2 7788 7049 1.02649 -0.0113843 -0.00368457 1 0 1 1 0 0 +EDGE2 7788 7009 1.07233 -0.00451564 -0.000536929 1 0 1 1 0 0 +EDGE2 7788 7007 -1.00441 0.0138318 -0.0237746 1 0 1 1 0 0 +EDGE2 7788 7008 0.0365308 0.00319182 0.00260428 1 0 1 1 0 0 +EDGE2 7788 7048 0.0145026 -0.0213386 0.00431591 1 0 1 1 0 0 +EDGE2 7788 7768 -0.0402571 0.0309988 0.0393363 1 0 1 1 0 0 +EDGE2 7788 7028 -0.00274398 0.0194439 -0.0269969 1 0 1 1 0 0 +EDGE2 7788 7047 -1.04666 0.0729909 -0.00885996 1 0 1 1 0 0 +EDGE2 7788 7767 -0.943501 0.0293005 -0.000383136 1 0 1 1 0 0 +EDGE2 7788 7787 -1.02464 0.0365322 -0.00323309 1 0 1 1 0 0 +EDGE2 7788 7027 -1.01119 -0.033743 0.0124295 1 0 1 1 0 0 +EDGE2 7789 7770 1.00064 -0.0179951 0.0132129 1 0 1 1 0 0 +EDGE2 7789 7769 -0.0820937 0.0440463 0.00593036 1 0 1 1 0 0 +EDGE2 7789 7010 0.986964 -0.0465846 0.00908982 1 0 1 1 0 0 +EDGE2 7789 7030 1.07304 0.0342553 0.0332759 1 0 1 1 0 0 +EDGE2 7789 7050 0.937621 -0.0625829 0.0152429 1 0 1 1 0 0 +EDGE2 7789 7029 -0.0379968 0.0432878 -0.00953828 1 0 1 1 0 0 +EDGE2 7789 7049 -0.0314111 -0.0169187 -0.0210517 1 0 1 1 0 0 +EDGE2 7789 7009 -0.0103931 -0.0459438 0.00943814 1 0 1 1 0 0 +EDGE2 7789 7008 -0.966144 -0.116041 0.0550898 1 0 1 1 0 0 +EDGE2 7789 7048 -0.976438 -0.0671454 0.00760804 1 0 1 1 0 0 +EDGE2 7789 7768 -1.01695 -0.06818 0.0192579 1 0 1 1 0 0 +EDGE2 7789 7788 -0.972242 0.0264673 -0.00274853 1 0 1 1 0 0 +EDGE2 7789 7028 -0.941658 -0.0946929 -0.0114552 1 0 1 1 0 0 +EDGE2 7790 7051 -0.0433764 -1.02642 -1.57403 1 0 1 1 0 0 +EDGE2 7790 7770 -0.0551946 -0.0492512 -0.000479556 1 0 1 1 0 0 +EDGE2 7790 7769 -0.976854 0.0755271 0.00925711 1 0 1 1 0 0 +EDGE2 7790 7010 -0.00843103 -0.0500074 -0.0078083 1 0 1 1 0 0 +EDGE2 7790 7030 0.0106424 -0.0311459 0.0229018 1 0 1 1 0 0 +EDGE2 7790 7050 -0.00897067 -0.00777265 -0.00951761 1 0 1 1 0 0 +EDGE2 7790 7789 -1.03413 0.0136887 -0.0076875 1 0 1 1 0 0 +EDGE2 7790 7029 -0.985196 -0.00866594 0.0136474 1 0 1 1 0 0 +EDGE2 7790 7049 -0.991388 -0.0490066 0.0227241 1 0 1 1 0 0 +EDGE2 7790 7009 -1.0527 0.0221866 0.0312963 1 0 1 1 0 0 +EDGE2 7790 7031 -0.0682265 1.01745 1.59806 1 0 1 1 0 0 +EDGE2 7790 7771 0.0509526 0.99505 1.54529 1 0 1 1 0 0 +EDGE2 7790 7011 0.10303 1.04952 1.54797 1 0 1 1 0 0 +EDGE2 7791 7770 -0.957497 0.00201356 -1.56894 1 0 1 1 0 0 +EDGE2 7791 7790 -0.995577 0.119164 -1.54355 1 0 1 1 0 0 +EDGE2 7791 7010 -1.04564 -0.0185559 -1.54567 1 0 1 1 0 0 +EDGE2 7791 7030 -0.946135 0.0419406 -1.55086 1 0 1 1 0 0 +EDGE2 7791 7050 -1.05796 0.0117831 -1.5943 1 0 1 1 0 0 +EDGE2 7791 7031 0.0305174 -0.0213604 0.0239215 1 0 1 1 0 0 +EDGE2 7791 7771 -0.0541956 0.0709039 0.0142268 1 0 1 1 0 0 +EDGE2 7791 7011 0.0276728 -0.00747668 -0.00405679 1 0 1 1 0 0 +EDGE2 7791 7032 0.948757 -0.029329 0.0116903 1 0 1 1 0 0 +EDGE2 7791 7772 1.04366 0.0310394 0.0174612 1 0 1 1 0 0 +EDGE2 7791 7012 1.01596 0.012437 0.0204525 1 0 1 1 0 0 +EDGE2 7792 7031 -1.0008 0.0559587 -0.011986 1 0 1 1 0 0 +EDGE2 7792 7771 -0.953679 0.0320049 -0.0571312 1 0 1 1 0 0 +EDGE2 7792 7791 -1.00913 0.0640186 -0.030021 1 0 1 1 0 0 +EDGE2 7792 7011 -1.05278 0.0294985 -0.00741334 1 0 1 1 0 0 +EDGE2 7792 7032 -0.0283832 0.0565563 -0.011697 1 0 1 1 0 0 +EDGE2 7792 7772 -0.0407002 0.0118238 0.00978831 1 0 1 1 0 0 +EDGE2 7792 7012 -0.0743812 -0.00674071 0.0338388 1 0 1 1 0 0 +EDGE2 7792 7033 0.994563 0.0515387 -0.0218983 1 0 1 1 0 0 +EDGE2 7792 7773 0.97376 -0.0228449 0.00223538 1 0 1 1 0 0 +EDGE2 7792 7013 1.01464 -0.0457683 0.0123248 1 0 1 1 0 0 +EDGE2 7793 7032 -0.987881 -0.00788822 0.0254167 1 0 1 1 0 0 +EDGE2 7793 7772 -1.11535 -0.0311101 0.0239734 1 0 1 1 0 0 +EDGE2 7793 7792 -0.998361 -0.00805758 0.0340598 1 0 1 1 0 0 +EDGE2 7793 7012 -0.969917 -0.0153704 0.00464379 1 0 1 1 0 0 +EDGE2 7793 7033 -0.0553447 -0.0104016 0.00291526 1 0 1 1 0 0 +EDGE2 7793 7773 0.049247 0.0471423 -0.0144704 1 0 1 1 0 0 +EDGE2 7793 7013 0.00443098 -0.105381 -0.00210905 1 0 1 1 0 0 +EDGE2 7793 7034 1.10916 0.1003 0.0180868 1 0 1 1 0 0 +EDGE2 7793 7774 0.958092 -0.0574536 0.00154858 1 0 1 1 0 0 +EDGE2 7793 7014 1.01992 -0.0131765 0.0388915 1 0 1 1 0 0 +EDGE2 7794 7033 -1.0845 0.00898959 0.00752753 1 0 1 1 0 0 +EDGE2 7794 7773 -1.06225 -0.036451 0.0616286 1 0 1 1 0 0 +EDGE2 7794 7793 -1.01654 -0.0695661 -0.00326446 1 0 1 1 0 0 +EDGE2 7794 7013 -0.999709 -0.0568903 -0.0462321 1 0 1 1 0 0 +EDGE2 7794 7034 -0.0216054 -0.00030185 0.00996844 1 0 1 1 0 0 +EDGE2 7794 7774 0.0317738 0.00478818 0.00969014 1 0 1 1 0 0 +EDGE2 7794 7014 -0.0036984 -0.0447471 -0.000806698 1 0 1 1 0 0 +EDGE2 7794 6995 0.921672 -0.0893304 -3.135 1 0 1 1 0 0 +EDGE2 7794 7035 0.93333 0.00703405 -0.00193844 1 0 1 1 0 0 +EDGE2 7794 7775 0.970032 0.055438 0.0268134 1 0 1 1 0 0 +EDGE2 7794 7015 0.912689 -0.00981203 -0.0166434 1 0 1 1 0 0 +EDGE2 7795 7034 -1.02718 -0.00351449 -0.0208158 1 0 1 1 0 0 +EDGE2 7795 7774 -1.04203 -0.000778447 0.00194302 1 0 1 1 0 0 +EDGE2 7795 7794 -0.986628 -0.00629057 -0.0297029 1 0 1 1 0 0 +EDGE2 7795 7014 -0.959279 0.0425454 -0.0207741 1 0 1 1 0 0 +EDGE2 7795 6995 0.0117717 -0.00653411 -3.14497 1 0 1 1 0 0 +EDGE2 7795 7035 -0.0686174 0.00329544 -0.00677495 1 0 1 1 0 0 +EDGE2 7795 7775 -0.0573316 -0.00675153 0.0200295 1 0 1 1 0 0 +EDGE2 7795 7015 -0.124257 0.00551957 -0.00235996 1 0 1 1 0 0 +EDGE2 7795 6994 1.02577 0.0318559 -3.15614 1 0 1 1 0 0 +EDGE2 7795 7016 0.046012 0.980029 1.6024 1 0 1 1 0 0 +EDGE2 7795 7036 -0.00456408 1.01742 1.53933 1 0 1 1 0 0 +EDGE2 7795 7776 0.0637498 0.976232 1.57196 1 0 1 1 0 0 +EDGE2 7795 6996 -0.0217198 1.09991 1.54169 1 0 1 1 0 0 +EDGE2 7796 6995 -1.04229 0.0392373 -1.57996 1 0 1 1 0 0 +EDGE2 7796 7035 -0.92043 -0.0253683 1.56612 1 0 1 1 0 0 +EDGE2 7796 7775 -1.05555 -0.0602183 1.55382 1 0 1 1 0 0 +EDGE2 7796 7795 -1.04544 -0.0263207 1.58996 1 0 1 1 0 0 +EDGE2 7796 7015 -1.00963 0.0400872 1.5758 1 0 1 1 0 0 +EDGE2 7797 7796 -0.894356 0.0560662 0.00851749 1 0 1 1 0 0 +EDGE2 7798 7797 -0.982027 0.0397075 -0.0123816 1 0 1 1 0 0 +EDGE2 7799 7798 -0.942773 -0.0284119 -0.00626183 1 0 1 1 0 0 +EDGE2 7800 7799 -0.978463 -0.0362521 -0.00868005 1 0 1 1 0 0 +EDGE2 7801 7800 -0.908608 0.0578838 1.60737 1 0 1 1 0 0 +EDGE2 7802 7801 -0.989758 -0.00672106 -0.0122755 1 0 1 1 0 0 +EDGE2 7803 7802 -0.896721 -0.00215849 0.0237431 1 0 1 1 0 0 +EDGE2 7804 7803 -1.06147 0.0315663 -0.0190051 1 0 1 1 0 0 +EDGE2 7805 7804 -0.906246 0.0216835 0.00206367 1 0 1 1 0 0 +EDGE2 7806 7805 -0.985764 0.0548182 1.58171 1 0 1 1 0 0 +EDGE2 7807 7806 -0.913925 0.0918026 -0.0218679 1 0 1 1 0 0 +EDGE2 7808 7807 -0.945153 -0.0112009 0.0280172 1 0 1 1 0 0 +EDGE2 7809 7808 -0.976122 -0.00201511 -0.00836688 1 0 1 1 0 0 +EDGE2 7809 7770 1.11779 -0.0444543 -3.1094 1 0 1 1 0 0 +EDGE2 7809 7790 0.994916 0.108601 -3.16882 1 0 1 1 0 0 +EDGE2 7809 7010 0.915369 0.059588 -3.15423 1 0 1 1 0 0 +EDGE2 7809 7030 1.00701 0.015785 -3.17797 1 0 1 1 0 0 +EDGE2 7809 7050 0.940841 -0.00957707 -3.15288 1 0 1 1 0 0 +EDGE2 7810 7809 -0.973821 0.0458766 -0.00895629 1 0 1 1 0 0 +EDGE2 7810 7051 -0.0491564 0.999023 1.57663 1 0 1 1 0 0 +EDGE2 7810 7770 -0.0668551 -0.0707962 -3.13596 1 0 1 1 0 0 +EDGE2 7810 7790 -0.0278399 0.0476926 -3.13709 1 0 1 1 0 0 +EDGE2 7810 7769 1.06593 -0.0128065 -3.13912 1 0 1 1 0 0 +EDGE2 7810 7010 0.0541507 0.0340828 -3.15582 1 0 1 1 0 0 +EDGE2 7810 7030 0.0135195 0.00276072 -3.15037 1 0 1 1 0 0 +EDGE2 7810 7050 -0.0509207 0.0654577 -3.15817 1 0 1 1 0 0 +EDGE2 7810 7789 1.08792 -0.0967975 -3.136 1 0 1 1 0 0 +EDGE2 7810 7029 1.05222 -0.0137847 -3.15542 1 0 1 1 0 0 +EDGE2 7810 7049 1.00865 -0.0331407 -3.12798 1 0 1 1 0 0 +EDGE2 7810 7009 0.956979 -0.0616951 -3.1338 1 0 1 1 0 0 +EDGE2 7810 7031 -0.054653 -0.975956 -1.57546 1 0 1 1 0 0 +EDGE2 7810 7771 0.0130097 -1.02687 -1.58075 1 0 1 1 0 0 +EDGE2 7810 7791 -0.0294535 -0.981075 -1.57034 1 0 1 1 0 0 +EDGE2 7810 7011 0.0228795 -1.02069 -1.56997 1 0 1 1 0 0 +EDGE2 7811 7052 1.02352 -0.0729995 0.0280471 1 0 1 1 0 0 +EDGE2 7811 7051 0.0332691 -0.0506958 -0.00305195 1 0 1 1 0 0 +EDGE2 7811 7770 -1.05011 0.00998115 1.56463 1 0 1 1 0 0 +EDGE2 7811 7810 -1.01523 -0.0653427 -1.59199 1 0 1 1 0 0 +EDGE2 7811 7790 -0.916316 -0.00470779 1.60265 1 0 1 1 0 0 +EDGE2 7811 7010 -1.11023 0.0540966 1.57826 1 0 1 1 0 0 +EDGE2 7811 7030 -0.978695 -0.0106204 1.57377 1 0 1 1 0 0 +EDGE2 7811 7050 -1.06162 -0.0535701 1.5359 1 0 1 1 0 0 +EDGE2 7812 7052 0.0246031 -0.0329498 0.0309503 1 0 1 1 0 0 +EDGE2 7812 7053 0.919377 0.0745721 -0.00375462 1 0 1 1 0 0 +EDGE2 7812 7811 -1.09241 0.0234882 0.000548278 1 0 1 1 0 0 +EDGE2 7812 7051 -0.940177 -0.0353683 0.0206119 1 0 1 1 0 0 +EDGE2 7813 7054 0.875186 0.0560281 0.0389871 1 0 1 1 0 0 +EDGE2 7813 7052 -0.899197 -0.0826496 -0.00873891 1 0 1 1 0 0 +EDGE2 7813 7053 -0.0400332 0.058873 -0.0135058 1 0 1 1 0 0 +EDGE2 7813 7812 -0.98822 -0.030015 -0.0353602 1 0 1 1 0 0 +EDGE2 7814 7813 -1.03147 -0.0113894 -0.0107108 1 0 1 1 0 0 +EDGE2 7814 7055 0.933272 0.00576784 -0.0266833 1 0 1 1 0 0 +EDGE2 7814 7054 -0.0175691 -0.0290283 -0.00895265 1 0 1 1 0 0 +EDGE2 7814 7053 -0.934024 -0.13336 -0.0258998 1 0 1 1 0 0 +EDGE2 7815 7056 0.00471899 0.971724 1.60221 1 0 1 1 0 0 +EDGE2 7815 7055 0.071088 0.0295724 0.0290928 1 0 1 1 0 0 +EDGE2 7815 7054 -0.976218 0.00676992 -0.020205 1 0 1 1 0 0 +EDGE2 7815 7814 -0.978752 -0.0175559 0.0138868 1 0 1 1 0 0 +EDGE2 7816 7057 0.97227 0.0172851 -0.00263573 1 0 1 1 0 0 +EDGE2 7816 7056 -0.0612741 0.0255384 0.00808889 1 0 1 1 0 0 +EDGE2 7816 7055 -1.00666 0.00551844 -1.55199 1 0 1 1 0 0 +EDGE2 7816 7815 -0.934595 -0.0499043 -1.59061 1 0 1 1 0 0 +EDGE2 7817 7058 0.984115 -0.0560666 0.0116311 1 0 1 1 0 0 +EDGE2 7817 7057 0.0263169 -0.0373289 -0.0150281 1 0 1 1 0 0 +EDGE2 7817 7056 -0.95389 0.0175813 -0.0338628 1 0 1 1 0 0 +EDGE2 7817 7816 -0.958217 -0.00299295 -0.0460948 1 0 1 1 0 0 +EDGE2 7818 7059 0.923137 0.0429065 0.0487757 1 0 1 1 0 0 +EDGE2 7818 7058 -0.0917738 -0.0159207 0.00556764 1 0 1 1 0 0 +EDGE2 7818 7057 -0.970499 -0.0139104 -0.00318833 1 0 1 1 0 0 +EDGE2 7818 7817 -1.03904 0.00495468 -0.0154078 1 0 1 1 0 0 +EDGE2 7819 7060 0.986377 0.0275757 -0.0239346 1 0 1 1 0 0 +EDGE2 7819 7100 0.902965 -0.0201395 -3.13928 1 0 1 1 0 0 +EDGE2 7819 7818 -1.08423 -0.0284262 0.0234446 1 0 1 1 0 0 +EDGE2 7819 7059 -0.0191637 0.0557174 0.00344493 1 0 1 1 0 0 +EDGE2 7819 7058 -1.0666 0.044181 0.00660444 1 0 1 1 0 0 +EDGE2 7820 7099 1.00292 0.0299298 -3.10985 1 0 1 1 0 0 +EDGE2 7820 7061 -0.0596121 -1.01 -1.54579 1 0 1 1 0 0 +EDGE2 7820 7101 0.064072 -1.03467 -1.59503 1 0 1 1 0 0 +EDGE2 7820 7060 0.053756 -0.00520584 0.0168862 1 0 1 1 0 0 +EDGE2 7820 7100 -0.0118602 -0.027293 -3.1571 1 0 1 1 0 0 +EDGE2 7820 7059 -1.04721 0.0129023 -0.043217 1 0 1 1 0 0 +EDGE2 7820 7819 -1.01231 0.0375586 0.00184777 1 0 1 1 0 0 +EDGE2 7821 7060 -1.00588 0.0611439 -1.54918 1 0 1 1 0 0 +EDGE2 7821 7820 -1.00057 0.0362594 -1.59721 1 0 1 1 0 0 +EDGE2 7821 7100 -1.02085 0.0453398 1.57527 1 0 1 1 0 0 +EDGE2 7822 7821 -0.922218 -0.0861999 0.00774977 1 0 1 1 0 0 +EDGE2 7823 7822 -0.896844 -0.0617398 -0.0248382 1 0 1 1 0 0 +EDGE2 7824 7823 -0.920775 0.00283408 0.00489219 1 0 1 1 0 0 +EDGE2 7824 7805 0.921727 -0.0104668 -3.12293 1 0 1 1 0 0 +EDGE2 7825 7824 -1.01218 -0.0414757 -0.00555575 1 0 1 1 0 0 +EDGE2 7825 7805 0.00740388 0.0864952 -3.12006 1 0 1 1 0 0 +EDGE2 7825 7804 0.97383 -0.00246406 -3.13675 1 0 1 1 0 0 +EDGE2 7825 7806 -0.0106975 1.02902 1.5211 1 0 1 1 0 0 +EDGE2 7826 7807 1.03936 0.00102701 -0.0074894 1 0 1 1 0 0 +EDGE2 7826 7805 -1.06095 0.0399249 1.56036 1 0 1 1 0 0 +EDGE2 7826 7825 -0.988075 -0.00743169 -1.5546 1 0 1 1 0 0 +EDGE2 7826 7806 0.00292526 0.0405017 0.0152134 1 0 1 1 0 0 +EDGE2 7827 7807 -0.0287706 0.0724521 -0.00653897 1 0 1 1 0 0 +EDGE2 7827 7826 -0.956189 -0.000973391 -0.0130352 1 0 1 1 0 0 +EDGE2 7827 7806 -0.997603 -0.0113984 0.000799632 1 0 1 1 0 0 +EDGE2 7827 7808 0.910581 -0.0670247 -0.00354745 1 0 1 1 0 0 +EDGE2 7828 7807 -0.942361 0.00409836 0.0221043 1 0 1 1 0 0 +EDGE2 7828 7827 -1.04315 0.00279873 0.00971469 1 0 1 1 0 0 +EDGE2 7828 7808 -0.0446175 0.0330011 -0.00106686 1 0 1 1 0 0 +EDGE2 7828 7809 0.99921 0.0283511 -0.0391927 1 0 1 1 0 0 +EDGE2 7829 7828 -1.06648 0.0249382 0.0014299 1 0 1 1 0 0 +EDGE2 7829 7808 -1.02942 0.0344852 -0.0255013 1 0 1 1 0 0 +EDGE2 7829 7809 0.0450616 0.0212665 -0.0112647 1 0 1 1 0 0 +EDGE2 7829 7770 0.981674 0.0780215 -3.13291 1 0 1 1 0 0 +EDGE2 7829 7810 1.03013 -0.0157244 0.0385793 1 0 1 1 0 0 +EDGE2 7829 7790 1.07321 -0.0361984 -3.11088 1 0 1 1 0 0 +EDGE2 7829 7010 1.0352 0.0552019 -3.16611 1 0 1 1 0 0 +EDGE2 7829 7030 0.938831 -0.00532208 -3.14155 1 0 1 1 0 0 +EDGE2 7829 7050 0.975928 -0.0441527 -3.12342 1 0 1 1 0 0 +EDGE2 7830 7829 -0.987491 -0.0471297 -0.0329704 1 0 1 1 0 0 +EDGE2 7830 7809 -1.01231 -0.0779141 -0.0274137 1 0 1 1 0 0 +EDGE2 7830 7811 -0.00422193 0.958756 1.55703 1 0 1 1 0 0 +EDGE2 7830 7051 0.0165367 1.02174 1.57469 1 0 1 1 0 0 +EDGE2 7830 7770 0.0642984 -0.0272851 -3.11779 1 0 1 1 0 0 +EDGE2 7830 7810 0.0279855 -0.0545373 -0.0236749 1 0 1 1 0 0 +EDGE2 7830 7790 -0.0564101 -0.0399398 -3.14497 1 0 1 1 0 0 +EDGE2 7830 7769 1.04375 0.00128685 -3.13518 1 0 1 1 0 0 +EDGE2 7830 7010 0.148407 -0.0148019 -3.17379 1 0 1 1 0 0 +EDGE2 7830 7030 -0.0522382 -0.0260743 -3.10554 1 0 1 1 0 0 +EDGE2 7830 7050 -0.00829267 0.0380382 -3.13759 1 0 1 1 0 0 +EDGE2 7830 7789 0.962166 0.0172498 -3.13792 1 0 1 1 0 0 +EDGE2 7830 7029 0.993641 0.0197998 -3.13297 1 0 1 1 0 0 +EDGE2 7830 7049 0.920775 0.023032 -3.15007 1 0 1 1 0 0 +EDGE2 7830 7009 0.92651 -0.0283189 -3.15483 1 0 1 1 0 0 +EDGE2 7830 7031 -0.0186476 -1.02938 -1.56369 1 0 1 1 0 0 +EDGE2 7830 7771 0.0323866 -0.979123 -1.56666 1 0 1 1 0 0 +EDGE2 7830 7791 0.0458249 -0.946472 -1.61026 1 0 1 1 0 0 +EDGE2 7830 7011 0.0166313 -1.03864 -1.5842 1 0 1 1 0 0 +EDGE2 7831 7052 1.02537 -0.0184562 0.0185932 1 0 1 1 0 0 +EDGE2 7831 7812 0.980318 0.0124051 0.0131753 1 0 1 1 0 0 +EDGE2 7831 7811 -0.103615 -0.0715406 0.00818369 1 0 1 1 0 0 +EDGE2 7831 7051 0.041834 -0.0239275 0.0106861 1 0 1 1 0 0 +EDGE2 7831 7770 -0.870193 0.0343428 1.56607 1 0 1 1 0 0 +EDGE2 7831 7810 -0.961543 0.00539081 -1.58231 1 0 1 1 0 0 +EDGE2 7831 7830 -1.06808 0.0363545 -1.56568 1 0 1 1 0 0 +EDGE2 7831 7790 -0.928996 0.108157 1.57008 1 0 1 1 0 0 +EDGE2 7831 7010 -1.0677 0.0526076 1.5941 1 0 1 1 0 0 +EDGE2 7831 7030 -1.01698 -0.00600476 1.55411 1 0 1 1 0 0 +EDGE2 7831 7050 -1.03787 0.0106217 1.60601 1 0 1 1 0 0 +EDGE2 7832 7813 1.0734 0.055006 -0.0193319 1 0 1 1 0 0 +EDGE2 7832 7052 -0.0525917 0.00641052 -0.014919 1 0 1 1 0 0 +EDGE2 7832 7053 0.973667 0.0339851 -0.0233849 1 0 1 1 0 0 +EDGE2 7832 7812 0.0497174 0.06719 -0.0114385 1 0 1 1 0 0 +EDGE2 7832 7811 -1.09745 0.00501587 0.0461643 1 0 1 1 0 0 +EDGE2 7832 7831 -0.976219 -0.02342 0.0250634 1 0 1 1 0 0 +EDGE2 7832 7051 -0.995071 0.106449 0.0064474 1 0 1 1 0 0 +EDGE2 7833 7813 0.0310762 -0.0941777 0.00984409 1 0 1 1 0 0 +EDGE2 7833 7054 1.03364 -0.0211049 -0.0103578 1 0 1 1 0 0 +EDGE2 7833 7814 0.969273 -0.0515629 -0.013703 1 0 1 1 0 0 +EDGE2 7833 7052 -1.00175 -0.0396773 0.00184948 1 0 1 1 0 0 +EDGE2 7833 7832 -1.00442 -0.0224244 -0.00587406 1 0 1 1 0 0 +EDGE2 7833 7053 0.0520392 -0.035054 0.0115711 1 0 1 1 0 0 +EDGE2 7833 7812 -1.08358 -0.00332699 -0.00231501 1 0 1 1 0 0 +EDGE2 7834 7813 -0.978003 -0.0493009 0.0399949 1 0 1 1 0 0 +EDGE2 7834 7055 1.00147 -0.00280444 0.011641 1 0 1 1 0 0 +EDGE2 7834 7815 0.935821 0.0736147 0.0127405 1 0 1 1 0 0 +EDGE2 7834 7054 0.0637253 0.028131 -0.00291385 1 0 1 1 0 0 +EDGE2 7834 7814 -0.0345982 -0.00688484 0.0225861 1 0 1 1 0 0 +EDGE2 7834 7833 -0.994172 0.0267547 0.00715748 1 0 1 1 0 0 +EDGE2 7834 7053 -0.901011 0.0180308 0.0216172 1 0 1 1 0 0 +EDGE2 7835 7056 0.0456681 0.953852 1.56593 1 0 1 1 0 0 +EDGE2 7835 7816 -0.043964 0.879313 1.57524 1 0 1 1 0 0 +EDGE2 7835 7834 -1.02571 0.0356721 -0.0161338 1 0 1 1 0 0 +EDGE2 7835 7055 0.0201913 0.0230072 -0.000720318 1 0 1 1 0 0 +EDGE2 7835 7815 -0.0695492 0.102626 -0.0547759 1 0 1 1 0 0 +EDGE2 7835 7054 -0.988607 0.0455022 0.0109064 1 0 1 1 0 0 +EDGE2 7835 7814 -0.936568 0.0429224 0.0137995 1 0 1 1 0 0 +EDGE2 7836 7057 1.00969 -0.0594974 -0.0133 1 0 1 1 0 0 +EDGE2 7836 7817 0.989929 -0.0367984 0.00435451 1 0 1 1 0 0 +EDGE2 7836 7056 0.0308559 0.0203134 0.0178917 1 0 1 1 0 0 +EDGE2 7836 7816 0.000139045 -0.00502035 0.0149995 1 0 1 1 0 0 +EDGE2 7836 7055 -1.02096 0.0340803 -1.54721 1 0 1 1 0 0 +EDGE2 7836 7815 -0.929604 -0.0297525 -1.59002 1 0 1 1 0 0 +EDGE2 7836 7835 -0.906816 -0.0537792 -1.56081 1 0 1 1 0 0 +EDGE2 7837 7818 0.982432 0.0672551 -0.0182329 1 0 1 1 0 0 +EDGE2 7837 7058 0.967374 -0.0280124 0.0161097 1 0 1 1 0 0 +EDGE2 7837 7057 -0.0135523 0.0368798 0.00839664 1 0 1 1 0 0 +EDGE2 7837 7817 -0.0737003 0.0440055 0.0070227 1 0 1 1 0 0 +EDGE2 7837 7836 -0.955388 -0.0109148 0.0131237 1 0 1 1 0 0 +EDGE2 7837 7056 -1.02889 0.0969002 -0.00663344 1 0 1 1 0 0 +EDGE2 7837 7816 -1.00826 0.000715077 -0.000923406 1 0 1 1 0 0 +EDGE2 7838 7818 0.0534016 0.0270672 -0.0320661 1 0 1 1 0 0 +EDGE2 7838 7059 0.928895 0.0314619 -0.0198441 1 0 1 1 0 0 +EDGE2 7838 7819 1.0263 0.0254216 -0.0202092 1 0 1 1 0 0 +EDGE2 7838 7058 0.0608535 0.0209478 0.0158375 1 0 1 1 0 0 +EDGE2 7838 7057 -1.0561 0.0304795 0.0118275 1 0 1 1 0 0 +EDGE2 7838 7837 -1.02614 -0.0206423 0.0242991 1 0 1 1 0 0 +EDGE2 7838 7817 -1.04205 0.0126716 -0.0303308 1 0 1 1 0 0 +EDGE2 7839 7060 1.04855 -0.0155359 0.015923 1 0 1 1 0 0 +EDGE2 7839 7820 1.05033 -0.0204847 0.0280235 1 0 1 1 0 0 +EDGE2 7839 7100 0.965224 -0.0928326 -3.15402 1 0 1 1 0 0 +EDGE2 7839 7818 -0.972439 0.129965 -0.0138769 1 0 1 1 0 0 +EDGE2 7839 7059 0.0624937 -0.0784029 0.00176921 1 0 1 1 0 0 +EDGE2 7839 7819 -0.090811 0.0656278 -0.0176826 1 0 1 1 0 0 +EDGE2 7839 7838 -0.932164 -0.0326602 0.0160416 1 0 1 1 0 0 +EDGE2 7839 7058 -1.0299 0.0378294 0.00567733 1 0 1 1 0 0 +EDGE2 7840 7099 1.0277 0.0563054 -3.11827 1 0 1 1 0 0 +EDGE2 7840 7061 -0.0942666 -1.09657 -1.54249 1 0 1 1 0 0 +EDGE2 7840 7101 0.0200805 -0.987493 -1.57417 1 0 1 1 0 0 +EDGE2 7840 7060 0.0319002 -0.0289847 0.00401635 1 0 1 1 0 0 +EDGE2 7840 7820 -0.00187729 0.0585636 0.051003 1 0 1 1 0 0 +EDGE2 7840 7100 0.057347 0.0416715 -3.16876 1 0 1 1 0 0 +EDGE2 7840 7821 0.00750454 0.927363 1.54007 1 0 1 1 0 0 +EDGE2 7840 7059 -1.0147 0.0757576 -0.0215364 1 0 1 1 0 0 +EDGE2 7840 7819 -0.922656 -0.0439377 0.0224984 1 0 1 1 0 0 +EDGE2 7840 7839 -1.03162 -0.0668605 0.0130229 1 0 1 1 0 0 +EDGE2 7841 7060 -0.993814 -0.0180046 -1.58327 1 0 1 1 0 0 +EDGE2 7841 7820 -1.00158 0.09021 -1.61422 1 0 1 1 0 0 +EDGE2 7841 7840 -1.06125 -0.0926519 -1.5737 1 0 1 1 0 0 +EDGE2 7841 7100 -0.899314 -0.0983898 1.51837 1 0 1 1 0 0 +EDGE2 7841 7821 0.084607 0.00094728 0.0123528 1 0 1 1 0 0 +EDGE2 7841 7822 1.00316 -0.0236521 -0.0416578 1 0 1 1 0 0 +EDGE2 7842 7841 -1.01874 -0.0918898 -0.00827908 1 0 1 1 0 0 +EDGE2 7842 7821 -0.954822 0.114806 0.0280743 1 0 1 1 0 0 +EDGE2 7842 7823 0.961906 0.0264152 0.00953112 1 0 1 1 0 0 +EDGE2 7842 7822 0.0605586 0.0273442 0.0128985 1 0 1 1 0 0 +EDGE2 7843 7823 -0.00419269 -0.00919815 -0.0399049 1 0 1 1 0 0 +EDGE2 7843 7822 -0.960153 0.0170956 -0.00585298 1 0 1 1 0 0 +EDGE2 7843 7842 -0.961896 0.00372947 0.00107483 1 0 1 1 0 0 +EDGE2 7843 7824 0.96911 0.0191193 0.00613951 1 0 1 1 0 0 +EDGE2 7844 7823 -1.03626 0.0129839 -0.0304635 1 0 1 1 0 0 +EDGE2 7844 7843 -1.02977 -0.0097093 0.0309636 1 0 1 1 0 0 +EDGE2 7844 7824 -0.0315634 -0.0499687 0.0128679 1 0 1 1 0 0 +EDGE2 7844 7805 1.07078 -0.00694146 -3.16597 1 0 1 1 0 0 +EDGE2 7844 7825 0.994705 -0.0845599 -0.000571763 1 0 1 1 0 0 +EDGE2 7845 7824 -1.03447 -0.00493146 -0.00318941 1 0 1 1 0 0 +EDGE2 7845 7844 -1.02949 0.143995 0.00578943 1 0 1 1 0 0 +EDGE2 7845 7805 0.0358372 0.0387547 -3.14772 1 0 1 1 0 0 +EDGE2 7845 7825 0.0442161 0.00489903 0.00510934 1 0 1 1 0 0 +EDGE2 7845 7804 1.01324 -0.0843328 -3.14107 1 0 1 1 0 0 +EDGE2 7845 7826 0.0140313 1.0792 1.56728 1 0 1 1 0 0 +EDGE2 7845 7806 -0.00447272 0.942621 1.53161 1 0 1 1 0 0 +EDGE2 7846 7807 1.03053 -0.0338473 -0.00834653 1 0 1 1 0 0 +EDGE2 7846 7845 -0.968421 0.0111212 -1.58091 1 0 1 1 0 0 +EDGE2 7846 7805 -0.962437 -0.0019137 1.56882 1 0 1 1 0 0 +EDGE2 7846 7825 -1.14769 0.0207084 -1.56415 1 0 1 1 0 0 +EDGE2 7846 7826 0.00471596 0.0691129 0.0110547 1 0 1 1 0 0 +EDGE2 7846 7806 -0.0804564 0.00407839 0.0198281 1 0 1 1 0 0 +EDGE2 7846 7827 0.977865 0.0467267 -0.0196498 1 0 1 1 0 0 +EDGE2 7847 7807 0.0874886 -0.103792 0.0273983 1 0 1 1 0 0 +EDGE2 7847 7826 -1.06641 0.0403586 -0.0038154 1 0 1 1 0 0 +EDGE2 7847 7846 -0.97813 0.0249809 -0.0462405 1 0 1 1 0 0 +EDGE2 7847 7806 -1.03478 -0.00143268 -0.0115078 1 0 1 1 0 0 +EDGE2 7847 7827 0.0456547 0.0220491 -0.00997874 1 0 1 1 0 0 +EDGE2 7847 7828 1.01591 -0.0150817 -0.027685 1 0 1 1 0 0 +EDGE2 7847 7808 0.85163 -0.02056 -0.000522273 1 0 1 1 0 0 +EDGE2 7848 7807 -0.96866 -0.0228694 -0.00966033 1 0 1 1 0 0 +EDGE2 7848 7847 -1.03938 -0.00664948 -0.00369149 1 0 1 1 0 0 +EDGE2 7848 7827 -1.00396 0.0452995 0.0102901 1 0 1 1 0 0 +EDGE2 7848 7829 1.03113 0.0042943 0.00882526 1 0 1 1 0 0 +EDGE2 7848 7828 0.0206759 0.0446412 -0.00497335 1 0 1 1 0 0 +EDGE2 7848 7808 -0.00164122 0.0447394 -0.0117281 1 0 1 1 0 0 +EDGE2 7848 7809 1.03726 0.0598913 -0.0234685 1 0 1 1 0 0 +EDGE2 7849 7829 -0.00442795 -0.0140178 0.0108501 1 0 1 1 0 0 +EDGE2 7849 7828 -0.940109 -0.0227354 0.033621 1 0 1 1 0 0 +EDGE2 7849 7848 -1.03054 -0.0443811 0.0212717 1 0 1 1 0 0 +EDGE2 7849 7808 -0.993115 0.0405042 0.00938242 1 0 1 1 0 0 +EDGE2 7849 7809 -0.0231241 -0.022903 0.0152877 1 0 1 1 0 0 +EDGE2 7849 7770 0.971951 -0.0327798 -3.15866 1 0 1 1 0 0 +EDGE2 7849 7810 0.94735 -0.05679 -0.0018866 1 0 1 1 0 0 +EDGE2 7849 7830 1.00636 0.0240474 -0.000764337 1 0 1 1 0 0 +EDGE2 7849 7790 0.959469 0.0070411 -3.15402 1 0 1 1 0 0 +EDGE2 7849 7010 1.05214 -0.00371398 -3.12663 1 0 1 1 0 0 +EDGE2 7849 7030 0.929358 -0.00142742 -3.16344 1 0 1 1 0 0 +EDGE2 7849 7050 1.08233 0.0776686 -3.15505 1 0 1 1 0 0 +EDGE2 7850 7829 -0.9279 -0.0119329 0.0159044 1 0 1 1 0 0 +EDGE2 7850 7849 -0.998105 -0.00476628 -0.00388305 1 0 1 1 0 0 +EDGE2 7850 7809 -1.0552 -0.0993681 -0.0170156 1 0 1 1 0 0 +EDGE2 7850 7811 -0.0590419 0.998963 1.58191 1 0 1 1 0 0 +EDGE2 7850 7831 -0.0845473 1.0285 1.55494 1 0 1 1 0 0 +EDGE2 7850 7051 0.0929055 1.10424 1.56171 1 0 1 1 0 0 +EDGE2 7850 7770 -0.039458 0.119165 -3.17086 1 0 1 1 0 0 +EDGE2 7850 7810 0.02432 -0.0430753 0.0277315 1 0 1 1 0 0 +EDGE2 7850 7830 0.057474 0.0435565 -0.0103378 1 0 1 1 0 0 +EDGE2 7850 7790 -0.00359089 -0.0156166 -3.16672 1 0 1 1 0 0 +EDGE2 7850 7769 0.992318 -0.0274663 -3.16263 1 0 1 1 0 0 +EDGE2 7850 7010 0.0107143 0.0166459 -3.1641 1 0 1 1 0 0 +EDGE2 7850 7030 -0.0596818 0.0917005 -3.13084 1 0 1 1 0 0 +EDGE2 7850 7050 0.0311084 -0.00235951 -3.13409 1 0 1 1 0 0 +EDGE2 7850 7789 0.986283 -0.0162762 -3.15092 1 0 1 1 0 0 +EDGE2 7850 7029 1.03344 0.00676416 -3.15444 1 0 1 1 0 0 +EDGE2 7850 7049 0.925653 0.00657009 -3.09715 1 0 1 1 0 0 +EDGE2 7850 7009 1.00475 -0.0820401 -3.15571 1 0 1 1 0 0 +EDGE2 7850 7031 0.0360668 -0.992301 -1.5674 1 0 1 1 0 0 +EDGE2 7850 7771 -0.0142411 -0.978227 -1.55976 1 0 1 1 0 0 +EDGE2 7850 7791 -0.0311725 -1.01948 -1.58685 1 0 1 1 0 0 +EDGE2 7850 7011 -0.0344876 -0.901889 -1.61299 1 0 1 1 0 0 +EDGE2 7851 7052 0.994133 0.13244 0.0353595 1 0 1 1 0 0 +EDGE2 7851 7832 0.93881 0.077866 -0.0102075 1 0 1 1 0 0 +EDGE2 7851 7812 1.04594 -0.0959644 0.00612152 1 0 1 1 0 0 +EDGE2 7851 7811 0.0832705 0.0618407 -0.0153137 1 0 1 1 0 0 +EDGE2 7851 7831 -0.0003678 -0.0474418 -0.0244926 1 0 1 1 0 0 +EDGE2 7851 7051 0.0223058 0.015945 0.0131004 1 0 1 1 0 0 +EDGE2 7851 7770 -0.971073 0.00049442 1.59186 1 0 1 1 0 0 +EDGE2 7851 7810 -0.902483 0.00551846 -1.55694 1 0 1 1 0 0 +EDGE2 7851 7830 -1.05592 0.0407705 -1.59069 1 0 1 1 0 0 +EDGE2 7851 7850 -0.9901 -0.0472141 -1.60787 1 0 1 1 0 0 +EDGE2 7851 7790 -0.991824 -0.0730151 1.57476 1 0 1 1 0 0 +EDGE2 7851 7010 -1.08004 0.065029 1.57219 1 0 1 1 0 0 +EDGE2 7851 7030 -1.12158 -0.0551087 1.57359 1 0 1 1 0 0 +EDGE2 7851 7050 -0.972077 0.00920141 1.57009 1 0 1 1 0 0 +EDGE2 7852 7813 1.00103 -0.00426365 0.00232006 1 0 1 1 0 0 +EDGE2 7852 7833 0.994942 0.0334791 -0.0278393 1 0 1 1 0 0 +EDGE2 7852 7052 0.037633 -0.0330654 0.0333678 1 0 1 1 0 0 +EDGE2 7852 7832 0.00806831 0.0214111 0.0377904 1 0 1 1 0 0 +EDGE2 7852 7053 1.00204 0.0607456 0.00698147 1 0 1 1 0 0 +EDGE2 7852 7812 0.0166266 0.0709814 0.00740505 1 0 1 1 0 0 +EDGE2 7852 7811 -0.969815 0.0169203 0.00100602 1 0 1 1 0 0 +EDGE2 7852 7831 -1.00656 -0.0248785 0.00228699 1 0 1 1 0 0 +EDGE2 7852 7851 -1.00908 -0.0144246 0.00235015 1 0 1 1 0 0 +EDGE2 7852 7051 -1.0888 -0.0084471 -0.00627648 1 0 1 1 0 0 +EDGE2 7853 7813 0.0681688 -0.0149295 -0.02234 1 0 1 1 0 0 +EDGE2 7853 7834 0.961873 -0.0301636 0.0186156 1 0 1 1 0 0 +EDGE2 7853 7054 0.997734 0.0178981 -0.0203939 1 0 1 1 0 0 +EDGE2 7853 7814 0.9783 -0.0257122 0.0122643 1 0 1 1 0 0 +EDGE2 7853 7833 -0.0227535 -0.0275477 0.0250977 1 0 1 1 0 0 +EDGE2 7853 7052 -0.99545 0.057519 0.0160302 1 0 1 1 0 0 +EDGE2 7853 7832 -0.99414 -0.0820219 0.0231281 1 0 1 1 0 0 +EDGE2 7853 7852 -1.01812 -0.0170738 -0.0391145 1 0 1 1 0 0 +EDGE2 7853 7053 -0.000270028 0.0402382 0.026014 1 0 1 1 0 0 +EDGE2 7853 7812 -1.04355 0.0722473 0.0216006 1 0 1 1 0 0 +EDGE2 7854 7813 -1.08631 -0.0281989 0.0269825 1 0 1 1 0 0 +EDGE2 7854 7834 0.0708919 -0.100975 0.0251594 1 0 1 1 0 0 +EDGE2 7854 7055 0.952606 -0.0156677 -0.00518213 1 0 1 1 0 0 +EDGE2 7854 7815 1.19991 -0.0339721 -0.00493832 1 0 1 1 0 0 +EDGE2 7854 7835 0.995715 -0.0677098 -0.0103323 1 0 1 1 0 0 +EDGE2 7854 7853 -0.963906 -0.0682357 -0.0151245 1 0 1 1 0 0 +EDGE2 7854 7054 -0.00712537 -0.0739565 0.0196256 1 0 1 1 0 0 +EDGE2 7854 7814 0.0108165 -0.0402535 0.0264659 1 0 1 1 0 0 +EDGE2 7854 7833 -1.02362 0.00288322 0.00208244 1 0 1 1 0 0 +EDGE2 7854 7053 -1.09191 -0.0302648 0.0035693 1 0 1 1 0 0 +EDGE2 7855 7836 -0.014284 0.997297 1.5665 1 0 1 1 0 0 +EDGE2 7855 7056 -0.0189251 0.98307 1.58849 1 0 1 1 0 0 +EDGE2 7855 7816 0.0646077 1.01286 1.57651 1 0 1 1 0 0 +EDGE2 7855 7834 -0.983099 0.119547 -0.0173435 1 0 1 1 0 0 +EDGE2 7855 7055 -0.0265039 -0.0111915 -0.0130018 1 0 1 1 0 0 +EDGE2 7855 7815 -0.0194238 -0.0395893 -0.0198907 1 0 1 1 0 0 +EDGE2 7855 7835 -0.0289404 0.0419733 0.015287 1 0 1 1 0 0 +EDGE2 7855 7854 -0.935852 -0.0528292 0.0275674 1 0 1 1 0 0 +EDGE2 7855 7054 -1.07251 0.0148297 0.0228275 1 0 1 1 0 0 +EDGE2 7855 7814 -0.936858 -0.0487309 0.0418336 1 0 1 1 0 0 +EDGE2 7856 7855 -0.983126 0.0173645 1.57321 1 0 1 1 0 0 +EDGE2 7856 7055 -0.981506 -0.00660086 1.57437 1 0 1 1 0 0 +EDGE2 7856 7815 -1.0316 -0.0228434 1.59268 1 0 1 1 0 0 +EDGE2 7856 7835 -0.96367 0.0142535 1.562 1 0 1 1 0 0 +EDGE2 7857 7856 -1.04854 -0.0709211 -0.00815895 1 0 1 1 0 0 +EDGE2 7858 7857 -1.07503 0.0300085 -0.00921609 1 0 1 1 0 0 +EDGE2 7859 7858 -0.96823 -0.000155464 0.0178143 1 0 1 1 0 0 +EDGE2 7859 7240 1.05659 -0.0417448 -3.13869 1 0 1 1 0 0 +EDGE2 7859 7760 0.952039 -0.0951129 -3.12811 1 0 1 1 0 0 +EDGE2 7860 7859 -0.959336 -0.0471927 0.0196319 1 0 1 1 0 0 +EDGE2 7860 7241 -0.059459 1.0241 1.57375 1 0 1 1 0 0 +EDGE2 7860 7240 0.00913618 0.0282501 -3.11982 1 0 1 1 0 0 +EDGE2 7860 7760 0.0176415 0.0089553 -3.17505 1 0 1 1 0 0 +EDGE2 7860 7761 -0.0177924 -1.07443 -1.60054 1 0 1 1 0 0 +EDGE2 7860 7239 0.972992 -0.0716354 -3.14299 1 0 1 1 0 0 +EDGE2 7860 7759 0.878275 0.11403 -3.14512 1 0 1 1 0 0 +EDGE2 7861 7242 0.959762 -0.0143691 -0.00784239 1 0 1 1 0 0 +EDGE2 7861 7241 0.00477621 0.0981689 -0.00321309 1 0 1 1 0 0 +EDGE2 7861 7240 -1.03231 -0.0735372 1.56965 1 0 1 1 0 0 +EDGE2 7861 7760 -0.968406 -0.0396581 1.58029 1 0 1 1 0 0 +EDGE2 7861 7860 -0.97715 0.00674402 -1.58944 1 0 1 1 0 0 +EDGE2 7862 7243 1.02205 0.0229933 -0.015804 1 0 1 1 0 0 +EDGE2 7862 7861 -1.0755 0.0897946 0.0111841 1 0 1 1 0 0 +EDGE2 7862 7242 -0.0295854 0.0225216 0.0210279 1 0 1 1 0 0 +EDGE2 7862 7241 -1.08474 0.0572114 0.00273034 1 0 1 1 0 0 +EDGE2 7863 7244 1.00751 0.0101365 0.0140244 1 0 1 1 0 0 +EDGE2 7863 7862 -0.892096 -0.0122608 0.0075371 1 0 1 1 0 0 +EDGE2 7863 7243 -0.0979867 0.110102 -0.00707548 1 0 1 1 0 0 +EDGE2 7863 7242 -0.90606 0.063736 0.0214823 1 0 1 1 0 0 +EDGE2 7864 7244 0.100737 -0.11289 -0.0168769 1 0 1 1 0 0 +EDGE2 7864 7245 1.06943 0.0531086 0.00105347 1 0 1 1 0 0 +EDGE2 7864 7243 -1.06619 0.0303313 -0.0064482 1 0 1 1 0 0 +EDGE2 7864 7863 -1.13973 0.0541901 0.0211063 1 0 1 1 0 0 +EDGE2 7865 7244 -1.02742 -0.0559581 0.00923712 1 0 1 1 0 0 +EDGE2 7865 7246 -0.015682 1.04838 1.57847 1 0 1 1 0 0 +EDGE2 7865 7245 -0.0596777 0.0367228 0.0254245 1 0 1 1 0 0 +EDGE2 7865 7864 -0.964902 0.0728873 -0.0557263 1 0 1 1 0 0 +EDGE2 7866 7247 1.02356 -0.0584138 -0.00104945 1 0 1 1 0 0 +EDGE2 7866 7246 -0.0828301 0.00898134 -0.0103573 1 0 1 1 0 0 +EDGE2 7866 7865 -0.996509 -0.0485895 -1.59089 1 0 1 1 0 0 +EDGE2 7866 7245 -1.02764 0.0785691 -1.59331 1 0 1 1 0 0 +EDGE2 7867 7248 1.03482 -0.0206034 0.0364417 1 0 1 1 0 0 +EDGE2 7867 7247 -0.0107211 -0.00384247 -0.00779443 1 0 1 1 0 0 +EDGE2 7867 7246 -0.988973 -0.00385903 0.00762058 1 0 1 1 0 0 +EDGE2 7867 7866 -0.990731 -0.0474358 0.00232716 1 0 1 1 0 0 +EDGE2 7868 7249 1.04512 -0.0479105 0.000925213 1 0 1 1 0 0 +EDGE2 7868 7248 0.0538559 0.0691219 -0.0132582 1 0 1 1 0 0 +EDGE2 7868 7247 -0.969 -0.0564931 -0.0452192 1 0 1 1 0 0 +EDGE2 7868 7867 -1.00139 -0.0165279 -0.0256673 1 0 1 1 0 0 +EDGE2 7869 7250 0.906215 -0.0278213 0.0175437 1 0 1 1 0 0 +EDGE2 7869 7430 1.02435 0.028199 -3.16592 1 0 1 1 0 0 +EDGE2 7869 7270 1.08918 0.0105364 -3.082 1 0 1 1 0 0 +EDGE2 7869 7110 0.990898 -0.0185771 -3.16803 1 0 1 1 0 0 +EDGE2 7869 7130 1.08089 0.0330099 -3.13948 1 0 1 1 0 0 +EDGE2 7869 7249 -0.0878743 -0.0382921 -0.00911466 1 0 1 1 0 0 +EDGE2 7869 7248 -0.892554 0.0266115 -0.000618181 1 0 1 1 0 0 +EDGE2 7869 7868 -0.970053 -3.66541e-05 -0.0318012 1 0 1 1 0 0 +EDGE2 7870 7131 0.039252 -0.995233 -1.57003 1 0 1 1 0 0 +EDGE2 7870 7271 0.133295 -0.984633 -1.57489 1 0 1 1 0 0 +EDGE2 7870 7431 -0.0675816 -0.945672 -1.55929 1 0 1 1 0 0 +EDGE2 7870 7251 -0.0649662 -0.988248 -1.55535 1 0 1 1 0 0 +EDGE2 7870 7111 0.0163369 -0.979573 -1.58015 1 0 1 1 0 0 +EDGE2 7870 7129 1.016 0.024028 -3.13959 1 0 1 1 0 0 +EDGE2 7870 7269 0.918261 0.100708 -3.15491 1 0 1 1 0 0 +EDGE2 7870 7429 1.0067 -0.089902 -3.1819 1 0 1 1 0 0 +EDGE2 7870 7109 0.91919 0.0458739 -3.13642 1 0 1 1 0 0 +EDGE2 7870 7250 0.0568572 0.151756 0.00774499 1 0 1 1 0 0 +EDGE2 7870 7430 -0.101657 0.0296647 -3.16945 1 0 1 1 0 0 +EDGE2 7870 7270 -0.0424202 -0.0163962 -3.14259 1 0 1 1 0 0 +EDGE2 7870 7110 0.00884067 0.016497 -3.1314 1 0 1 1 0 0 +EDGE2 7870 7130 -0.0631873 -0.0229669 -3.17096 1 0 1 1 0 0 +EDGE2 7870 7249 -0.9748 -0.0282938 0.0118178 1 0 1 1 0 0 +EDGE2 7870 7869 -0.952234 0.0378891 -0.00753693 1 0 1 1 0 0 +EDGE2 7871 7250 -0.991317 -0.123991 -1.5499 1 0 1 1 0 0 +EDGE2 7871 7430 -1.00778 -0.0790026 1.56345 1 0 1 1 0 0 +EDGE2 7871 7870 -0.927539 -0.00391398 -1.57297 1 0 1 1 0 0 +EDGE2 7871 7270 -1.0558 0.00250481 1.58338 1 0 1 1 0 0 +EDGE2 7871 7110 -0.961327 -0.0295237 1.58447 1 0 1 1 0 0 +EDGE2 7871 7130 -1.00278 0.0338968 1.59141 1 0 1 1 0 0 +EDGE2 7872 7871 -0.976895 -0.000476669 0.0458422 1 0 1 1 0 0 +EDGE2 7873 7872 -1.02859 0.0511548 -0.0386253 1 0 1 1 0 0 +EDGE2 7874 7855 0.96174 -0.0818705 -3.14269 1 0 1 1 0 0 +EDGE2 7874 7873 -0.976277 0.0507373 -0.00866979 1 0 1 1 0 0 +EDGE2 7874 7055 1.00215 -0.00779542 -3.19342 1 0 1 1 0 0 +EDGE2 7874 7815 1.02072 0.0158466 -3.14626 1 0 1 1 0 0 +EDGE2 7874 7835 0.876733 -0.0241971 -3.15999 1 0 1 1 0 0 +EDGE2 7875 7855 -0.104588 -0.00920554 -3.12621 1 0 1 1 0 0 +EDGE2 7875 7836 -0.0686793 -1.00397 -1.56503 1 0 1 1 0 0 +EDGE2 7875 7056 -0.0318743 -1.03405 -1.55108 1 0 1 1 0 0 +EDGE2 7875 7816 -0.164313 -0.996385 -1.57518 1 0 1 1 0 0 +EDGE2 7875 7874 -1.0399 0.0234029 -0.0178407 1 0 1 1 0 0 +EDGE2 7875 7834 0.978763 0.0519993 -3.15781 1 0 1 1 0 0 +EDGE2 7875 7055 -0.0462315 -0.0112469 -3.14027 1 0 1 1 0 0 +EDGE2 7875 7815 0.0334012 0.0682154 -3.1473 1 0 1 1 0 0 +EDGE2 7875 7835 -0.020931 -0.00437206 -3.13171 1 0 1 1 0 0 +EDGE2 7875 7854 0.99207 0.00309269 -3.10961 1 0 1 1 0 0 +EDGE2 7875 7054 1.01418 0.0921238 -3.11031 1 0 1 1 0 0 +EDGE2 7875 7814 1.00465 0.00218704 -3.12683 1 0 1 1 0 0 +EDGE2 7875 7856 0.0137226 0.991843 1.55368 1 0 1 1 0 0 +EDGE2 7876 7855 -1.06872 -0.0339584 1.56255 1 0 1 1 0 0 +EDGE2 7876 7875 -0.946763 -0.0191743 -1.55571 1 0 1 1 0 0 +EDGE2 7876 7055 -1.04416 -0.0734979 1.55413 1 0 1 1 0 0 +EDGE2 7876 7815 -1.02197 0.0248852 1.5898 1 0 1 1 0 0 +EDGE2 7876 7835 -0.991742 0.0132972 1.536 1 0 1 1 0 0 +EDGE2 7876 7856 0.0374034 0.00967965 0.0148597 1 0 1 1 0 0 +EDGE2 7876 7857 1.06153 -0.0746766 0.00140289 1 0 1 1 0 0 +EDGE2 7877 7876 -1.02252 -0.100376 -0.000777181 1 0 1 1 0 0 +EDGE2 7877 7856 -1.08088 -0.00103646 -0.00600358 1 0 1 1 0 0 +EDGE2 7877 7858 0.962422 0.0303968 0.0103943 1 0 1 1 0 0 +EDGE2 7877 7857 0.00129611 -0.00410442 -0.0104074 1 0 1 1 0 0 +EDGE2 7878 7858 0.0989834 0.141357 -0.00562491 1 0 1 1 0 0 +EDGE2 7878 7857 -1.04505 -0.000169862 -0.00646605 1 0 1 1 0 0 +EDGE2 7878 7877 -1.01067 0.0678966 0.0156296 1 0 1 1 0 0 +EDGE2 7878 7859 0.891809 -0.0120186 -0.0072382 1 0 1 1 0 0 +EDGE2 7879 7858 -1.0515 0.0690137 -0.0157107 1 0 1 1 0 0 +EDGE2 7879 7878 -1.01654 -0.00226433 0.0479755 1 0 1 1 0 0 +EDGE2 7879 7859 0.06191 0.0208669 0.0293277 1 0 1 1 0 0 +EDGE2 7879 7240 0.919815 -0.0112022 -3.15501 1 0 1 1 0 0 +EDGE2 7879 7760 1.04022 0.0245961 -3.17486 1 0 1 1 0 0 +EDGE2 7879 7860 0.948842 -0.00392586 0.0150266 1 0 1 1 0 0 +EDGE2 7880 7859 -0.987886 0.0171259 -0.00429359 1 0 1 1 0 0 +EDGE2 7880 7879 -1.04937 -0.00344638 -0.0210263 1 0 1 1 0 0 +EDGE2 7880 7861 -0.052847 0.994504 1.54553 1 0 1 1 0 0 +EDGE2 7880 7241 0.0819237 0.93254 1.59493 1 0 1 1 0 0 +EDGE2 7880 7240 0.0346965 0.0332175 -3.13717 1 0 1 1 0 0 +EDGE2 7880 7760 0.0479013 0.0334916 -3.13015 1 0 1 1 0 0 +EDGE2 7880 7860 0.00150262 -0.0584563 0.00404093 1 0 1 1 0 0 +EDGE2 7880 7761 -0.0255942 -1.07919 -1.5472 1 0 1 1 0 0 +EDGE2 7880 7239 1.08588 0.193344 -3.10787 1 0 1 1 0 0 +EDGE2 7880 7759 0.943151 -0.116492 -3.17768 1 0 1 1 0 0 +EDGE2 7881 7880 -1.05785 -0.061173 -1.55641 1 0 1 1 0 0 +EDGE2 7881 7862 1.02868 -0.0547352 0.0501746 1 0 1 1 0 0 +EDGE2 7881 7861 -0.0295177 0.0433567 0.0209791 1 0 1 1 0 0 +EDGE2 7881 7242 0.919797 -0.000303907 -0.00550582 1 0 1 1 0 0 +EDGE2 7881 7241 -0.0118913 0.00162061 0.0173587 1 0 1 1 0 0 +EDGE2 7881 7240 -0.893947 -0.0353191 1.56418 1 0 1 1 0 0 +EDGE2 7881 7760 -0.999299 0.0687145 1.56284 1 0 1 1 0 0 +EDGE2 7881 7860 -1.04382 -0.0595268 -1.5978 1 0 1 1 0 0 +EDGE2 7882 7862 -0.0194841 -0.00965064 0.00866435 1 0 1 1 0 0 +EDGE2 7882 7243 1.05021 -0.00373782 0.0229199 1 0 1 1 0 0 +EDGE2 7882 7863 0.986328 0.0176454 -0.0243974 1 0 1 1 0 0 +EDGE2 7882 7861 -0.962298 -0.0191071 -0.0135409 1 0 1 1 0 0 +EDGE2 7882 7881 -0.924587 -0.0135599 0.0199028 1 0 1 1 0 0 +EDGE2 7882 7242 -0.0508785 0.0510674 0.0199453 1 0 1 1 0 0 +EDGE2 7882 7241 -1.01643 0.0488397 -0.0224316 1 0 1 1 0 0 +EDGE2 7883 7244 0.939953 -0.0140354 0.0361558 1 0 1 1 0 0 +EDGE2 7883 7864 0.989978 0.015488 -0.0214196 1 0 1 1 0 0 +EDGE2 7883 7862 -0.968683 0.0917368 -0.0128299 1 0 1 1 0 0 +EDGE2 7883 7243 -0.0778208 0.0326526 0.000288407 1 0 1 1 0 0 +EDGE2 7883 7863 -0.016273 -0.09988 -0.00531794 1 0 1 1 0 0 +EDGE2 7883 7882 -1.0306 -2.87163e-05 0.0120753 1 0 1 1 0 0 +EDGE2 7883 7242 -1.03038 0.0242897 0.0116596 1 0 1 1 0 0 +EDGE2 7884 7244 -0.0629199 -0.00485225 0.00556246 1 0 1 1 0 0 +EDGE2 7884 7865 1.02503 0.136605 -0.0158114 1 0 1 1 0 0 +EDGE2 7884 7245 0.982732 -0.0141479 -0.0422283 1 0 1 1 0 0 +EDGE2 7884 7864 0.054043 -0.0361178 -0.0185791 1 0 1 1 0 0 +EDGE2 7884 7243 -0.989704 -0.0190127 0.0172637 1 0 1 1 0 0 +EDGE2 7884 7863 -0.964872 -0.0465566 0.00184731 1 0 1 1 0 0 +EDGE2 7884 7883 -1.02215 0.0389388 -0.00823857 1 0 1 1 0 0 +EDGE2 7885 7244 -1.03595 0.0372021 0.0285955 1 0 1 1 0 0 +EDGE2 7885 7884 -0.99756 -0.0570014 0.00326684 1 0 1 1 0 0 +EDGE2 7885 7246 0.0125511 0.97207 1.53989 1 0 1 1 0 0 +EDGE2 7885 7866 -0.0190545 0.985151 1.58537 1 0 1 1 0 0 +EDGE2 7885 7865 -0.0530497 0.0666216 0.00586103 1 0 1 1 0 0 +EDGE2 7885 7245 -0.0162239 -0.00463404 -0.0296855 1 0 1 1 0 0 +EDGE2 7885 7864 -1.06104 0.0235158 -0.0205788 1 0 1 1 0 0 +EDGE2 7886 7865 -1.00618 0.030454 1.58343 1 0 1 1 0 0 +EDGE2 7886 7885 -1.13566 -0.0251703 1.58677 1 0 1 1 0 0 +EDGE2 7886 7245 -0.918317 0.00148719 1.53704 1 0 1 1 0 0 +EDGE2 7887 7886 -0.945974 0.0219427 0.0254804 1 0 1 1 0 0 +EDGE2 7888 7887 -1.0057 0.0315152 -0.00551413 1 0 1 1 0 0 +EDGE2 7889 7888 -1.04886 -0.0653779 -0.00205751 1 0 1 1 0 0 +EDGE2 7889 7750 0.921057 0.00855081 -3.14282 1 0 1 1 0 0 +EDGE2 7889 7230 1.00359 -0.0664882 -3.15975 1 0 1 1 0 0 +EDGE2 7890 7889 -0.984094 0.0521721 0.0192744 1 0 1 1 0 0 +EDGE2 7890 7750 0.0525651 -0.0172893 -3.17056 1 0 1 1 0 0 +EDGE2 7890 7229 0.970633 0.0523091 -3.12588 1 0 1 1 0 0 +EDGE2 7890 7749 0.9012 0.0442101 -3.14825 1 0 1 1 0 0 +EDGE2 7890 7230 -0.0531811 0.016031 -3.10495 1 0 1 1 0 0 +EDGE2 7890 7231 -0.0139955 -0.987586 -1.59111 1 0 1 1 0 0 +EDGE2 7890 7751 -0.00112515 -0.970033 -1.56417 1 0 1 1 0 0 +EDGE2 7891 7750 -1.03737 -0.00445304 1.57607 1 0 1 1 0 0 +EDGE2 7891 7890 -1.05359 -0.00842776 -1.53865 1 0 1 1 0 0 +EDGE2 7891 7230 -0.977175 -0.0626582 1.58894 1 0 1 1 0 0 +EDGE2 7892 7891 -0.944264 0.00362039 -0.0105216 1 0 1 1 0 0 +EDGE2 7893 7892 -1.01098 -0.0358074 -0.00226676 1 0 1 1 0 0 +EDGE2 7894 7195 0.991379 -0.0103587 -3.15031 1 0 1 1 0 0 +EDGE2 7894 7893 -0.957115 0.0176135 0.00253152 1 0 1 1 0 0 +EDGE2 7895 7194 0.991559 -0.0204287 -3.10275 1 0 1 1 0 0 +EDGE2 7895 7195 0.0636971 -0.0299225 -3.12107 1 0 1 1 0 0 +EDGE2 7895 7894 -1.07852 0.0272948 0.0252318 1 0 1 1 0 0 +EDGE2 7895 7196 -0.0154492 -1.00938 -1.57749 1 0 1 1 0 0 +EDGE2 7896 7895 -1.00394 -0.00475068 -1.55832 1 0 1 1 0 0 +EDGE2 7896 7195 -1.0358 0.0307315 1.5686 1 0 1 1 0 0 +EDGE2 7897 7896 -0.957275 -0.0460648 -0.0108403 1 0 1 1 0 0 +EDGE2 7898 7897 -0.965652 0.0369479 0.0138561 1 0 1 1 0 0 +EDGE2 7899 7320 1.00353 -0.0111924 -3.10774 1 0 1 1 0 0 +EDGE2 7899 7360 0.987879 0.00950248 -3.15259 1 0 1 1 0 0 +EDGE2 7899 7340 0.921563 -0.0113993 -3.17214 1 0 1 1 0 0 +EDGE2 7899 7180 0.964322 0.00427183 -3.13801 1 0 1 1 0 0 +EDGE2 7899 7280 1.05794 -0.0140031 -3.15128 1 0 1 1 0 0 +EDGE2 7899 7300 1.00024 0.0609805 -3.12287 1 0 1 1 0 0 +EDGE2 7899 7898 -1.03663 0.000242299 -0.000982379 1 0 1 1 0 0 +EDGE2 7900 7341 -0.00486429 -0.994789 -1.55307 1 0 1 1 0 0 +EDGE2 7900 7339 0.950317 0.0666154 -3.18222 1 0 1 1 0 0 +EDGE2 7900 7359 1.04302 -0.0471969 -3.13487 1 0 1 1 0 0 +EDGE2 7900 7279 0.999254 0.0164032 -3.13783 1 0 1 1 0 0 +EDGE2 7900 7299 0.954945 -0.00013193 -3.17051 1 0 1 1 0 0 +EDGE2 7900 7319 1.03124 0.0727856 -3.14546 1 0 1 1 0 0 +EDGE2 7900 7179 1.00179 0.0116301 -3.14341 1 0 1 1 0 0 +EDGE2 7900 7361 -0.0343181 -1.04587 -1.59966 1 0 1 1 0 0 +EDGE2 7900 7320 -0.00666882 -0.0132202 -3.1563 1 0 1 1 0 0 +EDGE2 7900 7281 0.0244755 -1.00959 -1.56314 1 0 1 1 0 0 +EDGE2 7900 7301 0.0190482 -0.943517 -1.54294 1 0 1 1 0 0 +EDGE2 7900 7321 0.0410458 -0.991124 -1.57897 1 0 1 1 0 0 +EDGE2 7900 7181 -0.00186446 -1.01389 -1.57009 1 0 1 1 0 0 +EDGE2 7900 7360 0.0260069 0.0292574 -3.13375 1 0 1 1 0 0 +EDGE2 7900 7340 0.0246691 0.0545353 -3.14745 1 0 1 1 0 0 +EDGE2 7900 7180 0.0285629 0.0757595 -3.12532 1 0 1 1 0 0 +EDGE2 7900 7280 0.00220831 -0.0342417 -3.13616 1 0 1 1 0 0 +EDGE2 7900 7300 -0.0605944 0.0922246 -3.10633 1 0 1 1 0 0 +EDGE2 7900 7899 -0.969508 -0.0475296 -0.00125784 1 0 1 1 0 0 +EDGE2 7901 7320 -0.946372 0.0433553 1.54578 1 0 1 1 0 0 +EDGE2 7901 7360 -1.01436 -0.046312 1.58528 1 0 1 1 0 0 +EDGE2 7901 7900 -1.00785 -0.033386 -1.5507 1 0 1 1 0 0 +EDGE2 7901 7340 -0.959866 -0.00201527 1.57329 1 0 1 1 0 0 +EDGE2 7901 7180 -0.948422 0.0483277 1.56712 1 0 1 1 0 0 +EDGE2 7901 7280 -1.02801 0.0303698 1.57547 1 0 1 1 0 0 +EDGE2 7901 7300 -0.967808 0.0128117 1.57138 1 0 1 1 0 0 +EDGE2 7902 7901 -0.961157 0.0247437 0.000559758 1 0 1 1 0 0 +EDGE2 7903 7902 -0.920178 -0.0112478 0.0096771 1 0 1 1 0 0 +EDGE2 7904 7903 -1.05471 -0.0702125 0.0296867 1 0 1 1 0 0 +EDGE2 7904 7865 0.986378 -0.0601306 -3.12087 1 0 1 1 0 0 +EDGE2 7904 7885 0.988408 -0.0602637 -3.13387 1 0 1 1 0 0 +EDGE2 7904 7245 1.07327 0.0888529 -3.15151 1 0 1 1 0 0 +EDGE2 7905 7244 0.958104 0.0319657 -3.15314 1 0 1 1 0 0 +EDGE2 7905 7884 1.04537 0.0070283 -3.12171 1 0 1 1 0 0 +EDGE2 7905 7246 -0.00707576 -1.01761 -1.58661 1 0 1 1 0 0 +EDGE2 7905 7866 0.0447163 -0.992802 -1.55431 1 0 1 1 0 0 +EDGE2 7905 7904 -0.985625 0.0848625 0.00213001 1 0 1 1 0 0 +EDGE2 7905 7865 0.0657272 0.00400666 -3.13479 1 0 1 1 0 0 +EDGE2 7905 7885 -0.0133438 -0.0314552 -3.14913 1 0 1 1 0 0 +EDGE2 7905 7245 0.0158798 0.0698712 -3.12224 1 0 1 1 0 0 +EDGE2 7905 7864 0.893213 -0.0121491 -3.12852 1 0 1 1 0 0 +EDGE2 7905 7886 -0.0726989 0.904735 1.61591 1 0 1 1 0 0 +EDGE2 7906 7865 -0.941004 -0.0434627 1.55523 1 0 1 1 0 0 +EDGE2 7906 7885 -1.07517 0.0554084 1.56007 1 0 1 1 0 0 +EDGE2 7906 7905 -0.976985 -0.0174207 -1.56389 1 0 1 1 0 0 +EDGE2 7906 7245 -1.03526 -0.0125222 1.54665 1 0 1 1 0 0 +EDGE2 7906 7887 0.954812 0.0370948 0.0244018 1 0 1 1 0 0 +EDGE2 7906 7886 -0.0658322 0.0816236 0.010001 1 0 1 1 0 0 +EDGE2 7907 7887 -0.032938 -0.0394094 0.0170254 1 0 1 1 0 0 +EDGE2 7907 7886 -0.997169 0.0523109 -0.0181624 1 0 1 1 0 0 +EDGE2 7907 7906 -1.00517 -0.0227202 0.00178168 1 0 1 1 0 0 +EDGE2 7907 7888 0.918631 0.00253306 0.0122057 1 0 1 1 0 0 +EDGE2 7908 7887 -1.03422 -0.0126376 -0.0236727 1 0 1 1 0 0 +EDGE2 7908 7907 -1.04193 0.0163799 -0.021675 1 0 1 1 0 0 +EDGE2 7908 7888 -0.0119142 -0.0599603 -0.0273692 1 0 1 1 0 0 +EDGE2 7908 7889 0.989852 -0.0938567 0.0287391 1 0 1 1 0 0 +EDGE2 7909 7888 -0.95201 0.0524045 0.0104044 1 0 1 1 0 0 +EDGE2 7909 7908 -1.01094 0.0629664 0.0099637 1 0 1 1 0 0 +EDGE2 7909 7889 -0.0162408 0.0673665 0.0170346 1 0 1 1 0 0 +EDGE2 7909 7750 0.970968 -0.0885821 -3.09963 1 0 1 1 0 0 +EDGE2 7909 7890 1.06445 0.0787594 0.0121885 1 0 1 1 0 0 +EDGE2 7909 7230 1.05009 -0.0197586 -3.16485 1 0 1 1 0 0 +EDGE2 7910 7909 -0.98418 -0.0274399 0.0177947 1 0 1 1 0 0 +EDGE2 7910 7889 -1.01514 0.0308009 -0.0155756 1 0 1 1 0 0 +EDGE2 7910 7750 0.0564877 -0.00772912 -3.15196 1 0 1 1 0 0 +EDGE2 7910 7890 0.00846216 -0.0555308 0.00870728 1 0 1 1 0 0 +EDGE2 7910 7891 -0.0701179 0.95346 1.55086 1 0 1 1 0 0 +EDGE2 7910 7229 1.03819 -0.115782 -3.14231 1 0 1 1 0 0 +EDGE2 7910 7749 1.02025 0.0485642 -3.11054 1 0 1 1 0 0 +EDGE2 7910 7230 -0.059862 -0.0596751 -3.12857 1 0 1 1 0 0 +EDGE2 7910 7231 -0.022454 -1.01198 -1.5544 1 0 1 1 0 0 +EDGE2 7910 7751 -0.0582538 -0.981026 -1.58639 1 0 1 1 0 0 +EDGE2 7911 7750 -1.03985 -0.0932205 1.57301 1 0 1 1 0 0 +EDGE2 7911 7890 -0.967488 0.030902 -1.58372 1 0 1 1 0 0 +EDGE2 7911 7891 -0.0868874 0.0217321 -0.0113372 1 0 1 1 0 0 +EDGE2 7911 7892 1.04436 0.0301495 0.0135618 1 0 1 1 0 0 +EDGE2 7911 7910 -0.978907 0.0219189 -1.54286 1 0 1 1 0 0 +EDGE2 7911 7230 -0.938359 -0.0223616 1.56272 1 0 1 1 0 0 +EDGE2 7912 7893 0.965812 0.00186119 -0.0189276 1 0 1 1 0 0 +EDGE2 7912 7891 -0.949088 4.96698e-06 -0.0352433 1 0 1 1 0 0 +EDGE2 7912 7911 -1.06252 -0.00688984 -0.0016849 1 0 1 1 0 0 +EDGE2 7912 7892 -0.0197933 0.0280015 0.0218992 1 0 1 1 0 0 +EDGE2 7913 7912 -0.93147 0.000134971 -0.00669288 1 0 1 1 0 0 +EDGE2 7913 7894 0.981491 0.0211122 0.00506395 1 0 1 1 0 0 +EDGE2 7913 7893 -0.0212971 0.0159955 -0.0217398 1 0 1 1 0 0 +EDGE2 7913 7892 -0.934874 -0.0012263 -0.0497707 1 0 1 1 0 0 +EDGE2 7914 7895 0.891515 0.00751224 0.00618293 1 0 1 1 0 0 +EDGE2 7914 7195 1.05712 0.0294719 -3.14943 1 0 1 1 0 0 +EDGE2 7914 7913 -1.09593 0.0613709 -0.0104079 1 0 1 1 0 0 +EDGE2 7914 7894 -0.00481477 0.0147838 0.00846006 1 0 1 1 0 0 +EDGE2 7914 7893 -1.01282 0.0148514 -0.00966556 1 0 1 1 0 0 +EDGE2 7915 7194 1.01226 0.0264234 -3.13355 1 0 1 1 0 0 +EDGE2 7915 7914 -0.975904 -0.0199014 -0.0012398 1 0 1 1 0 0 +EDGE2 7915 7895 -0.0282231 -0.0411191 0.0102878 1 0 1 1 0 0 +EDGE2 7915 7896 0.0656715 1.03707 1.60928 1 0 1 1 0 0 +EDGE2 7915 7195 -0.028505 0.00126144 -3.11805 1 0 1 1 0 0 +EDGE2 7915 7894 -1.08795 0.0135754 0.00276965 1 0 1 1 0 0 +EDGE2 7915 7196 -0.0153015 -0.991105 -1.57569 1 0 1 1 0 0 +EDGE2 7916 7897 0.971072 0.037777 -0.0237855 1 0 1 1 0 0 +EDGE2 7916 7895 -0.909158 0.00815817 -1.54659 1 0 1 1 0 0 +EDGE2 7916 7915 -0.972677 -0.0786669 -1.58022 1 0 1 1 0 0 +EDGE2 7916 7896 0.0090186 0.0904594 -0.000272849 1 0 1 1 0 0 +EDGE2 7916 7195 -1.05756 0.0503228 1.55365 1 0 1 1 0 0 +EDGE2 7917 7916 -0.966206 -0.0126669 -0.0200132 1 0 1 1 0 0 +EDGE2 7917 7897 -0.0111747 0.0053941 0.0608893 1 0 1 1 0 0 +EDGE2 7917 7898 1.0111 0.0336532 0.0252699 1 0 1 1 0 0 +EDGE2 7917 7896 -0.978112 -0.0231737 -0.0124727 1 0 1 1 0 0 +EDGE2 7918 7897 -0.998404 -0.049349 0.0153015 1 0 1 1 0 0 +EDGE2 7918 7898 0.12221 -0.028872 -0.022519 1 0 1 1 0 0 +EDGE2 7918 7899 0.92471 -0.0600525 -0.0437903 1 0 1 1 0 0 +EDGE2 7918 7917 -1.08042 0.0362203 -0.00183467 1 0 1 1 0 0 +EDGE2 7919 7320 0.973814 -0.0264 -3.13017 1 0 1 1 0 0 +EDGE2 7919 7360 1.10616 0.0353606 -3.12208 1 0 1 1 0 0 +EDGE2 7919 7900 1.01597 -0.00410822 -0.033511 1 0 1 1 0 0 +EDGE2 7919 7340 1.02739 0.0578433 -3.17637 1 0 1 1 0 0 +EDGE2 7919 7180 1.05475 0.0783637 -3.19498 1 0 1 1 0 0 +EDGE2 7919 7280 1.05303 -0.0212922 -3.15001 1 0 1 1 0 0 +EDGE2 7919 7300 0.954786 -0.0783456 -3.12735 1 0 1 1 0 0 +EDGE2 7919 7898 -1.0274 0.0346024 -0.0112574 1 0 1 1 0 0 +EDGE2 7919 7918 -1.03055 0.000946815 0.0087993 1 0 1 1 0 0 +EDGE2 7919 7899 -0.0341694 -0.0189741 -0.0579749 1 0 1 1 0 0 +EDGE2 7920 7341 -0.0511952 -1.16866 -1.58577 1 0 1 1 0 0 +EDGE2 7920 7339 0.970355 -0.0494435 -3.16011 1 0 1 1 0 0 +EDGE2 7920 7359 1.01543 -0.0620746 -3.11178 1 0 1 1 0 0 +EDGE2 7920 7279 0.976163 -0.0125579 -3.15565 1 0 1 1 0 0 +EDGE2 7920 7299 0.964247 -0.0303233 -3.11099 1 0 1 1 0 0 +EDGE2 7920 7319 0.982534 0.071756 -3.16078 1 0 1 1 0 0 +EDGE2 7920 7179 1.00656 -0.007225 -3.13535 1 0 1 1 0 0 +EDGE2 7920 7361 0.0657676 -1.09846 -1.57586 1 0 1 1 0 0 +EDGE2 7920 7919 -0.964095 0.00882214 -0.0410449 1 0 1 1 0 0 +EDGE2 7920 7320 -0.0414854 -0.0551942 -3.10672 1 0 1 1 0 0 +EDGE2 7920 7281 -0.0223466 -0.959715 -1.59177 1 0 1 1 0 0 +EDGE2 7920 7301 -0.0354464 -1.02546 -1.54211 1 0 1 1 0 0 +EDGE2 7920 7321 -0.0275179 -1.06838 -1.53393 1 0 1 1 0 0 +EDGE2 7920 7181 -0.114394 -1.00949 -1.57485 1 0 1 1 0 0 +EDGE2 7920 7360 -0.000928563 0.000643331 -3.13817 1 0 1 1 0 0 +EDGE2 7920 7900 0.0353563 0.0329651 0.0230776 1 0 1 1 0 0 +EDGE2 7920 7340 0.0117227 -0.0390111 -3.11663 1 0 1 1 0 0 +EDGE2 7920 7901 -0.0311754 0.998649 1.52433 1 0 1 1 0 0 +EDGE2 7920 7180 0.00765093 -0.00458436 -3.14152 1 0 1 1 0 0 +EDGE2 7920 7280 -0.013626 0.0132403 -3.13402 1 0 1 1 0 0 +EDGE2 7920 7300 0.0691026 0.0690735 -3.15695 1 0 1 1 0 0 +EDGE2 7920 7899 -0.954244 0.131124 -0.00408808 1 0 1 1 0 0 +EDGE2 7921 7341 -0.0599737 -0.00199479 0.0206676 1 0 1 1 0 0 +EDGE2 7921 7282 0.955021 0.0895452 -0.0402246 1 0 1 1 0 0 +EDGE2 7921 7322 0.899858 0.0810931 0.00488883 1 0 1 1 0 0 +EDGE2 7921 7342 0.945045 -0.0465478 -0.0121556 1 0 1 1 0 0 +EDGE2 7921 7362 1.08117 0.0307783 0.0334888 1 0 1 1 0 0 +EDGE2 7921 7302 1.03092 -0.00291662 0.0194699 1 0 1 1 0 0 +EDGE2 7921 7182 0.994867 -0.0421005 -0.0169695 1 0 1 1 0 0 +EDGE2 7921 7361 0.034092 0.033034 0.00138663 1 0 1 1 0 0 +EDGE2 7921 7320 -0.971173 0.133148 -1.54548 1 0 1 1 0 0 +EDGE2 7921 7281 0.0149263 -0.0580397 0.016554 1 0 1 1 0 0 +EDGE2 7921 7301 0.0727474 0.0304481 0.0204505 1 0 1 1 0 0 +EDGE2 7921 7321 0.0301094 0.11038 -0.0110876 1 0 1 1 0 0 +EDGE2 7921 7181 0.0264806 0.01088 0.0186585 1 0 1 1 0 0 +EDGE2 7921 7360 -0.999396 -0.0128462 -1.5322 1 0 1 1 0 0 +EDGE2 7921 7900 -1.01572 -0.0383407 1.56372 1 0 1 1 0 0 +EDGE2 7921 7920 -0.871981 -0.0531651 1.549 1 0 1 1 0 0 +EDGE2 7921 7340 -1.02418 -0.0120534 -1.5457 1 0 1 1 0 0 +EDGE2 7921 7180 -0.909384 0.00321072 -1.54367 1 0 1 1 0 0 +EDGE2 7921 7280 -1.04096 0.0146618 -1.55948 1 0 1 1 0 0 +EDGE2 7921 7300 -1.07097 0.0431164 -1.59517 1 0 1 1 0 0 +EDGE2 7922 7341 -1.034 0.0463036 -0.00963435 1 0 1 1 0 0 +EDGE2 7922 7343 1.04901 -0.030907 0.0349985 1 0 1 1 0 0 +EDGE2 7922 7363 0.997118 -0.116714 0.0133235 1 0 1 1 0 0 +EDGE2 7922 7283 1.0707 -0.035844 -0.0396319 1 0 1 1 0 0 +EDGE2 7922 7303 1.06485 -0.0326638 0.00186465 1 0 1 1 0 0 +EDGE2 7922 7323 1.0921 -0.0206554 -0.00650742 1 0 1 1 0 0 +EDGE2 7922 7183 0.968921 0.0449934 -0.0172492 1 0 1 1 0 0 +EDGE2 7922 7282 0.0619509 -0.00390592 -0.00943832 1 0 1 1 0 0 +EDGE2 7922 7322 -0.000386434 0.032921 0.031156 1 0 1 1 0 0 +EDGE2 7922 7342 -0.102537 0.0991111 0.0116333 1 0 1 1 0 0 +EDGE2 7922 7362 -0.0552761 0.0413894 -0.0171511 1 0 1 1 0 0 +EDGE2 7922 7302 -0.0390238 0.0434983 -0.00723408 1 0 1 1 0 0 +EDGE2 7922 7921 -0.94434 0.0881783 -0.0160243 1 0 1 1 0 0 +EDGE2 7922 7182 -0.0158427 -0.0902484 -0.00748433 1 0 1 1 0 0 +EDGE2 7922 7361 -0.961815 0.0430309 0.000877668 1 0 1 1 0 0 +EDGE2 7922 7281 -1.07355 0.0253714 -0.0128102 1 0 1 1 0 0 +EDGE2 7922 7301 -0.956869 -0.00853594 -0.0350464 1 0 1 1 0 0 +EDGE2 7922 7321 -0.999306 -0.0330506 -0.0311093 1 0 1 1 0 0 +EDGE2 7922 7181 -1.05643 -0.00847022 0.00307688 1 0 1 1 0 0 +EDGE2 7923 7304 1.08598 -0.038085 0.0142186 1 0 1 1 0 0 +EDGE2 7923 7344 1.03906 -0.0276625 0.0160462 1 0 1 1 0 0 +EDGE2 7923 7364 1.05268 0.0322432 -0.032544 1 0 1 1 0 0 +EDGE2 7923 7324 1.10085 0.029243 -0.000666839 1 0 1 1 0 0 +EDGE2 7923 7922 -0.964351 -0.0194822 -0.00376672 1 0 1 1 0 0 +EDGE2 7923 7343 0.00945089 -0.0046289 0.0392233 1 0 1 1 0 0 +EDGE2 7923 7184 1.05784 0.0601826 0.0137874 1 0 1 1 0 0 +EDGE2 7923 7284 1.03071 0.0944599 -0.0308797 1 0 1 1 0 0 +EDGE2 7923 7363 0.0182714 0.0463652 6.77104e-05 1 0 1 1 0 0 +EDGE2 7923 7283 -0.0166554 0.0430252 -0.0511208 1 0 1 1 0 0 +EDGE2 7923 7303 0.015901 0.0936737 -0.0211312 1 0 1 1 0 0 +EDGE2 7923 7323 0.0736356 0.0132173 -0.0146051 1 0 1 1 0 0 +EDGE2 7923 7183 0.0288731 -0.00832316 -0.0146131 1 0 1 1 0 0 +EDGE2 7923 7282 -0.941348 -0.092506 -0.011063 1 0 1 1 0 0 +EDGE2 7923 7322 -0.961117 0.047203 0.000938404 1 0 1 1 0 0 +EDGE2 7923 7342 -1.04163 -0.00836424 0.00975402 1 0 1 1 0 0 +EDGE2 7923 7362 -0.945921 0.00902176 0.00387034 1 0 1 1 0 0 +EDGE2 7923 7302 -1.01307 0.0262104 -0.00155826 1 0 1 1 0 0 +EDGE2 7923 7182 -0.988882 0.083052 -0.000727794 1 0 1 1 0 0 +EDGE2 7924 7525 1.04569 -0.0119724 -3.09128 1 0 1 1 0 0 +EDGE2 7924 7285 0.963341 -0.0326066 -0.0198412 1 0 1 1 0 0 +EDGE2 7924 7325 0.9629 -0.0445504 0.0200074 1 0 1 1 0 0 +EDGE2 7924 7345 0.961627 -0.00837013 0.0195176 1 0 1 1 0 0 +EDGE2 7924 7365 0.974484 0.044705 -0.00906867 1 0 1 1 0 0 +EDGE2 7924 7305 0.965265 0.0932155 0.00114751 1 0 1 1 0 0 +EDGE2 7924 7185 0.94475 -0.0836355 -0.0502402 1 0 1 1 0 0 +EDGE2 7924 7304 0.0386451 0.0321042 0.0162298 1 0 1 1 0 0 +EDGE2 7924 7344 0.0212587 -0.071571 0.0278051 1 0 1 1 0 0 +EDGE2 7924 7364 0.0269701 -0.0527837 0.0504005 1 0 1 1 0 0 +EDGE2 7924 7324 0.068769 0.0431615 -0.0331858 1 0 1 1 0 0 +EDGE2 7924 7343 -1.01837 -0.0139852 0.0120663 1 0 1 1 0 0 +EDGE2 7924 7923 -0.975961 0.0247893 -0.0202641 1 0 1 1 0 0 +EDGE2 7924 7184 0.0353399 0.00407153 -0.0567251 1 0 1 1 0 0 +EDGE2 7924 7284 0.0391444 -0.0469344 -0.0364063 1 0 1 1 0 0 +EDGE2 7924 7363 -0.990941 -0.0619084 -0.0285301 1 0 1 1 0 0 +EDGE2 7924 7283 -0.989641 -0.0532154 -0.00269954 1 0 1 1 0 0 +EDGE2 7924 7303 -1.03304 0.0433757 -0.00445958 1 0 1 1 0 0 +EDGE2 7924 7323 -0.988111 0.00336109 -0.0112608 1 0 1 1 0 0 +EDGE2 7924 7183 -0.990533 0.00996624 0.00306977 1 0 1 1 0 0 +EDGE2 7925 7326 0.0157676 1.0572 1.56777 1 0 1 1 0 0 +EDGE2 7925 7526 -0.0520334 0.958798 1.56895 1 0 1 1 0 0 +EDGE2 7925 7346 -0.0182511 1.05755 1.59079 1 0 1 1 0 0 +EDGE2 7925 7286 0.103685 1.04577 1.5639 1 0 1 1 0 0 +EDGE2 7925 7306 0.085493 1.00266 1.57712 1 0 1 1 0 0 +EDGE2 7925 7525 0.153135 -0.0484773 -3.169 1 0 1 1 0 0 +EDGE2 7925 7524 0.945021 -0.0530157 -3.15864 1 0 1 1 0 0 +EDGE2 7925 7285 -0.0268728 0.0109084 0.0243353 1 0 1 1 0 0 +EDGE2 7925 7325 -0.040366 0.0738854 -0.0351973 1 0 1 1 0 0 +EDGE2 7925 7345 0.0347414 -0.0681868 0.00570085 1 0 1 1 0 0 +EDGE2 7925 7365 -0.0062955 0.0160869 -0.000846021 1 0 1 1 0 0 +EDGE2 7925 7305 0.083149 -0.02012 0.014367 1 0 1 1 0 0 +EDGE2 7925 7366 0.0090454 -1.0543 -1.55815 1 0 1 1 0 0 +EDGE2 7925 7185 0.0508058 -0.0784567 0.0259378 1 0 1 1 0 0 +EDGE2 7925 7186 0.0446853 -0.968678 -1.58583 1 0 1 1 0 0 +EDGE2 7925 7304 -1.03453 0.0230973 -0.000215634 1 0 1 1 0 0 +EDGE2 7925 7344 -1.06259 0.024008 0.00102788 1 0 1 1 0 0 +EDGE2 7925 7364 -0.960393 0.0208063 0.000199365 1 0 1 1 0 0 +EDGE2 7925 7924 -0.962333 0.0144137 0.0177413 1 0 1 1 0 0 +EDGE2 7925 7324 -0.966955 -0.0675138 -0.015111 1 0 1 1 0 0 +EDGE2 7925 7184 -1.04563 0.0112258 -0.0258253 1 0 1 1 0 0 +EDGE2 7925 7284 -0.894596 -0.045487 -0.0207617 1 0 1 1 0 0 +EDGE2 7926 7326 -0.0350129 0.0360791 0.00931685 1 0 1 1 0 0 +EDGE2 7926 7527 1.00198 -0.0568764 0.00759118 1 0 1 1 0 0 +EDGE2 7926 7307 1.03459 -0.0801639 0.028933 1 0 1 1 0 0 +EDGE2 7926 7327 1.00622 0.0250428 0.00783001 1 0 1 1 0 0 +EDGE2 7926 7347 1.03105 0.0166898 0.00797595 1 0 1 1 0 0 +EDGE2 7926 7287 1.06047 0.0272554 -0.0155607 1 0 1 1 0 0 +EDGE2 7926 7526 -0.0814654 0.106402 -0.0245931 1 0 1 1 0 0 +EDGE2 7926 7346 0.0147727 -0.0480384 -0.00828403 1 0 1 1 0 0 +EDGE2 7926 7286 0.0143111 -0.0476302 0.0231627 1 0 1 1 0 0 +EDGE2 7926 7306 0.0546754 0.0493164 -0.0254895 1 0 1 1 0 0 +EDGE2 7926 7525 -0.930523 -0.0664952 1.59085 1 0 1 1 0 0 +EDGE2 7926 7925 -1.10919 0.0223644 -1.57323 1 0 1 1 0 0 +EDGE2 7926 7285 -1.03596 0.0500894 -1.57251 1 0 1 1 0 0 +EDGE2 7926 7325 -1.03097 0.0106088 -1.56733 1 0 1 1 0 0 +EDGE2 7926 7345 -0.99257 -0.0430181 -1.57721 1 0 1 1 0 0 +EDGE2 7926 7365 -0.98592 -0.0811851 -1.5581 1 0 1 1 0 0 +EDGE2 7926 7305 -1.04873 0.0856905 -1.57743 1 0 1 1 0 0 +EDGE2 7926 7185 -0.967714 -0.0569433 -1.57597 1 0 1 1 0 0 +EDGE2 7927 7326 -0.995684 0.0292656 0.00370344 1 0 1 1 0 0 +EDGE2 7927 7527 0.0447996 -0.0023554 -0.0206028 1 0 1 1 0 0 +EDGE2 7927 7308 1.08158 -0.045737 -0.008221 1 0 1 1 0 0 +EDGE2 7927 7348 0.980517 0.00735484 -0.00259238 1 0 1 1 0 0 +EDGE2 7927 7528 1.07549 -0.0944261 -0.0222709 1 0 1 1 0 0 +EDGE2 7927 7328 0.962162 -0.00922772 0.00833522 1 0 1 1 0 0 +EDGE2 7927 7288 1.08333 0.0471416 -0.00444635 1 0 1 1 0 0 +EDGE2 7927 7307 0.0129217 0.00277868 -0.00777908 1 0 1 1 0 0 +EDGE2 7927 7327 0.00872556 0.0476739 0.00787549 1 0 1 1 0 0 +EDGE2 7927 7347 0.0816313 0.108817 0.0480564 1 0 1 1 0 0 +EDGE2 7927 7287 -0.115419 0.0217332 0.023495 1 0 1 1 0 0 +EDGE2 7927 7526 -1.06134 -0.125604 -0.0202479 1 0 1 1 0 0 +EDGE2 7927 7926 -0.933727 0.0690163 0.0111604 1 0 1 1 0 0 +EDGE2 7927 7346 -0.920766 -0.149713 -0.0182321 1 0 1 1 0 0 +EDGE2 7927 7286 -1.01706 -0.0520371 0.0299406 1 0 1 1 0 0 +EDGE2 7927 7306 -0.983524 -0.0605103 0.0136534 1 0 1 1 0 0 +EDGE2 7928 7329 0.96257 -0.0550763 -0.0192211 1 0 1 1 0 0 +EDGE2 7928 7529 1.03258 -0.0669577 0.0124219 1 0 1 1 0 0 +EDGE2 7928 7349 0.972988 -0.000435451 0.00391826 1 0 1 1 0 0 +EDGE2 7928 7289 1.04202 -0.0666556 0.0187679 1 0 1 1 0 0 +EDGE2 7928 7309 1.08327 -0.0640019 -0.0257925 1 0 1 1 0 0 +EDGE2 7928 7527 -0.968656 0.0303053 -0.0248116 1 0 1 1 0 0 +EDGE2 7928 7308 0.0269332 -0.0515454 0.0198749 1 0 1 1 0 0 +EDGE2 7928 7348 -0.0386398 0.0512327 -0.00256654 1 0 1 1 0 0 +EDGE2 7928 7528 0.022062 0.00125638 -0.00700179 1 0 1 1 0 0 +EDGE2 7928 7328 0.00260792 -0.032695 0.0286598 1 0 1 1 0 0 +EDGE2 7928 7288 0.038508 0.0334294 -0.0027947 1 0 1 1 0 0 +EDGE2 7928 7927 -1.01164 0.042373 -0.0187627 1 0 1 1 0 0 +EDGE2 7928 7307 -0.983324 -0.000122298 0.045902 1 0 1 1 0 0 +EDGE2 7928 7327 -1.02346 0.0672277 0.0184602 1 0 1 1 0 0 +EDGE2 7928 7347 -1.01926 0.0664969 -0.0318408 1 0 1 1 0 0 +EDGE2 7928 7287 -1.0052 -0.0323055 0.0200663 1 0 1 1 0 0 +EDGE2 7929 7530 1.05801 -0.0403587 -0.029014 1 0 1 1 0 0 +EDGE2 7929 7310 0.982231 -0.0106738 0.0121597 1 0 1 1 0 0 +EDGE2 7929 7350 0.997269 0.00541498 -0.00934731 1 0 1 1 0 0 +EDGE2 7929 7450 1.05585 0.0784478 -3.16164 1 0 1 1 0 0 +EDGE2 7929 7510 0.988132 0.0211518 -3.14701 1 0 1 1 0 0 +EDGE2 7929 7330 0.950711 -0.053191 -0.00820226 1 0 1 1 0 0 +EDGE2 7929 7170 1.03636 -0.00359561 -3.09623 1 0 1 1 0 0 +EDGE2 7929 7290 1.09294 -0.0364158 0.0104709 1 0 1 1 0 0 +EDGE2 7929 7329 0.0166136 0.0893958 -0.00856523 1 0 1 1 0 0 +EDGE2 7929 7529 0.00135489 0.0163858 0.00266428 1 0 1 1 0 0 +EDGE2 7929 7349 0.0414101 -0.0155259 0.026906 1 0 1 1 0 0 +EDGE2 7929 7289 0.0462995 -0.0346029 0.0342458 1 0 1 1 0 0 +EDGE2 7929 7309 -0.0544298 0.0961544 -0.00194014 1 0 1 1 0 0 +EDGE2 7929 7308 -1.04983 -0.0161207 -0.0216465 1 0 1 1 0 0 +EDGE2 7929 7348 -1.09116 -0.0429239 -0.0138026 1 0 1 1 0 0 +EDGE2 7929 7528 -1.07244 -0.00937234 0.0105061 1 0 1 1 0 0 +EDGE2 7929 7928 -1.07208 0.0681143 -0.0251608 1 0 1 1 0 0 +EDGE2 7929 7328 -1.02601 -0.0795738 -0.0242144 1 0 1 1 0 0 +EDGE2 7929 7288 -1.04179 -0.0586349 0.0114218 1 0 1 1 0 0 +EDGE2 7930 7449 1.06115 -0.023439 -3.12243 1 0 1 1 0 0 +EDGE2 7930 7509 1.00235 0.0857023 -3.13061 1 0 1 1 0 0 +EDGE2 7930 7169 0.892911 -0.0449193 -3.13478 1 0 1 1 0 0 +EDGE2 7930 7530 -0.0151346 -0.0101768 0.0138656 1 0 1 1 0 0 +EDGE2 7930 7511 0.00996249 -1.06085 -1.56832 1 0 1 1 0 0 +EDGE2 7930 7531 -0.0177816 -1.04398 -1.53987 1 0 1 1 0 0 +EDGE2 7930 7451 0.0847174 -0.995465 -1.58926 1 0 1 1 0 0 +EDGE2 7930 7310 0.0195294 -0.0183812 -0.0378788 1 0 1 1 0 0 +EDGE2 7930 7350 0.0314816 0.126069 -0.00774369 1 0 1 1 0 0 +EDGE2 7930 7450 -0.0246733 -0.0564683 -3.10459 1 0 1 1 0 0 +EDGE2 7930 7510 0.00977834 0.0410849 -3.16875 1 0 1 1 0 0 +EDGE2 7930 7330 0.0445754 0.0735598 -0.0020007 1 0 1 1 0 0 +EDGE2 7930 7170 0.0229204 0.0527421 -3.12236 1 0 1 1 0 0 +EDGE2 7930 7290 -0.00913126 0.0182436 -0.0067203 1 0 1 1 0 0 +EDGE2 7930 7329 -1.0539 -0.00518148 0.0113605 1 0 1 1 0 0 +EDGE2 7930 7529 -0.997684 -0.00276039 0.0081423 1 0 1 1 0 0 +EDGE2 7930 7929 -1.0559 0.0255395 0.041066 1 0 1 1 0 0 +EDGE2 7930 7349 -0.980999 0.104063 0.0125043 1 0 1 1 0 0 +EDGE2 7930 7289 -0.958702 0.0540541 0.0201443 1 0 1 1 0 0 +EDGE2 7930 7309 -0.900095 -0.0104184 0.0142008 1 0 1 1 0 0 +EDGE2 7930 7291 0.0200355 1.08469 1.56674 1 0 1 1 0 0 +EDGE2 7930 7331 -0.0710848 0.971738 1.55149 1 0 1 1 0 0 +EDGE2 7930 7351 -0.0295755 0.979677 1.58792 1 0 1 1 0 0 +EDGE2 7930 7311 -0.0358358 0.98326 1.58096 1 0 1 1 0 0 +EDGE2 7930 7171 0.0405608 1.06157 1.53817 1 0 1 1 0 0 +EDGE2 7931 7530 -1.04107 0.0357928 1.58435 1 0 1 1 0 0 +EDGE2 7931 7512 1.02552 0.0176688 -0.0103798 1 0 1 1 0 0 +EDGE2 7931 7532 0.999406 -0.0921431 -0.00437355 1 0 1 1 0 0 +EDGE2 7931 7511 -0.0175455 -0.00451163 -0.00653088 1 0 1 1 0 0 +EDGE2 7931 7452 0.977425 -0.0676666 0.00441055 1 0 1 1 0 0 +EDGE2 7931 7531 -0.00383005 0.0583881 0.022595 1 0 1 1 0 0 +EDGE2 7931 7451 0.0212399 0.0648731 0.000713379 1 0 1 1 0 0 +EDGE2 7931 7930 -0.981977 0.066665 1.55791 1 0 1 1 0 0 +EDGE2 7931 7310 -0.984539 -0.0399821 1.5523 1 0 1 1 0 0 +EDGE2 7931 7350 -0.988865 -0.00976766 1.53552 1 0 1 1 0 0 +EDGE2 7931 7450 -0.952683 -0.0262685 -1.6159 1 0 1 1 0 0 +EDGE2 7931 7510 -0.998412 -0.0381736 -1.54998 1 0 1 1 0 0 +EDGE2 7931 7330 -1.05274 0.00330587 1.56959 1 0 1 1 0 0 +EDGE2 7931 7170 -0.977678 0.00298375 -1.54373 1 0 1 1 0 0 +EDGE2 7931 7290 -0.926453 -0.0615049 1.58779 1 0 1 1 0 0 +EDGE2 7932 7512 -0.00626703 -0.133773 -0.0128949 1 0 1 1 0 0 +EDGE2 7932 7513 0.915326 0.0204424 -0.00277025 1 0 1 1 0 0 +EDGE2 7932 7533 0.929321 0.00282544 -0.0303475 1 0 1 1 0 0 +EDGE2 7932 7453 0.997339 0.0962585 -0.00923417 1 0 1 1 0 0 +EDGE2 7932 7532 -0.000999456 -0.0471484 0.0169616 1 0 1 1 0 0 +EDGE2 7932 7511 -0.981188 -0.0478585 0.0114879 1 0 1 1 0 0 +EDGE2 7932 7931 -0.946618 -0.118535 0.0158765 1 0 1 1 0 0 +EDGE2 7932 7452 -0.0140841 0.0312127 -0.0102607 1 0 1 1 0 0 +EDGE2 7932 7531 -1.00136 0.0167901 -0.0128659 1 0 1 1 0 0 +EDGE2 7932 7451 -1.01655 0.0373724 0.0162609 1 0 1 1 0 0 +EDGE2 7933 7514 1.00694 -0.0832118 0.00131153 1 0 1 1 0 0 +EDGE2 7933 7534 0.95928 -0.0570712 -0.0104255 1 0 1 1 0 0 +EDGE2 7933 7512 -1.04188 0.0370255 0.0292435 1 0 1 1 0 0 +EDGE2 7933 7513 0.0202295 -0.0961379 -0.0184384 1 0 1 1 0 0 +EDGE2 7933 7454 0.877415 -0.00707085 0.0115636 1 0 1 1 0 0 +EDGE2 7933 7533 -0.00427333 0.0171851 0.00238381 1 0 1 1 0 0 +EDGE2 7933 7932 -1.01958 0.0433991 0.0204379 1 0 1 1 0 0 +EDGE2 7933 7453 -0.0329829 -0.0202714 0.0205104 1 0 1 1 0 0 +EDGE2 7933 7532 -0.998081 -0.0533289 0.0204443 1 0 1 1 0 0 +EDGE2 7933 7452 -1.05792 0.015425 0.0173643 1 0 1 1 0 0 +EDGE2 7934 7535 1.03929 0.0456177 0.0105672 1 0 1 1 0 0 +EDGE2 7934 7575 0.977418 0.0021768 -3.13797 1 0 1 1 0 0 +EDGE2 7934 7555 0.923902 -0.00337776 -3.12126 1 0 1 1 0 0 +EDGE2 7934 7455 0.919329 0.0370226 -0.00169518 1 0 1 1 0 0 +EDGE2 7934 7475 0.990339 -0.0782363 -3.15316 1 0 1 1 0 0 +EDGE2 7934 7515 0.963631 0.026903 0.0126823 1 0 1 1 0 0 +EDGE2 7934 7395 0.985849 0.0192786 -3.11532 1 0 1 1 0 0 +EDGE2 7934 7514 0.0245834 0.0308035 -0.0323709 1 0 1 1 0 0 +EDGE2 7934 7534 -0.0366585 0.019555 0.0130112 1 0 1 1 0 0 +EDGE2 7934 7513 -1.01186 -0.0451867 0.00732678 1 0 1 1 0 0 +EDGE2 7934 7933 -1.02169 0.00484896 0.0201784 1 0 1 1 0 0 +EDGE2 7934 7454 0.0111059 0.0482515 0.00566332 1 0 1 1 0 0 +EDGE2 7934 7533 -1.07745 -0.0262463 0.0123237 1 0 1 1 0 0 +EDGE2 7934 7453 -1.10245 0.0423947 -0.00652379 1 0 1 1 0 0 +EDGE2 7935 7476 0.0592619 1.04936 1.58611 1 0 1 1 0 0 +EDGE2 7935 7396 0.00706119 0.994728 1.53762 1 0 1 1 0 0 +EDGE2 7935 7394 0.987647 -0.0352887 -3.1535 1 0 1 1 0 0 +EDGE2 7935 7554 1.08411 -0.101986 -3.16568 1 0 1 1 0 0 +EDGE2 7935 7574 1.08298 0.0250276 -3.1473 1 0 1 1 0 0 +EDGE2 7935 7474 0.989441 -0.0402517 -3.15742 1 0 1 1 0 0 +EDGE2 7935 7535 0.0583498 0.0330595 0.0153347 1 0 1 1 0 0 +EDGE2 7935 7575 -0.0108972 -0.0310058 -3.10753 1 0 1 1 0 0 +EDGE2 7935 7555 -0.0401999 -0.0614976 -3.1602 1 0 1 1 0 0 +EDGE2 7935 7455 0.0745536 0.0198037 -0.0093786 1 0 1 1 0 0 +EDGE2 7935 7475 -0.0170895 -0.0602044 -3.13429 1 0 1 1 0 0 +EDGE2 7935 7515 0.00511172 -0.00254941 -0.0222785 1 0 1 1 0 0 +EDGE2 7935 7395 0.0142775 0.0287385 -3.17239 1 0 1 1 0 0 +EDGE2 7935 7576 -0.00986444 -1.05454 -1.54899 1 0 1 1 0 0 +EDGE2 7935 7516 0.0790529 -0.891028 -1.5521 1 0 1 1 0 0 +EDGE2 7935 7536 0.0693028 -1.0533 -1.5681 1 0 1 1 0 0 +EDGE2 7935 7556 0.0195306 -1.03281 -1.56656 1 0 1 1 0 0 +EDGE2 7935 7456 0.035717 -0.964225 -1.60218 1 0 1 1 0 0 +EDGE2 7935 7514 -0.917347 -0.0728836 -0.0247304 1 0 1 1 0 0 +EDGE2 7935 7934 -1.02756 -0.014183 0.0242427 1 0 1 1 0 0 +EDGE2 7935 7534 -1.06854 -0.00256441 -0.0125099 1 0 1 1 0 0 +EDGE2 7935 7454 -0.986753 -0.0490206 -0.0131371 1 0 1 1 0 0 +EDGE2 7936 7537 0.970294 -0.02873 0.0279557 1 0 1 1 0 0 +EDGE2 7936 7535 -0.901004 0.159701 1.58694 1 0 1 1 0 0 +EDGE2 7936 7575 -1.01851 -0.0312536 -1.58684 1 0 1 1 0 0 +EDGE2 7936 7935 -1.05688 0.043597 1.60055 1 0 1 1 0 0 +EDGE2 7936 7555 -1.0182 -0.0154424 -1.53712 1 0 1 1 0 0 +EDGE2 7936 7455 -1.10192 0.0848083 1.57496 1 0 1 1 0 0 +EDGE2 7936 7475 -0.982502 0.0154758 -1.57912 1 0 1 1 0 0 +EDGE2 7936 7515 -1.02783 0.0744178 1.54826 1 0 1 1 0 0 +EDGE2 7936 7395 -1.09104 0.0338202 -1.55256 1 0 1 1 0 0 +EDGE2 7936 7576 0.0224564 -0.0753125 -0.0352027 1 0 1 1 0 0 +EDGE2 7936 7516 -0.0351805 -0.0021706 0.0117748 1 0 1 1 0 0 +EDGE2 7936 7536 0.115285 0.0729558 -0.0140438 1 0 1 1 0 0 +EDGE2 7936 7556 0.0305598 0.07211 0.00337967 1 0 1 1 0 0 +EDGE2 7936 7456 0.0011637 0.0732779 0.00440653 1 0 1 1 0 0 +EDGE2 7936 7577 1.02266 -0.0761414 -0.0340979 1 0 1 1 0 0 +EDGE2 7936 7557 1.00716 0.0341755 -0.0232547 1 0 1 1 0 0 +EDGE2 7936 7517 0.991147 0.00579415 -0.00475292 1 0 1 1 0 0 +EDGE2 7936 7457 0.98789 -0.139222 -0.0283235 1 0 1 1 0 0 +EDGE2 7937 7537 -0.0240408 0.0454713 0.0050141 1 0 1 1 0 0 +EDGE2 7937 7576 -1.00277 -0.00473114 0.0151834 1 0 1 1 0 0 +EDGE2 7937 7936 -1.03861 -0.0318645 -0.00613123 1 0 1 1 0 0 +EDGE2 7937 7516 -0.915516 -0.0784397 0.00164411 1 0 1 1 0 0 +EDGE2 7937 7536 -1.0882 -0.0795225 -0.0138353 1 0 1 1 0 0 +EDGE2 7937 7556 -0.984735 -0.049824 -0.0119635 1 0 1 1 0 0 +EDGE2 7937 7456 -0.935917 0.0276048 0.0448709 1 0 1 1 0 0 +EDGE2 7937 7577 -0.0357585 -0.0485276 -0.0176727 1 0 1 1 0 0 +EDGE2 7937 7557 0.035082 0.0252314 0.0142838 1 0 1 1 0 0 +EDGE2 7937 7517 -0.0438251 -0.0214827 -0.0291337 1 0 1 1 0 0 +EDGE2 7937 7457 0.0519908 -0.015978 0.00859695 1 0 1 1 0 0 +EDGE2 7937 7458 0.999821 -0.0604923 -0.0265862 1 0 1 1 0 0 +EDGE2 7937 7538 1.02623 -0.0276977 -0.012802 1 0 1 1 0 0 +EDGE2 7937 7558 0.986173 0.0309871 -0.028136 1 0 1 1 0 0 +EDGE2 7937 7578 1.05437 0.0497149 -0.0131777 1 0 1 1 0 0 +EDGE2 7937 7518 0.949633 -0.061542 0.00482981 1 0 1 1 0 0 +EDGE2 7938 7537 -0.906164 -0.0243584 -0.0287197 1 0 1 1 0 0 +EDGE2 7938 7577 -0.959396 -0.00114265 -0.000423718 1 0 1 1 0 0 +EDGE2 7938 7937 -0.956507 0.0277476 0.00388571 1 0 1 1 0 0 +EDGE2 7938 7557 -1.03578 0.0522953 0.00378507 1 0 1 1 0 0 +EDGE2 7938 7517 -1.01303 0.0354258 0.0211049 1 0 1 1 0 0 +EDGE2 7938 7457 -0.954297 -0.0622511 -0.0117295 1 0 1 1 0 0 +EDGE2 7938 7539 0.977901 0.00427575 -0.00551017 1 0 1 1 0 0 +EDGE2 7938 7458 -0.0245436 -0.0472593 0.000628863 1 0 1 1 0 0 +EDGE2 7938 7538 0.0501438 0.00413019 -0.00165223 1 0 1 1 0 0 +EDGE2 7938 7558 -0.024348 0.00489701 0.0142241 1 0 1 1 0 0 +EDGE2 7938 7578 -0.0221597 0.0281364 0.00513547 1 0 1 1 0 0 +EDGE2 7938 7518 0.0228139 -0.00604303 -0.00731868 1 0 1 1 0 0 +EDGE2 7938 7579 1.02357 0.0193569 -0.00254475 1 0 1 1 0 0 +EDGE2 7938 7559 1.01527 -0.0191599 -0.0318416 1 0 1 1 0 0 +EDGE2 7938 7459 1.00309 0.0271258 0.0155277 1 0 1 1 0 0 +EDGE2 7938 7519 1.00101 -0.0703728 0.00390114 1 0 1 1 0 0 +EDGE2 7939 7520 0.985359 0.0402202 -0.0464167 1 0 1 1 0 0 +EDGE2 7939 7539 -0.0140858 -0.0278011 -0.0107135 1 0 1 1 0 0 +EDGE2 7939 7938 -1.04025 -0.0418299 -0.00183089 1 0 1 1 0 0 +EDGE2 7939 7458 -0.901977 0.019742 0.000378304 1 0 1 1 0 0 +EDGE2 7939 7538 -0.955977 -0.0144256 0.0255116 1 0 1 1 0 0 +EDGE2 7939 7558 -0.945885 -0.0181989 -0.0333386 1 0 1 1 0 0 +EDGE2 7939 7578 -1.08945 0.0597271 -0.0327988 1 0 1 1 0 0 +EDGE2 7939 7518 -0.958028 -0.060942 0.00282471 1 0 1 1 0 0 +EDGE2 7939 7579 -0.0716426 -0.00284043 0.0313101 1 0 1 1 0 0 +EDGE2 7939 7559 -0.0229252 0.0432566 -0.014966 1 0 1 1 0 0 +EDGE2 7939 7459 -0.0147313 -0.0423053 -0.0232836 1 0 1 1 0 0 +EDGE2 7939 7519 0.0554123 -0.0604898 0.0167827 1 0 1 1 0 0 +EDGE2 7939 7540 0.971134 -0.00164424 0.00399078 1 0 1 1 0 0 +EDGE2 7939 7580 1.02646 -0.0467144 0.0226283 1 0 1 1 0 0 +EDGE2 7939 7560 1.01649 -0.0515503 0.0134365 1 0 1 1 0 0 +EDGE2 7939 7380 0.893052 0.0857469 -3.13769 1 0 1 1 0 0 +EDGE2 7939 7460 0.964654 -0.0565514 0.0469341 1 0 1 1 0 0 +EDGE2 7940 7520 0.0377598 0.000196989 0.0111299 1 0 1 1 0 0 +EDGE2 7940 7539 -0.927286 0.0442508 0.0200362 1 0 1 1 0 0 +EDGE2 7940 7579 -1.0258 0.092413 -0.0107488 1 0 1 1 0 0 +EDGE2 7940 7939 -0.987872 0.0424402 -0.00953477 1 0 1 1 0 0 +EDGE2 7940 7559 -0.995148 -0.00490435 -0.0157795 1 0 1 1 0 0 +EDGE2 7940 7459 -0.918984 -0.0383963 0.0112343 1 0 1 1 0 0 +EDGE2 7940 7519 -0.911617 -0.0709896 -0.02282 1 0 1 1 0 0 +EDGE2 7940 7540 -0.0286387 0.0554969 -0.0048928 1 0 1 1 0 0 +EDGE2 7940 7561 -0.145754 0.960046 1.5828 1 0 1 1 0 0 +EDGE2 7940 7581 0.0479949 0.994075 1.5433 1 0 1 1 0 0 +EDGE2 7940 7381 0.0431462 1.01405 1.55559 1 0 1 1 0 0 +EDGE2 7940 7461 -0.034938 1.03944 1.62014 1 0 1 1 0 0 +EDGE2 7940 7541 -0.00768998 0.983256 1.54471 1 0 1 1 0 0 +EDGE2 7940 7580 0.0519051 0.0573297 -0.00888277 1 0 1 1 0 0 +EDGE2 7940 7560 -0.0290402 0.0233409 0.0212213 1 0 1 1 0 0 +EDGE2 7940 7380 -0.0193872 -0.0113846 -3.15738 1 0 1 1 0 0 +EDGE2 7940 7460 0.0420602 0.0674208 -0.0257079 1 0 1 1 0 0 +EDGE2 7940 7521 0.0255848 -1.01113 -1.57052 1 0 1 1 0 0 +EDGE2 7940 7379 1.00566 -0.0559042 -3.14172 1 0 1 1 0 0 +EDGE2 7941 7520 -0.94884 -0.0190803 1.56519 1 0 1 1 0 0 +EDGE2 7941 7540 -1.00154 0.00452331 1.55671 1 0 1 1 0 0 +EDGE2 7941 7580 -1.03045 0.0222376 1.5723 1 0 1 1 0 0 +EDGE2 7941 7940 -0.918383 -0.0380612 1.5887 1 0 1 1 0 0 +EDGE2 7941 7560 -1.06673 -0.0355082 1.55283 1 0 1 1 0 0 +EDGE2 7941 7522 1.04179 -0.00320071 0.0210794 1 0 1 1 0 0 +EDGE2 7941 7380 -0.940014 0.0482894 -1.56347 1 0 1 1 0 0 +EDGE2 7941 7460 -1.04356 0.034362 1.56445 1 0 1 1 0 0 +EDGE2 7941 7521 -0.00428892 -0.0400993 -0.0202313 1 0 1 1 0 0 +EDGE2 7942 7522 0.0822951 0.0552657 -0.0162435 1 0 1 1 0 0 +EDGE2 7942 7941 -0.910929 -0.00716665 0.00757095 1 0 1 1 0 0 +EDGE2 7942 7521 -0.967013 0.0116245 0.0168994 1 0 1 1 0 0 +EDGE2 7942 7523 1.01125 0.0327676 -0.0380436 1 0 1 1 0 0 +EDGE2 7943 7522 -1.00847 -0.0520911 -0.000892589 1 0 1 1 0 0 +EDGE2 7943 7942 -0.978139 0.042962 -0.00627467 1 0 1 1 0 0 +EDGE2 7943 7523 -0.0201795 0.0348277 -0.0455873 1 0 1 1 0 0 +EDGE2 7943 7524 1.02779 -0.0589426 -0.0117034 1 0 1 1 0 0 +EDGE2 7944 7943 -1.01644 0.0381003 -0.00601772 1 0 1 1 0 0 +EDGE2 7944 7523 -1.00521 -0.0500633 -0.0239928 1 0 1 1 0 0 +EDGE2 7944 7525 1.02906 0.0637435 -0.0205696 1 0 1 1 0 0 +EDGE2 7944 7925 1.00684 0.132111 -3.11981 1 0 1 1 0 0 +EDGE2 7944 7524 0.0756461 0.0212707 0.0480689 1 0 1 1 0 0 +EDGE2 7944 7285 0.968575 0.0975558 -3.11793 1 0 1 1 0 0 +EDGE2 7944 7325 0.912662 -0.00290446 -3.12867 1 0 1 1 0 0 +EDGE2 7944 7345 0.889137 -0.0271841 -3.13758 1 0 1 1 0 0 +EDGE2 7944 7365 0.982086 -0.0289029 -3.15507 1 0 1 1 0 0 +EDGE2 7944 7305 0.950916 -0.066986 -3.14531 1 0 1 1 0 0 +EDGE2 7944 7185 0.967262 0.0116515 -3.17655 1 0 1 1 0 0 +EDGE2 7945 7944 -1.00655 0.0166095 0.00893242 1 0 1 1 0 0 +EDGE2 7945 7326 -0.0985146 -1.03093 -1.57658 1 0 1 1 0 0 +EDGE2 7945 7526 0.0637588 -1.00815 -1.57868 1 0 1 1 0 0 +EDGE2 7945 7926 0.00795857 -1.02891 -1.52831 1 0 1 1 0 0 +EDGE2 7945 7346 0.0104031 -0.979268 -1.56369 1 0 1 1 0 0 +EDGE2 7945 7286 0.0749116 -0.998741 -1.568 1 0 1 1 0 0 +EDGE2 7945 7306 -0.0572258 -1.00276 -1.56312 1 0 1 1 0 0 +EDGE2 7945 7525 -0.138937 0.0273254 0.00126412 1 0 1 1 0 0 +EDGE2 7945 7925 0.0501125 -0.0288943 -3.09026 1 0 1 1 0 0 +EDGE2 7945 7524 -0.953265 -0.13008 -0.00148323 1 0 1 1 0 0 +EDGE2 7945 7285 -0.0823337 -0.0103377 -3.14385 1 0 1 1 0 0 +EDGE2 7945 7325 0.0053135 0.0845869 -3.14768 1 0 1 1 0 0 +EDGE2 7945 7345 -0.050506 0.0626529 -3.14635 1 0 1 1 0 0 +EDGE2 7945 7365 -0.0296815 -0.0908305 -3.10903 1 0 1 1 0 0 +EDGE2 7945 7305 -0.080342 0.0593227 -3.15513 1 0 1 1 0 0 +EDGE2 7945 7366 -0.0258333 0.96721 1.57036 1 0 1 1 0 0 +EDGE2 7945 7185 -0.0459486 -0.0682586 -3.17286 1 0 1 1 0 0 +EDGE2 7945 7186 0.00796415 0.955449 1.55983 1 0 1 1 0 0 +EDGE2 7945 7304 1.033 0.0661143 -3.1631 1 0 1 1 0 0 +EDGE2 7945 7344 1.0236 0.0164343 -3.12636 1 0 1 1 0 0 +EDGE2 7945 7364 1.02436 0.0707492 -3.13243 1 0 1 1 0 0 +EDGE2 7945 7924 0.969717 0.0306038 -3.14401 1 0 1 1 0 0 +EDGE2 7945 7324 0.955298 -0.108133 -3.12392 1 0 1 1 0 0 +EDGE2 7945 7184 0.954454 -0.0323032 -3.15243 1 0 1 1 0 0 +EDGE2 7945 7284 0.913436 -0.00451201 -3.13689 1 0 1 1 0 0 +EDGE2 7946 7326 -0.00990228 0.0289554 0.0212579 1 0 1 1 0 0 +EDGE2 7946 7527 0.95113 0.0770315 -0.0577971 1 0 1 1 0 0 +EDGE2 7946 7927 1.0794 -0.0535493 0.0130268 1 0 1 1 0 0 +EDGE2 7946 7307 1.05307 0.0740085 -0.00733268 1 0 1 1 0 0 +EDGE2 7946 7327 1.09699 0.0107958 -0.0112192 1 0 1 1 0 0 +EDGE2 7946 7347 0.96276 -0.0473518 -0.0220631 1 0 1 1 0 0 +EDGE2 7946 7287 0.939798 -0.064626 -0.0175998 1 0 1 1 0 0 +EDGE2 7946 7526 -0.0778881 -0.059966 0.0103664 1 0 1 1 0 0 +EDGE2 7946 7926 0.00914456 -0.000920061 0.00653784 1 0 1 1 0 0 +EDGE2 7946 7346 -0.0487573 0.0783779 0.0047413 1 0 1 1 0 0 +EDGE2 7946 7286 -0.0294424 -0.0548839 -0.0127529 1 0 1 1 0 0 +EDGE2 7946 7306 -0.0527265 0.0107322 0.0064558 1 0 1 1 0 0 +EDGE2 7946 7525 -1.04429 0.0705756 1.58561 1 0 1 1 0 0 +EDGE2 7946 7925 -0.987227 0.059628 -1.56741 1 0 1 1 0 0 +EDGE2 7946 7945 -1.0935 0.0793188 1.57076 1 0 1 1 0 0 +EDGE2 7946 7285 -0.880327 -0.0369599 -1.58401 1 0 1 1 0 0 +EDGE2 7946 7325 -0.887645 0.0853877 -1.54075 1 0 1 1 0 0 +EDGE2 7946 7345 -1.02718 -0.0134151 -1.57287 1 0 1 1 0 0 +EDGE2 7946 7365 -0.981825 -0.00757927 -1.58979 1 0 1 1 0 0 +EDGE2 7946 7305 -1.0145 -0.0766013 -1.55644 1 0 1 1 0 0 +EDGE2 7946 7185 -1.00659 -0.0549663 -1.56777 1 0 1 1 0 0 +EDGE2 7947 7326 -0.965812 -0.0509874 -0.00581463 1 0 1 1 0 0 +EDGE2 7947 7527 -0.0158748 -0.00599787 0.00213707 1 0 1 1 0 0 +EDGE2 7947 7308 0.959439 0.0322587 0.0209766 1 0 1 1 0 0 +EDGE2 7947 7348 1.02385 -0.0395883 0.033297 1 0 1 1 0 0 +EDGE2 7947 7528 1.03263 -0.0302907 0.0228632 1 0 1 1 0 0 +EDGE2 7947 7928 1.05152 0.0444058 -0.0111162 1 0 1 1 0 0 +EDGE2 7947 7328 0.944887 0.0847969 0.021257 1 0 1 1 0 0 +EDGE2 7947 7288 1.07029 -0.0213169 0.0204391 1 0 1 1 0 0 +EDGE2 7947 7927 -0.000281513 -0.0344098 -0.00532983 1 0 1 1 0 0 +EDGE2 7947 7307 0.00117629 0.046728 0.0137369 1 0 1 1 0 0 +EDGE2 7947 7327 -0.014431 -0.0285601 -0.00763567 1 0 1 1 0 0 +EDGE2 7947 7347 0.0115193 -0.0987369 -0.0138829 1 0 1 1 0 0 +EDGE2 7947 7287 0.0187002 0.0888565 -0.00542681 1 0 1 1 0 0 +EDGE2 7947 7526 -0.94848 -0.0294872 0.00764238 1 0 1 1 0 0 +EDGE2 7947 7926 -1.00588 0.0329654 -0.00905726 1 0 1 1 0 0 +EDGE2 7947 7946 -1.00853 -0.123781 -0.0161127 1 0 1 1 0 0 +EDGE2 7947 7346 -0.963269 -0.0675148 0.00898821 1 0 1 1 0 0 +EDGE2 7947 7286 -0.952609 0.0754777 -0.0152371 1 0 1 1 0 0 +EDGE2 7947 7306 -0.985705 -0.00878792 0.0354405 1 0 1 1 0 0 +EDGE2 7948 7329 1.07471 0.0117347 -0.00614053 1 0 1 1 0 0 +EDGE2 7948 7529 1.08462 -0.0431017 -0.0139608 1 0 1 1 0 0 +EDGE2 7948 7929 1.00881 -0.0288682 0.0133428 1 0 1 1 0 0 +EDGE2 7948 7349 0.965599 -0.0389117 -0.0300084 1 0 1 1 0 0 +EDGE2 7948 7289 1.03801 0.0160788 0.007837 1 0 1 1 0 0 +EDGE2 7948 7309 1.01612 -0.0367119 -0.00497349 1 0 1 1 0 0 +EDGE2 7948 7527 -0.935451 -0.0438176 -0.01833 1 0 1 1 0 0 +EDGE2 7948 7308 -0.00680238 -0.0238754 -0.0223059 1 0 1 1 0 0 +EDGE2 7948 7348 -0.00842564 -0.0988586 0.0236482 1 0 1 1 0 0 +EDGE2 7948 7528 -0.00431005 -0.0465888 -0.00381415 1 0 1 1 0 0 +EDGE2 7948 7928 -0.0136109 0.0830808 0.0154424 1 0 1 1 0 0 +EDGE2 7948 7328 0.0385598 -0.0276317 -0.00915458 1 0 1 1 0 0 +EDGE2 7948 7947 -0.965111 0.0381609 0.0522248 1 0 1 1 0 0 +EDGE2 7948 7288 0.0177961 0.0465415 0.0176032 1 0 1 1 0 0 +EDGE2 7948 7927 -0.964007 0.100782 0.0411377 1 0 1 1 0 0 +EDGE2 7948 7307 -1.06607 -0.0123843 -0.00891662 1 0 1 1 0 0 +EDGE2 7948 7327 -1.00648 -0.00201393 0.00188897 1 0 1 1 0 0 +EDGE2 7948 7347 -0.966289 0.0371258 -0.0126249 1 0 1 1 0 0 +EDGE2 7948 7287 -1.07747 0.00849926 -0.018561 1 0 1 1 0 0 +EDGE2 7949 7948 -1.05453 0.0744164 0.0467672 1 0 1 1 0 0 +EDGE2 7949 7530 1.04678 -0.0941788 -0.0112863 1 0 1 1 0 0 +EDGE2 7949 7930 0.934284 0.0574199 -0.0226373 1 0 1 1 0 0 +EDGE2 7949 7310 1.00569 0.00888364 -0.0187695 1 0 1 1 0 0 +EDGE2 7949 7350 0.908776 0.037928 0.021156 1 0 1 1 0 0 +EDGE2 7949 7450 1.05493 -0.00506915 -3.12866 1 0 1 1 0 0 +EDGE2 7949 7510 0.936697 0.0285514 -3.14552 1 0 1 1 0 0 +EDGE2 7949 7330 0.961224 -0.00889942 0.017867 1 0 1 1 0 0 +EDGE2 7949 7170 0.997529 0.113944 -3.13598 1 0 1 1 0 0 +EDGE2 7949 7290 1.01621 0.00644006 0.0117007 1 0 1 1 0 0 +EDGE2 7949 7329 -0.0124205 -0.0159613 -0.014199 1 0 1 1 0 0 +EDGE2 7949 7529 0.0456211 0.0261958 -0.000976924 1 0 1 1 0 0 +EDGE2 7949 7929 -0.0252913 0.0102396 -0.020299 1 0 1 1 0 0 +EDGE2 7949 7349 -0.0063965 -0.0838168 -0.0299141 1 0 1 1 0 0 +EDGE2 7949 7289 0.0266237 -0.0760392 -0.00734742 1 0 1 1 0 0 +EDGE2 7949 7309 -0.0385947 0.0145171 -0.00562478 1 0 1 1 0 0 +EDGE2 7949 7308 -0.987025 -0.0633917 0.000752666 1 0 1 1 0 0 +EDGE2 7949 7348 -1.04193 -0.00931541 -0.00649721 1 0 1 1 0 0 +EDGE2 7949 7528 -0.993636 -0.0482162 -0.0141145 1 0 1 1 0 0 +EDGE2 7949 7928 -0.928066 0.125295 0.00465713 1 0 1 1 0 0 +EDGE2 7949 7328 -0.96479 -0.0509783 0.0122325 1 0 1 1 0 0 +EDGE2 7949 7288 -1.02212 -0.0306115 -0.0348998 1 0 1 1 0 0 +EDGE2 7950 7449 1.08851 0.0200467 -3.13837 1 0 1 1 0 0 +EDGE2 7950 7509 1.06309 0.00731443 -3.17178 1 0 1 1 0 0 +EDGE2 7950 7169 0.955064 0.0608803 -3.11975 1 0 1 1 0 0 +EDGE2 7950 7530 0.085079 -0.0890088 0.0396125 1 0 1 1 0 0 +EDGE2 7950 7511 0.00937272 -1.00767 -1.59216 1 0 1 1 0 0 +EDGE2 7950 7931 -0.0119185 -1.06794 -1.58705 1 0 1 1 0 0 +EDGE2 7950 7531 0.0349933 -1.02696 -1.58536 1 0 1 1 0 0 +EDGE2 7950 7451 -0.0368505 -1.0104 -1.61432 1 0 1 1 0 0 +EDGE2 7950 7930 0.0666858 -0.00320595 0.00959081 1 0 1 1 0 0 +EDGE2 7950 7310 0.0882136 0.0617153 0.0286825 1 0 1 1 0 0 +EDGE2 7950 7350 0.0160681 -0.0220703 -0.00674276 1 0 1 1 0 0 +EDGE2 7950 7450 -0.0648221 -0.0299119 -3.13604 1 0 1 1 0 0 +EDGE2 7950 7510 0.00418617 -0.0145084 -3.10344 1 0 1 1 0 0 +EDGE2 7950 7330 0.0890644 0.0895828 0.0268263 1 0 1 1 0 0 +EDGE2 7950 7170 -0.0350396 -0.0315559 -3.12335 1 0 1 1 0 0 +EDGE2 7950 7290 -0.0308746 -0.0212332 -0.0319854 1 0 1 1 0 0 +EDGE2 7950 7329 -0.967768 -0.0411068 -0.0236841 1 0 1 1 0 0 +EDGE2 7950 7529 -1.05261 0.00127068 -0.0178518 1 0 1 1 0 0 +EDGE2 7950 7929 -1.05556 0.0393329 0.0295605 1 0 1 1 0 0 +EDGE2 7950 7949 -1.01172 -0.00811853 0.0116465 1 0 1 1 0 0 +EDGE2 7950 7349 -1.03545 -0.0480529 -0.00375857 1 0 1 1 0 0 +EDGE2 7950 7289 -0.984525 0.0411503 0.00581437 1 0 1 1 0 0 +EDGE2 7950 7309 -0.951916 0.0548537 0.00333437 1 0 1 1 0 0 +EDGE2 7950 7291 -0.0196996 0.965256 1.56002 1 0 1 1 0 0 +EDGE2 7950 7331 0.00432592 0.971494 1.54689 1 0 1 1 0 0 +EDGE2 7950 7351 0.0355686 0.968026 1.57384 1 0 1 1 0 0 +EDGE2 7950 7311 -0.0346478 0.84758 1.57238 1 0 1 1 0 0 +EDGE2 7950 7171 0.0585071 1.05328 1.58303 1 0 1 1 0 0 +EDGE2 7951 7530 -0.976077 -0.0545282 1.57366 1 0 1 1 0 0 +EDGE2 7951 7512 0.966843 -0.0365524 -0.0239199 1 0 1 1 0 0 +EDGE2 7951 7932 0.952783 -0.0108675 -0.00966124 1 0 1 1 0 0 +EDGE2 7951 7532 0.986549 -0.00663946 0.00186442 1 0 1 1 0 0 +EDGE2 7951 7511 0.0906866 0.0790415 -0.0278425 1 0 1 1 0 0 +EDGE2 7951 7931 0.0252253 -0.0876294 -0.013798 1 0 1 1 0 0 +EDGE2 7951 7452 0.804952 -0.0299209 0.0171621 1 0 1 1 0 0 +EDGE2 7951 7531 0.0690191 -0.00733846 -0.0181855 1 0 1 1 0 0 +EDGE2 7951 7950 -1.04251 0.0262659 1.55605 1 0 1 1 0 0 +EDGE2 7951 7451 -0.0045296 0.0235379 0.00600744 1 0 1 1 0 0 +EDGE2 7951 7930 -0.975951 -0.128251 1.59543 1 0 1 1 0 0 +EDGE2 7951 7310 -1.02247 0.0530974 1.55151 1 0 1 1 0 0 +EDGE2 7951 7350 -1.01038 -0.00184741 1.58591 1 0 1 1 0 0 +EDGE2 7951 7450 -0.977821 0.047657 -1.5899 1 0 1 1 0 0 +EDGE2 7951 7510 -1.06778 0.0489599 -1.59464 1 0 1 1 0 0 +EDGE2 7951 7330 -0.955924 -0.0941973 1.5645 1 0 1 1 0 0 +EDGE2 7951 7170 -0.935866 0.0445643 -1.52232 1 0 1 1 0 0 +EDGE2 7951 7290 -1.06624 0.0649572 1.57282 1 0 1 1 0 0 +EDGE2 7952 7512 -0.0105832 -0.0438617 -0.0038771 1 0 1 1 0 0 +EDGE2 7952 7513 1.11312 0.0148959 -0.0201827 1 0 1 1 0 0 +EDGE2 7952 7933 0.984526 0.00380603 0.0276613 1 0 1 1 0 0 +EDGE2 7952 7533 0.980372 -0.0490682 0.0189227 1 0 1 1 0 0 +EDGE2 7952 7932 0.0805285 0.0305105 0.017091 1 0 1 1 0 0 +EDGE2 7952 7453 1.02305 0.00330772 -0.00511611 1 0 1 1 0 0 +EDGE2 7952 7532 0.0543572 0.0975551 0.0271233 1 0 1 1 0 0 +EDGE2 7952 7511 -1.01958 0.0393376 0.022765 1 0 1 1 0 0 +EDGE2 7952 7931 -1.01242 0.00243103 -0.0339549 1 0 1 1 0 0 +EDGE2 7952 7951 -1.01808 -0.025023 -0.00817977 1 0 1 1 0 0 +EDGE2 7952 7452 0.0863246 -0.00781519 -0.00290823 1 0 1 1 0 0 +EDGE2 7952 7531 -0.954671 -0.00572838 -0.0147985 1 0 1 1 0 0 +EDGE2 7952 7451 -1.00149 0.0369342 -0.0133823 1 0 1 1 0 0 +EDGE2 7953 7514 1.06264 0.0289503 0.0224134 1 0 1 1 0 0 +EDGE2 7953 7934 0.958437 0.0430918 -0.00132063 1 0 1 1 0 0 +EDGE2 7953 7534 1.06415 0.00741225 0.00925702 1 0 1 1 0 0 +EDGE2 7953 7512 -1.02273 -0.068351 0.0177647 1 0 1 1 0 0 +EDGE2 7953 7513 0.0427869 -0.0834806 -0.0146264 1 0 1 1 0 0 +EDGE2 7953 7933 -0.103301 -0.00809544 0.0267791 1 0 1 1 0 0 +EDGE2 7953 7454 0.984077 -0.0384805 0.0227691 1 0 1 1 0 0 +EDGE2 7953 7533 -0.0414794 -0.0299825 -0.0100362 1 0 1 1 0 0 +EDGE2 7953 7932 -0.943864 -0.034937 0.00919382 1 0 1 1 0 0 +EDGE2 7953 7952 -0.963327 0.0272773 -0.00332374 1 0 1 1 0 0 +EDGE2 7953 7453 0.00914917 0.0210188 0.0202562 1 0 1 1 0 0 +EDGE2 7953 7532 -0.953946 -0.0470864 -0.0170123 1 0 1 1 0 0 +EDGE2 7953 7452 -1.00657 0.063411 0.0340834 1 0 1 1 0 0 +EDGE2 7954 7535 1.03131 0.076403 -0.000340526 1 0 1 1 0 0 +EDGE2 7954 7575 1.07334 -0.00144474 -3.16664 1 0 1 1 0 0 +EDGE2 7954 7935 1.03965 0.0104468 0.0226554 1 0 1 1 0 0 +EDGE2 7954 7555 1.03414 0.0631652 -3.0967 1 0 1 1 0 0 +EDGE2 7954 7455 0.969476 -0.00531006 0.00592858 1 0 1 1 0 0 +EDGE2 7954 7475 0.943143 0.0721132 -3.14847 1 0 1 1 0 0 +EDGE2 7954 7515 0.968496 -0.0171156 0.0101525 1 0 1 1 0 0 +EDGE2 7954 7395 1.02601 -0.0258863 -3.15998 1 0 1 1 0 0 +EDGE2 7954 7514 -0.0337047 0.0285835 -0.0178994 1 0 1 1 0 0 +EDGE2 7954 7934 -0.0366132 -0.00917074 0.0403216 1 0 1 1 0 0 +EDGE2 7954 7534 0.0258924 -0.0384197 0.0156044 1 0 1 1 0 0 +EDGE2 7954 7513 -0.845401 -0.00119025 6.48723e-05 1 0 1 1 0 0 +EDGE2 7954 7933 -1.01889 0.0298402 -0.0148678 1 0 1 1 0 0 +EDGE2 7954 7953 -0.927999 -0.0246114 0.0137399 1 0 1 1 0 0 +EDGE2 7954 7454 0.0278105 0.045122 -0.0190201 1 0 1 1 0 0 +EDGE2 7954 7533 -1.025 -0.128318 -0.0384861 1 0 1 1 0 0 +EDGE2 7954 7453 -0.983631 -0.00848203 0.0613463 1 0 1 1 0 0 +EDGE2 7955 7476 -0.0142677 0.956913 1.55411 1 0 1 1 0 0 +EDGE2 7955 7396 0.0500897 1.02474 1.58232 1 0 1 1 0 0 +EDGE2 7955 7394 1.05902 0.0555546 -3.15436 1 0 1 1 0 0 +EDGE2 7955 7554 0.925757 0.0677885 -3.14695 1 0 1 1 0 0 +EDGE2 7955 7574 0.911889 -0.0134627 -3.12295 1 0 1 1 0 0 +EDGE2 7955 7474 1.01294 -0.0101338 -3.14468 1 0 1 1 0 0 +EDGE2 7955 7535 0.0100344 0.0170575 -0.0351485 1 0 1 1 0 0 +EDGE2 7955 7575 0.0297096 -0.0496143 -3.10458 1 0 1 1 0 0 +EDGE2 7955 7935 0.0112798 -0.0469758 -0.0168783 1 0 1 1 0 0 +EDGE2 7955 7555 0.00900605 -0.00836566 -3.09122 1 0 1 1 0 0 +EDGE2 7955 7455 0.0357318 0.00578744 -0.0116072 1 0 1 1 0 0 +EDGE2 7955 7475 -0.0230358 0.0104708 -3.13823 1 0 1 1 0 0 +EDGE2 7955 7515 -0.0464531 0.116349 -0.0283009 1 0 1 1 0 0 +EDGE2 7955 7395 0.0437604 -0.0512685 -3.14509 1 0 1 1 0 0 +EDGE2 7955 7576 0.0280576 -1.01929 -1.56595 1 0 1 1 0 0 +EDGE2 7955 7936 0.0704522 -0.973168 -1.55972 1 0 1 1 0 0 +EDGE2 7955 7516 0.0710944 -0.968593 -1.55099 1 0 1 1 0 0 +EDGE2 7955 7536 -0.0611009 -0.959912 -1.57777 1 0 1 1 0 0 +EDGE2 7955 7556 -0.0128794 -1.03401 -1.59205 1 0 1 1 0 0 +EDGE2 7955 7456 0.0343909 -1.02058 -1.53562 1 0 1 1 0 0 +EDGE2 7955 7514 -1.0169 -2.11525e-05 0.0242203 1 0 1 1 0 0 +EDGE2 7955 7934 -1.03966 0.0244777 -0.00204529 1 0 1 1 0 0 +EDGE2 7955 7954 -0.939247 0.0144061 0.0011067 1 0 1 1 0 0 +EDGE2 7955 7534 -0.982652 0.0186344 0.00592068 1 0 1 1 0 0 +EDGE2 7955 7454 -0.904012 0.0395384 0.0189752 1 0 1 1 0 0 +EDGE2 7956 7537 1.03573 -0.0285958 -0.00744222 1 0 1 1 0 0 +EDGE2 7956 7535 -1.03796 0.0171642 1.58256 1 0 1 1 0 0 +EDGE2 7956 7575 -1.00608 0.00221864 -1.56699 1 0 1 1 0 0 +EDGE2 7956 7935 -1.07901 0.0180427 1.55584 1 0 1 1 0 0 +EDGE2 7956 7955 -1.00413 -0.142472 1.54571 1 0 1 1 0 0 +EDGE2 7956 7555 -0.87318 0.0493891 -1.56553 1 0 1 1 0 0 +EDGE2 7956 7455 -1.03808 0.0217997 1.56068 1 0 1 1 0 0 +EDGE2 7956 7475 -0.925571 -0.0151462 -1.54465 1 0 1 1 0 0 +EDGE2 7956 7515 -1.04782 0.0220336 1.56486 1 0 1 1 0 0 +EDGE2 7956 7395 -0.996817 -0.0115906 -1.57616 1 0 1 1 0 0 +EDGE2 7956 7576 0.0521088 -0.0141861 0.000474656 1 0 1 1 0 0 +EDGE2 7956 7936 0.00302645 -0.0204133 0.00465899 1 0 1 1 0 0 +EDGE2 7956 7516 0.00941906 -0.0365836 -0.0308785 1 0 1 1 0 0 +EDGE2 7956 7536 -0.0381157 0.00550091 -0.010564 1 0 1 1 0 0 +EDGE2 7956 7556 0.0927983 -0.0175061 0.0139025 1 0 1 1 0 0 +EDGE2 7956 7456 -0.00262381 -0.0698224 -0.0268756 1 0 1 1 0 0 +EDGE2 7956 7577 1.0532 0.0805561 -0.00886824 1 0 1 1 0 0 +EDGE2 7956 7937 1.04055 -0.102249 0.00662223 1 0 1 1 0 0 +EDGE2 7956 7557 1.02273 -0.0468191 0.0161364 1 0 1 1 0 0 +EDGE2 7956 7517 0.993417 -0.0538175 0.030313 1 0 1 1 0 0 +EDGE2 7956 7457 0.99488 0.0372255 -0.0183232 1 0 1 1 0 0 +EDGE2 7957 7537 -0.125613 -0.0204462 0.0241657 1 0 1 1 0 0 +EDGE2 7957 7576 -0.981566 -0.0112125 -0.0301632 1 0 1 1 0 0 +EDGE2 7957 7936 -0.952109 -0.034295 0.0134012 1 0 1 1 0 0 +EDGE2 7957 7956 -0.913834 0.0185991 -0.00810879 1 0 1 1 0 0 +EDGE2 7957 7516 -0.994197 0.00513703 -0.00401442 1 0 1 1 0 0 +EDGE2 7957 7536 -0.985737 -0.074499 -0.0109569 1 0 1 1 0 0 +EDGE2 7957 7556 -1.03127 0.00935822 -0.0264714 1 0 1 1 0 0 +EDGE2 7957 7456 -1.06011 0.0769599 0.0181554 1 0 1 1 0 0 +EDGE2 7957 7577 -0.00734328 -0.0161823 -0.0293635 1 0 1 1 0 0 +EDGE2 7957 7937 -0.0208573 0.0168637 -0.00986614 1 0 1 1 0 0 +EDGE2 7957 7557 -0.0905074 0.00183318 0.046022 1 0 1 1 0 0 +EDGE2 7957 7517 -0.0023273 0.0380897 -0.00435903 1 0 1 1 0 0 +EDGE2 7957 7457 -0.0175886 0.0495648 0.0100459 1 0 1 1 0 0 +EDGE2 7957 7938 0.985327 -0.0952256 -0.00157988 1 0 1 1 0 0 +EDGE2 7957 7458 1.02462 0.028796 0.0078858 1 0 1 1 0 0 +EDGE2 7957 7538 1.02211 0.0288154 0.0315088 1 0 1 1 0 0 +EDGE2 7957 7558 0.972823 -0.0101522 -0.0183712 1 0 1 1 0 0 +EDGE2 7957 7578 0.98153 0.0515275 0.000504682 1 0 1 1 0 0 +EDGE2 7957 7518 1.03588 0.000780052 -0.0196258 1 0 1 1 0 0 +EDGE2 7958 7537 -1.02256 -0.0397586 -0.00890091 1 0 1 1 0 0 +EDGE2 7958 7957 -0.893759 0.038368 -0.00255241 1 0 1 1 0 0 +EDGE2 7958 7577 -0.980494 -0.0100565 0.0167182 1 0 1 1 0 0 +EDGE2 7958 7937 -0.976257 0.0224717 0.0161778 1 0 1 1 0 0 +EDGE2 7958 7557 -0.908827 -0.0177914 0.0222589 1 0 1 1 0 0 +EDGE2 7958 7517 -0.902678 0.00522485 0.0124407 1 0 1 1 0 0 +EDGE2 7958 7457 -0.98055 -0.00295289 0.00875451 1 0 1 1 0 0 +EDGE2 7958 7539 0.895241 0.0848452 0.0076137 1 0 1 1 0 0 +EDGE2 7958 7938 -0.0339668 -0.0710457 0.0310099 1 0 1 1 0 0 +EDGE2 7958 7458 -0.0982119 -0.0682521 0.0146379 1 0 1 1 0 0 +EDGE2 7958 7538 -0.0772768 -0.0416133 -0.0043892 1 0 1 1 0 0 +EDGE2 7958 7558 0.0636278 0.0652129 0.0238413 1 0 1 1 0 0 +EDGE2 7958 7578 0.0399795 0.0642873 -0.0130389 1 0 1 1 0 0 +EDGE2 7958 7518 0.0213753 -0.0270837 -0.00177331 1 0 1 1 0 0 +EDGE2 7958 7579 1.02316 0.135049 0.000662279 1 0 1 1 0 0 +EDGE2 7958 7939 1.05374 -0.0988941 0.0429634 1 0 1 1 0 0 +EDGE2 7958 7559 1.03495 -0.0792908 0.0113812 1 0 1 1 0 0 +EDGE2 7958 7459 0.998529 0.0531248 0.00729183 1 0 1 1 0 0 +EDGE2 7958 7519 0.985848 0.00724232 0.0195101 1 0 1 1 0 0 +EDGE2 7959 7520 0.952358 -0.00442205 0.0304354 1 0 1 1 0 0 +EDGE2 7959 7539 0.0422341 0.00252634 0.00723252 1 0 1 1 0 0 +EDGE2 7959 7938 -1.01818 -0.0567442 -0.0166965 1 0 1 1 0 0 +EDGE2 7959 7958 -0.949211 0.0519942 0.000357924 1 0 1 1 0 0 +EDGE2 7959 7458 -0.964003 0.0580471 0.0115476 1 0 1 1 0 0 +EDGE2 7959 7538 -0.963704 0.0466241 -0.00724327 1 0 1 1 0 0 +EDGE2 7959 7558 -1.00436 -0.00893332 -0.0237645 1 0 1 1 0 0 +EDGE2 7959 7578 -1.01825 -0.0452941 0.0227117 1 0 1 1 0 0 +EDGE2 7959 7518 -0.932626 -0.0117409 0.0114189 1 0 1 1 0 0 +EDGE2 7959 7579 0.0268321 0.0718273 0.0196636 1 0 1 1 0 0 +EDGE2 7959 7939 0.00762715 -0.0863391 0.00447668 1 0 1 1 0 0 +EDGE2 7959 7559 -0.0210384 -0.076952 0.0116532 1 0 1 1 0 0 +EDGE2 7959 7459 -0.016959 -0.0696301 0.0146831 1 0 1 1 0 0 +EDGE2 7959 7519 -0.0228943 -0.0046828 -0.0375426 1 0 1 1 0 0 +EDGE2 7959 7540 0.993731 -0.0691342 0.0385146 1 0 1 1 0 0 +EDGE2 7959 7580 0.903707 -0.0219111 -0.00271298 1 0 1 1 0 0 +EDGE2 7959 7940 1.0835 -0.0786757 -0.0152318 1 0 1 1 0 0 +EDGE2 7959 7560 1.05615 0.0174075 0.0115098 1 0 1 1 0 0 +EDGE2 7959 7380 0.894901 0.0294688 -3.13334 1 0 1 1 0 0 +EDGE2 7959 7460 1.00764 -0.0911865 0.0031876 1 0 1 1 0 0 +EDGE2 7960 7520 -0.0145503 0.061412 0.00832809 1 0 1 1 0 0 +EDGE2 7960 7539 -0.91068 -0.0517095 -0.0123099 1 0 1 1 0 0 +EDGE2 7960 7579 -0.947599 -0.0363531 0.0313637 1 0 1 1 0 0 +EDGE2 7960 7939 -0.978624 -0.00960131 0.0318086 1 0 1 1 0 0 +EDGE2 7960 7959 -1.0129 -0.00771373 -0.00268636 1 0 1 1 0 0 +EDGE2 7960 7559 -0.957473 -0.0861128 0.0230508 1 0 1 1 0 0 +EDGE2 7960 7459 -0.990693 0.0105829 0.0189796 1 0 1 1 0 0 +EDGE2 7960 7519 -1.05956 0.0523432 0.00198579 1 0 1 1 0 0 +EDGE2 7960 7540 -0.00104386 -0.0725516 -0.00536879 1 0 1 1 0 0 +EDGE2 7960 7561 -0.00499849 1.12375 1.54369 1 0 1 1 0 0 +EDGE2 7960 7581 0.0482804 0.98289 1.55012 1 0 1 1 0 0 +EDGE2 7960 7381 -0.000834468 0.965342 1.58004 1 0 1 1 0 0 +EDGE2 7960 7461 0.0579234 1.0519 1.55376 1 0 1 1 0 0 +EDGE2 7960 7541 -0.0945204 1.03024 1.57026 1 0 1 1 0 0 +EDGE2 7960 7580 0.00682933 0.0269542 0.0210632 1 0 1 1 0 0 +EDGE2 7960 7940 -0.0306422 0.00265122 -0.00311938 1 0 1 1 0 0 +EDGE2 7960 7560 -0.036388 0.0408254 -0.0311958 1 0 1 1 0 0 +EDGE2 7960 7941 0.0463052 -0.958286 -1.5671 1 0 1 1 0 0 +EDGE2 7960 7380 0.0194465 -0.0418214 -3.12546 1 0 1 1 0 0 +EDGE2 7960 7460 -0.0465372 0.00684951 0.0211217 1 0 1 1 0 0 +EDGE2 7960 7521 -0.0329859 -0.972519 -1.61197 1 0 1 1 0 0 +EDGE2 7960 7379 1.00987 -0.103284 -3.15081 1 0 1 1 0 0 +EDGE2 7961 7520 -0.991202 -0.0223055 -1.58328 1 0 1 1 0 0 +EDGE2 7961 7540 -1.06603 -0.0419706 -1.56644 1 0 1 1 0 0 +EDGE2 7961 7561 0.0481584 -0.0759265 0.0226096 1 0 1 1 0 0 +EDGE2 7961 7542 0.919058 0.00568669 0.0430619 1 0 1 1 0 0 +EDGE2 7961 7582 0.956085 0.0599941 -0.00761066 1 0 1 1 0 0 +EDGE2 7961 7562 0.989961 0.0327687 -0.0270225 1 0 1 1 0 0 +EDGE2 7961 7382 1.09899 -0.0841324 0.000827942 1 0 1 1 0 0 +EDGE2 7961 7462 0.926364 0.0157729 0.01349 1 0 1 1 0 0 +EDGE2 7961 7581 -0.0240515 -0.0255357 -0.00968197 1 0 1 1 0 0 +EDGE2 7961 7381 0.00623179 -0.100695 -0.000511127 1 0 1 1 0 0 +EDGE2 7961 7461 0.0443556 0.0381215 -0.0121837 1 0 1 1 0 0 +EDGE2 7961 7541 -0.0245778 -0.0466144 -0.0086948 1 0 1 1 0 0 +EDGE2 7961 7580 -1.03261 -0.0144657 -1.53414 1 0 1 1 0 0 +EDGE2 7961 7940 -1.0467 0.0241103 -1.56992 1 0 1 1 0 0 +EDGE2 7961 7960 -1.04875 0.0568576 -1.56674 1 0 1 1 0 0 +EDGE2 7961 7560 -1.0434 0.0821635 -1.57097 1 0 1 1 0 0 +EDGE2 7961 7380 -0.932775 -0.0513129 1.55896 1 0 1 1 0 0 +EDGE2 7961 7460 -1.13739 0.0525675 -1.5619 1 0 1 1 0 0 +EDGE2 7962 7463 0.902669 0.00338264 -0.0250573 1 0 1 1 0 0 +EDGE2 7962 7563 1.12107 -0.012773 0.00381413 1 0 1 1 0 0 +EDGE2 7962 7583 0.986724 -0.0851521 0.0536931 1 0 1 1 0 0 +EDGE2 7962 7543 1.00254 0.0371641 0.00554094 1 0 1 1 0 0 +EDGE2 7962 7561 -1.04159 0.0552706 0.00705511 1 0 1 1 0 0 +EDGE2 7962 7542 0.0513571 -0.0113792 -0.0225046 1 0 1 1 0 0 +EDGE2 7962 7582 -0.0181938 0.0772815 -0.0170027 1 0 1 1 0 0 +EDGE2 7962 7383 0.99226 0.0129964 -0.0290509 1 0 1 1 0 0 +EDGE2 7962 7562 0.0454914 0.0319699 -0.00899615 1 0 1 1 0 0 +EDGE2 7962 7961 -1.00309 0.0290103 -0.00572102 1 0 1 1 0 0 +EDGE2 7962 7382 -0.0189544 0.0305541 -0.0140168 1 0 1 1 0 0 +EDGE2 7962 7462 -0.0300914 0.116238 0.0194116 1 0 1 1 0 0 +EDGE2 7962 7581 -1.11767 0.102402 0.000585582 1 0 1 1 0 0 +EDGE2 7962 7381 -1.0191 -0.042838 0.00847879 1 0 1 1 0 0 +EDGE2 7962 7461 -0.949787 -1.28162e-05 0.028706 1 0 1 1 0 0 +EDGE2 7962 7541 -0.987012 -0.00699264 0.0403642 1 0 1 1 0 0 +EDGE2 7963 7463 -0.0749187 0.034761 0.0361641 1 0 1 1 0 0 +EDGE2 7963 7544 1.00782 -0.0160966 0.00896414 1 0 1 1 0 0 +EDGE2 7963 7584 1.01025 0.0208285 0.02069 1 0 1 1 0 0 +EDGE2 7963 7564 1.00953 -0.0608983 0.00562204 1 0 1 1 0 0 +EDGE2 7963 7464 0.983074 -0.042697 0.0298403 1 0 1 1 0 0 +EDGE2 7963 7384 0.88501 -0.00853804 -0.026667 1 0 1 1 0 0 +EDGE2 7963 7563 -0.0792221 0.0961298 0.0199654 1 0 1 1 0 0 +EDGE2 7963 7583 0.0796681 0.0179325 0.00211908 1 0 1 1 0 0 +EDGE2 7963 7543 -0.116281 -0.0267382 0.0135735 1 0 1 1 0 0 +EDGE2 7963 7542 -1.05587 0.0643272 -0.00804643 1 0 1 1 0 0 +EDGE2 7963 7582 -1.03227 0.00212077 -0.0382343 1 0 1 1 0 0 +EDGE2 7963 7962 -0.992519 0.124364 0.0180379 1 0 1 1 0 0 +EDGE2 7963 7383 0.00259074 0.015844 0.0416343 1 0 1 1 0 0 +EDGE2 7963 7562 -1.10514 -0.056179 -0.0286137 1 0 1 1 0 0 +EDGE2 7963 7382 -0.948378 0.0240686 -0.0190287 1 0 1 1 0 0 +EDGE2 7963 7462 -1.01544 0.0509983 -0.0420001 1 0 1 1 0 0 +EDGE2 7964 7463 -0.99089 -0.0481812 -0.0400785 1 0 1 1 0 0 +EDGE2 7964 7544 0.0101839 -0.00359383 0.0477054 1 0 1 1 0 0 +EDGE2 7964 7465 1.0441 -0.0646038 0.00705788 1 0 1 1 0 0 +EDGE2 7964 7565 1.02428 -0.064091 0.00241441 1 0 1 1 0 0 +EDGE2 7964 7585 0.910169 0.084306 0.00644819 1 0 1 1 0 0 +EDGE2 7964 7545 1.01725 -0.0514829 -0.0156259 1 0 1 1 0 0 +EDGE2 7964 7584 0.0506949 -0.00470065 0.0169612 1 0 1 1 0 0 +EDGE2 7964 7385 1.01989 -0.11015 0.0306691 1 0 1 1 0 0 +EDGE2 7964 7564 0.0539161 -0.0340083 0.00243813 1 0 1 1 0 0 +EDGE2 7964 7963 -1.0398 0.0590065 0.0167955 1 0 1 1 0 0 +EDGE2 7964 7464 0.0632443 -0.0649727 0.00289696 1 0 1 1 0 0 +EDGE2 7964 7384 -0.0463865 -0.0367235 0.0364297 1 0 1 1 0 0 +EDGE2 7964 7563 -1.00869 0.00972363 0.0182016 1 0 1 1 0 0 +EDGE2 7964 7583 -1.11824 -0.0630927 -0.0195656 1 0 1 1 0 0 +EDGE2 7964 7543 -0.923636 -0.0792993 0.00562784 1 0 1 1 0 0 +EDGE2 7964 7383 -1.01196 0.0273607 0.0627361 1 0 1 1 0 0 +EDGE2 7965 7466 -0.00544814 0.90199 1.57211 1 0 1 1 0 0 +EDGE2 7965 7546 -0.0182035 1.00542 1.56812 1 0 1 1 0 0 +EDGE2 7965 7566 -0.0200784 0.992799 1.54788 1 0 1 1 0 0 +EDGE2 7965 7386 0.0289413 1.01888 1.56864 1 0 1 1 0 0 +EDGE2 7965 7544 -0.993347 0.00168086 -0.00291542 1 0 1 1 0 0 +EDGE2 7965 7465 0.0382373 -0.062317 -0.0390162 1 0 1 1 0 0 +EDGE2 7965 7565 0.0745065 -0.0118876 0.0150751 1 0 1 1 0 0 +EDGE2 7965 7585 -0.0484634 0.0542794 -0.0237241 1 0 1 1 0 0 +EDGE2 7965 7545 0.0462624 0.0355382 -0.000600073 1 0 1 1 0 0 +EDGE2 7965 7584 -0.980018 -0.0435839 0.0393848 1 0 1 1 0 0 +EDGE2 7965 7964 -0.918651 -0.0622075 -0.0056042 1 0 1 1 0 0 +EDGE2 7965 7385 -0.0490862 -0.0436666 -0.0105202 1 0 1 1 0 0 +EDGE2 7965 7564 -0.952671 -0.0701328 -0.0300033 1 0 1 1 0 0 +EDGE2 7965 7464 -0.985429 -0.0678306 0.0394244 1 0 1 1 0 0 +EDGE2 7965 7384 -0.920246 0.0248839 -0.0105259 1 0 1 1 0 0 +EDGE2 7965 7586 -0.0647238 -1.01058 -1.56542 1 0 1 1 0 0 +EDGE2 7966 7465 -0.954026 0.00991253 1.60942 1 0 1 1 0 0 +EDGE2 7966 7565 -0.9459 0.025278 1.57723 1 0 1 1 0 0 +EDGE2 7966 7585 -1.00399 0.0995466 1.58273 1 0 1 1 0 0 +EDGE2 7966 7965 -1.02549 -0.0371799 1.53973 1 0 1 1 0 0 +EDGE2 7966 7545 -0.949415 -0.0290787 1.55662 1 0 1 1 0 0 +EDGE2 7966 7385 -1.01074 0.0429343 1.58027 1 0 1 1 0 0 +EDGE2 7966 7586 -0.0239404 0.0245358 -0.0182735 1 0 1 1 0 0 +EDGE2 7966 7587 0.974523 0.0313337 0.0161024 1 0 1 1 0 0 +EDGE2 7967 7586 -1.01853 -0.0290251 0.00615263 1 0 1 1 0 0 +EDGE2 7967 7966 -0.983285 0.00509609 0.0252735 1 0 1 1 0 0 +EDGE2 7967 7587 -0.0823766 -0.0559397 0.0181756 1 0 1 1 0 0 +EDGE2 7967 7588 0.942502 0.0157265 -0.0186778 1 0 1 1 0 0 +EDGE2 7968 7967 -0.997045 -0.073563 -0.0227092 1 0 1 1 0 0 +EDGE2 7968 7587 -0.953797 0.0141554 -0.016874 1 0 1 1 0 0 +EDGE2 7968 7589 1.05091 0.112914 -0.00535289 1 0 1 1 0 0 +EDGE2 7968 7588 -0.0241299 -0.0337294 -0.0302189 1 0 1 1 0 0 +EDGE2 7969 7590 1.03671 0.0139843 -0.0145605 1 0 1 1 0 0 +EDGE2 7969 7968 -0.965543 0.0336116 -0.010269 1 0 1 1 0 0 +EDGE2 7969 7589 -0.0488607 0.0396829 0.0372031 1 0 1 1 0 0 +EDGE2 7969 7588 -0.952854 -0.00547044 -0.000420098 1 0 1 1 0 0 +EDGE2 7970 7590 0.000848638 0.0793319 0.0102461 1 0 1 1 0 0 +EDGE2 7970 7589 -1.00187 -0.00839003 -0.026895 1 0 1 1 0 0 +EDGE2 7970 7969 -1.08466 -0.0891884 0.0121772 1 0 1 1 0 0 +EDGE2 7970 7591 0.0856388 -0.996895 -1.58911 1 0 1 1 0 0 +EDGE2 7971 7590 -0.945235 -0.0834241 1.5781 1 0 1 1 0 0 +EDGE2 7971 7970 -0.967481 -0.0238625 1.61079 1 0 1 1 0 0 +EDGE2 7971 7591 -0.00833139 0.0173389 0.0227573 1 0 1 1 0 0 +EDGE2 7971 7592 0.960711 0.00667706 -0.0159041 1 0 1 1 0 0 +EDGE2 7972 7591 -1.0286 0.0881727 -0.00669827 1 0 1 1 0 0 +EDGE2 7972 7971 -1.07867 0.0589512 0.0131541 1 0 1 1 0 0 +EDGE2 7972 7592 0.0750142 -0.049148 -0.0208141 1 0 1 1 0 0 +EDGE2 7972 7593 0.980591 -0.0232488 -0.00946741 1 0 1 1 0 0 +EDGE2 7973 7972 -1.02936 0.0254218 -0.00300876 1 0 1 1 0 0 +EDGE2 7973 7592 -0.997806 -0.0183116 0.0176708 1 0 1 1 0 0 +EDGE2 7973 7593 -0.0330615 0.0715535 0.0314852 1 0 1 1 0 0 +EDGE2 7973 7594 1.00951 -0.00554463 0.0012877 1 0 1 1 0 0 +EDGE2 7974 7973 -0.986775 0.0416137 0.00737054 1 0 1 1 0 0 +EDGE2 7974 7593 -1.06882 -0.051164 0.0340213 1 0 1 1 0 0 +EDGE2 7974 7594 0.0237411 -0.0101019 0.0333781 1 0 1 1 0 0 +EDGE2 7974 7375 1.04077 -0.051234 -3.11125 1 0 1 1 0 0 +EDGE2 7974 7595 0.955492 0.106093 0.00500917 1 0 1 1 0 0 +EDGE2 7974 7635 1.01242 0.0326554 -3.16652 1 0 1 1 0 0 +EDGE2 7975 7974 -0.981937 0.0196369 0.0542125 1 0 1 1 0 0 +EDGE2 7975 7594 -1.03251 0.0881201 -0.000258961 1 0 1 1 0 0 +EDGE2 7975 7376 0.0447479 -1.02494 -1.56376 1 0 1 1 0 0 +EDGE2 7975 7596 -0.0446807 1.03425 1.56263 1 0 1 1 0 0 +EDGE2 7975 7636 -0.0275952 0.943467 1.57355 1 0 1 1 0 0 +EDGE2 7975 7375 0.0285662 0.00802931 -3.15152 1 0 1 1 0 0 +EDGE2 7975 7595 0.0193409 -0.020229 0.0356101 1 0 1 1 0 0 +EDGE2 7975 7635 0.00925158 0.0823787 -3.13859 1 0 1 1 0 0 +EDGE2 7975 7634 1.122 -0.0222639 -3.16043 1 0 1 1 0 0 +EDGE2 7975 7374 1.03657 -0.0433401 -3.14246 1 0 1 1 0 0 +EDGE2 7976 7975 -1.05861 -0.152114 -1.58992 1 0 1 1 0 0 +EDGE2 7976 7596 -0.0718005 0.0454258 -0.00519885 1 0 1 1 0 0 +EDGE2 7976 7636 0.0937486 -0.0197372 -0.0275337 1 0 1 1 0 0 +EDGE2 7976 7375 -0.986156 -0.0525957 1.56609 1 0 1 1 0 0 +EDGE2 7976 7595 -1.09083 -0.000977385 -1.57442 1 0 1 1 0 0 +EDGE2 7976 7635 -0.951845 -0.0315598 1.55465 1 0 1 1 0 0 +EDGE2 7976 7597 1.04446 0.0596154 -0.016561 1 0 1 1 0 0 +EDGE2 7976 7637 1.06074 -0.0475522 -0.00709765 1 0 1 1 0 0 +EDGE2 7977 7596 -0.98696 -0.00241906 -0.042828 1 0 1 1 0 0 +EDGE2 7977 7636 -0.973103 0.0631096 -0.0317466 1 0 1 1 0 0 +EDGE2 7977 7976 -1.01069 -0.0339732 0.0026283 1 0 1 1 0 0 +EDGE2 7977 7638 0.942303 -0.0233714 0.0157827 1 0 1 1 0 0 +EDGE2 7977 7597 0.0225899 0.0175609 -0.00725878 1 0 1 1 0 0 +EDGE2 7977 7637 0.00863134 0.103317 -0.00330132 1 0 1 1 0 0 +EDGE2 7977 7598 1.04055 -0.0558845 0.0332294 1 0 1 1 0 0 +EDGE2 7978 7638 0.0601982 -0.0526442 -0.00648274 1 0 1 1 0 0 +EDGE2 7978 7597 -0.886597 -0.0341796 -0.026077 1 0 1 1 0 0 +EDGE2 7978 7637 -0.97594 -0.061733 -0.00445101 1 0 1 1 0 0 +EDGE2 7978 7977 -1.00476 0.00734439 -0.00208389 1 0 1 1 0 0 +EDGE2 7978 7639 0.98025 0.0531366 -0.020366 1 0 1 1 0 0 +EDGE2 7978 7598 -0.0896622 -0.05081 -0.010656 1 0 1 1 0 0 +EDGE2 7978 7599 0.986451 0.0539762 0.00685308 1 0 1 1 0 0 +EDGE2 7979 7638 -0.985234 0.0838345 0.0138127 1 0 1 1 0 0 +EDGE2 7979 7978 -1.01295 -0.0334517 -0.014634 1 0 1 1 0 0 +EDGE2 7979 7639 0.023743 0.0127025 0.026513 1 0 1 1 0 0 +EDGE2 7979 7598 -1.01398 -0.102406 0.0172744 1 0 1 1 0 0 +EDGE2 7979 7599 -0.0651453 -0.0874939 0.00351078 1 0 1 1 0 0 +EDGE2 7979 7600 1.0255 0.102469 0.0328236 1 0 1 1 0 0 +EDGE2 7979 7640 1.01095 0.0673852 -0.0153546 1 0 1 1 0 0 +EDGE2 7979 7620 1.04741 -0.0176958 -3.14067 1 0 1 1 0 0 +EDGE2 7980 7639 -0.918291 -0.00804611 0.00514524 1 0 1 1 0 0 +EDGE2 7980 7979 -1.09627 -0.0913505 0.0109036 1 0 1 1 0 0 +EDGE2 7980 7599 -0.922981 0.00758814 0.00935544 1 0 1 1 0 0 +EDGE2 7980 7600 -0.0592869 0.0139746 -0.0182246 1 0 1 1 0 0 +EDGE2 7980 7640 -0.0334105 -0.0211029 -0.0209304 1 0 1 1 0 0 +EDGE2 7980 7641 -0.0515374 1.09518 1.5549 1 0 1 1 0 0 +EDGE2 7980 7620 -0.00584301 -0.0536456 -3.1531 1 0 1 1 0 0 +EDGE2 7980 7619 0.974033 0.0409441 -3.16028 1 0 1 1 0 0 +EDGE2 7980 7601 0.0386468 -1.05852 -1.58053 1 0 1 1 0 0 +EDGE2 7980 7621 0.0164674 -0.998451 -1.55694 1 0 1 1 0 0 +EDGE2 7981 7642 1.01413 -0.0464947 0.0207753 1 0 1 1 0 0 +EDGE2 7981 7600 -1.05488 -0.0787795 -1.57407 1 0 1 1 0 0 +EDGE2 7981 7640 -1.02415 -0.0447589 -1.54919 1 0 1 1 0 0 +EDGE2 7981 7980 -1.03931 -0.00939016 -1.54481 1 0 1 1 0 0 +EDGE2 7981 7641 0.00589299 -0.00926025 0.0299855 1 0 1 1 0 0 +EDGE2 7981 7620 -1.0798 -0.0248021 1.56624 1 0 1 1 0 0 +EDGE2 7982 7981 -1.04671 -0.0209002 0.0112697 1 0 1 1 0 0 +EDGE2 7982 7642 0.000815773 0.0460842 0.0275262 1 0 1 1 0 0 +EDGE2 7982 7643 0.999976 0.00974802 0.00428861 1 0 1 1 0 0 +EDGE2 7982 7641 -1.00991 0.0937992 0.0265746 1 0 1 1 0 0 +EDGE2 7983 7644 1.03462 -0.0364512 -0.0237126 1 0 1 1 0 0 +EDGE2 7983 7642 -0.945965 0.0447026 0.0158803 1 0 1 1 0 0 +EDGE2 7983 7982 -1.0378 -0.0326164 -0.010661 1 0 1 1 0 0 +EDGE2 7983 7643 0.0185085 -0.00440588 0.0116977 1 0 1 1 0 0 +EDGE2 7984 7983 -1.10092 0.0306943 0.0101362 1 0 1 1 0 0 +EDGE2 7984 7645 1.06569 -0.0195771 -0.000907007 1 0 1 1 0 0 +EDGE2 7984 7644 0.0292767 0.0729244 -0.00589876 1 0 1 1 0 0 +EDGE2 7984 7643 -0.85892 0.0621585 -0.0147386 1 0 1 1 0 0 +EDGE2 7985 7984 -0.964744 -0.025941 0.0478365 1 0 1 1 0 0 +EDGE2 7985 7645 0.046722 -0.0665405 -0.00697521 1 0 1 1 0 0 +EDGE2 7985 7644 -0.921581 0.000938293 -0.0206804 1 0 1 1 0 0 +EDGE2 7985 7646 -0.0326102 -1.00808 -1.55315 1 0 1 1 0 0 +EDGE2 7986 7645 -0.919785 -0.0593162 1.56365 1 0 1 1 0 0 +EDGE2 7986 7985 -1.0621 -0.00873358 1.56958 1 0 1 1 0 0 +EDGE2 7986 7646 0.0599679 -0.124133 0.00551437 1 0 1 1 0 0 +EDGE2 7986 7647 1.08314 0.00547561 0.020946 1 0 1 1 0 0 +EDGE2 7987 7646 -0.976034 0.0201907 -0.000807101 1 0 1 1 0 0 +EDGE2 7987 7986 -0.949407 -0.0214869 -0.00647123 1 0 1 1 0 0 +EDGE2 7987 7647 -0.0805762 -0.0287559 -0.0266645 1 0 1 1 0 0 +EDGE2 7987 7648 0.971432 -0.0425621 -0.00370716 1 0 1 1 0 0 +EDGE2 7988 7647 -1.08662 -0.0206055 -0.000953088 1 0 1 1 0 0 +EDGE2 7988 7987 -1.00024 0.0537169 -0.0257941 1 0 1 1 0 0 +EDGE2 7988 7648 -0.0280126 -0.0508036 0.0274991 1 0 1 1 0 0 +EDGE2 7988 7649 0.890757 -0.0038909 0.0369297 1 0 1 1 0 0 +EDGE2 7989 7988 -1.10515 -0.00611368 -0.0249522 1 0 1 1 0 0 +EDGE2 7989 7648 -0.978212 -0.00552812 0.0129799 1 0 1 1 0 0 +EDGE2 7989 7649 -0.0455337 -0.0128468 -0.0482627 1 0 1 1 0 0 +EDGE2 7989 7650 1.06667 -0.090474 0.030638 1 0 1 1 0 0 +EDGE2 7990 7989 -0.992894 0.0112126 0.00280546 1 0 1 1 0 0 +EDGE2 7990 7651 0.0853524 0.950483 1.55954 1 0 1 1 0 0 +EDGE2 7990 7649 -1.04349 0.0897688 -1.70542e-05 1 0 1 1 0 0 +EDGE2 7990 7650 -0.0116657 0.028617 0.00937096 1 0 1 1 0 0 +EDGE2 7991 7652 0.876863 -0.0353998 0.00164617 1 0 1 1 0 0 +EDGE2 7991 7651 -0.0923908 -0.0957192 0.0210354 1 0 1 1 0 0 +EDGE2 7991 7990 -0.985197 -0.0611511 -1.60449 1 0 1 1 0 0 +EDGE2 7991 7650 -0.888991 0.0529885 -1.55691 1 0 1 1 0 0 +EDGE2 7992 7653 1.04412 -0.0293037 0.0136912 1 0 1 1 0 0 +EDGE2 7992 7991 -0.961867 -0.0375751 0.00441873 1 0 1 1 0 0 +EDGE2 7992 7652 -0.068768 0.081079 -0.0252032 1 0 1 1 0 0 +EDGE2 7992 7651 -1.00182 0.0657039 -0.0100296 1 0 1 1 0 0 +EDGE2 7993 7654 1.02257 0.0586338 0.00188565 1 0 1 1 0 0 +EDGE2 7993 7653 0.0593783 0.0177042 0.00959824 1 0 1 1 0 0 +EDGE2 7993 7652 -1.01821 0.0156164 0.0144091 1 0 1 1 0 0 +EDGE2 7993 7992 -1.07813 0.0134011 0.0092461 1 0 1 1 0 0 +EDGE2 7994 7654 -0.0387774 -0.0647463 -0.0226719 1 0 1 1 0 0 +EDGE2 7994 7655 1.05262 -0.0013732 0.0270303 1 0 1 1 0 0 +EDGE2 7994 7653 -0.971298 -0.0107554 0.0133662 1 0 1 1 0 0 +EDGE2 7994 7993 -0.890721 0.0158365 -0.0447389 1 0 1 1 0 0 +EDGE2 7995 7656 0.076482 -0.963502 -1.57985 1 0 1 1 0 0 +EDGE2 7995 7654 -1.01117 -0.134471 -0.0189871 1 0 1 1 0 0 +EDGE2 7995 7655 0.0243855 -0.0306284 -0.0354536 1 0 1 1 0 0 +EDGE2 7995 7994 -0.978932 -0.10748 0.0150863 1 0 1 1 0 0 +EDGE2 7996 7656 -0.077101 0.0449633 0.00760016 1 0 1 1 0 0 +EDGE2 7996 7655 -1.01918 0.0701514 1.55916 1 0 1 1 0 0 +EDGE2 7996 7995 -0.996415 0.116811 1.5517 1 0 1 1 0 0 +EDGE2 7996 7657 1.03141 -0.0424335 0.00540035 1 0 1 1 0 0 +EDGE2 7997 7656 -1.02877 -0.0146314 -0.0128987 1 0 1 1 0 0 +EDGE2 7997 7996 -1.01591 0.0468653 0.00838034 1 0 1 1 0 0 +EDGE2 7997 7658 1.00365 -0.00819669 0.0252863 1 0 1 1 0 0 +EDGE2 7997 7657 0.0212348 -0.0949369 0.017291 1 0 1 1 0 0 +EDGE2 7998 7658 0.0379251 0.0474992 -0.0188443 1 0 1 1 0 0 +EDGE2 7998 7657 -0.920849 0.0772162 0.0319731 1 0 1 1 0 0 +EDGE2 7998 7997 -1.02758 -0.0413692 -0.0249954 1 0 1 1 0 0 +EDGE2 7998 7659 1.01853 0.00352581 -0.0364714 1 0 1 1 0 0 +EDGE2 7999 7658 -1.0435 0.0820097 -0.010935 1 0 1 1 0 0 +EDGE2 7999 7998 -0.982946 -0.0293478 -0.00119184 1 0 1 1 0 0 +EDGE2 7999 7659 0.0321579 -0.0591873 -0.0145092 1 0 1 1 0 0 +EDGE2 7999 7660 0.942723 0.00945515 -0.0300498 1 0 1 1 0 0 +EDGE2 7999 7680 1.00483 0.0572231 -3.13238 1 0 1 1 0 0 +EDGE2 7999 6360 0.912992 -0.00882623 -3.15335 1 0 1 1 0 0 +EDGE2 8000 7999 -1.02094 -0.0223354 -0.012733 1 0 1 1 0 0 +EDGE2 8000 7659 -1.012 -0.0505403 -0.0104154 1 0 1 1 0 0 +EDGE2 8000 7660 0.0236036 0.00708783 -0.0141683 1 0 1 1 0 0 +EDGE2 8000 7680 -0.0452677 -0.0344366 -3.1496 1 0 1 1 0 0 +EDGE2 8000 6360 0.00386752 -0.0862352 -3.13057 1 0 1 1 0 0 +EDGE2 8000 6359 0.999264 0.0629235 -3.13159 1 0 1 1 0 0 +EDGE2 8000 7679 0.944452 0.00255616 -3.12474 1 0 1 1 0 0 +EDGE2 8000 6361 -0.0490985 -1.04837 -1.56977 1 0 1 1 0 0 +EDGE2 8000 7661 -0.0158736 -1.07844 -1.60928 1 0 1 1 0 0 +EDGE2 8000 7681 0.0203073 -1.00962 -1.59021 1 0 1 1 0 0 +EDGE2 8001 7660 -0.961536 0.0380677 1.56212 1 0 1 1 0 0 +EDGE2 8001 7680 -1.0287 -0.129854 -1.58201 1 0 1 1 0 0 +EDGE2 8001 8000 -0.98189 0.0246904 1.56314 1 0 1 1 0 0 +EDGE2 8001 6360 -0.967648 -0.0132066 -1.56304 1 0 1 1 0 0 +EDGE2 8001 7682 0.979325 -0.108248 0.0264448 1 0 1 1 0 0 +EDGE2 8001 6361 -0.0247338 -0.0529937 0.00741464 1 0 1 1 0 0 +EDGE2 8001 7661 0.0665159 -0.0356183 0.0180469 1 0 1 1 0 0 +EDGE2 8001 7681 -0.0240446 -0.0438778 -0.00586033 1 0 1 1 0 0 +EDGE2 8001 6362 0.977031 0.0244864 0.0144625 1 0 1 1 0 0 +EDGE2 8001 7662 1.0027 -0.00848325 0.00261826 1 0 1 1 0 0 +EDGE2 8002 8001 -0.938328 0.0143415 0.014201 1 0 1 1 0 0 +EDGE2 8002 7682 -0.0257582 -0.0651235 0.0145975 1 0 1 1 0 0 +EDGE2 8002 6361 -1.01393 0.00920844 0.0196852 1 0 1 1 0 0 +EDGE2 8002 7661 -0.953059 -0.0318633 -0.00729902 1 0 1 1 0 0 +EDGE2 8002 7681 -1.05752 0.0769404 0.0286289 1 0 1 1 0 0 +EDGE2 8002 6362 -0.0557226 -0.152686 0.0153142 1 0 1 1 0 0 +EDGE2 8002 7662 0.0183607 0.111572 -0.0151277 1 0 1 1 0 0 +EDGE2 8002 6363 1.07132 -0.0593021 0.0208769 1 0 1 1 0 0 +EDGE2 8002 7663 1.05999 0.0240182 0.0123469 1 0 1 1 0 0 +EDGE2 8002 7683 0.922079 -0.0322767 0.000811873 1 0 1 1 0 0 +EDGE2 8003 7682 -0.936345 0.0433664 -0.000379336 1 0 1 1 0 0 +EDGE2 8003 8002 -0.958986 0.0341575 0.0100683 1 0 1 1 0 0 +EDGE2 8003 6362 -1.03284 0.0208388 -0.0227858 1 0 1 1 0 0 +EDGE2 8003 7662 -1.01779 0.0291172 0.0214219 1 0 1 1 0 0 +EDGE2 8003 7684 0.956 -0.0502678 0.00105011 1 0 1 1 0 0 +EDGE2 8003 6363 0.0587677 -0.0254957 0.0102861 1 0 1 1 0 0 +EDGE2 8003 7663 0.0359612 -0.050626 -0.00235277 1 0 1 1 0 0 +EDGE2 8003 7683 0.0473312 0.0129646 0.00970064 1 0 1 1 0 0 +EDGE2 8003 6364 0.961391 -0.0363102 0.0191701 1 0 1 1 0 0 +EDGE2 8003 7664 1.06501 0.00700614 -0.00607152 1 0 1 1 0 0 +EDGE2 8004 7665 1.05978 0.0343976 -0.00504674 1 0 1 1 0 0 +EDGE2 8004 7684 -0.0890836 -0.0349331 0.0106776 1 0 1 1 0 0 +EDGE2 8004 8003 -0.948085 0.0256842 0.00928132 1 0 1 1 0 0 +EDGE2 8004 6363 -1.06555 -0.0580214 -0.00898348 1 0 1 1 0 0 +EDGE2 8004 7663 -1.05694 0.0310468 0.00628694 1 0 1 1 0 0 +EDGE2 8004 7683 -1.01829 0.0329592 -0.0221752 1 0 1 1 0 0 +EDGE2 8004 6364 0.0278218 -0.013291 -0.00364128 1 0 1 1 0 0 +EDGE2 8004 7664 -0.0485697 0.0634933 0.00542421 1 0 1 1 0 0 +EDGE2 8004 7685 0.983107 0.107808 -0.008646 1 0 1 1 0 0 +EDGE2 8004 6365 0.991477 0.0342773 -0.00275346 1 0 1 1 0 0 +EDGE2 8005 7665 -0.0806217 0.0539519 -0.00904252 1 0 1 1 0 0 +EDGE2 8005 7684 -0.977198 0.00591091 -0.0074708 1 0 1 1 0 0 +EDGE2 8005 8004 -1.04134 -0.0470644 -0.0136872 1 0 1 1 0 0 +EDGE2 8005 6364 -1.06057 -0.0439752 -0.0257429 1 0 1 1 0 0 +EDGE2 8005 7664 -0.980625 -0.0259995 0.0456925 1 0 1 1 0 0 +EDGE2 8005 7685 0.01455 0.00879169 0.00230361 1 0 1 1 0 0 +EDGE2 8005 6366 0.0447215 0.985952 1.54368 1 0 1 1 0 0 +EDGE2 8005 7686 -0.058958 0.968641 1.59123 1 0 1 1 0 0 +EDGE2 8005 6365 0.026716 -0.0691592 0.00577144 1 0 1 1 0 0 +EDGE2 8005 7666 0.0545476 0.909438 1.56393 1 0 1 1 0 0 +EDGE2 8006 7665 -1.04507 0.00150083 -1.55887 1 0 1 1 0 0 +EDGE2 8006 8005 -0.981053 0.00411178 -1.6024 1 0 1 1 0 0 +EDGE2 8006 7685 -0.959244 -0.0372334 -1.57605 1 0 1 1 0 0 +EDGE2 8006 6366 -0.0327169 0.048266 -0.0123009 1 0 1 1 0 0 +EDGE2 8006 7686 -0.022214 0.0199054 -0.0131403 1 0 1 1 0 0 +EDGE2 8006 6365 -0.88576 0.0178559 -1.58945 1 0 1 1 0 0 +EDGE2 8006 7666 0.000897113 -0.0570856 -0.00970336 1 0 1 1 0 0 +EDGE2 8006 7667 0.936487 0.0501963 -0.00820144 1 0 1 1 0 0 +EDGE2 8006 7687 1.00367 0.0555253 0.0137114 1 0 1 1 0 0 +EDGE2 8006 6367 0.992156 0.0195974 0.0201772 1 0 1 1 0 0 +EDGE2 8007 6366 -0.964581 0.0279473 0.0110787 1 0 1 1 0 0 +EDGE2 8007 7686 -1.03586 -0.0955757 0.0267529 1 0 1 1 0 0 +EDGE2 8007 8006 -0.987335 -0.0218126 0.0211407 1 0 1 1 0 0 +EDGE2 8007 7666 -0.989682 -0.0167293 -0.0143306 1 0 1 1 0 0 +EDGE2 8007 7667 0.0143105 0.0591506 0.0130429 1 0 1 1 0 0 +EDGE2 8007 7687 0.0469027 -0.0864207 0.034295 1 0 1 1 0 0 +EDGE2 8007 6367 0.0187412 -0.0417637 -0.00332724 1 0 1 1 0 0 +EDGE2 8007 7668 0.904306 0.103057 0.00359372 1 0 1 1 0 0 +EDGE2 8007 7688 1.00703 -0.0246579 -0.0174034 1 0 1 1 0 0 +EDGE2 8007 6368 0.981997 0.00180095 0.0232571 1 0 1 1 0 0 +EDGE2 8008 7667 -0.918215 0.0565282 -0.00279204 1 0 1 1 0 0 +EDGE2 8008 7687 -1.03588 0.014057 -0.0496059 1 0 1 1 0 0 +EDGE2 8008 8007 -0.940882 0.0236436 0.0081506 1 0 1 1 0 0 +EDGE2 8008 6367 -0.95073 0.000143895 0.0160517 1 0 1 1 0 0 +EDGE2 8008 7668 -0.0800137 0.0806524 -0.0142668 1 0 1 1 0 0 +EDGE2 8008 7688 0.0369242 -0.0483583 0.0214071 1 0 1 1 0 0 +EDGE2 8008 6368 0.0221481 -0.0670514 -0.0216076 1 0 1 1 0 0 +EDGE2 8008 7669 1.01164 0.00279631 -0.00429935 1 0 1 1 0 0 +EDGE2 8008 7689 1.09226 0.0183938 0.0205155 1 0 1 1 0 0 +EDGE2 8008 6369 0.917778 -0.0826949 -0.012888 1 0 1 1 0 0 +EDGE2 8009 8008 -0.929317 -0.0121571 -0.0165396 1 0 1 1 0 0 +EDGE2 8009 7668 -0.991515 -0.0435587 -0.00755787 1 0 1 1 0 0 +EDGE2 8009 7688 -0.900201 0.00965187 -0.0189921 1 0 1 1 0 0 +EDGE2 8009 6368 -1.04628 -0.0776108 0.0297212 1 0 1 1 0 0 +EDGE2 8009 7669 -0.0384895 -0.0732008 -0.0242585 1 0 1 1 0 0 +EDGE2 8009 7689 -0.014622 -0.00988011 -0.00681382 1 0 1 1 0 0 +EDGE2 8009 6369 0.0354058 0.00617091 -0.0223379 1 0 1 1 0 0 +EDGE2 8009 7690 1.00217 0.0471498 -0.0105416 1 0 1 1 0 0 +EDGE2 8009 6370 0.996309 0.0356181 0.00379552 1 0 1 1 0 0 +EDGE2 8009 7670 0.953989 0.0479517 -0.0177876 1 0 1 1 0 0 +EDGE2 8010 7691 0.0459062 -0.95331 -1.57632 1 0 1 1 0 0 +EDGE2 8010 7669 -0.988058 0.00850725 0.0177458 1 0 1 1 0 0 +EDGE2 8010 7689 -0.943594 0.00201895 0.00985289 1 0 1 1 0 0 +EDGE2 8010 8009 -0.970061 0.00388433 0.0380855 1 0 1 1 0 0 +EDGE2 8010 6369 -1.02445 0.0581751 0.000920258 1 0 1 1 0 0 +EDGE2 8010 6371 -0.0476177 1.01374 1.56986 1 0 1 1 0 0 +EDGE2 8010 7671 0.0237619 1.00116 1.56416 1 0 1 1 0 0 +EDGE2 8010 7690 -0.00469383 0.0465671 0.00343214 1 0 1 1 0 0 +EDGE2 8010 6370 0.0178242 -0.0544182 -0.00550525 1 0 1 1 0 0 +EDGE2 8010 7670 0.0531237 -0.0756904 0.0161453 1 0 1 1 0 0 +EDGE2 8011 7691 -0.0709643 0.0112706 -0.0285007 1 0 1 1 0 0 +EDGE2 8011 8010 -0.993219 0.047224 1.56408 1 0 1 1 0 0 +EDGE2 8011 7690 -0.99004 -0.00859269 1.60465 1 0 1 1 0 0 +EDGE2 8011 6370 -0.997131 -0.0378551 1.573 1 0 1 1 0 0 +EDGE2 8011 7670 -0.994055 0.0329469 1.56696 1 0 1 1 0 0 +EDGE2 8011 7692 0.99206 -0.120494 0.0191512 1 0 1 1 0 0 +EDGE2 8012 7691 -1.02611 0.0669668 0.00355723 1 0 1 1 0 0 +EDGE2 8012 8011 -1.00001 -0.000108434 -0.00540802 1 0 1 1 0 0 +EDGE2 8012 7692 -0.00136388 -0.11427 -0.0382923 1 0 1 1 0 0 +EDGE2 8012 7693 0.940126 0.027968 -0.0217302 1 0 1 1 0 0 +EDGE2 8013 7692 -1.01099 0.0427672 0.0160371 1 0 1 1 0 0 +EDGE2 8013 8012 -1.06246 0.0288041 0.0111472 1 0 1 1 0 0 +EDGE2 8013 7693 0.0569952 0.0522288 -0.0369245 1 0 1 1 0 0 +EDGE2 8013 7694 0.92919 -0.0398328 0.00428249 1 0 1 1 0 0 +EDGE2 8014 8013 -0.99504 0.0363154 0.0198293 1 0 1 1 0 0 +EDGE2 8014 7693 -1.00708 0.00946715 -0.000254413 1 0 1 1 0 0 +EDGE2 8014 7715 1.05868 -0.00683984 -3.1341 1 0 1 1 0 0 +EDGE2 8014 7694 -0.0281668 -0.0238007 0.00562984 1 0 1 1 0 0 +EDGE2 8014 7695 0.972421 -0.0149474 0.00685513 1 0 1 1 0 0 +EDGE2 8015 7716 -0.0761519 -1.01323 -1.5609 1 0 1 1 0 0 +EDGE2 8015 7696 -0.00703447 -1.06555 -1.55055 1 0 1 1 0 0 +EDGE2 8015 7715 0.0260842 -0.00966955 -3.14313 1 0 1 1 0 0 +EDGE2 8015 7694 -0.957443 0.0210435 0.00522529 1 0 1 1 0 0 +EDGE2 8015 8014 -0.948828 0.0184162 -0.0145521 1 0 1 1 0 0 +EDGE2 8015 7695 0.00193437 0.0254484 0.0110963 1 0 1 1 0 0 +EDGE2 8015 7714 0.973704 -0.0355531 -3.17728 1 0 1 1 0 0 +EDGE2 8016 7715 -1.05197 -0.0789734 1.58117 1 0 1 1 0 0 +EDGE2 8016 8015 -0.963828 0.0191885 -1.56617 1 0 1 1 0 0 +EDGE2 8016 7695 -1.01014 0.0479543 -1.57928 1 0 1 1 0 0 +EDGE2 8017 8016 -1.05473 -0.0619223 -0.018912 1 0 1 1 0 0 +EDGE2 8018 8017 -0.995357 0.0673293 0.0130838 1 0 1 1 0 0 +EDGE2 8019 6460 0.983109 -0.0364375 -3.13062 1 0 1 1 0 0 +EDGE2 8019 8018 -0.940582 0.00698694 0.0238933 1 0 1 1 0 0 +EDGE2 8019 6440 0.940989 0.0287962 -3.1315 1 0 1 1 0 0 +EDGE2 8019 6420 1.06491 -0.0179557 -3.16144 1 0 1 1 0 0 +EDGE2 8020 6460 0.0770644 0.00181794 -3.17004 1 0 1 1 0 0 +EDGE2 8020 8019 -1.00731 -0.101084 0.0251148 1 0 1 1 0 0 +EDGE2 8020 6461 0.0191836 -0.970192 -1.59219 1 0 1 1 0 0 +EDGE2 8020 6440 0.00694606 -0.0313208 -3.11794 1 0 1 1 0 0 +EDGE2 8020 6420 0.00513981 0.0104434 -3.1128 1 0 1 1 0 0 +EDGE2 8020 6421 0.0350864 -1.00484 -1.56617 1 0 1 1 0 0 +EDGE2 8020 6441 0.0235534 -1.052 -1.5978 1 0 1 1 0 0 +EDGE2 8020 6459 1.00692 0.101604 -3.15381 1 0 1 1 0 0 +EDGE2 8020 6419 0.955446 -0.0245672 -3.14852 1 0 1 1 0 0 +EDGE2 8020 6439 0.950322 0.0510958 -3.15471 1 0 1 1 0 0 +EDGE2 8021 6460 -1.05512 -0.00271352 1.5582 1 0 1 1 0 0 +EDGE2 8021 8020 -1.06881 -0.0557021 -1.57419 1 0 1 1 0 0 +EDGE2 8021 6440 -1.00004 -0.0562862 1.56358 1 0 1 1 0 0 +EDGE2 8021 6420 -0.92609 0.037107 1.56924 1 0 1 1 0 0 +EDGE2 8022 8021 -1.01674 0.0340929 -0.0225367 1 0 1 1 0 0 +EDGE2 8023 8022 -1.02965 -0.0198245 -0.00931661 1 0 1 1 0 0 +EDGE2 8024 6385 1.01459 0.0654946 -3.12043 1 0 1 1 0 0 +EDGE2 8024 8023 -0.990178 -0.0363448 -0.0241504 1 0 1 1 0 0 +EDGE2 8025 6385 -0.0224716 -0.0135788 -3.12683 1 0 1 1 0 0 +EDGE2 8025 6384 1.0752 -0.0474806 -3.17575 1 0 1 1 0 0 +EDGE2 8025 6386 0.0646203 -0.964293 -1.57511 1 0 1 1 0 0 +EDGE2 8025 8024 -1.08051 -0.0323606 0.0115142 1 0 1 1 0 0 +EDGE2 8026 6385 -1.02204 0.00100031 1.57581 1 0 1 1 0 0 +EDGE2 8026 8025 -0.920263 -0.0307882 -1.57959 1 0 1 1 0 0 +EDGE2 8027 8026 -1.00567 -0.0556055 0.00808194 1 0 1 1 0 0 +EDGE2 8028 8027 -1.08426 -0.00330118 0.00607383 1 0 1 1 0 0 +EDGE2 8029 8010 1.0613 -0.012041 -3.0978 1 0 1 1 0 0 +EDGE2 8029 7690 1.08562 -0.0544714 -3.21064 1 0 1 1 0 0 +EDGE2 8029 6370 0.952022 0.000927486 -3.16459 1 0 1 1 0 0 +EDGE2 8029 7670 0.958361 0.015635 -3.1377 1 0 1 1 0 0 +EDGE2 8029 8028 -0.931152 -0.061198 0.0160875 1 0 1 1 0 0 +EDGE2 8030 7691 0.0172473 0.969154 1.59862 1 0 1 1 0 0 +EDGE2 8030 8010 -0.0975632 0.0230537 -3.13929 1 0 1 1 0 0 +EDGE2 8030 7669 0.994782 0.0697981 -3.1337 1 0 1 1 0 0 +EDGE2 8030 7689 1.03504 0.0445995 -3.15777 1 0 1 1 0 0 +EDGE2 8030 8009 0.902439 -0.0425876 -3.15461 1 0 1 1 0 0 +EDGE2 8030 6369 0.955287 -0.00130488 -3.11618 1 0 1 1 0 0 +EDGE2 8030 6371 -0.090754 -1.08843 -1.58698 1 0 1 1 0 0 +EDGE2 8030 7671 0.0329184 -0.944542 -1.5645 1 0 1 1 0 0 +EDGE2 8030 7690 -0.0500056 0.096903 -3.14737 1 0 1 1 0 0 +EDGE2 8030 6370 0.00114115 -0.0418674 -3.14996 1 0 1 1 0 0 +EDGE2 8030 7670 0.000275416 0.0879539 -3.14969 1 0 1 1 0 0 +EDGE2 8030 8011 0.0836903 0.99773 1.5584 1 0 1 1 0 0 +EDGE2 8030 8029 -0.983714 0.005356 0.0312055 1 0 1 1 0 0 +EDGE2 8031 7691 0.0566389 0.0513334 -0.0290067 1 0 1 1 0 0 +EDGE2 8031 8010 -0.961589 -0.0451969 1.55632 1 0 1 1 0 0 +EDGE2 8031 8030 -0.90378 -0.00391036 -1.58808 1 0 1 1 0 0 +EDGE2 8031 7690 -1.01507 -0.00313988 1.60438 1 0 1 1 0 0 +EDGE2 8031 6370 -1.01711 -0.0426161 1.54138 1 0 1 1 0 0 +EDGE2 8031 7670 -1.05054 -0.0379413 1.56569 1 0 1 1 0 0 +EDGE2 8031 8011 0.0703477 0.0994479 -0.0240011 1 0 1 1 0 0 +EDGE2 8031 7692 0.992955 0.014539 0.00245236 1 0 1 1 0 0 +EDGE2 8031 8012 0.956066 -0.045733 0.0187739 1 0 1 1 0 0 +EDGE2 8032 7691 -1.07662 0.0468191 -0.0244001 1 0 1 1 0 0 +EDGE2 8032 8031 -0.989705 -0.0184992 -0.0105005 1 0 1 1 0 0 +EDGE2 8032 8011 -1.02343 0.0101817 0.00195708 1 0 1 1 0 0 +EDGE2 8032 8013 0.912424 0.0379568 -0.00285019 1 0 1 1 0 0 +EDGE2 8032 7692 0.0211728 -0.0207869 -0.00991654 1 0 1 1 0 0 +EDGE2 8032 8012 -0.0210767 -0.0286757 0.0261671 1 0 1 1 0 0 +EDGE2 8032 7693 0.990068 0.068728 0.0295653 1 0 1 1 0 0 +EDGE2 8033 8013 0.0183734 -0.0684988 0.00880613 1 0 1 1 0 0 +EDGE2 8033 7692 -0.972917 0.0457905 -0.0178282 1 0 1 1 0 0 +EDGE2 8033 8012 -0.92818 0.0663515 0.00326129 1 0 1 1 0 0 +EDGE2 8033 8032 -1.08655 0.0431431 -0.0282659 1 0 1 1 0 0 +EDGE2 8033 7693 -0.0625442 0.107035 0.000520447 1 0 1 1 0 0 +EDGE2 8033 7694 1.0483 -0.046553 -0.00490896 1 0 1 1 0 0 +EDGE2 8033 8014 0.902594 -0.0992718 -0.011163 1 0 1 1 0 0 +EDGE2 8034 8013 -0.915688 0.00829183 -0.0161782 1 0 1 1 0 0 +EDGE2 8034 8033 -0.994934 -0.00909549 -0.0203748 1 0 1 1 0 0 +EDGE2 8034 7693 -0.965387 -0.0358471 -0.0147921 1 0 1 1 0 0 +EDGE2 8034 7715 0.935418 0.0224028 -3.14536 1 0 1 1 0 0 +EDGE2 8034 7694 -0.0329004 -0.0702676 0.0278591 1 0 1 1 0 0 +EDGE2 8034 8014 0.0126527 -0.0229225 0.00594579 1 0 1 1 0 0 +EDGE2 8034 8015 0.980994 0.0275472 0.0181493 1 0 1 1 0 0 +EDGE2 8034 7695 1.02492 -0.013917 -0.0103504 1 0 1 1 0 0 +EDGE2 8035 7716 0.0940919 -1.11355 -1.57176 1 0 1 1 0 0 +EDGE2 8035 7696 0.0582091 -0.988134 -1.58727 1 0 1 1 0 0 +EDGE2 8035 8034 -0.971025 0.009234 0.00348534 1 0 1 1 0 0 +EDGE2 8035 7715 -0.0203541 -0.0860744 -3.12566 1 0 1 1 0 0 +EDGE2 8035 7694 -0.989305 -0.0761395 -0.0129011 1 0 1 1 0 0 +EDGE2 8035 8014 -1.07497 0.000239929 0.0400998 1 0 1 1 0 0 +EDGE2 8035 8015 0.151343 -0.0364523 -0.00176882 1 0 1 1 0 0 +EDGE2 8035 8016 0.074149 0.934477 1.58009 1 0 1 1 0 0 +EDGE2 8035 7695 -0.0181462 -0.0738238 0.00564014 1 0 1 1 0 0 +EDGE2 8035 7714 1.04104 0.0976615 -3.16763 1 0 1 1 0 0 +EDGE2 8036 7717 1.05642 0.0105425 0.0485276 1 0 1 1 0 0 +EDGE2 8036 7716 0.0565147 0.0278718 -0.0141911 1 0 1 1 0 0 +EDGE2 8036 7697 1.01202 0.00877927 -0.000543032 1 0 1 1 0 0 +EDGE2 8036 7696 0.102239 -0.0120967 0.00549643 1 0 1 1 0 0 +EDGE2 8036 7715 -1.05042 0.00414036 -1.55672 1 0 1 1 0 0 +EDGE2 8036 8035 -1.01206 -0.0347257 1.57799 1 0 1 1 0 0 +EDGE2 8036 8015 -0.983873 -0.00859645 1.57246 1 0 1 1 0 0 +EDGE2 8036 7695 -0.953052 0.0440938 1.60254 1 0 1 1 0 0 +EDGE2 8037 7717 0.0374034 0.00501476 -0.0203263 1 0 1 1 0 0 +EDGE2 8037 7698 0.941389 0.0320293 -0.00101598 1 0 1 1 0 0 +EDGE2 8037 7718 1.03707 -0.0277437 -0.0202528 1 0 1 1 0 0 +EDGE2 8037 7716 -0.969496 0.0573349 -0.00267791 1 0 1 1 0 0 +EDGE2 8037 8036 -0.976055 -0.0594668 -0.0288813 1 0 1 1 0 0 +EDGE2 8037 7697 0.0443538 0.0118686 -0.036403 1 0 1 1 0 0 +EDGE2 8037 7696 -0.940714 0.0694939 -0.023333 1 0 1 1 0 0 +EDGE2 8038 7717 -0.929445 -0.0491922 -0.0166331 1 0 1 1 0 0 +EDGE2 8038 7699 0.974162 0.0662217 0.0313938 1 0 1 1 0 0 +EDGE2 8038 7719 0.958778 -0.0290383 0.00199833 1 0 1 1 0 0 +EDGE2 8038 7698 -0.00619501 0.0815425 0.0180918 1 0 1 1 0 0 +EDGE2 8038 7718 -0.0066027 0.00337751 -0.00358692 1 0 1 1 0 0 +EDGE2 8038 8037 -1.02585 -0.00552929 0.000293994 1 0 1 1 0 0 +EDGE2 8038 7697 -0.985115 -0.0692767 0.00311034 1 0 1 1 0 0 +EDGE2 8039 7699 0.106675 -0.0432521 -0.0121195 1 0 1 1 0 0 +EDGE2 8039 7719 0.0326314 0.000154673 -0.0157513 1 0 1 1 0 0 +EDGE2 8039 7700 1.00716 0.103314 -0.0398154 1 0 1 1 0 0 +EDGE2 8039 7720 0.875557 -0.00784367 0.00278943 1 0 1 1 0 0 +EDGE2 8039 7698 -1.0039 -0.00409199 -0.0144066 1 0 1 1 0 0 +EDGE2 8039 7718 -1.05802 -0.0259807 -0.0242141 1 0 1 1 0 0 +EDGE2 8039 8038 -0.984595 -0.00618337 -0.00656442 1 0 1 1 0 0 +EDGE2 8040 7699 -1.11812 0.0204601 -0.000137178 1 0 1 1 0 0 +EDGE2 8040 7719 -0.900013 -0.0248021 0.00591669 1 0 1 1 0 0 +EDGE2 8040 7700 0.00258981 -0.01523 0.0057653 1 0 1 1 0 0 +EDGE2 8040 7720 0.0197826 -0.0973419 0.0358732 1 0 1 1 0 0 +EDGE2 8040 8039 -1.00967 -0.0381178 0.0294294 1 0 1 1 0 0 +EDGE2 8040 7701 -0.041374 1.01694 1.56476 1 0 1 1 0 0 +EDGE2 8040 7721 0.0451953 1.0674 1.55128 1 0 1 1 0 0 +EDGE2 8041 7700 -1.02888 -0.0290088 -1.58701 1 0 1 1 0 0 +EDGE2 8041 7720 -1.09769 0.0460167 -1.58354 1 0 1 1 0 0 +EDGE2 8041 8040 -0.891266 -0.0172381 -1.5598 1 0 1 1 0 0 +EDGE2 8041 7722 1.03689 0.0266095 0.00198869 1 0 1 1 0 0 +EDGE2 8041 7701 -0.0224956 -0.0146872 -0.010256 1 0 1 1 0 0 +EDGE2 8041 7721 0.0119723 0.0369996 -0.00173001 1 0 1 1 0 0 +EDGE2 8041 7702 0.93991 0.0387004 0.0129863 1 0 1 1 0 0 +EDGE2 8042 7722 -0.0641524 0.0755131 -0.0184556 1 0 1 1 0 0 +EDGE2 8042 7701 -1.00754 0.0850753 -0.00882911 1 0 1 1 0 0 +EDGE2 8042 7721 -0.930814 0.00555828 0.0160751 1 0 1 1 0 0 +EDGE2 8042 8041 -0.980559 0.0281997 -0.00234605 1 0 1 1 0 0 +EDGE2 8042 7723 0.961982 -0.0501654 -0.0340165 1 0 1 1 0 0 +EDGE2 8042 7702 0.052808 -0.054349 0.0117862 1 0 1 1 0 0 +EDGE2 8042 7703 1.00899 0.00663069 0.00900631 1 0 1 1 0 0 +EDGE2 8043 7722 -0.918652 0.0422514 0.0247204 1 0 1 1 0 0 +EDGE2 8043 8042 -1.04267 -0.0103375 0.0283456 1 0 1 1 0 0 +EDGE2 8043 7724 1.00612 0.0234937 0.0284286 1 0 1 1 0 0 +EDGE2 8043 7723 -0.00134919 -0.0170113 0.00946427 1 0 1 1 0 0 +EDGE2 8043 7702 -0.991729 0.0600538 -0.00769658 1 0 1 1 0 0 +EDGE2 8043 7703 -0.00595207 0.0202115 -0.000659036 1 0 1 1 0 0 +EDGE2 8043 7704 1.02423 0.0159345 -0.00863704 1 0 1 1 0 0 +EDGE2 8044 7724 -0.0270962 0.0628005 -0.0149583 1 0 1 1 0 0 +EDGE2 8044 7723 -0.995745 0.0513366 -0.022866 1 0 1 1 0 0 +EDGE2 8044 8043 -0.984253 -0.0549427 -0.0282861 1 0 1 1 0 0 +EDGE2 8044 7703 -0.985798 -0.0998413 0.0277224 1 0 1 1 0 0 +EDGE2 8044 7725 0.984351 -0.0163748 0.0110779 1 0 1 1 0 0 +EDGE2 8044 7704 -0.0782721 0.0339356 -0.00294341 1 0 1 1 0 0 +EDGE2 8044 7705 1.00277 -0.0365889 -0.00572368 1 0 1 1 0 0 +EDGE2 8045 7726 -0.0177469 -0.960071 -1.5943 1 0 1 1 0 0 +EDGE2 8045 7724 -1.11509 0.0443895 -0.0196554 1 0 1 1 0 0 +EDGE2 8045 8044 -0.999855 0.0066746 -0.00266591 1 0 1 1 0 0 +EDGE2 8045 7725 -0.00361668 0.00117396 -0.00235218 1 0 1 1 0 0 +EDGE2 8045 7704 -1.16857 -0.0923863 0.00351332 1 0 1 1 0 0 +EDGE2 8045 7705 0.00277118 -0.0674371 -0.0200828 1 0 1 1 0 0 +EDGE2 8045 7706 0.0662821 0.975125 1.59463 1 0 1 1 0 0 +EDGE2 8046 7725 -1.05543 -0.02662 -1.58191 1 0 1 1 0 0 +EDGE2 8046 8045 -0.977247 0.0101138 -1.56846 1 0 1 1 0 0 +EDGE2 8046 7705 -1.08215 0.0418292 -1.5949 1 0 1 1 0 0 +EDGE2 8046 7706 0.0305933 -0.0331305 0.00676048 1 0 1 1 0 0 +EDGE2 8046 7707 0.969057 0.0763332 -0.0246708 1 0 1 1 0 0 +EDGE2 8047 8046 -0.947161 0.0480451 -0.0112988 1 0 1 1 0 0 +EDGE2 8047 7706 -0.983445 -0.0816867 0.015071 1 0 1 1 0 0 +EDGE2 8047 7707 0.00661869 -0.00291549 0.0235704 1 0 1 1 0 0 +EDGE2 8047 7708 1.10466 0.0911022 -0.0110911 1 0 1 1 0 0 +EDGE2 8048 8047 -1.03828 -0.00809906 0.000749269 1 0 1 1 0 0 +EDGE2 8048 7707 -0.959658 0.0196645 0.000548849 1 0 1 1 0 0 +EDGE2 8048 7708 -0.105644 -0.0371646 -0.0427326 1 0 1 1 0 0 +EDGE2 8048 7709 0.960706 -0.0803025 -0.0463639 1 0 1 1 0 0 +EDGE2 8049 7708 -1.04983 0.0703248 0.0243387 1 0 1 1 0 0 +EDGE2 8049 8048 -0.954759 -0.0714291 0.00268885 1 0 1 1 0 0 +EDGE2 8049 7709 -0.00550146 0.0154489 0.0247941 1 0 1 1 0 0 +EDGE2 8049 7710 1.0048 -0.0626145 0.010436 1 0 1 1 0 0 +EDGE2 8050 8049 -1.07051 -0.0287956 -0.0145045 1 0 1 1 0 0 +EDGE2 8050 7709 -0.979371 -0.043811 -0.0160197 1 0 1 1 0 0 +EDGE2 8050 7710 0.0235282 0.0303688 0.00261751 1 0 1 1 0 0 +EDGE2 8050 7711 -0.0168019 0.92667 1.59752 1 0 1 1 0 0 +EDGE2 8051 7710 -1.09451 -0.0406403 1.5974 1 0 1 1 0 0 +EDGE2 8051 8050 -0.996429 -0.000939058 1.59975 1 0 1 1 0 0 +EDGE2 8052 8051 -1.0596 -0.0738648 -0.00478566 1 0 1 1 0 0 +EDGE2 8053 8052 -0.940834 -0.042316 -0.0324118 1 0 1 1 0 0 +EDGE2 8054 8053 -1.01818 -0.00543487 0.0153247 1 0 1 1 0 0 +EDGE2 8055 8054 -1.01298 0.0148396 0.0297748 1 0 1 1 0 0 +EDGE2 8056 8055 -1.00861 -0.0141718 1.56057 1 0 1 1 0 0 +EDGE2 8057 8056 -1.00042 -0.0148598 -0.0245793 1 0 1 1 0 0 +EDGE2 8058 8057 -1.04824 0.0735158 0.0101188 1 0 1 1 0 0 +EDGE2 8059 8058 -0.980863 0.0097301 0.00483767 1 0 1 1 0 0 +EDGE2 8060 8059 -0.983158 -0.0556283 -3.83322e-05 1 0 1 1 0 0 +EDGE2 8061 8060 -0.996617 -0.0133093 -1.56182 1 0 1 1 0 0 +EDGE2 8062 8061 -0.950803 0.0898241 -0.024565 1 0 1 1 0 0 +EDGE2 8063 8062 -1.06525 -0.0128265 0.0153357 1 0 1 1 0 0 +EDGE2 8064 8063 -1.01859 0.0308765 -0.0301201 1 0 1 1 0 0 +EDGE2 8064 6605 1.14324 -0.0204338 -3.12934 1 0 1 1 0 0 +EDGE2 8065 8064 -0.929735 -0.0932641 -0.00344696 1 0 1 1 0 0 +EDGE2 8065 6606 0.0161324 -1.01161 -1.55836 1 0 1 1 0 0 +EDGE2 8065 6605 0.0774731 -0.0346245 -3.13901 1 0 1 1 0 0 +EDGE2 8065 6604 0.989298 -0.0632114 -3.17227 1 0 1 1 0 0 +EDGE2 8066 6605 -0.974805 0.0243283 1.56522 1 0 1 1 0 0 +EDGE2 8066 8065 -1.01737 -0.0578707 -1.56107 1 0 1 1 0 0 +EDGE2 8067 8066 -0.980424 -0.0307662 0.0324148 1 0 1 1 0 0 +EDGE2 8068 8067 -0.899212 -0.0543025 0.0191105 1 0 1 1 0 0 +EDGE2 8069 8068 -1.0053 -0.0116186 -0.0287302 1 0 1 1 0 0 +EDGE2 8069 6530 1.0376 -0.0958687 -3.12348 1 0 1 1 0 0 +EDGE2 8069 6670 0.985834 0.0516335 -3.14258 1 0 1 1 0 0 +EDGE2 8070 8069 -1.08265 0.0385365 -0.0113541 1 0 1 1 0 0 +EDGE2 8070 6529 0.901012 -0.00527766 -3.12277 1 0 1 1 0 0 +EDGE2 8070 6669 1.03787 0.00548381 -3.13596 1 0 1 1 0 0 +EDGE2 8070 6530 -0.0189696 0.0471138 -3.10541 1 0 1 1 0 0 +EDGE2 8070 6670 -0.0447928 -0.0014759 -3.16918 1 0 1 1 0 0 +EDGE2 8070 6531 -0.0638332 -1.02476 -1.59701 1 0 1 1 0 0 +EDGE2 8070 6671 -0.0534382 -0.992411 -1.55725 1 0 1 1 0 0 +EDGE2 8071 8070 -0.90848 0.024262 -1.57709 1 0 1 1 0 0 +EDGE2 8071 6530 -0.965754 0.0640063 1.54968 1 0 1 1 0 0 +EDGE2 8071 6670 -0.917982 -0.0243969 1.53704 1 0 1 1 0 0 +EDGE2 8072 8071 -0.968355 0.027351 0.032341 1 0 1 1 0 0 +EDGE2 8073 8072 -0.943901 -0.0877849 -0.00538672 1 0 1 1 0 0 +EDGE2 8074 8055 0.998207 0.016593 -3.13485 1 0 1 1 0 0 +EDGE2 8074 8073 -0.969641 -0.00255919 -0.0303923 1 0 1 1 0 0 +EDGE2 8075 8055 -0.0281388 -0.0975018 -3.11957 1 0 1 1 0 0 +EDGE2 8075 8056 0.0610442 0.974581 1.58583 1 0 1 1 0 0 +EDGE2 8075 8054 1.03749 -0.036061 -3.14633 1 0 1 1 0 0 +EDGE2 8075 8074 -1.10432 -0.0364576 0.00211627 1 0 1 1 0 0 +EDGE2 8076 8055 -1.03344 -0.0179257 -1.57245 1 0 1 1 0 0 +EDGE2 8076 8075 -1.01934 -0.0840168 1.54465 1 0 1 1 0 0 +EDGE2 8077 8076 -0.962187 0.0244605 0.0285047 1 0 1 1 0 0 +EDGE2 8078 8077 -0.9546 -0.000616505 -0.0153679 1 0 1 1 0 0 +EDGE2 8079 6520 1.02595 0.122295 -3.14549 1 0 1 1 0 0 +EDGE2 8079 8078 -0.924171 0.00622517 -0.0194511 1 0 1 1 0 0 +EDGE2 8080 6520 -0.0306964 -0.00720928 -3.13219 1 0 1 1 0 0 +EDGE2 8080 8079 -1.02044 -0.0564299 0.00684934 1 0 1 1 0 0 +EDGE2 8080 6519 1.01356 0.00744113 -3.13104 1 0 1 1 0 0 +EDGE2 8080 6521 0.0279359 -1.03296 -1.55795 1 0 1 1 0 0 +EDGE2 8081 6520 -1.01578 0.00700516 -1.54982 1 0 1 1 0 0 +EDGE2 8081 8080 -0.97554 0.0525612 1.54077 1 0 1 1 0 0 +EDGE2 8081 6521 0.0354028 -0.0392579 0.0339609 1 0 1 1 0 0 +EDGE2 8081 6522 0.971136 0.00557266 -0.020067 1 0 1 1 0 0 +EDGE2 8082 6521 -1.05276 -0.0344058 -0.00477251 1 0 1 1 0 0 +EDGE2 8082 8081 -0.992244 -0.00787787 0.0136271 1 0 1 1 0 0 +EDGE2 8082 6522 -0.0263594 -0.00590971 -0.00917901 1 0 1 1 0 0 +EDGE2 8082 6523 1.00967 -0.0226518 -0.00797839 1 0 1 1 0 0 +EDGE2 8083 8082 -1.01452 0.0627059 -0.0304712 1 0 1 1 0 0 +EDGE2 8083 6522 -0.94411 0.0311484 0.0031434 1 0 1 1 0 0 +EDGE2 8083 6524 1.1088 0.0169157 0.00723465 1 0 1 1 0 0 +EDGE2 8083 6523 0.0724737 0.119036 -0.0181532 1 0 1 1 0 0 +EDGE2 8084 8083 -1.01098 0.0161587 -0.0113408 1 0 1 1 0 0 +EDGE2 8084 6524 -0.0892911 0.0699233 0.0167364 1 0 1 1 0 0 +EDGE2 8084 6523 -1.01158 -0.0451246 -0.010735 1 0 1 1 0 0 +EDGE2 8084 6525 0.991627 -0.0502232 0.0226439 1 0 1 1 0 0 +EDGE2 8084 6665 0.959565 -0.0291027 -3.12394 1 0 1 1 0 0 +EDGE2 8085 6666 0.000734005 -1.07762 -1.58113 1 0 1 1 0 0 +EDGE2 8085 6526 0.0600606 -1.11611 -1.56988 1 0 1 1 0 0 +EDGE2 8085 6524 -1.04531 0.0572903 0.00323579 1 0 1 1 0 0 +EDGE2 8085 8084 -1.05352 -0.0497426 0.00116394 1 0 1 1 0 0 +EDGE2 8085 6525 -0.0312085 0.0537541 -0.0163878 1 0 1 1 0 0 +EDGE2 8085 6665 -0.101985 0.0584296 -3.13788 1 0 1 1 0 0 +EDGE2 8085 6664 1.05465 0.0574258 -3.12006 1 0 1 1 0 0 +EDGE2 8086 8085 -1.01309 -0.0671949 -1.5105 1 0 1 1 0 0 +EDGE2 8086 6525 -1.02217 -0.0170228 -1.54305 1 0 1 1 0 0 +EDGE2 8086 6665 -1.04668 -0.0398469 1.56058 1 0 1 1 0 0 +EDGE2 8087 8086 -0.981098 0.00261995 0.0188771 1 0 1 1 0 0 +EDGE2 8088 8087 -0.936991 0.0543339 -0.0245479 1 0 1 1 0 0 +EDGE2 8089 8088 -1.02399 -0.0343852 -0.0266112 1 0 1 1 0 0 +EDGE2 8090 8089 -0.864989 -0.0470425 -0.0192481 1 0 1 1 0 0 +EDGE2 8091 8090 -1.02464 -0.0262449 -1.58001 1 0 1 1 0 0 +EDGE2 8092 8091 -1.04065 0.0685931 -0.0154147 1 0 1 1 0 0 +EDGE2 8093 8092 -1.09934 -0.0277239 -0.017614 1 0 1 1 0 0 +EDGE2 8094 6495 1.03727 0.0528413 -3.1373 1 0 1 1 0 0 +EDGE2 8094 6515 0.990218 -0.0770423 -3.16774 1 0 1 1 0 0 +EDGE2 8094 6475 0.989435 0.00905286 -3.15053 1 0 1 1 0 0 +EDGE2 8094 8093 -1.00392 -0.0557674 -0.037303 1 0 1 1 0 0 +EDGE2 8095 6516 0.0384304 1.09499 1.5908 1 0 1 1 0 0 +EDGE2 8095 6474 0.991272 0.0165542 -3.14605 1 0 1 1 0 0 +EDGE2 8095 6514 1.04933 -0.0266108 -3.15453 1 0 1 1 0 0 +EDGE2 8095 6494 0.942165 0.0106052 -3.15596 1 0 1 1 0 0 +EDGE2 8095 8094 -1.10658 -0.0977601 -0.0311885 1 0 1 1 0 0 +EDGE2 8095 6495 0.00115099 0.0595171 -3.12607 1 0 1 1 0 0 +EDGE2 8095 6515 0.0360514 0.058835 -3.12896 1 0 1 1 0 0 +EDGE2 8095 6475 0.0692094 -0.014875 -3.16777 1 0 1 1 0 0 +EDGE2 8095 6476 0.029781 -1.06239 -1.57118 1 0 1 1 0 0 +EDGE2 8095 6496 0.0339615 -0.934108 -1.55125 1 0 1 1 0 0 +EDGE2 8096 6495 -1.01877 -0.054732 -1.58333 1 0 1 1 0 0 +EDGE2 8096 6515 -1.05748 0.0275947 -1.56511 1 0 1 1 0 0 +EDGE2 8096 8095 -0.999466 -0.0198058 1.57388 1 0 1 1 0 0 +EDGE2 8096 6475 -1.02429 -0.0271789 -1.59919 1 0 1 1 0 0 +EDGE2 8096 6497 1.02683 -0.0147644 0.0153359 1 0 1 1 0 0 +EDGE2 8096 6476 -0.0540297 0.0441826 -0.00917079 1 0 1 1 0 0 +EDGE2 8096 6496 -0.0136764 -0.00708775 -0.0157976 1 0 1 1 0 0 +EDGE2 8096 6477 1.0858 0.0123968 0.0244029 1 0 1 1 0 0 +EDGE2 8097 6478 1.02091 -0.0476449 -0.00354776 1 0 1 1 0 0 +EDGE2 8097 6497 0.0259142 -0.0078098 -0.0117569 1 0 1 1 0 0 +EDGE2 8097 6476 -0.986174 0.0168337 0.00644602 1 0 1 1 0 0 +EDGE2 8097 6496 -1.05107 0.0124524 -0.0364669 1 0 1 1 0 0 +EDGE2 8097 8096 -0.957329 0.03961 0.0430858 1 0 1 1 0 0 +EDGE2 8097 6498 0.96052 -0.0225963 0.0283229 1 0 1 1 0 0 +EDGE2 8097 6477 0.0214917 0.00423996 -0.0377745 1 0 1 1 0 0 +EDGE2 8098 6478 0.013803 0.0914108 0.00571943 1 0 1 1 0 0 +EDGE2 8098 6497 -0.982736 -0.0126659 -0.00892226 1 0 1 1 0 0 +EDGE2 8098 8097 -0.945676 -0.00848902 -0.0127945 1 0 1 1 0 0 +EDGE2 8098 6498 -0.000959173 -0.0132122 -0.0139805 1 0 1 1 0 0 +EDGE2 8098 6477 -1.00356 -0.00425884 -0.0083119 1 0 1 1 0 0 +EDGE2 8098 6479 1.04497 0.0429625 -0.00474654 1 0 1 1 0 0 +EDGE2 8098 6499 0.998057 -0.0200443 -0.0221056 1 0 1 1 0 0 +EDGE2 8099 6478 -1.00498 0.060776 0.0316745 1 0 1 1 0 0 +EDGE2 8099 6498 -1.04493 -0.0156664 -0.0205441 1 0 1 1 0 0 +EDGE2 8099 8098 -0.944824 0.00657183 0.0279232 1 0 1 1 0 0 +EDGE2 8099 6479 -0.0702061 -0.0226804 -0.0177904 1 0 1 1 0 0 +EDGE2 8099 6499 0.0538556 -0.0282186 0.0103287 1 0 1 1 0 0 +EDGE2 8099 6480 0.994929 -0.0171268 -0.00599374 1 0 1 1 0 0 +EDGE2 8099 6500 1.04393 0.00320715 -0.010422 1 0 1 1 0 0 +EDGE2 8100 8099 -1.09196 -0.0738427 -0.00937679 1 0 1 1 0 0 +EDGE2 8100 6479 -0.973623 0.0435793 0.0342653 1 0 1 1 0 0 +EDGE2 8100 6499 -0.966081 -0.0698058 -0.00730638 1 0 1 1 0 0 +EDGE2 8100 6480 -0.00182611 -0.0132322 -0.00207515 1 0 1 1 0 0 +EDGE2 8100 6501 -0.0461493 1.02031 1.57317 1 0 1 1 0 0 +EDGE2 8100 6481 0.00905571 1.04338 1.60092 1 0 1 1 0 0 +EDGE2 8100 6500 -0.0160817 0.0473525 0.0382401 1 0 1 1 0 0 +EDGE2 8101 6480 -0.959155 -0.0585568 1.57493 1 0 1 1 0 0 +EDGE2 8101 8100 -0.956328 -0.0207646 1.56584 1 0 1 1 0 0 +EDGE2 8101 6500 -0.904097 0.0158171 1.55571 1 0 1 1 0 0 +EDGE2 8102 8101 -1.01732 0.0761737 0.00745055 1 0 1 1 0 0 +EDGE2 8103 8102 -0.952502 -0.0335665 0.00189129 1 0 1 1 0 0 +EDGE2 8104 8103 -0.932411 0.020957 0.00960426 1 0 1 1 0 0 +EDGE2 8105 8104 -0.924794 0.00900871 0.0167936 1 0 1 1 0 0 +EDGE2 8106 8105 -1.03912 0.007076 1.53672 1 0 1 1 0 0 +EDGE2 8107 8106 -0.962625 -0.00474052 0.0390225 1 0 1 1 0 0 +EDGE2 8108 8107 -0.985243 0.0316242 0.00943491 1 0 1 1 0 0 +EDGE2 8109 8090 1.04635 -0.0288676 -3.13446 1 0 1 1 0 0 +EDGE2 8109 8108 -1.07019 0.0293508 -0.0352289 1 0 1 1 0 0 +EDGE2 8110 8091 -0.0161716 -0.989445 -1.58766 1 0 1 1 0 0 +EDGE2 8110 8089 0.938172 -0.00829109 -3.15281 1 0 1 1 0 0 +EDGE2 8110 8090 -0.0480605 -0.00642014 -3.17195 1 0 1 1 0 0 +EDGE2 8110 8109 -0.993536 -0.0660013 0.00710509 1 0 1 1 0 0 +EDGE2 8111 8090 -1.04391 -0.0139114 1.59546 1 0 1 1 0 0 +EDGE2 8111 8110 -0.994447 0.0245514 -1.59746 1 0 1 1 0 0 +EDGE2 8112 8111 -1.03728 -0.0536202 0.00835514 1 0 1 1 0 0 +EDGE2 8113 8112 -1.00062 -0.0337125 -0.00658713 1 0 1 1 0 0 +EDGE2 8114 8113 -1.03713 -0.0668955 0.0106971 1 0 1 1 0 0 +EDGE2 8115 8114 -0.976242 -0.000719311 -0.0295924 1 0 1 1 0 0 +EDGE2 8116 8115 -1.06745 0.0302561 -1.54866 1 0 1 1 0 0 +EDGE2 8117 8116 -0.976202 0.0489069 0.00389636 1 0 1 1 0 0 +EDGE2 8118 8117 -0.95497 0.0280072 -0.00757542 1 0 1 1 0 0 +EDGE2 8119 8118 -0.92217 0.0439207 0.00407504 1 0 1 1 0 0 +EDGE2 8120 8119 -1.00586 0.0106479 0.0186129 1 0 1 1 0 0 +EDGE2 8121 8120 -1.03064 0.0416652 -1.57632 1 0 1 1 0 0 +EDGE2 8122 8121 -0.949793 0.00520528 0.0178764 1 0 1 1 0 0 +EDGE2 8123 8122 -1.05254 0.0565705 0.0178215 1 0 1 1 0 0 +EDGE2 8124 8105 1.07916 -0.0567538 -3.11845 1 0 1 1 0 0 +EDGE2 8124 8123 -0.99692 -0.0780337 0.0178461 1 0 1 1 0 0 +EDGE2 8125 8106 -0.0328556 1.07789 1.58639 1 0 1 1 0 0 +EDGE2 8125 8104 0.98122 0.0551303 -3.12112 1 0 1 1 0 0 +EDGE2 8125 8105 0.0448176 -0.00603444 -3.11854 1 0 1 1 0 0 +EDGE2 8125 8124 -0.993726 -0.00387071 0.00914878 1 0 1 1 0 0 +EDGE2 8126 8125 -0.981007 0.0728928 1.53107 1 0 1 1 0 0 +EDGE2 8126 8105 -0.976699 -0.0290851 -1.57848 1 0 1 1 0 0 +EDGE2 8127 8126 -1.04782 -0.10655 -0.0234167 1 0 1 1 0 0 +EDGE2 8128 8127 -0.985555 -0.0390518 0.0347001 1 0 1 1 0 0 +EDGE2 8129 8128 -0.917198 0.0837955 -0.00588139 1 0 1 1 0 0 +EDGE2 8130 8129 -1.03359 -0.00121868 -0.025086 1 0 1 1 0 0 +EDGE2 8131 8130 -1.13547 0.0188982 -1.57545 1 0 1 1 0 0 +EDGE2 8132 8131 -0.974791 -0.0827604 0.0104538 1 0 1 1 0 0 +EDGE2 8133 8132 -1.01202 0.0504618 0.0220273 1 0 1 1 0 0 +EDGE2 8134 8133 -0.930137 -0.0493171 0.00269888 1 0 1 1 0 0 +EDGE2 8135 8134 -0.946139 0.0210039 0.0251588 1 0 1 1 0 0 +EDGE2 8136 8135 -1.06759 -0.0178278 -1.5855 1 0 1 1 0 0 +EDGE2 8137 8136 -0.91633 -0.0241854 -0.00445839 1 0 1 1 0 0 +EDGE2 8138 8137 -1.04677 0.099559 -0.0261489 1 0 1 1 0 0 +EDGE2 8139 6480 0.898761 -0.0569289 -3.12719 1 0 1 1 0 0 +EDGE2 8139 8100 0.946994 -0.0144938 -3.10916 1 0 1 1 0 0 +EDGE2 8139 6500 1.07422 0.0192704 -3.11915 1 0 1 1 0 0 +EDGE2 8139 8138 -0.948373 0.106793 -0.00149887 1 0 1 1 0 0 +EDGE2 8140 8099 0.893271 -0.0204752 -3.12564 1 0 1 1 0 0 +EDGE2 8140 6479 0.867434 0.000192523 -3.11545 1 0 1 1 0 0 +EDGE2 8140 6499 1.06885 0.0227769 -3.17563 1 0 1 1 0 0 +EDGE2 8140 6480 -0.0522499 -0.0490698 -3.15384 1 0 1 1 0 0 +EDGE2 8140 6501 0.0893842 -1.02341 -1.53448 1 0 1 1 0 0 +EDGE2 8140 8100 0.0676207 -0.0261804 -3.16768 1 0 1 1 0 0 +EDGE2 8140 6481 -0.0811966 -1.08253 -1.56599 1 0 1 1 0 0 +EDGE2 8140 6500 -0.0658318 0.0995818 -3.15795 1 0 1 1 0 0 +EDGE2 8140 8101 -0.0614076 0.974777 1.55296 1 0 1 1 0 0 +EDGE2 8140 8139 -1.02507 0.0217727 0.0209331 1 0 1 1 0 0 +EDGE2 8141 8140 -0.93875 -0.00336131 -1.60334 1 0 1 1 0 0 +EDGE2 8141 6480 -1.01535 0.0464137 1.51922 1 0 1 1 0 0 +EDGE2 8141 8100 -1.02856 0.0294476 1.56068 1 0 1 1 0 0 +EDGE2 8141 6500 -1.06245 0.0397827 1.60952 1 0 1 1 0 0 +EDGE2 8141 8101 -0.0967581 -0.0422234 -0.026959 1 0 1 1 0 0 +EDGE2 8141 8102 1.00177 0.0556395 -0.00257502 1 0 1 1 0 0 +EDGE2 8142 8101 -1.06585 0.01974 0.000837421 1 0 1 1 0 0 +EDGE2 8142 8102 -0.0142644 -0.0934255 -0.0202787 1 0 1 1 0 0 +EDGE2 8142 8103 0.881173 -0.084096 0.0145826 1 0 1 1 0 0 +EDGE2 8142 8141 -1.05091 -0.00260111 -0.00118016 1 0 1 1 0 0 +EDGE2 8143 8102 -1.05318 -0.0131391 -0.0275491 1 0 1 1 0 0 +EDGE2 8143 8104 0.930386 -0.0225633 0.0013759 1 0 1 1 0 0 +EDGE2 8143 8103 -0.0384176 -0.0225458 -0.0155997 1 0 1 1 0 0 +EDGE2 8143 8142 -0.930714 -0.0163036 0.0087774 1 0 1 1 0 0 +EDGE2 8144 8104 0.0162584 0.0218776 0.0190924 1 0 1 1 0 0 +EDGE2 8144 8103 -1.07203 0.0893949 -0.0148336 1 0 1 1 0 0 +EDGE2 8144 8143 -1.04105 0.0257597 -0.00564387 1 0 1 1 0 0 +EDGE2 8144 8125 1.01353 0.0573326 -3.16208 1 0 1 1 0 0 +EDGE2 8144 8105 0.931267 -0.0559487 0.00464423 1 0 1 1 0 0 +EDGE2 8145 8106 -0.0687376 -0.982553 -1.56013 1 0 1 1 0 0 +EDGE2 8145 8104 -1.04616 -0.0663987 0.00978423 1 0 1 1 0 0 +EDGE2 8145 8144 -0.923513 0.0785093 -0.00944223 1 0 1 1 0 0 +EDGE2 8145 8125 0.0234898 0.0540078 -3.13805 1 0 1 1 0 0 +EDGE2 8145 8105 -0.102873 0.027446 0.00410015 1 0 1 1 0 0 +EDGE2 8145 8124 1.09633 -0.0366262 -3.12231 1 0 1 1 0 0 +EDGE2 8145 8126 -0.0385745 1.07844 1.57394 1 0 1 1 0 0 +EDGE2 8146 8125 -1.08835 -0.0397355 1.57331 1 0 1 1 0 0 +EDGE2 8146 8105 -0.983843 -0.0674818 -1.57825 1 0 1 1 0 0 +EDGE2 8146 8145 -1.01986 0.0196387 -1.57405 1 0 1 1 0 0 +EDGE2 8146 8126 0.0207367 0.145727 0.0498861 1 0 1 1 0 0 +EDGE2 8146 8127 0.966689 0.0240248 0.0175783 1 0 1 1 0 0 +EDGE2 8147 8146 -0.989664 0.0633169 -0.0225038 1 0 1 1 0 0 +EDGE2 8147 8126 -1.10432 0.0411719 -0.0518447 1 0 1 1 0 0 +EDGE2 8147 8127 0.0604893 -0.0804468 0.0110817 1 0 1 1 0 0 +EDGE2 8147 8128 1.0673 -0.00866952 0.0123558 1 0 1 1 0 0 +EDGE2 8148 8127 -1.04271 0.00317125 -0.00428507 1 0 1 1 0 0 +EDGE2 8148 8147 -1.04395 -0.0586819 -0.0142783 1 0 1 1 0 0 +EDGE2 8148 8128 -0.044296 -0.0186748 0.0295805 1 0 1 1 0 0 +EDGE2 8148 8129 0.931768 0.0052787 -0.0216193 1 0 1 1 0 0 +EDGE2 8149 8128 -0.964977 -0.009324 -0.0165202 1 0 1 1 0 0 +EDGE2 8149 8148 -1.03493 -0.00429212 0.000159084 1 0 1 1 0 0 +EDGE2 8149 8129 -0.0092268 -0.0142317 -0.0322599 1 0 1 1 0 0 +EDGE2 8149 8130 1.03349 -0.0544193 0.0284263 1 0 1 1 0 0 +EDGE2 8150 8129 -0.997938 -0.0461944 -0.0218545 1 0 1 1 0 0 +EDGE2 8150 8149 -0.961677 0.120499 0.01532 1 0 1 1 0 0 +EDGE2 8150 8130 -0.0391744 -0.00873818 -0.0170256 1 0 1 1 0 0 +EDGE2 8150 8131 0.0564319 1.0434 1.5879 1 0 1 1 0 0 +EDGE2 8151 8130 -0.962633 -0.0124438 -1.54804 1 0 1 1 0 0 +EDGE2 8151 8132 1.02091 -0.000971477 -0.00569662 1 0 1 1 0 0 +EDGE2 8151 8131 -0.0145176 0.0306823 -0.00310783 1 0 1 1 0 0 +EDGE2 8151 8150 -0.98258 -0.0167242 -1.55339 1 0 1 1 0 0 +EDGE2 8152 8132 0.0166556 -0.00244307 0.0277851 1 0 1 1 0 0 +EDGE2 8152 8133 0.972866 0.0363667 -0.0245982 1 0 1 1 0 0 +EDGE2 8152 8131 -0.976577 0.0569464 -0.00132342 1 0 1 1 0 0 +EDGE2 8152 8151 -0.939221 0.0473392 0.0258533 1 0 1 1 0 0 +EDGE2 8153 8132 -0.971419 0.0787149 0.00795307 1 0 1 1 0 0 +EDGE2 8153 8133 -0.0457546 0.0932704 0.0153134 1 0 1 1 0 0 +EDGE2 8153 8134 0.941149 0.0664412 0.000697386 1 0 1 1 0 0 +EDGE2 8153 8152 -1.06248 0.0370387 -0.000301305 1 0 1 1 0 0 +EDGE2 8154 8135 1.0592 0.0305116 -0.0186035 1 0 1 1 0 0 +EDGE2 8154 8133 -0.985147 0.118133 0.00820776 1 0 1 1 0 0 +EDGE2 8154 8134 -0.0138055 -0.0437329 -0.0220719 1 0 1 1 0 0 +EDGE2 8154 8153 -1.07538 0.0163546 -0.0317413 1 0 1 1 0 0 +EDGE2 8155 8136 0.0500754 1.00809 1.57001 1 0 1 1 0 0 +EDGE2 8155 8135 -0.0171441 -0.0412996 -0.0275929 1 0 1 1 0 0 +EDGE2 8155 8134 -1.0327 -0.0768589 -0.00618428 1 0 1 1 0 0 +EDGE2 8155 8154 -0.94575 -0.051487 -0.0315962 1 0 1 1 0 0 +EDGE2 8156 8137 0.982314 -0.00332207 0.00941676 1 0 1 1 0 0 +EDGE2 8156 8136 -0.0334632 0.0415245 -0.045785 1 0 1 1 0 0 +EDGE2 8156 8135 -1.08966 -0.0504118 -1.55818 1 0 1 1 0 0 +EDGE2 8156 8155 -1.04504 -0.0695828 -1.56768 1 0 1 1 0 0 +EDGE2 8157 8156 -0.971471 -0.0183337 0.0381383 1 0 1 1 0 0 +EDGE2 8157 8138 1.02483 0.0517737 -0.0251627 1 0 1 1 0 0 +EDGE2 8157 8137 -0.0208211 0.0623229 -0.0061386 1 0 1 1 0 0 +EDGE2 8157 8136 -1.00587 -0.128048 0.00631896 1 0 1 1 0 0 +EDGE2 8158 8157 -1.02213 0.00713918 0.0243024 1 0 1 1 0 0 +EDGE2 8158 8139 0.998314 -0.0137917 -0.0198931 1 0 1 1 0 0 +EDGE2 8158 8138 -0.0614901 -0.0530055 0.0124728 1 0 1 1 0 0 +EDGE2 8158 8137 -0.994385 -0.0311521 -0.0165986 1 0 1 1 0 0 +EDGE2 8159 8140 1.07128 -0.00790778 -0.0126659 1 0 1 1 0 0 +EDGE2 8159 6480 0.945293 0.0402722 -3.14614 1 0 1 1 0 0 +EDGE2 8159 8100 0.952349 0.0672806 -3.15273 1 0 1 1 0 0 +EDGE2 8159 6500 0.954693 0.0227943 -3.174 1 0 1 1 0 0 +EDGE2 8159 8139 -0.0410316 0.0443398 0.0231096 1 0 1 1 0 0 +EDGE2 8159 8158 -0.955965 -0.0434937 -0.0168629 1 0 1 1 0 0 +EDGE2 8159 8138 -1.02096 0.0061399 0.0175903 1 0 1 1 0 0 +EDGE2 8160 8140 0.0172483 -0.0250913 0.00745331 1 0 1 1 0 0 +EDGE2 8160 8099 0.903812 0.00730801 -3.14899 1 0 1 1 0 0 +EDGE2 8160 6479 1.06327 0.023152 -3.16176 1 0 1 1 0 0 +EDGE2 8160 6499 1.08623 0.012799 -3.14859 1 0 1 1 0 0 +EDGE2 8160 6480 0.0409959 -0.00748827 -3.09138 1 0 1 1 0 0 +EDGE2 8160 6501 0.0929508 -1.04492 -1.56048 1 0 1 1 0 0 +EDGE2 8160 8100 0.0563429 -0.128495 -3.14616 1 0 1 1 0 0 +EDGE2 8160 6481 -0.00716869 -1.06314 -1.6 1 0 1 1 0 0 +EDGE2 8160 6500 0.03639 0.00801948 -3.18248 1 0 1 1 0 0 +EDGE2 8160 8101 0.000175511 0.987164 1.56864 1 0 1 1 0 0 +EDGE2 8160 8141 0.0320273 1.05115 1.54949 1 0 1 1 0 0 +EDGE2 8160 8139 -1.14749 -0.0538691 -0.00305404 1 0 1 1 0 0 +EDGE2 8160 8159 -1.00447 -0.00786019 -0.0421331 1 0 1 1 0 0 +EDGE2 8161 8140 -0.99633 0.0224406 -1.58945 1 0 1 1 0 0 +EDGE2 8161 6480 -1.01476 -0.0554997 1.56589 1 0 1 1 0 0 +EDGE2 8161 8100 -1.02874 -0.0310268 1.59837 1 0 1 1 0 0 +EDGE2 8161 6500 -0.99663 0.0431115 1.51549 1 0 1 1 0 0 +EDGE2 8161 8101 -0.00110301 -0.00136871 0.00410231 1 0 1 1 0 0 +EDGE2 8161 8102 1.12129 -0.000957858 -0.0143177 1 0 1 1 0 0 +EDGE2 8161 8141 0.0305888 0.0278646 -0.0111587 1 0 1 1 0 0 +EDGE2 8161 8160 -0.92948 0.0236227 -1.60137 1 0 1 1 0 0 +EDGE2 8161 8142 1.05397 0.0315802 -0.0097087 1 0 1 1 0 0 +EDGE2 8162 8101 -0.959313 0.0128852 -0.0101279 1 0 1 1 0 0 +EDGE2 8162 8102 -0.0438099 -0.0797059 -0.00671798 1 0 1 1 0 0 +EDGE2 8162 8103 0.968238 0.0785871 0.00358281 1 0 1 1 0 0 +EDGE2 8162 8141 -0.993441 -0.0199718 0.00269534 1 0 1 1 0 0 +EDGE2 8162 8143 1.03515 0.0105822 -0.00197469 1 0 1 1 0 0 +EDGE2 8162 8142 0.0159348 -0.118239 0.0348652 1 0 1 1 0 0 +EDGE2 8162 8161 -0.992832 -0.0946818 0.0232969 1 0 1 1 0 0 +EDGE2 8163 8102 -0.954807 -0.0674779 -0.0135143 1 0 1 1 0 0 +EDGE2 8163 8104 1.04579 -0.0564789 0.036585 1 0 1 1 0 0 +EDGE2 8163 8103 0.0917867 -0.024465 -0.0427845 1 0 1 1 0 0 +EDGE2 8163 8162 -1.02617 0.00909507 -0.0029466 1 0 1 1 0 0 +EDGE2 8163 8144 1.06585 0.0327478 -0.00431686 1 0 1 1 0 0 +EDGE2 8163 8143 0.0140399 -0.00690036 0.00579839 1 0 1 1 0 0 +EDGE2 8163 8142 -0.970547 0.0112979 -0.0080944 1 0 1 1 0 0 +EDGE2 8164 8104 0.0735013 -0.0515392 0.0249155 1 0 1 1 0 0 +EDGE2 8164 8103 -1.02688 -0.0252804 -0.00191222 1 0 1 1 0 0 +EDGE2 8164 8144 -0.039466 -0.0209457 0.00949676 1 0 1 1 0 0 +EDGE2 8164 8143 -1.06142 0.0106064 0.0105386 1 0 1 1 0 0 +EDGE2 8164 8163 -1.07326 -0.0409643 -0.00250136 1 0 1 1 0 0 +EDGE2 8164 8125 0.991741 0.0808995 -3.15671 1 0 1 1 0 0 +EDGE2 8164 8105 1.0159 0.021723 -0.00953953 1 0 1 1 0 0 +EDGE2 8164 8145 1.0065 0.0245629 -0.0230529 1 0 1 1 0 0 +EDGE2 8165 8106 -0.0151742 -1.15777 -1.5547 1 0 1 1 0 0 +EDGE2 8165 8104 -0.965746 -0.0349165 -0.00372279 1 0 1 1 0 0 +EDGE2 8165 8144 -0.967543 0.0366966 0.00628277 1 0 1 1 0 0 +EDGE2 8165 8164 -0.975383 0.0724187 -0.0154916 1 0 1 1 0 0 +EDGE2 8165 8125 -0.0248457 0.0451462 -3.14004 1 0 1 1 0 0 +EDGE2 8165 8105 0.0284034 -0.0103725 -0.0169249 1 0 1 1 0 0 +EDGE2 8165 8124 0.997785 -0.0459234 -3.16925 1 0 1 1 0 0 +EDGE2 8165 8146 -0.0133041 0.886126 1.5794 1 0 1 1 0 0 +EDGE2 8165 8145 0.0212827 0.0527769 -0.00249058 1 0 1 1 0 0 +EDGE2 8165 8126 0.0359865 0.986921 1.57011 1 0 1 1 0 0 +EDGE2 8166 8125 -0.932181 -0.0250357 1.57089 1 0 1 1 0 0 +EDGE2 8166 8105 -1.00189 0.110882 -1.55575 1 0 1 1 0 0 +EDGE2 8166 8146 -0.0371744 0.0320802 0.0111861 1 0 1 1 0 0 +EDGE2 8166 8165 -0.962937 -0.0256373 -1.55514 1 0 1 1 0 0 +EDGE2 8166 8145 -1.11401 -0.0527284 -1.58585 1 0 1 1 0 0 +EDGE2 8166 8126 -0.0228182 -0.0500582 0.0251909 1 0 1 1 0 0 +EDGE2 8166 8127 1.00958 0.0319803 0.0057443 1 0 1 1 0 0 +EDGE2 8166 8147 1.00258 -0.0569155 0.0170024 1 0 1 1 0 0 +EDGE2 8167 8146 -0.995678 0.0532253 -0.00283514 1 0 1 1 0 0 +EDGE2 8167 8126 -1.0179 0.0403306 -0.00674472 1 0 1 1 0 0 +EDGE2 8167 8127 -0.0236357 0.015057 -0.01254 1 0 1 1 0 0 +EDGE2 8167 8166 -0.999953 0.017554 -0.00569014 1 0 1 1 0 0 +EDGE2 8167 8147 0.0133304 -0.0439686 -0.0102085 1 0 1 1 0 0 +EDGE2 8167 8128 0.916447 0.0479969 -0.0118815 1 0 1 1 0 0 +EDGE2 8167 8148 1.01117 -0.0055456 -0.0119594 1 0 1 1 0 0 +EDGE2 8168 8167 -1.04491 0.0275459 0.0367378 1 0 1 1 0 0 +EDGE2 8168 8127 -1.08899 -0.00300245 -0.019172 1 0 1 1 0 0 +EDGE2 8168 8147 -1.01305 0.00200891 -0.00750549 1 0 1 1 0 0 +EDGE2 8168 8128 0.00147682 0.0488145 0.012357 1 0 1 1 0 0 +EDGE2 8168 8148 -0.00453176 -0.0622796 0.0106215 1 0 1 1 0 0 +EDGE2 8168 8129 1.07848 0.0223801 0.0226699 1 0 1 1 0 0 +EDGE2 8168 8149 1.02894 -0.00678431 0.00645541 1 0 1 1 0 0 +EDGE2 8169 8168 -1.04825 -0.104034 -0.0122713 1 0 1 1 0 0 +EDGE2 8169 8128 -0.968503 -0.0292738 0.00663707 1 0 1 1 0 0 +EDGE2 8169 8148 -1.01165 0.0638643 -0.0122698 1 0 1 1 0 0 +EDGE2 8169 8129 0.121646 -0.0219265 -0.0297143 1 0 1 1 0 0 +EDGE2 8169 8149 0.00310871 0.0112719 -0.0116149 1 0 1 1 0 0 +EDGE2 8169 8130 0.986939 0.0460639 0.00665224 1 0 1 1 0 0 +EDGE2 8169 8150 0.91904 0.00777243 -0.0457178 1 0 1 1 0 0 +EDGE2 8170 8169 -1.039 -0.0416094 0.014382 1 0 1 1 0 0 +EDGE2 8170 8129 -0.995587 -0.0327285 -0.00739347 1 0 1 1 0 0 +EDGE2 8170 8149 -1.04257 -0.0855877 0.00558804 1 0 1 1 0 0 +EDGE2 8170 8130 -0.017479 0.048948 -0.00667299 1 0 1 1 0 0 +EDGE2 8170 8131 -0.142835 0.963871 1.55817 1 0 1 1 0 0 +EDGE2 8170 8151 -0.0126711 1.02794 1.57315 1 0 1 1 0 0 +EDGE2 8170 8150 0.0222419 -0.010164 0.00564633 1 0 1 1 0 0 +EDGE2 8171 8170 -0.967057 -0.0060429 1.57471 1 0 1 1 0 0 +EDGE2 8171 8130 -0.973404 -0.0328628 1.58226 1 0 1 1 0 0 +EDGE2 8171 8150 -0.937814 -0.0435285 1.54593 1 0 1 1 0 0 +EDGE2 8172 8171 -1.07155 -0.0784285 -0.00355796 1 0 1 1 0 0 +EDGE2 8173 8172 -0.975258 0.0133001 -0.0054551 1 0 1 1 0 0 +EDGE2 8174 8173 -0.998083 -0.0914053 -0.0283175 1 0 1 1 0 0 +EDGE2 8175 8174 -1.02804 -0.000149194 0.00858491 1 0 1 1 0 0 +EDGE2 8176 8175 -1.0143 -0.00114075 -1.56939 1 0 1 1 0 0 +EDGE2 8177 8176 -1.018 -0.00438593 -0.0158885 1 0 1 1 0 0 +EDGE2 8178 8177 -0.976568 0.000620969 0.0365558 1 0 1 1 0 0 +EDGE2 8179 8178 -1.04231 -0.0737934 -0.00814144 1 0 1 1 0 0 +EDGE2 8180 8179 -0.926113 0.0204665 0.0173872 1 0 1 1 0 0 +EDGE2 8181 8180 -0.936356 -0.0504502 1.60754 1 0 1 1 0 0 +EDGE2 8182 8181 -0.974147 0.0993544 0.0287152 1 0 1 1 0 0 +EDGE2 8183 8182 -0.963454 0.0584695 0.0177305 1 0 1 1 0 0 +EDGE2 8184 8183 -1.02578 0.0390635 0.00484441 1 0 1 1 0 0 +EDGE2 8185 8184 -1.00562 -0.0642128 -0.00225577 1 0 1 1 0 0 +EDGE2 8186 8185 -0.948321 0.0606064 -1.54331 1 0 1 1 0 0 +EDGE2 8187 8186 -0.902927 0.0745008 0.0283697 1 0 1 1 0 0 +EDGE2 8188 8187 -0.987162 0.0586616 0.00529636 1 0 1 1 0 0 +EDGE2 8189 8188 -0.985625 0.0125582 -0.00731126 1 0 1 1 0 0 +EDGE2 8190 8189 -0.962027 -0.00531442 -0.0511458 1 0 1 1 0 0 +EDGE2 8191 8190 -1.05116 -0.0377214 1.58473 1 0 1 1 0 0 +EDGE2 8192 8191 -0.939747 0.0830677 -0.00337321 1 0 1 1 0 0 +EDGE2 8193 8192 -1.00207 0.104111 0.00955612 1 0 1 1 0 0 +EDGE2 8194 8193 -0.92963 0.0321474 0.0053904 1 0 1 1 0 0 +EDGE2 8195 8194 -0.965737 0.061761 -0.0074091 1 0 1 1 0 0 +EDGE2 8196 8195 -0.994102 -0.0400327 -1.56756 1 0 1 1 0 0 +EDGE2 8197 8196 -1.04449 0.0187093 -0.0436798 1 0 1 1 0 0 +EDGE2 8198 8197 -0.996765 0.0510769 -0.0424784 1 0 1 1 0 0 +EDGE2 8199 8198 -1.0197 0.0228548 -0.021468 1 0 1 1 0 0 +EDGE2 8200 8199 -0.997507 0.0409383 -0.000598777 1 0 1 1 0 0 +EDGE2 8201 8200 -0.98848 -0.0615709 1.57089 1 0 1 1 0 0 +EDGE2 8202 8201 -0.91789 0.0538998 0.0263259 1 0 1 1 0 0 +EDGE2 8203 8202 -0.932141 0.0131801 -0.00678882 1 0 1 1 0 0 +EDGE2 8204 8203 -1.07757 0.00212096 0.0187143 1 0 1 1 0 0 +EDGE2 8205 8204 -1.01779 0.0917069 -0.00317718 1 0 1 1 0 0 +EDGE2 8206 8205 -0.957862 -0.0215063 -1.53985 1 0 1 1 0 0 +EDGE2 8207 8206 -1.04492 -0.0163928 -0.0125744 1 0 1 1 0 0 +EDGE2 8208 8207 -0.990464 -0.0112262 0.00263463 1 0 1 1 0 0 +EDGE2 8209 8208 -1.00078 0.0061434 0.0335579 1 0 1 1 0 0 +EDGE2 8210 8209 -0.995308 -0.0465638 -0.0126613 1 0 1 1 0 0 +EDGE2 8211 8210 -1.00081 -0.0394677 -1.5742 1 0 1 1 0 0 +EDGE2 8212 8211 -0.857882 -0.0413359 0.0151093 1 0 1 1 0 0 +EDGE2 8213 8212 -1.03015 0.0789654 0.0145017 1 0 1 1 0 0 +EDGE2 8214 8213 -1.00391 -0.0219983 0.00877725 1 0 1 1 0 0 +EDGE2 8215 8214 -1.01195 -0.055003 0.0113583 1 0 1 1 0 0 +EDGE2 8216 8215 -1.02249 0.0278952 -1.58059 1 0 1 1 0 0 +EDGE2 8217 8216 -0.998607 0.0267395 0.00375382 1 0 1 1 0 0 +EDGE2 8218 8217 -0.957869 0.0458553 0.0369184 1 0 1 1 0 0 +EDGE2 8219 8200 0.973876 0.0353012 -3.1337 1 0 1 1 0 0 +EDGE2 8219 8218 -0.951276 0.0363548 -0.0222328 1 0 1 1 0 0 +EDGE2 8220 8199 0.900426 -0.057171 -3.1469 1 0 1 1 0 0 +EDGE2 8220 8200 -0.0927208 0.0470347 -3.12632 1 0 1 1 0 0 +EDGE2 8220 8219 -1.03972 -0.0677521 -0.0532332 1 0 1 1 0 0 +EDGE2 8220 8201 0.0112237 1.02619 1.55485 1 0 1 1 0 0 +EDGE2 8221 8220 -0.98391 0.0630646 -1.56024 1 0 1 1 0 0 +EDGE2 8221 8200 -1.02188 -0.0232491 1.56471 1 0 1 1 0 0 +EDGE2 8221 8201 -0.0410917 -0.00518852 -0.00138268 1 0 1 1 0 0 +EDGE2 8221 8202 0.95881 -0.0583152 0.000919188 1 0 1 1 0 0 +EDGE2 8222 8201 -0.941925 0.00595798 -0.0120358 1 0 1 1 0 0 +EDGE2 8222 8221 -1.05607 0.0628922 0.0514248 1 0 1 1 0 0 +EDGE2 8222 8202 -0.00410431 -0.0178341 -0.02206 1 0 1 1 0 0 +EDGE2 8222 8203 0.934878 0.0638829 0.000363317 1 0 1 1 0 0 +EDGE2 8223 8202 -0.981752 0.00896076 -0.0253724 1 0 1 1 0 0 +EDGE2 8223 8222 -0.996035 0.02341 0.0077448 1 0 1 1 0 0 +EDGE2 8223 8203 -0.0833425 -0.0102974 -0.0046327 1 0 1 1 0 0 +EDGE2 8223 8204 1.02089 -0.0595527 0.0409907 1 0 1 1 0 0 +EDGE2 8224 8203 -1.09142 0.0126512 -0.00260876 1 0 1 1 0 0 +EDGE2 8224 8223 -1.02245 0.0360653 0.0136883 1 0 1 1 0 0 +EDGE2 8224 8204 -0.0307536 -0.0742528 -0.00743537 1 0 1 1 0 0 +EDGE2 8224 8205 1.06416 -0.0754742 -0.0049188 1 0 1 1 0 0 +EDGE2 8225 8224 -0.984813 0.057547 0.0052052 1 0 1 1 0 0 +EDGE2 8225 8204 -0.997749 0.0296311 0.00723238 1 0 1 1 0 0 +EDGE2 8225 8205 -0.0600381 -0.0267832 -0.00418346 1 0 1 1 0 0 +EDGE2 8225 8206 -0.00319798 0.977643 1.54897 1 0 1 1 0 0 +EDGE2 8226 8205 -1.1138 -0.0401427 -1.56396 1 0 1 1 0 0 +EDGE2 8226 8225 -0.982968 -0.0511002 -1.56424 1 0 1 1 0 0 +EDGE2 8226 8206 -0.0606519 -0.145029 -0.00802572 1 0 1 1 0 0 +EDGE2 8226 8207 0.933192 0.0124403 -0.0163438 1 0 1 1 0 0 +EDGE2 8227 8208 1.01463 -0.0664765 -0.0255294 1 0 1 1 0 0 +EDGE2 8227 8206 -1.00882 0.0277998 0.00899284 1 0 1 1 0 0 +EDGE2 8227 8226 -0.967217 -0.00808462 0.005978 1 0 1 1 0 0 +EDGE2 8227 8207 0.0601185 0.0934682 -0.0164005 1 0 1 1 0 0 +EDGE2 8228 8208 0.0787904 0.109736 0.00261293 1 0 1 1 0 0 +EDGE2 8228 8227 -0.975264 0.0054379 0.011034 1 0 1 1 0 0 +EDGE2 8228 8207 -0.865244 0.0538293 -0.0171382 1 0 1 1 0 0 +EDGE2 8228 8209 1.02331 0.00710876 0.0252061 1 0 1 1 0 0 +EDGE2 8229 8208 -0.996729 -0.0218075 -0.0219597 1 0 1 1 0 0 +EDGE2 8229 8228 -0.989628 0.0968652 -0.0266787 1 0 1 1 0 0 +EDGE2 8229 8209 -0.0298074 0.0605314 -0.0135421 1 0 1 1 0 0 +EDGE2 8229 8210 0.98458 -0.0596318 0.0147458 1 0 1 1 0 0 +EDGE2 8230 8209 -0.969695 0.0515749 0.0251675 1 0 1 1 0 0 +EDGE2 8230 8229 -1.06162 -0.00296372 -0.0218429 1 0 1 1 0 0 +EDGE2 8230 8211 -0.0299998 1.06327 1.56344 1 0 1 1 0 0 +EDGE2 8230 8210 0.0471677 -0.00535558 0.0237298 1 0 1 1 0 0 +EDGE2 8231 8211 0.0413223 0.0256558 0.0342799 1 0 1 1 0 0 +EDGE2 8231 8212 0.936773 -0.0306047 0.0201714 1 0 1 1 0 0 +EDGE2 8231 8210 -0.934913 -0.0117046 -1.55256 1 0 1 1 0 0 +EDGE2 8231 8230 -0.987923 0.0397304 -1.5747 1 0 1 1 0 0 +EDGE2 8232 8213 0.959174 0.0316397 -0.0385795 1 0 1 1 0 0 +EDGE2 8232 8211 -1.004 -0.0236485 0.0106632 1 0 1 1 0 0 +EDGE2 8232 8212 -0.0436342 -0.0375041 0.0115262 1 0 1 1 0 0 +EDGE2 8232 8231 -1.07883 0.0803251 -0.0262362 1 0 1 1 0 0 +EDGE2 8233 8214 0.947696 0.0239017 0.0162995 1 0 1 1 0 0 +EDGE2 8233 8213 0.0133726 0.0713189 -0.0318106 1 0 1 1 0 0 +EDGE2 8233 8212 -1.00107 -0.00379622 0.022695 1 0 1 1 0 0 +EDGE2 8233 8232 -0.948626 0.0146772 -0.0192269 1 0 1 1 0 0 +EDGE2 8234 8233 -0.919143 -0.0594702 0.00276401 1 0 1 1 0 0 +EDGE2 8234 8215 0.974512 0.0216003 -0.0259005 1 0 1 1 0 0 +EDGE2 8234 8214 0.0391165 0.0125846 -0.0193438 1 0 1 1 0 0 +EDGE2 8234 8213 -1.02292 -0.0263931 0.0163368 1 0 1 1 0 0 +EDGE2 8235 8216 -0.0429198 0.899594 1.55108 1 0 1 1 0 0 +EDGE2 8235 8215 0.017591 -0.0498934 0.00541529 1 0 1 1 0 0 +EDGE2 8235 8214 -0.952146 -0.0398544 0.0123152 1 0 1 1 0 0 +EDGE2 8235 8234 -0.917277 -0.0305086 0.0274208 1 0 1 1 0 0 +EDGE2 8236 8217 1.05692 -0.00446657 -0.00280084 1 0 1 1 0 0 +EDGE2 8236 8235 -1.0665 0.0172845 -1.51772 1 0 1 1 0 0 +EDGE2 8236 8216 0.012132 -0.0306854 0.00400759 1 0 1 1 0 0 +EDGE2 8236 8215 -0.960787 0.0157796 -1.55814 1 0 1 1 0 0 +EDGE2 8237 8218 0.980985 0.00534973 0.0255665 1 0 1 1 0 0 +EDGE2 8237 8217 -0.0611302 0.0327557 0.00557685 1 0 1 1 0 0 +EDGE2 8237 8236 -0.941904 -0.0871445 -0.0130777 1 0 1 1 0 0 +EDGE2 8237 8216 -0.995911 -0.0480912 0.00694205 1 0 1 1 0 0 +EDGE2 8238 8219 1.02352 -0.0133535 -0.00880879 1 0 1 1 0 0 +EDGE2 8238 8218 -0.0777623 0.0467875 0.0168031 1 0 1 1 0 0 +EDGE2 8238 8237 -1.01614 -0.0111624 -0.0474344 1 0 1 1 0 0 +EDGE2 8238 8217 -1.06509 0.0154833 -0.0438469 1 0 1 1 0 0 +EDGE2 8239 8220 1.01675 0.0124853 0.0194143 1 0 1 1 0 0 +EDGE2 8239 8200 0.992222 -0.0396589 -3.12606 1 0 1 1 0 0 +EDGE2 8239 8219 -0.0521372 0.0120699 -0.00314637 1 0 1 1 0 0 +EDGE2 8239 8218 -1.04821 -0.0399922 0.0177569 1 0 1 1 0 0 +EDGE2 8239 8238 -0.966805 0.0176086 -0.00166883 1 0 1 1 0 0 +EDGE2 8240 8199 1.04762 0.0446834 -3.17671 1 0 1 1 0 0 +EDGE2 8240 8220 0.00806645 -0.00980906 0.0220627 1 0 1 1 0 0 +EDGE2 8240 8200 0.0631744 -0.0151343 -3.16743 1 0 1 1 0 0 +EDGE2 8240 8239 -1.0485 -0.00191219 0.00436395 1 0 1 1 0 0 +EDGE2 8240 8219 -0.991266 -0.0769866 -0.00400622 1 0 1 1 0 0 +EDGE2 8240 8201 -0.0741952 1.07132 1.50734 1 0 1 1 0 0 +EDGE2 8240 8221 0.0156034 0.95158 1.58812 1 0 1 1 0 0 +EDGE2 8241 8220 -1.10354 -0.060127 -1.57664 1 0 1 1 0 0 +EDGE2 8241 8240 -1.03765 -0.0557537 -1.54686 1 0 1 1 0 0 +EDGE2 8241 8200 -0.985052 -0.0837294 1.55398 1 0 1 1 0 0 +EDGE2 8241 8201 0.0636216 -0.112447 -0.0230334 1 0 1 1 0 0 +EDGE2 8241 8221 -0.0427196 -0.0339851 0.0251208 1 0 1 1 0 0 +EDGE2 8241 8202 0.995644 0.0557472 -0.00526897 1 0 1 1 0 0 +EDGE2 8241 8222 1.02368 -0.0252593 -0.00403338 1 0 1 1 0 0 +EDGE2 8242 8201 -0.959662 -0.0405926 0.00416258 1 0 1 1 0 0 +EDGE2 8242 8221 -1.00342 0.0322407 0.02012 1 0 1 1 0 0 +EDGE2 8242 8241 -1.01605 -0.0752761 0.0345807 1 0 1 1 0 0 +EDGE2 8242 8202 0.00586799 -0.0806815 -0.0031694 1 0 1 1 0 0 +EDGE2 8242 8222 -0.0125575 0.0387267 -0.00234544 1 0 1 1 0 0 +EDGE2 8242 8203 0.976618 -0.0995313 -0.0255743 1 0 1 1 0 0 +EDGE2 8242 8223 1.0786 -0.0249911 -0.0203636 1 0 1 1 0 0 +EDGE2 8243 8242 -1.11882 -0.00561753 0.0126483 1 0 1 1 0 0 +EDGE2 8243 8202 -1.11618 -0.0316885 0.00952078 1 0 1 1 0 0 +EDGE2 8243 8222 -0.978275 0.0487618 -0.0205399 1 0 1 1 0 0 +EDGE2 8243 8203 -0.0140963 -0.0693724 -0.0173464 1 0 1 1 0 0 +EDGE2 8243 8223 0.078233 -0.0039025 -0.0364708 1 0 1 1 0 0 +EDGE2 8243 8224 1.03379 -0.0472122 0.0209807 1 0 1 1 0 0 +EDGE2 8243 8204 1.14769 -0.0144695 0.0195623 1 0 1 1 0 0 +EDGE2 8244 8203 -1.01934 0.0383502 0.0162059 1 0 1 1 0 0 +EDGE2 8244 8243 -0.988468 -0.0159494 0.022705 1 0 1 1 0 0 +EDGE2 8244 8223 -1.02882 0.00155906 -0.0132586 1 0 1 1 0 0 +EDGE2 8244 8224 0.0492092 0.0524925 -0.00420859 1 0 1 1 0 0 +EDGE2 8244 8204 0.00363722 0.0321229 -0.0300417 1 0 1 1 0 0 +EDGE2 8244 8205 1.04631 -0.0167465 0.0249674 1 0 1 1 0 0 +EDGE2 8244 8225 1.00888 0.0761576 0.00571119 1 0 1 1 0 0 +EDGE2 8245 8224 -1.02621 0.0533317 -0.00499299 1 0 1 1 0 0 +EDGE2 8245 8244 -1.03477 0.0442978 -0.00629713 1 0 1 1 0 0 +EDGE2 8245 8204 -0.949749 -0.104656 0.0151595 1 0 1 1 0 0 +EDGE2 8245 8205 -0.108452 0.0241207 -0.00473781 1 0 1 1 0 0 +EDGE2 8245 8225 0.0781798 -0.102384 -0.0135887 1 0 1 1 0 0 +EDGE2 8245 8206 -0.0347004 1.01868 1.58562 1 0 1 1 0 0 +EDGE2 8245 8226 0.0197745 0.947336 1.58772 1 0 1 1 0 0 +EDGE2 8246 8205 -1.07147 0.0146675 -1.59064 1 0 1 1 0 0 +EDGE2 8246 8245 -1.0176 0.067423 -1.5921 1 0 1 1 0 0 +EDGE2 8246 8225 -0.9694 0.0195784 -1.54593 1 0 1 1 0 0 +EDGE2 8246 8227 1.06213 -0.0369561 0.00546158 1 0 1 1 0 0 +EDGE2 8246 8206 0.0779591 -0.0216489 0.009646 1 0 1 1 0 0 +EDGE2 8246 8226 0.0207244 0.0123991 -0.0183528 1 0 1 1 0 0 +EDGE2 8246 8207 0.991896 0.0101491 0.000285459 1 0 1 1 0 0 +EDGE2 8247 8208 0.923725 -0.00738429 0.034984 1 0 1 1 0 0 +EDGE2 8247 8227 -0.012085 0.0838846 -0.00309352 1 0 1 1 0 0 +EDGE2 8247 8206 -1.04251 -0.0244071 -0.00689656 1 0 1 1 0 0 +EDGE2 8247 8226 -0.975514 0.01507 -0.0280038 1 0 1 1 0 0 +EDGE2 8247 8246 -0.926061 -0.0155432 0.0209068 1 0 1 1 0 0 +EDGE2 8247 8228 1.00102 0.0765454 0.0267351 1 0 1 1 0 0 +EDGE2 8247 8207 0.0499682 0.0024394 0.015593 1 0 1 1 0 0 +EDGE2 8248 8208 0.0958696 0.0368249 -0.00506488 1 0 1 1 0 0 +EDGE2 8248 8227 -1.02425 0.00875194 0.00406314 1 0 1 1 0 0 +EDGE2 8248 8247 -1.05428 -0.0397038 -0.0111132 1 0 1 1 0 0 +EDGE2 8248 8228 -0.0438545 0.0430628 -0.0204637 1 0 1 1 0 0 +EDGE2 8248 8207 -1.06862 -0.0352177 0.0182392 1 0 1 1 0 0 +EDGE2 8248 8209 0.987124 0.034211 0.0196021 1 0 1 1 0 0 +EDGE2 8248 8229 1.02275 -0.00112907 -0.000726807 1 0 1 1 0 0 +EDGE2 8249 8208 -0.992905 -0.039142 -0.0244395 1 0 1 1 0 0 +EDGE2 8249 8228 -1.06049 0.0108236 -0.0103398 1 0 1 1 0 0 +EDGE2 8249 8248 -0.984066 -0.0508106 -0.0014706 1 0 1 1 0 0 +EDGE2 8249 8209 0.0446784 0.0435243 -0.0022855 1 0 1 1 0 0 +EDGE2 8249 8229 0.0302183 -0.0108907 0.00060423 1 0 1 1 0 0 +EDGE2 8249 8210 1.04248 0.00340778 -0.028441 1 0 1 1 0 0 +EDGE2 8249 8230 0.924989 0.0149265 -0.0257998 1 0 1 1 0 0 +EDGE2 8250 8209 -1.05778 0.00393714 -0.0350344 1 0 1 1 0 0 +EDGE2 8250 8229 -0.922007 -0.0205619 -0.0219591 1 0 1 1 0 0 +EDGE2 8250 8249 -0.998538 0.0817909 -0.00896695 1 0 1 1 0 0 +EDGE2 8250 8211 0.00970567 0.953025 1.56445 1 0 1 1 0 0 +EDGE2 8250 8231 -0.003197 0.905957 1.58123 1 0 1 1 0 0 +EDGE2 8250 8210 -0.0113086 -0.0632451 -0.0436425 1 0 1 1 0 0 +EDGE2 8250 8230 0.000195542 -0.00793141 -0.00777217 1 0 1 1 0 0 +EDGE2 8251 8211 -0.0582759 0.0593612 0.0259978 1 0 1 1 0 0 +EDGE2 8251 8212 0.951623 -0.0608762 -0.00593987 1 0 1 1 0 0 +EDGE2 8251 8232 1.06404 -0.00114001 -0.013531 1 0 1 1 0 0 +EDGE2 8251 8231 -0.0228746 -0.112448 -0.0065588 1 0 1 1 0 0 +EDGE2 8251 8210 -1.03298 0.0285519 -1.5881 1 0 1 1 0 0 +EDGE2 8251 8230 -0.932585 -0.00768395 -1.53762 1 0 1 1 0 0 +EDGE2 8251 8250 -1.02611 0.0546 -1.56516 1 0 1 1 0 0 +EDGE2 8252 8233 1.02472 0.0435745 0.0314518 1 0 1 1 0 0 +EDGE2 8252 8213 1.01275 -0.0149466 0.00490286 1 0 1 1 0 0 +EDGE2 8252 8211 -1.04663 -0.05651 0.0369778 1 0 1 1 0 0 +EDGE2 8252 8251 -1.03912 0.0347417 0.0097549 1 0 1 1 0 0 +EDGE2 8252 8212 -0.016886 0.121479 -0.00226509 1 0 1 1 0 0 +EDGE2 8252 8232 0.00570242 -0.0925054 -0.00799102 1 0 1 1 0 0 +EDGE2 8252 8231 -0.987854 -0.00113289 0.0106011 1 0 1 1 0 0 +EDGE2 8253 8233 0.0734306 0.0271145 -0.00989951 1 0 1 1 0 0 +EDGE2 8253 8214 1.00871 0.0151939 -0.00167391 1 0 1 1 0 0 +EDGE2 8253 8234 0.973787 0.0682002 0.00991443 1 0 1 1 0 0 +EDGE2 8253 8252 -0.951457 -0.00561533 -0.00630559 1 0 1 1 0 0 +EDGE2 8253 8213 -0.0235969 0.0572674 0.00646703 1 0 1 1 0 0 +EDGE2 8253 8212 -0.990242 -0.0794413 0.00685245 1 0 1 1 0 0 +EDGE2 8253 8232 -0.987289 0.0464269 -0.00410796 1 0 1 1 0 0 +EDGE2 8254 8233 -1.03172 -0.00866802 -0.030299 1 0 1 1 0 0 +EDGE2 8254 8235 0.991829 -0.0154246 0.027304 1 0 1 1 0 0 +EDGE2 8254 8215 1.1073 0.0948951 0.0168342 1 0 1 1 0 0 +EDGE2 8254 8214 0.0568134 0.0450485 0.00289636 1 0 1 1 0 0 +EDGE2 8254 8234 -0.0151577 0.00398916 -0.0117083 1 0 1 1 0 0 +EDGE2 8254 8253 -0.944588 -0.041508 0.0313582 1 0 1 1 0 0 +EDGE2 8254 8213 -0.893095 0.0922574 -0.0174059 1 0 1 1 0 0 +EDGE2 8255 8236 -0.0261346 1.00967 1.56345 1 0 1 1 0 0 +EDGE2 8255 8254 -1.01912 -0.0555686 0.0377622 1 0 1 1 0 0 +EDGE2 8255 8235 -0.0669881 0.0574759 0.00567161 1 0 1 1 0 0 +EDGE2 8255 8216 -0.0687402 0.954604 1.57417 1 0 1 1 0 0 +EDGE2 8255 8215 -0.00500649 -0.0511609 -0.0200284 1 0 1 1 0 0 +EDGE2 8255 8214 -1.03057 0.0585836 0.023121 1 0 1 1 0 0 +EDGE2 8255 8234 -1.07977 0.0672256 -0.0193806 1 0 1 1 0 0 +EDGE2 8256 8237 0.946912 -0.0363607 0.0322854 1 0 1 1 0 0 +EDGE2 8256 8217 0.915046 -0.0114521 0.0184884 1 0 1 1 0 0 +EDGE2 8256 8236 0.00942112 -0.00862734 -0.00248278 1 0 1 1 0 0 +EDGE2 8256 8235 -1.00509 0.0292097 -1.57562 1 0 1 1 0 0 +EDGE2 8256 8255 -0.908613 0.015613 -1.56508 1 0 1 1 0 0 +EDGE2 8256 8216 -0.0784569 0.078957 -0.017907 1 0 1 1 0 0 +EDGE2 8256 8215 -0.961285 0.0909576 -1.54316 1 0 1 1 0 0 +EDGE2 8257 8218 0.990252 0.0070395 0.00864207 1 0 1 1 0 0 +EDGE2 8257 8238 0.953151 0.0054225 0.0169411 1 0 1 1 0 0 +EDGE2 8257 8237 -0.0552379 -0.0125173 -0.0145047 1 0 1 1 0 0 +EDGE2 8257 8217 -0.0519839 -0.0504452 0.024482 1 0 1 1 0 0 +EDGE2 8257 8236 -0.865035 0.0174861 0.00584965 1 0 1 1 0 0 +EDGE2 8257 8256 -1.02535 0.0623752 0.00200424 1 0 1 1 0 0 +EDGE2 8257 8216 -0.993653 0.025308 0.0216844 1 0 1 1 0 0 +EDGE2 8258 8257 -1.10913 0.0379823 -0.0232138 1 0 1 1 0 0 +EDGE2 8258 8239 1.09739 -0.100081 -0.0218964 1 0 1 1 0 0 +EDGE2 8258 8219 0.958461 0.0724047 -0.00192669 1 0 1 1 0 0 +EDGE2 8258 8218 -0.00947333 -0.029127 0.000162907 1 0 1 1 0 0 +EDGE2 8258 8238 -0.0528225 -0.075304 0.0164423 1 0 1 1 0 0 +EDGE2 8258 8237 -0.98629 0.0138728 0.00284631 1 0 1 1 0 0 +EDGE2 8258 8217 -0.907547 -0.0536092 0.0472199 1 0 1 1 0 0 +EDGE2 8259 8220 1.06737 -0.00487528 -0.0150582 1 0 1 1 0 0 +EDGE2 8259 8240 0.956087 -0.00302284 0.012077 1 0 1 1 0 0 +EDGE2 8259 8200 1.03815 -0.00440541 -3.15669 1 0 1 1 0 0 +EDGE2 8259 8239 -0.0376118 -0.0130869 -0.0225918 1 0 1 1 0 0 +EDGE2 8259 8219 0.0853862 -0.0571537 -0.0246668 1 0 1 1 0 0 +EDGE2 8259 8218 -0.90439 -0.0409916 -0.0136461 1 0 1 1 0 0 +EDGE2 8259 8238 -0.988361 0.0341223 -0.0206372 1 0 1 1 0 0 +EDGE2 8259 8258 -1.05446 -0.065474 0.00675505 1 0 1 1 0 0 +EDGE2 8260 8199 0.99643 0.037721 -3.13955 1 0 1 1 0 0 +EDGE2 8260 8220 -0.00758691 -0.047968 -0.0184265 1 0 1 1 0 0 +EDGE2 8260 8240 -0.0624102 -0.0469879 0.00959461 1 0 1 1 0 0 +EDGE2 8260 8200 -0.11754 -0.00115003 -3.15158 1 0 1 1 0 0 +EDGE2 8260 8239 -1.02416 0.0616588 0.0193192 1 0 1 1 0 0 +EDGE2 8260 8259 -1.12404 -0.079438 -0.0192838 1 0 1 1 0 0 +EDGE2 8260 8219 -0.948942 -0.00981219 0.00993347 1 0 1 1 0 0 +EDGE2 8260 8201 -0.0543415 1.10005 1.60329 1 0 1 1 0 0 +EDGE2 8260 8221 0.0278937 1.02334 1.61867 1 0 1 1 0 0 +EDGE2 8260 8241 0.0251447 0.950799 1.57682 1 0 1 1 0 0 +EDGE2 8261 8260 -1.07994 0.0145369 -1.55503 1 0 1 1 0 0 +EDGE2 8261 8220 -1.00615 0.0580551 -1.54857 1 0 1 1 0 0 +EDGE2 8261 8240 -0.958311 0.019829 -1.58694 1 0 1 1 0 0 +EDGE2 8261 8200 -0.947591 0.0419612 1.56499 1 0 1 1 0 0 +EDGE2 8261 8242 1.03079 -0.0106563 0.000162083 1 0 1 1 0 0 +EDGE2 8261 8201 -0.0768259 -0.025592 -0.0524239 1 0 1 1 0 0 +EDGE2 8261 8221 -0.123987 0.0087919 0.00920582 1 0 1 1 0 0 +EDGE2 8261 8241 0.0535429 0.0344224 0.0195281 1 0 1 1 0 0 +EDGE2 8261 8202 1.05116 -0.039574 -0.0213365 1 0 1 1 0 0 +EDGE2 8261 8222 0.974181 -0.0594749 0.00826368 1 0 1 1 0 0 +EDGE2 8262 8261 -1.00529 0.0141786 -0.0344171 1 0 1 1 0 0 +EDGE2 8262 8242 0.00903942 0.00716662 0.0103129 1 0 1 1 0 0 +EDGE2 8262 8201 -0.998896 0.00581125 -0.0246455 1 0 1 1 0 0 +EDGE2 8262 8221 -0.975419 0.0422453 -0.0115841 1 0 1 1 0 0 +EDGE2 8262 8241 -1.01195 -0.0465259 -0.0311389 1 0 1 1 0 0 +EDGE2 8262 8202 -0.0530466 0.0878077 -0.0181108 1 0 1 1 0 0 +EDGE2 8262 8222 0.064572 0.0364004 -0.00941935 1 0 1 1 0 0 +EDGE2 8262 8203 0.901386 0.0660768 -0.0101419 1 0 1 1 0 0 +EDGE2 8262 8243 1.00095 0.0229822 0.0219095 1 0 1 1 0 0 +EDGE2 8262 8223 1.02559 0.0928713 0.0134604 1 0 1 1 0 0 +EDGE2 8263 8242 -0.986957 0.0185063 -0.0105842 1 0 1 1 0 0 +EDGE2 8263 8262 -1.06302 -0.0279911 0.0219947 1 0 1 1 0 0 +EDGE2 8263 8202 -0.975403 0.0203895 -0.00244493 1 0 1 1 0 0 +EDGE2 8263 8222 -0.927388 0.00900546 -0.00310777 1 0 1 1 0 0 +EDGE2 8263 8203 0.0358739 0.0219437 0.0165182 1 0 1 1 0 0 +EDGE2 8263 8243 0.0253816 -0.0416419 0.00933062 1 0 1 1 0 0 +EDGE2 8263 8223 -0.0668649 -0.0263562 -0.0176944 1 0 1 1 0 0 +EDGE2 8263 8224 0.98876 -0.0223881 -0.0572485 1 0 1 1 0 0 +EDGE2 8263 8244 1.07861 -0.0705238 -0.032232 1 0 1 1 0 0 +EDGE2 8263 8204 0.97531 -0.025927 -0.00491311 1 0 1 1 0 0 +EDGE2 8264 8203 -1.01127 -0.0980026 0.0296459 1 0 1 1 0 0 +EDGE2 8264 8243 -1.00306 0.101294 -0.00942588 1 0 1 1 0 0 +EDGE2 8264 8263 -1.00629 0.0313574 0.00709064 1 0 1 1 0 0 +EDGE2 8264 8223 -1.10332 -0.0107614 -0.0152312 1 0 1 1 0 0 +EDGE2 8264 8224 -0.0110055 -0.0111078 0.00549138 1 0 1 1 0 0 +EDGE2 8264 8244 0.041313 0.0646115 0.0111575 1 0 1 1 0 0 +EDGE2 8264 8204 -0.00659897 -0.0413976 0.00293218 1 0 1 1 0 0 +EDGE2 8264 8205 1.00066 0.0245296 -0.00489627 1 0 1 1 0 0 +EDGE2 8264 8245 0.998337 0.0586882 0.0316349 1 0 1 1 0 0 +EDGE2 8264 8225 1.02801 -0.108694 -0.0248441 1 0 1 1 0 0 +EDGE2 8265 8224 -0.963769 0.0370291 -0.0111927 1 0 1 1 0 0 +EDGE2 8265 8244 -1.01302 0.0135025 -0.00140744 1 0 1 1 0 0 +EDGE2 8265 8264 -0.974084 -0.0439592 -0.0229289 1 0 1 1 0 0 +EDGE2 8265 8204 -1.04532 -0.0089798 -0.00640024 1 0 1 1 0 0 +EDGE2 8265 8205 0.052543 0.0105352 -0.0364164 1 0 1 1 0 0 +EDGE2 8265 8245 0.103919 -0.0653499 -0.021 1 0 1 1 0 0 +EDGE2 8265 8225 -0.000712426 0.0214877 -0.0135598 1 0 1 1 0 0 +EDGE2 8265 8206 -0.0292819 1.06155 1.57258 1 0 1 1 0 0 +EDGE2 8265 8226 0.0413064 1.04298 1.58166 1 0 1 1 0 0 +EDGE2 8265 8246 -0.0219061 1.04588 1.59624 1 0 1 1 0 0 +EDGE2 8266 8265 -0.941288 0.0377711 1.57521 1 0 1 1 0 0 +EDGE2 8266 8205 -0.911723 -0.0849228 1.59459 1 0 1 1 0 0 +EDGE2 8266 8245 -0.994284 0.00143679 1.57715 1 0 1 1 0 0 +EDGE2 8266 8225 -0.919164 0.0623346 1.53849 1 0 1 1 0 0 +EDGE2 8267 8266 -1.00635 0.0144186 0.0154127 1 0 1 1 0 0 +EDGE2 8268 8267 -1.02718 -0.0427451 -0.0240116 1 0 1 1 0 0 +EDGE2 8269 8268 -0.954938 -0.0295167 0.00891609 1 0 1 1 0 0 +EDGE2 8270 8269 -0.956308 -0.0309418 -0.0173789 1 0 1 1 0 0 +EDGE2 8271 8270 -0.958236 0.0881535 -1.59202 1 0 1 1 0 0 +EDGE2 8272 8271 -0.968465 0.0441416 0.0106201 1 0 1 1 0 0 +EDGE2 8273 8272 -1.01766 -0.0401473 -0.0293362 1 0 1 1 0 0 +EDGE2 8274 8273 -1.09491 0.040008 -0.0123149 1 0 1 1 0 0 +EDGE2 8275 8274 -0.979035 -0.100183 -0.0118611 1 0 1 1 0 0 +EDGE2 8276 8275 -0.907223 -0.03755 -1.58917 1 0 1 1 0 0 +EDGE2 8277 8276 -0.982108 -0.0235209 0.00569364 1 0 1 1 0 0 +EDGE2 8278 8277 -1.00126 -0.0663184 0.0440823 1 0 1 1 0 0 +EDGE2 8279 8278 -0.90294 -0.00498535 -0.0205709 1 0 1 1 0 0 +EDGE2 8280 8279 -1.0293 -0.0606119 0.0214781 1 0 1 1 0 0 +EDGE2 8281 8280 -0.942716 0.0138954 1.56831 1 0 1 1 0 0 +EDGE2 8282 8281 -1.06258 -0.0782851 -0.00944337 1 0 1 1 0 0 +EDGE2 8283 8282 -1.03519 -0.0915626 0.0306426 1 0 1 1 0 0 +EDGE2 8284 8283 -0.977934 -0.000833582 0.0135372 1 0 1 1 0 0 +EDGE2 8285 8284 -0.901379 -0.00392534 0.0187161 1 0 1 1 0 0 +EDGE2 8286 8285 -1.06212 -0.0301747 -1.57878 1 0 1 1 0 0 +EDGE2 8287 8286 -1.03498 -0.0364718 0.00866562 1 0 1 1 0 0 +EDGE2 8288 8287 -0.976351 -0.0429503 -0.00090334 1 0 1 1 0 0 +EDGE2 8289 8288 -0.942311 -0.0219986 0.0390854 1 0 1 1 0 0 +EDGE2 8290 8289 -1.00788 0.105388 0.0055603 1 0 1 1 0 0 +EDGE2 8291 8290 -1.05655 -0.0846853 1.56023 1 0 1 1 0 0 +EDGE2 8292 8291 -1.00676 0.0447434 -0.0223746 1 0 1 1 0 0 +EDGE2 8293 8292 -0.931496 0.00493539 -0.0356157 1 0 1 1 0 0 +EDGE2 8294 8293 -0.994634 0.00138965 -0.0190524 1 0 1 1 0 0 +EDGE2 8295 8294 -0.995063 -0.00268073 -0.0127557 1 0 1 1 0 0 +EDGE2 8296 8295 -1.11734 0.103544 -1.60163 1 0 1 1 0 0 +EDGE2 8297 8296 -1.04018 0.063289 0.0118917 1 0 1 1 0 0 +EDGE2 8298 8297 -0.904813 0.0250052 0.013651 1 0 1 1 0 0 +EDGE2 8299 8298 -1.06455 -0.00535263 -0.0194254 1 0 1 1 0 0 +EDGE2 8300 8299 -1.00205 0.0722661 -0.00457142 1 0 1 1 0 0 +EDGE2 8301 8300 -0.942757 -0.0589266 -1.57767 1 0 1 1 0 0 +EDGE2 8302 8301 -1.01506 0.0260259 0.0300158 1 0 1 1 0 0 +EDGE2 8303 8302 -1.02648 -0.0188646 -0.0179536 1 0 1 1 0 0 +EDGE2 8304 8303 -0.990227 0.0846377 0.00338221 1 0 1 1 0 0 +EDGE2 8305 8304 -0.993032 -0.0859318 0.00552084 1 0 1 1 0 0 +EDGE2 8306 8305 -0.968649 -0.0351358 1.59151 1 0 1 1 0 0 +EDGE2 8307 8306 -0.997834 0.0114945 0.0234466 1 0 1 1 0 0 +EDGE2 8308 8307 -0.974851 -0.0283284 0.00301839 1 0 1 1 0 0 +EDGE2 8309 8308 -0.998559 -0.0314259 0.0259718 1 0 1 1 0 0 +EDGE2 8310 8309 -0.950282 0.00721874 0.0366262 1 0 1 1 0 0 +EDGE2 8311 8310 -0.963365 0.0282924 -1.58288 1 0 1 1 0 0 +EDGE2 8312 8311 -1.02475 0.0720977 0.0237202 1 0 1 1 0 0 +EDGE2 8313 8312 -1.00507 0.000667639 0.0131713 1 0 1 1 0 0 +EDGE2 8314 8313 -0.995006 0.0636671 -0.000592387 1 0 1 1 0 0 +EDGE2 8315 8314 -1.07412 -0.0753124 -0.0231628 1 0 1 1 0 0 +EDGE2 8316 8315 -1.00819 -0.0167909 1.55222 1 0 1 1 0 0 +EDGE2 8317 8316 -0.987344 0.019905 -0.0313365 1 0 1 1 0 0 +EDGE2 8318 8317 -1.07677 0.00742557 0.00817737 1 0 1 1 0 0 +EDGE2 8319 8318 -1.03285 0.0704269 0.00755632 1 0 1 1 0 0 +EDGE2 8320 8319 -1.03817 -0.0650128 0.0191244 1 0 1 1 0 0 +EDGE2 8321 8320 -0.98758 -0.0978291 -1.5436 1 0 1 1 0 0 +EDGE2 8322 8321 -0.956268 0.0428623 0.0167698 1 0 1 1 0 0 +EDGE2 8323 8322 -0.981266 -0.0247861 0.0158988 1 0 1 1 0 0 +EDGE2 8324 8323 -1.0463 0.0331779 0.0105042 1 0 1 1 0 0 +EDGE2 8325 8324 -1.0314 0.00599357 -0.00246025 1 0 1 1 0 0 +EDGE2 8326 8325 -0.982981 -0.0347377 -1.55212 1 0 1 1 0 0 +EDGE2 8327 8326 -1.00482 0.00207504 0.0104544 1 0 1 1 0 0 +EDGE2 8328 8327 -0.962502 -0.0427496 -0.0089812 1 0 1 1 0 0 +EDGE2 8329 8328 -1.0715 -0.0548881 0.0150549 1 0 1 1 0 0 +EDGE2 8330 8329 -1.06461 -0.0320611 -0.00855143 1 0 1 1 0 0 +EDGE2 8331 8330 -0.99318 0.0673534 1.59307 1 0 1 1 0 0 +EDGE2 8332 8331 -1.05717 -0.0942832 -0.0289624 1 0 1 1 0 0 +EDGE2 8333 8332 -0.988874 -0.00610679 0.0202065 1 0 1 1 0 0 +EDGE2 8334 8333 -0.985325 0.0288358 -0.0145982 1 0 1 1 0 0 +EDGE2 8334 1035 0.983726 -0.00626209 -3.11685 1 0 1 1 0 0 +EDGE2 8335 1034 0.926488 0.0163502 -3.16581 1 0 1 1 0 0 +EDGE2 8335 1035 -0.0845504 0.0303833 -3.16057 1 0 1 1 0 0 +EDGE2 8335 8334 -1.01473 0.0405399 -0.0226731 1 0 1 1 0 0 +EDGE2 8335 1036 -0.00100295 -1.0201 -1.56764 1 0 1 1 0 0 +EDGE2 8336 1035 -0.938732 0.026625 -1.56629 1 0 1 1 0 0 +EDGE2 8336 8335 -1.04168 -0.0133955 1.55947 1 0 1 1 0 0 +EDGE2 8336 1036 -0.0628938 -0.00113116 0.0215106 1 0 1 1 0 0 +EDGE2 8336 1037 1.11127 0.00282963 0.030959 1 0 1 1 0 0 +EDGE2 8337 8336 -1.00494 0.057215 -0.0274568 1 0 1 1 0 0 +EDGE2 8337 1036 -0.965457 -0.0814007 -0.0177097 1 0 1 1 0 0 +EDGE2 8337 1037 0.0789457 -0.0287872 -0.0216048 1 0 1 1 0 0 +EDGE2 8337 1038 0.984362 0.0460225 -0.00674179 1 0 1 1 0 0 +EDGE2 8338 1037 -0.904236 -0.0366908 -0.0100138 1 0 1 1 0 0 +EDGE2 8338 8337 -1.03598 0.0433897 -0.0136407 1 0 1 1 0 0 +EDGE2 8338 1038 -0.0257328 0.0279855 0.0150889 1 0 1 1 0 0 +EDGE2 8338 1039 1.02173 0.0371314 -0.00162779 1 0 1 1 0 0 +EDGE2 8339 1038 -0.988109 -0.0307751 0.0121538 1 0 1 1 0 0 +EDGE2 8339 8338 -1.00469 0.0100636 0.00261918 1 0 1 1 0 0 +EDGE2 8339 1039 -0.0531329 -0.0572392 0.0324824 1 0 1 1 0 0 +EDGE2 8339 1040 1.03813 -0.0936912 -0.00919118 1 0 1 1 0 0 +EDGE2 8340 8339 -1.02501 0.00447523 -0.0102251 1 0 1 1 0 0 +EDGE2 8340 1039 -1.02938 0.016173 0.0225113 1 0 1 1 0 0 +EDGE2 8340 1041 -0.0283151 0.97386 1.56678 1 0 1 1 0 0 +EDGE2 8340 1040 -0.0144916 0.048323 -0.0267287 1 0 1 1 0 0 +EDGE2 8341 1041 0.0032282 0.057391 0.00184323 1 0 1 1 0 0 +EDGE2 8341 1042 0.999957 -0.0293606 -0.0244859 1 0 1 1 0 0 +EDGE2 8341 1040 -1.00816 0.0201555 -1.55255 1 0 1 1 0 0 +EDGE2 8341 8340 -0.95863 0.0132967 -1.56174 1 0 1 1 0 0 +EDGE2 8342 1043 1.01547 0.102641 -0.0277315 1 0 1 1 0 0 +EDGE2 8342 1041 -0.887899 -0.00392176 0.0158988 1 0 1 1 0 0 +EDGE2 8342 1042 -0.00602448 -0.0388916 0.0265587 1 0 1 1 0 0 +EDGE2 8342 8341 -0.9743 -0.031599 -0.00507944 1 0 1 1 0 0 +EDGE2 8343 1044 0.944621 0.0210264 0.000728439 1 0 1 1 0 0 +EDGE2 8343 1043 0.0388755 0.073532 0.000643332 1 0 1 1 0 0 +EDGE2 8343 1042 -1.01152 0.0513177 -0.0189371 1 0 1 1 0 0 +EDGE2 8343 8342 -1.06426 0.0204107 0.0211063 1 0 1 1 0 0 +EDGE2 8344 1045 0.950022 -0.0168195 0.0306276 1 0 1 1 0 0 +EDGE2 8344 1085 0.928894 0.0676654 -3.14144 1 0 1 1 0 0 +EDGE2 8344 5865 1.0866 -0.0346888 -3.16045 1 0 1 1 0 0 +EDGE2 8344 8343 -0.99789 0.039264 0.02358 1 0 1 1 0 0 +EDGE2 8344 1044 -0.0490418 -0.0328354 -0.0281196 1 0 1 1 0 0 +EDGE2 8344 1043 -0.967207 0.0589531 0.0300279 1 0 1 1 0 0 +EDGE2 8345 1046 0.040975 1.05292 1.59469 1 0 1 1 0 0 +EDGE2 8345 1084 1.0144 -0.0310385 -3.15911 1 0 1 1 0 0 +EDGE2 8345 5864 0.957501 0.0107063 -3.13837 1 0 1 1 0 0 +EDGE2 8345 8344 -1.01933 0.00583485 0.00723054 1 0 1 1 0 0 +EDGE2 8345 1045 0.0146836 -0.0165311 -0.00190273 1 0 1 1 0 0 +EDGE2 8345 1085 0.0639143 0.000882311 -3.15175 1 0 1 1 0 0 +EDGE2 8345 5865 0.00158965 -0.0320786 -3.12373 1 0 1 1 0 0 +EDGE2 8345 1044 -1.05398 -0.0133895 -0.00322953 1 0 1 1 0 0 +EDGE2 8345 1086 -0.0460747 -1.0137 -1.54343 1 0 1 1 0 0 +EDGE2 8345 5866 0.0341834 -1.08939 -1.57678 1 0 1 1 0 0 +EDGE2 8346 8345 -0.954924 -0.105969 1.56561 1 0 1 1 0 0 +EDGE2 8346 1045 -0.907399 0.0960528 1.54317 1 0 1 1 0 0 +EDGE2 8346 1085 -0.970203 -0.0109747 -1.55899 1 0 1 1 0 0 +EDGE2 8346 5865 -1.02914 -0.0726188 -1.61973 1 0 1 1 0 0 +EDGE2 8346 1086 0.00846889 0.0051395 0.022444 1 0 1 1 0 0 +EDGE2 8346 5866 0.0534146 -0.0472595 -0.0298847 1 0 1 1 0 0 +EDGE2 8346 5867 1.03258 -0.00261546 -0.0251514 1 0 1 1 0 0 +EDGE2 8346 1087 0.95803 -0.0856145 -0.00303461 1 0 1 1 0 0 +EDGE2 8347 8346 -1.0036 0.144212 0.00130264 1 0 1 1 0 0 +EDGE2 8347 1086 -0.934275 0.0271149 -0.0275958 1 0 1 1 0 0 +EDGE2 8347 5866 -1.01564 0.0297299 -0.00958669 1 0 1 1 0 0 +EDGE2 8347 5867 -0.0570014 -0.072246 -0.0427802 1 0 1 1 0 0 +EDGE2 8347 1087 -0.031044 0.0169927 -0.0219167 1 0 1 1 0 0 +EDGE2 8347 1088 1.07886 -0.04191 0.0132917 1 0 1 1 0 0 +EDGE2 8347 5868 1.00523 0.0309544 -0.0115291 1 0 1 1 0 0 +EDGE2 8348 5867 -0.979411 0.000760254 0.0216006 1 0 1 1 0 0 +EDGE2 8348 8347 -1.11359 0.0869817 -0.00552279 1 0 1 1 0 0 +EDGE2 8348 1087 -0.971593 0.156865 0.0122839 1 0 1 1 0 0 +EDGE2 8348 1088 -0.0713286 -0.0256676 -0.00915465 1 0 1 1 0 0 +EDGE2 8348 5868 0.0186402 -0.0255858 0.00204412 1 0 1 1 0 0 +EDGE2 8348 5869 0.971789 0.0199849 -0.0182341 1 0 1 1 0 0 +EDGE2 8348 1089 0.992336 -0.0334895 0.0101399 1 0 1 1 0 0 +EDGE2 8349 8348 -0.975686 0.00049856 -0.000590149 1 0 1 1 0 0 +EDGE2 8349 1088 -1.05631 -0.0180865 -0.00208703 1 0 1 1 0 0 +EDGE2 8349 5868 -1.03902 0.0837221 -0.00916629 1 0 1 1 0 0 +EDGE2 8349 5869 -0.0480763 0.0399073 -0.0228665 1 0 1 1 0 0 +EDGE2 8349 1089 0.0512875 -0.0797507 -0.0235099 1 0 1 1 0 0 +EDGE2 8349 5870 1.01538 0.00921775 0.0216227 1 0 1 1 0 0 +EDGE2 8349 1090 1.04995 0.0238249 -0.0315456 1 0 1 1 0 0 +EDGE2 8350 5869 -1.00395 -0.0809268 -0.0138427 1 0 1 1 0 0 +EDGE2 8350 8349 -0.97623 -0.0291937 0.0198145 1 0 1 1 0 0 +EDGE2 8350 1089 -1.01831 -0.00904495 0.0214068 1 0 1 1 0 0 +EDGE2 8350 1091 0.0156836 0.99497 1.56967 1 0 1 1 0 0 +EDGE2 8350 5871 -0.00286664 0.934753 1.53636 1 0 1 1 0 0 +EDGE2 8350 5870 -0.0854526 0.00782048 0.00982462 1 0 1 1 0 0 +EDGE2 8350 1090 -0.0603779 -0.0299098 0.00618456 1 0 1 1 0 0 +EDGE2 8351 1092 1.02028 -0.0444514 0.0136552 1 0 1 1 0 0 +EDGE2 8351 5872 0.981263 0.0082774 -0.0410109 1 0 1 1 0 0 +EDGE2 8351 1091 0.0132943 -0.0844699 0.0321715 1 0 1 1 0 0 +EDGE2 8351 5871 0.0292027 0.00167344 0.0166416 1 0 1 1 0 0 +EDGE2 8351 5870 -0.969995 -0.000547753 -1.57956 1 0 1 1 0 0 +EDGE2 8351 8350 -0.955348 0.0471393 -1.64242 1 0 1 1 0 0 +EDGE2 8351 1090 -0.991657 0.0582602 -1.5883 1 0 1 1 0 0 +EDGE2 8352 1092 0.0246491 0.059912 0.0413933 1 0 1 1 0 0 +EDGE2 8352 1093 1.03343 -0.101639 0.00360336 1 0 1 1 0 0 +EDGE2 8352 5873 1.04491 -0.0141495 0.0140547 1 0 1 1 0 0 +EDGE2 8352 5872 -0.0154579 -0.0788412 -0.00430099 1 0 1 1 0 0 +EDGE2 8352 8351 -1.02032 0.0481468 0.000148868 1 0 1 1 0 0 +EDGE2 8352 1091 -0.919984 0.00176231 -0.0197748 1 0 1 1 0 0 +EDGE2 8352 5871 -1.01977 0.063395 0.0408042 1 0 1 1 0 0 +EDGE2 8353 1092 -1.08548 -0.0554088 0.0391622 1 0 1 1 0 0 +EDGE2 8353 1094 1.03987 -0.0505809 -0.0110408 1 0 1 1 0 0 +EDGE2 8353 5874 0.991492 -0.0353811 -0.00330635 1 0 1 1 0 0 +EDGE2 8353 1093 0.00958209 0.0393288 0.00744628 1 0 1 1 0 0 +EDGE2 8353 5873 -0.0185244 0.00333488 -0.0147977 1 0 1 1 0 0 +EDGE2 8353 8352 -1.02559 0.0639091 -0.0127421 1 0 1 1 0 0 +EDGE2 8353 5872 -1.02477 0.0126999 0.00253497 1 0 1 1 0 0 +EDGE2 8354 5795 1.07504 -0.0184847 -3.13615 1 0 1 1 0 0 +EDGE2 8354 5875 0.975747 -0.0617497 0.0126418 1 0 1 1 0 0 +EDGE2 8354 5855 1.00566 0.0960294 -3.13584 1 0 1 1 0 0 +EDGE2 8354 3035 1.02259 0.0610321 -3.11769 1 0 1 1 0 0 +EDGE2 8354 3055 1.01297 -0.0187142 -3.13255 1 0 1 1 0 0 +EDGE2 8354 1095 0.97008 0.0365256 -0.0010313 1 0 1 1 0 0 +EDGE2 8354 1115 0.944079 0.0241147 -3.13621 1 0 1 1 0 0 +EDGE2 8354 1135 0.990434 0.0216261 -3.17186 1 0 1 1 0 0 +EDGE2 8354 8353 -0.998391 -0.0508572 0.00355966 1 0 1 1 0 0 +EDGE2 8354 1094 0.054814 0.0388071 0.00223324 1 0 1 1 0 0 +EDGE2 8354 5874 0.0124544 0.0743778 0.00957391 1 0 1 1 0 0 +EDGE2 8354 1093 -0.955711 -0.0374386 0.00067968 1 0 1 1 0 0 +EDGE2 8354 5873 -1.08889 0.030265 -0.020164 1 0 1 1 0 0 +EDGE2 8355 5795 -0.0669622 -0.0160392 -3.14223 1 0 1 1 0 0 +EDGE2 8355 5856 -0.00695653 0.935118 1.54986 1 0 1 1 0 0 +EDGE2 8355 5876 -0.00295778 0.942286 1.56755 1 0 1 1 0 0 +EDGE2 8355 3056 0.0441219 0.958686 1.57197 1 0 1 1 0 0 +EDGE2 8355 5794 0.931276 0.0367122 -3.12844 1 0 1 1 0 0 +EDGE2 8355 5854 1.06486 -0.0374804 -3.12423 1 0 1 1 0 0 +EDGE2 8355 1134 1.0129 -0.0862321 -3.13839 1 0 1 1 0 0 +EDGE2 8355 3034 1.04231 -0.15573 -3.1534 1 0 1 1 0 0 +EDGE2 8355 3054 0.977734 -0.000341297 -3.15257 1 0 1 1 0 0 +EDGE2 8355 1114 1.07347 0.0131571 -3.14801 1 0 1 1 0 0 +EDGE2 8355 5875 0.0456671 0.0279634 0.00665564 1 0 1 1 0 0 +EDGE2 8355 5855 -0.0276585 -0.0501733 -3.11786 1 0 1 1 0 0 +EDGE2 8355 3035 -0.0402656 -0.0697378 -3.17758 1 0 1 1 0 0 +EDGE2 8355 3055 0.111374 0.0268501 -3.09834 1 0 1 1 0 0 +EDGE2 8355 1095 0.0265923 0.0427477 0.0310679 1 0 1 1 0 0 +EDGE2 8355 1115 -0.0243167 0.0483864 -3.1455 1 0 1 1 0 0 +EDGE2 8355 1135 0.00986823 -0.0089143 -3.10865 1 0 1 1 0 0 +EDGE2 8355 1094 -0.957242 -0.0675052 0.00523016 1 0 1 1 0 0 +EDGE2 8355 8354 -1.019 0.0415643 0.0299274 1 0 1 1 0 0 +EDGE2 8355 5874 -1.05761 -0.109291 0.00411046 1 0 1 1 0 0 +EDGE2 8355 1116 -0.0186205 -1.01389 -1.57488 1 0 1 1 0 0 +EDGE2 8355 3036 0.065099 -1.07075 -1.5718 1 0 1 1 0 0 +EDGE2 8355 5796 0.0144618 -1.07297 -1.56015 1 0 1 1 0 0 +EDGE2 8355 1136 -0.131614 -1.00064 -1.54671 1 0 1 1 0 0 +EDGE2 8355 1096 -0.077958 -0.925835 -1.5649 1 0 1 1 0 0 +EDGE2 8356 5795 -1.0206 -0.0677107 1.60558 1 0 1 1 0 0 +EDGE2 8356 5877 0.920314 -0.00772245 -0.00824135 1 0 1 1 0 0 +EDGE2 8356 3057 1.06275 0.0319148 -0.00711023 1 0 1 1 0 0 +EDGE2 8356 5857 1.05213 0.00488905 0.0264737 1 0 1 1 0 0 +EDGE2 8356 5856 0.0344168 -0.0384883 0.00434067 1 0 1 1 0 0 +EDGE2 8356 5876 -0.00591577 0.016045 0.00438459 1 0 1 1 0 0 +EDGE2 8356 3056 -0.0129947 -0.0118143 0.00874494 1 0 1 1 0 0 +EDGE2 8356 5875 -1.02786 0.0222731 -1.59387 1 0 1 1 0 0 +EDGE2 8356 8355 -0.961041 -0.0335467 -1.58725 1 0 1 1 0 0 +EDGE2 8356 5855 -0.995425 -0.050431 1.56688 1 0 1 1 0 0 +EDGE2 8356 3035 -0.951584 0.0059293 1.57359 1 0 1 1 0 0 +EDGE2 8356 3055 -1.03091 -0.0325046 1.5465 1 0 1 1 0 0 +EDGE2 8356 1095 -1.05043 -0.0532849 -1.56668 1 0 1 1 0 0 +EDGE2 8356 1115 -0.978317 0.0118994 1.58522 1 0 1 1 0 0 +EDGE2 8356 1135 -1.00268 0.00181713 1.58608 1 0 1 1 0 0 +EDGE2 8357 3058 1.08251 0.00269528 -0.0115601 1 0 1 1 0 0 +EDGE2 8357 5858 1.00844 -0.0356759 0.0124239 1 0 1 1 0 0 +EDGE2 8357 5878 1.03876 -0.0438051 0.0278551 1 0 1 1 0 0 +EDGE2 8357 5877 -0.00509555 0.0329855 -0.00312811 1 0 1 1 0 0 +EDGE2 8357 3057 -0.00968417 -0.026897 -0.0269164 1 0 1 1 0 0 +EDGE2 8357 5857 -0.0251177 -0.14691 -0.0127888 1 0 1 1 0 0 +EDGE2 8357 8356 -0.895946 0.0289358 -0.0111657 1 0 1 1 0 0 +EDGE2 8357 5856 -0.962524 -0.0360048 -0.0173083 1 0 1 1 0 0 +EDGE2 8357 5876 -1.0092 -0.0100442 0.0117263 1 0 1 1 0 0 +EDGE2 8357 3056 -0.997683 0.0196381 0.00194269 1 0 1 1 0 0 +EDGE2 8358 5859 1.00899 0.048405 -0.0334763 1 0 1 1 0 0 +EDGE2 8358 5879 1.04498 0.00647456 0.0233711 1 0 1 1 0 0 +EDGE2 8358 3059 0.880133 -0.0221063 -0.0133388 1 0 1 1 0 0 +EDGE2 8358 3058 -0.0750112 -0.00497134 0.0163077 1 0 1 1 0 0 +EDGE2 8358 5858 0.0308309 -0.0282612 0.00186476 1 0 1 1 0 0 +EDGE2 8358 5878 -0.0369614 -0.0678813 -0.0112113 1 0 1 1 0 0 +EDGE2 8358 5877 -1.07664 0.0111854 -0.0164359 1 0 1 1 0 0 +EDGE2 8358 8357 -1.03125 -0.0040641 -0.0353455 1 0 1 1 0 0 +EDGE2 8358 3057 -1.05466 -0.0644414 -0.0465858 1 0 1 1 0 0 +EDGE2 8358 5857 -0.909559 0.021725 -0.0062589 1 0 1 1 0 0 +EDGE2 8359 3060 0.96123 0.0382903 -0.0129605 1 0 1 1 0 0 +EDGE2 8359 3160 0.974469 0.0814619 -3.1475 1 0 1 1 0 0 +EDGE2 8359 5860 0.978885 -0.0366526 0.00102912 1 0 1 1 0 0 +EDGE2 8359 5880 0.943371 -0.0386481 0.00985189 1 0 1 1 0 0 +EDGE2 8359 3080 0.927189 0.00718515 -3.18998 1 0 1 1 0 0 +EDGE2 8359 1080 1.06595 -0.046778 -3.17143 1 0 1 1 0 0 +EDGE2 8359 5859 0.00637283 0.0114403 0.00315414 1 0 1 1 0 0 +EDGE2 8359 5879 -0.0510442 0.0685943 -0.012232 1 0 1 1 0 0 +EDGE2 8359 3059 -0.0333005 0.00817277 0.00504925 1 0 1 1 0 0 +EDGE2 8359 8358 -0.858077 -0.0697078 -0.02797 1 0 1 1 0 0 +EDGE2 8359 3058 -0.993405 -0.0499889 0.00718726 1 0 1 1 0 0 +EDGE2 8359 5858 -0.939192 0.0929881 0.0279696 1 0 1 1 0 0 +EDGE2 8359 5878 -1.01327 0.00723679 0.0102709 1 0 1 1 0 0 +EDGE2 8360 3079 1.00344 -0.0243739 -3.15087 1 0 1 1 0 0 +EDGE2 8360 3159 1.05096 0.0168403 -3.1284 1 0 1 1 0 0 +EDGE2 8360 1079 1.06428 0.00420741 -3.12355 1 0 1 1 0 0 +EDGE2 8360 3081 -0.00346154 -0.921559 -1.59611 1 0 1 1 0 0 +EDGE2 8360 3161 -0.0241538 -0.981422 -1.56922 1 0 1 1 0 0 +EDGE2 8360 5881 -0.0624179 -1.04233 -1.54624 1 0 1 1 0 0 +EDGE2 8360 3061 -0.00662078 -1.03971 -1.56566 1 0 1 1 0 0 +EDGE2 8360 3060 0.0298069 -0.0934244 0.00369895 1 0 1 1 0 0 +EDGE2 8360 3160 0.0672475 0.00552454 -3.14581 1 0 1 1 0 0 +EDGE2 8360 5860 0.0208315 -0.0950223 0.0187945 1 0 1 1 0 0 +EDGE2 8360 5880 -0.07768 -0.0166747 0.0420726 1 0 1 1 0 0 +EDGE2 8360 3080 0.0205906 -0.00979243 -3.13376 1 0 1 1 0 0 +EDGE2 8360 1080 0.00640517 -0.0246162 -3.11565 1 0 1 1 0 0 +EDGE2 8360 1081 -0.0363262 0.973675 1.61042 1 0 1 1 0 0 +EDGE2 8360 5861 -0.0711699 1.02579 1.57289 1 0 1 1 0 0 +EDGE2 8360 5859 -1.11884 -0.0660198 -0.0100763 1 0 1 1 0 0 +EDGE2 8360 5879 -1.03245 -0.0500429 -0.00784783 1 0 1 1 0 0 +EDGE2 8360 8359 -0.951719 0.0230065 -0.022809 1 0 1 1 0 0 +EDGE2 8360 3059 -1.01654 0.0280306 0.0147095 1 0 1 1 0 0 +EDGE2 8361 8360 -0.948935 -0.0409575 1.56224 1 0 1 1 0 0 +EDGE2 8361 3082 1.05009 0.0368091 0.00213906 1 0 1 1 0 0 +EDGE2 8361 3162 1.05267 -0.0193065 -0.00342268 1 0 1 1 0 0 +EDGE2 8361 5882 0.966903 0.0129328 0.00447288 1 0 1 1 0 0 +EDGE2 8361 3062 1.02508 0.0115709 0.016656 1 0 1 1 0 0 +EDGE2 8361 3081 -0.0445139 0.0302517 0.00428872 1 0 1 1 0 0 +EDGE2 8361 3161 0.0173461 0.0723755 -0.0206553 1 0 1 1 0 0 +EDGE2 8361 5881 0.022966 -0.0168941 -0.00753164 1 0 1 1 0 0 +EDGE2 8361 3061 0.0340495 -0.0332258 -0.0186316 1 0 1 1 0 0 +EDGE2 8361 3060 -0.867634 0.0669599 1.57841 1 0 1 1 0 0 +EDGE2 8361 3160 -0.973133 0.0277637 -1.57799 1 0 1 1 0 0 +EDGE2 8361 5860 -1.0834 -0.0508176 1.53212 1 0 1 1 0 0 +EDGE2 8361 5880 -1.00406 -0.0442579 1.57053 1 0 1 1 0 0 +EDGE2 8361 3080 -0.961108 -0.00894358 -1.56005 1 0 1 1 0 0 +EDGE2 8361 1080 -0.964247 -0.00309066 -1.56955 1 0 1 1 0 0 +EDGE2 8362 3083 1.06186 0.013665 -0.0110525 1 0 1 1 0 0 +EDGE2 8362 3163 1.01026 0.0719865 0.0610941 1 0 1 1 0 0 +EDGE2 8362 5883 0.971012 -0.0267049 0.0152942 1 0 1 1 0 0 +EDGE2 8362 3063 1.00804 -0.00256671 -0.0157866 1 0 1 1 0 0 +EDGE2 8362 3082 0.0037228 0.0641659 -0.0435776 1 0 1 1 0 0 +EDGE2 8362 3162 -0.0136154 0.0120505 -0.0211345 1 0 1 1 0 0 +EDGE2 8362 5882 -0.0263777 0.0550672 0.0132726 1 0 1 1 0 0 +EDGE2 8362 3062 -0.00370079 0.0258113 0.0127268 1 0 1 1 0 0 +EDGE2 8362 8361 -1.00799 0.00564234 0.0156002 1 0 1 1 0 0 +EDGE2 8362 3081 -0.979528 0.0580985 -0.0254157 1 0 1 1 0 0 +EDGE2 8362 3161 -1.03181 0.0546613 -0.00118323 1 0 1 1 0 0 +EDGE2 8362 5881 -0.998859 0.00751679 -0.00514662 1 0 1 1 0 0 +EDGE2 8362 3061 -0.88301 -0.0419704 -0.00614184 1 0 1 1 0 0 +EDGE2 8363 3064 0.960936 -0.0507922 0.0145812 1 0 1 1 0 0 +EDGE2 8363 3164 0.969488 0.109309 0.000379516 1 0 1 1 0 0 +EDGE2 8363 5884 1.02159 -0.0465672 -0.0453088 1 0 1 1 0 0 +EDGE2 8363 3084 0.937429 0.0644956 -0.0306316 1 0 1 1 0 0 +EDGE2 8363 3083 0.0983464 0.00995207 -0.0197097 1 0 1 1 0 0 +EDGE2 8363 3163 0.0072796 -0.0105187 0.0286424 1 0 1 1 0 0 +EDGE2 8363 5883 -0.09258 0.0827895 0.0235548 1 0 1 1 0 0 +EDGE2 8363 3063 0.0242706 0.0469543 0.017293 1 0 1 1 0 0 +EDGE2 8363 8362 -1.05153 -0.0120179 0.0108657 1 0 1 1 0 0 +EDGE2 8363 3082 -1.00621 0.0436931 -0.0388398 1 0 1 1 0 0 +EDGE2 8363 3162 -0.976907 0.0422587 -0.0120935 1 0 1 1 0 0 +EDGE2 8363 5882 -0.972381 -0.0266282 -0.023573 1 0 1 1 0 0 +EDGE2 8363 3062 -1.05249 0.0376873 -0.00261131 1 0 1 1 0 0 +EDGE2 8364 3105 0.9823 0.09468 -3.15235 1 0 1 1 0 0 +EDGE2 8364 3485 1.08186 -0.0134979 -3.15196 1 0 1 1 0 0 +EDGE2 8364 5845 1.03711 0.0248295 -3.17392 1 0 1 1 0 0 +EDGE2 8364 5885 1.04157 -0.0171231 0.00938816 1 0 1 1 0 0 +EDGE2 8364 5825 0.982016 0.084249 -3.08616 1 0 1 1 0 0 +EDGE2 8364 3145 0.980252 -0.0860361 -3.16571 1 0 1 1 0 0 +EDGE2 8364 3165 0.941675 0.0533194 -0.00636664 1 0 1 1 0 0 +EDGE2 8364 3385 0.91028 -0.0845184 -3.16635 1 0 1 1 0 0 +EDGE2 8364 3125 0.979669 -0.0215459 -3.17151 1 0 1 1 0 0 +EDGE2 8364 1185 0.988475 -0.0180099 -3.14559 1 0 1 1 0 0 +EDGE2 8364 3065 0.910008 0.0162993 -0.00551151 1 0 1 1 0 0 +EDGE2 8364 3085 0.904436 0.0316895 0.0122023 1 0 1 1 0 0 +EDGE2 8364 1165 0.937446 0.0962993 -3.13749 1 0 1 1 0 0 +EDGE2 8364 3064 0.0100713 0.128239 0.00553831 1 0 1 1 0 0 +EDGE2 8364 3164 -0.0435665 0.0406291 0.000736719 1 0 1 1 0 0 +EDGE2 8364 5884 -0.111342 -0.0218738 0.0108543 1 0 1 1 0 0 +EDGE2 8364 3084 0.0230821 0.0676411 0.0287139 1 0 1 1 0 0 +EDGE2 8364 8363 -1.04685 -0.0268862 0.0136046 1 0 1 1 0 0 +EDGE2 8364 3083 -1.05774 0.0895436 0.00266362 1 0 1 1 0 0 +EDGE2 8364 3163 -0.861769 -0.00683727 -0.0144179 1 0 1 1 0 0 +EDGE2 8364 5883 -1.03305 0.0217901 0.0175587 1 0 1 1 0 0 +EDGE2 8364 3063 -0.922589 0.00137249 0.0393932 1 0 1 1 0 0 +EDGE2 8365 3146 0.060202 0.971162 1.56633 1 0 1 1 0 0 +EDGE2 8365 3386 -0.0785986 0.959516 1.58141 1 0 1 1 0 0 +EDGE2 8365 5886 -0.00787269 0.993204 1.57693 1 0 1 1 0 0 +EDGE2 8365 3066 -0.0416487 0.992335 1.55937 1 0 1 1 0 0 +EDGE2 8365 3144 1.04178 -0.00379803 -3.1303 1 0 1 1 0 0 +EDGE2 8365 3484 0.94384 0.103057 -3.1368 1 0 1 1 0 0 +EDGE2 8365 5824 0.968156 0.00290282 -3.16799 1 0 1 1 0 0 +EDGE2 8365 5844 0.998964 -0.0179187 -3.13288 1 0 1 1 0 0 +EDGE2 8365 3384 1.04598 -0.0650497 -3.1273 1 0 1 1 0 0 +EDGE2 8365 1184 0.974151 0.0201211 -3.14161 1 0 1 1 0 0 +EDGE2 8365 3104 0.989303 0.0857108 -3.17814 1 0 1 1 0 0 +EDGE2 8365 3124 0.970258 0.0351069 -3.15723 1 0 1 1 0 0 +EDGE2 8365 1164 0.968493 0.0420295 -3.16423 1 0 1 1 0 0 +EDGE2 8365 3166 -0.0288423 -1.08284 -1.55741 1 0 1 1 0 0 +EDGE2 8365 3105 -0.00150997 0.0210769 -3.14806 1 0 1 1 0 0 +EDGE2 8365 3485 -0.00809488 -0.042407 -3.13821 1 0 1 1 0 0 +EDGE2 8365 5845 -0.00780475 0.0357314 -3.1557 1 0 1 1 0 0 +EDGE2 8365 5885 0.0691255 0.0710438 -0.0645527 1 0 1 1 0 0 +EDGE2 8365 5825 -0.0427686 -0.0704206 -3.1361 1 0 1 1 0 0 +EDGE2 8365 3145 0.0438398 0.0765512 -3.13734 1 0 1 1 0 0 +EDGE2 8365 3165 0.00808329 0.0889539 0.00522607 1 0 1 1 0 0 +EDGE2 8365 3385 0.00201987 -0.0171066 -3.13729 1 0 1 1 0 0 +EDGE2 8365 3125 -0.0618322 0.0584497 -3.11343 1 0 1 1 0 0 +EDGE2 8365 1185 0.0123753 0.0170229 -3.13306 1 0 1 1 0 0 +EDGE2 8365 3065 -0.033651 0.0980071 0.0125513 1 0 1 1 0 0 +EDGE2 8365 3085 0.0094831 -0.0835472 0.02718 1 0 1 1 0 0 +EDGE2 8365 1165 -0.0583318 0.0545657 -3.16422 1 0 1 1 0 0 +EDGE2 8365 5826 0.000476004 -1.06532 -1.58458 1 0 1 1 0 0 +EDGE2 8365 5846 -0.0649247 -0.974559 -1.55722 1 0 1 1 0 0 +EDGE2 8365 3486 0.0396845 -1.01838 -1.59059 1 0 1 1 0 0 +EDGE2 8365 1166 -0.0283847 -1.00612 -1.58701 1 0 1 1 0 0 +EDGE2 8365 3086 0.0125482 -1.05683 -1.57892 1 0 1 1 0 0 +EDGE2 8365 3106 -0.0416894 -1.12551 -1.59279 1 0 1 1 0 0 +EDGE2 8365 3126 -0.0242734 -1.00436 -1.55966 1 0 1 1 0 0 +EDGE2 8365 1186 -0.0662879 -1.03614 -1.57064 1 0 1 1 0 0 +EDGE2 8365 3064 -0.947085 0.0176467 0.0176098 1 0 1 1 0 0 +EDGE2 8365 3164 -1.01113 0.00131755 -0.00672299 1 0 1 1 0 0 +EDGE2 8365 5884 -0.939048 -0.0371394 0.00895697 1 0 1 1 0 0 +EDGE2 8365 8364 -1.06047 0.012212 0.0262684 1 0 1 1 0 0 +EDGE2 8365 3084 -0.888647 -0.0149354 -0.00511329 1 0 1 1 0 0 +EDGE2 8366 3147 0.968208 -0.0733045 0.0126602 1 0 1 1 0 0 +EDGE2 8366 5887 1.04649 0.0115634 -0.0194502 1 0 1 1 0 0 +EDGE2 8366 3387 0.921888 -0.0106028 0.0051563 1 0 1 1 0 0 +EDGE2 8366 3067 0.982044 -0.001606 -0.00677339 1 0 1 1 0 0 +EDGE2 8366 3146 0.0204285 -0.0661794 0.00975276 1 0 1 1 0 0 +EDGE2 8366 3386 0.0666533 0.056182 0.00636953 1 0 1 1 0 0 +EDGE2 8366 5886 0.00881809 0.0371512 0.0153576 1 0 1 1 0 0 +EDGE2 8366 3066 -0.0127713 -0.0654988 -0.0316904 1 0 1 1 0 0 +EDGE2 8366 3105 -1.03338 0.0169455 1.59759 1 0 1 1 0 0 +EDGE2 8366 3485 -1.02606 0.0636591 1.57956 1 0 1 1 0 0 +EDGE2 8366 5845 -1.04175 -1.95537e-05 1.54475 1 0 1 1 0 0 +EDGE2 8366 5885 -0.951925 -0.0327463 -1.56609 1 0 1 1 0 0 +EDGE2 8366 8365 -1.02907 0.0183432 -1.57669 1 0 1 1 0 0 +EDGE2 8366 5825 -0.923971 -0.0385715 1.57151 1 0 1 1 0 0 +EDGE2 8366 3145 -0.98212 -0.0885231 1.59189 1 0 1 1 0 0 +EDGE2 8366 3165 -0.998988 -0.0636465 -1.59179 1 0 1 1 0 0 +EDGE2 8366 3385 -0.829953 0.00685682 1.56874 1 0 1 1 0 0 +EDGE2 8366 3125 -1.05334 0.0446135 1.59742 1 0 1 1 0 0 +EDGE2 8366 1185 -1.01506 0.0164292 1.58966 1 0 1 1 0 0 +EDGE2 8366 3065 -0.930767 -0.0131103 -1.57934 1 0 1 1 0 0 +EDGE2 8366 3085 -0.916145 0.0294138 -1.5902 1 0 1 1 0 0 +EDGE2 8366 1165 -1.00545 -0.0465997 1.60117 1 0 1 1 0 0 +EDGE2 8367 8366 -0.969396 -0.0288771 0.000638175 1 0 1 1 0 0 +EDGE2 8367 5888 0.964469 0.00868499 -0.00957197 1 0 1 1 0 0 +EDGE2 8367 3068 0.905052 0.037747 0.0130307 1 0 1 1 0 0 +EDGE2 8367 3148 0.982623 0.0603404 -0.0110758 1 0 1 1 0 0 +EDGE2 8367 3388 0.931265 0.0449331 -0.00548815 1 0 1 1 0 0 +EDGE2 8367 3147 -0.0258832 0.100352 -0.00953199 1 0 1 1 0 0 +EDGE2 8367 5887 -0.0123909 0.0242438 -0.00151144 1 0 1 1 0 0 +EDGE2 8367 3387 -0.0482362 0.0516723 0.00197583 1 0 1 1 0 0 +EDGE2 8367 3067 0.00535653 -0.00409862 0.00342775 1 0 1 1 0 0 +EDGE2 8367 3146 -0.963752 -0.0256356 -0.0113464 1 0 1 1 0 0 +EDGE2 8367 3386 -0.969408 0.0461552 -0.0304976 1 0 1 1 0 0 +EDGE2 8367 5886 -0.941607 0.0787203 -0.0310124 1 0 1 1 0 0 +EDGE2 8367 3066 -0.980575 0.0403886 0.00524959 1 0 1 1 0 0 +EDGE2 8368 5889 0.980821 -0.0689507 0.00599267 1 0 1 1 0 0 +EDGE2 8368 3149 0.926365 0.116306 0.00134381 1 0 1 1 0 0 +EDGE2 8368 3389 1.07704 0.0855227 -0.00701873 1 0 1 1 0 0 +EDGE2 8368 3069 0.992377 0.0121967 -0.0170227 1 0 1 1 0 0 +EDGE2 8368 5888 0.0329139 -0.0129702 -0.019959 1 0 1 1 0 0 +EDGE2 8368 3068 0.0465655 -0.0384647 0.0209278 1 0 1 1 0 0 +EDGE2 8368 3148 0.0158874 -0.0765245 -0.00971728 1 0 1 1 0 0 +EDGE2 8368 3388 -0.0269842 -0.00795409 -0.00402658 1 0 1 1 0 0 +EDGE2 8368 3147 -0.994475 0.0240222 0.0277975 1 0 1 1 0 0 +EDGE2 8368 5887 -1.05304 -0.0366555 -0.00415508 1 0 1 1 0 0 +EDGE2 8368 8367 -1.03688 -0.0453639 -0.00733157 1 0 1 1 0 0 +EDGE2 8368 3387 -0.999844 -0.0739508 -0.015795 1 0 1 1 0 0 +EDGE2 8368 3067 -1.10781 -0.0407386 0.0115255 1 0 1 1 0 0 +EDGE2 8369 3070 0.999 -0.0163623 -0.0027565 1 0 1 1 0 0 +EDGE2 8369 3390 1.03118 0.0502577 0.0185189 1 0 1 1 0 0 +EDGE2 8369 3410 0.999028 -0.0152333 -3.12431 1 0 1 1 0 0 +EDGE2 8369 5890 0.99726 -0.0504563 -0.055681 1 0 1 1 0 0 +EDGE2 8369 3150 1.01934 -0.0270941 0.0028302 1 0 1 1 0 0 +EDGE2 8369 5889 -0.0186162 -0.0293696 0.00639333 1 0 1 1 0 0 +EDGE2 8369 3149 0.109186 0.00784175 0.00849674 1 0 1 1 0 0 +EDGE2 8369 3389 -0.019378 -0.180167 -0.00543886 1 0 1 1 0 0 +EDGE2 8369 3069 -0.0950387 0.0548105 0.0147793 1 0 1 1 0 0 +EDGE2 8369 5888 -0.923967 0.0765383 -0.010634 1 0 1 1 0 0 +EDGE2 8369 8368 -0.957848 -0.0381793 -0.00906802 1 0 1 1 0 0 +EDGE2 8369 3068 -0.984859 0.0481013 -0.00152939 1 0 1 1 0 0 +EDGE2 8369 3148 -0.98925 0.0129531 -0.0080632 1 0 1 1 0 0 +EDGE2 8369 3388 -1.03957 0.0210243 0.0109309 1 0 1 1 0 0 +EDGE2 8370 3409 1.00096 -0.0407774 -3.12471 1 0 1 1 0 0 +EDGE2 8370 3411 0.034528 -1.00422 -1.54032 1 0 1 1 0 0 +EDGE2 8370 5891 -0.0139296 -1.01327 -1.5422 1 0 1 1 0 0 +EDGE2 8370 3391 0.0376012 -1.02675 -1.60767 1 0 1 1 0 0 +EDGE2 8370 3070 -0.141701 0.0643739 -0.0368344 1 0 1 1 0 0 +EDGE2 8370 3390 -0.0742186 -0.0334035 0.0206429 1 0 1 1 0 0 +EDGE2 8370 3410 -0.015944 0.0307166 -3.13744 1 0 1 1 0 0 +EDGE2 8370 5890 -0.0196362 -0.0876342 -0.0191562 1 0 1 1 0 0 +EDGE2 8370 3150 -0.0396578 -0.000816322 0.0090306 1 0 1 1 0 0 +EDGE2 8370 5889 -1.04637 -0.0309179 -0.0198014 1 0 1 1 0 0 +EDGE2 8370 8369 -0.981256 0.0781684 0.0149265 1 0 1 1 0 0 +EDGE2 8370 3149 -1.08553 -0.0345952 0.00694332 1 0 1 1 0 0 +EDGE2 8370 3389 -0.972657 -0.0100103 0.00587407 1 0 1 1 0 0 +EDGE2 8370 3069 -0.961294 0.0496305 0.0122777 1 0 1 1 0 0 +EDGE2 8370 3151 -0.00965765 0.999059 1.5644 1 0 1 1 0 0 +EDGE2 8370 3071 0.0425415 1.03831 1.53541 1 0 1 1 0 0 +EDGE2 8371 8370 -0.971439 0.000795609 -1.5969 1 0 1 1 0 0 +EDGE2 8371 3070 -1.04563 0.0276392 -1.60907 1 0 1 1 0 0 +EDGE2 8371 3390 -1.00019 0.00118845 -1.57979 1 0 1 1 0 0 +EDGE2 8371 3410 -1.00788 -0.0339629 1.55065 1 0 1 1 0 0 +EDGE2 8371 5890 -0.977724 0.0366724 -1.58002 1 0 1 1 0 0 +EDGE2 8371 3150 -1.07781 -0.0621672 -1.58983 1 0 1 1 0 0 +EDGE2 8371 3072 1.03701 0.00874824 0.00694282 1 0 1 1 0 0 +EDGE2 8371 3151 -0.0136816 -0.0140083 0.0145195 1 0 1 1 0 0 +EDGE2 8371 3071 0.0864168 3.17573e-05 -0.00421422 1 0 1 1 0 0 +EDGE2 8371 3152 1.05535 -0.0611482 -0.0113903 1 0 1 1 0 0 +EDGE2 8372 3072 0.0710648 -0.0144442 -0.0157011 1 0 1 1 0 0 +EDGE2 8372 3151 -0.986855 -0.0203287 0.00328293 1 0 1 1 0 0 +EDGE2 8372 8371 -0.997635 0.0681968 0.000262116 1 0 1 1 0 0 +EDGE2 8372 3071 -1.07662 0.0144876 -0.0123254 1 0 1 1 0 0 +EDGE2 8372 3152 0.0127461 -0.0485162 -0.0104188 1 0 1 1 0 0 +EDGE2 8372 3153 1.00137 0.0427952 0.0287036 1 0 1 1 0 0 +EDGE2 8372 3073 0.952037 0.0384966 0.03048 1 0 1 1 0 0 +EDGE2 8373 3072 -1.08856 0.0311329 -0.0348184 1 0 1 1 0 0 +EDGE2 8373 8372 -0.940824 -0.0201887 0.0051723 1 0 1 1 0 0 +EDGE2 8373 3152 -1.1081 0.0197607 0.0167574 1 0 1 1 0 0 +EDGE2 8373 3153 0.0830241 0.0283571 -0.0100862 1 0 1 1 0 0 +EDGE2 8373 3073 0.0467026 0.0138559 -0.00308091 1 0 1 1 0 0 +EDGE2 8373 3074 0.959167 0.0811737 0.0045789 1 0 1 1 0 0 +EDGE2 8373 3154 0.958834 0.0275593 0.016485 1 0 1 1 0 0 +EDGE2 8374 3153 -0.993406 0.00521496 -0.0155757 1 0 1 1 0 0 +EDGE2 8374 8373 -1.09893 -0.0986277 -0.00611893 1 0 1 1 0 0 +EDGE2 8374 3073 -1.0517 0.076525 0.0176337 1 0 1 1 0 0 +EDGE2 8374 1075 0.951413 0.0831981 -3.15044 1 0 1 1 0 0 +EDGE2 8374 3074 -0.00299306 -0.0618258 -0.028863 1 0 1 1 0 0 +EDGE2 8374 3154 0.0338993 0.0192182 -0.0222357 1 0 1 1 0 0 +EDGE2 8374 3155 1.03596 0.0256278 -0.00122062 1 0 1 1 0 0 +EDGE2 8374 3075 0.998324 0.0628143 -0.0271655 1 0 1 1 0 0 +EDGE2 8374 995 1.03124 0.0579976 -3.18393 1 0 1 1 0 0 +EDGE2 8374 1015 1.05954 0.0117634 -3.12188 1 0 1 1 0 0 +EDGE2 8374 1055 1.02136 -0.00697623 -3.16012 1 0 1 1 0 0 +EDGE2 8375 1016 -0.0268821 -0.941581 -1.56205 1 0 1 1 0 0 +EDGE2 8375 1056 0.0190941 -1.02726 -1.55527 1 0 1 1 0 0 +EDGE2 8375 996 0.0215202 -1.01437 -1.60311 1 0 1 1 0 0 +EDGE2 8375 8374 -0.962488 -0.0501018 -0.00520363 1 0 1 1 0 0 +EDGE2 8375 1075 -0.0386171 -0.112252 -3.11434 1 0 1 1 0 0 +EDGE2 8375 3074 -0.907128 -0.00601845 0.0379843 1 0 1 1 0 0 +EDGE2 8375 3154 -0.947482 0.0195779 -0.00110914 1 0 1 1 0 0 +EDGE2 8375 3155 0.0039299 0.0318113 0.00383448 1 0 1 1 0 0 +EDGE2 8375 3075 0.0034783 -0.0989351 -0.0195113 1 0 1 1 0 0 +EDGE2 8375 1074 0.923625 0.00412257 -3.15232 1 0 1 1 0 0 +EDGE2 8375 995 0.0178054 -0.0264284 -3.13797 1 0 1 1 0 0 +EDGE2 8375 1015 0.0125726 0.00707565 -3.14629 1 0 1 1 0 0 +EDGE2 8375 1055 0.080459 -0.0617009 -3.15913 1 0 1 1 0 0 +EDGE2 8375 1014 1.12181 0.0357268 -3.11145 1 0 1 1 0 0 +EDGE2 8375 1054 0.960458 0.00171702 -3.13584 1 0 1 1 0 0 +EDGE2 8375 994 1.04825 -0.00526683 -3.1631 1 0 1 1 0 0 +EDGE2 8375 3156 0.0646842 1.1236 1.54644 1 0 1 1 0 0 +EDGE2 8375 1076 -0.0253321 1.0227 1.57397 1 0 1 1 0 0 +EDGE2 8375 3076 -0.0446487 0.969148 1.56922 1 0 1 1 0 0 +EDGE2 8376 1075 -1.00317 -0.0513727 1.55557 1 0 1 1 0 0 +EDGE2 8376 3155 -0.996459 -0.00403081 -1.55726 1 0 1 1 0 0 +EDGE2 8376 8375 -0.8981 -0.0459212 -1.5391 1 0 1 1 0 0 +EDGE2 8376 3075 -1.0006 -0.0368307 -1.57586 1 0 1 1 0 0 +EDGE2 8376 995 -1.02292 -0.0331116 1.58875 1 0 1 1 0 0 +EDGE2 8376 1015 -1.0047 0.051865 1.52802 1 0 1 1 0 0 +EDGE2 8376 1055 -1.01858 -0.0129221 1.57393 1 0 1 1 0 0 +EDGE2 8376 3156 -0.0240537 0.0365096 -0.0221674 1 0 1 1 0 0 +EDGE2 8376 1076 0.0632261 0.046509 -0.0421871 1 0 1 1 0 0 +EDGE2 8376 3076 -0.0530174 0.0146357 -0.00581764 1 0 1 1 0 0 +EDGE2 8376 3077 0.976586 -0.0538604 -0.0132987 1 0 1 1 0 0 +EDGE2 8376 3157 0.997154 -0.0552041 0.0262191 1 0 1 1 0 0 +EDGE2 8376 1077 0.987911 -0.0259035 0.00952225 1 0 1 1 0 0 +EDGE2 8377 3078 0.951304 0.0074857 -0.00942838 1 0 1 1 0 0 +EDGE2 8377 3156 -1.02359 -0.0066523 0.0175951 1 0 1 1 0 0 +EDGE2 8377 8376 -0.919996 0.0541242 0.00587584 1 0 1 1 0 0 +EDGE2 8377 1076 -1.02261 0.0860701 0.00188703 1 0 1 1 0 0 +EDGE2 8377 3076 -1.0464 0.0708955 -0.00719257 1 0 1 1 0 0 +EDGE2 8377 3077 -0.0213766 -0.0484353 0.0442526 1 0 1 1 0 0 +EDGE2 8377 3157 -0.0487476 -0.0387514 -0.057458 1 0 1 1 0 0 +EDGE2 8377 1077 -0.0342758 0.0357091 -0.0339406 1 0 1 1 0 0 +EDGE2 8377 3158 0.918024 0.00758473 0.0339452 1 0 1 1 0 0 +EDGE2 8377 1078 1.00602 0.000632238 0.00754008 1 0 1 1 0 0 +EDGE2 8378 3078 -0.0200137 0.0234962 -0.00530616 1 0 1 1 0 0 +EDGE2 8378 3077 -0.974702 -0.0179912 0.00848501 1 0 1 1 0 0 +EDGE2 8378 3157 -0.935393 0.00704792 0.0235536 1 0 1 1 0 0 +EDGE2 8378 8377 -0.995309 0.0176207 0.000548129 1 0 1 1 0 0 +EDGE2 8378 1077 -1.00926 0.0899931 -0.00326191 1 0 1 1 0 0 +EDGE2 8378 3158 -0.00621703 0.0105963 -0.00636919 1 0 1 1 0 0 +EDGE2 8378 1078 0.000693676 -0.0289623 -0.0193111 1 0 1 1 0 0 +EDGE2 8378 3079 1.08441 -0.0256141 0.0275253 1 0 1 1 0 0 +EDGE2 8378 3159 0.972607 0.0728758 0.00520461 1 0 1 1 0 0 +EDGE2 8378 1079 0.998837 0.0197363 0.0199059 1 0 1 1 0 0 +EDGE2 8379 8360 1.02207 -0.0783783 -3.16458 1 0 1 1 0 0 +EDGE2 8379 3078 -1.00976 -0.00560395 0.00549705 1 0 1 1 0 0 +EDGE2 8379 8378 -0.881983 0.00924 -0.0110577 1 0 1 1 0 0 +EDGE2 8379 3158 -0.987385 -0.0681854 -0.0181387 1 0 1 1 0 0 +EDGE2 8379 1078 -1.11517 0.0517847 -0.00445577 1 0 1 1 0 0 +EDGE2 8379 3079 0.053798 0.0536419 -0.024722 1 0 1 1 0 0 +EDGE2 8379 3159 -0.0640472 -0.0694965 -0.014545 1 0 1 1 0 0 +EDGE2 8379 1079 -0.0399738 0.0581268 -0.0153121 1 0 1 1 0 0 +EDGE2 8379 3060 0.971285 -0.0294963 -3.17258 1 0 1 1 0 0 +EDGE2 8379 3160 1.01915 -0.0074813 0.00898697 1 0 1 1 0 0 +EDGE2 8379 5860 0.953563 -0.00999382 -3.1168 1 0 1 1 0 0 +EDGE2 8379 5880 1.07433 0.0215132 -3.12478 1 0 1 1 0 0 +EDGE2 8379 3080 0.95137 0.0329687 -0.00549904 1 0 1 1 0 0 +EDGE2 8379 1080 1.07214 -0.00329597 -0.0230253 1 0 1 1 0 0 +EDGE2 8380 8360 -0.0176057 0.0616172 -3.11405 1 0 1 1 0 0 +EDGE2 8380 8379 -0.979811 -0.0250241 0.0149522 1 0 1 1 0 0 +EDGE2 8380 3079 -1.01856 0.0495375 0.0437862 1 0 1 1 0 0 +EDGE2 8380 3159 -1.01168 0.00285736 -0.0022636 1 0 1 1 0 0 +EDGE2 8380 1079 -1.08672 0.00961142 -0.000357199 1 0 1 1 0 0 +EDGE2 8380 8361 0.0262997 0.981645 1.57551 1 0 1 1 0 0 +EDGE2 8380 3081 0.0275187 1.04306 1.59638 1 0 1 1 0 0 +EDGE2 8380 3161 0.0528153 0.978911 1.52982 1 0 1 1 0 0 +EDGE2 8380 5881 -0.0330245 1.03526 1.57581 1 0 1 1 0 0 +EDGE2 8380 3061 -0.0188203 0.987228 1.57471 1 0 1 1 0 0 +EDGE2 8380 3060 -0.0528533 -0.0362052 -3.15031 1 0 1 1 0 0 +EDGE2 8380 3160 -0.0351407 -0.00396333 -0.00877516 1 0 1 1 0 0 +EDGE2 8380 5860 -0.00650324 -0.042931 -3.1565 1 0 1 1 0 0 +EDGE2 8380 5880 0.0470553 -0.0411224 -3.1292 1 0 1 1 0 0 +EDGE2 8380 3080 -0.0607867 0.0480479 0.0153607 1 0 1 1 0 0 +EDGE2 8380 1080 -0.103709 -0.0172188 0.0121843 1 0 1 1 0 0 +EDGE2 8380 1081 -0.0522345 -1.04621 -1.57051 1 0 1 1 0 0 +EDGE2 8380 5861 0.0522086 -0.956086 -1.53391 1 0 1 1 0 0 +EDGE2 8380 5859 0.914765 0.0568291 -3.17285 1 0 1 1 0 0 +EDGE2 8380 5879 1.12371 0.0781161 -3.15767 1 0 1 1 0 0 +EDGE2 8380 8359 1.01353 0.00688701 -3.16232 1 0 1 1 0 0 +EDGE2 8380 3059 1.01405 0.0020972 -3.11178 1 0 1 1 0 0 +EDGE2 8381 8360 -0.919703 0.00719748 1.53808 1 0 1 1 0 0 +EDGE2 8381 8362 0.994138 0.0920136 -0.0122539 1 0 1 1 0 0 +EDGE2 8381 3082 1.02511 -0.133549 0.00694807 1 0 1 1 0 0 +EDGE2 8381 3162 1.03155 0.0405622 0.0253418 1 0 1 1 0 0 +EDGE2 8381 5882 1.08235 -0.0887232 -0.0389292 1 0 1 1 0 0 +EDGE2 8381 3062 0.970857 -0.0359301 0.00546304 1 0 1 1 0 0 +EDGE2 8381 8361 -0.00934201 0.0289893 -0.0175099 1 0 1 1 0 0 +EDGE2 8381 3081 -0.0621729 -0.112957 -0.0300075 1 0 1 1 0 0 +EDGE2 8381 3161 0.0277607 -0.0886474 0.0113715 1 0 1 1 0 0 +EDGE2 8381 5881 -0.0496401 -0.0035331 -0.029907 1 0 1 1 0 0 +EDGE2 8381 3061 -0.0180393 0.058052 -0.00113958 1 0 1 1 0 0 +EDGE2 8381 8380 -0.917033 0.0441233 -1.57455 1 0 1 1 0 0 +EDGE2 8381 3060 -1.01994 -0.0652554 1.57179 1 0 1 1 0 0 +EDGE2 8381 3160 -0.99977 0.0298887 -1.5616 1 0 1 1 0 0 +EDGE2 8381 5860 -1.03654 -0.0180155 1.55091 1 0 1 1 0 0 +EDGE2 8381 5880 -0.953267 -0.0345495 1.58262 1 0 1 1 0 0 +EDGE2 8381 3080 -0.998313 -0.00232886 -1.58457 1 0 1 1 0 0 +EDGE2 8381 1080 -1.03867 -0.00134402 -1.53925 1 0 1 1 0 0 +EDGE2 8382 8363 1.06128 0.0992337 0.0108591 1 0 1 1 0 0 +EDGE2 8382 3083 1.01046 0.0223286 0.0235829 1 0 1 1 0 0 +EDGE2 8382 3163 1.0675 -0.0373774 -0.0220883 1 0 1 1 0 0 +EDGE2 8382 5883 1.03161 0.0125618 -0.0173581 1 0 1 1 0 0 +EDGE2 8382 3063 0.947865 -0.0588583 -0.00894151 1 0 1 1 0 0 +EDGE2 8382 8362 0.0327109 0.0861455 -0.00154151 1 0 1 1 0 0 +EDGE2 8382 3082 -0.0022731 -0.0539905 0.0236412 1 0 1 1 0 0 +EDGE2 8382 3162 -0.0186851 -0.00129655 0.00187409 1 0 1 1 0 0 +EDGE2 8382 5882 -0.00406216 -0.0737181 0.00407331 1 0 1 1 0 0 +EDGE2 8382 3062 -0.0578929 0.0434534 0.00514888 1 0 1 1 0 0 +EDGE2 8382 8361 -0.985594 0.122847 -0.0095414 1 0 1 1 0 0 +EDGE2 8382 8381 -0.937735 0.0118176 0.000599667 1 0 1 1 0 0 +EDGE2 8382 3081 -0.988354 -0.012998 0.0209286 1 0 1 1 0 0 +EDGE2 8382 3161 -1.1817 -0.0968104 -0.0262531 1 0 1 1 0 0 +EDGE2 8382 5881 -1.04596 -0.0834344 0.00943718 1 0 1 1 0 0 +EDGE2 8382 3061 -0.975435 -0.0107779 -0.0024087 1 0 1 1 0 0 +EDGE2 8383 3064 0.927917 -0.0371637 -0.0112678 1 0 1 1 0 0 +EDGE2 8383 3164 0.993279 -0.0264326 -0.00882874 1 0 1 1 0 0 +EDGE2 8383 5884 0.882987 0.0920413 0.0100895 1 0 1 1 0 0 +EDGE2 8383 8364 1.0563 0.00620733 -0.00407965 1 0 1 1 0 0 +EDGE2 8383 3084 0.890828 -0.0195784 -0.00703987 1 0 1 1 0 0 +EDGE2 8383 8363 0.00617933 -0.0449126 -0.00699943 1 0 1 1 0 0 +EDGE2 8383 3083 -0.0430439 -0.0301082 0.0406981 1 0 1 1 0 0 +EDGE2 8383 3163 -0.0746531 0.0356696 0.00952364 1 0 1 1 0 0 +EDGE2 8383 5883 0.0115747 0.0240693 -0.0368292 1 0 1 1 0 0 +EDGE2 8383 3063 -0.0135809 -0.0254505 0.00439611 1 0 1 1 0 0 +EDGE2 8383 8362 -1.01152 0.0181891 -0.0158725 1 0 1 1 0 0 +EDGE2 8383 8382 -0.915233 0.0647363 -0.00217886 1 0 1 1 0 0 +EDGE2 8383 3082 -1.00004 0.0385197 -0.0315765 1 0 1 1 0 0 +EDGE2 8383 3162 -1.08762 0.0634215 -0.0125607 1 0 1 1 0 0 +EDGE2 8383 5882 -1.00439 0.00740063 0.00264451 1 0 1 1 0 0 +EDGE2 8383 3062 -0.968078 -0.0943244 -0.00108769 1 0 1 1 0 0 +EDGE2 8384 3105 0.925234 0.0689648 -3.13184 1 0 1 1 0 0 +EDGE2 8384 3485 0.971544 -0.0531197 -3.09197 1 0 1 1 0 0 +EDGE2 8384 5845 0.947939 0.0291598 -3.16378 1 0 1 1 0 0 +EDGE2 8384 5885 1.06857 -0.127068 -0.0394904 1 0 1 1 0 0 +EDGE2 8384 8365 1.03705 -0.00908587 0.00349937 1 0 1 1 0 0 +EDGE2 8384 5825 1.0009 0.034749 -3.11882 1 0 1 1 0 0 +EDGE2 8384 3145 1.0579 0.0349837 -3.16629 1 0 1 1 0 0 +EDGE2 8384 3165 1.00096 0.0543451 0.0239962 1 0 1 1 0 0 +EDGE2 8384 3385 1.07864 0.00946353 -3.15942 1 0 1 1 0 0 +EDGE2 8384 3125 1.03002 0.00169864 -3.13188 1 0 1 1 0 0 +EDGE2 8384 1185 0.947804 -0.0293471 -3.15397 1 0 1 1 0 0 +EDGE2 8384 3065 1.01882 -0.00330732 -0.0249259 1 0 1 1 0 0 +EDGE2 8384 3085 0.97469 0.00844589 0.000479658 1 0 1 1 0 0 +EDGE2 8384 1165 1.0092 0.0263209 -3.1365 1 0 1 1 0 0 +EDGE2 8384 3064 0.0798132 0.0758254 -0.0119389 1 0 1 1 0 0 +EDGE2 8384 3164 0.0334757 0.070482 0.0127712 1 0 1 1 0 0 +EDGE2 8384 5884 0.038782 0.00562686 -0.0077368 1 0 1 1 0 0 +EDGE2 8384 8364 0.0673608 0.00354234 -0.0243048 1 0 1 1 0 0 +EDGE2 8384 3084 0.0181362 -0.0147925 0.00630019 1 0 1 1 0 0 +EDGE2 8384 8363 -1.08361 -0.00535402 0.00189742 1 0 1 1 0 0 +EDGE2 8384 8383 -1.0772 -0.0315528 0.00679619 1 0 1 1 0 0 +EDGE2 8384 3083 -0.911186 -0.0617653 0.0234064 1 0 1 1 0 0 +EDGE2 8384 3163 -1.01347 -0.00634966 -0.0331188 1 0 1 1 0 0 +EDGE2 8384 5883 -1.00393 0.0753501 -0.00244764 1 0 1 1 0 0 +EDGE2 8384 3063 -0.986919 -0.0787053 -0.00601768 1 0 1 1 0 0 +EDGE2 8385 8366 -0.00309955 0.957329 1.5739 1 0 1 1 0 0 +EDGE2 8385 3146 -0.0540367 0.943853 1.57484 1 0 1 1 0 0 +EDGE2 8385 3386 0.016388 1.00569 1.55025 1 0 1 1 0 0 +EDGE2 8385 5886 -0.0775851 1.02112 1.59407 1 0 1 1 0 0 +EDGE2 8385 3066 -0.0408203 1.05127 1.55714 1 0 1 1 0 0 +EDGE2 8385 3144 1.06073 -0.0407544 -3.153 1 0 1 1 0 0 +EDGE2 8385 3484 1.08271 0.00750306 -3.1588 1 0 1 1 0 0 +EDGE2 8385 5824 1.03644 -0.07077 -3.13157 1 0 1 1 0 0 +EDGE2 8385 5844 0.994916 0.0658055 -3.12392 1 0 1 1 0 0 +EDGE2 8385 3384 0.992925 -0.0835143 -3.14751 1 0 1 1 0 0 +EDGE2 8385 1184 0.994443 -0.0703521 -3.15785 1 0 1 1 0 0 +EDGE2 8385 3104 0.964662 0.0169244 -3.13286 1 0 1 1 0 0 +EDGE2 8385 3124 1.04303 0.0367515 -3.16235 1 0 1 1 0 0 +EDGE2 8385 1164 0.942707 0.0453672 -3.14519 1 0 1 1 0 0 +EDGE2 8385 3166 0.0460184 -1.04706 -1.56613 1 0 1 1 0 0 +EDGE2 8385 3105 -0.11568 0.0432498 -3.13028 1 0 1 1 0 0 +EDGE2 8385 3485 -0.0470402 -0.00141859 -3.15793 1 0 1 1 0 0 +EDGE2 8385 5845 -0.0747098 0.0206871 -3.09682 1 0 1 1 0 0 +EDGE2 8385 5885 -0.127052 -0.00429426 -0.0251194 1 0 1 1 0 0 +EDGE2 8385 8365 -0.0439569 0.13111 0.0130645 1 0 1 1 0 0 +EDGE2 8385 5825 0.00216103 0.0163479 -3.13697 1 0 1 1 0 0 +EDGE2 8385 3145 0.0493556 0.103096 -3.15879 1 0 1 1 0 0 +EDGE2 8385 3165 -0.128087 -0.0191375 0.0103179 1 0 1 1 0 0 +EDGE2 8385 3385 -0.0337681 -0.0257814 -3.1168 1 0 1 1 0 0 +EDGE2 8385 3125 0.0166513 0.0577079 -3.13204 1 0 1 1 0 0 +EDGE2 8385 1185 -0.0119265 -0.0149111 -3.17534 1 0 1 1 0 0 +EDGE2 8385 3065 0.0342414 0.0332217 -0.0358709 1 0 1 1 0 0 +EDGE2 8385 3085 0.0167765 -0.0038314 0.00984239 1 0 1 1 0 0 +EDGE2 8385 1165 0.0188818 -0.0284886 -3.14214 1 0 1 1 0 0 +EDGE2 8385 5826 0.0343564 -1.01564 -1.61992 1 0 1 1 0 0 +EDGE2 8385 5846 0.0528645 -1.02046 -1.57456 1 0 1 1 0 0 +EDGE2 8385 3486 0.0198538 -0.985062 -1.56345 1 0 1 1 0 0 +EDGE2 8385 1166 -0.0147231 -0.956949 -1.5736 1 0 1 1 0 0 +EDGE2 8385 3086 -0.0233411 -1.00063 -1.57921 1 0 1 1 0 0 +EDGE2 8385 3106 -0.0350128 -0.914396 -1.53511 1 0 1 1 0 0 +EDGE2 8385 3126 -0.0570169 -0.99181 -1.59682 1 0 1 1 0 0 +EDGE2 8385 1186 -0.0466359 -1.0036 -1.57703 1 0 1 1 0 0 +EDGE2 8385 3064 -0.970537 -0.0313414 -0.0167615 1 0 1 1 0 0 +EDGE2 8385 8384 -1.0903 -0.0438546 -0.0156204 1 0 1 1 0 0 +EDGE2 8385 3164 -0.914896 -0.0784854 0.00545535 1 0 1 1 0 0 +EDGE2 8385 5884 -1.00834 -0.0270511 -0.0275491 1 0 1 1 0 0 +EDGE2 8385 8364 -1.09144 -0.0199826 0.00784037 1 0 1 1 0 0 +EDGE2 8385 3084 -0.947026 0.138297 0.0520089 1 0 1 1 0 0 +EDGE2 8386 8385 -0.971319 -0.0356481 1.57178 1 0 1 1 0 0 +EDGE2 8386 3166 0.0274315 0.00861304 0.015899 1 0 1 1 0 0 +EDGE2 8386 3105 -1.00834 0.0210729 -1.5723 1 0 1 1 0 0 +EDGE2 8386 3485 -0.969835 0.0194187 -1.54619 1 0 1 1 0 0 +EDGE2 8386 5845 -0.943335 -0.150826 -1.56878 1 0 1 1 0 0 +EDGE2 8386 5885 -1.05653 0.0371091 1.597 1 0 1 1 0 0 +EDGE2 8386 8365 -1.06112 -0.0177324 1.54742 1 0 1 1 0 0 +EDGE2 8386 5825 -1.06825 -0.097684 -1.579 1 0 1 1 0 0 +EDGE2 8386 3145 -0.997703 0.0431102 -1.56942 1 0 1 1 0 0 +EDGE2 8386 3165 -0.925406 0.0536024 1.61697 1 0 1 1 0 0 +EDGE2 8386 3385 -0.965748 -0.0659535 -1.56155 1 0 1 1 0 0 +EDGE2 8386 3125 -1.04447 -0.0575942 -1.59026 1 0 1 1 0 0 +EDGE2 8386 1185 -0.92646 0.0117204 -1.59546 1 0 1 1 0 0 +EDGE2 8386 3065 -0.914447 0.0294069 1.56214 1 0 1 1 0 0 +EDGE2 8386 3085 -0.996059 -0.0474151 1.56283 1 0 1 1 0 0 +EDGE2 8386 1165 -1.00447 0.031987 -1.58565 1 0 1 1 0 0 +EDGE2 8386 5826 0.0355601 0.00435899 0.0263478 1 0 1 1 0 0 +EDGE2 8386 5846 0.000762977 0.0264479 0.0202715 1 0 1 1 0 0 +EDGE2 8386 3486 0.0106875 -0.0172828 -0.00654756 1 0 1 1 0 0 +EDGE2 8386 5847 0.947939 0.0262352 -0.00191943 1 0 1 1 0 0 +EDGE2 8386 1166 0.0141236 -0.00709225 -0.0006718 1 0 1 1 0 0 +EDGE2 8386 3086 0.042078 0.0489972 -0.0332269 1 0 1 1 0 0 +EDGE2 8386 3106 -0.0237119 0.046715 -0.0107213 1 0 1 1 0 0 +EDGE2 8386 3126 -0.00549964 -0.00703469 0.00454335 1 0 1 1 0 0 +EDGE2 8386 1186 -0.0994099 -0.00928505 0.00211328 1 0 1 1 0 0 +EDGE2 8386 3107 0.98976 0.0436976 0.0152264 1 0 1 1 0 0 +EDGE2 8386 3167 0.982316 -0.0210628 -0.0146223 1 0 1 1 0 0 +EDGE2 8386 3487 1.06971 -0.0788594 0.00425506 1 0 1 1 0 0 +EDGE2 8386 5827 0.930971 0.0609663 0.0195145 1 0 1 1 0 0 +EDGE2 8386 3127 0.997451 -0.0462605 -0.00796933 1 0 1 1 0 0 +EDGE2 8386 1187 1.00594 0.0721806 0.0527566 1 0 1 1 0 0 +EDGE2 8386 3087 0.994221 0.0208518 0.0117191 1 0 1 1 0 0 +EDGE2 8386 1167 0.958035 0.107073 0.0136571 1 0 1 1 0 0 +EDGE2 8387 3166 -1.08906 0.017264 0.0147396 1 0 1 1 0 0 +EDGE2 8387 5826 -0.991878 0.0177176 -0.0221547 1 0 1 1 0 0 +EDGE2 8387 5846 -0.9654 0.00931268 0.0016267 1 0 1 1 0 0 +EDGE2 8387 8386 -0.980598 -0.011496 0.00105132 1 0 1 1 0 0 +EDGE2 8387 3486 -1.02449 0.00646555 -0.0117287 1 0 1 1 0 0 +EDGE2 8387 5847 -0.0655724 0.0154875 -0.0113563 1 0 1 1 0 0 +EDGE2 8387 1166 -1.0204 0.0179515 0.00143417 1 0 1 1 0 0 +EDGE2 8387 3086 -1.01854 0.0370327 -0.0144379 1 0 1 1 0 0 +EDGE2 8387 3106 -0.936481 -0.00125155 0.00164225 1 0 1 1 0 0 +EDGE2 8387 3126 -1.03567 -0.0867528 -0.00154442 1 0 1 1 0 0 +EDGE2 8387 1186 -1.03265 0.0191136 0.012591 1 0 1 1 0 0 +EDGE2 8387 3107 -0.0240357 0.0623771 -0.0218366 1 0 1 1 0 0 +EDGE2 8387 3167 -0.00556373 0.137328 -0.0448467 1 0 1 1 0 0 +EDGE2 8387 3487 0.0316434 -0.0849377 0.017137 1 0 1 1 0 0 +EDGE2 8387 5827 -0.000959532 0.0462706 0.0109018 1 0 1 1 0 0 +EDGE2 8387 3127 0.00134056 0.0820536 -0.032036 1 0 1 1 0 0 +EDGE2 8387 1187 0.0378994 0.00525171 -0.037661 1 0 1 1 0 0 +EDGE2 8387 3087 -0.030115 0.00835308 0.0097307 1 0 1 1 0 0 +EDGE2 8387 1167 -0.000934917 0.0602538 -0.0354746 1 0 1 1 0 0 +EDGE2 8387 3128 1.03739 0.00489329 -0.0242966 1 0 1 1 0 0 +EDGE2 8387 3488 0.949964 0.0173691 -0.00759763 1 0 1 1 0 0 +EDGE2 8387 5828 0.989745 -0.055769 -0.0366341 1 0 1 1 0 0 +EDGE2 8387 5848 0.837521 -0.0232463 -0.00728522 1 0 1 1 0 0 +EDGE2 8387 3168 1.08058 0.0473183 -0.0115029 1 0 1 1 0 0 +EDGE2 8387 1188 1.01025 0.0181799 0.00415194 1 0 1 1 0 0 +EDGE2 8387 3088 0.892363 0.0139334 -0.00162462 1 0 1 1 0 0 +EDGE2 8387 3108 0.995393 -0.0415889 0.0192667 1 0 1 1 0 0 +EDGE2 8387 1168 0.950243 0.00424 -0.0322593 1 0 1 1 0 0 +EDGE2 8388 5847 -1.00581 -0.0928856 -0.0165659 1 0 1 1 0 0 +EDGE2 8388 8387 -0.934575 0.0378315 -0.0120292 1 0 1 1 0 0 +EDGE2 8388 3107 -1.08453 -0.00464358 -0.0222112 1 0 1 1 0 0 +EDGE2 8388 3167 -1.00825 -0.0565848 0.0249263 1 0 1 1 0 0 +EDGE2 8388 3487 -1.00572 -0.0255762 -0.0070831 1 0 1 1 0 0 +EDGE2 8388 5827 -0.970347 -0.0371698 0.0251428 1 0 1 1 0 0 +EDGE2 8388 3127 -0.864851 0.100443 -0.00282997 1 0 1 1 0 0 +EDGE2 8388 1187 -1.02421 0.110585 -0.0616684 1 0 1 1 0 0 +EDGE2 8388 3087 -1.03505 -0.0158478 -0.0075351 1 0 1 1 0 0 +EDGE2 8388 1167 -0.964775 0.00545664 -0.00742402 1 0 1 1 0 0 +EDGE2 8388 3128 0.0467884 -0.0280935 -8.49602e-05 1 0 1 1 0 0 +EDGE2 8388 3488 -0.0259098 -0.0350649 -0.0238623 1 0 1 1 0 0 +EDGE2 8388 5828 0.0304312 -0.000214961 -0.00831001 1 0 1 1 0 0 +EDGE2 8388 5848 -0.0858175 -0.00745594 -0.00929419 1 0 1 1 0 0 +EDGE2 8388 3168 0.0879355 -0.0639577 -0.0149523 1 0 1 1 0 0 +EDGE2 8388 1188 -0.0551211 0.0712624 -0.0320533 1 0 1 1 0 0 +EDGE2 8388 3088 0.0815106 -0.00231671 -0.0148487 1 0 1 1 0 0 +EDGE2 8388 3108 0.0460456 -0.000778979 0.0109258 1 0 1 1 0 0 +EDGE2 8388 1168 0.0156072 -0.0453278 0.00574394 1 0 1 1 0 0 +EDGE2 8388 5849 0.981945 -0.0417176 0.0134409 1 0 1 1 0 0 +EDGE2 8388 3109 1.05664 -0.0987737 -0.0316008 1 0 1 1 0 0 +EDGE2 8388 3169 0.9645 0.0200971 0.0105114 1 0 1 1 0 0 +EDGE2 8388 3489 1.03446 -0.0111692 0.00804478 1 0 1 1 0 0 +EDGE2 8388 5829 1.07036 0.0200425 -0.000878521 1 0 1 1 0 0 +EDGE2 8388 3129 1.07959 0.0462179 0.00188831 1 0 1 1 0 0 +EDGE2 8388 1189 1.03295 0.103799 -0.00416167 1 0 1 1 0 0 +EDGE2 8388 3089 0.98894 -0.0583396 0.0120611 1 0 1 1 0 0 +EDGE2 8388 1169 0.978887 0.0310906 0.0275952 1 0 1 1 0 0 +EDGE2 8389 8388 -1.06744 -0.0700418 -0.0175662 1 0 1 1 0 0 +EDGE2 8389 3128 -0.965127 0.0629155 0.00144253 1 0 1 1 0 0 +EDGE2 8389 3488 -1.09624 -0.0303996 0.0032991 1 0 1 1 0 0 +EDGE2 8389 5828 -1.01937 -0.00192255 0.0129131 1 0 1 1 0 0 +EDGE2 8389 5848 -1.023 0.10399 -0.0106604 1 0 1 1 0 0 +EDGE2 8389 3168 -1.04563 -0.0353659 -0.00591635 1 0 1 1 0 0 +EDGE2 8389 1188 -1.05096 0.000266078 0.0238977 1 0 1 1 0 0 +EDGE2 8389 3088 -1.09094 0.00141596 -0.0337227 1 0 1 1 0 0 +EDGE2 8389 3108 -1.09502 -0.0578084 -0.0401637 1 0 1 1 0 0 +EDGE2 8389 1168 -0.992679 0.013452 0.00852585 1 0 1 1 0 0 +EDGE2 8389 5849 0.0589807 0.0817773 -0.000154845 1 0 1 1 0 0 +EDGE2 8389 3109 -0.0102467 0.0501761 0.0123017 1 0 1 1 0 0 +EDGE2 8389 3169 0.0123705 -0.0597551 0.0177525 1 0 1 1 0 0 +EDGE2 8389 3489 0.050473 -0.0629496 -0.0219415 1 0 1 1 0 0 +EDGE2 8389 5829 -0.0237361 -0.0177216 0.0331114 1 0 1 1 0 0 +EDGE2 8389 3129 -0.01737 0.0110509 -0.00641422 1 0 1 1 0 0 +EDGE2 8389 1189 0.00458172 0.0694178 0.000937055 1 0 1 1 0 0 +EDGE2 8389 3089 0.0360093 -0.0581616 -0.00650941 1 0 1 1 0 0 +EDGE2 8389 1169 0.0209252 -0.0158602 -0.0346418 1 0 1 1 0 0 +EDGE2 8389 3050 1.00162 -0.00241611 -3.17597 1 0 1 1 0 0 +EDGE2 8389 5850 0.964019 0.017646 0.0313472 1 0 1 1 0 0 +EDGE2 8389 3170 0.964579 0.0194016 0.0353391 1 0 1 1 0 0 +EDGE2 8389 5790 1.04287 -0.00148496 -3.12005 1 0 1 1 0 0 +EDGE2 8389 5810 1.02579 -0.0707821 -3.09287 1 0 1 1 0 0 +EDGE2 8389 5830 1.02009 -0.0237691 0.0104028 1 0 1 1 0 0 +EDGE2 8389 3490 1.06391 0.00715443 0.0208323 1 0 1 1 0 0 +EDGE2 8389 3110 1.12229 -0.0522074 0.00657122 1 0 1 1 0 0 +EDGE2 8389 3130 1.00716 -0.0493345 -0.00617931 1 0 1 1 0 0 +EDGE2 8389 3090 1.07084 0.0510556 0.0257949 1 0 1 1 0 0 +EDGE2 8389 1130 0.968408 0.0576859 -3.13783 1 0 1 1 0 0 +EDGE2 8389 1170 0.93638 -0.0410999 0.0307815 1 0 1 1 0 0 +EDGE2 8389 1190 1.01733 -0.0154505 -0.00152609 1 0 1 1 0 0 +EDGE2 8389 3030 0.916384 0.0227848 -3.16224 1 0 1 1 0 0 +EDGE2 8389 1150 0.985453 -0.0886901 -3.17904 1 0 1 1 0 0 +EDGE2 8389 1110 1.06788 -0.0449179 -3.15308 1 0 1 1 0 0 +EDGE2 8390 5849 -1.00503 -0.0361456 0.0141478 1 0 1 1 0 0 +EDGE2 8390 8389 -1.059 0.0230194 0.0216767 1 0 1 1 0 0 +EDGE2 8390 3109 -1.01899 -0.0644723 -0.0356485 1 0 1 1 0 0 +EDGE2 8390 3169 -0.978096 -0.015558 0.0275482 1 0 1 1 0 0 +EDGE2 8390 3489 -0.974666 -0.00582601 0.00430712 1 0 1 1 0 0 +EDGE2 8390 5829 -0.884567 0.0209435 -0.00932157 1 0 1 1 0 0 +EDGE2 8390 3129 -1.05119 -0.0085036 -0.0119844 1 0 1 1 0 0 +EDGE2 8390 1189 -0.974068 -0.0268235 -0.0343515 1 0 1 1 0 0 +EDGE2 8390 3089 -0.942586 -0.0175786 -0.0122499 1 0 1 1 0 0 +EDGE2 8390 1169 -1.03803 0.0838702 -0.0248767 1 0 1 1 0 0 +EDGE2 8390 3050 -0.0338393 0.00998399 -3.14594 1 0 1 1 0 0 +EDGE2 8390 3131 -0.0338619 0.946392 1.56938 1 0 1 1 0 0 +EDGE2 8390 3491 0.0156415 1.01175 1.54117 1 0 1 1 0 0 +EDGE2 8390 5811 0.0741277 1.03343 1.56878 1 0 1 1 0 0 +EDGE2 8390 5831 0.0796216 1.01251 1.58396 1 0 1 1 0 0 +EDGE2 8390 3171 0.0933809 0.964923 1.56248 1 0 1 1 0 0 +EDGE2 8390 5850 0.00938224 -0.00145108 0.0240788 1 0 1 1 0 0 +EDGE2 8390 1151 0.0405594 0.977034 1.60122 1 0 1 1 0 0 +EDGE2 8390 1191 -0.0343864 1.00098 1.53225 1 0 1 1 0 0 +EDGE2 8390 3091 0.014474 1.02889 1.58367 1 0 1 1 0 0 +EDGE2 8390 3111 -0.0397367 1.04573 1.56809 1 0 1 1 0 0 +EDGE2 8390 1171 -0.0394493 1.03236 1.56323 1 0 1 1 0 0 +EDGE2 8390 3170 0.00173797 0.0126807 0.0239237 1 0 1 1 0 0 +EDGE2 8390 5790 0.0232078 0.0771946 -3.13496 1 0 1 1 0 0 +EDGE2 8390 5810 0.132788 0.065721 -3.14406 1 0 1 1 0 0 +EDGE2 8390 5830 -0.0410338 0.0569874 0.00589544 1 0 1 1 0 0 +EDGE2 8390 3490 -0.0278022 -0.0689269 -0.00618602 1 0 1 1 0 0 +EDGE2 8390 3110 -0.065552 0.0705915 -0.00422049 1 0 1 1 0 0 +EDGE2 8390 3130 0.00787984 0.124992 0.00546227 1 0 1 1 0 0 +EDGE2 8390 3090 0.0846193 -0.0282163 0.00345561 1 0 1 1 0 0 +EDGE2 8390 5789 0.979117 -0.0578324 -3.11573 1 0 1 1 0 0 +EDGE2 8390 1130 0.0193525 -0.0102633 -3.16879 1 0 1 1 0 0 +EDGE2 8390 1170 0.0375905 -0.107795 -0.013586 1 0 1 1 0 0 +EDGE2 8390 1190 -0.0268232 0.000397896 0.00485811 1 0 1 1 0 0 +EDGE2 8390 3030 0.0280172 0.0150052 -3.18209 1 0 1 1 0 0 +EDGE2 8390 1150 -0.038359 -0.0270721 -3.10371 1 0 1 1 0 0 +EDGE2 8390 1110 0.0251592 -0.00989777 -3.18281 1 0 1 1 0 0 +EDGE2 8390 5809 1.02372 0.00977217 -3.15118 1 0 1 1 0 0 +EDGE2 8390 1109 0.97891 0.0396759 -3.12471 1 0 1 1 0 0 +EDGE2 8390 1149 1.08901 -0.050091 -3.11226 1 0 1 1 0 0 +EDGE2 8390 3029 0.994079 -0.048994 -3.146 1 0 1 1 0 0 +EDGE2 8390 3049 1.01003 0.0811372 -3.14824 1 0 1 1 0 0 +EDGE2 8390 1129 0.884 -0.0510128 -3.09718 1 0 1 1 0 0 +EDGE2 8390 5851 0.0472082 -0.956664 -1.55658 1 0 1 1 0 0 +EDGE2 8390 1111 -0.0270687 -1.03909 -1.54617 1 0 1 1 0 0 +EDGE2 8390 3031 -0.00732331 -1.07099 -1.56176 1 0 1 1 0 0 +EDGE2 8390 3051 -0.039449 -1.02107 -1.55036 1 0 1 1 0 0 +EDGE2 8390 5791 0.00420216 -1.00859 -1.58139 1 0 1 1 0 0 +EDGE2 8390 1131 0.0159628 -0.980306 -1.58383 1 0 1 1 0 0 +EDGE2 8391 3050 -1.06917 -0.00156507 -1.55933 1 0 1 1 0 0 +EDGE2 8391 5850 -0.91927 0.0783498 1.56189 1 0 1 1 0 0 +EDGE2 8391 8390 -0.977653 -0.0284292 1.59722 1 0 1 1 0 0 +EDGE2 8391 3170 -0.97897 -0.0201344 1.55363 1 0 1 1 0 0 +EDGE2 8391 5790 -1.04956 0.0432982 -1.56422 1 0 1 1 0 0 +EDGE2 8391 5810 -1.02622 -0.0129892 -1.60296 1 0 1 1 0 0 +EDGE2 8391 5830 -0.936213 -0.079729 1.55214 1 0 1 1 0 0 +EDGE2 8391 3490 -0.971242 -0.0338604 1.61096 1 0 1 1 0 0 +EDGE2 8391 3110 -1.01804 0.0369931 1.58491 1 0 1 1 0 0 +EDGE2 8391 3130 -0.939823 -0.0721421 1.58027 1 0 1 1 0 0 +EDGE2 8391 3090 -1.03209 -0.0144957 1.57745 1 0 1 1 0 0 +EDGE2 8391 1130 -1.01719 -0.0140556 -1.59198 1 0 1 1 0 0 +EDGE2 8391 1170 -0.985057 -0.0185565 1.55484 1 0 1 1 0 0 +EDGE2 8391 1190 -0.975301 0.0406337 1.5524 1 0 1 1 0 0 +EDGE2 8391 3030 -1.03428 0.0569539 -1.57061 1 0 1 1 0 0 +EDGE2 8391 1150 -0.913061 0.030031 -1.55012 1 0 1 1 0 0 +EDGE2 8391 1110 -0.981752 0.063412 -1.58674 1 0 1 1 0 0 +EDGE2 8391 5851 -0.0448715 -0.0366456 0.0144319 1 0 1 1 0 0 +EDGE2 8391 3052 0.950377 0.0399599 -0.03268 1 0 1 1 0 0 +EDGE2 8391 1111 -0.0136428 0.0315788 -0.0207544 1 0 1 1 0 0 +EDGE2 8391 3031 -0.0214954 -0.0509662 0.0451841 1 0 1 1 0 0 +EDGE2 8391 3051 -0.00391401 0.0111476 -0.0358212 1 0 1 1 0 0 +EDGE2 8391 5791 -0.0283676 -0.0300256 0.0182792 1 0 1 1 0 0 +EDGE2 8391 1131 0.00855096 -0.0345122 -0.000278607 1 0 1 1 0 0 +EDGE2 8391 5852 0.996915 -0.027855 -0.0143831 1 0 1 1 0 0 +EDGE2 8391 5792 0.973181 -0.00637013 0.0193716 1 0 1 1 0 0 +EDGE2 8391 1112 0.991215 -0.092557 0.0207694 1 0 1 1 0 0 +EDGE2 8391 1132 0.964339 -0.00702125 -0.0187183 1 0 1 1 0 0 +EDGE2 8391 3032 0.941681 0.0539275 -0.0138606 1 0 1 1 0 0 +EDGE2 8392 5851 -1.03278 -0.0985818 0.0106829 1 0 1 1 0 0 +EDGE2 8392 8391 -1.00494 -0.0316654 0.0168838 1 0 1 1 0 0 +EDGE2 8392 1133 0.949473 -0.0143605 -0.00111772 1 0 1 1 0 0 +EDGE2 8392 3052 -0.0103225 0.0912326 -0.0243031 1 0 1 1 0 0 +EDGE2 8392 1111 -0.940938 -0.0402935 0.0173244 1 0 1 1 0 0 +EDGE2 8392 3031 -1.0115 0.0479729 -0.0305779 1 0 1 1 0 0 +EDGE2 8392 3051 -0.989776 0.0454647 0.0178591 1 0 1 1 0 0 +EDGE2 8392 5791 -1.05824 0.0438291 0.0218465 1 0 1 1 0 0 +EDGE2 8392 1131 -0.942414 -0.0118352 0.0419934 1 0 1 1 0 0 +EDGE2 8392 5852 0.0161337 -0.0177624 0.00623261 1 0 1 1 0 0 +EDGE2 8392 5792 -0.00733562 -0.0592483 0.00116487 1 0 1 1 0 0 +EDGE2 8392 1112 0.00627999 -0.01058 -0.0137211 1 0 1 1 0 0 +EDGE2 8392 1132 0.0203142 0.00993097 0.00671153 1 0 1 1 0 0 +EDGE2 8392 3032 -0.0576132 -0.0311619 0.0176918 1 0 1 1 0 0 +EDGE2 8392 3053 1.0232 -0.00124717 0.0310823 1 0 1 1 0 0 +EDGE2 8392 5793 1.03434 0.0828516 0.00767529 1 0 1 1 0 0 +EDGE2 8392 5853 0.903039 0.00618305 0.0349277 1 0 1 1 0 0 +EDGE2 8392 3033 1.0581 0.0692214 -0.00175905 1 0 1 1 0 0 +EDGE2 8392 1113 0.990299 0.0108248 -0.00622533 1 0 1 1 0 0 +EDGE2 8393 1133 0.0149613 0.0704946 -0.018386 1 0 1 1 0 0 +EDGE2 8393 3052 -0.971307 0.00195815 0.0231547 1 0 1 1 0 0 +EDGE2 8393 5852 -0.981049 0.0565395 0.000800689 1 0 1 1 0 0 +EDGE2 8393 8392 -1.00292 -0.0233192 -0.014967 1 0 1 1 0 0 +EDGE2 8393 5792 -1.06647 0.108032 0.0328508 1 0 1 1 0 0 +EDGE2 8393 1112 -0.947719 -0.0525433 0.0273947 1 0 1 1 0 0 +EDGE2 8393 1132 -0.999449 0.0395161 -0.0111643 1 0 1 1 0 0 +EDGE2 8393 3032 -1.067 0.0166206 0.0293202 1 0 1 1 0 0 +EDGE2 8393 3053 0.0813059 -0.00727371 0.00768517 1 0 1 1 0 0 +EDGE2 8393 5793 -0.0986479 -0.0273653 -0.00426784 1 0 1 1 0 0 +EDGE2 8393 5853 0.00767748 -0.0606664 0.0347611 1 0 1 1 0 0 +EDGE2 8393 3033 0.00670126 0.00897322 0.00620829 1 0 1 1 0 0 +EDGE2 8393 5794 0.954354 -0.0309849 0.029616 1 0 1 1 0 0 +EDGE2 8393 1113 -0.00958143 0.0388794 0.000550498 1 0 1 1 0 0 +EDGE2 8393 5854 0.978381 0.0238371 0.0105447 1 0 1 1 0 0 +EDGE2 8393 1134 1.08625 0.0780337 0.0154769 1 0 1 1 0 0 +EDGE2 8393 3034 0.97887 0.0371597 0.00852483 1 0 1 1 0 0 +EDGE2 8393 3054 1.10469 0.0152801 0.0212371 1 0 1 1 0 0 +EDGE2 8393 1114 1.03184 0.129929 -0.0055517 1 0 1 1 0 0 +EDGE2 8394 5795 0.982667 -0.0250882 0.033595 1 0 1 1 0 0 +EDGE2 8394 1133 -0.983072 -0.0553876 -0.037077 1 0 1 1 0 0 +EDGE2 8394 8393 -1.07839 -0.0671554 0.00184562 1 0 1 1 0 0 +EDGE2 8394 3053 -1.08962 0.0420125 0.0226747 1 0 1 1 0 0 +EDGE2 8394 5793 -0.924181 0.0524171 -0.000500689 1 0 1 1 0 0 +EDGE2 8394 5853 -0.920542 -0.0198907 0.0303549 1 0 1 1 0 0 +EDGE2 8394 3033 -0.939807 0.0527489 -0.0177078 1 0 1 1 0 0 +EDGE2 8394 5794 0.0784292 0.0656141 0.0210325 1 0 1 1 0 0 +EDGE2 8394 1113 -1.02094 0.0594485 -0.00712826 1 0 1 1 0 0 +EDGE2 8394 5854 0.0462562 0.0936719 -0.0184734 1 0 1 1 0 0 +EDGE2 8394 1134 -0.0183917 0.0242255 -0.0160566 1 0 1 1 0 0 +EDGE2 8394 3034 -0.0672776 0.052292 0.0316707 1 0 1 1 0 0 +EDGE2 8394 3054 -0.0214965 -0.0637451 0.0116883 1 0 1 1 0 0 +EDGE2 8394 1114 0.0034267 -0.0354607 0.00922596 1 0 1 1 0 0 +EDGE2 8394 5875 0.965324 -0.0110831 -3.1308 1 0 1 1 0 0 +EDGE2 8394 8355 1.02495 -0.0109034 -3.13728 1 0 1 1 0 0 +EDGE2 8394 5855 0.96872 0.0344156 -0.0136915 1 0 1 1 0 0 +EDGE2 8394 3035 1.00693 0.00490083 -0.0159902 1 0 1 1 0 0 +EDGE2 8394 3055 1.02994 -0.0110784 0.0368441 1 0 1 1 0 0 +EDGE2 8394 1095 1.00247 -0.0178135 -3.1202 1 0 1 1 0 0 +EDGE2 8394 1115 0.973425 -0.0576647 -0.00477131 1 0 1 1 0 0 +EDGE2 8394 1135 0.967849 0.0401858 0.0319513 1 0 1 1 0 0 +EDGE2 8395 5795 -0.0494389 -0.050302 -0.00885078 1 0 1 1 0 0 +EDGE2 8395 8356 -0.11388 -1.03235 -1.57626 1 0 1 1 0 0 +EDGE2 8395 5856 0.0017317 -1.06591 -1.59646 1 0 1 1 0 0 +EDGE2 8395 5876 0.0887289 -0.982421 -1.55913 1 0 1 1 0 0 +EDGE2 8395 3056 -0.0901086 -1.00766 -1.58237 1 0 1 1 0 0 +EDGE2 8395 5794 -0.979491 0.0615609 0.0131087 1 0 1 1 0 0 +EDGE2 8395 8394 -1.06459 0.00698008 -0.0296346 1 0 1 1 0 0 +EDGE2 8395 5854 -1.01609 -0.0423141 0.00818039 1 0 1 1 0 0 +EDGE2 8395 1134 -1.02847 0.0186821 -0.0166592 1 0 1 1 0 0 +EDGE2 8395 3034 -0.917141 -0.0816442 0.013569 1 0 1 1 0 0 +EDGE2 8395 3054 -1.03845 -0.030628 -0.00715398 1 0 1 1 0 0 +EDGE2 8395 1114 -1.01898 0.0170871 -0.0193654 1 0 1 1 0 0 +EDGE2 8395 5875 0.0433443 -0.0229828 -3.13989 1 0 1 1 0 0 +EDGE2 8395 8355 0.0371893 -0.0447146 -3.14893 1 0 1 1 0 0 +EDGE2 8395 5855 -0.0113379 0.00101595 0.0257533 1 0 1 1 0 0 +EDGE2 8395 3035 0.0875516 0.0513008 0.0301417 1 0 1 1 0 0 +EDGE2 8395 3055 0.0569575 -0.0155407 -0.033052 1 0 1 1 0 0 +EDGE2 8395 1095 0.031956 -0.0129442 -3.16503 1 0 1 1 0 0 +EDGE2 8395 1115 0.0265658 -0.0545151 -0.0278707 1 0 1 1 0 0 +EDGE2 8395 1135 0.0145208 -0.0230354 0.0169853 1 0 1 1 0 0 +EDGE2 8395 1094 0.98926 0.0409841 -3.13943 1 0 1 1 0 0 +EDGE2 8395 8354 0.991012 -0.0718156 -3.11873 1 0 1 1 0 0 +EDGE2 8395 5874 1.00583 -0.0539358 -3.15202 1 0 1 1 0 0 +EDGE2 8395 1116 0.047309 1.04159 1.59259 1 0 1 1 0 0 +EDGE2 8395 3036 0.0380571 0.925063 1.60422 1 0 1 1 0 0 +EDGE2 8395 5796 0.0466173 0.97394 1.57042 1 0 1 1 0 0 +EDGE2 8395 1136 0.00670508 1.00493 1.58152 1 0 1 1 0 0 +EDGE2 8395 1096 0.00485552 1.03042 1.54466 1 0 1 1 0 0 +EDGE2 8396 5795 -1.02405 -0.0121587 1.55437 1 0 1 1 0 0 +EDGE2 8396 5877 1.01626 0.0331845 0.044645 1 0 1 1 0 0 +EDGE2 8396 8357 0.971003 -0.0243832 -0.0430381 1 0 1 1 0 0 +EDGE2 8396 3057 1.02439 0.0382029 0.0246694 1 0 1 1 0 0 +EDGE2 8396 5857 1.04282 0.0117125 -0.0196422 1 0 1 1 0 0 +EDGE2 8396 8356 -0.0578125 0.0631592 -0.01402 1 0 1 1 0 0 +EDGE2 8396 5856 0.0320587 0.0370999 -0.0134345 1 0 1 1 0 0 +EDGE2 8396 5876 -0.0322856 0.0119037 0.0230291 1 0 1 1 0 0 +EDGE2 8396 3056 -0.0547969 -0.0581062 -0.0117625 1 0 1 1 0 0 +EDGE2 8396 8395 -1.0112 -0.107989 1.55631 1 0 1 1 0 0 +EDGE2 8396 5875 -0.992907 0.0366171 -1.59254 1 0 1 1 0 0 +EDGE2 8396 8355 -0.970394 -0.0806407 -1.56941 1 0 1 1 0 0 +EDGE2 8396 5855 -1.0561 -0.0141376 1.55174 1 0 1 1 0 0 +EDGE2 8396 3035 -1.12975 -0.00103491 1.57336 1 0 1 1 0 0 +EDGE2 8396 3055 -0.999808 0.0439823 1.55296 1 0 1 1 0 0 +EDGE2 8396 1095 -0.991648 -0.046797 -1.59497 1 0 1 1 0 0 +EDGE2 8396 1115 -1.03755 0.0381556 1.58864 1 0 1 1 0 0 +EDGE2 8396 1135 -1.02654 -0.0099765 1.54907 1 0 1 1 0 0 +EDGE2 8397 8358 0.926899 -0.00387174 -0.011946 1 0 1 1 0 0 +EDGE2 8397 3058 1.01461 0.0180969 0.00249783 1 0 1 1 0 0 +EDGE2 8397 5858 0.92779 -0.0145451 -0.0249313 1 0 1 1 0 0 +EDGE2 8397 5878 1.03447 -0.102476 0.00123168 1 0 1 1 0 0 +EDGE2 8397 5877 0.0465288 0.0269251 -0.00386464 1 0 1 1 0 0 +EDGE2 8397 8357 -0.0777285 0.0134333 -0.0257079 1 0 1 1 0 0 +EDGE2 8397 3057 0.024553 0.0235538 0.000685649 1 0 1 1 0 0 +EDGE2 8397 5857 -0.0031575 0.0147115 0.0261218 1 0 1 1 0 0 +EDGE2 8397 8356 -0.968377 -0.0774541 0.0281205 1 0 1 1 0 0 +EDGE2 8397 8396 -0.987126 -0.102705 -0.028246 1 0 1 1 0 0 +EDGE2 8397 5856 -1.01472 -0.0207108 -0.0230815 1 0 1 1 0 0 +EDGE2 8397 5876 -1.04122 0.0064864 -0.0250867 1 0 1 1 0 0 +EDGE2 8397 3056 -1.07234 0.0460665 0.0108113 1 0 1 1 0 0 +EDGE2 8398 5859 0.933355 0.00485579 0.0190815 1 0 1 1 0 0 +EDGE2 8398 5879 0.886076 -0.00258147 -0.00757303 1 0 1 1 0 0 +EDGE2 8398 8359 0.961079 0.0163657 0.00578536 1 0 1 1 0 0 +EDGE2 8398 3059 0.952257 0.0184078 -0.0348467 1 0 1 1 0 0 +EDGE2 8398 8358 -0.0529279 0.0299727 0.00897993 1 0 1 1 0 0 +EDGE2 8398 3058 0.029014 0.0312877 -0.0244149 1 0 1 1 0 0 +EDGE2 8398 5858 0.0219387 0.00532229 -0.0270924 1 0 1 1 0 0 +EDGE2 8398 5878 0.0233925 0.0326812 0.000346343 1 0 1 1 0 0 +EDGE2 8398 5877 -1.07455 -0.029775 -0.000148816 1 0 1 1 0 0 +EDGE2 8398 8397 -1.05408 -0.000349956 -0.00759131 1 0 1 1 0 0 +EDGE2 8398 8357 -1.04443 0.0475225 0.0158024 1 0 1 1 0 0 +EDGE2 8398 3057 -1.00615 0.0187253 0.00864429 1 0 1 1 0 0 +EDGE2 8398 5857 -1.00914 0.0189214 -0.0028844 1 0 1 1 0 0 +EDGE2 8399 8360 0.950499 -0.0177382 -0.016208 1 0 1 1 0 0 +EDGE2 8399 8380 1.03951 -0.0767451 -3.14626 1 0 1 1 0 0 +EDGE2 8399 3060 0.989139 0.046389 0.00834717 1 0 1 1 0 0 +EDGE2 8399 3160 1.00706 0.0127389 -3.1468 1 0 1 1 0 0 +EDGE2 8399 5860 0.954139 0.0426919 0.0160678 1 0 1 1 0 0 +EDGE2 8399 5880 1.04564 -0.0333646 0.0201363 1 0 1 1 0 0 +EDGE2 8399 3080 1.0507 -0.0337575 -3.13021 1 0 1 1 0 0 +EDGE2 8399 1080 1.076 -0.022463 -3.15138 1 0 1 1 0 0 +EDGE2 8399 5859 0.0503171 -0.00798026 -0.00103676 1 0 1 1 0 0 +EDGE2 8399 5879 0.0182273 -0.0485341 -0.034275 1 0 1 1 0 0 +EDGE2 8399 8359 0.0368734 -0.0272063 -0.041888 1 0 1 1 0 0 +EDGE2 8399 3059 -0.093005 0.00498211 -0.0163567 1 0 1 1 0 0 +EDGE2 8399 8358 -0.907306 0.0638808 -0.00903116 1 0 1 1 0 0 +EDGE2 8399 8398 -1.01899 0.0172313 -0.014028 1 0 1 1 0 0 +EDGE2 8399 3058 -0.943962 0.0699691 0.0130005 1 0 1 1 0 0 +EDGE2 8399 5858 -0.999396 0.113076 0.0189849 1 0 1 1 0 0 +EDGE2 8399 5878 -1.01593 -0.0263072 -0.0207275 1 0 1 1 0 0 +EDGE2 8400 8360 -0.00233144 0.0758441 -0.0285794 1 0 1 1 0 0 +EDGE2 8400 8379 1.01693 0.0563809 -3.12032 1 0 1 1 0 0 +EDGE2 8400 3079 1.10691 0.0412302 -3.13925 1 0 1 1 0 0 +EDGE2 8400 3159 1.09981 -0.0715186 -3.13862 1 0 1 1 0 0 +EDGE2 8400 1079 1.02995 0.0810178 -3.12344 1 0 1 1 0 0 +EDGE2 8400 8361 0.0546611 -0.990673 -1.61137 1 0 1 1 0 0 +EDGE2 8400 8381 0.00663999 -0.993011 -1.62265 1 0 1 1 0 0 +EDGE2 8400 3081 -0.0266533 -0.971652 -1.57402 1 0 1 1 0 0 +EDGE2 8400 3161 -0.0124285 -1.06977 -1.58789 1 0 1 1 0 0 +EDGE2 8400 5881 0.0959483 -1.04372 -1.58919 1 0 1 1 0 0 +EDGE2 8400 3061 0.0579969 -1.05405 -1.57402 1 0 1 1 0 0 +EDGE2 8400 8380 -0.043018 -0.0481263 -3.18073 1 0 1 1 0 0 +EDGE2 8400 3060 0.0810678 -0.0448356 -0.0120399 1 0 1 1 0 0 +EDGE2 8400 3160 -0.0429232 -0.0278989 -3.1777 1 0 1 1 0 0 +EDGE2 8400 5860 -0.0213983 -0.0516045 -0.0182678 1 0 1 1 0 0 +EDGE2 8400 5880 0.0632228 -0.0258199 0.0164568 1 0 1 1 0 0 +EDGE2 8400 3080 -0.0675718 -0.0146829 -3.124 1 0 1 1 0 0 +EDGE2 8400 1080 0.0904858 -0.0252155 -3.1434 1 0 1 1 0 0 +EDGE2 8400 1081 0.0175256 0.986233 1.56935 1 0 1 1 0 0 +EDGE2 8400 5861 -0.0188111 1.08537 1.56228 1 0 1 1 0 0 +EDGE2 8400 8399 -0.999229 0.0472447 0.0223123 1 0 1 1 0 0 +EDGE2 8400 5859 -0.984019 -0.0243782 -0.0329205 1 0 1 1 0 0 +EDGE2 8400 5879 -1.05788 0.0771465 0.0239818 1 0 1 1 0 0 +EDGE2 8400 8359 -1.01679 -0.0234061 -0.0165975 1 0 1 1 0 0 +EDGE2 8400 3059 -0.961313 0.0343447 -0.0464619 1 0 1 1 0 0 +EDGE2 8401 8360 -0.992123 0.0585431 -1.55376 1 0 1 1 0 0 +EDGE2 8401 8400 -0.985849 -0.044537 -1.58969 1 0 1 1 0 0 +EDGE2 8401 8380 -0.997514 -0.00861828 1.5613 1 0 1 1 0 0 +EDGE2 8401 5862 1.02968 -0.0246443 0.0087413 1 0 1 1 0 0 +EDGE2 8401 3060 -0.981486 -0.0484276 -1.57294 1 0 1 1 0 0 +EDGE2 8401 3160 -1.05446 0.0667255 1.55937 1 0 1 1 0 0 +EDGE2 8401 5860 -0.886258 0.0790231 -1.584 1 0 1 1 0 0 +EDGE2 8401 5880 -1.02129 0.0372205 -1.60253 1 0 1 1 0 0 +EDGE2 8401 3080 -0.974821 -0.0656819 1.56837 1 0 1 1 0 0 +EDGE2 8401 1080 -1.04129 0.0424785 1.55173 1 0 1 1 0 0 +EDGE2 8401 1081 0.0407572 0.0314414 -0.021223 1 0 1 1 0 0 +EDGE2 8401 5861 -0.0177134 -0.0346836 -0.00355591 1 0 1 1 0 0 +EDGE2 8401 1082 1.05707 0.0734101 -0.00256626 1 0 1 1 0 0 +EDGE2 8402 5862 0.0382358 0.0659654 0.00448026 1 0 1 1 0 0 +EDGE2 8402 8401 -1.02663 -0.0829636 0.0199877 1 0 1 1 0 0 +EDGE2 8402 1081 -0.955102 -0.0040225 0.0112536 1 0 1 1 0 0 +EDGE2 8402 5861 -0.956745 0.0413226 0.0300808 1 0 1 1 0 0 +EDGE2 8402 1082 0.103658 -0.00691287 -0.000973953 1 0 1 1 0 0 +EDGE2 8402 1083 1.08876 0.0492807 0.0180104 1 0 1 1 0 0 +EDGE2 8402 5863 0.987507 0.0690848 0.0367817 1 0 1 1 0 0 +EDGE2 8403 5862 -1.09365 -0.0062145 0.0161142 1 0 1 1 0 0 +EDGE2 8403 8402 -1.00331 -0.0360036 -0.0372165 1 0 1 1 0 0 +EDGE2 8403 1082 -1.04863 -0.0320405 -0.00656451 1 0 1 1 0 0 +EDGE2 8403 1083 0.0913999 -0.0522141 -0.014316 1 0 1 1 0 0 +EDGE2 8403 5863 0.0555555 0.0189349 -0.000264667 1 0 1 1 0 0 +EDGE2 8403 1084 0.976918 0.0447336 0.0102225 1 0 1 1 0 0 +EDGE2 8403 5864 1.03513 -0.0764128 -0.0373121 1 0 1 1 0 0 +EDGE2 8404 8345 1.03157 0.0412329 -3.12752 1 0 1 1 0 0 +EDGE2 8404 8403 -1.00395 -0.00778589 0.0154062 1 0 1 1 0 0 +EDGE2 8404 1083 -1.0131 -0.052467 -0.0280232 1 0 1 1 0 0 +EDGE2 8404 5863 -0.949931 -0.0409166 0.021131 1 0 1 1 0 0 +EDGE2 8404 1084 0.0665378 -0.0800118 0.0116242 1 0 1 1 0 0 +EDGE2 8404 5864 0.0305894 0.0410098 0.0189741 1 0 1 1 0 0 +EDGE2 8404 1045 0.962771 -0.0511271 -3.12561 1 0 1 1 0 0 +EDGE2 8404 1085 0.995599 0.0673826 -0.00390009 1 0 1 1 0 0 +EDGE2 8404 5865 1.00396 -0.0498793 0.00655572 1 0 1 1 0 0 +EDGE2 8405 8345 -0.0293703 0.0539744 -3.14283 1 0 1 1 0 0 +EDGE2 8405 1046 0.0914494 -0.992779 -1.58769 1 0 1 1 0 0 +EDGE2 8405 1084 -1.00818 -0.0437025 0.00414805 1 0 1 1 0 0 +EDGE2 8405 5864 -0.945483 0.101342 0.0233207 1 0 1 1 0 0 +EDGE2 8405 8404 -1.01936 -0.0290537 -0.0168471 1 0 1 1 0 0 +EDGE2 8405 8344 0.993604 0.0122707 -3.12666 1 0 1 1 0 0 +EDGE2 8405 1045 -0.148796 0.0328021 -3.16586 1 0 1 1 0 0 +EDGE2 8405 1085 -0.0656238 0.00780738 -0.00830318 1 0 1 1 0 0 +EDGE2 8405 5865 0.0537181 -0.0470678 -0.0145502 1 0 1 1 0 0 +EDGE2 8405 1044 0.970374 0.0107784 -3.14537 1 0 1 1 0 0 +EDGE2 8405 8346 0.0355209 1.03229 1.60269 1 0 1 1 0 0 +EDGE2 8405 1086 0.0261045 1.05039 1.57512 1 0 1 1 0 0 +EDGE2 8405 5866 -0.012287 1.01301 1.54709 1 0 1 1 0 0 +EDGE2 8406 8345 -0.96705 -0.0775957 1.58467 1 0 1 1 0 0 +EDGE2 8406 8405 -1.03873 -0.00938384 -1.5524 1 0 1 1 0 0 +EDGE2 8406 1045 -1.02964 0.0771298 1.55624 1 0 1 1 0 0 +EDGE2 8406 1085 -0.998764 -0.00804507 -1.57465 1 0 1 1 0 0 +EDGE2 8406 5865 -1.01198 0.0280192 -1.55711 1 0 1 1 0 0 +EDGE2 8406 8346 0.0245895 0.0129579 0.0167026 1 0 1 1 0 0 +EDGE2 8406 1086 -0.0252423 0.0273847 -0.026363 1 0 1 1 0 0 +EDGE2 8406 5866 -0.00855379 0.0569865 -0.0183181 1 0 1 1 0 0 +EDGE2 8406 5867 0.970273 -0.0834243 -0.000481184 1 0 1 1 0 0 +EDGE2 8406 8347 0.994755 -0.0324134 0.0215296 1 0 1 1 0 0 +EDGE2 8406 1087 1.02683 0.0108528 0.00168721 1 0 1 1 0 0 +EDGE2 8407 8346 -0.978295 -0.028662 -0.012533 1 0 1 1 0 0 +EDGE2 8407 8406 -1.0067 0.0692965 0.0134396 1 0 1 1 0 0 +EDGE2 8407 1086 -1.02638 0.0487285 -0.0112223 1 0 1 1 0 0 +EDGE2 8407 5866 -1.02059 -0.0236333 0.0237162 1 0 1 1 0 0 +EDGE2 8407 5867 -0.0160337 0.0403017 -0.00378184 1 0 1 1 0 0 +EDGE2 8407 8347 -0.0249797 0.0232912 -0.00199943 1 0 1 1 0 0 +EDGE2 8407 1087 0.0416255 -0.0766608 -0.00371731 1 0 1 1 0 0 +EDGE2 8407 8348 0.984335 0.032611 0.0175251 1 0 1 1 0 0 +EDGE2 8407 1088 0.997983 0.0622938 0.00213482 1 0 1 1 0 0 +EDGE2 8407 5868 1.06234 0.00209184 0.0101088 1 0 1 1 0 0 +EDGE2 8408 8407 -0.990032 -0.049915 -0.0140444 1 0 1 1 0 0 +EDGE2 8408 5867 -0.911942 0.0403777 -0.0116132 1 0 1 1 0 0 +EDGE2 8408 8347 -0.995121 -0.0122237 0.00641681 1 0 1 1 0 0 +EDGE2 8408 1087 -1.02201 0.0169544 0.00796761 1 0 1 1 0 0 +EDGE2 8408 8348 0.0573447 -0.0210978 -0.00606164 1 0 1 1 0 0 +EDGE2 8408 1088 0.00714106 -0.00902972 0.0370764 1 0 1 1 0 0 +EDGE2 8408 5868 0.0114632 -0.0178941 -0.0232416 1 0 1 1 0 0 +EDGE2 8408 5869 1.02605 -0.0710651 -0.0274398 1 0 1 1 0 0 +EDGE2 8408 8349 0.950382 -0.00727946 -0.0171242 1 0 1 1 0 0 +EDGE2 8408 1089 0.898551 -0.020934 -0.0093257 1 0 1 1 0 0 +EDGE2 8409 8348 -0.927673 0.0086736 0.00703522 1 0 1 1 0 0 +EDGE2 8409 8408 -0.957449 -0.00693197 -0.0219768 1 0 1 1 0 0 +EDGE2 8409 1088 -1.02326 -0.103689 -0.030962 1 0 1 1 0 0 +EDGE2 8409 5868 -0.955601 -0.0186137 0.00596626 1 0 1 1 0 0 +EDGE2 8409 5869 -0.0583833 -0.0952929 0.0174248 1 0 1 1 0 0 +EDGE2 8409 8349 -0.116166 -0.0833179 -0.00516949 1 0 1 1 0 0 +EDGE2 8409 1089 0.0136141 -0.0456022 0.0085498 1 0 1 1 0 0 +EDGE2 8409 5870 1.12917 -0.0176875 -0.0115311 1 0 1 1 0 0 +EDGE2 8409 8350 1.01722 -0.064508 0.0151355 1 0 1 1 0 0 +EDGE2 8409 1090 0.919294 0.0052153 -0.00979899 1 0 1 1 0 0 +EDGE2 8410 5869 -1.00859 -0.105301 0.0279952 1 0 1 1 0 0 +EDGE2 8410 8349 -1.00786 -0.0291918 0.00443527 1 0 1 1 0 0 +EDGE2 8410 8409 -0.966005 0.0992435 -0.0416802 1 0 1 1 0 0 +EDGE2 8410 1089 -0.973354 0.0191244 -0.0331764 1 0 1 1 0 0 +EDGE2 8410 8351 -0.0327253 1.03236 1.57731 1 0 1 1 0 0 +EDGE2 8410 1091 0.0316279 0.980134 1.56557 1 0 1 1 0 0 +EDGE2 8410 5871 0.0292859 1.01874 1.56545 1 0 1 1 0 0 +EDGE2 8410 5870 -0.0371829 -0.045306 -0.0193194 1 0 1 1 0 0 +EDGE2 8410 8350 -0.046098 -0.0199221 0.00534246 1 0 1 1 0 0 +EDGE2 8410 1090 -0.0565903 -0.0490195 -0.0209638 1 0 1 1 0 0 +EDGE2 8411 1092 1.06885 0.00856392 0.017845 1 0 1 1 0 0 +EDGE2 8411 8352 0.959886 0.0434024 -0.000590642 1 0 1 1 0 0 +EDGE2 8411 5872 1.05143 0.00299852 -0.0131882 1 0 1 1 0 0 +EDGE2 8411 8351 -0.0492522 0.0213094 0.00783203 1 0 1 1 0 0 +EDGE2 8411 1091 -0.0405218 0.0415302 0.000523821 1 0 1 1 0 0 +EDGE2 8411 5871 0.00249264 0.00780879 -0.0343312 1 0 1 1 0 0 +EDGE2 8411 5870 -1.0087 0.0237231 -1.54414 1 0 1 1 0 0 +EDGE2 8411 8350 -1.00781 -0.0665332 -1.57652 1 0 1 1 0 0 +EDGE2 8411 8410 -0.94351 -0.00244677 -1.56232 1 0 1 1 0 0 +EDGE2 8411 1090 -0.96598 -0.0119878 -1.57542 1 0 1 1 0 0 +EDGE2 8412 1092 0.00784656 0.0598498 -0.019752 1 0 1 1 0 0 +EDGE2 8412 8353 1.01936 -0.0958395 -0.0159391 1 0 1 1 0 0 +EDGE2 8412 1093 0.927062 -0.0916371 -0.0204362 1 0 1 1 0 0 +EDGE2 8412 5873 0.98854 0.000478292 -0.00853875 1 0 1 1 0 0 +EDGE2 8412 8352 0.0132525 -0.0641419 -0.0145159 1 0 1 1 0 0 +EDGE2 8412 5872 0.0752637 -0.00308382 -0.0214766 1 0 1 1 0 0 +EDGE2 8412 8351 -0.905947 0.0242273 0.00362568 1 0 1 1 0 0 +EDGE2 8412 8411 -1.01432 0.0124147 0.0156648 1 0 1 1 0 0 +EDGE2 8412 1091 -1.00378 0.0628076 -0.0355976 1 0 1 1 0 0 +EDGE2 8412 5871 -0.965056 -0.0319562 0.013568 1 0 1 1 0 0 +EDGE2 8413 1092 -0.970234 0.00854647 -0.0255645 1 0 1 1 0 0 +EDGE2 8413 8353 -0.0516651 0.0265 -0.0109908 1 0 1 1 0 0 +EDGE2 8413 1094 0.996859 -0.00871278 -0.0108651 1 0 1 1 0 0 +EDGE2 8413 8354 1.03298 -0.0678209 -0.0100607 1 0 1 1 0 0 +EDGE2 8413 5874 0.891773 0.0333414 -0.0140134 1 0 1 1 0 0 +EDGE2 8413 1093 0.0501938 -0.0185882 0.0700886 1 0 1 1 0 0 +EDGE2 8413 5873 -0.0890863 -0.0699008 0.00353383 1 0 1 1 0 0 +EDGE2 8413 8352 -0.944905 0.068896 0.0152263 1 0 1 1 0 0 +EDGE2 8413 8412 -0.977154 -0.0141041 -0.00553474 1 0 1 1 0 0 +EDGE2 8413 5872 -1.01155 0.0139942 -0.00487234 1 0 1 1 0 0 +EDGE2 8414 5795 0.966214 -0.0884895 -3.14684 1 0 1 1 0 0 +EDGE2 8414 8395 0.911205 0.00810238 -3.12628 1 0 1 1 0 0 +EDGE2 8414 5875 0.964948 -0.0319092 0.00197279 1 0 1 1 0 0 +EDGE2 8414 8355 0.998927 0.045122 0.0274121 1 0 1 1 0 0 +EDGE2 8414 5855 0.843106 -0.0260203 -3.16473 1 0 1 1 0 0 +EDGE2 8414 3035 1.06272 0.0227246 -3.10807 1 0 1 1 0 0 +EDGE2 8414 3055 0.979542 0.0234438 -3.16417 1 0 1 1 0 0 +EDGE2 8414 1095 1.00525 -0.034597 0.000538603 1 0 1 1 0 0 +EDGE2 8414 1115 0.985976 -0.0792959 -3.15844 1 0 1 1 0 0 +EDGE2 8414 1135 0.957275 0.0582965 -3.1441 1 0 1 1 0 0 +EDGE2 8414 8353 -0.932233 -0.0487109 0.0193501 1 0 1 1 0 0 +EDGE2 8414 1094 0.048068 -0.0257896 0.0237445 1 0 1 1 0 0 +EDGE2 8414 8354 -0.0679834 0.0370288 0.0153893 1 0 1 1 0 0 +EDGE2 8414 5874 -0.111224 0.0333982 0.0207954 1 0 1 1 0 0 +EDGE2 8414 8413 -1.04675 0.0163553 -0.0143178 1 0 1 1 0 0 +EDGE2 8414 1093 -1.01109 -0.0387593 -0.0127297 1 0 1 1 0 0 +EDGE2 8414 5873 -0.962101 -0.0268876 -0.0179009 1 0 1 1 0 0 +EDGE2 8415 5795 0.0248507 -0.0537619 -3.15003 1 0 1 1 0 0 +EDGE2 8415 8356 0.0309058 0.977606 1.57559 1 0 1 1 0 0 +EDGE2 8415 8396 -0.0410029 1.02942 1.55121 1 0 1 1 0 0 +EDGE2 8415 5856 -0.0309726 0.929516 1.58418 1 0 1 1 0 0 +EDGE2 8415 5876 -0.123134 1.01469 1.57148 1 0 1 1 0 0 +EDGE2 8415 3056 0.048663 1.03787 1.59169 1 0 1 1 0 0 +EDGE2 8415 5794 0.983068 -0.0491684 -3.12807 1 0 1 1 0 0 +EDGE2 8415 8394 1.05108 -0.0010974 -3.17833 1 0 1 1 0 0 +EDGE2 8415 5854 0.937599 -0.0464391 -3.13652 1 0 1 1 0 0 +EDGE2 8415 1134 1.00302 0.000246036 -3.13419 1 0 1 1 0 0 +EDGE2 8415 3034 0.940859 -0.0166052 -3.12543 1 0 1 1 0 0 +EDGE2 8415 3054 1.03553 -0.0587637 -3.14158 1 0 1 1 0 0 +EDGE2 8415 1114 0.988157 -0.0201067 -3.14009 1 0 1 1 0 0 +EDGE2 8415 8395 -0.00325538 0.0185412 -3.12137 1 0 1 1 0 0 +EDGE2 8415 5875 0.142557 -0.0111587 0.0055024 1 0 1 1 0 0 +EDGE2 8415 8355 0.00650684 -0.101905 0.0125606 1 0 1 1 0 0 +EDGE2 8415 5855 -0.0490075 0.104624 -3.14544 1 0 1 1 0 0 +EDGE2 8415 3035 -0.0112592 0.0507718 -3.13985 1 0 1 1 0 0 +EDGE2 8415 3055 0.0416527 0.0137238 -3.15229 1 0 1 1 0 0 +EDGE2 8415 1095 0.0831293 -0.00176899 -0.013465 1 0 1 1 0 0 +EDGE2 8415 1115 0.0400407 -0.0366746 -3.15166 1 0 1 1 0 0 +EDGE2 8415 1135 0.0462338 0.0172778 -3.09363 1 0 1 1 0 0 +EDGE2 8415 1094 -1.0612 0.0377042 -0.0156249 1 0 1 1 0 0 +EDGE2 8415 8354 -1.01349 -0.0203954 -0.0536464 1 0 1 1 0 0 +EDGE2 8415 8414 -1.06135 -0.0386025 -0.00758083 1 0 1 1 0 0 +EDGE2 8415 5874 -0.990941 -0.12719 -0.00510938 1 0 1 1 0 0 +EDGE2 8415 1116 -0.0286705 -0.895544 -1.527 1 0 1 1 0 0 +EDGE2 8415 3036 0.069536 -1.00321 -1.59866 1 0 1 1 0 0 +EDGE2 8415 5796 0.0242787 -1.03151 -1.57858 1 0 1 1 0 0 +EDGE2 8415 1136 -0.04431 -1.04544 -1.52975 1 0 1 1 0 0 +EDGE2 8415 1096 -0.0520649 -0.941242 -1.58887 1 0 1 1 0 0 +EDGE2 8416 5795 -1.04628 -0.00355656 1.56109 1 0 1 1 0 0 +EDGE2 8416 5877 1.09731 0.0898746 -0.00265217 1 0 1 1 0 0 +EDGE2 8416 8397 1.0336 0.0312602 -0.00750709 1 0 1 1 0 0 +EDGE2 8416 8357 0.931509 0.00135091 -0.02981 1 0 1 1 0 0 +EDGE2 8416 3057 1.01728 -0.105909 0.0402428 1 0 1 1 0 0 +EDGE2 8416 5857 0.897019 -0.0103391 -0.0140885 1 0 1 1 0 0 +EDGE2 8416 8356 0.0186238 -0.0215087 -0.038421 1 0 1 1 0 0 +EDGE2 8416 8396 0.0337761 0.0516766 0.0229021 1 0 1 1 0 0 +EDGE2 8416 5856 0.0268347 0.01849 0.0208676 1 0 1 1 0 0 +EDGE2 8416 5876 0.0097499 0.00582124 0.0202912 1 0 1 1 0 0 +EDGE2 8416 3056 -0.0805757 0.0179674 0.00887195 1 0 1 1 0 0 +EDGE2 8416 8395 -1.12808 -0.065136 1.5961 1 0 1 1 0 0 +EDGE2 8416 8415 -0.910196 -0.0171822 -1.57544 1 0 1 1 0 0 +EDGE2 8416 5875 -0.992261 0.0605958 -1.56427 1 0 1 1 0 0 +EDGE2 8416 8355 -0.973065 -0.0383272 -1.56269 1 0 1 1 0 0 +EDGE2 8416 5855 -0.965522 0.0215783 1.57812 1 0 1 1 0 0 +EDGE2 8416 3035 -1.01309 0.0386247 1.53402 1 0 1 1 0 0 +EDGE2 8416 3055 -1.08723 0.0702184 1.58203 1 0 1 1 0 0 +EDGE2 8416 1095 -0.964058 -0.0129916 -1.59733 1 0 1 1 0 0 +EDGE2 8416 1115 -1.07104 0.0491011 1.57097 1 0 1 1 0 0 +EDGE2 8416 1135 -1.0092 -0.0142934 1.56914 1 0 1 1 0 0 +EDGE2 8417 8358 0.968204 0.0374317 -0.0100126 1 0 1 1 0 0 +EDGE2 8417 8398 1.08764 0.080013 -0.016118 1 0 1 1 0 0 +EDGE2 8417 3058 0.971686 0.044993 0.00793838 1 0 1 1 0 0 +EDGE2 8417 5858 1.06393 -0.0309022 0.0093972 1 0 1 1 0 0 +EDGE2 8417 5878 0.974864 -0.0804196 0.0163033 1 0 1 1 0 0 +EDGE2 8417 5877 0.0593304 0.0190355 0.0115493 1 0 1 1 0 0 +EDGE2 8417 8397 -0.00603931 -0.00386485 0.0215679 1 0 1 1 0 0 +EDGE2 8417 8357 0.025039 0.0931984 0.0171374 1 0 1 1 0 0 +EDGE2 8417 3057 -0.0415118 0.0236972 0.00440876 1 0 1 1 0 0 +EDGE2 8417 5857 -0.0267203 0.0631035 0.0139205 1 0 1 1 0 0 +EDGE2 8417 8356 -0.979574 0.00103042 -0.0231035 1 0 1 1 0 0 +EDGE2 8417 8416 -1.00468 -0.00187012 -0.0094408 1 0 1 1 0 0 +EDGE2 8417 8396 -0.982288 0.06815 -0.00709327 1 0 1 1 0 0 +EDGE2 8417 5856 -0.982156 -0.0139728 -0.0108449 1 0 1 1 0 0 +EDGE2 8417 5876 -0.982398 -0.0559706 0.0137937 1 0 1 1 0 0 +EDGE2 8417 3056 -0.973527 -0.0891236 -0.0105674 1 0 1 1 0 0 +EDGE2 8418 8399 1.04358 -0.0821306 -0.0162081 1 0 1 1 0 0 +EDGE2 8418 5859 1.01289 0.0249361 -0.0121378 1 0 1 1 0 0 +EDGE2 8418 5879 0.95471 0.0429154 -0.0258721 1 0 1 1 0 0 +EDGE2 8418 8359 1.08061 -0.012375 -0.019252 1 0 1 1 0 0 +EDGE2 8418 3059 0.906772 0.0239311 0.0163048 1 0 1 1 0 0 +EDGE2 8418 8358 0.0304408 0.0452167 -0.037342 1 0 1 1 0 0 +EDGE2 8418 8398 0.0390565 -0.072419 0.0167043 1 0 1 1 0 0 +EDGE2 8418 3058 -0.0183512 0.0244543 -0.0121556 1 0 1 1 0 0 +EDGE2 8418 5858 0.0436131 0.0503478 0.0224828 1 0 1 1 0 0 +EDGE2 8418 5878 0.0809539 0.0130526 0.0397758 1 0 1 1 0 0 +EDGE2 8418 5877 -0.976726 -0.0497466 -0.00520386 1 0 1 1 0 0 +EDGE2 8418 8397 -1.06412 -0.041917 0.00458844 1 0 1 1 0 0 +EDGE2 8418 8417 -0.969424 0.0871381 -0.010523 1 0 1 1 0 0 +EDGE2 8418 8357 -1.03305 -0.0247134 -0.000243761 1 0 1 1 0 0 +EDGE2 8418 3057 -0.958813 0.0111706 -0.0183168 1 0 1 1 0 0 +EDGE2 8418 5857 -0.990276 -0.0473674 0.00468877 1 0 1 1 0 0 +EDGE2 8419 8360 1.1436 0.0594521 0.0423785 1 0 1 1 0 0 +EDGE2 8419 8400 0.907559 -0.160237 -0.00455122 1 0 1 1 0 0 +EDGE2 8419 8380 0.945276 0.063246 -3.12871 1 0 1 1 0 0 +EDGE2 8419 3060 0.95925 0.0484254 0.00441512 1 0 1 1 0 0 +EDGE2 8419 3160 0.980067 -0.00105756 -3.10006 1 0 1 1 0 0 +EDGE2 8419 5860 1.06829 -0.0473658 -0.00663827 1 0 1 1 0 0 +EDGE2 8419 5880 0.999048 0.0111815 0.00177142 1 0 1 1 0 0 +EDGE2 8419 3080 0.966212 -0.0114385 -3.17318 1 0 1 1 0 0 +EDGE2 8419 1080 0.942863 -0.0526246 -3.15688 1 0 1 1 0 0 +EDGE2 8419 8399 -0.0474175 0.0204675 -0.0170867 1 0 1 1 0 0 +EDGE2 8419 5859 0.00291563 -0.0210869 0.0512879 1 0 1 1 0 0 +EDGE2 8419 5879 0.0375375 0.02606 0.0023928 1 0 1 1 0 0 +EDGE2 8419 8359 -0.100386 -0.0184803 -0.0279236 1 0 1 1 0 0 +EDGE2 8419 3059 -0.0771984 0.0905303 0.00534318 1 0 1 1 0 0 +EDGE2 8419 8358 -1.08199 0.0428654 0.00403603 1 0 1 1 0 0 +EDGE2 8419 8418 -1.08185 0.0745327 -0.000555607 1 0 1 1 0 0 +EDGE2 8419 8398 -1.08189 -0.015328 0.000812136 1 0 1 1 0 0 +EDGE2 8419 3058 -1.07776 0.0510013 -0.0452913 1 0 1 1 0 0 +EDGE2 8419 5858 -0.99655 0.0519082 0.0186564 1 0 1 1 0 0 +EDGE2 8419 5878 -0.772296 -0.0788498 0.0092513 1 0 1 1 0 0 +EDGE2 8420 8360 -0.0732625 -0.0153992 0.0234617 1 0 1 1 0 0 +EDGE2 8420 8379 1.03519 0.0324264 -3.15807 1 0 1 1 0 0 +EDGE2 8420 3079 1.00289 -0.0363822 -3.14588 1 0 1 1 0 0 +EDGE2 8420 3159 0.955204 -0.0343788 -3.13328 1 0 1 1 0 0 +EDGE2 8420 1079 0.966607 0.0249032 -3.10667 1 0 1 1 0 0 +EDGE2 8420 8361 -0.0875864 -1.06026 -1.57354 1 0 1 1 0 0 +EDGE2 8420 8381 0.0395412 -0.968184 -1.56031 1 0 1 1 0 0 +EDGE2 8420 3081 0.0765275 -0.981837 -1.52316 1 0 1 1 0 0 +EDGE2 8420 3161 -0.0502344 -1.00315 -1.60398 1 0 1 1 0 0 +EDGE2 8420 5881 -0.0688622 -1.10232 -1.54336 1 0 1 1 0 0 +EDGE2 8420 3061 0.0339013 -0.990089 -1.57071 1 0 1 1 0 0 +EDGE2 8420 8400 0.0346933 -0.0297728 0.00708281 1 0 1 1 0 0 +EDGE2 8420 8380 0.0334463 0.0322723 -3.11695 1 0 1 1 0 0 +EDGE2 8420 8401 0.0468454 1.02525 1.57067 1 0 1 1 0 0 +EDGE2 8420 3060 -0.00499067 -0.0282463 -0.00485181 1 0 1 1 0 0 +EDGE2 8420 3160 0.0572728 -0.0662547 -3.14744 1 0 1 1 0 0 +EDGE2 8420 5860 0.0600345 -0.0372762 -0.0115717 1 0 1 1 0 0 +EDGE2 8420 5880 0.0349649 -0.0847629 -0.0134262 1 0 1 1 0 0 +EDGE2 8420 3080 -0.0433621 -0.0219146 -3.15198 1 0 1 1 0 0 +EDGE2 8420 1080 -0.0347572 -0.0701144 -3.1076 1 0 1 1 0 0 +EDGE2 8420 1081 0.0206738 0.949791 1.57364 1 0 1 1 0 0 +EDGE2 8420 5861 0.0548742 1.04771 1.58098 1 0 1 1 0 0 +EDGE2 8420 8399 -0.991919 -0.0236049 -0.0257677 1 0 1 1 0 0 +EDGE2 8420 8419 -0.955396 0.0196707 0.0168899 1 0 1 1 0 0 +EDGE2 8420 5859 -0.974536 -0.0500877 -0.0150973 1 0 1 1 0 0 +EDGE2 8420 5879 -0.970605 0.109584 -0.0155065 1 0 1 1 0 0 +EDGE2 8420 8359 -1.05965 0.0222916 -0.0180696 1 0 1 1 0 0 +EDGE2 8420 3059 -0.914732 0.00369666 0.00907692 1 0 1 1 0 0 +EDGE2 8421 8360 -1.03003 -0.00408286 1.56423 1 0 1 1 0 0 +EDGE2 8421 8362 1.02102 0.0421355 0.0370512 1 0 1 1 0 0 +EDGE2 8421 8382 0.955457 -0.092106 0.0335582 1 0 1 1 0 0 +EDGE2 8421 3082 0.947417 0.0263519 0.0023986 1 0 1 1 0 0 +EDGE2 8421 3162 0.971779 0.0409701 0.0207177 1 0 1 1 0 0 +EDGE2 8421 5882 1.01487 -0.0609573 -0.0181244 1 0 1 1 0 0 +EDGE2 8421 3062 0.925117 0.0964457 -0.0356323 1 0 1 1 0 0 +EDGE2 8421 8361 0.0349705 -0.0435836 0.0368576 1 0 1 1 0 0 +EDGE2 8421 8381 -0.00302199 -0.0807081 -0.0149033 1 0 1 1 0 0 +EDGE2 8421 3081 0.044035 -0.0828869 0.029098 1 0 1 1 0 0 +EDGE2 8421 3161 0.0159788 0.0019708 0.026974 1 0 1 1 0 0 +EDGE2 8421 5881 -0.0589912 0.0372523 0.0389454 1 0 1 1 0 0 +EDGE2 8421 3061 0.0293885 -0.0262328 -0.00426437 1 0 1 1 0 0 +EDGE2 8421 8400 -0.901156 0.0461764 1.56726 1 0 1 1 0 0 +EDGE2 8421 8420 -0.96881 0.0179417 1.57233 1 0 1 1 0 0 +EDGE2 8421 8380 -0.975966 -0.0418414 -1.55785 1 0 1 1 0 0 +EDGE2 8421 3060 -0.971189 0.09021 1.59547 1 0 1 1 0 0 +EDGE2 8421 3160 -1.01339 -0.0273294 -1.59392 1 0 1 1 0 0 +EDGE2 8421 5860 -0.915681 0.00858565 1.57183 1 0 1 1 0 0 +EDGE2 8421 5880 -0.956754 0.0834762 1.5576 1 0 1 1 0 0 +EDGE2 8421 3080 -0.986869 -0.024395 -1.5837 1 0 1 1 0 0 +EDGE2 8421 1080 -1.01123 0.0387449 -1.5515 1 0 1 1 0 0 +EDGE2 8422 8363 0.952901 0.0103045 -0.0240137 1 0 1 1 0 0 +EDGE2 8422 8383 1.03755 0.0846337 0.0224972 1 0 1 1 0 0 +EDGE2 8422 3083 0.974099 0.0440621 0.013479 1 0 1 1 0 0 +EDGE2 8422 3163 1.04469 -0.102033 0.0116571 1 0 1 1 0 0 +EDGE2 8422 5883 1.10105 0.0150028 -0.00447232 1 0 1 1 0 0 +EDGE2 8422 3063 1.01388 -0.0231098 0.00560072 1 0 1 1 0 0 +EDGE2 8422 8362 -0.0764477 -0.00728988 0.0147378 1 0 1 1 0 0 +EDGE2 8422 8382 -0.0692266 -0.0226263 -0.0030421 1 0 1 1 0 0 +EDGE2 8422 3082 -0.0170675 -0.019817 -0.0122403 1 0 1 1 0 0 +EDGE2 8422 3162 -0.00188889 0.0120945 -0.0141557 1 0 1 1 0 0 +EDGE2 8422 5882 0.0464923 -0.0729425 0.00783158 1 0 1 1 0 0 +EDGE2 8422 3062 -0.0124231 0.0137651 0.00382413 1 0 1 1 0 0 +EDGE2 8422 8361 -1.03282 -0.0226785 -0.0180497 1 0 1 1 0 0 +EDGE2 8422 8421 -0.937064 -0.075585 -0.00415427 1 0 1 1 0 0 +EDGE2 8422 8381 -1.03713 0.00423922 -0.00501151 1 0 1 1 0 0 +EDGE2 8422 3081 -0.973473 -0.00897231 -0.00405082 1 0 1 1 0 0 +EDGE2 8422 3161 -0.971764 -0.0579206 -0.0142249 1 0 1 1 0 0 +EDGE2 8422 5881 -1.06853 0.0337899 0.0211559 1 0 1 1 0 0 +EDGE2 8422 3061 -0.908942 -0.0217506 0.00460748 1 0 1 1 0 0 +EDGE2 8423 3064 0.979508 -0.0674249 0.0329178 1 0 1 1 0 0 +EDGE2 8423 8384 0.95354 -0.0110803 -0.0155975 1 0 1 1 0 0 +EDGE2 8423 3164 0.97968 -0.0152114 -0.000519064 1 0 1 1 0 0 +EDGE2 8423 5884 1.02873 0.0126907 -0.00939896 1 0 1 1 0 0 +EDGE2 8423 8364 1.00254 0.0241888 0.0174906 1 0 1 1 0 0 +EDGE2 8423 3084 1.01267 6.33972e-07 0.00780197 1 0 1 1 0 0 +EDGE2 8423 8363 0.00689516 0.0235671 -0.0504364 1 0 1 1 0 0 +EDGE2 8423 8383 -0.0312696 0.0561737 -0.0177824 1 0 1 1 0 0 +EDGE2 8423 3083 -0.038198 -0.0489679 -0.0020806 1 0 1 1 0 0 +EDGE2 8423 3163 0.0436681 0.0456327 -0.0177529 1 0 1 1 0 0 +EDGE2 8423 5883 0.00613448 0.0113747 0.00577943 1 0 1 1 0 0 +EDGE2 8423 3063 0.0307745 0.049952 -0.013732 1 0 1 1 0 0 +EDGE2 8423 8362 -0.963381 -0.0373796 -0.00644727 1 0 1 1 0 0 +EDGE2 8423 8422 -0.999655 -0.0335442 -0.00491679 1 0 1 1 0 0 +EDGE2 8423 8382 -1.04314 0.0106207 -0.0366999 1 0 1 1 0 0 +EDGE2 8423 3082 -1.03369 0.154652 0.0162202 1 0 1 1 0 0 +EDGE2 8423 3162 -0.983593 -0.0244841 -0.0372884 1 0 1 1 0 0 +EDGE2 8423 5882 -1.08041 0.106725 -0.0249789 1 0 1 1 0 0 +EDGE2 8423 3062 -0.951612 -0.0847273 0.0154232 1 0 1 1 0 0 +EDGE2 8424 8385 1.01064 -0.00205338 -0.0194449 1 0 1 1 0 0 +EDGE2 8424 3105 1.10814 -0.000431645 -3.14082 1 0 1 1 0 0 +EDGE2 8424 3485 1.04251 -0.0653311 -3.09583 1 0 1 1 0 0 +EDGE2 8424 5845 1.08483 -0.0499478 -3.13278 1 0 1 1 0 0 +EDGE2 8424 5885 1.01896 0.0389715 0.0174533 1 0 1 1 0 0 +EDGE2 8424 8365 0.983914 -0.0240208 -0.0281883 1 0 1 1 0 0 +EDGE2 8424 5825 0.879446 0.00792798 -3.11013 1 0 1 1 0 0 +EDGE2 8424 3145 0.98997 -0.0602677 -3.16617 1 0 1 1 0 0 +EDGE2 8424 3165 1.07489 -0.00330571 -0.0351677 1 0 1 1 0 0 +EDGE2 8424 3385 0.99831 0.054285 -3.12349 1 0 1 1 0 0 +EDGE2 8424 3125 1.19365 0.020294 -3.1543 1 0 1 1 0 0 +EDGE2 8424 1185 1.04213 -0.085317 -3.09877 1 0 1 1 0 0 +EDGE2 8424 3065 1.03329 -0.0218792 -0.0121636 1 0 1 1 0 0 +EDGE2 8424 3085 0.997819 -0.0390049 0.00371553 1 0 1 1 0 0 +EDGE2 8424 1165 0.995589 0.0275137 -3.1419 1 0 1 1 0 0 +EDGE2 8424 3064 0.0861222 0.0421256 -0.0262218 1 0 1 1 0 0 +EDGE2 8424 8384 2.34909e-05 0.023761 -0.00804375 1 0 1 1 0 0 +EDGE2 8424 3164 -0.0177701 0.00115975 -0.0182824 1 0 1 1 0 0 +EDGE2 8424 5884 -0.0253041 0.050276 -0.00552217 1 0 1 1 0 0 +EDGE2 8424 8364 -0.039096 0.0817278 -0.032963 1 0 1 1 0 0 +EDGE2 8424 3084 0.00492884 0.00292604 0.0409986 1 0 1 1 0 0 +EDGE2 8424 8363 -1.00009 -0.0233018 -0.00900576 1 0 1 1 0 0 +EDGE2 8424 8423 -0.975923 -0.00868108 0.0051707 1 0 1 1 0 0 +EDGE2 8424 8383 -0.990502 -0.0415403 -0.0162326 1 0 1 1 0 0 +EDGE2 8424 3083 -0.982359 0.0880415 0.00756186 1 0 1 1 0 0 +EDGE2 8424 3163 -1.03603 0.0126883 0.0109768 1 0 1 1 0 0 +EDGE2 8424 5883 -0.976631 0.051134 -0.00129023 1 0 1 1 0 0 +EDGE2 8424 3063 -0.988837 0.00375053 -0.0273868 1 0 1 1 0 0 +EDGE2 8425 8385 0.0506505 0.014908 -0.0192405 1 0 1 1 0 0 +EDGE2 8425 8366 0.020614 0.926688 1.53142 1 0 1 1 0 0 +EDGE2 8425 3146 -0.00362339 0.982021 1.53638 1 0 1 1 0 0 +EDGE2 8425 3386 0.0594061 0.895683 1.56521 1 0 1 1 0 0 +EDGE2 8425 5886 0.0582071 0.973844 1.55037 1 0 1 1 0 0 +EDGE2 8425 3066 0.019446 1.06944 1.63355 1 0 1 1 0 0 +EDGE2 8425 3144 0.989212 0.0278119 -3.14419 1 0 1 1 0 0 +EDGE2 8425 3484 1.00488 -0.0271793 -3.1045 1 0 1 1 0 0 +EDGE2 8425 5824 0.957566 0.0180663 -3.13205 1 0 1 1 0 0 +EDGE2 8425 5844 1.04751 0.0460534 -3.13401 1 0 1 1 0 0 +EDGE2 8425 3384 0.904241 0.0343078 -3.14001 1 0 1 1 0 0 +EDGE2 8425 1184 1.0253 0.0700486 -3.13192 1 0 1 1 0 0 +EDGE2 8425 3104 0.949174 0.0159307 -3.14595 1 0 1 1 0 0 +EDGE2 8425 3124 0.970925 0.0470657 -3.16004 1 0 1 1 0 0 +EDGE2 8425 1164 1.00114 0.0356815 -3.1243 1 0 1 1 0 0 +EDGE2 8425 3166 -0.0272849 -0.983143 -1.60393 1 0 1 1 0 0 +EDGE2 8425 3105 -0.0215554 0.0232824 -3.15472 1 0 1 1 0 0 +EDGE2 8425 3485 -0.0763394 -0.156392 -3.15544 1 0 1 1 0 0 +EDGE2 8425 5845 0.0284012 0.0106987 -3.11775 1 0 1 1 0 0 +EDGE2 8425 5885 -0.0552982 -0.00271133 0.00435374 1 0 1 1 0 0 +EDGE2 8425 8365 0.00709731 -0.00659204 -0.00796669 1 0 1 1 0 0 +EDGE2 8425 5825 0.0155783 0.0607486 -3.1423 1 0 1 1 0 0 +EDGE2 8425 3145 -0.0136633 0.0570919 -3.14679 1 0 1 1 0 0 +EDGE2 8425 3165 -0.00992706 -0.107467 0.0144529 1 0 1 1 0 0 +EDGE2 8425 3385 0.105995 0.0740021 -3.14026 1 0 1 1 0 0 +EDGE2 8425 3125 0.00858979 0.008265 -3.15292 1 0 1 1 0 0 +EDGE2 8425 1185 -0.0357619 0.0547708 -3.11802 1 0 1 1 0 0 +EDGE2 8425 3065 -0.0349761 0.0320484 0.00961692 1 0 1 1 0 0 +EDGE2 8425 3085 0.0666539 -0.0169513 -0.0172278 1 0 1 1 0 0 +EDGE2 8425 1165 0.0103306 -0.0401994 -3.12076 1 0 1 1 0 0 +EDGE2 8425 5826 0.0129376 -1.05248 -1.58032 1 0 1 1 0 0 +EDGE2 8425 5846 0.0759961 -1.13105 -1.54253 1 0 1 1 0 0 +EDGE2 8425 8386 0.0667088 -1.13717 -1.56487 1 0 1 1 0 0 +EDGE2 8425 3486 -0.0408208 -0.971673 -1.58087 1 0 1 1 0 0 +EDGE2 8425 1166 -0.0269054 -1.06671 -1.57827 1 0 1 1 0 0 +EDGE2 8425 3086 0.0549432 -1.03246 -1.55611 1 0 1 1 0 0 +EDGE2 8425 3106 0.00144689 -1.02917 -1.54861 1 0 1 1 0 0 +EDGE2 8425 3126 -0.0083234 -1.05321 -1.55472 1 0 1 1 0 0 +EDGE2 8425 1186 0.015846 -1.08659 -1.60215 1 0 1 1 0 0 +EDGE2 8425 3064 -0.926184 -0.0720696 0.000708495 1 0 1 1 0 0 +EDGE2 8425 8384 -1.01097 0.0390928 0.0182582 1 0 1 1 0 0 +EDGE2 8425 8424 -1.03477 -0.0366238 0.00162742 1 0 1 1 0 0 +EDGE2 8425 3164 -1.04192 0.049626 0.0269002 1 0 1 1 0 0 +EDGE2 8425 5884 -1.028 -0.000677677 0.00369117 1 0 1 1 0 0 +EDGE2 8425 8364 -0.972905 -0.0184435 0.0423469 1 0 1 1 0 0 +EDGE2 8425 3084 -1.0354 0.0590343 -0.0041022 1 0 1 1 0 0 +EDGE2 8426 8385 -0.98168 -0.0304138 -1.57982 1 0 1 1 0 0 +EDGE2 8426 8366 0.0589356 -0.0201389 -0.00740711 1 0 1 1 0 0 +EDGE2 8426 3147 0.978872 0.0264755 0.00581854 1 0 1 1 0 0 +EDGE2 8426 5887 0.907276 0.00833539 0.0167502 1 0 1 1 0 0 +EDGE2 8426 8367 1.05246 -0.129674 0.000738575 1 0 1 1 0 0 +EDGE2 8426 3387 0.962392 0.00478847 -0.0106862 1 0 1 1 0 0 +EDGE2 8426 3067 0.98976 -0.0288296 -0.020024 1 0 1 1 0 0 +EDGE2 8426 3146 -0.0550003 -0.0655633 -0.0090623 1 0 1 1 0 0 +EDGE2 8426 3386 0.0222387 -0.0138495 -0.0246524 1 0 1 1 0 0 +EDGE2 8426 5886 -0.0613406 0.0636665 -0.000394407 1 0 1 1 0 0 +EDGE2 8426 3066 -0.0615617 0.0160215 -0.0121625 1 0 1 1 0 0 +EDGE2 8426 8425 -1.01926 -0.106747 -1.52212 1 0 1 1 0 0 +EDGE2 8426 3105 -1.02946 -0.0439944 1.55385 1 0 1 1 0 0 +EDGE2 8426 3485 -1.02025 0.0356011 1.57287 1 0 1 1 0 0 +EDGE2 8426 5845 -1.00495 -0.0261771 1.58569 1 0 1 1 0 0 +EDGE2 8426 5885 -0.944609 0.0210977 -1.53523 1 0 1 1 0 0 +EDGE2 8426 8365 -1.05454 0.0905726 -1.56568 1 0 1 1 0 0 +EDGE2 8426 5825 -0.999873 -0.0112772 1.57278 1 0 1 1 0 0 +EDGE2 8426 3145 -0.922388 -0.0282821 1.53975 1 0 1 1 0 0 +EDGE2 8426 3165 -1.00577 -0.0130378 -1.57174 1 0 1 1 0 0 +EDGE2 8426 3385 -1.00207 0.00951057 1.58365 1 0 1 1 0 0 +EDGE2 8426 3125 -1.05483 -0.0796023 1.56435 1 0 1 1 0 0 +EDGE2 8426 1185 -0.904428 -0.113894 1.55375 1 0 1 1 0 0 +EDGE2 8426 3065 -1.01733 -0.0486182 -1.54833 1 0 1 1 0 0 +EDGE2 8426 3085 -0.982939 -0.00379873 -1.55999 1 0 1 1 0 0 +EDGE2 8426 1165 -1.00776 -0.0230236 1.53835 1 0 1 1 0 0 +EDGE2 8427 8366 -1.0253 -0.00245014 -0.0156322 1 0 1 1 0 0 +EDGE2 8427 5888 1.01786 -0.0106331 0.00840586 1 0 1 1 0 0 +EDGE2 8427 8368 0.974375 0.000312161 -0.00584596 1 0 1 1 0 0 +EDGE2 8427 3068 0.987284 0.0176799 -0.00372174 1 0 1 1 0 0 +EDGE2 8427 3148 1.02224 0.0524768 -0.000811971 1 0 1 1 0 0 +EDGE2 8427 3388 0.891611 0.04506 -0.0595237 1 0 1 1 0 0 +EDGE2 8427 3147 -0.0718691 -0.101678 0.0182678 1 0 1 1 0 0 +EDGE2 8427 5887 0.00752428 -0.0717483 -0.0225841 1 0 1 1 0 0 +EDGE2 8427 8367 -0.0453565 0.00191145 -0.00716407 1 0 1 1 0 0 +EDGE2 8427 3387 0.073528 -0.0275634 0.00308887 1 0 1 1 0 0 +EDGE2 8427 3067 0.0211105 0.0327205 0.018536 1 0 1 1 0 0 +EDGE2 8427 8426 -0.960122 0.0477263 0.0132127 1 0 1 1 0 0 +EDGE2 8427 3146 -1.02235 0.0400152 -0.00310428 1 0 1 1 0 0 +EDGE2 8427 3386 -1.02377 0.00468195 0.0440544 1 0 1 1 0 0 +EDGE2 8427 5886 -1.04476 -0.040069 -0.050051 1 0 1 1 0 0 +EDGE2 8427 3066 -0.995988 -0.0540074 0.0151817 1 0 1 1 0 0 +EDGE2 8428 5889 0.989658 0.0406414 -0.039105 1 0 1 1 0 0 +EDGE2 8428 8369 0.919332 -0.0353217 0.0322696 1 0 1 1 0 0 +EDGE2 8428 3149 1.03216 -0.0525518 -0.00984701 1 0 1 1 0 0 +EDGE2 8428 3389 1.0313 0.112113 -0.0311443 1 0 1 1 0 0 +EDGE2 8428 3069 0.931279 -0.0127197 -0.00384727 1 0 1 1 0 0 +EDGE2 8428 5888 -0.100623 -0.0262412 -0.0234699 1 0 1 1 0 0 +EDGE2 8428 8368 -0.0781603 0.0381289 0.0037641 1 0 1 1 0 0 +EDGE2 8428 3068 -0.00661719 0.0384641 -0.0217704 1 0 1 1 0 0 +EDGE2 8428 3148 -0.0476265 0.0209039 0.0444677 1 0 1 1 0 0 +EDGE2 8428 3388 -0.0349442 -0.0662634 -0.00946715 1 0 1 1 0 0 +EDGE2 8428 3147 -1.05394 0.0297193 0.0153454 1 0 1 1 0 0 +EDGE2 8428 5887 -1.07807 -0.0628673 0.0177478 1 0 1 1 0 0 +EDGE2 8428 8367 -0.992315 -0.0101051 -0.00496294 1 0 1 1 0 0 +EDGE2 8428 8427 -0.979793 0.0763163 -0.0214749 1 0 1 1 0 0 +EDGE2 8428 3387 -0.925805 -0.0158038 0.0260705 1 0 1 1 0 0 +EDGE2 8428 3067 -0.940585 0.0334855 0.011734 1 0 1 1 0 0 +EDGE2 8429 8370 0.951165 -0.0113568 0.020723 1 0 1 1 0 0 +EDGE2 8429 3070 0.986277 -0.0234101 0.00220665 1 0 1 1 0 0 +EDGE2 8429 3390 1.0638 0.0210055 0.00163842 1 0 1 1 0 0 +EDGE2 8429 3410 0.984561 -0.0799562 -3.16352 1 0 1 1 0 0 +EDGE2 8429 5890 1.10663 -0.0265275 -0.0404818 1 0 1 1 0 0 +EDGE2 8429 3150 1.04756 -0.108069 -0.0223792 1 0 1 1 0 0 +EDGE2 8429 5889 -0.0384445 0.0913216 0.00310463 1 0 1 1 0 0 +EDGE2 8429 8369 0.00844446 -0.0759042 0.0192373 1 0 1 1 0 0 +EDGE2 8429 3149 -0.0292588 0.0383731 -0.017449 1 0 1 1 0 0 +EDGE2 8429 3389 -0.0907127 -0.0467157 -0.00864091 1 0 1 1 0 0 +EDGE2 8429 3069 -0.0341205 0.0320763 -0.00874952 1 0 1 1 0 0 +EDGE2 8429 5888 -1.05373 0.0975228 0.0195227 1 0 1 1 0 0 +EDGE2 8429 8428 -1.00144 0.00863867 -0.0252673 1 0 1 1 0 0 +EDGE2 8429 8368 -1.06587 0.0835436 0.00864748 1 0 1 1 0 0 +EDGE2 8429 3068 -1.04958 0.0520361 -0.0282595 1 0 1 1 0 0 +EDGE2 8429 3148 -0.883027 0.0346519 0.0263795 1 0 1 1 0 0 +EDGE2 8429 3388 -0.950883 0.00914942 0.0067829 1 0 1 1 0 0 +EDGE2 8430 3409 1.05103 -0.0703885 -3.14551 1 0 1 1 0 0 +EDGE2 8430 8370 0.0514844 -0.0616655 0.0204674 1 0 1 1 0 0 +EDGE2 8430 3411 -0.037963 -1.01785 -1.55825 1 0 1 1 0 0 +EDGE2 8430 5891 0.0472156 -0.948228 -1.57801 1 0 1 1 0 0 +EDGE2 8430 3391 -0.0712758 -0.965693 -1.53284 1 0 1 1 0 0 +EDGE2 8430 3070 0.0621391 -0.00774557 -0.00402013 1 0 1 1 0 0 +EDGE2 8430 3390 0.0279369 0.00519691 0.00440739 1 0 1 1 0 0 +EDGE2 8430 3410 -0.122916 -0.102908 -3.14998 1 0 1 1 0 0 +EDGE2 8430 5890 0.0139225 0.00760279 -0.0053891 1 0 1 1 0 0 +EDGE2 8430 3150 0.0148625 0.0621082 0.0351609 1 0 1 1 0 0 +EDGE2 8430 5889 -0.981746 -0.00916772 0.00402059 1 0 1 1 0 0 +EDGE2 8430 8429 -0.881449 -0.0687367 -0.0111107 1 0 1 1 0 0 +EDGE2 8430 8369 -1.09224 0.0230356 0.0016883 1 0 1 1 0 0 +EDGE2 8430 3149 -1.08284 0.0503122 -0.0214175 1 0 1 1 0 0 +EDGE2 8430 3389 -0.862647 -0.0570369 0.00157328 1 0 1 1 0 0 +EDGE2 8430 3069 -1.07421 -0.0590079 0.0293529 1 0 1 1 0 0 +EDGE2 8430 3151 -0.0451656 1.03172 1.52824 1 0 1 1 0 0 +EDGE2 8430 8371 -0.00988632 1.06501 1.5668 1 0 1 1 0 0 +EDGE2 8430 3071 0.0346742 1.02918 1.55231 1 0 1 1 0 0 +EDGE2 8431 8370 -0.916774 0.0109545 1.55289 1 0 1 1 0 0 +EDGE2 8431 3412 0.995304 -0.0908207 -0.0163406 1 0 1 1 0 0 +EDGE2 8431 5892 1.03049 -0.0815472 0.0196854 1 0 1 1 0 0 +EDGE2 8431 3392 1.00494 0.0201423 -0.0236085 1 0 1 1 0 0 +EDGE2 8431 3411 0.126473 0.0157364 -0.0232513 1 0 1 1 0 0 +EDGE2 8431 5891 0.0737113 -0.0268237 0.0284227 1 0 1 1 0 0 +EDGE2 8431 3391 -0.0615583 -0.0239269 -0.0213558 1 0 1 1 0 0 +EDGE2 8431 8430 -0.933668 -0.0441963 1.58188 1 0 1 1 0 0 +EDGE2 8431 3070 -0.979668 -0.0668062 1.62034 1 0 1 1 0 0 +EDGE2 8431 3390 -0.950298 0.0624719 1.57509 1 0 1 1 0 0 +EDGE2 8431 3410 -0.966258 -0.0273578 -1.54272 1 0 1 1 0 0 +EDGE2 8431 5890 -1.01389 0.0194049 1.59595 1 0 1 1 0 0 +EDGE2 8431 3150 -1.01338 -0.121866 1.54133 1 0 1 1 0 0 +EDGE2 8432 3413 1.08871 0.0905748 0.00682127 1 0 1 1 0 0 +EDGE2 8432 5893 0.955337 0.0315682 0.0255097 1 0 1 1 0 0 +EDGE2 8432 3393 0.885364 0.122132 0.0503374 1 0 1 1 0 0 +EDGE2 8432 3412 -0.0573552 0.00998076 0.00829245 1 0 1 1 0 0 +EDGE2 8432 5892 -0.0247738 -0.0560657 -0.00361032 1 0 1 1 0 0 +EDGE2 8432 3392 0.0151846 -0.0373536 0.0173605 1 0 1 1 0 0 +EDGE2 8432 3411 -0.964538 -0.0253827 -0.00685109 1 0 1 1 0 0 +EDGE2 8432 5891 -0.942308 0.00556454 -0.00946714 1 0 1 1 0 0 +EDGE2 8432 8431 -0.950725 0.0634293 -0.00364252 1 0 1 1 0 0 +EDGE2 8432 3391 -0.972154 -0.103733 -0.0143899 1 0 1 1 0 0 +EDGE2 8433 3414 1.0434 0.00963428 -0.000468842 1 0 1 1 0 0 +EDGE2 8433 5894 1.01847 -0.0415764 -0.0106149 1 0 1 1 0 0 +EDGE2 8433 3394 0.983366 -0.0325384 -0.00943365 1 0 1 1 0 0 +EDGE2 8433 3413 0.0135415 0.0502478 -0.040777 1 0 1 1 0 0 +EDGE2 8433 5893 0.024833 0.02996 0.00050388 1 0 1 1 0 0 +EDGE2 8433 3393 -0.0887292 0.0381983 0.0235702 1 0 1 1 0 0 +EDGE2 8433 3412 -0.978233 -0.00228983 0.00295705 1 0 1 1 0 0 +EDGE2 8433 5892 -1.01132 -0.00467299 -0.0139581 1 0 1 1 0 0 +EDGE2 8433 8432 -1.07499 0.0172194 0.0284746 1 0 1 1 0 0 +EDGE2 8433 3392 -1.01036 0.0457214 -0.0128902 1 0 1 1 0 0 +EDGE2 8434 3395 1.03371 -0.0566046 0.0162901 1 0 1 1 0 0 +EDGE2 8434 3435 0.99718 0.106919 -3.12768 1 0 1 1 0 0 +EDGE2 8434 5895 0.876306 -0.0854308 -0.0113108 1 0 1 1 0 0 +EDGE2 8434 3415 0.955965 0.0800738 -0.00373606 1 0 1 1 0 0 +EDGE2 8434 855 0.949649 -0.0454804 -3.10687 1 0 1 1 0 0 +EDGE2 8434 895 0.977683 -0.0145598 -3.11371 1 0 1 1 0 0 +EDGE2 8434 915 0.995142 -0.0348424 -3.15526 1 0 1 1 0 0 +EDGE2 8434 835 1.05143 0.0235002 -3.183 1 0 1 1 0 0 +EDGE2 8434 3414 0.0401894 0.0594101 0.0121645 1 0 1 1 0 0 +EDGE2 8434 5894 0.0173628 0.034935 0.0108437 1 0 1 1 0 0 +EDGE2 8434 3394 0.0199546 -0.0179806 0.0172337 1 0 1 1 0 0 +EDGE2 8434 3413 -0.984807 -0.0234942 -0.00142557 1 0 1 1 0 0 +EDGE2 8434 5893 -0.970231 0.0581652 -0.0150748 1 0 1 1 0 0 +EDGE2 8434 8433 -1.01664 0.0511732 -0.044897 1 0 1 1 0 0 +EDGE2 8434 3393 -1.0137 0.0204832 0.0323654 1 0 1 1 0 0 +EDGE2 8435 3395 -0.0414752 0.0681825 0.0101041 1 0 1 1 0 0 +EDGE2 8435 3396 -0.083697 0.983634 1.55108 1 0 1 1 0 0 +EDGE2 8435 5896 -0.00864432 1.00554 1.55622 1 0 1 1 0 0 +EDGE2 8435 916 0.0228252 1.01137 1.55664 1 0 1 1 0 0 +EDGE2 8435 3434 0.948152 -0.0744797 -3.14598 1 0 1 1 0 0 +EDGE2 8435 894 0.977599 -0.0743726 -3.166 1 0 1 1 0 0 +EDGE2 8435 914 0.97185 0.000387352 -3.15229 1 0 1 1 0 0 +EDGE2 8435 834 0.994122 -0.00702529 -3.10864 1 0 1 1 0 0 +EDGE2 8435 854 0.970868 0.0394569 -3.14107 1 0 1 1 0 0 +EDGE2 8435 3435 0.0311351 -0.00238325 -3.12901 1 0 1 1 0 0 +EDGE2 8435 5895 -0.0732357 -0.0244209 0.000804741 1 0 1 1 0 0 +EDGE2 8435 3415 0.0316311 -0.0145532 0.0257758 1 0 1 1 0 0 +EDGE2 8435 855 -0.0493252 0.0441905 -3.17074 1 0 1 1 0 0 +EDGE2 8435 895 -0.0114385 0.0379184 -3.1251 1 0 1 1 0 0 +EDGE2 8435 915 -0.0239597 -0.0353174 -3.10634 1 0 1 1 0 0 +EDGE2 8435 835 0.0241578 0.0182829 -3.15213 1 0 1 1 0 0 +EDGE2 8435 3414 -0.996914 -0.0163962 0.0344277 1 0 1 1 0 0 +EDGE2 8435 5894 -1.01444 0.0665922 -0.0319444 1 0 1 1 0 0 +EDGE2 8435 8434 -1.06365 0.0589021 0.018145 1 0 1 1 0 0 +EDGE2 8435 3394 -0.992558 0.0557507 0.00752404 1 0 1 1 0 0 +EDGE2 8435 3436 0.0888143 -1.00852 -1.54077 1 0 1 1 0 0 +EDGE2 8435 856 -0.0461703 -0.95057 -1.56953 1 0 1 1 0 0 +EDGE2 8435 896 0.00228264 -1.01347 -1.56878 1 0 1 1 0 0 +EDGE2 8435 3416 -0.079992 -0.984365 -1.57869 1 0 1 1 0 0 +EDGE2 8435 836 -0.0544042 -0.960657 -1.61592 1 0 1 1 0 0 +EDGE2 8436 3395 -0.990309 0.0246658 -1.57788 1 0 1 1 0 0 +EDGE2 8436 917 0.971926 0.0123818 -0.0370808 1 0 1 1 0 0 +EDGE2 8436 3397 1.05778 -0.021701 0.0119211 1 0 1 1 0 0 +EDGE2 8436 5897 1.01378 0.0126472 -0.0138461 1 0 1 1 0 0 +EDGE2 8436 3396 -0.0576402 -0.0351833 0.0227182 1 0 1 1 0 0 +EDGE2 8436 5896 -0.0620818 -0.000456091 0.0113207 1 0 1 1 0 0 +EDGE2 8436 916 -0.0147159 -0.0422282 0.0133071 1 0 1 1 0 0 +EDGE2 8436 8435 -0.999395 -0.0453763 -1.56362 1 0 1 1 0 0 +EDGE2 8436 3435 -1.00813 0.0452034 1.56256 1 0 1 1 0 0 +EDGE2 8436 5895 -0.994462 -0.0601218 -1.57466 1 0 1 1 0 0 +EDGE2 8436 3415 -0.952466 0.0107835 -1.57846 1 0 1 1 0 0 +EDGE2 8436 855 -1.03191 -0.0260295 1.57354 1 0 1 1 0 0 +EDGE2 8436 895 -1.01024 -0.0556945 1.59519 1 0 1 1 0 0 +EDGE2 8436 915 -0.978533 0.0479055 1.58162 1 0 1 1 0 0 +EDGE2 8436 835 -0.959429 0.0631418 1.54875 1 0 1 1 0 0 +EDGE2 8437 918 0.953955 -0.00743798 -0.00678102 1 0 1 1 0 0 +EDGE2 8437 3398 1.09998 0.0289501 -0.0306566 1 0 1 1 0 0 +EDGE2 8437 5898 0.965677 -0.0022581 -0.0147458 1 0 1 1 0 0 +EDGE2 8437 917 0.00648334 -0.0706044 -0.0297639 1 0 1 1 0 0 +EDGE2 8437 3397 0.0899366 0.0331519 -0.0210509 1 0 1 1 0 0 +EDGE2 8437 5897 0.022467 0.00162266 -0.00541621 1 0 1 1 0 0 +EDGE2 8437 3396 -0.898693 -0.00909246 -0.0117406 1 0 1 1 0 0 +EDGE2 8437 5896 -1.06416 -0.00147994 -0.0179319 1 0 1 1 0 0 +EDGE2 8437 8436 -1.05582 0.017351 -0.00967498 1 0 1 1 0 0 +EDGE2 8437 916 -0.945267 -0.058234 0.0480143 1 0 1 1 0 0 +EDGE2 8438 5899 1.03645 0.0725187 0.028234 1 0 1 1 0 0 +EDGE2 8438 919 0.943905 -0.0311689 0.0164014 1 0 1 1 0 0 +EDGE2 8438 3399 0.924763 -0.0156869 0.0196491 1 0 1 1 0 0 +EDGE2 8438 918 -0.0214396 0.0159655 0.0215367 1 0 1 1 0 0 +EDGE2 8438 3398 -0.060152 0.068066 -0.0277085 1 0 1 1 0 0 +EDGE2 8438 5898 -0.032331 -0.0552056 0.0263946 1 0 1 1 0 0 +EDGE2 8438 8437 -1.00598 -0.012645 -0.0238608 1 0 1 1 0 0 +EDGE2 8438 917 -1.03986 0.0622347 0.0415226 1 0 1 1 0 0 +EDGE2 8438 3397 -0.948442 0.0160023 -0.00711265 1 0 1 1 0 0 +EDGE2 8438 5897 -1.02831 0.0334101 0.0188663 1 0 1 1 0 0 +EDGE2 8439 5900 1.01281 0.00049892 0.0141603 1 0 1 1 0 0 +EDGE2 8439 920 1.0392 -0.0716912 0.00181023 1 0 1 1 0 0 +EDGE2 8439 3400 1.0421 0.0215843 -0.00584432 1 0 1 1 0 0 +EDGE2 8439 680 1.00351 -0.0156836 -3.14752 1 0 1 1 0 0 +EDGE2 8439 5899 -0.0709558 -0.0539258 -0.0214413 1 0 1 1 0 0 +EDGE2 8439 8438 -1.05397 -0.0699431 -0.0195618 1 0 1 1 0 0 +EDGE2 8439 919 0.101754 0.0344897 0.00064472 1 0 1 1 0 0 +EDGE2 8439 3399 0.00387903 0.0377794 -0.0133138 1 0 1 1 0 0 +EDGE2 8439 918 -0.972976 -0.0479999 -0.027439 1 0 1 1 0 0 +EDGE2 8439 3398 -0.931681 0.0373698 0.0372857 1 0 1 1 0 0 +EDGE2 8439 5898 -0.936435 0.00100517 0.0299862 1 0 1 1 0 0 +EDGE2 8440 921 -0.0225688 1.04708 1.59696 1 0 1 1 0 0 +EDGE2 8440 679 1.02614 -0.0604892 -3.15794 1 0 1 1 0 0 +EDGE2 8440 681 0.0963252 -1.02653 -1.57924 1 0 1 1 0 0 +EDGE2 8440 5901 -0.031388 -0.908649 -1.59367 1 0 1 1 0 0 +EDGE2 8440 5900 -0.0462604 0.0573766 0.0299747 1 0 1 1 0 0 +EDGE2 8440 920 0.0169649 0.0417616 -0.0584955 1 0 1 1 0 0 +EDGE2 8440 3400 -0.0426625 0.019845 -0.000594631 1 0 1 1 0 0 +EDGE2 8440 680 0.00290326 -0.0701386 -3.11798 1 0 1 1 0 0 +EDGE2 8440 3401 0.00907684 0.970274 1.55884 1 0 1 1 0 0 +EDGE2 8440 5899 -0.991129 0.0271991 -0.0193577 1 0 1 1 0 0 +EDGE2 8440 8439 -0.931264 -0.0318626 0.0220714 1 0 1 1 0 0 +EDGE2 8440 919 -0.991363 -0.0114008 -0.00586917 1 0 1 1 0 0 +EDGE2 8440 3399 -0.956257 -0.00603452 0.0124013 1 0 1 1 0 0 +EDGE2 8441 921 -0.0519487 -0.0273559 -0.0162891 1 0 1 1 0 0 +EDGE2 8441 5900 -1.00233 0.00508024 -1.54891 1 0 1 1 0 0 +EDGE2 8441 8440 -0.959039 -0.111245 -1.55979 1 0 1 1 0 0 +EDGE2 8441 920 -1.04818 0.0357436 -1.60047 1 0 1 1 0 0 +EDGE2 8441 3400 -0.90504 -0.0518258 -1.59332 1 0 1 1 0 0 +EDGE2 8441 680 -0.983059 0.0140709 1.54414 1 0 1 1 0 0 +EDGE2 8441 3401 0.0398287 0.0714674 0.0100613 1 0 1 1 0 0 +EDGE2 8441 3402 0.964977 0.0531129 0.00522374 1 0 1 1 0 0 +EDGE2 8441 922 0.951517 0.0699024 -0.0382069 1 0 1 1 0 0 +EDGE2 8442 921 -0.969958 -0.0558902 0.0138043 1 0 1 1 0 0 +EDGE2 8442 8441 -0.956767 -0.0455291 -0.00573053 1 0 1 1 0 0 +EDGE2 8442 3401 -0.969798 0.0191225 0.00313019 1 0 1 1 0 0 +EDGE2 8442 3402 -0.00346479 0.0171754 0.0365242 1 0 1 1 0 0 +EDGE2 8442 922 -0.0339591 -0.0500982 0.00621147 1 0 1 1 0 0 +EDGE2 8442 923 0.984614 0.0130867 -0.0148749 1 0 1 1 0 0 +EDGE2 8442 3403 1.04238 -0.0790451 0.0190386 1 0 1 1 0 0 +EDGE2 8443 3402 -1.02625 0.0021852 0.00144301 1 0 1 1 0 0 +EDGE2 8443 8442 -1.01369 0.0171877 0.0499492 1 0 1 1 0 0 +EDGE2 8443 922 -1.01574 -0.0394645 0.0143252 1 0 1 1 0 0 +EDGE2 8443 923 -0.00575957 0.0374733 0.00453285 1 0 1 1 0 0 +EDGE2 8443 3403 -0.0135896 0.0217826 0.00946001 1 0 1 1 0 0 +EDGE2 8443 924 1.03529 0.0101245 0.0249579 1 0 1 1 0 0 +EDGE2 8443 3404 1.08184 -0.0311689 -0.0232432 1 0 1 1 0 0 +EDGE2 8444 923 -0.941217 -0.0472914 0.00667045 1 0 1 1 0 0 +EDGE2 8444 3403 -0.967564 0.0272933 0.0170395 1 0 1 1 0 0 +EDGE2 8444 8443 -1.0775 -0.0509796 -0.00758208 1 0 1 1 0 0 +EDGE2 8444 924 -0.0828945 0.0442573 -0.0229214 1 0 1 1 0 0 +EDGE2 8444 3404 0.0162949 -0.0585524 -0.0293049 1 0 1 1 0 0 +EDGE2 8444 925 1.01358 0.0355941 -0.0209196 1 0 1 1 0 0 +EDGE2 8444 3405 0.990092 -0.0655825 0.00294408 1 0 1 1 0 0 +EDGE2 8445 926 -0.00182704 -0.939386 -1.5513 1 0 1 1 0 0 +EDGE2 8445 3406 -0.0228205 0.975685 1.56776 1 0 1 1 0 0 +EDGE2 8445 8444 -0.901393 -0.0138788 0.0233197 1 0 1 1 0 0 +EDGE2 8445 924 -1.0258 0.0461415 0.0269319 1 0 1 1 0 0 +EDGE2 8445 3404 -1.12586 0.00389259 -0.0122937 1 0 1 1 0 0 +EDGE2 8445 925 0.08249 0.00258264 -0.0106471 1 0 1 1 0 0 +EDGE2 8445 3405 0.0530166 -0.0556016 -0.00492279 1 0 1 1 0 0 +EDGE2 8446 927 0.97914 0.0391809 -0.000557829 1 0 1 1 0 0 +EDGE2 8446 926 -0.0537879 -0.0601419 -0.001819 1 0 1 1 0 0 +EDGE2 8446 8445 -1.01034 -0.0460637 1.58719 1 0 1 1 0 0 +EDGE2 8446 925 -0.91953 -0.0505005 1.58691 1 0 1 1 0 0 +EDGE2 8446 3405 -0.97646 0.111086 1.59477 1 0 1 1 0 0 +EDGE2 8447 8446 -1.03385 0.0265216 0.023953 1 0 1 1 0 0 +EDGE2 8447 928 0.988593 -0.0384658 0.0340004 1 0 1 1 0 0 +EDGE2 8447 927 0.0328535 -0.0238462 -0.00512795 1 0 1 1 0 0 +EDGE2 8447 926 -0.946259 0.0106155 -0.0314125 1 0 1 1 0 0 +EDGE2 8448 929 1.04134 0.0146717 0.00762673 1 0 1 1 0 0 +EDGE2 8448 8447 -1.02093 -0.0295769 -0.0460611 1 0 1 1 0 0 +EDGE2 8448 928 -0.00197575 -0.013681 0.00134722 1 0 1 1 0 0 +EDGE2 8448 927 -0.949009 -0.0705072 -0.0250881 1 0 1 1 0 0 +EDGE2 8449 930 1.02121 -0.0355951 -0.0151817 1 0 1 1 0 0 +EDGE2 8449 670 1.00824 -0.0886866 -3.1443 1 0 1 1 0 0 +EDGE2 8449 929 -0.0432732 0.0199794 -0.0200055 1 0 1 1 0 0 +EDGE2 8449 928 -0.980061 -0.0401721 -0.0234836 1 0 1 1 0 0 +EDGE2 8449 8448 -1.03994 0.0423848 0.0123809 1 0 1 1 0 0 +EDGE2 8450 669 1.08418 0.119761 -3.17489 1 0 1 1 0 0 +EDGE2 8450 671 -0.0361235 -0.979931 -1.54714 1 0 1 1 0 0 +EDGE2 8450 930 0.00242316 0.039317 0.000502331 1 0 1 1 0 0 +EDGE2 8450 670 0.0230875 -0.0197162 -3.11443 1 0 1 1 0 0 +EDGE2 8450 931 -0.0445056 0.963639 1.59165 1 0 1 1 0 0 +EDGE2 8450 8449 -1.02353 -0.0395345 0.00668026 1 0 1 1 0 0 +EDGE2 8450 929 -0.8971 -0.022429 0.0144826 1 0 1 1 0 0 +EDGE2 8451 930 -1.00049 0.0366226 -1.58132 1 0 1 1 0 0 +EDGE2 8451 8450 -0.940919 -0.0112612 -1.55919 1 0 1 1 0 0 +EDGE2 8451 670 -0.96055 0.0355748 1.57795 1 0 1 1 0 0 +EDGE2 8451 931 -0.0733506 0.0125994 0.0294185 1 0 1 1 0 0 +EDGE2 8451 932 0.891048 0.00142381 -0.0175165 1 0 1 1 0 0 +EDGE2 8452 8451 -0.980633 -0.147553 -0.015122 1 0 1 1 0 0 +EDGE2 8452 931 -1.03648 0.0143187 0.00735177 1 0 1 1 0 0 +EDGE2 8452 933 1.05644 0.0371714 -0.016236 1 0 1 1 0 0 +EDGE2 8452 932 0.0188439 0.065679 0.0188436 1 0 1 1 0 0 +EDGE2 8453 8452 -1.02483 -0.0102309 0.0130668 1 0 1 1 0 0 +EDGE2 8453 934 1.0035 -0.0213423 0.0370891 1 0 1 1 0 0 +EDGE2 8453 933 0.0286689 -0.00405805 0.0238835 1 0 1 1 0 0 +EDGE2 8453 932 -1.0012 0.0153163 -0.0189402 1 0 1 1 0 0 +EDGE2 8454 955 0.921997 0.0035128 -3.12589 1 0 1 1 0 0 +EDGE2 8454 934 -0.0302187 -0.00217693 0.0253185 1 0 1 1 0 0 +EDGE2 8454 933 -1.02646 -0.042132 0.00775976 1 0 1 1 0 0 +EDGE2 8454 8453 -0.930788 -0.0170123 -0.0186613 1 0 1 1 0 0 +EDGE2 8454 975 1.07437 0.0269607 -3.15272 1 0 1 1 0 0 +EDGE2 8454 935 1.05851 -0.0419645 -0.027962 1 0 1 1 0 0 +EDGE2 8455 956 -0.0335764 -0.98813 -1.59839 1 0 1 1 0 0 +EDGE2 8455 936 -0.0721665 1.06826 1.5738 1 0 1 1 0 0 +EDGE2 8455 955 -0.0102035 0.0105915 -3.13495 1 0 1 1 0 0 +EDGE2 8455 934 -1.10882 -0.0285499 0.00953896 1 0 1 1 0 0 +EDGE2 8455 8454 -1.01466 -0.0263373 -0.0159439 1 0 1 1 0 0 +EDGE2 8455 975 -0.0577684 -0.0191713 -3.16455 1 0 1 1 0 0 +EDGE2 8455 954 1.08592 0.0462519 -3.13429 1 0 1 1 0 0 +EDGE2 8455 974 0.962218 0.0209628 -3.13692 1 0 1 1 0 0 +EDGE2 8455 935 0.0446133 0.0196861 0.0106768 1 0 1 1 0 0 +EDGE2 8455 976 -0.0550961 1.04001 1.58049 1 0 1 1 0 0 +EDGE2 8456 936 0.0621716 0.0325553 -0.0242199 1 0 1 1 0 0 +EDGE2 8456 955 -1.02765 -0.0576428 1.6008 1 0 1 1 0 0 +EDGE2 8456 975 -0.916387 -0.00825272 1.55983 1 0 1 1 0 0 +EDGE2 8456 8455 -1.04423 -0.0137457 -1.5729 1 0 1 1 0 0 +EDGE2 8456 935 -1.00497 -0.0564671 -1.55626 1 0 1 1 0 0 +EDGE2 8456 976 0.0202367 0.0165748 -0.00266587 1 0 1 1 0 0 +EDGE2 8456 937 1.05185 -0.0225357 0.0110715 1 0 1 1 0 0 +EDGE2 8456 977 1.01897 0.0271545 -0.00473975 1 0 1 1 0 0 +EDGE2 8457 936 -0.95983 -0.0171943 0.0233212 1 0 1 1 0 0 +EDGE2 8457 8456 -0.991061 -0.0471606 -0.0177732 1 0 1 1 0 0 +EDGE2 8457 976 -1.09474 0.00873888 0.0448996 1 0 1 1 0 0 +EDGE2 8457 938 1.03421 0.0116271 0.0136339 1 0 1 1 0 0 +EDGE2 8457 937 0.00849165 -0.0564465 0.0261573 1 0 1 1 0 0 +EDGE2 8457 977 0.0654706 -0.0132891 0.00645609 1 0 1 1 0 0 +EDGE2 8457 978 0.899118 0.0208899 0.0123522 1 0 1 1 0 0 +EDGE2 8458 8457 -0.985033 -0.00734585 0.0154652 1 0 1 1 0 0 +EDGE2 8458 938 0.0598103 -0.0145616 0.00822245 1 0 1 1 0 0 +EDGE2 8458 937 -1.01273 -0.0345942 -0.029226 1 0 1 1 0 0 +EDGE2 8458 977 -0.988252 0.0349612 0.0105613 1 0 1 1 0 0 +EDGE2 8458 978 -0.0663502 -0.0392352 -0.00491074 1 0 1 1 0 0 +EDGE2 8458 979 1.06211 0.0285237 -0.00766872 1 0 1 1 0 0 +EDGE2 8458 939 0.955707 -0.0279197 0.00201589 1 0 1 1 0 0 +EDGE2 8459 938 -0.99597 -0.0744558 0.0187838 1 0 1 1 0 0 +EDGE2 8459 8458 -1.03621 0.0266282 0.0029111 1 0 1 1 0 0 +EDGE2 8459 978 -0.921264 0.0846932 0.00462033 1 0 1 1 0 0 +EDGE2 8459 979 -0.00743653 0.0481581 -0.0122207 1 0 1 1 0 0 +EDGE2 8459 939 0.0945017 -0.0791988 0.00970575 1 0 1 1 0 0 +EDGE2 8459 980 0.959163 -0.0302405 0.0204568 1 0 1 1 0 0 +EDGE2 8459 1020 1.03392 -0.105504 -3.14583 1 0 1 1 0 0 +EDGE2 8459 1060 0.958238 0.0446438 -3.11339 1 0 1 1 0 0 +EDGE2 8459 1000 1.01292 0.040951 -3.12907 1 0 1 1 0 0 +EDGE2 8459 940 0.978488 -0.0920757 0.011512 1 0 1 1 0 0 +EDGE2 8460 979 -1.02766 -0.00324778 0.0077972 1 0 1 1 0 0 +EDGE2 8460 8459 -1.0036 -0.0428635 0.0212841 1 0 1 1 0 0 +EDGE2 8460 939 -1.00616 0.0868349 0.0170742 1 0 1 1 0 0 +EDGE2 8460 980 -0.0186279 0.0372045 -0.0242401 1 0 1 1 0 0 +EDGE2 8460 1020 0.025034 0.133981 -3.16969 1 0 1 1 0 0 +EDGE2 8460 1060 -0.000817897 0.00977707 -3.13996 1 0 1 1 0 0 +EDGE2 8460 1000 -0.00704216 0.0480763 -3.14413 1 0 1 1 0 0 +EDGE2 8460 1001 0.000497228 -0.920384 -1.63093 1 0 1 1 0 0 +EDGE2 8460 1061 0.0386426 -0.984575 -1.57732 1 0 1 1 0 0 +EDGE2 8460 940 -0.031333 0.0734025 -0.0125074 1 0 1 1 0 0 +EDGE2 8460 1021 -0.0519507 -1.05433 -1.58975 1 0 1 1 0 0 +EDGE2 8460 941 -0.0141941 -1.01831 -1.53407 1 0 1 1 0 0 +EDGE2 8460 981 0.030565 -0.99654 -1.55721 1 0 1 1 0 0 +EDGE2 8460 1019 0.943602 0.00109557 -3.14278 1 0 1 1 0 0 +EDGE2 8460 1059 1.0076 0.0109091 -3.13115 1 0 1 1 0 0 +EDGE2 8460 999 0.995759 -0.0342146 -3.15941 1 0 1 1 0 0 +EDGE2 8461 980 -1.01977 0.0058925 -1.54886 1 0 1 1 0 0 +EDGE2 8461 1020 -0.99965 0.0235873 1.58348 1 0 1 1 0 0 +EDGE2 8461 1060 -0.944222 -0.00565869 1.58532 1 0 1 1 0 0 +EDGE2 8461 8460 -1.07359 0.0350427 -1.58944 1 0 1 1 0 0 +EDGE2 8461 1000 -1.01086 0.0116649 1.60068 1 0 1 1 0 0 +EDGE2 8461 940 -0.972641 -0.0610481 -1.60237 1 0 1 1 0 0 +EDGE2 8462 8461 -1.0338 0.00231069 0.0116543 1 0 1 1 0 0 +EDGE2 8463 8462 -1.03198 -0.0331213 -0.00682979 1 0 1 1 0 0 +EDGE2 8464 8445 0.992543 0.0556585 -3.10579 1 0 1 1 0 0 +EDGE2 8464 925 0.958413 -0.018447 -3.1119 1 0 1 1 0 0 +EDGE2 8464 3405 1.0005 -0.0517885 -3.14684 1 0 1 1 0 0 +EDGE2 8464 8463 -1.03163 0.0424769 0.00299595 1 0 1 1 0 0 +EDGE2 8465 8446 -0.0166483 1.02368 1.56445 1 0 1 1 0 0 +EDGE2 8465 926 -0.0525744 0.85794 1.54348 1 0 1 1 0 0 +EDGE2 8465 3406 -0.0397815 -0.931165 -1.54672 1 0 1 1 0 0 +EDGE2 8465 8444 0.993413 -0.0762085 -3.11425 1 0 1 1 0 0 +EDGE2 8465 8445 0.0376369 0.00759902 -3.12696 1 0 1 1 0 0 +EDGE2 8465 924 0.890949 0.0403828 -3.16319 1 0 1 1 0 0 +EDGE2 8465 3404 1.0087 0.0671201 -3.16257 1 0 1 1 0 0 +EDGE2 8465 925 -0.0721333 -0.112589 -3.13811 1 0 1 1 0 0 +EDGE2 8465 3405 -0.0320447 -0.043759 -3.14178 1 0 1 1 0 0 +EDGE2 8465 8464 -1.04484 -0.0128961 0.0290056 1 0 1 1 0 0 +EDGE2 8466 3406 -0.0594365 -0.0802608 0.014151 1 0 1 1 0 0 +EDGE2 8466 8445 -1.00603 -0.016384 -1.57913 1 0 1 1 0 0 +EDGE2 8466 8465 -1.11565 0.0128143 1.59872 1 0 1 1 0 0 +EDGE2 8466 925 -1.00514 0.0506991 -1.56158 1 0 1 1 0 0 +EDGE2 8466 3405 -0.992411 0.0434628 -1.5527 1 0 1 1 0 0 +EDGE2 8466 3407 1.04482 -0.0423862 0.00841152 1 0 1 1 0 0 +EDGE2 8467 3406 -0.907358 -0.0261291 -0.0183032 1 0 1 1 0 0 +EDGE2 8467 8466 -1.05745 0.0016526 0.0138913 1 0 1 1 0 0 +EDGE2 8467 3408 0.974408 0.00438032 0.0401732 1 0 1 1 0 0 +EDGE2 8467 3407 -0.00734386 -0.0429054 -0.0148571 1 0 1 1 0 0 +EDGE2 8468 3408 0.0119971 -0.0156153 -0.00590853 1 0 1 1 0 0 +EDGE2 8468 3407 -0.953044 0.00921886 -0.0138692 1 0 1 1 0 0 +EDGE2 8468 8467 -1.03436 0.00619559 -0.00182037 1 0 1 1 0 0 +EDGE2 8468 3409 1.01896 0.022356 0.0122699 1 0 1 1 0 0 +EDGE2 8469 3408 -0.993826 -0.05228 -0.00530604 1 0 1 1 0 0 +EDGE2 8469 8468 -1.02129 0.0573593 -0.0267788 1 0 1 1 0 0 +EDGE2 8469 3409 -0.047456 -0.0884896 0.0379651 1 0 1 1 0 0 +EDGE2 8469 8370 1.0643 -0.00101831 -3.10527 1 0 1 1 0 0 +EDGE2 8469 8430 0.966915 0.0167071 -3.15865 1 0 1 1 0 0 +EDGE2 8469 3070 1.0084 0.0147986 -3.18311 1 0 1 1 0 0 +EDGE2 8469 3390 1.0436 0.0225929 -3.13628 1 0 1 1 0 0 +EDGE2 8469 3410 1.01977 -0.0118001 -0.00940748 1 0 1 1 0 0 +EDGE2 8469 5890 1.0593 -0.107349 -3.17839 1 0 1 1 0 0 +EDGE2 8469 3150 0.886751 0.0418947 -3.12975 1 0 1 1 0 0 +EDGE2 8470 8469 -0.961506 -0.0228606 0.0139908 1 0 1 1 0 0 +EDGE2 8470 3409 -1.05607 0.00233537 -0.00220748 1 0 1 1 0 0 +EDGE2 8470 8370 0.0203482 0.0321956 -3.12666 1 0 1 1 0 0 +EDGE2 8470 3411 0.0069863 1.00499 1.5918 1 0 1 1 0 0 +EDGE2 8470 5891 -0.0656646 1.04061 1.55166 1 0 1 1 0 0 +EDGE2 8470 8431 -0.00691849 1.01669 1.52895 1 0 1 1 0 0 +EDGE2 8470 3391 0.00730091 1.09384 1.60458 1 0 1 1 0 0 +EDGE2 8470 8430 -0.0449705 0.013039 -3.14643 1 0 1 1 0 0 +EDGE2 8470 3070 -0.0774126 -0.0552081 -3.14732 1 0 1 1 0 0 +EDGE2 8470 3390 0.0608433 0.0581517 -3.15606 1 0 1 1 0 0 +EDGE2 8470 3410 0.0976874 -0.000201555 0.00741148 1 0 1 1 0 0 +EDGE2 8470 5890 -0.0174857 0.0348854 -3.14357 1 0 1 1 0 0 +EDGE2 8470 3150 -0.05863 0.073934 -3.12309 1 0 1 1 0 0 +EDGE2 8470 5889 0.940447 0.0192109 -3.13517 1 0 1 1 0 0 +EDGE2 8470 8429 0.892885 -0.0234869 -3.11304 1 0 1 1 0 0 +EDGE2 8470 8369 0.954232 -0.0289519 -3.1119 1 0 1 1 0 0 +EDGE2 8470 3149 1.04876 -0.0292139 -3.1002 1 0 1 1 0 0 +EDGE2 8470 3389 1.04605 0.0656397 -3.13557 1 0 1 1 0 0 +EDGE2 8470 3069 1.0494 -0.0112303 -3.13631 1 0 1 1 0 0 +EDGE2 8470 3151 -0.0267639 -0.894781 -1.57439 1 0 1 1 0 0 +EDGE2 8470 8371 -0.0746557 -1.02462 -1.5666 1 0 1 1 0 0 +EDGE2 8470 3071 -0.0625989 -0.965112 -1.58543 1 0 1 1 0 0 +EDGE2 8471 8370 -0.914983 0.0504525 -1.562 1 0 1 1 0 0 +EDGE2 8471 8470 -1.0095 0.0971591 1.60358 1 0 1 1 0 0 +EDGE2 8471 8430 -1.02157 -0.0172547 -1.55624 1 0 1 1 0 0 +EDGE2 8471 3070 -1.02847 -0.0643332 -1.56736 1 0 1 1 0 0 +EDGE2 8471 3390 -0.971032 -0.00553655 -1.56629 1 0 1 1 0 0 +EDGE2 8471 3410 -0.969594 0.0248546 1.55922 1 0 1 1 0 0 +EDGE2 8471 5890 -1.04427 0.0271901 -1.589 1 0 1 1 0 0 +EDGE2 8471 3150 -0.980083 0.0266445 -1.55488 1 0 1 1 0 0 +EDGE2 8471 3072 0.96727 0.0618882 -0.0194486 1 0 1 1 0 0 +EDGE2 8471 3151 -0.033688 0.0631583 0.0309273 1 0 1 1 0 0 +EDGE2 8471 8371 0.0384284 -0.0339532 -0.0137293 1 0 1 1 0 0 +EDGE2 8471 3071 0.00010086 -0.0524918 0.0115499 1 0 1 1 0 0 +EDGE2 8471 8372 0.931242 -0.0119415 0.0461948 1 0 1 1 0 0 +EDGE2 8471 3152 1.05462 -0.0896102 0.0236699 1 0 1 1 0 0 +EDGE2 8472 3072 0.0520174 -0.00242474 -0.00391326 1 0 1 1 0 0 +EDGE2 8472 3151 -1.05182 0.0233551 0.00216328 1 0 1 1 0 0 +EDGE2 8472 8371 -1.02093 -0.0483773 -0.0172463 1 0 1 1 0 0 +EDGE2 8472 8471 -0.956638 0.0086196 -0.00715883 1 0 1 1 0 0 +EDGE2 8472 3071 -0.916076 -0.0123744 -0.00237875 1 0 1 1 0 0 +EDGE2 8472 8372 -0.0142768 -0.0799805 0.0103217 1 0 1 1 0 0 +EDGE2 8472 3152 -0.000423989 0.0125024 -0.00249507 1 0 1 1 0 0 +EDGE2 8472 3153 0.96181 0.0664668 0.00949065 1 0 1 1 0 0 +EDGE2 8472 8373 1.08473 -0.0687087 -0.0128237 1 0 1 1 0 0 +EDGE2 8472 3073 0.91166 -0.0464132 -0.0152757 1 0 1 1 0 0 +EDGE2 8473 8374 1.0376 -0.00977809 0.014821 1 0 1 1 0 0 +EDGE2 8473 3072 -1.03062 -0.04209 -0.00699371 1 0 1 1 0 0 +EDGE2 8473 8372 -0.999362 -0.00036416 -0.00845266 1 0 1 1 0 0 +EDGE2 8473 8472 -0.951107 -0.0140869 0.0052113 1 0 1 1 0 0 +EDGE2 8473 3152 -0.960041 -0.00158292 -0.00478135 1 0 1 1 0 0 +EDGE2 8473 3153 -0.0864632 -0.0414943 0.00348072 1 0 1 1 0 0 +EDGE2 8473 8373 -0.0315312 0.070478 0.00296546 1 0 1 1 0 0 +EDGE2 8473 3073 -0.0408967 -0.0387466 0.0356053 1 0 1 1 0 0 +EDGE2 8473 3074 0.977674 -0.0318368 0.0834134 1 0 1 1 0 0 +EDGE2 8473 3154 0.973308 -0.0574784 0.0161979 1 0 1 1 0 0 +EDGE2 8474 8374 0.00968912 0.0254173 -0.016623 1 0 1 1 0 0 +EDGE2 8474 3153 -0.975348 0.0803229 0.0283866 1 0 1 1 0 0 +EDGE2 8474 8473 -0.999779 -0.0111666 -0.0104343 1 0 1 1 0 0 +EDGE2 8474 8373 -1.02232 0.0411769 -0.0102367 1 0 1 1 0 0 +EDGE2 8474 3073 -0.977661 -0.104021 -0.00595454 1 0 1 1 0 0 +EDGE2 8474 1075 1.01423 0.00615279 -3.12648 1 0 1 1 0 0 +EDGE2 8474 3074 0.126694 -0.0243001 -0.00656102 1 0 1 1 0 0 +EDGE2 8474 3154 -0.00454953 -0.0570302 0.00616219 1 0 1 1 0 0 +EDGE2 8474 3155 1.05332 0.0249799 -0.0179589 1 0 1 1 0 0 +EDGE2 8474 8375 1.00044 -0.024986 -0.0411526 1 0 1 1 0 0 +EDGE2 8474 3075 1.03655 0.100038 0.0111321 1 0 1 1 0 0 +EDGE2 8474 995 1.01985 0.0450155 -3.09557 1 0 1 1 0 0 +EDGE2 8474 1015 1.02488 -0.0607982 -3.12906 1 0 1 1 0 0 +EDGE2 8474 1055 1.06002 -0.0415776 -3.15263 1 0 1 1 0 0 +EDGE2 8475 1016 -0.0748539 -1.00064 -1.5639 1 0 1 1 0 0 +EDGE2 8475 1056 -0.0927295 -1.02512 -1.53604 1 0 1 1 0 0 +EDGE2 8475 996 -0.0301275 -1.01169 -1.58588 1 0 1 1 0 0 +EDGE2 8475 8374 -1.04628 0.000346322 -0.0150378 1 0 1 1 0 0 +EDGE2 8475 8474 -1.08437 -0.0259875 -0.00401357 1 0 1 1 0 0 +EDGE2 8475 1075 0.0105952 -0.0238961 -3.11414 1 0 1 1 0 0 +EDGE2 8475 3074 -0.893116 0.0264223 -0.01058 1 0 1 1 0 0 +EDGE2 8475 3154 -0.930535 -0.0438982 -0.0170133 1 0 1 1 0 0 +EDGE2 8475 3155 -0.0209852 0.0277421 -0.0288081 1 0 1 1 0 0 +EDGE2 8475 8375 -0.00480993 0.00753056 0.0234125 1 0 1 1 0 0 +EDGE2 8475 3075 -0.133958 -0.005091 -0.00430182 1 0 1 1 0 0 +EDGE2 8475 1074 0.995614 0.0474066 -3.11593 1 0 1 1 0 0 +EDGE2 8475 995 -0.0167839 0.00318554 -3.14441 1 0 1 1 0 0 +EDGE2 8475 1015 -0.0465683 -0.0111857 -3.15253 1 0 1 1 0 0 +EDGE2 8475 1055 0.0858545 -0.0275468 -3.12805 1 0 1 1 0 0 +EDGE2 8475 1014 1.01213 0.052428 -3.15154 1 0 1 1 0 0 +EDGE2 8475 1054 1.05633 0.0443423 -3.13801 1 0 1 1 0 0 +EDGE2 8475 994 0.990155 -0.0231193 -3.16115 1 0 1 1 0 0 +EDGE2 8475 3156 -0.0315191 0.964809 1.57642 1 0 1 1 0 0 +EDGE2 8475 8376 -0.0314801 0.943146 1.58025 1 0 1 1 0 0 +EDGE2 8475 1076 0.000406941 1.00329 1.58166 1 0 1 1 0 0 +EDGE2 8475 3076 0.0600462 0.939999 1.5879 1 0 1 1 0 0 +EDGE2 8476 1075 -0.954856 0.0592414 1.5674 1 0 1 1 0 0 +EDGE2 8476 3155 -0.961868 0.0330993 -1.55387 1 0 1 1 0 0 +EDGE2 8476 8375 -1.0067 -0.0228686 -1.59026 1 0 1 1 0 0 +EDGE2 8476 8475 -0.933768 -0.05012 -1.55843 1 0 1 1 0 0 +EDGE2 8476 3075 -1.07222 0.0398291 -1.55215 1 0 1 1 0 0 +EDGE2 8476 995 -0.941676 0.0885986 1.60378 1 0 1 1 0 0 +EDGE2 8476 1015 -0.999627 -0.0636066 1.57901 1 0 1 1 0 0 +EDGE2 8476 1055 -1.01485 0.0462208 1.59549 1 0 1 1 0 0 +EDGE2 8476 3156 -0.035407 0.0218357 0.0034911 1 0 1 1 0 0 +EDGE2 8476 8376 0.0484827 0.0567073 0.00731731 1 0 1 1 0 0 +EDGE2 8476 1076 0.00768893 0.0162265 0.0345801 1 0 1 1 0 0 +EDGE2 8476 3076 -0.0147822 -0.0423677 0.0174649 1 0 1 1 0 0 +EDGE2 8476 3077 1.02462 -0.0463912 -0.00815691 1 0 1 1 0 0 +EDGE2 8476 3157 0.989292 0.0068178 0.0288227 1 0 1 1 0 0 +EDGE2 8476 8377 1.02922 -0.0173133 0.0274569 1 0 1 1 0 0 +EDGE2 8476 1077 1.02519 -0.0500188 -0.00258107 1 0 1 1 0 0 +EDGE2 8477 3078 0.993605 0.0367279 -0.0336422 1 0 1 1 0 0 +EDGE2 8477 3156 -0.938299 -0.0348574 -0.00490406 1 0 1 1 0 0 +EDGE2 8477 8476 -1.06522 -0.0388397 -0.00102019 1 0 1 1 0 0 +EDGE2 8477 8376 -1.06458 0.0694966 -0.00592167 1 0 1 1 0 0 +EDGE2 8477 1076 -0.950006 0.0520378 -0.0134291 1 0 1 1 0 0 +EDGE2 8477 3076 -0.996859 0.0221128 0.00134702 1 0 1 1 0 0 +EDGE2 8477 3077 -0.0161165 -0.0320994 -0.0242546 1 0 1 1 0 0 +EDGE2 8477 3157 0.0246163 0.0498452 0.0249997 1 0 1 1 0 0 +EDGE2 8477 8377 -0.0140068 0.0331465 -0.000577835 1 0 1 1 0 0 +EDGE2 8477 1077 -0.0138173 0.01106 0.0233406 1 0 1 1 0 0 +EDGE2 8477 8378 1.05839 -0.109534 -0.0322285 1 0 1 1 0 0 +EDGE2 8477 3158 1.00408 0.00391381 -0.00815811 1 0 1 1 0 0 +EDGE2 8477 1078 0.960398 -0.0277935 -0.00563324 1 0 1 1 0 0 +EDGE2 8478 3078 0.0209723 -0.0322996 0.0163976 1 0 1 1 0 0 +EDGE2 8478 8477 -1.05448 0.0412326 0.0162878 1 0 1 1 0 0 +EDGE2 8478 3077 -0.939076 -0.024987 0.0130862 1 0 1 1 0 0 +EDGE2 8478 3157 -0.958101 -0.0246749 -0.0109577 1 0 1 1 0 0 +EDGE2 8478 8377 -1.04472 0.0241264 -0.0136892 1 0 1 1 0 0 +EDGE2 8478 1077 -1.02008 0.0325907 -0.0142633 1 0 1 1 0 0 +EDGE2 8478 8378 -0.0545033 -0.0630902 -0.0268689 1 0 1 1 0 0 +EDGE2 8478 3158 0.098221 -0.0770296 -0.020636 1 0 1 1 0 0 +EDGE2 8478 8379 1.02419 -0.0871778 0.013998 1 0 1 1 0 0 +EDGE2 8478 1078 -0.00884044 -0.0328645 0.00728555 1 0 1 1 0 0 +EDGE2 8478 3079 0.913362 -0.00347334 0.0237522 1 0 1 1 0 0 +EDGE2 8478 3159 0.893896 0.0413227 -0.00620381 1 0 1 1 0 0 +EDGE2 8478 1079 1.01532 -0.0463151 -0.0179428 1 0 1 1 0 0 +EDGE2 8479 8360 1.039 -0.0606058 -3.12434 1 0 1 1 0 0 +EDGE2 8479 3078 -1.01855 -0.0669216 -0.00428046 1 0 1 1 0 0 +EDGE2 8479 8378 -0.945638 0.0650962 -0.0547457 1 0 1 1 0 0 +EDGE2 8479 8478 -1.10729 0.12879 0.0344702 1 0 1 1 0 0 +EDGE2 8479 3158 -1.09539 -0.00627902 0.0146139 1 0 1 1 0 0 +EDGE2 8479 8379 -0.048439 -0.0123682 0.00423577 1 0 1 1 0 0 +EDGE2 8479 1078 -1.05804 -0.093977 0.0222558 1 0 1 1 0 0 +EDGE2 8479 3079 0.118764 -0.0975188 0.0328735 1 0 1 1 0 0 +EDGE2 8479 3159 -0.0348398 0.0301247 -0.0197091 1 0 1 1 0 0 +EDGE2 8479 1079 0.00497465 -0.0460615 -0.00785942 1 0 1 1 0 0 +EDGE2 8479 8400 0.967731 -0.0250047 -3.14774 1 0 1 1 0 0 +EDGE2 8479 8420 0.971571 -0.0556089 -3.1546 1 0 1 1 0 0 +EDGE2 8479 8380 0.973122 -0.0922925 0.0143986 1 0 1 1 0 0 +EDGE2 8479 3060 0.958892 0.00935222 -3.13709 1 0 1 1 0 0 +EDGE2 8479 3160 1.01404 -0.0394318 -0.00545328 1 0 1 1 0 0 +EDGE2 8479 5860 0.970289 0.0119028 -3.09922 1 0 1 1 0 0 +EDGE2 8479 5880 0.972129 -0.0224736 -3.11038 1 0 1 1 0 0 +EDGE2 8479 3080 0.927896 -0.0734693 0.000914948 1 0 1 1 0 0 +EDGE2 8479 1080 1.0306 -0.0273127 -0.0280611 1 0 1 1 0 0 +EDGE2 8480 8360 0.0769863 -0.00672074 -3.13562 1 0 1 1 0 0 +EDGE2 8480 8379 -1.04455 0.0212571 -0.0508223 1 0 1 1 0 0 +EDGE2 8480 8479 -1.00418 0.0212142 0.00102402 1 0 1 1 0 0 +EDGE2 8480 3079 -1.00963 0.0365684 -0.00269395 1 0 1 1 0 0 +EDGE2 8480 3159 -0.947101 -0.0189921 -0.0354577 1 0 1 1 0 0 +EDGE2 8480 1079 -0.897093 0.03557 -0.00604884 1 0 1 1 0 0 +EDGE2 8480 8361 -0.0330427 1.00016 1.54154 1 0 1 1 0 0 +EDGE2 8480 8421 -0.068285 1.09791 1.56661 1 0 1 1 0 0 +EDGE2 8480 8381 0.0409209 0.978251 1.58381 1 0 1 1 0 0 +EDGE2 8480 3081 0.0845381 1.04378 1.58812 1 0 1 1 0 0 +EDGE2 8480 3161 0.00715364 1.02291 1.5755 1 0 1 1 0 0 +EDGE2 8480 5881 -0.0126676 0.983286 1.57001 1 0 1 1 0 0 +EDGE2 8480 3061 0.0119929 0.951187 1.56893 1 0 1 1 0 0 +EDGE2 8480 8400 -0.0462189 -0.0171213 -3.12469 1 0 1 1 0 0 +EDGE2 8480 8420 0.0835054 0.0596357 -3.12481 1 0 1 1 0 0 +EDGE2 8480 8380 0.0180395 0.00930811 0.0171769 1 0 1 1 0 0 +EDGE2 8480 8401 -0.0273036 -1.00844 -1.58112 1 0 1 1 0 0 +EDGE2 8480 3060 -0.0136439 0.00772925 -3.10934 1 0 1 1 0 0 +EDGE2 8480 3160 -0.0799315 0.0540986 0.00689744 1 0 1 1 0 0 +EDGE2 8480 5860 0.0347049 -0.0410626 -3.15379 1 0 1 1 0 0 +EDGE2 8480 5880 -0.0403528 0.00759826 -3.15472 1 0 1 1 0 0 +EDGE2 8480 3080 -0.00984751 0.0286425 -0.0184727 1 0 1 1 0 0 +EDGE2 8480 1080 -0.0512225 0.0854297 -0.00473403 1 0 1 1 0 0 +EDGE2 8480 1081 -0.00543569 -1.0237 -1.55181 1 0 1 1 0 0 +EDGE2 8480 5861 -0.063584 -0.948173 -1.57795 1 0 1 1 0 0 +EDGE2 8480 8399 0.969952 0.0237281 -3.15184 1 0 1 1 0 0 +EDGE2 8480 8419 1.00126 0.0100237 -3.14212 1 0 1 1 0 0 +EDGE2 8480 5859 1.00358 -0.030501 -3.15451 1 0 1 1 0 0 +EDGE2 8480 5879 0.978979 -0.0476758 -3.15405 1 0 1 1 0 0 +EDGE2 8480 8359 1.07581 0.0484432 -3.08815 1 0 1 1 0 0 +EDGE2 8480 3059 0.958348 0.0878613 -3.18247 1 0 1 1 0 0 +EDGE2 8481 8360 -0.931145 0.00534896 1.58447 1 0 1 1 0 0 +EDGE2 8481 8362 1.00613 0.0307841 0.0241965 1 0 1 1 0 0 +EDGE2 8481 8422 1.01454 0.0486235 -0.0225361 1 0 1 1 0 0 +EDGE2 8481 8382 0.990936 0.0522799 0.0166791 1 0 1 1 0 0 +EDGE2 8481 3082 1.00329 0.0592527 0.0348889 1 0 1 1 0 0 +EDGE2 8481 3162 0.934262 0.0260361 0.00129246 1 0 1 1 0 0 +EDGE2 8481 5882 0.852099 -0.036381 0.000746864 1 0 1 1 0 0 +EDGE2 8481 3062 1.0974 0.10115 -0.0234318 1 0 1 1 0 0 +EDGE2 8481 8361 -0.13352 -0.0112141 -0.0180345 1 0 1 1 0 0 +EDGE2 8481 8421 -0.0389279 0.0282547 -0.0634489 1 0 1 1 0 0 +EDGE2 8481 8381 0.00699534 -0.00434542 -0.00495021 1 0 1 1 0 0 +EDGE2 8481 3081 -0.00840106 0.0278695 -0.00872105 1 0 1 1 0 0 +EDGE2 8481 3161 -0.065481 0.0331351 -0.00929717 1 0 1 1 0 0 +EDGE2 8481 5881 0.00184362 0.0439187 -0.0198661 1 0 1 1 0 0 +EDGE2 8481 3061 0.0670215 -0.0187455 -0.00554353 1 0 1 1 0 0 +EDGE2 8481 8480 -0.976195 -0.026801 -1.5919 1 0 1 1 0 0 +EDGE2 8481 8400 -1.04157 0.0267401 1.55664 1 0 1 1 0 0 +EDGE2 8481 8420 -0.994337 -0.0402304 1.54936 1 0 1 1 0 0 +EDGE2 8481 8380 -0.929113 -0.0419403 -1.5657 1 0 1 1 0 0 +EDGE2 8481 3060 -0.894577 0.0919284 1.57115 1 0 1 1 0 0 +EDGE2 8481 3160 -0.876023 0.0854331 -1.55457 1 0 1 1 0 0 +EDGE2 8481 5860 -0.880783 -0.138206 1.52783 1 0 1 1 0 0 +EDGE2 8481 5880 -1.02569 0.0615198 1.57674 1 0 1 1 0 0 +EDGE2 8481 3080 -0.995725 -0.0272364 -1.56459 1 0 1 1 0 0 +EDGE2 8481 1080 -1.05572 -0.0307147 -1.58864 1 0 1 1 0 0 +EDGE2 8482 8363 0.967637 0.000978887 0.0181485 1 0 1 1 0 0 +EDGE2 8482 8423 0.964247 0.0676167 0.00967093 1 0 1 1 0 0 +EDGE2 8482 8383 0.975852 -0.0269615 -0.0183289 1 0 1 1 0 0 +EDGE2 8482 3083 0.989887 -0.0236832 0.0560411 1 0 1 1 0 0 +EDGE2 8482 3163 1.02011 0.0657071 0.00318764 1 0 1 1 0 0 +EDGE2 8482 5883 1.04823 -0.0268279 0.00282884 1 0 1 1 0 0 +EDGE2 8482 3063 0.994199 -0.0155184 -0.0194131 1 0 1 1 0 0 +EDGE2 8482 8362 -0.00291669 0.00687896 -0.0234646 1 0 1 1 0 0 +EDGE2 8482 8422 0.0382259 -0.070819 -0.0154807 1 0 1 1 0 0 +EDGE2 8482 8382 -0.0114138 0.103323 0.0186638 1 0 1 1 0 0 +EDGE2 8482 3082 -0.0022891 -0.0687565 0.0202715 1 0 1 1 0 0 +EDGE2 8482 3162 0.0594667 0.0188701 0.00381593 1 0 1 1 0 0 +EDGE2 8482 5882 -0.0273241 -0.0316767 0.0131339 1 0 1 1 0 0 +EDGE2 8482 3062 -0.0348355 -0.0480818 0.00344883 1 0 1 1 0 0 +EDGE2 8482 8361 -1.00771 -0.0375683 0.00729271 1 0 1 1 0 0 +EDGE2 8482 8421 -0.934787 0.0567125 0.00357428 1 0 1 1 0 0 +EDGE2 8482 8481 -0.96958 0.0491035 0.0248942 1 0 1 1 0 0 +EDGE2 8482 8381 -1.01186 0.00732699 -0.00831726 1 0 1 1 0 0 +EDGE2 8482 3081 -0.987743 0.102936 0.0055151 1 0 1 1 0 0 +EDGE2 8482 3161 -1.0121 0.0484197 -0.017224 1 0 1 1 0 0 +EDGE2 8482 5881 -0.9978 -0.0182412 -0.0283731 1 0 1 1 0 0 +EDGE2 8482 3061 -1.01957 0.0454113 0.0117032 1 0 1 1 0 0 +EDGE2 8483 3064 0.988299 -0.0491815 -0.0245094 1 0 1 1 0 0 +EDGE2 8483 8384 0.931729 0.0162296 -0.0398566 1 0 1 1 0 0 +EDGE2 8483 8424 1.07133 0.0183406 0.0143293 1 0 1 1 0 0 +EDGE2 8483 3164 0.965856 0.0259544 0.0270056 1 0 1 1 0 0 +EDGE2 8483 5884 0.947868 -0.0553214 -2.29814e-05 1 0 1 1 0 0 +EDGE2 8483 8364 1.10485 -0.0190513 0.00525168 1 0 1 1 0 0 +EDGE2 8483 3084 0.975617 -0.0897843 -0.028428 1 0 1 1 0 0 +EDGE2 8483 8363 -0.0324041 -0.0393613 -0.00131687 1 0 1 1 0 0 +EDGE2 8483 8423 -0.0485718 0.0452735 0.0160017 1 0 1 1 0 0 +EDGE2 8483 8383 0.00298897 -0.0328139 -0.00709336 1 0 1 1 0 0 +EDGE2 8483 3083 -0.0330884 -0.0071977 0.0264424 1 0 1 1 0 0 +EDGE2 8483 3163 0.0900387 -0.081339 0.0313332 1 0 1 1 0 0 +EDGE2 8483 5883 0.149256 0.0649781 0.0451211 1 0 1 1 0 0 +EDGE2 8483 3063 -0.0209588 -0.0175005 0.0144109 1 0 1 1 0 0 +EDGE2 8483 8362 -1.07188 -0.10216 0.0316204 1 0 1 1 0 0 +EDGE2 8483 8422 -1.01047 -0.00662333 -0.00374286 1 0 1 1 0 0 +EDGE2 8483 8482 -0.891213 -0.0614246 -0.000773723 1 0 1 1 0 0 +EDGE2 8483 8382 -0.925898 -0.0306373 0.00531709 1 0 1 1 0 0 +EDGE2 8483 3082 -1.00987 0.01984 0.0451228 1 0 1 1 0 0 +EDGE2 8483 3162 -0.997286 0.0356064 0.0170482 1 0 1 1 0 0 +EDGE2 8483 5882 -1.0282 0.0481485 -0.0168616 1 0 1 1 0 0 +EDGE2 8483 3062 -0.958191 -0.0122259 -0.00936533 1 0 1 1 0 0 +EDGE2 8484 8385 0.887489 -0.0407497 -0.0126341 1 0 1 1 0 0 +EDGE2 8484 8425 0.981338 -0.059432 -0.00411992 1 0 1 1 0 0 +EDGE2 8484 3105 0.995558 0.0567723 -3.12674 1 0 1 1 0 0 +EDGE2 8484 3485 1.04207 0.00335514 -3.12463 1 0 1 1 0 0 +EDGE2 8484 5845 0.951671 0.0172342 -3.07814 1 0 1 1 0 0 +EDGE2 8484 5885 1.06813 -0.060178 -0.00292585 1 0 1 1 0 0 +EDGE2 8484 8365 1.0025 -0.0262524 0.031068 1 0 1 1 0 0 +EDGE2 8484 5825 0.979158 -0.0236714 -3.14858 1 0 1 1 0 0 +EDGE2 8484 3145 1.04382 -0.0264181 -3.14644 1 0 1 1 0 0 +EDGE2 8484 3165 1.01433 -0.0071918 -0.00319757 1 0 1 1 0 0 +EDGE2 8484 3385 1.01652 -0.0795904 -3.14334 1 0 1 1 0 0 +EDGE2 8484 3125 1.01338 0.0719331 -3.13898 1 0 1 1 0 0 +EDGE2 8484 1185 1.03973 0.000731936 -3.14033 1 0 1 1 0 0 +EDGE2 8484 3065 0.981461 0.100055 0.0119712 1 0 1 1 0 0 +EDGE2 8484 3085 0.908113 -0.0145952 -0.0177213 1 0 1 1 0 0 +EDGE2 8484 1165 1.03384 0.0211596 -3.14516 1 0 1 1 0 0 +EDGE2 8484 3064 -0.0153651 -0.0388033 0.0202545 1 0 1 1 0 0 +EDGE2 8484 8384 -0.026073 -0.0582933 0.00289165 1 0 1 1 0 0 +EDGE2 8484 8424 0.114988 0.0250179 -0.00134842 1 0 1 1 0 0 +EDGE2 8484 3164 0.018463 -0.00158304 -0.0150304 1 0 1 1 0 0 +EDGE2 8484 5884 0.086776 0.0445104 0.0284078 1 0 1 1 0 0 +EDGE2 8484 8364 -0.000104807 0.00235236 -0.00860525 1 0 1 1 0 0 +EDGE2 8484 3084 0.0716674 0.0175199 -0.0113233 1 0 1 1 0 0 +EDGE2 8484 8363 -0.934019 0.021045 -0.00339309 1 0 1 1 0 0 +EDGE2 8484 8423 -1.03856 -0.0395707 -0.0261029 1 0 1 1 0 0 +EDGE2 8484 8483 -1.04817 -0.0946912 -0.0522649 1 0 1 1 0 0 +EDGE2 8484 8383 -0.95995 0.0422203 -0.0188831 1 0 1 1 0 0 +EDGE2 8484 3083 -0.970702 0.020844 -0.033267 1 0 1 1 0 0 +EDGE2 8484 3163 -1.02532 -0.0279778 0.00434386 1 0 1 1 0 0 +EDGE2 8484 5883 -1.01401 0.0473267 -0.0364657 1 0 1 1 0 0 +EDGE2 8484 3063 -0.963598 -0.0457002 -0.0243283 1 0 1 1 0 0 +EDGE2 8485 8385 0.0661201 0.0130292 0.014699 1 0 1 1 0 0 +EDGE2 8485 8366 0.00963322 0.951203 1.58077 1 0 1 1 0 0 +EDGE2 8485 8426 -0.0379037 0.976616 1.54912 1 0 1 1 0 0 +EDGE2 8485 3146 0.0437169 1.01783 1.58546 1 0 1 1 0 0 +EDGE2 8485 3386 0.00721539 1.01142 1.57788 1 0 1 1 0 0 +EDGE2 8485 5886 0.00439486 0.991751 1.56909 1 0 1 1 0 0 +EDGE2 8485 3066 -0.0414938 0.934336 1.5366 1 0 1 1 0 0 +EDGE2 8485 3144 1.0191 -0.00843638 -3.15202 1 0 1 1 0 0 +EDGE2 8485 3484 0.878269 0.00683341 -3.14386 1 0 1 1 0 0 +EDGE2 8485 5824 0.929319 0.00825556 -3.13433 1 0 1 1 0 0 +EDGE2 8485 5844 0.904016 -0.0364119 -3.1495 1 0 1 1 0 0 +EDGE2 8485 3384 0.962419 -0.0140897 -3.13965 1 0 1 1 0 0 +EDGE2 8485 1184 1.0348 0.063472 -3.12714 1 0 1 1 0 0 +EDGE2 8485 3104 1.06232 0.021952 -3.17535 1 0 1 1 0 0 +EDGE2 8485 3124 1.05005 -0.0655415 -3.16305 1 0 1 1 0 0 +EDGE2 8485 1164 0.985073 -0.0328808 -3.15459 1 0 1 1 0 0 +EDGE2 8485 8425 -0.0208556 0.106693 -0.0150801 1 0 1 1 0 0 +EDGE2 8485 3166 0.0837337 -0.956191 -1.58273 1 0 1 1 0 0 +EDGE2 8485 3105 0.0197621 -0.00208633 -3.13338 1 0 1 1 0 0 +EDGE2 8485 3485 -0.0366672 -0.0692668 -3.15544 1 0 1 1 0 0 +EDGE2 8485 5845 -0.0298794 0.0117998 -3.13387 1 0 1 1 0 0 +EDGE2 8485 5885 -0.0812995 -0.0360512 -0.0205732 1 0 1 1 0 0 +EDGE2 8485 8365 -0.000227317 -0.0295076 -0.00320897 1 0 1 1 0 0 +EDGE2 8485 5825 0.0636388 0.0183335 -3.13446 1 0 1 1 0 0 +EDGE2 8485 3145 -0.0298711 -0.0687085 -3.16017 1 0 1 1 0 0 +EDGE2 8485 3165 -0.077821 -0.00454316 -0.00613116 1 0 1 1 0 0 +EDGE2 8485 3385 0.0586281 -0.0333917 -3.12411 1 0 1 1 0 0 +EDGE2 8485 3125 -0.081574 -0.0664304 -3.12127 1 0 1 1 0 0 +EDGE2 8485 1185 -0.00297359 -0.0171517 -3.13856 1 0 1 1 0 0 +EDGE2 8485 3065 0.0924665 0.0230891 -0.020369 1 0 1 1 0 0 +EDGE2 8485 3085 -0.0250404 0.0468518 0.0289379 1 0 1 1 0 0 +EDGE2 8485 1165 -0.023088 -0.0114422 -3.15255 1 0 1 1 0 0 +EDGE2 8485 5826 -0.0161887 -1.06072 -1.60132 1 0 1 1 0 0 +EDGE2 8485 5846 0.0431776 -1.01412 -1.56512 1 0 1 1 0 0 +EDGE2 8485 8386 -0.0638449 -1.04081 -1.60013 1 0 1 1 0 0 +EDGE2 8485 3486 -0.0671627 -0.991994 -1.57477 1 0 1 1 0 0 +EDGE2 8485 1166 0.0447762 -0.910857 -1.58201 1 0 1 1 0 0 +EDGE2 8485 3086 -0.000601106 -0.865363 -1.57394 1 0 1 1 0 0 +EDGE2 8485 3106 0.0160642 -1.00701 -1.59504 1 0 1 1 0 0 +EDGE2 8485 3126 0.00809832 -0.950509 -1.56569 1 0 1 1 0 0 +EDGE2 8485 1186 -0.0025137 -1.02709 -1.56369 1 0 1 1 0 0 +EDGE2 8485 3064 -0.984995 -0.0433283 0.0254258 1 0 1 1 0 0 +EDGE2 8485 8384 -1.00899 -0.0276098 -0.0126626 1 0 1 1 0 0 +EDGE2 8485 8484 -1.04436 -0.0230612 0.00221607 1 0 1 1 0 0 +EDGE2 8485 8424 -0.968693 0.0479899 -0.00236562 1 0 1 1 0 0 +EDGE2 8485 3164 -0.98803 0.0274673 -0.00851853 1 0 1 1 0 0 +EDGE2 8485 5884 -1.02276 -0.00382873 0.0323742 1 0 1 1 0 0 +EDGE2 8485 8364 -0.979969 0.0743783 0.0272273 1 0 1 1 0 0 +EDGE2 8485 3084 -1.09148 0.0128246 -0.0195867 1 0 1 1 0 0 +EDGE2 8486 8385 -0.979365 -0.104182 1.55796 1 0 1 1 0 0 +EDGE2 8486 8485 -0.99585 0.182166 1.557 1 0 1 1 0 0 +EDGE2 8486 8425 -1.05722 -0.0179798 1.60617 1 0 1 1 0 0 +EDGE2 8486 3166 -0.0271336 0.0689228 0.0112012 1 0 1 1 0 0 +EDGE2 8486 3105 -0.97437 -0.0155449 -1.60795 1 0 1 1 0 0 +EDGE2 8486 3485 -1.01499 0.0198615 -1.5505 1 0 1 1 0 0 +EDGE2 8486 5845 -0.994921 0.0135381 -1.5592 1 0 1 1 0 0 +EDGE2 8486 5885 -0.952139 -0.0794913 1.59054 1 0 1 1 0 0 +EDGE2 8486 8365 -1.06545 0.0201272 1.58085 1 0 1 1 0 0 +EDGE2 8486 5825 -0.983831 -0.0347338 -1.58167 1 0 1 1 0 0 +EDGE2 8486 3145 -1.0083 -0.0370197 -1.57564 1 0 1 1 0 0 +EDGE2 8486 3165 -1.00585 0.11422 1.53696 1 0 1 1 0 0 +EDGE2 8486 3385 -1.01389 0.0626183 -1.56032 1 0 1 1 0 0 +EDGE2 8486 3125 -0.995331 0.045772 -1.57321 1 0 1 1 0 0 +EDGE2 8486 1185 -0.966076 -0.0286821 -1.5589 1 0 1 1 0 0 +EDGE2 8486 3065 -0.973758 0.00652098 1.56806 1 0 1 1 0 0 +EDGE2 8486 3085 -1.03785 0.0242828 1.55812 1 0 1 1 0 0 +EDGE2 8486 1165 -0.985397 -0.084605 -1.56124 1 0 1 1 0 0 +EDGE2 8486 5826 0.0389275 -0.0176967 -0.0315087 1 0 1 1 0 0 +EDGE2 8486 5846 0.0514101 -0.0374273 0.00305913 1 0 1 1 0 0 +EDGE2 8486 8386 -0.122387 -0.0626534 -0.00520122 1 0 1 1 0 0 +EDGE2 8486 3486 0.071783 0.0734454 0.019159 1 0 1 1 0 0 +EDGE2 8486 5847 0.99007 0.0927153 -0.0101186 1 0 1 1 0 0 +EDGE2 8486 1166 -0.00881421 -0.0756517 0.0256656 1 0 1 1 0 0 +EDGE2 8486 3086 0.0603619 0.0103665 0.00842329 1 0 1 1 0 0 +EDGE2 8486 3106 0.0483331 -0.0431088 0.00317266 1 0 1 1 0 0 +EDGE2 8486 3126 0.0742434 -0.00994399 0.000981584 1 0 1 1 0 0 +EDGE2 8486 1186 0.0402645 -0.00423123 0.0281359 1 0 1 1 0 0 +EDGE2 8486 8387 1.05588 0.0594963 0.00449743 1 0 1 1 0 0 +EDGE2 8486 3107 0.927455 -0.0215107 0.00561063 1 0 1 1 0 0 +EDGE2 8486 3167 1.01216 -0.101822 0.00937281 1 0 1 1 0 0 +EDGE2 8486 3487 0.907372 -0.0106108 -0.0213115 1 0 1 1 0 0 +EDGE2 8486 5827 1.02505 -0.0339869 -0.032341 1 0 1 1 0 0 +EDGE2 8486 3127 1.0125 0.116125 0.00855086 1 0 1 1 0 0 +EDGE2 8486 1187 0.980159 0.0154872 -0.0210555 1 0 1 1 0 0 +EDGE2 8486 3087 1.05602 0.0967898 -0.0181881 1 0 1 1 0 0 +EDGE2 8486 1167 1.04332 0.0067407 -0.0348872 1 0 1 1 0 0 +EDGE2 8487 3166 -0.946632 -0.0110073 0.0455817 1 0 1 1 0 0 +EDGE2 8487 8486 -0.933826 -0.00958705 0.0110746 1 0 1 1 0 0 +EDGE2 8487 5826 -0.980214 -0.0594296 -0.0142406 1 0 1 1 0 0 +EDGE2 8487 5846 -0.940209 0.0387675 -0.00222696 1 0 1 1 0 0 +EDGE2 8487 8386 -1.01539 0.0379752 0.00101624 1 0 1 1 0 0 +EDGE2 8487 3486 -0.989165 0.00117301 0.0193548 1 0 1 1 0 0 +EDGE2 8487 5847 0.0562881 -0.0101977 -0.00714047 1 0 1 1 0 0 +EDGE2 8487 1166 -1.06109 -0.0500812 0.0103587 1 0 1 1 0 0 +EDGE2 8487 3086 -1.03867 -0.0469847 0.0217795 1 0 1 1 0 0 +EDGE2 8487 3106 -1.04018 -0.03611 -0.0128732 1 0 1 1 0 0 +EDGE2 8487 3126 -0.945172 0.028357 -0.00684679 1 0 1 1 0 0 +EDGE2 8487 1186 -1.00605 0.071309 -0.00079527 1 0 1 1 0 0 +EDGE2 8487 8387 0.0329827 0.0765856 0.00811933 1 0 1 1 0 0 +EDGE2 8487 3107 0.0156737 0.018766 0.018362 1 0 1 1 0 0 +EDGE2 8487 3167 0.00181723 0.0315204 -0.00552819 1 0 1 1 0 0 +EDGE2 8487 3487 0.0613419 0.0171391 0.00754284 1 0 1 1 0 0 +EDGE2 8487 5827 0.146255 -0.018025 -0.0356939 1 0 1 1 0 0 +EDGE2 8487 3127 0.0307089 0.0435526 -0.0312234 1 0 1 1 0 0 +EDGE2 8487 1187 0.0147551 0.0257496 -0.00991147 1 0 1 1 0 0 +EDGE2 8487 3087 -0.108399 0.0985567 0.0018629 1 0 1 1 0 0 +EDGE2 8487 1167 -0.0839914 -0.0205045 0.00141145 1 0 1 1 0 0 +EDGE2 8487 8388 0.988361 -0.0399884 0.00664416 1 0 1 1 0 0 +EDGE2 8487 3128 0.991207 -0.0695311 0.0197063 1 0 1 1 0 0 +EDGE2 8487 3488 1.01056 0.0499091 -0.0197134 1 0 1 1 0 0 +EDGE2 8487 5828 1.1547 0.0585168 -0.0225136 1 0 1 1 0 0 +EDGE2 8487 5848 0.997361 -0.0460343 0.00343123 1 0 1 1 0 0 +EDGE2 8487 3168 1.03376 -0.052005 -0.0125652 1 0 1 1 0 0 +EDGE2 8487 1188 1.02119 0.0319111 -0.00613276 1 0 1 1 0 0 +EDGE2 8487 3088 0.952901 0.0397591 0.0251439 1 0 1 1 0 0 +EDGE2 8487 3108 1.02264 -0.0844952 -0.00397766 1 0 1 1 0 0 +EDGE2 8487 1168 0.988144 0.099326 0.0137831 1 0 1 1 0 0 +EDGE2 8488 5847 -1.03747 0.0272903 0.00425713 1 0 1 1 0 0 +EDGE2 8488 8387 -0.942084 0.0446243 0.0281568 1 0 1 1 0 0 +EDGE2 8488 8487 -0.992749 0.070398 0.00794313 1 0 1 1 0 0 +EDGE2 8488 3107 -1.02243 -0.0104576 -0.0304027 1 0 1 1 0 0 +EDGE2 8488 3167 -1.02157 -0.0840906 0.00797633 1 0 1 1 0 0 +EDGE2 8488 3487 -0.977139 0.0212818 0.0113725 1 0 1 1 0 0 +EDGE2 8488 5827 -1.05332 -0.0425815 0.00943603 1 0 1 1 0 0 +EDGE2 8488 3127 -0.950949 -0.0817958 -0.0074567 1 0 1 1 0 0 +EDGE2 8488 1187 -1.015 0.0662637 -0.0280613 1 0 1 1 0 0 +EDGE2 8488 3087 -1.04421 -0.0141169 -0.015807 1 0 1 1 0 0 +EDGE2 8488 1167 -1.02593 -0.0170577 -0.00616291 1 0 1 1 0 0 +EDGE2 8488 8388 -0.0861533 0.0252936 -0.0163441 1 0 1 1 0 0 +EDGE2 8488 3128 0.0375568 -0.0218542 0.00318823 1 0 1 1 0 0 +EDGE2 8488 3488 0.102543 -0.0851185 -0.0250755 1 0 1 1 0 0 +EDGE2 8488 5828 0.0228526 -0.0730491 0.000263154 1 0 1 1 0 0 +EDGE2 8488 5848 0.0916936 0.032799 0.0159739 1 0 1 1 0 0 +EDGE2 8488 3168 -0.0383531 0.0171814 -0.0182455 1 0 1 1 0 0 +EDGE2 8488 1188 0.0867308 0.0271585 0.0128461 1 0 1 1 0 0 +EDGE2 8488 3088 -0.026908 0.0192716 -0.0342619 1 0 1 1 0 0 +EDGE2 8488 3108 0.0831245 -0.0124895 0.0209076 1 0 1 1 0 0 +EDGE2 8488 1168 0.0462458 0.0329351 -0.0177034 1 0 1 1 0 0 +EDGE2 8488 5849 1.04387 0.00502136 -0.0174978 1 0 1 1 0 0 +EDGE2 8488 8389 0.927117 0.0440811 0.0567701 1 0 1 1 0 0 +EDGE2 8488 3109 1.0077 0.00941419 -0.00758903 1 0 1 1 0 0 +EDGE2 8488 3169 1.01331 0.0148786 0.0250309 1 0 1 1 0 0 +EDGE2 8488 3489 1.01292 0.0687049 -0.0146948 1 0 1 1 0 0 +EDGE2 8488 5829 1.0995 0.0147458 -0.00521958 1 0 1 1 0 0 +EDGE2 8488 3129 1.01478 -0.0415653 -0.0172944 1 0 1 1 0 0 +EDGE2 8488 1189 0.998511 0.0136787 -0.00363874 1 0 1 1 0 0 +EDGE2 8488 3089 1.01899 -0.0271462 -0.00427848 1 0 1 1 0 0 +EDGE2 8488 1169 0.993444 -0.05249 -0.00497838 1 0 1 1 0 0 +EDGE2 8489 8488 -0.955331 0.0473867 -0.00815349 1 0 1 1 0 0 +EDGE2 8489 8388 -1.05495 -0.00938806 6.18882e-05 1 0 1 1 0 0 +EDGE2 8489 3128 -1.02375 -0.0345257 0.0136814 1 0 1 1 0 0 +EDGE2 8489 3488 -0.992896 0.041532 -0.0182174 1 0 1 1 0 0 +EDGE2 8489 5828 -1.09132 -0.0769319 0.00900002 1 0 1 1 0 0 +EDGE2 8489 5848 -1.03996 -0.0313715 -0.00806541 1 0 1 1 0 0 +EDGE2 8489 3168 -0.957563 -0.0278192 0.0277838 1 0 1 1 0 0 +EDGE2 8489 1188 -0.962896 -0.0157097 -0.0184612 1 0 1 1 0 0 +EDGE2 8489 3088 -0.94508 -0.0864841 0.0037718 1 0 1 1 0 0 +EDGE2 8489 3108 -1.02442 0.033123 -0.00122409 1 0 1 1 0 0 +EDGE2 8489 1168 -0.978742 -0.00371299 -0.00281528 1 0 1 1 0 0 +EDGE2 8489 5849 -0.0346869 0.0053993 0.0328748 1 0 1 1 0 0 +EDGE2 8489 8389 0.0383229 0.0122878 0.0298668 1 0 1 1 0 0 +EDGE2 8489 3109 0.0271335 0.0326227 -0.00240199 1 0 1 1 0 0 +EDGE2 8489 3169 0.0299835 -0.0326848 -0.00104255 1 0 1 1 0 0 +EDGE2 8489 3489 -0.0948177 0.00205054 -0.00560326 1 0 1 1 0 0 +EDGE2 8489 5829 0.073383 -0.0144005 0.0146138 1 0 1 1 0 0 +EDGE2 8489 3129 0.0449075 0.00990766 -0.0348616 1 0 1 1 0 0 +EDGE2 8489 1189 0.0199151 0.0391929 -0.000239135 1 0 1 1 0 0 +EDGE2 8489 3089 -0.0229492 0.0463052 -0.00391763 1 0 1 1 0 0 +EDGE2 8489 1169 0.00774341 0.020335 0.024552 1 0 1 1 0 0 +EDGE2 8489 3050 0.991293 0.0125819 -3.08575 1 0 1 1 0 0 +EDGE2 8489 5850 0.940047 -0.0885706 0.0128686 1 0 1 1 0 0 +EDGE2 8489 8390 1.00608 0.0367026 0.0137839 1 0 1 1 0 0 +EDGE2 8489 3170 1.02152 -0.0688097 0.00268282 1 0 1 1 0 0 +EDGE2 8489 5790 1.03772 -0.0564014 -3.12791 1 0 1 1 0 0 +EDGE2 8489 5810 1.0662 -0.00307222 -3.12185 1 0 1 1 0 0 +EDGE2 8489 5830 0.988374 -0.0325988 -0.0175193 1 0 1 1 0 0 +EDGE2 8489 3490 1.01048 0.0179896 -0.00552813 1 0 1 1 0 0 +EDGE2 8489 3110 0.985483 -0.00614279 0.0162455 1 0 1 1 0 0 +EDGE2 8489 3130 0.977869 -0.106257 -0.0344266 1 0 1 1 0 0 +EDGE2 8489 3090 1.03425 -0.025978 0.010284 1 0 1 1 0 0 +EDGE2 8489 1130 0.894881 -0.0733548 -3.13725 1 0 1 1 0 0 +EDGE2 8489 1170 1.05917 -0.110397 0.0108873 1 0 1 1 0 0 +EDGE2 8489 1190 1.03527 -0.0208365 0.0493017 1 0 1 1 0 0 +EDGE2 8489 3030 0.984758 0.0109252 -3.11081 1 0 1 1 0 0 +EDGE2 8489 1150 1.08819 -0.118296 -3.14736 1 0 1 1 0 0 +EDGE2 8489 1110 0.987998 -0.0283842 -3.1584 1 0 1 1 0 0 +EDGE2 8490 5849 -0.94742 -0.0159309 -0.0258722 1 0 1 1 0 0 +EDGE2 8490 8489 -1.0861 -0.0287581 0.00526703 1 0 1 1 0 0 +EDGE2 8490 8389 -0.920246 -0.0762085 -0.0184762 1 0 1 1 0 0 +EDGE2 8490 3109 -1.02249 0.0777006 0.0391499 1 0 1 1 0 0 +EDGE2 8490 3169 -1.00201 0.0233746 0.00516465 1 0 1 1 0 0 +EDGE2 8490 3489 -1.01141 0.0545159 0.0062772 1 0 1 1 0 0 +EDGE2 8490 5829 -0.966298 -0.0516348 0.0204903 1 0 1 1 0 0 +EDGE2 8490 3129 -0.971629 0.123576 -0.0115713 1 0 1 1 0 0 +EDGE2 8490 1189 -0.971093 -0.0162704 0.00826962 1 0 1 1 0 0 +EDGE2 8490 3089 -0.994995 -0.0129643 0.0105441 1 0 1 1 0 0 +EDGE2 8490 1169 -0.986304 0.0273737 0.0156838 1 0 1 1 0 0 +EDGE2 8490 3050 0.0672443 0.0505179 -3.15854 1 0 1 1 0 0 +EDGE2 8490 3131 -0.113825 0.950988 1.5459 1 0 1 1 0 0 +EDGE2 8490 3491 -0.0306326 0.981476 1.54237 1 0 1 1 0 0 +EDGE2 8490 5811 0.113437 1.02434 1.59572 1 0 1 1 0 0 +EDGE2 8490 5831 -0.0618729 0.963002 1.59392 1 0 1 1 0 0 +EDGE2 8490 3171 -0.0108991 0.919407 1.56391 1 0 1 1 0 0 +EDGE2 8490 5850 -0.0154367 0.00256953 -0.00596757 1 0 1 1 0 0 +EDGE2 8490 1151 -0.0378592 0.970171 1.56756 1 0 1 1 0 0 +EDGE2 8490 1191 0.0189248 0.975331 1.54971 1 0 1 1 0 0 +EDGE2 8490 3091 0.028091 1.00482 1.54782 1 0 1 1 0 0 +EDGE2 8490 3111 -0.0845137 0.972784 1.52076 1 0 1 1 0 0 +EDGE2 8490 1171 0.0166882 1.03585 1.56884 1 0 1 1 0 0 +EDGE2 8490 8390 0.0501692 -0.0195814 -0.00647424 1 0 1 1 0 0 +EDGE2 8490 3170 0.00384307 -0.0641366 0.00737033 1 0 1 1 0 0 +EDGE2 8490 5790 0.0659498 0.00865723 -3.13241 1 0 1 1 0 0 +EDGE2 8490 5810 -0.0173161 0.0251379 -3.10629 1 0 1 1 0 0 +EDGE2 8490 5830 -0.13741 -0.0283745 0.00351017 1 0 1 1 0 0 +EDGE2 8490 3490 0.0577754 -0.0418707 -0.0134975 1 0 1 1 0 0 +EDGE2 8490 3110 0.0337382 -0.0512955 0.0131145 1 0 1 1 0 0 +EDGE2 8490 3130 0.064602 0.013541 0.0147559 1 0 1 1 0 0 +EDGE2 8490 3090 0.0333155 0.0601229 -0.00329506 1 0 1 1 0 0 +EDGE2 8490 5789 1.01802 0.00417042 -3.15855 1 0 1 1 0 0 +EDGE2 8490 1130 -0.0354444 -0.03376 -3.10183 1 0 1 1 0 0 +EDGE2 8490 1170 0.0445137 -0.0250663 0.0137416 1 0 1 1 0 0 +EDGE2 8490 1190 0.0493779 -0.0437359 -0.0175915 1 0 1 1 0 0 +EDGE2 8490 3030 0.0438198 0.0164113 -3.20412 1 0 1 1 0 0 +EDGE2 8490 1150 0.0226473 -0.0249885 -3.14209 1 0 1 1 0 0 +EDGE2 8490 1110 -0.055273 0.0598184 -3.14755 1 0 1 1 0 0 +EDGE2 8490 5809 1.00406 0.0678119 -3.12082 1 0 1 1 0 0 +EDGE2 8490 1109 1.0378 -0.00291584 -3.1547 1 0 1 1 0 0 +EDGE2 8490 1149 0.978236 0.0384469 -3.13832 1 0 1 1 0 0 +EDGE2 8490 3029 1.0753 -0.0962519 -3.1479 1 0 1 1 0 0 +EDGE2 8490 3049 0.983055 -0.0180272 -3.13505 1 0 1 1 0 0 +EDGE2 8490 1129 0.969407 -0.0431938 -3.1433 1 0 1 1 0 0 +EDGE2 8490 5851 -0.0372798 -1.04338 -1.58866 1 0 1 1 0 0 +EDGE2 8490 8391 -0.0840043 -1.03532 -1.53897 1 0 1 1 0 0 +EDGE2 8490 1111 0.0117337 -0.986338 -1.55033 1 0 1 1 0 0 +EDGE2 8490 3031 -0.0612105 -0.988276 -1.54089 1 0 1 1 0 0 +EDGE2 8490 3051 -0.0210657 -0.897743 -1.57499 1 0 1 1 0 0 +EDGE2 8490 5791 0.0520649 -1.02735 -1.57928 1 0 1 1 0 0 +EDGE2 8490 1131 0.0622524 -1.02665 -1.56078 1 0 1 1 0 0 +EDGE2 8491 3050 -0.97843 -0.0261473 1.57972 1 0 1 1 0 0 +EDGE2 8491 3131 0.031904 -0.00549696 -0.0222556 1 0 1 1 0 0 +EDGE2 8491 3092 0.967269 -0.0748859 -0.00224439 1 0 1 1 0 0 +EDGE2 8491 5812 1.0403 0.0482572 -0.00226856 1 0 1 1 0 0 +EDGE2 8491 5832 0.962359 0.0412628 0.0212812 1 0 1 1 0 0 +EDGE2 8491 3132 0.970543 0.0180389 -0.0222609 1 0 1 1 0 0 +EDGE2 8491 3172 0.960641 0.0374456 0.00345639 1 0 1 1 0 0 +EDGE2 8491 3492 0.978582 -0.000884993 0.0145917 1 0 1 1 0 0 +EDGE2 8491 3112 0.899537 -0.0142292 -0.0097463 1 0 1 1 0 0 +EDGE2 8491 1152 1.03466 -0.00966775 0.0115458 1 0 1 1 0 0 +EDGE2 8491 1172 1.11294 -0.00249978 -0.0227026 1 0 1 1 0 0 +EDGE2 8491 1192 1.03163 0.0494085 0.00825562 1 0 1 1 0 0 +EDGE2 8491 3491 0.00930225 -0.0158411 -0.0304378 1 0 1 1 0 0 +EDGE2 8491 5811 0.0363826 -0.0254452 -0.0077423 1 0 1 1 0 0 +EDGE2 8491 5831 0.0501726 0.0320978 0.00752705 1 0 1 1 0 0 +EDGE2 8491 3171 -0.0194187 -0.00646561 -0.0263827 1 0 1 1 0 0 +EDGE2 8491 5850 -1.00592 0.117128 -1.53264 1 0 1 1 0 0 +EDGE2 8491 1151 0.0199522 0.0616917 -0.0180299 1 0 1 1 0 0 +EDGE2 8491 1191 -0.0610904 -0.0145481 0.00605192 1 0 1 1 0 0 +EDGE2 8491 3091 -0.00520928 -0.0810952 -0.00633566 1 0 1 1 0 0 +EDGE2 8491 3111 -0.0925107 0.0469276 -0.0444793 1 0 1 1 0 0 +EDGE2 8491 1171 0.075846 0.0233555 0.0153035 1 0 1 1 0 0 +EDGE2 8491 8490 -0.994663 0.0269222 -1.54356 1 0 1 1 0 0 +EDGE2 8491 8390 -1.0499 0.0464506 -1.57434 1 0 1 1 0 0 +EDGE2 8491 3170 -1.0659 0.0146745 -1.59067 1 0 1 1 0 0 +EDGE2 8491 5790 -1.0094 0.0593205 1.60513 1 0 1 1 0 0 +EDGE2 8491 5810 -1.02546 0.0207713 1.55672 1 0 1 1 0 0 +EDGE2 8491 5830 -0.943982 0.0467433 -1.57048 1 0 1 1 0 0 +EDGE2 8491 3490 -1.06528 -0.00590985 -1.5988 1 0 1 1 0 0 +EDGE2 8491 3110 -1.08202 -0.00236248 -1.58943 1 0 1 1 0 0 +EDGE2 8491 3130 -0.910222 -0.041626 -1.56559 1 0 1 1 0 0 +EDGE2 8491 3090 -1.03997 -0.0248052 -1.58622 1 0 1 1 0 0 +EDGE2 8491 1130 -0.972899 0.0774894 1.59036 1 0 1 1 0 0 +EDGE2 8491 1170 -0.963996 0.0262917 -1.56469 1 0 1 1 0 0 +EDGE2 8491 1190 -0.890342 0.0527715 -1.55956 1 0 1 1 0 0 +EDGE2 8491 3030 -0.997394 -0.0156426 1.57547 1 0 1 1 0 0 +EDGE2 8491 1150 -0.971125 -0.00531972 1.55957 1 0 1 1 0 0 +EDGE2 8491 1110 -0.984659 0.0144118 1.55063 1 0 1 1 0 0 +EDGE2 8492 1173 1.01097 -0.0808539 0.002275 1 0 1 1 0 0 +EDGE2 8492 3133 0.978748 0.0960621 0.0124002 1 0 1 1 0 0 +EDGE2 8492 3493 0.997504 0.0826619 0.01762 1 0 1 1 0 0 +EDGE2 8492 5813 1.06931 0.0380774 0.003189 1 0 1 1 0 0 +EDGE2 8492 5833 1.02978 -0.00600147 0.043215 1 0 1 1 0 0 +EDGE2 8492 3173 1.05488 0.0285646 -0.0432495 1 0 1 1 0 0 +EDGE2 8492 3093 1.03543 9.72713e-06 -0.0138616 1 0 1 1 0 0 +EDGE2 8492 3113 0.985582 0.0163734 0.0120064 1 0 1 1 0 0 +EDGE2 8492 1193 1.04166 -0.0372722 -0.0352839 1 0 1 1 0 0 +EDGE2 8492 3131 -0.974834 -0.0298404 -0.0218113 1 0 1 1 0 0 +EDGE2 8492 3092 -0.0308581 -0.00236445 0.014282 1 0 1 1 0 0 +EDGE2 8492 5812 -0.0223891 -0.0647304 -0.0347534 1 0 1 1 0 0 +EDGE2 8492 1153 1.00279 -0.0700735 -0.0344978 1 0 1 1 0 0 +EDGE2 8492 5832 0.0430584 -0.0385596 -0.00419892 1 0 1 1 0 0 +EDGE2 8492 3132 -0.0374059 0.0576674 0.0352979 1 0 1 1 0 0 +EDGE2 8492 3172 0.0329207 0.021046 0.026119 1 0 1 1 0 0 +EDGE2 8492 3492 -0.0372836 0.0240504 -0.00452234 1 0 1 1 0 0 +EDGE2 8492 3112 -0.00473393 0.0317967 -0.0332297 1 0 1 1 0 0 +EDGE2 8492 8491 -1.00143 0.0599849 -0.00812491 1 0 1 1 0 0 +EDGE2 8492 1152 0.029168 0.0227079 0.0180674 1 0 1 1 0 0 +EDGE2 8492 1172 -0.0758206 -0.0150098 0.0214345 1 0 1 1 0 0 +EDGE2 8492 1192 0.021295 0.00237146 0.000718514 1 0 1 1 0 0 +EDGE2 8492 3491 -1.03322 0.00592739 -0.0068434 1 0 1 1 0 0 +EDGE2 8492 5811 -0.99936 -0.0148375 -0.0248271 1 0 1 1 0 0 +EDGE2 8492 5831 -1.02616 0.00220862 0.0359964 1 0 1 1 0 0 +EDGE2 8492 3171 -1.01612 -0.0573169 -0.00113956 1 0 1 1 0 0 +EDGE2 8492 1151 -1.09308 -0.000952625 -0.00806569 1 0 1 1 0 0 +EDGE2 8492 1191 -1.02234 -0.0322752 0.000987657 1 0 1 1 0 0 +EDGE2 8492 3091 -1.02075 0.00997488 -0.0315844 1 0 1 1 0 0 +EDGE2 8492 3111 -1.01518 0.0165845 0.0454268 1 0 1 1 0 0 +EDGE2 8492 1171 -0.918643 0.00322461 -0.00786885 1 0 1 1 0 0 +EDGE2 8493 1173 0.0667679 -0.00984399 0.00565123 1 0 1 1 0 0 +EDGE2 8493 1174 0.95359 -0.0783955 -0.00705547 1 0 1 1 0 0 +EDGE2 8493 3174 1.06643 -0.0790424 -0.0173446 1 0 1 1 0 0 +EDGE2 8493 5814 0.975595 -0.0378991 0.000631191 1 0 1 1 0 0 +EDGE2 8493 5834 0.958127 -0.0768847 0.0110325 1 0 1 1 0 0 +EDGE2 8493 3494 1.02954 -0.0719894 0.00334498 1 0 1 1 0 0 +EDGE2 8493 3094 0.923743 0.00976816 -0.00621854 1 0 1 1 0 0 +EDGE2 8493 3114 0.963463 -0.0856464 0.00116837 1 0 1 1 0 0 +EDGE2 8493 3134 0.987972 0.0373857 0.0276552 1 0 1 1 0 0 +EDGE2 8493 1194 1.02878 -0.0423555 0.024645 1 0 1 1 0 0 +EDGE2 8493 1154 1.04696 -0.0370721 -0.0130754 1 0 1 1 0 0 +EDGE2 8493 3133 -0.0827791 -0.0569133 0.0194464 1 0 1 1 0 0 +EDGE2 8493 3493 0.0288176 0.00779554 0.0335766 1 0 1 1 0 0 +EDGE2 8493 5813 -0.0302402 -0.0628475 -0.0236662 1 0 1 1 0 0 +EDGE2 8493 5833 -0.0837528 0.0403707 -0.0219212 1 0 1 1 0 0 +EDGE2 8493 3173 -0.0711702 0.102065 0.00517378 1 0 1 1 0 0 +EDGE2 8493 3093 -0.0338552 0.0601696 -0.0151535 1 0 1 1 0 0 +EDGE2 8493 3113 0.0318568 -0.0191775 -0.00861876 1 0 1 1 0 0 +EDGE2 8493 1193 0.0147526 0.00377116 -0.00631789 1 0 1 1 0 0 +EDGE2 8493 3092 -1.02392 -0.0589245 -0.0439257 1 0 1 1 0 0 +EDGE2 8493 5812 -1.01829 -0.0483333 -0.00624869 1 0 1 1 0 0 +EDGE2 8493 8492 -0.98877 0.0662231 -0.016781 1 0 1 1 0 0 +EDGE2 8493 1153 0.0522348 -0.0480059 0.0125241 1 0 1 1 0 0 +EDGE2 8493 5832 -0.914382 0.0203181 0.0509374 1 0 1 1 0 0 +EDGE2 8493 3132 -1.02995 0.0313805 -0.022271 1 0 1 1 0 0 +EDGE2 8493 3172 -1.02839 0.0241989 0.0303756 1 0 1 1 0 0 +EDGE2 8493 3492 -0.989758 -0.0692278 -0.0063706 1 0 1 1 0 0 +EDGE2 8493 3112 -1.00405 0.0104116 0.0204111 1 0 1 1 0 0 +EDGE2 8493 1152 -1.06733 -0.0129983 -0.0166938 1 0 1 1 0 0 +EDGE2 8493 1172 -0.997353 -0.0203771 0.0366522 1 0 1 1 0 0 +EDGE2 8493 1192 -0.977305 -0.114681 -0.0138807 1 0 1 1 0 0 +EDGE2 8494 3495 0.973416 0.036674 0.0379745 1 0 1 1 0 0 +EDGE2 8494 5835 1.0671 -0.0611722 0.00575223 1 0 1 1 0 0 +EDGE2 8494 5815 0.986189 -0.0375123 0.0347621 1 0 1 1 0 0 +EDGE2 8494 1173 -0.986249 -0.0398649 0.0373968 1 0 1 1 0 0 +EDGE2 8494 1174 -0.000363146 0.0148378 0.00634558 1 0 1 1 0 0 +EDGE2 8494 3115 0.988503 -0.0540959 -0.0183026 1 0 1 1 0 0 +EDGE2 8494 3175 1.02883 -0.0862867 0.0118503 1 0 1 1 0 0 +EDGE2 8494 3375 1.0001 -0.0475366 -3.14683 1 0 1 1 0 0 +EDGE2 8494 3475 0.950327 -0.000696761 -3.12249 1 0 1 1 0 0 +EDGE2 8494 3135 1.12207 0.0168863 0.049187 1 0 1 1 0 0 +EDGE2 8494 1175 1.02991 -0.0436178 0.0188266 1 0 1 1 0 0 +EDGE2 8494 1195 1.00638 0.0997783 0.0125732 1 0 1 1 0 0 +EDGE2 8494 3095 1.06624 -0.124532 0.0050403 1 0 1 1 0 0 +EDGE2 8494 1155 0.989441 -0.0634619 -0.014607 1 0 1 1 0 0 +EDGE2 8494 3174 0.00821792 -0.00363013 -0.00663162 1 0 1 1 0 0 +EDGE2 8494 5814 -0.0132101 -0.0159752 -0.0258589 1 0 1 1 0 0 +EDGE2 8494 5834 0.0133853 -0.0170986 -0.00468502 1 0 1 1 0 0 +EDGE2 8494 3494 0.0649343 -0.01964 0.00766126 1 0 1 1 0 0 +EDGE2 8494 3094 -0.0256302 0.00683312 0.0124312 1 0 1 1 0 0 +EDGE2 8494 3114 -0.0254462 -0.0169414 0.00243073 1 0 1 1 0 0 +EDGE2 8494 3134 0.0125669 -0.0317947 0.0134633 1 0 1 1 0 0 +EDGE2 8494 1194 0.0157497 -0.0373042 -0.0337032 1 0 1 1 0 0 +EDGE2 8494 8493 -1.04916 -0.0345245 0.0184108 1 0 1 1 0 0 +EDGE2 8494 1154 0.0264936 -0.0149479 0.0261095 1 0 1 1 0 0 +EDGE2 8494 3133 -1.03719 0.0723721 0.0247804 1 0 1 1 0 0 +EDGE2 8494 3493 -1.01654 -0.0177132 0.0209741 1 0 1 1 0 0 +EDGE2 8494 5813 -0.965377 0.0826289 -0.0186215 1 0 1 1 0 0 +EDGE2 8494 5833 -0.980038 -0.0273997 -0.0234146 1 0 1 1 0 0 +EDGE2 8494 3173 -1.03818 0.0222956 0.00390033 1 0 1 1 0 0 +EDGE2 8494 3093 -1.02215 -0.0699952 -0.005505 1 0 1 1 0 0 +EDGE2 8494 3113 -0.971098 -0.0678927 -0.00897065 1 0 1 1 0 0 +EDGE2 8494 1193 -1.01664 -0.0350792 0.0104341 1 0 1 1 0 0 +EDGE2 8494 1153 -1.05602 0.0379138 -0.0165089 1 0 1 1 0 0 +EDGE2 8495 3495 -0.085969 0.0807071 0.0215593 1 0 1 1 0 0 +EDGE2 8495 3474 1.0665 -0.0583807 -3.16189 1 0 1 1 0 0 +EDGE2 8495 3374 1.07775 -0.0134863 -3.11551 1 0 1 1 0 0 +EDGE2 8495 1196 -0.00777772 0.965496 1.60059 1 0 1 1 0 0 +EDGE2 8495 3476 -0.0315875 1.03793 1.55557 1 0 1 1 0 0 +EDGE2 8495 5836 -0.071435 0.902459 1.56682 1 0 1 1 0 0 +EDGE2 8495 5816 -0.0613174 0.910218 1.57186 1 0 1 1 0 0 +EDGE2 8495 3116 -0.0221614 0.968551 1.55691 1 0 1 1 0 0 +EDGE2 8495 3136 0.0359972 1.02862 1.54669 1 0 1 1 0 0 +EDGE2 8495 3376 -0.0724242 0.903468 1.5627 1 0 1 1 0 0 +EDGE2 8495 3096 -0.11112 0.922659 1.56865 1 0 1 1 0 0 +EDGE2 8495 1156 -0.0504603 1.05843 1.5734 1 0 1 1 0 0 +EDGE2 8495 1176 0.0840749 1.02708 1.58936 1 0 1 1 0 0 +EDGE2 8495 5835 0.0968212 -0.0385527 -0.0446439 1 0 1 1 0 0 +EDGE2 8495 5815 -0.00633808 -0.048531 0.00837599 1 0 1 1 0 0 +EDGE2 8495 1174 -1.03339 -0.0244121 -0.0145059 1 0 1 1 0 0 +EDGE2 8495 3115 -0.0259727 0.00456535 0.0207272 1 0 1 1 0 0 +EDGE2 8495 3175 0.0532093 -0.0415846 0.00497289 1 0 1 1 0 0 +EDGE2 8495 3375 0.0573895 0.0753688 -3.13491 1 0 1 1 0 0 +EDGE2 8495 3475 0.0964407 -0.00489984 -3.15103 1 0 1 1 0 0 +EDGE2 8495 3135 -0.0850835 0.0579516 -0.0263596 1 0 1 1 0 0 +EDGE2 8495 1175 0.0401339 -0.0108323 0.00943977 1 0 1 1 0 0 +EDGE2 8495 1195 0.046487 0.025199 -0.0235648 1 0 1 1 0 0 +EDGE2 8495 3095 0.00751497 0.0181287 -0.0359981 1 0 1 1 0 0 +EDGE2 8495 1155 0.0274867 -0.0142495 -0.0159388 1 0 1 1 0 0 +EDGE2 8495 3174 -0.927155 -0.0560418 -0.00242022 1 0 1 1 0 0 +EDGE2 8495 5814 -0.921631 0.0363106 0.0174707 1 0 1 1 0 0 +EDGE2 8495 5834 -0.966929 -0.0563238 0.0126324 1 0 1 1 0 0 +EDGE2 8495 8494 -1.02038 -0.0711608 0.000881792 1 0 1 1 0 0 +EDGE2 8495 3494 -0.937263 0.0519178 -0.0092616 1 0 1 1 0 0 +EDGE2 8495 3094 -0.996142 0.086437 -0.0221431 1 0 1 1 0 0 +EDGE2 8495 3114 -1.04532 -0.00278675 -0.00449898 1 0 1 1 0 0 +EDGE2 8495 3134 -1.0392 0.00465641 0.0363126 1 0 1 1 0 0 +EDGE2 8495 1194 -1.03922 -0.0154311 -0.0302602 1 0 1 1 0 0 +EDGE2 8495 1154 -0.987854 -0.00648588 0.0715904 1 0 1 1 0 0 +EDGE2 8495 3176 0.0118204 -1.03684 -1.55528 1 0 1 1 0 0 +EDGE2 8495 3496 -0.000693156 -0.998986 -1.55641 1 0 1 1 0 0 +EDGE2 8496 3495 -0.989791 -0.00253653 -1.54885 1 0 1 1 0 0 +EDGE2 8496 1197 0.967309 0.0755657 -0.0362563 1 0 1 1 0 0 +EDGE2 8496 3477 0.952541 0.0436844 0.0179379 1 0 1 1 0 0 +EDGE2 8496 5837 1.04728 0.0203971 -0.0072211 1 0 1 1 0 0 +EDGE2 8496 5817 1.03887 0.0357453 -0.0281251 1 0 1 1 0 0 +EDGE2 8496 3117 1.00774 0.0334345 0.0453168 1 0 1 1 0 0 +EDGE2 8496 3137 1.10836 -0.0864853 -0.00820254 1 0 1 1 0 0 +EDGE2 8496 3377 1.02827 0.0210165 -0.0385877 1 0 1 1 0 0 +EDGE2 8496 3097 0.926219 -0.0632784 -0.0508223 1 0 1 1 0 0 +EDGE2 8496 1177 1.02598 0.0707083 0.0232702 1 0 1 1 0 0 +EDGE2 8496 1157 1.01504 0.0341774 -0.016015 1 0 1 1 0 0 +EDGE2 8496 1196 0.00217823 -0.0659997 -0.025895 1 0 1 1 0 0 +EDGE2 8496 3476 -0.059623 0.0671488 -0.00597865 1 0 1 1 0 0 +EDGE2 8496 5836 -0.0149789 0.0668109 0.00870256 1 0 1 1 0 0 +EDGE2 8496 5816 0.0814094 -0.0176132 -0.0296555 1 0 1 1 0 0 +EDGE2 8496 3116 0.115007 0.0301009 -0.0221435 1 0 1 1 0 0 +EDGE2 8496 3136 -0.057699 0.022388 -0.0224813 1 0 1 1 0 0 +EDGE2 8496 3376 -0.0379861 -0.0403786 -0.0251354 1 0 1 1 0 0 +EDGE2 8496 3096 0.047885 0.00171668 0.0253941 1 0 1 1 0 0 +EDGE2 8496 1156 -0.00594284 0.0548597 0.0115489 1 0 1 1 0 0 +EDGE2 8496 1176 0.0450381 -0.00918014 -0.0126002 1 0 1 1 0 0 +EDGE2 8496 5835 -1.09024 0.0430243 -1.57002 1 0 1 1 0 0 +EDGE2 8496 8495 -1.01978 0.0502915 -1.57596 1 0 1 1 0 0 +EDGE2 8496 5815 -0.979292 0.0231958 -1.55926 1 0 1 1 0 0 +EDGE2 8496 3115 -0.964475 -0.0344298 -1.57567 1 0 1 1 0 0 +EDGE2 8496 3175 -0.983416 0.026292 -1.5583 1 0 1 1 0 0 +EDGE2 8496 3375 -0.871944 -0.00874045 1.5655 1 0 1 1 0 0 +EDGE2 8496 3475 -0.996972 0.044076 1.58202 1 0 1 1 0 0 +EDGE2 8496 3135 -0.981596 -0.0496745 -1.54235 1 0 1 1 0 0 +EDGE2 8496 1175 -1.09206 0.0783286 -1.58768 1 0 1 1 0 0 +EDGE2 8496 1195 -1.08032 -0.0394675 -1.57902 1 0 1 1 0 0 +EDGE2 8496 3095 -0.970944 -0.0746312 -1.55685 1 0 1 1 0 0 +EDGE2 8496 1155 -1.05003 0.0120623 -1.55419 1 0 1 1 0 0 +EDGE2 8497 1197 -0.114698 0.107624 0.0239475 1 0 1 1 0 0 +EDGE2 8497 5818 1.01993 0.0595758 -0.017223 1 0 1 1 0 0 +EDGE2 8497 5838 1.06082 0.0234965 -0.0316342 1 0 1 1 0 0 +EDGE2 8497 3098 1.0289 0.034601 0.0220948 1 0 1 1 0 0 +EDGE2 8497 3138 1.0093 0.0527264 -0.00596318 1 0 1 1 0 0 +EDGE2 8497 3378 1.06953 -0.0377423 -0.0407128 1 0 1 1 0 0 +EDGE2 8497 3478 1.0103 -0.0241296 0.00189123 1 0 1 1 0 0 +EDGE2 8497 3118 0.995951 -0.0560574 0.012589 1 0 1 1 0 0 +EDGE2 8497 1178 1.04751 0.0450947 -0.02199 1 0 1 1 0 0 +EDGE2 8497 1198 1.05076 -0.0860897 0.0262352 1 0 1 1 0 0 +EDGE2 8497 1158 0.95608 0.0316927 -0.0171539 1 0 1 1 0 0 +EDGE2 8497 3477 0.06661 0.0122459 -0.00557784 1 0 1 1 0 0 +EDGE2 8497 5837 -0.0312875 0.0851669 -0.0299532 1 0 1 1 0 0 +EDGE2 8497 5817 -0.0489937 0.0586975 -0.00244994 1 0 1 1 0 0 +EDGE2 8497 3117 0.00121115 -0.0998224 0.00895267 1 0 1 1 0 0 +EDGE2 8497 3137 0.128678 -0.0296632 0.0315462 1 0 1 1 0 0 +EDGE2 8497 3377 0.109395 -0.052548 -0.0300427 1 0 1 1 0 0 +EDGE2 8497 3097 -0.0073225 -0.0676832 -0.0320592 1 0 1 1 0 0 +EDGE2 8497 1177 0.0691927 -0.0450873 -0.00856756 1 0 1 1 0 0 +EDGE2 8497 1157 0.0101787 0.0371247 0.0233644 1 0 1 1 0 0 +EDGE2 8497 1196 -0.953037 -0.0376975 0.0273727 1 0 1 1 0 0 +EDGE2 8497 3476 -1.03011 0.0315891 -0.00487659 1 0 1 1 0 0 +EDGE2 8497 5836 -0.958161 -0.0178031 -0.016083 1 0 1 1 0 0 +EDGE2 8497 8496 -0.940081 0.0214132 0.00978549 1 0 1 1 0 0 +EDGE2 8497 5816 -0.917021 -0.00341751 -0.0106489 1 0 1 1 0 0 +EDGE2 8497 3116 -0.910984 -0.0380532 0.00503941 1 0 1 1 0 0 +EDGE2 8497 3136 -1.10511 -0.0364296 -0.0127813 1 0 1 1 0 0 +EDGE2 8497 3376 -0.940918 0.0393548 0.0184428 1 0 1 1 0 0 +EDGE2 8497 3096 -1.03697 0.0350677 0.0268095 1 0 1 1 0 0 +EDGE2 8497 1156 -1.12865 -0.0549879 0.0300751 1 0 1 1 0 0 +EDGE2 8497 1176 -1.05695 0.0274295 0.0161382 1 0 1 1 0 0 +EDGE2 8498 1197 -0.915091 0.0239613 -0.0315371 1 0 1 1 0 0 +EDGE2 8498 5839 0.891779 -0.0431255 -0.0386281 1 0 1 1 0 0 +EDGE2 8498 3119 0.990851 0.00969651 -0.021953 1 0 1 1 0 0 +EDGE2 8498 3379 0.996709 -0.0247065 0.0167093 1 0 1 1 0 0 +EDGE2 8498 3479 1.01228 -0.0234768 0.0099503 1 0 1 1 0 0 +EDGE2 8498 5819 0.995121 -0.0402915 -0.0291295 1 0 1 1 0 0 +EDGE2 8498 3139 1.12022 0.00494703 -0.0017743 1 0 1 1 0 0 +EDGE2 8498 1179 0.934981 0.0588246 -0.00112999 1 0 1 1 0 0 +EDGE2 8498 1199 1.01238 0.0764317 -0.025062 1 0 1 1 0 0 +EDGE2 8498 3099 0.954618 0.0822735 0.00157953 1 0 1 1 0 0 +EDGE2 8498 1159 0.991654 0.0517566 -0.0231379 1 0 1 1 0 0 +EDGE2 8498 5818 -0.0331159 -0.0408627 -0.00356737 1 0 1 1 0 0 +EDGE2 8498 5838 -0.00617962 0.0527227 0.00948377 1 0 1 1 0 0 +EDGE2 8498 3098 -0.0392757 -0.0295371 0.00485999 1 0 1 1 0 0 +EDGE2 8498 3138 -0.0948545 0.0221557 -0.00235845 1 0 1 1 0 0 +EDGE2 8498 3378 0.00748231 0.0877727 0.00221732 1 0 1 1 0 0 +EDGE2 8498 3478 0.0560004 0.0246088 -0.0269332 1 0 1 1 0 0 +EDGE2 8498 3118 0.0520859 0.0550111 0.00233704 1 0 1 1 0 0 +EDGE2 8498 1178 0.0539046 0.0263604 0.023543 1 0 1 1 0 0 +EDGE2 8498 1198 -0.0319286 0.0326899 -0.0258293 1 0 1 1 0 0 +EDGE2 8498 1158 -0.0153525 0.00964929 0.00845217 1 0 1 1 0 0 +EDGE2 8498 3477 -1.00632 -0.0097858 -0.0194987 1 0 1 1 0 0 +EDGE2 8498 5837 -1.01672 -0.0314657 0.0233427 1 0 1 1 0 0 +EDGE2 8498 8497 -0.97928 -0.0305581 0.0113586 1 0 1 1 0 0 +EDGE2 8498 5817 -0.956549 -0.0737388 -0.0291696 1 0 1 1 0 0 +EDGE2 8498 3117 -1.0185 0.0700699 -0.0141783 1 0 1 1 0 0 +EDGE2 8498 3137 -1.04925 0.0941175 -0.0125087 1 0 1 1 0 0 +EDGE2 8498 3377 -0.955938 0.0233423 0.00888436 1 0 1 1 0 0 +EDGE2 8498 3097 -1.02918 0.000766967 -0.0362352 1 0 1 1 0 0 +EDGE2 8498 1177 -0.996096 -0.0125521 -0.02201 1 0 1 1 0 0 +EDGE2 8498 1157 -1.03312 -0.0435231 -0.0473953 1 0 1 1 0 0 +EDGE2 8499 5820 0.961216 -0.0393206 -0.0454888 1 0 1 1 0 0 +EDGE2 8499 5840 1.05065 0.028823 0.00721055 1 0 1 1 0 0 +EDGE2 8499 1160 1.10338 -0.0821124 -0.0137908 1 0 1 1 0 0 +EDGE2 8499 3140 0.992821 0.0121295 -0.0317643 1 0 1 1 0 0 +EDGE2 8499 3420 0.942337 0.0448471 -3.16188 1 0 1 1 0 0 +EDGE2 8499 3440 0.923608 -0.0138924 -3.14391 1 0 1 1 0 0 +EDGE2 8499 3480 1.10747 0.0203002 -0.00730007 1 0 1 1 0 0 +EDGE2 8499 3380 0.982383 0.0330067 0.00853545 1 0 1 1 0 0 +EDGE2 8499 1200 1.02836 0.0290378 -0.0379839 1 0 1 1 0 0 +EDGE2 8499 3100 1.0513 -0.00403724 0.0236414 1 0 1 1 0 0 +EDGE2 8499 3120 0.99323 0.0734997 -0.013212 1 0 1 1 0 0 +EDGE2 8499 1180 1.00405 0.0987982 0.000783278 1 0 1 1 0 0 +EDGE2 8499 900 1.06675 -0.0416209 -3.13486 1 0 1 1 0 0 +EDGE2 8499 840 1.02059 0.0355006 -3.14672 1 0 1 1 0 0 +EDGE2 8499 860 0.918931 0.0419898 -3.16369 1 0 1 1 0 0 +EDGE2 8499 5839 0.0139162 0.00355943 0.00401376 1 0 1 1 0 0 +EDGE2 8499 3119 0.0335863 0.00734373 -0.0377583 1 0 1 1 0 0 +EDGE2 8499 3379 0.0109556 -0.000161318 -0.00538689 1 0 1 1 0 0 +EDGE2 8499 3479 -0.0401429 -0.0458826 0.0115391 1 0 1 1 0 0 +EDGE2 8499 5819 0.0237555 -0.0134979 0.0123746 1 0 1 1 0 0 +EDGE2 8499 3139 0.0527618 -0.0251397 0.0361353 1 0 1 1 0 0 +EDGE2 8499 1179 0.0260867 -0.021694 0.0347916 1 0 1 1 0 0 +EDGE2 8499 1199 0.00457169 0.00473163 -0.0114438 1 0 1 1 0 0 +EDGE2 8499 3099 0.0287026 -0.0166642 0.0382799 1 0 1 1 0 0 +EDGE2 8499 1159 0.0108707 0.0265509 -0.0323661 1 0 1 1 0 0 +EDGE2 8499 5818 -1.033 -0.0287423 0.0261055 1 0 1 1 0 0 +EDGE2 8499 5838 -1.09529 -0.0453271 -0.0301148 1 0 1 1 0 0 +EDGE2 8499 8498 -1.03845 -0.0404222 0.0141428 1 0 1 1 0 0 +EDGE2 8499 3098 -0.937997 -0.00971295 -0.0334208 1 0 1 1 0 0 +EDGE2 8499 3138 -1.02172 -0.0279972 0.00136141 1 0 1 1 0 0 +EDGE2 8499 3378 -1.01558 0.0883214 0.0206534 1 0 1 1 0 0 +EDGE2 8499 3478 -0.986971 0.0331059 -0.00644236 1 0 1 1 0 0 +EDGE2 8499 3118 -0.998675 0.0197788 -0.00819824 1 0 1 1 0 0 +EDGE2 8499 1178 -0.980397 -0.0162112 0.014758 1 0 1 1 0 0 +EDGE2 8499 1198 -1.05705 -0.0702809 -0.0383107 1 0 1 1 0 0 +EDGE2 8499 1158 -1.02148 -0.0143168 0.0379838 1 0 1 1 0 0 +EDGE2 8500 5820 0.0668745 0.0514914 0.027383 1 0 1 1 0 0 +EDGE2 8500 839 0.925827 0.055132 -3.15896 1 0 1 1 0 0 +EDGE2 8500 899 1.0082 0.0412887 -3.12097 1 0 1 1 0 0 +EDGE2 8500 3419 0.928419 -0.0423933 -3.12607 1 0 1 1 0 0 +EDGE2 8500 3439 0.986779 0.0383358 -3.14578 1 0 1 1 0 0 +EDGE2 8500 859 0.951879 -0.0218211 -3.11802 1 0 1 1 0 0 +EDGE2 8500 3441 -0.0406472 -1.02306 -1.5657 1 0 1 1 0 0 +EDGE2 8500 841 0.00359312 -1.12039 -1.58284 1 0 1 1 0 0 +EDGE2 8500 901 0.00310334 -0.976032 -1.5826 1 0 1 1 0 0 +EDGE2 8500 1201 0.0321945 -1.00435 -1.55194 1 0 1 1 0 0 +EDGE2 8500 3421 -0.00647491 -0.949808 -1.56938 1 0 1 1 0 0 +EDGE2 8500 861 -0.036747 -0.953738 -1.55289 1 0 1 1 0 0 +EDGE2 8500 5840 -0.120541 -0.0527597 -0.0130779 1 0 1 1 0 0 +EDGE2 8500 5821 0.0230655 1.00829 1.5519 1 0 1 1 0 0 +EDGE2 8500 1160 0.0366443 0.0326635 0.00750525 1 0 1 1 0 0 +EDGE2 8500 3140 -0.0232848 0.0434362 -0.0111688 1 0 1 1 0 0 +EDGE2 8500 3420 -0.0958099 -0.0701512 -3.13092 1 0 1 1 0 0 +EDGE2 8500 3440 0.0469823 0.0525727 -3.18144 1 0 1 1 0 0 +EDGE2 8500 3480 -0.0372596 -0.0433505 -0.0140494 1 0 1 1 0 0 +EDGE2 8500 3380 0.0362176 0.0675489 0.00818393 1 0 1 1 0 0 +EDGE2 8500 1200 0.0539265 0.112196 0.0088651 1 0 1 1 0 0 +EDGE2 8500 3100 -0.00312269 -0.000248609 -0.0204217 1 0 1 1 0 0 +EDGE2 8500 3120 0.0388882 0.00141644 0.00511108 1 0 1 1 0 0 +EDGE2 8500 1180 -0.0320489 -0.0138076 0.00373042 1 0 1 1 0 0 +EDGE2 8500 900 0.0105986 0.012202 -3.1181 1 0 1 1 0 0 +EDGE2 8500 840 0.00427096 0.122216 -3.1173 1 0 1 1 0 0 +EDGE2 8500 860 -0.0362765 -0.11556 -3.09769 1 0 1 1 0 0 +EDGE2 8500 5841 0.0125988 0.992119 1.56156 1 0 1 1 0 0 +EDGE2 8500 3101 0.0262907 1.05464 1.57139 1 0 1 1 0 0 +EDGE2 8500 3141 0.0508802 1.09747 1.60816 1 0 1 1 0 0 +EDGE2 8500 3381 -0.0691379 1.0559 1.58886 1 0 1 1 0 0 +EDGE2 8500 3481 0.0673791 0.986967 1.59032 1 0 1 1 0 0 +EDGE2 8500 3121 0.0276869 0.814448 1.56477 1 0 1 1 0 0 +EDGE2 8500 1161 0.0642955 1.01656 1.54074 1 0 1 1 0 0 +EDGE2 8500 1181 -0.024418 0.966363 1.57837 1 0 1 1 0 0 +EDGE2 8500 5839 -1.00743 -0.0324841 0.0103808 1 0 1 1 0 0 +EDGE2 8500 8499 -0.974651 0.0514785 0.0448967 1 0 1 1 0 0 +EDGE2 8500 3119 -0.989438 0.121116 -0.0332745 1 0 1 1 0 0 +EDGE2 8500 3379 -1.05265 0.0246218 -0.0247693 1 0 1 1 0 0 +EDGE2 8500 3479 -0.983778 0.0245379 -0.0363887 1 0 1 1 0 0 +EDGE2 8500 5819 -1.01302 0.0568203 0.00412052 1 0 1 1 0 0 +EDGE2 8500 3139 -1.11561 -0.0183593 0.00685547 1 0 1 1 0 0 +EDGE2 8500 1179 -0.982071 0.0428896 -0.009868 1 0 1 1 0 0 +EDGE2 8500 1199 -0.960863 -0.090839 -0.0413685 1 0 1 1 0 0 +EDGE2 8500 3099 -0.989185 0.0411623 -0.00414062 1 0 1 1 0 0 +EDGE2 8500 1159 -1.02646 -0.0278235 -0.00562928 1 0 1 1 0 0 +EDGE2 8501 5820 -0.975544 -0.031833 1.54921 1 0 1 1 0 0 +EDGE2 8501 3441 -0.0613505 0.00783624 0.00976904 1 0 1 1 0 0 +EDGE2 8501 902 1.00658 -0.0515653 -0.0326839 1 0 1 1 0 0 +EDGE2 8501 3422 1.03294 0.080589 0.0154565 1 0 1 1 0 0 +EDGE2 8501 3442 0.951686 -0.0226783 0.0139284 1 0 1 1 0 0 +EDGE2 8501 1202 0.999955 0.0286505 -0.0359288 1 0 1 1 0 0 +EDGE2 8501 842 0.973192 -0.0360286 0.0147525 1 0 1 1 0 0 +EDGE2 8501 862 0.887368 -0.04059 0.00114132 1 0 1 1 0 0 +EDGE2 8501 841 -0.0421943 -0.0626383 0.00904553 1 0 1 1 0 0 +EDGE2 8501 901 0.0599979 0.0390503 -0.0097035 1 0 1 1 0 0 +EDGE2 8501 1201 -0.0680467 -0.0093342 -0.000313977 1 0 1 1 0 0 +EDGE2 8501 3421 0.0568369 -0.0715576 0.0167064 1 0 1 1 0 0 +EDGE2 8501 861 0.0207114 -0.00373438 -0.0205099 1 0 1 1 0 0 +EDGE2 8501 8500 -1.00943 -0.0203399 1.55935 1 0 1 1 0 0 +EDGE2 8501 5840 -1.02202 0.0296479 1.54726 1 0 1 1 0 0 +EDGE2 8501 1160 -1.03803 -0.0257256 1.5628 1 0 1 1 0 0 +EDGE2 8501 3140 -1.04138 -0.0308322 1.55685 1 0 1 1 0 0 +EDGE2 8501 3420 -1.06269 0.0274316 -1.565 1 0 1 1 0 0 +EDGE2 8501 3440 -0.984017 0.0385085 -1.5931 1 0 1 1 0 0 +EDGE2 8501 3480 -1.00412 -0.0683249 1.56451 1 0 1 1 0 0 +EDGE2 8501 3380 -0.969616 -0.0147728 1.54468 1 0 1 1 0 0 +EDGE2 8501 1200 -0.999375 -0.0432986 1.58077 1 0 1 1 0 0 +EDGE2 8501 3100 -0.964903 0.069776 1.56791 1 0 1 1 0 0 +EDGE2 8501 3120 -1.03143 0.0069348 1.55118 1 0 1 1 0 0 +EDGE2 8501 1180 -0.928737 -0.0230561 1.55676 1 0 1 1 0 0 +EDGE2 8501 900 -0.913894 -0.0101205 -1.58767 1 0 1 1 0 0 +EDGE2 8501 840 -1.01746 -0.00824292 -1.59275 1 0 1 1 0 0 +EDGE2 8501 860 -1.05324 -0.0472039 -1.57104 1 0 1 1 0 0 +EDGE2 8502 3423 0.912943 0.0166781 -0.00288224 1 0 1 1 0 0 +EDGE2 8502 3443 1.02535 -0.0333193 -0.020416 1 0 1 1 0 0 +EDGE2 8502 863 1.12248 0.0240349 0.0152584 1 0 1 1 0 0 +EDGE2 8502 903 0.948232 0.0700171 0.00627445 1 0 1 1 0 0 +EDGE2 8502 1203 0.990164 -0.0309881 -0.0200734 1 0 1 1 0 0 +EDGE2 8502 843 1.08916 -0.105577 -0.00625804 1 0 1 1 0 0 +EDGE2 8502 3441 -0.956057 -0.0745114 0.000488085 1 0 1 1 0 0 +EDGE2 8502 902 -0.0608422 -0.0035453 0.00345828 1 0 1 1 0 0 +EDGE2 8502 3422 -0.0231467 0.0352448 0.00467132 1 0 1 1 0 0 +EDGE2 8502 3442 0.0246441 -0.00883337 -0.0132868 1 0 1 1 0 0 +EDGE2 8502 1202 0.0239015 -0.025957 0.0054367 1 0 1 1 0 0 +EDGE2 8502 842 -0.0190078 0.0565875 -0.06036 1 0 1 1 0 0 +EDGE2 8502 862 -0.0271486 -0.025071 -0.0570664 1 0 1 1 0 0 +EDGE2 8502 8501 -0.935892 -0.00831486 -0.0229071 1 0 1 1 0 0 +EDGE2 8502 841 -1.06637 -0.00318684 -0.00629218 1 0 1 1 0 0 +EDGE2 8502 901 -1.07647 -0.0318056 -0.0383464 1 0 1 1 0 0 +EDGE2 8502 1201 -0.886989 0.0112371 0.00732986 1 0 1 1 0 0 +EDGE2 8502 3421 -0.944852 0.0578032 0.0137855 1 0 1 1 0 0 +EDGE2 8502 861 -1.02745 -0.0125013 0.00176137 1 0 1 1 0 0 +EDGE2 8503 864 0.97498 0.0397689 0.0139754 1 0 1 1 0 0 +EDGE2 8503 1204 0.983282 0.00199759 0.0125482 1 0 1 1 0 0 +EDGE2 8503 3424 0.954293 0.0360379 -0.00701794 1 0 1 1 0 0 +EDGE2 8503 3444 1.02276 -0.0596077 -0.00204846 1 0 1 1 0 0 +EDGE2 8503 904 0.99309 0.0125164 0.0183245 1 0 1 1 0 0 +EDGE2 8503 3423 -0.114687 0.13302 -0.000480513 1 0 1 1 0 0 +EDGE2 8503 844 0.946307 -0.00855892 0.0109829 1 0 1 1 0 0 +EDGE2 8503 3443 -0.00796959 0.0118149 -0.0428168 1 0 1 1 0 0 +EDGE2 8503 863 -0.0588801 -0.00440674 -0.0359242 1 0 1 1 0 0 +EDGE2 8503 903 0.00458252 0.0819566 0.0020675 1 0 1 1 0 0 +EDGE2 8503 1203 0.0515235 -0.0366809 0.0221059 1 0 1 1 0 0 +EDGE2 8503 843 -0.00820249 0.10794 0.0425374 1 0 1 1 0 0 +EDGE2 8503 902 -1.00664 0.104901 -0.0135498 1 0 1 1 0 0 +EDGE2 8503 3422 -1.07014 -0.0191966 -0.0286068 1 0 1 1 0 0 +EDGE2 8503 3442 -0.947526 -0.0477965 -0.0235161 1 0 1 1 0 0 +EDGE2 8503 8502 -0.89683 -0.00270211 0.0100733 1 0 1 1 0 0 +EDGE2 8503 1202 -1.01356 -0.0598953 -0.0111055 1 0 1 1 0 0 +EDGE2 8503 842 -0.964881 -0.0148063 0.014854 1 0 1 1 0 0 +EDGE2 8503 862 -1.05851 -0.0399257 0.0552662 1 0 1 1 0 0 +EDGE2 8504 865 1.03544 0.0819065 0.00555124 1 0 1 1 0 0 +EDGE2 8504 3225 0.986636 -0.0290619 -3.12009 1 0 1 1 0 0 +EDGE2 8504 3425 1.03974 0.018893 0.0301533 1 0 1 1 0 0 +EDGE2 8504 3445 1.03124 0.0476846 -0.00273969 1 0 1 1 0 0 +EDGE2 8504 3465 1.05529 -0.00281045 -3.10811 1 0 1 1 0 0 +EDGE2 8504 3365 1.04138 0.0862784 -3.10372 1 0 1 1 0 0 +EDGE2 8504 1205 0.969456 0.000917156 0.0170003 1 0 1 1 0 0 +EDGE2 8504 3205 1.0161 0.0642241 -3.11543 1 0 1 1 0 0 +EDGE2 8504 905 0.882107 -0.0252616 -0.0140009 1 0 1 1 0 0 +EDGE2 8504 864 0.0613024 -0.0361725 -0.00555773 1 0 1 1 0 0 +EDGE2 8504 705 1.06216 0.0727717 -3.14205 1 0 1 1 0 0 +EDGE2 8504 825 0.986534 0.0141879 -3.14536 1 0 1 1 0 0 +EDGE2 8504 845 0.982101 -0.0593817 0.0392839 1 0 1 1 0 0 +EDGE2 8504 1204 0.011775 -0.0885561 -0.0214946 1 0 1 1 0 0 +EDGE2 8504 3424 0.0289268 -0.0133285 -0.0111199 1 0 1 1 0 0 +EDGE2 8504 3444 -0.00988084 -0.0150992 0.0166364 1 0 1 1 0 0 +EDGE2 8504 904 -0.00197127 -0.0226021 0.0130296 1 0 1 1 0 0 +EDGE2 8504 3423 -0.947848 -0.0141052 0.0125008 1 0 1 1 0 0 +EDGE2 8504 8503 -0.997954 0.00713404 0.0177138 1 0 1 1 0 0 +EDGE2 8504 844 -0.0884272 -0.0673917 0.00396582 1 0 1 1 0 0 +EDGE2 8504 3443 -1.14625 -0.0630538 -0.0159048 1 0 1 1 0 0 +EDGE2 8504 863 -0.892734 0.045325 -0.0252243 1 0 1 1 0 0 +EDGE2 8504 903 -0.977541 -0.0512233 -0.0147662 1 0 1 1 0 0 +EDGE2 8504 1203 -0.937662 0.0294748 -0.0205147 1 0 1 1 0 0 +EDGE2 8504 843 -0.936431 -0.0514063 -0.0306279 1 0 1 1 0 0 +EDGE2 8505 3364 1.0448 -0.030201 -3.13653 1 0 1 1 0 0 +EDGE2 8505 3464 0.98301 0.018657 -3.17637 1 0 1 1 0 0 +EDGE2 8505 824 1.05667 -0.00669257 -3.13078 1 0 1 1 0 0 +EDGE2 8505 3204 0.99922 -0.00660691 -3.16219 1 0 1 1 0 0 +EDGE2 8505 3224 1.0356 -0.0439712 -3.17492 1 0 1 1 0 0 +EDGE2 8505 704 0.879629 -0.065612 -3.16726 1 0 1 1 0 0 +EDGE2 8505 865 0.0457543 -0.0345993 -0.0189705 1 0 1 1 0 0 +EDGE2 8505 3446 -0.000282495 1.00983 1.55403 1 0 1 1 0 0 +EDGE2 8505 3225 0.0322923 -0.0194631 -3.17903 1 0 1 1 0 0 +EDGE2 8505 826 0.0803868 0.984109 1.53737 1 0 1 1 0 0 +EDGE2 8505 866 0.0431314 1.01262 1.56842 1 0 1 1 0 0 +EDGE2 8505 906 0.0224522 1.0411 1.55869 1 0 1 1 0 0 +EDGE2 8505 3426 0.0818624 1.04651 1.54676 1 0 1 1 0 0 +EDGE2 8505 846 0.0220483 0.964413 1.54888 1 0 1 1 0 0 +EDGE2 8505 3425 0.0292751 -0.0952956 0.0138124 1 0 1 1 0 0 +EDGE2 8505 3445 0.00478747 0.00666019 0.00795038 1 0 1 1 0 0 +EDGE2 8505 3465 -0.0306774 -0.0506607 -3.13447 1 0 1 1 0 0 +EDGE2 8505 3365 -0.0674165 -0.0292805 -3.14171 1 0 1 1 0 0 +EDGE2 8505 1205 -0.0303649 0.0408569 -0.00375465 1 0 1 1 0 0 +EDGE2 8505 3205 -0.000877432 -0.00434317 -3.13951 1 0 1 1 0 0 +EDGE2 8505 905 0.0538482 0.0793261 0.0397373 1 0 1 1 0 0 +EDGE2 8505 864 -0.990735 0.0897173 -0.030891 1 0 1 1 0 0 +EDGE2 8505 8504 -0.962835 -0.0391402 -0.0197547 1 0 1 1 0 0 +EDGE2 8505 705 0.0345045 -0.0619823 -3.12931 1 0 1 1 0 0 +EDGE2 8505 825 -0.0599961 0.0218092 -3.13435 1 0 1 1 0 0 +EDGE2 8505 845 0.0101313 -0.00358385 0.0167822 1 0 1 1 0 0 +EDGE2 8505 1204 -0.976231 0.0235658 -0.00245758 1 0 1 1 0 0 +EDGE2 8505 3424 -1.13854 -0.0429804 -0.0219915 1 0 1 1 0 0 +EDGE2 8505 3444 -0.998654 0.0208114 -0.00141869 1 0 1 1 0 0 +EDGE2 8505 904 -0.98464 -0.0202215 -0.00208709 1 0 1 1 0 0 +EDGE2 8505 844 -0.932958 0.0143962 0.0258747 1 0 1 1 0 0 +EDGE2 8505 1206 -0.0102771 -1.03473 -1.55825 1 0 1 1 0 0 +EDGE2 8505 3226 0.0346601 -1.00941 -1.53338 1 0 1 1 0 0 +EDGE2 8505 3366 0.00155166 -0.903756 -1.57816 1 0 1 1 0 0 +EDGE2 8505 3466 -0.0240576 -0.933069 -1.57227 1 0 1 1 0 0 +EDGE2 8505 3206 0.0497161 -1.02934 -1.55841 1 0 1 1 0 0 +EDGE2 8505 706 -0.014685 -0.970546 -1.58825 1 0 1 1 0 0 +EDGE2 8506 8505 -0.982065 -9.01056e-05 1.55851 1 0 1 1 0 0 +EDGE2 8506 865 -0.990529 0.029271 1.5666 1 0 1 1 0 0 +EDGE2 8506 3225 -0.984996 -0.0415232 -1.54012 1 0 1 1 0 0 +EDGE2 8506 3425 -0.96176 -0.0554419 1.58153 1 0 1 1 0 0 +EDGE2 8506 3445 -1.05638 0.0259545 1.59656 1 0 1 1 0 0 +EDGE2 8506 3465 -1.01366 -0.00736928 -1.55364 1 0 1 1 0 0 +EDGE2 8506 3365 -1.04469 -0.0513688 -1.55254 1 0 1 1 0 0 +EDGE2 8506 1205 -1.0237 -0.0239682 1.57502 1 0 1 1 0 0 +EDGE2 8506 3205 -1.05923 0.0111951 -1.58116 1 0 1 1 0 0 +EDGE2 8506 905 -0.984165 -0.0743863 1.57411 1 0 1 1 0 0 +EDGE2 8506 705 -1.02639 0.122339 -1.58342 1 0 1 1 0 0 +EDGE2 8506 825 -0.999472 -0.00642937 -1.57158 1 0 1 1 0 0 +EDGE2 8506 845 -0.917807 -0.0289303 1.57035 1 0 1 1 0 0 +EDGE2 8506 3367 0.946137 0.0151894 0.030034 1 0 1 1 0 0 +EDGE2 8506 1206 0.026935 0.0302305 0.0375523 1 0 1 1 0 0 +EDGE2 8506 3226 0.000687988 0.0164873 0.000721934 1 0 1 1 0 0 +EDGE2 8506 3366 -0.00727948 0.0618444 0.00901196 1 0 1 1 0 0 +EDGE2 8506 3466 -0.0080424 -0.035484 -0.000793235 1 0 1 1 0 0 +EDGE2 8506 3206 -0.0116704 -0.0404779 0.0141202 1 0 1 1 0 0 +EDGE2 8506 706 -0.0153285 -0.0488307 -0.00295702 1 0 1 1 0 0 +EDGE2 8506 3467 1.00171 0.0184581 0.00858889 1 0 1 1 0 0 +EDGE2 8506 1207 1.02437 -0.00239317 -0.00111242 1 0 1 1 0 0 +EDGE2 8506 3207 1.0022 -0.0448977 0.000211931 1 0 1 1 0 0 +EDGE2 8506 3227 0.99559 -0.0454905 -0.0168172 1 0 1 1 0 0 +EDGE2 8506 707 1.08947 -0.0345899 0.0130204 1 0 1 1 0 0 +EDGE2 8507 8506 -0.938267 0.0157424 -0.0153841 1 0 1 1 0 0 +EDGE2 8507 3228 1.05785 -0.0726499 -0.00480648 1 0 1 1 0 0 +EDGE2 8507 3367 0.0274182 0.02929 0.016735 1 0 1 1 0 0 +EDGE2 8507 1206 -0.987587 0.00431223 0.0098038 1 0 1 1 0 0 +EDGE2 8507 3226 -1.00617 0.0821691 -0.0546365 1 0 1 1 0 0 +EDGE2 8507 3366 -0.984154 -0.028261 -0.0115561 1 0 1 1 0 0 +EDGE2 8507 3466 -0.931009 0.0489937 0.0224182 1 0 1 1 0 0 +EDGE2 8507 3206 -0.9363 -0.0277275 -0.00586785 1 0 1 1 0 0 +EDGE2 8507 706 -1.04993 -0.0152228 -0.00784218 1 0 1 1 0 0 +EDGE2 8507 3467 0.0452155 0.0456442 0.0225741 1 0 1 1 0 0 +EDGE2 8507 1207 0.0474495 0.0357111 -0.000978712 1 0 1 1 0 0 +EDGE2 8507 3207 -0.103593 0.0916186 -0.0322076 1 0 1 1 0 0 +EDGE2 8507 3227 -0.0352911 -0.0237273 -0.000447932 1 0 1 1 0 0 +EDGE2 8507 707 0.0214733 0.0122775 -0.0284281 1 0 1 1 0 0 +EDGE2 8507 3468 0.986068 0.0127272 0.00875951 1 0 1 1 0 0 +EDGE2 8507 3368 0.90837 -0.00534266 -0.0025973 1 0 1 1 0 0 +EDGE2 8507 708 1.04698 -0.0039047 0.00728074 1 0 1 1 0 0 +EDGE2 8507 1208 1.04252 -0.00377594 -0.0127916 1 0 1 1 0 0 +EDGE2 8507 3208 0.907183 0.00853424 0.0206982 1 0 1 1 0 0 +EDGE2 8508 8507 -0.980364 0.0331127 0.00663534 1 0 1 1 0 0 +EDGE2 8508 3228 -0.016425 -0.00488438 0.0174305 1 0 1 1 0 0 +EDGE2 8508 3367 -0.935347 0.0166121 -0.0151455 1 0 1 1 0 0 +EDGE2 8508 3467 -1.03426 -0.0163318 -0.017119 1 0 1 1 0 0 +EDGE2 8508 1207 -0.904075 0.0066681 0.0236847 1 0 1 1 0 0 +EDGE2 8508 3207 -1.01075 -0.068126 0.0119186 1 0 1 1 0 0 +EDGE2 8508 3227 -0.952339 -0.0421479 -0.0231871 1 0 1 1 0 0 +EDGE2 8508 707 -0.967739 -0.00363639 -0.00272226 1 0 1 1 0 0 +EDGE2 8508 3468 0.052628 -0.0402894 0.0461534 1 0 1 1 0 0 +EDGE2 8508 3368 -0.0305869 -0.0397433 -0.012156 1 0 1 1 0 0 +EDGE2 8508 3369 0.941285 -0.023056 0.032394 1 0 1 1 0 0 +EDGE2 8508 708 0.138966 0.0343023 0.0198573 1 0 1 1 0 0 +EDGE2 8508 1208 0.00519055 -0.132579 0.0380929 1 0 1 1 0 0 +EDGE2 8508 3208 0.0556467 -0.000115718 -0.0200506 1 0 1 1 0 0 +EDGE2 8508 3469 1.05785 0.0392844 0.00590299 1 0 1 1 0 0 +EDGE2 8508 1209 1.03167 -0.100653 0.00221553 1 0 1 1 0 0 +EDGE2 8508 3209 1.03142 0.106966 0.0185235 1 0 1 1 0 0 +EDGE2 8508 3229 0.94924 0.0582726 -0.0130225 1 0 1 1 0 0 +EDGE2 8508 709 0.89527 -0.0893312 0.000912034 1 0 1 1 0 0 +EDGE2 8509 8508 -0.979137 0.102292 0.032305 1 0 1 1 0 0 +EDGE2 8509 3228 -1.00972 0.0253734 0.000786058 1 0 1 1 0 0 +EDGE2 8509 3468 -0.985453 -0.0672655 0.0133747 1 0 1 1 0 0 +EDGE2 8509 3368 -1.01872 -0.0892647 0.0258356 1 0 1 1 0 0 +EDGE2 8509 3370 0.983011 -0.0190037 0.0244904 1 0 1 1 0 0 +EDGE2 8509 3470 0.898691 0.0831518 -0.0131519 1 0 1 1 0 0 +EDGE2 8509 3369 0.0103819 0.0848044 -0.00152307 1 0 1 1 0 0 +EDGE2 8509 708 -0.927042 -0.00217475 -0.00834817 1 0 1 1 0 0 +EDGE2 8509 1208 -1.05523 0.0720176 -0.00817594 1 0 1 1 0 0 +EDGE2 8509 3208 -1.07779 -0.00971095 0.0511016 1 0 1 1 0 0 +EDGE2 8509 3469 0.0460568 0.102868 0.00559125 1 0 1 1 0 0 +EDGE2 8509 1209 0.0656351 -0.0148884 -0.0046962 1 0 1 1 0 0 +EDGE2 8509 3209 0.138512 0.0508371 -0.0300448 1 0 1 1 0 0 +EDGE2 8509 3229 0.029886 0.0302163 -0.0226739 1 0 1 1 0 0 +EDGE2 8509 709 0.0929008 -0.018977 -0.0149437 1 0 1 1 0 0 +EDGE2 8509 730 1.02231 0.0162832 -3.13726 1 0 1 1 0 0 +EDGE2 8509 3190 0.946126 0.0186829 -3.17909 1 0 1 1 0 0 +EDGE2 8509 3210 1.0653 0.00756607 0.0046327 1 0 1 1 0 0 +EDGE2 8509 3230 1.01504 0.0115735 0.00075374 1 0 1 1 0 0 +EDGE2 8509 1210 1.05233 0.011499 0.0270718 1 0 1 1 0 0 +EDGE2 8509 710 1.08396 -0.0633161 0.0352492 1 0 1 1 0 0 +EDGE2 8510 8509 -0.937537 0.00603641 -0.0118067 1 0 1 1 0 0 +EDGE2 8510 1211 0.0532215 1.04418 1.56352 1 0 1 1 0 0 +EDGE2 8510 3211 -0.0573716 1.00705 1.56439 1 0 1 1 0 0 +EDGE2 8510 3231 0.011434 1.04967 1.59882 1 0 1 1 0 0 +EDGE2 8510 3191 -0.0273999 0.987885 1.57 1 0 1 1 0 0 +EDGE2 8510 711 -0.0218824 0.984713 1.55826 1 0 1 1 0 0 +EDGE2 8510 731 0.0827873 1.1009 1.56795 1 0 1 1 0 0 +EDGE2 8510 3370 -0.039049 0.0533181 0.00490648 1 0 1 1 0 0 +EDGE2 8510 3470 -0.0420375 -0.112981 -0.02267 1 0 1 1 0 0 +EDGE2 8510 3369 -1.11649 0.0640435 -0.0260092 1 0 1 1 0 0 +EDGE2 8510 3469 -0.995318 0.0125151 -0.00258656 1 0 1 1 0 0 +EDGE2 8510 1209 -1.00512 0.0192403 0.0106631 1 0 1 1 0 0 +EDGE2 8510 3209 -1.02534 0.00250195 0.00724972 1 0 1 1 0 0 +EDGE2 8510 3229 -0.979122 -0.0193517 -0.0311299 1 0 1 1 0 0 +EDGE2 8510 709 -1.0308 -0.0292625 -0.019765 1 0 1 1 0 0 +EDGE2 8510 730 0.10852 -0.0128877 -3.12778 1 0 1 1 0 0 +EDGE2 8510 3190 -0.0219572 0.00574092 -3.14993 1 0 1 1 0 0 +EDGE2 8510 3210 -0.0744554 0.0277734 0.0122644 1 0 1 1 0 0 +EDGE2 8510 3230 0.0645069 -0.0187104 -0.0411692 1 0 1 1 0 0 +EDGE2 8510 1210 0.0496362 0.0542729 0.00899549 1 0 1 1 0 0 +EDGE2 8510 3471 -0.118288 -1.03692 -1.57178 1 0 1 1 0 0 +EDGE2 8510 710 0.0401532 0.0872117 0.00253861 1 0 1 1 0 0 +EDGE2 8510 3371 -0.0345859 -1.09344 -1.5965 1 0 1 1 0 0 +EDGE2 8510 3189 0.957044 0.00883248 -3.14059 1 0 1 1 0 0 +EDGE2 8510 729 0.951169 0.0117877 -3.14859 1 0 1 1 0 0 +EDGE2 8511 8510 -0.980291 0.0621561 1.5752 1 0 1 1 0 0 +EDGE2 8511 3370 -1.01847 -0.0773079 1.58977 1 0 1 1 0 0 +EDGE2 8511 3470 -1.04006 -0.0280619 1.55225 1 0 1 1 0 0 +EDGE2 8511 730 -1.02024 0.0227693 -1.56983 1 0 1 1 0 0 +EDGE2 8511 3190 -0.946005 0.0840486 -1.5956 1 0 1 1 0 0 +EDGE2 8511 3210 -1.00664 -0.0576957 1.54477 1 0 1 1 0 0 +EDGE2 8511 3230 -0.995817 -0.112223 1.50152 1 0 1 1 0 0 +EDGE2 8511 1210 -0.994118 -0.041653 1.54948 1 0 1 1 0 0 +EDGE2 8511 3471 -0.0768089 -0.0360835 0.00739213 1 0 1 1 0 0 +EDGE2 8511 710 -0.933487 -0.0763536 1.55232 1 0 1 1 0 0 +EDGE2 8511 3371 -0.00124891 0.0390563 -0.0394423 1 0 1 1 0 0 +EDGE2 8511 3372 0.99324 0.0277395 -0.000554328 1 0 1 1 0 0 +EDGE2 8511 3472 1.00709 -0.0397864 -0.0149299 1 0 1 1 0 0 +EDGE2 8512 3471 -0.916037 0.0730819 -0.00832384 1 0 1 1 0 0 +EDGE2 8512 8511 -1.04596 -0.0199602 0.0187642 1 0 1 1 0 0 +EDGE2 8512 3371 -1.03467 0.109265 -0.00885873 1 0 1 1 0 0 +EDGE2 8512 3373 0.955998 -0.0380809 0.0344996 1 0 1 1 0 0 +EDGE2 8512 3372 0.103107 -0.0533613 0.0183869 1 0 1 1 0 0 +EDGE2 8512 3472 0.0593316 0.0310199 0.0115612 1 0 1 1 0 0 +EDGE2 8512 3473 1.05938 0.0449346 0.00251057 1 0 1 1 0 0 +EDGE2 8513 8512 -0.911497 -0.0200648 -0.0146571 1 0 1 1 0 0 +EDGE2 8513 3373 -0.0331087 0.0403428 0.00461183 1 0 1 1 0 0 +EDGE2 8513 3372 -0.957474 -0.0144111 0.0115914 1 0 1 1 0 0 +EDGE2 8513 3472 -1.05493 -0.0926595 -0.00979744 1 0 1 1 0 0 +EDGE2 8513 3473 -0.0482674 0.0126039 0.000844387 1 0 1 1 0 0 +EDGE2 8513 3474 1.02764 0.0317511 -0.0201157 1 0 1 1 0 0 +EDGE2 8513 3374 1.02937 -0.10453 -0.00449748 1 0 1 1 0 0 +EDGE2 8514 3495 1.03824 0.0225453 -3.13219 1 0 1 1 0 0 +EDGE2 8514 3373 -1.06182 -0.00252959 -0.0124619 1 0 1 1 0 0 +EDGE2 8514 8513 -1.12405 0.00257588 0.00129244 1 0 1 1 0 0 +EDGE2 8514 3473 -1.02461 0.0490836 -0.0349156 1 0 1 1 0 0 +EDGE2 8514 3474 -0.0760933 0.0831601 0.0093874 1 0 1 1 0 0 +EDGE2 8514 3374 0.0287561 -0.0294075 0.00691905 1 0 1 1 0 0 +EDGE2 8514 5835 1.0625 0.0265477 -3.16621 1 0 1 1 0 0 +EDGE2 8514 8495 0.962642 0.045109 -3.12196 1 0 1 1 0 0 +EDGE2 8514 5815 0.968693 -0.0639798 -3.1346 1 0 1 1 0 0 +EDGE2 8514 3115 1.00448 0.0128011 -3.13212 1 0 1 1 0 0 +EDGE2 8514 3175 1.05627 0.0432495 -3.11371 1 0 1 1 0 0 +EDGE2 8514 3375 0.950072 0.0487133 0.0114111 1 0 1 1 0 0 +EDGE2 8514 3475 1.01095 -0.0367319 -0.0300892 1 0 1 1 0 0 +EDGE2 8514 3135 1.07191 0.0382543 -3.15056 1 0 1 1 0 0 +EDGE2 8514 1175 1.02746 -0.0635775 -3.17427 1 0 1 1 0 0 +EDGE2 8514 1195 1.08175 -0.0499283 -3.13594 1 0 1 1 0 0 +EDGE2 8514 3095 0.968863 -0.0476347 -3.11617 1 0 1 1 0 0 +EDGE2 8514 1155 0.923453 -0.00176399 -3.11283 1 0 1 1 0 0 +EDGE2 8515 3495 0.0390567 0.00877213 -3.13084 1 0 1 1 0 0 +EDGE2 8515 3474 -0.975635 0.0121123 0.00547353 1 0 1 1 0 0 +EDGE2 8515 8514 -0.986177 0.0314105 -0.0345065 1 0 1 1 0 0 +EDGE2 8515 3374 -0.999593 0.0246753 -0.00995414 1 0 1 1 0 0 +EDGE2 8515 1196 -0.00581462 -1.1346 -1.56797 1 0 1 1 0 0 +EDGE2 8515 3476 -0.0202906 -1.0238 -1.57861 1 0 1 1 0 0 +EDGE2 8515 5836 0.0341585 -0.905392 -1.5414 1 0 1 1 0 0 +EDGE2 8515 8496 0.0126281 -1.01558 -1.56108 1 0 1 1 0 0 +EDGE2 8515 5816 0.0144288 -1.00857 -1.56824 1 0 1 1 0 0 +EDGE2 8515 3116 -0.022688 -0.975203 -1.58061 1 0 1 1 0 0 +EDGE2 8515 3136 -0.00812552 -1.06119 -1.52301 1 0 1 1 0 0 +EDGE2 8515 3376 0.0219679 -0.972887 -1.60401 1 0 1 1 0 0 +EDGE2 8515 3096 -0.00307245 -0.928658 -1.55548 1 0 1 1 0 0 +EDGE2 8515 1156 -0.0410711 -0.892241 -1.56982 1 0 1 1 0 0 +EDGE2 8515 1176 0.00847714 -0.992026 -1.57902 1 0 1 1 0 0 +EDGE2 8515 5835 -0.135 0.00270832 -3.13458 1 0 1 1 0 0 +EDGE2 8515 8495 -0.0178166 -0.00362484 -3.11386 1 0 1 1 0 0 +EDGE2 8515 5815 0.00582803 -0.0241117 -3.13762 1 0 1 1 0 0 +EDGE2 8515 1174 0.98781 -0.028884 -3.17913 1 0 1 1 0 0 +EDGE2 8515 3115 -0.0583876 -0.0608003 -3.12985 1 0 1 1 0 0 +EDGE2 8515 3175 -0.00977486 0.0445967 -3.12682 1 0 1 1 0 0 +EDGE2 8515 3375 0.0163816 0.0230193 -0.00726573 1 0 1 1 0 0 +EDGE2 8515 3475 0.0766543 0.0690102 -0.00932766 1 0 1 1 0 0 +EDGE2 8515 3135 -0.0511985 0.0221243 -3.12589 1 0 1 1 0 0 +EDGE2 8515 1175 0.00630034 -0.117974 -3.16117 1 0 1 1 0 0 +EDGE2 8515 1195 -0.0313219 -0.0213561 -3.15947 1 0 1 1 0 0 +EDGE2 8515 3095 -0.0671846 0.0234496 -3.16089 1 0 1 1 0 0 +EDGE2 8515 1155 0.0526773 0.0592449 -3.16211 1 0 1 1 0 0 +EDGE2 8515 3174 0.934366 0.0216774 -3.1278 1 0 1 1 0 0 +EDGE2 8515 5814 0.916373 -0.0392769 -3.12423 1 0 1 1 0 0 +EDGE2 8515 5834 0.969593 0.0124548 -3.16184 1 0 1 1 0 0 +EDGE2 8515 8494 0.950696 0.0780058 -3.13819 1 0 1 1 0 0 +EDGE2 8515 3494 1.00133 -0.129496 -3.13399 1 0 1 1 0 0 +EDGE2 8515 3094 1.00291 0.00777003 -3.14948 1 0 1 1 0 0 +EDGE2 8515 3114 0.995037 -0.00859454 -3.14786 1 0 1 1 0 0 +EDGE2 8515 3134 0.935614 0.0809567 -3.15645 1 0 1 1 0 0 +EDGE2 8515 1194 0.96148 -0.00981013 -3.15528 1 0 1 1 0 0 +EDGE2 8515 1154 0.914297 -0.0528652 -3.17595 1 0 1 1 0 0 +EDGE2 8515 3176 -0.0529295 0.955559 1.55574 1 0 1 1 0 0 +EDGE2 8515 3496 0.0335407 1.14722 1.59681 1 0 1 1 0 0 +EDGE2 8516 3495 -1.02394 0.0171448 1.55686 1 0 1 1 0 0 +EDGE2 8516 5835 -0.893459 -0.0358612 1.54885 1 0 1 1 0 0 +EDGE2 8516 8495 -1.00208 -0.0337422 1.57836 1 0 1 1 0 0 +EDGE2 8516 8515 -1.00226 -0.0403521 -1.56568 1 0 1 1 0 0 +EDGE2 8516 5815 -1.02996 0.020884 1.55375 1 0 1 1 0 0 +EDGE2 8516 3115 -0.963989 -0.01494 1.52039 1 0 1 1 0 0 +EDGE2 8516 3175 -0.975142 0.0397824 1.56274 1 0 1 1 0 0 +EDGE2 8516 3375 -1.01242 -0.0816319 -1.5882 1 0 1 1 0 0 +EDGE2 8516 3475 -1.02193 -0.0405188 -1.53631 1 0 1 1 0 0 +EDGE2 8516 3135 -1.02138 0.0676763 1.5555 1 0 1 1 0 0 +EDGE2 8516 1175 -1.04087 -0.0374348 1.59359 1 0 1 1 0 0 +EDGE2 8516 1195 -0.929504 0.0322871 1.57607 1 0 1 1 0 0 +EDGE2 8516 3095 -1.04392 -0.000437522 1.59725 1 0 1 1 0 0 +EDGE2 8516 1155 -1.02854 0.00174778 1.58051 1 0 1 1 0 0 +EDGE2 8516 3176 -0.0856847 0.110643 -0.0122844 1 0 1 1 0 0 +EDGE2 8516 3496 -0.0147519 0.135737 -0.0288334 1 0 1 1 0 0 +EDGE2 8516 3177 0.930424 -0.0472092 0.0104396 1 0 1 1 0 0 +EDGE2 8516 3497 0.967497 -0.0222188 -0.00536584 1 0 1 1 0 0 +EDGE2 8517 8516 -1.02383 -0.0298356 -0.00717714 1 0 1 1 0 0 +EDGE2 8517 3176 -1.00981 0.0403432 0.0151677 1 0 1 1 0 0 +EDGE2 8517 3496 -0.976532 -0.0162143 0.0279247 1 0 1 1 0 0 +EDGE2 8517 3178 0.936833 0.0208609 -0.0215487 1 0 1 1 0 0 +EDGE2 8517 3177 0.0636223 0.0101745 -0.0117496 1 0 1 1 0 0 +EDGE2 8517 3497 -0.0285089 -0.0108876 0.0335272 1 0 1 1 0 0 +EDGE2 8517 3498 1.03584 0.0504318 -0.0225566 1 0 1 1 0 0 +EDGE2 8518 8517 -1.05345 0.0448725 0.000719939 1 0 1 1 0 0 +EDGE2 8518 3178 -0.0161455 -0.0265319 0.0170294 1 0 1 1 0 0 +EDGE2 8518 3177 -1.08615 -0.108394 0.0169996 1 0 1 1 0 0 +EDGE2 8518 3497 -0.970399 0.0646501 -0.0500088 1 0 1 1 0 0 +EDGE2 8518 3498 -0.0686672 -0.0133926 0.0244506 1 0 1 1 0 0 +EDGE2 8518 3179 1.04395 0.0156433 0.00807514 1 0 1 1 0 0 +EDGE2 8518 3499 0.939016 -0.0587397 -0.00771164 1 0 1 1 0 0 +EDGE2 8519 3178 -1.06959 0.0863894 0.0115342 1 0 1 1 0 0 +EDGE2 8519 8518 -1.06019 -0.0455429 0.00744189 1 0 1 1 0 0 +EDGE2 8519 3498 -1.05135 0.00915382 0.0443552 1 0 1 1 0 0 +EDGE2 8519 3179 -0.0472768 0.0544561 -0.0142348 1 0 1 1 0 0 +EDGE2 8519 3499 0.0493071 -0.0133252 -0.00858555 1 0 1 1 0 0 +EDGE2 8519 3020 0.984113 0.0404522 -3.10934 1 0 1 1 0 0 +EDGE2 8519 3180 1.03173 0.0166219 0.00596885 1 0 1 1 0 0 +EDGE2 8519 3500 0.971098 -0.0135819 -0.0145183 1 0 1 1 0 0 +EDGE2 8520 3179 -1.02631 -0.0735458 -0.00666285 1 0 1 1 0 0 +EDGE2 8520 3499 -0.98433 0.113355 0.0223184 1 0 1 1 0 0 +EDGE2 8520 8519 -0.958214 -0.0149443 0.00182963 1 0 1 1 0 0 +EDGE2 8520 3181 -0.047898 1.00683 1.57061 1 0 1 1 0 0 +EDGE2 8520 3501 -0.0588275 -1.06939 -1.59305 1 0 1 1 0 0 +EDGE2 8520 3020 0.0204179 -0.00339043 -3.12837 1 0 1 1 0 0 +EDGE2 8520 3180 -0.0218847 -0.0411227 0.025619 1 0 1 1 0 0 +EDGE2 8520 3500 0.00231523 -0.102992 -0.0173279 1 0 1 1 0 0 +EDGE2 8520 3021 -0.0956044 -0.976044 -1.5679 1 0 1 1 0 0 +EDGE2 8520 3019 0.988299 -0.107637 -3.15854 1 0 1 1 0 0 +EDGE2 8521 8520 -1.02501 -0.00850143 -1.59482 1 0 1 1 0 0 +EDGE2 8521 3181 0.0115886 0.0436986 -0.00609878 1 0 1 1 0 0 +EDGE2 8521 3182 0.972 0.13496 0.00882208 1 0 1 1 0 0 +EDGE2 8521 3020 -0.998043 0.000198478 1.57138 1 0 1 1 0 0 +EDGE2 8521 3180 -0.968982 0.0446548 -1.55592 1 0 1 1 0 0 +EDGE2 8521 3500 -1.11928 -0.0145555 -1.60787 1 0 1 1 0 0 +EDGE2 8522 3181 -1.08622 -0.00153344 -0.00807366 1 0 1 1 0 0 +EDGE2 8522 3182 0.0344572 0.110593 0.00216546 1 0 1 1 0 0 +EDGE2 8522 3183 1.03827 0.0322981 -0.0318564 1 0 1 1 0 0 +EDGE2 8522 8521 -1.05881 -0.0685162 -0.0158432 1 0 1 1 0 0 +EDGE2 8523 3184 0.996013 0.064333 -0.00948874 1 0 1 1 0 0 +EDGE2 8523 3182 -1.06048 -0.00973169 0.00357517 1 0 1 1 0 0 +EDGE2 8523 8522 -0.932635 0.000622563 0.0213902 1 0 1 1 0 0 +EDGE2 8523 3183 0.00443844 0.103198 -0.00518324 1 0 1 1 0 0 +EDGE2 8524 8523 -1.03266 0.0501444 -0.0105607 1 0 1 1 0 0 +EDGE2 8524 3285 0.978624 -0.0356376 -3.16244 1 0 1 1 0 0 +EDGE2 8524 3005 1.00252 -0.0356597 -3.11032 1 0 1 1 0 0 +EDGE2 8524 3185 1.03877 -0.0205882 -0.00960591 1 0 1 1 0 0 +EDGE2 8524 3265 1.04754 0.0260604 -3.13262 1 0 1 1 0 0 +EDGE2 8524 725 1.01612 0.0395723 -3.11654 1 0 1 1 0 0 +EDGE2 8524 3184 0.0169825 -0.000114435 0.0275827 1 0 1 1 0 0 +EDGE2 8524 3183 -1.01695 0.0196844 0.00708095 1 0 1 1 0 0 +EDGE2 8525 3004 0.991169 -0.0328255 -3.10257 1 0 1 1 0 0 +EDGE2 8525 3284 1.04577 -0.0773959 -3.13619 1 0 1 1 0 0 +EDGE2 8525 3264 0.989564 0.0379992 -3.15581 1 0 1 1 0 0 +EDGE2 8525 724 0.931439 0.00846815 -3.11149 1 0 1 1 0 0 +EDGE2 8525 8524 -0.992139 -0.0147651 -0.0176939 1 0 1 1 0 0 +EDGE2 8525 3285 -0.0213766 -0.105451 -3.14405 1 0 1 1 0 0 +EDGE2 8525 3186 -0.0211909 0.980087 1.54598 1 0 1 1 0 0 +EDGE2 8525 726 0.0616181 0.982667 1.54924 1 0 1 1 0 0 +EDGE2 8525 3005 -0.0534312 0.0836252 -3.10544 1 0 1 1 0 0 +EDGE2 8525 3185 -0.0308241 -0.00902947 0.0182105 1 0 1 1 0 0 +EDGE2 8525 3265 0.0127567 0.0541845 -3.10987 1 0 1 1 0 0 +EDGE2 8525 725 -0.0379224 0.0588236 -3.11607 1 0 1 1 0 0 +EDGE2 8525 3184 -0.959824 -0.0464469 -0.00439243 1 0 1 1 0 0 +EDGE2 8525 3266 -0.0457079 -0.95449 -1.55419 1 0 1 1 0 0 +EDGE2 8525 3286 -0.0766602 -0.953707 -1.61842 1 0 1 1 0 0 +EDGE2 8525 3006 -0.0249645 -1.02138 -1.58694 1 0 1 1 0 0 +EDGE2 8526 8525 -0.975316 -0.0229759 1.59487 1 0 1 1 0 0 +EDGE2 8526 3285 -1.02127 0.0706955 -1.59623 1 0 1 1 0 0 +EDGE2 8526 3005 -0.971086 0.0932303 -1.59567 1 0 1 1 0 0 +EDGE2 8526 3185 -1.03975 0.0228088 1.58483 1 0 1 1 0 0 +EDGE2 8526 3265 -0.955503 -0.0771157 -1.54523 1 0 1 1 0 0 +EDGE2 8526 725 -0.949205 0.0777363 -1.57708 1 0 1 1 0 0 +EDGE2 8526 3266 0.0584789 0.00782398 -0.014651 1 0 1 1 0 0 +EDGE2 8526 3286 0.0965891 0.0117157 0.0216743 1 0 1 1 0 0 +EDGE2 8526 3006 0.066127 0.0138455 0.0189914 1 0 1 1 0 0 +EDGE2 8526 3007 0.97193 -0.000192402 -0.00760616 1 0 1 1 0 0 +EDGE2 8526 3267 0.94855 0.0549355 -0.0164138 1 0 1 1 0 0 +EDGE2 8526 3287 1.03217 -0.0279811 -0.0104773 1 0 1 1 0 0 +EDGE2 8527 8526 -1.0357 -0.00569691 -0.00216795 1 0 1 1 0 0 +EDGE2 8527 3266 -1.03509 -0.028281 -0.000165935 1 0 1 1 0 0 +EDGE2 8527 3286 -0.9353 -0.108393 -0.0187923 1 0 1 1 0 0 +EDGE2 8527 3006 -0.964125 0.0522842 0.00588677 1 0 1 1 0 0 +EDGE2 8527 3268 0.856754 -0.0730407 -0.0236968 1 0 1 1 0 0 +EDGE2 8527 3007 0.00130769 -0.0827327 -0.0191763 1 0 1 1 0 0 +EDGE2 8527 3267 0.0400187 -0.0390148 -0.0225189 1 0 1 1 0 0 +EDGE2 8527 3287 0.129364 0.000455304 -0.0084101 1 0 1 1 0 0 +EDGE2 8527 3288 0.932476 0.0119236 0.0525536 1 0 1 1 0 0 +EDGE2 8527 3008 0.909784 -0.0105004 -0.0567453 1 0 1 1 0 0 +EDGE2 8528 8527 -0.98628 0.00795341 0.0356536 1 0 1 1 0 0 +EDGE2 8528 3268 0.115348 -0.0521918 0.0121826 1 0 1 1 0 0 +EDGE2 8528 3007 -0.978661 -0.0901366 0.0187756 1 0 1 1 0 0 +EDGE2 8528 3267 -0.947377 -0.0403743 -0.0144917 1 0 1 1 0 0 +EDGE2 8528 3287 -1.00459 -0.0218151 0.00197005 1 0 1 1 0 0 +EDGE2 8528 3288 -0.0984608 -0.0811962 0.0105122 1 0 1 1 0 0 +EDGE2 8528 3269 1.01873 0.032554 -0.0270322 1 0 1 1 0 0 +EDGE2 8528 3289 1.02159 -0.0488154 -0.0119348 1 0 1 1 0 0 +EDGE2 8528 3008 0.0716595 0.00762234 -0.0129319 1 0 1 1 0 0 +EDGE2 8528 3009 0.961154 0.0262243 0.00632913 1 0 1 1 0 0 +EDGE2 8529 8528 -1.06983 -0.0764428 -0.0461746 1 0 1 1 0 0 +EDGE2 8529 5450 0.990913 0.02177 -3.14248 1 0 1 1 0 0 +EDGE2 8529 3290 1.04504 0.0512202 -0.0109784 1 0 1 1 0 0 +EDGE2 8529 3268 -0.969627 -0.00256519 0.0144649 1 0 1 1 0 0 +EDGE2 8529 3288 -1.01963 -0.0100831 0.0183458 1 0 1 1 0 0 +EDGE2 8529 3269 0.127243 0.052291 0.0162587 1 0 1 1 0 0 +EDGE2 8529 3289 0.037662 0.0667486 0.00399278 1 0 1 1 0 0 +EDGE2 8529 3008 -0.984156 0.0284648 -0.0224753 1 0 1 1 0 0 +EDGE2 8529 3009 -0.153896 -0.00368401 -0.0443517 1 0 1 1 0 0 +EDGE2 8529 2970 1.05859 -0.0529406 -3.15227 1 0 1 1 0 0 +EDGE2 8529 3270 1.06189 0.00192075 0.00944407 1 0 1 1 0 0 +EDGE2 8529 3010 1.02853 -0.0369169 -0.00375513 1 0 1 1 0 0 +EDGE2 8529 2710 0.991989 0.0655163 -3.12355 1 0 1 1 0 0 +EDGE2 8530 8529 -0.981853 0.0195701 0.0295633 1 0 1 1 0 0 +EDGE2 8530 3271 0.0267745 1.05171 1.56891 1 0 1 1 0 0 +EDGE2 8530 3291 -0.0228672 0.987142 1.56712 1 0 1 1 0 0 +EDGE2 8530 5450 -0.108135 -0.0243316 -3.12738 1 0 1 1 0 0 +EDGE2 8530 2971 0.0362831 1.08253 1.54309 1 0 1 1 0 0 +EDGE2 8530 5449 0.903374 -0.0631967 -3.14975 1 0 1 1 0 0 +EDGE2 8530 2711 -0.145547 -0.943629 -1.57665 1 0 1 1 0 0 +EDGE2 8530 3290 -0.0417284 -0.133089 -0.0507563 1 0 1 1 0 0 +EDGE2 8530 3269 -0.973687 -0.0639943 -0.016575 1 0 1 1 0 0 +EDGE2 8530 3289 -0.945552 -0.0331737 0.0149069 1 0 1 1 0 0 +EDGE2 8530 3009 -1.0642 -0.0575725 0.0308193 1 0 1 1 0 0 +EDGE2 8530 2970 -0.0675339 0.0660472 -3.15636 1 0 1 1 0 0 +EDGE2 8530 3270 -0.0208791 -0.0253559 -0.0128292 1 0 1 1 0 0 +EDGE2 8530 3010 -0.0657296 -0.0231863 0.0146214 1 0 1 1 0 0 +EDGE2 8530 5451 -0.0562392 -1.07931 -1.59375 1 0 1 1 0 0 +EDGE2 8530 2710 -0.0465929 -0.0144222 -3.14709 1 0 1 1 0 0 +EDGE2 8530 3011 0.00783044 -0.932468 -1.5478 1 0 1 1 0 0 +EDGE2 8530 2969 1.07394 -0.0476905 -3.12379 1 0 1 1 0 0 +EDGE2 8530 2709 1.03632 -0.0124447 -3.13184 1 0 1 1 0 0 +EDGE2 8531 5450 -0.952922 -0.0373509 -1.55442 1 0 1 1 0 0 +EDGE2 8531 8530 -1.03304 0.0411109 1.57685 1 0 1 1 0 0 +EDGE2 8531 2711 -0.0226425 0.0601158 -0.00346169 1 0 1 1 0 0 +EDGE2 8531 3290 -1.09157 0.0648836 1.55832 1 0 1 1 0 0 +EDGE2 8531 2970 -1.03778 -0.0172327 -1.59325 1 0 1 1 0 0 +EDGE2 8531 3270 -0.91165 0.0793603 1.54922 1 0 1 1 0 0 +EDGE2 8531 3010 -0.973312 0.0878863 1.5522 1 0 1 1 0 0 +EDGE2 8531 5451 -0.0365305 -0.0112913 -0.0120996 1 0 1 1 0 0 +EDGE2 8531 2710 -0.966254 0.0636101 -1.5796 1 0 1 1 0 0 +EDGE2 8531 3011 -0.036311 -0.0557312 -0.043301 1 0 1 1 0 0 +EDGE2 8531 3012 1.05355 0.0318191 0.0248755 1 0 1 1 0 0 +EDGE2 8531 5452 0.988199 0.0168665 -0.0312344 1 0 1 1 0 0 +EDGE2 8531 2712 0.965092 -0.00144676 -0.0522336 1 0 1 1 0 0 +EDGE2 8532 2711 -0.96014 -0.0424308 -0.0225958 1 0 1 1 0 0 +EDGE2 8532 5451 -1.05621 -0.0524769 0.0110673 1 0 1 1 0 0 +EDGE2 8532 8531 -1.0271 0.0697051 -0.00405238 1 0 1 1 0 0 +EDGE2 8532 3011 -1.00066 0.0402146 0.00923634 1 0 1 1 0 0 +EDGE2 8532 3012 0.00309138 -0.00653202 -0.0240798 1 0 1 1 0 0 +EDGE2 8532 5452 0.00473406 -0.00814874 0.00788363 1 0 1 1 0 0 +EDGE2 8532 2713 1.02776 -0.0101435 0.0152889 1 0 1 1 0 0 +EDGE2 8532 5453 1.04006 0.0125345 0.00638349 1 0 1 1 0 0 +EDGE2 8532 2712 -0.00169695 0.0516848 0.0141828 1 0 1 1 0 0 +EDGE2 8532 3013 1.02593 -0.0154095 0.024707 1 0 1 1 0 0 +EDGE2 8533 3012 -1.05675 0.0167478 0.0077111 1 0 1 1 0 0 +EDGE2 8533 5452 -1.01248 -0.0441799 -0.00683266 1 0 1 1 0 0 +EDGE2 8533 8532 -0.993244 0.0829904 0.018952 1 0 1 1 0 0 +EDGE2 8533 2713 -0.0405701 0.00317798 0.010579 1 0 1 1 0 0 +EDGE2 8533 5453 -0.030224 0.0322113 0.00506499 1 0 1 1 0 0 +EDGE2 8533 2712 -0.993426 -0.0307197 -0.00134895 1 0 1 1 0 0 +EDGE2 8533 3013 -0.0132607 -0.0261757 -0.0172556 1 0 1 1 0 0 +EDGE2 8533 3014 0.997928 0.0226017 0.00139552 1 0 1 1 0 0 +EDGE2 8533 5454 0.98801 -0.0784564 0.0300172 1 0 1 1 0 0 +EDGE2 8533 2714 1.09558 0.0130417 0.0100382 1 0 1 1 0 0 +EDGE2 8534 2713 -1.04763 0.0491774 -0.000850131 1 0 1 1 0 0 +EDGE2 8534 5453 -1.06599 -0.0267482 -0.00316499 1 0 1 1 0 0 +EDGE2 8534 8533 -1.04262 0.13162 0.0387707 1 0 1 1 0 0 +EDGE2 8534 3013 -0.950627 0.0601427 -0.0226663 1 0 1 1 0 0 +EDGE2 8534 3014 0.0583555 0.0444775 0.0128442 1 0 1 1 0 0 +EDGE2 8534 5454 -0.0304437 -0.0476054 0.0142136 1 0 1 1 0 0 +EDGE2 8534 2714 0.02716 -0.0207394 0.0109166 1 0 1 1 0 0 +EDGE2 8534 5455 1.05439 0.0346151 0.0157566 1 0 1 1 0 0 +EDGE2 8534 2715 0.983192 -0.0557759 0.0336659 1 0 1 1 0 0 +EDGE2 8534 3015 0.998512 0.0376078 -0.00620308 1 0 1 1 0 0 +EDGE2 8534 3515 0.906672 0.0182183 -3.13532 1 0 1 1 0 0 +EDGE2 8535 3014 -0.958573 0.0754999 0.0374905 1 0 1 1 0 0 +EDGE2 8535 5454 -0.958711 0.0605138 0.0287286 1 0 1 1 0 0 +EDGE2 8535 8534 -1.01557 -0.00725027 -0.017222 1 0 1 1 0 0 +EDGE2 8535 2714 -1.06346 0.0126474 -0.0305546 1 0 1 1 0 0 +EDGE2 8535 3516 0.00697512 1.00997 1.59054 1 0 1 1 0 0 +EDGE2 8535 5455 0.00596717 -0.000589813 0.0476456 1 0 1 1 0 0 +EDGE2 8535 3016 -0.0374004 -1.06529 -1.55403 1 0 1 1 0 0 +EDGE2 8535 2715 -0.0306142 -0.0678223 0.0354565 1 0 1 1 0 0 +EDGE2 8535 3015 -0.0399232 0.0621477 0.00108044 1 0 1 1 0 0 +EDGE2 8535 3515 0.0716001 0.00583422 -3.10348 1 0 1 1 0 0 +EDGE2 8535 5456 0.0463526 0.968678 1.57848 1 0 1 1 0 0 +EDGE2 8535 3514 0.986718 -0.0195873 -3.12312 1 0 1 1 0 0 +EDGE2 8535 2716 -0.00838445 1.05349 1.55402 1 0 1 1 0 0 +EDGE2 8536 5455 -0.999131 0.010512 1.55694 1 0 1 1 0 0 +EDGE2 8536 3016 -0.0470779 0.0408133 -0.00892497 1 0 1 1 0 0 +EDGE2 8536 3017 1.07632 0.0524717 0.0435214 1 0 1 1 0 0 +EDGE2 8536 8535 -1.00863 0.0990973 1.57652 1 0 1 1 0 0 +EDGE2 8536 2715 -0.948146 -0.0416957 1.58451 1 0 1 1 0 0 +EDGE2 8536 3015 -1.02243 -0.0587187 1.60931 1 0 1 1 0 0 +EDGE2 8536 3515 -1.0176 0.00470444 -1.54945 1 0 1 1 0 0 +EDGE2 8537 3018 1.02639 -0.0283757 0.00122416 1 0 1 1 0 0 +EDGE2 8537 3016 -1.08918 -0.0635635 -0.0306566 1 0 1 1 0 0 +EDGE2 8537 8536 -0.940661 -0.0664167 0.0153877 1 0 1 1 0 0 +EDGE2 8537 3017 0.00441106 -0.0187775 0.0046992 1 0 1 1 0 0 +EDGE2 8538 3019 0.971457 0.0932666 -0.00334355 1 0 1 1 0 0 +EDGE2 8538 8537 -0.986091 -0.0631279 0.0258764 1 0 1 1 0 0 +EDGE2 8538 3018 -0.0497025 -0.101837 0.0034726 1 0 1 1 0 0 +EDGE2 8538 3017 -0.959368 0.118941 0.0171915 1 0 1 1 0 0 +EDGE2 8539 8520 0.968268 -0.0247553 -3.14648 1 0 1 1 0 0 +EDGE2 8539 3020 0.967173 0.0526542 -0.0139581 1 0 1 1 0 0 +EDGE2 8539 3180 1.00491 0.00413924 -3.1755 1 0 1 1 0 0 +EDGE2 8539 3500 1.05846 0.0181954 -3.16366 1 0 1 1 0 0 +EDGE2 8539 3019 0.0168834 0.0411605 -0.0129623 1 0 1 1 0 0 +EDGE2 8539 3018 -0.960289 0.0182493 0.00902 1 0 1 1 0 0 +EDGE2 8539 8538 -1.0053 0.00555848 0.0253487 1 0 1 1 0 0 +EDGE2 8540 3179 1.00337 -0.0399419 -3.1604 1 0 1 1 0 0 +EDGE2 8540 3499 0.975465 -0.0599958 -3.13219 1 0 1 1 0 0 +EDGE2 8540 8519 0.965677 -0.0208411 -3.16475 1 0 1 1 0 0 +EDGE2 8540 8520 0.0952173 -0.0077082 -3.12499 1 0 1 1 0 0 +EDGE2 8540 3181 -0.0179863 -0.956326 -1.57863 1 0 1 1 0 0 +EDGE2 8540 8521 -0.00687558 -1.02533 -1.55035 1 0 1 1 0 0 +EDGE2 8540 3501 0.0191167 0.963331 1.54389 1 0 1 1 0 0 +EDGE2 8540 3020 0.00189266 0.016196 0.00410501 1 0 1 1 0 0 +EDGE2 8540 3180 0.0339513 0.0312088 -3.13876 1 0 1 1 0 0 +EDGE2 8540 3500 -0.0267717 -0.0037662 -3.13822 1 0 1 1 0 0 +EDGE2 8540 8539 -0.976293 0.0447632 -0.00757443 1 0 1 1 0 0 +EDGE2 8540 3021 -0.0410483 1.05907 1.5726 1 0 1 1 0 0 +EDGE2 8540 3019 -0.976683 0.0482652 -0.0269374 1 0 1 1 0 0 +EDGE2 8541 8520 -1.03721 0.103218 1.58121 1 0 1 1 0 0 +EDGE2 8541 8540 -0.959433 0.0434939 -1.57354 1 0 1 1 0 0 +EDGE2 8541 3501 0.00845399 0.0546866 0.0119106 1 0 1 1 0 0 +EDGE2 8541 3020 -1.0283 -0.0406985 -1.58595 1 0 1 1 0 0 +EDGE2 8541 3180 -0.948863 0.035906 1.60636 1 0 1 1 0 0 +EDGE2 8541 3500 -1.0046 -0.0518067 1.53969 1 0 1 1 0 0 +EDGE2 8541 3021 -0.0273184 0.0448484 0.0338942 1 0 1 1 0 0 +EDGE2 8541 3022 0.959695 0.0158158 0.0122036 1 0 1 1 0 0 +EDGE2 8541 3502 1.03426 -0.063078 0.0214949 1 0 1 1 0 0 +EDGE2 8542 3501 -0.984317 -0.0962709 -0.00350768 1 0 1 1 0 0 +EDGE2 8542 8541 -1.02058 0.0166494 -0.0148805 1 0 1 1 0 0 +EDGE2 8542 3021 -1.02535 0.0724745 -0.0306363 1 0 1 1 0 0 +EDGE2 8542 3503 0.980042 -0.0210843 0.00753299 1 0 1 1 0 0 +EDGE2 8542 3022 -0.0181114 -0.0856357 -0.00725399 1 0 1 1 0 0 +EDGE2 8542 3502 -0.0245954 0.157286 -0.00247664 1 0 1 1 0 0 +EDGE2 8542 3023 0.944922 0.0348001 -0.0130199 1 0 1 1 0 0 +EDGE2 8543 3503 0.0404156 -0.0467373 0.0279653 1 0 1 1 0 0 +EDGE2 8543 3022 -1.00077 -0.0460661 -6.36866e-07 1 0 1 1 0 0 +EDGE2 8543 3502 -0.956718 -0.0897402 -0.00162171 1 0 1 1 0 0 +EDGE2 8543 8542 -1.11091 -0.0403174 -0.00701344 1 0 1 1 0 0 +EDGE2 8543 3504 0.996123 -0.0854626 -0.0112791 1 0 1 1 0 0 +EDGE2 8543 3023 -0.0305728 -0.0183047 0.00458684 1 0 1 1 0 0 +EDGE2 8543 3024 0.968461 -0.0194558 0.0288725 1 0 1 1 0 0 +EDGE2 8544 3503 -0.956486 0.013347 0.0128177 1 0 1 1 0 0 +EDGE2 8544 8543 -1.0024 -0.0444824 -0.00422474 1 0 1 1 0 0 +EDGE2 8544 3504 -0.00906333 -0.0368056 -0.0377902 1 0 1 1 0 0 +EDGE2 8544 3023 -0.989155 -0.00123198 -0.00146819 1 0 1 1 0 0 +EDGE2 8544 3024 0.00889379 0.0854961 -0.0214328 1 0 1 1 0 0 +EDGE2 8544 5805 1.03356 -0.055873 -3.14588 1 0 1 1 0 0 +EDGE2 8544 1145 1.07408 0.0600063 -3.08344 1 0 1 1 0 0 +EDGE2 8544 3045 0.971588 -0.00589654 -3.10606 1 0 1 1 0 0 +EDGE2 8544 3505 0.951385 -0.059889 -0.0330371 1 0 1 1 0 0 +EDGE2 8544 5785 0.998258 -0.0325793 -3.12737 1 0 1 1 0 0 +EDGE2 8544 3025 0.989172 0.0209353 0.000891419 1 0 1 1 0 0 +EDGE2 8544 1105 1.07245 0.0361675 -3.13965 1 0 1 1 0 0 +EDGE2 8544 1125 0.969356 -0.0292503 -3.18064 1 0 1 1 0 0 +EDGE2 8545 3504 -1.04992 -0.0115594 0.00684191 1 0 1 1 0 0 +EDGE2 8545 8544 -1.06528 0.00611624 0.010994 1 0 1 1 0 0 +EDGE2 8545 3024 -0.977004 -0.0132827 -0.0412677 1 0 1 1 0 0 +EDGE2 8545 5805 -0.00188503 0.032032 -3.19094 1 0 1 1 0 0 +EDGE2 8545 3046 -0.0282124 -0.997634 -1.60719 1 0 1 1 0 0 +EDGE2 8545 5806 -0.0390477 -1.06781 -1.56731 1 0 1 1 0 0 +EDGE2 8545 5786 -0.0506785 -0.980305 -1.57032 1 0 1 1 0 0 +EDGE2 8545 1126 -0.054599 -0.983824 -1.5365 1 0 1 1 0 0 +EDGE2 8545 1146 -0.0159257 -0.980455 -1.56031 1 0 1 1 0 0 +EDGE2 8545 3026 -0.00806062 -1.0839 -1.56313 1 0 1 1 0 0 +EDGE2 8545 1106 0.0354712 -0.976437 -1.56287 1 0 1 1 0 0 +EDGE2 8545 5784 1.02036 0.0436899 -3.12381 1 0 1 1 0 0 +EDGE2 8545 1145 -0.00812703 0.014228 -3.14457 1 0 1 1 0 0 +EDGE2 8545 3045 0.0391034 0.00878821 -3.17454 1 0 1 1 0 0 +EDGE2 8545 3505 0.0124089 -0.0147519 -0.00892439 1 0 1 1 0 0 +EDGE2 8545 5785 -0.0421299 -0.00979434 -3.19836 1 0 1 1 0 0 +EDGE2 8545 3025 0.0880362 0.0480099 0.000989572 1 0 1 1 0 0 +EDGE2 8545 1105 -0.042609 0.0373991 -3.13293 1 0 1 1 0 0 +EDGE2 8545 1125 -0.0699615 0.0350082 -3.13835 1 0 1 1 0 0 +EDGE2 8545 5804 0.985223 0.0431225 -3.15697 1 0 1 1 0 0 +EDGE2 8545 1124 1.00437 0.0205948 -3.13635 1 0 1 1 0 0 +EDGE2 8545 1144 0.981772 0.0123587 -3.12092 1 0 1 1 0 0 +EDGE2 8545 3044 1.02262 -0.0135854 -3.17647 1 0 1 1 0 0 +EDGE2 8545 1104 0.950538 -0.0583333 -3.12581 1 0 1 1 0 0 +EDGE2 8545 3506 0.0565673 0.994183 1.54421 1 0 1 1 0 0 +EDGE2 8546 3027 1.04592 -0.0733452 0.00578824 1 0 1 1 0 0 +EDGE2 8546 5787 1.02713 0.00201254 0.0294899 1 0 1 1 0 0 +EDGE2 8546 5807 0.881563 0.0705918 0.0088916 1 0 1 1 0 0 +EDGE2 8546 3047 1.03106 0.0646416 -0.0189441 1 0 1 1 0 0 +EDGE2 8546 5805 -0.996282 -0.0176976 -1.53089 1 0 1 1 0 0 +EDGE2 8546 1127 0.931769 -0.0189084 0.0156995 1 0 1 1 0 0 +EDGE2 8546 1147 1.07534 -0.0539444 0.021357 1 0 1 1 0 0 +EDGE2 8546 1107 0.979142 0.0723511 0.0198818 1 0 1 1 0 0 +EDGE2 8546 3046 0.0892498 -0.0235792 -0.0220784 1 0 1 1 0 0 +EDGE2 8546 5806 0.0620982 0.00338042 0.0143523 1 0 1 1 0 0 +EDGE2 8546 5786 -0.0521619 0.0207994 0.0143485 1 0 1 1 0 0 +EDGE2 8546 1126 0.0918104 -0.0648544 -0.0161166 1 0 1 1 0 0 +EDGE2 8546 1146 0.00486581 -0.00984318 -0.00441303 1 0 1 1 0 0 +EDGE2 8546 3026 -0.0198497 0.0502937 0.0295467 1 0 1 1 0 0 +EDGE2 8546 1106 -0.00889201 0.0182407 0.0238479 1 0 1 1 0 0 +EDGE2 8546 8545 -1.03047 0.0446459 1.58735 1 0 1 1 0 0 +EDGE2 8546 1145 -1.05882 -0.0847147 -1.54604 1 0 1 1 0 0 +EDGE2 8546 3045 -1.01129 0.0199857 -1.57977 1 0 1 1 0 0 +EDGE2 8546 3505 -1.0261 0.0733278 1.59822 1 0 1 1 0 0 +EDGE2 8546 5785 -0.933452 -0.0999537 -1.58281 1 0 1 1 0 0 +EDGE2 8546 3025 -0.954183 0.03913 1.5449 1 0 1 1 0 0 +EDGE2 8546 1105 -1.00228 -0.107494 -1.55636 1 0 1 1 0 0 +EDGE2 8546 1125 -1.0451 -0.0284285 -1.5992 1 0 1 1 0 0 +EDGE2 8547 3027 0.0297565 0.0208425 -0.0115165 1 0 1 1 0 0 +EDGE2 8547 3048 0.924906 -0.0322406 0.00968363 1 0 1 1 0 0 +EDGE2 8547 5808 0.879772 -0.0605682 -0.0142084 1 0 1 1 0 0 +EDGE2 8547 5788 0.852197 0.0934535 0.0380115 1 0 1 1 0 0 +EDGE2 8547 3028 0.943028 -0.00406934 -0.00201891 1 0 1 1 0 0 +EDGE2 8547 1108 0.976112 0.0653576 -0.00983159 1 0 1 1 0 0 +EDGE2 8547 1128 0.934787 -0.0085535 -0.00194249 1 0 1 1 0 0 +EDGE2 8547 1148 0.953123 0.00973935 -0.0254725 1 0 1 1 0 0 +EDGE2 8547 5787 0.0125548 0.037294 -0.020839 1 0 1 1 0 0 +EDGE2 8547 5807 0.0538757 -0.0324532 -0.00769401 1 0 1 1 0 0 +EDGE2 8547 3047 0.05549 -0.0499823 0.0291302 1 0 1 1 0 0 +EDGE2 8547 1127 0.0299997 0.00383557 0.00901042 1 0 1 1 0 0 +EDGE2 8547 1147 -0.101411 0.053009 0.0157109 1 0 1 1 0 0 +EDGE2 8547 1107 0.0138788 0.0153452 -0.0150871 1 0 1 1 0 0 +EDGE2 8547 3046 -1.06594 -0.0160373 -0.0130946 1 0 1 1 0 0 +EDGE2 8547 5806 -1.07486 -0.0310644 -0.0250205 1 0 1 1 0 0 +EDGE2 8547 8546 -1.03625 -0.0349674 -0.0107347 1 0 1 1 0 0 +EDGE2 8547 5786 -0.98183 0.029067 0.0333694 1 0 1 1 0 0 +EDGE2 8547 1126 -0.944119 0.00969066 0.0314861 1 0 1 1 0 0 +EDGE2 8547 1146 -1.0045 -0.0145833 -0.0451091 1 0 1 1 0 0 +EDGE2 8547 3026 -0.980864 -0.0440774 -0.015084 1 0 1 1 0 0 +EDGE2 8547 1106 -1.01477 0.0165455 -0.012969 1 0 1 1 0 0 +EDGE2 8548 3027 -1.10676 -0.0551571 -0.0027983 1 0 1 1 0 0 +EDGE2 8548 3048 0.0170781 -0.0135699 0.0486023 1 0 1 1 0 0 +EDGE2 8548 5789 0.979237 -0.052337 0.00621872 1 0 1 1 0 0 +EDGE2 8548 5809 1.01498 -0.0375289 -0.00749995 1 0 1 1 0 0 +EDGE2 8548 1109 1.03364 -0.0291982 0.0130951 1 0 1 1 0 0 +EDGE2 8548 1149 0.975683 -0.118777 0.0125219 1 0 1 1 0 0 +EDGE2 8548 3029 0.985132 0.0269929 0.00366854 1 0 1 1 0 0 +EDGE2 8548 3049 1.07022 -0.0612528 0.0107617 1 0 1 1 0 0 +EDGE2 8548 1129 1.03315 0.0589446 0.0363676 1 0 1 1 0 0 +EDGE2 8548 5808 -0.053586 -0.0177126 0.00747192 1 0 1 1 0 0 +EDGE2 8548 5788 0.0428606 -0.0552904 -0.0247396 1 0 1 1 0 0 +EDGE2 8548 3028 -0.0306006 -0.01994 0.011806 1 0 1 1 0 0 +EDGE2 8548 8547 -0.978672 -0.0788941 -0.00854867 1 0 1 1 0 0 +EDGE2 8548 1108 0.0272174 -0.0348125 -0.00843824 1 0 1 1 0 0 +EDGE2 8548 1128 -0.00584606 -0.0643058 0.0347949 1 0 1 1 0 0 +EDGE2 8548 1148 0.0422778 -0.0123731 -0.0246708 1 0 1 1 0 0 +EDGE2 8548 5787 -0.980753 -0.026141 -0.008043 1 0 1 1 0 0 +EDGE2 8548 5807 -1.03829 0.0120234 -0.00641354 1 0 1 1 0 0 +EDGE2 8548 3047 -1.11775 0.00716843 0.00864967 1 0 1 1 0 0 +EDGE2 8548 1127 -0.902069 0.00182734 0.00400535 1 0 1 1 0 0 +EDGE2 8548 1147 -1.04792 0.0226661 0.0136911 1 0 1 1 0 0 +EDGE2 8548 1107 -0.983601 -0.0135091 0.00877999 1 0 1 1 0 0 +EDGE2 8549 3050 0.938479 0.0477339 0.0571174 1 0 1 1 0 0 +EDGE2 8549 5850 0.994893 -0.0159955 -3.16382 1 0 1 1 0 0 +EDGE2 8549 8490 1.0662 0.0496543 -3.13928 1 0 1 1 0 0 +EDGE2 8549 8390 0.998157 0.00494289 -3.15382 1 0 1 1 0 0 +EDGE2 8549 3170 0.933127 -0.0193737 -3.14044 1 0 1 1 0 0 +EDGE2 8549 5790 0.966619 0.022716 0.0155547 1 0 1 1 0 0 +EDGE2 8549 5810 1.05347 -0.028323 -0.0232665 1 0 1 1 0 0 +EDGE2 8549 5830 1.01234 0.0821708 -3.15866 1 0 1 1 0 0 +EDGE2 8549 3490 0.930812 -0.018857 -3.15102 1 0 1 1 0 0 +EDGE2 8549 3110 0.983744 -0.0242429 -3.15917 1 0 1 1 0 0 +EDGE2 8549 3130 0.972622 -0.0280545 -3.12406 1 0 1 1 0 0 +EDGE2 8549 3090 1.06719 -0.0587348 -3.15144 1 0 1 1 0 0 +EDGE2 8549 3048 -1.06233 -0.0217944 -0.0311613 1 0 1 1 0 0 +EDGE2 8549 5789 -0.0462872 -0.0679956 -0.00884618 1 0 1 1 0 0 +EDGE2 8549 1130 0.993328 0.00739656 -0.0387918 1 0 1 1 0 0 +EDGE2 8549 1170 0.981787 -0.0819259 -3.16311 1 0 1 1 0 0 +EDGE2 8549 1190 1.05214 0.104919 -3.1613 1 0 1 1 0 0 +EDGE2 8549 3030 1.02871 0.0779703 0.00707945 1 0 1 1 0 0 +EDGE2 8549 1150 0.986232 0.0114867 -0.0226151 1 0 1 1 0 0 +EDGE2 8549 1110 0.949123 -0.0328167 0.000935956 1 0 1 1 0 0 +EDGE2 8549 5809 -0.0319997 0.0055624 0.017719 1 0 1 1 0 0 +EDGE2 8549 1109 -0.00313 -0.00614282 0.018965 1 0 1 1 0 0 +EDGE2 8549 1149 0.134969 -0.00372877 0.00245705 1 0 1 1 0 0 +EDGE2 8549 3029 0.0386892 0.0113686 0.0407008 1 0 1 1 0 0 +EDGE2 8549 3049 0.0395553 0.0408376 0.0287848 1 0 1 1 0 0 +EDGE2 8549 1129 -0.0553176 0.0316388 -0.010733 1 0 1 1 0 0 +EDGE2 8549 5808 -0.898859 0.0471485 -0.00677652 1 0 1 1 0 0 +EDGE2 8549 8548 -1.04596 0.00492701 -0.00628157 1 0 1 1 0 0 +EDGE2 8549 5788 -0.953338 -0.0141393 -0.0212268 1 0 1 1 0 0 +EDGE2 8549 3028 -0.93861 0.00277347 -0.0124673 1 0 1 1 0 0 +EDGE2 8549 1108 -1.06008 0.0158967 -0.0309546 1 0 1 1 0 0 +EDGE2 8549 1128 -0.897399 0.0126141 0.000702667 1 0 1 1 0 0 +EDGE2 8549 1148 -0.993903 0.0532504 -0.033984 1 0 1 1 0 0 +EDGE2 8550 5849 1.02026 -0.0366387 -3.14325 1 0 1 1 0 0 +EDGE2 8550 8489 0.973853 -0.0771653 -3.12056 1 0 1 1 0 0 +EDGE2 8550 8389 0.97533 -0.0564348 -3.16196 1 0 1 1 0 0 +EDGE2 8550 3109 0.97719 -0.0133696 -3.13656 1 0 1 1 0 0 +EDGE2 8550 3169 1.10532 0.0372391 -3.12409 1 0 1 1 0 0 +EDGE2 8550 3489 0.991666 -0.0536955 -3.14813 1 0 1 1 0 0 +EDGE2 8550 5829 1.02443 -0.0168193 -3.17246 1 0 1 1 0 0 +EDGE2 8550 3129 1.07723 -0.011487 -3.15598 1 0 1 1 0 0 +EDGE2 8550 1189 1.0217 0.0742013 -3.13365 1 0 1 1 0 0 +EDGE2 8550 3089 0.916519 0.0277238 -3.11757 1 0 1 1 0 0 +EDGE2 8550 1169 1.00114 -0.0381267 -3.1137 1 0 1 1 0 0 +EDGE2 8550 3050 -0.0396128 -0.00234204 0.0215289 1 0 1 1 0 0 +EDGE2 8550 3131 0.0360805 -1.08244 -1.53421 1 0 1 1 0 0 +EDGE2 8550 8491 -0.0441649 -0.997775 -1.58197 1 0 1 1 0 0 +EDGE2 8550 3491 0.016452 -0.930682 -1.5695 1 0 1 1 0 0 +EDGE2 8550 5811 0.037408 -0.968996 -1.55076 1 0 1 1 0 0 +EDGE2 8550 5831 -0.0828036 -1.02954 -1.52251 1 0 1 1 0 0 +EDGE2 8550 3171 0.00528788 -1.0318 -1.57187 1 0 1 1 0 0 +EDGE2 8550 5850 -0.00332302 -0.136604 -3.13697 1 0 1 1 0 0 +EDGE2 8550 1151 -0.0554655 -0.983996 -1.57684 1 0 1 1 0 0 +EDGE2 8550 1191 -0.0080207 -0.949834 -1.59609 1 0 1 1 0 0 +EDGE2 8550 3091 -0.0617343 -0.893986 -1.59035 1 0 1 1 0 0 +EDGE2 8550 3111 0.0190046 -0.951344 -1.60068 1 0 1 1 0 0 +EDGE2 8550 1171 0.0469763 -1.0472 -1.58286 1 0 1 1 0 0 +EDGE2 8550 8490 -0.035442 0.046217 -3.12565 1 0 1 1 0 0 +EDGE2 8550 8390 0.159232 -0.0324455 -3.11499 1 0 1 1 0 0 +EDGE2 8550 3170 0.111253 -0.0191504 -3.15676 1 0 1 1 0 0 +EDGE2 8550 5790 -0.0898902 -0.0104208 -0.00216819 1 0 1 1 0 0 +EDGE2 8550 5810 -0.0516172 0.0292311 -0.0152659 1 0 1 1 0 0 +EDGE2 8550 5830 0.00109529 -0.0593849 -3.14013 1 0 1 1 0 0 +EDGE2 8550 3490 0.0115822 -0.0271899 -3.12604 1 0 1 1 0 0 +EDGE2 8550 3110 -0.0119345 -0.0321839 -3.11994 1 0 1 1 0 0 +EDGE2 8550 3130 0.0564561 -0.081939 -3.14327 1 0 1 1 0 0 +EDGE2 8550 3090 0.0733608 -0.0339402 -3.13996 1 0 1 1 0 0 +EDGE2 8550 5789 -0.964207 0.0600251 -0.0187894 1 0 1 1 0 0 +EDGE2 8550 1130 0.0720193 0.0167261 0.00789846 1 0 1 1 0 0 +EDGE2 8550 1170 0.0502078 0.0975093 -3.13448 1 0 1 1 0 0 +EDGE2 8550 1190 -0.0293203 -0.029913 -3.18156 1 0 1 1 0 0 +EDGE2 8550 3030 0.0142329 0.0185191 0.00500676 1 0 1 1 0 0 +EDGE2 8550 1150 0.0468505 0.0616754 0.00426793 1 0 1 1 0 0 +EDGE2 8550 8549 -1.05449 0.0467592 -0.0374337 1 0 1 1 0 0 +EDGE2 8550 1110 0.0587844 -0.0306589 -0.000703928 1 0 1 1 0 0 +EDGE2 8550 5809 -0.984637 0.0327991 0.0232893 1 0 1 1 0 0 +EDGE2 8550 1109 -0.930062 -0.0472193 -0.0166554 1 0 1 1 0 0 +EDGE2 8550 1149 -0.980469 0.00465926 -0.0125515 1 0 1 1 0 0 +EDGE2 8550 3029 -0.966511 0.0460157 0.00723237 1 0 1 1 0 0 +EDGE2 8550 3049 -0.995616 -0.0605315 -0.0135031 1 0 1 1 0 0 +EDGE2 8550 1129 -0.955746 -0.0155397 0.0104573 1 0 1 1 0 0 +EDGE2 8550 5851 -0.0433057 0.95213 1.6195 1 0 1 1 0 0 +EDGE2 8550 8391 0.00511928 0.97929 1.57097 1 0 1 1 0 0 +EDGE2 8550 1111 0.00112938 1.03447 1.61581 1 0 1 1 0 0 +EDGE2 8550 3031 0.000671164 1.02205 1.54732 1 0 1 1 0 0 +EDGE2 8550 3051 -0.0396522 1.01322 1.53372 1 0 1 1 0 0 +EDGE2 8550 5791 0.0132231 0.945781 1.55243 1 0 1 1 0 0 +EDGE2 8550 1131 -0.0261606 0.985211 1.56439 1 0 1 1 0 0 +EDGE2 8551 3050 -0.950968 -0.0382322 -1.55435 1 0 1 1 0 0 +EDGE2 8551 5850 -0.949841 0.0366084 1.61388 1 0 1 1 0 0 +EDGE2 8551 8490 -1.02534 -0.0659736 1.57653 1 0 1 1 0 0 +EDGE2 8551 8550 -1.06122 0.010764 -1.56988 1 0 1 1 0 0 +EDGE2 8551 8390 -0.954565 0.0115576 1.56389 1 0 1 1 0 0 +EDGE2 8551 3170 -0.964452 -0.00874041 1.55856 1 0 1 1 0 0 +EDGE2 8551 5790 -0.997602 -0.0214404 -1.56827 1 0 1 1 0 0 +EDGE2 8551 5810 -0.949134 -0.0447079 -1.56239 1 0 1 1 0 0 +EDGE2 8551 5830 -1.04515 0.103143 1.57017 1 0 1 1 0 0 +EDGE2 8551 3490 -0.971813 0.103278 1.55335 1 0 1 1 0 0 +EDGE2 8551 3110 -0.918433 0.0636683 1.56667 1 0 1 1 0 0 +EDGE2 8551 3130 -1.00526 -0.093092 1.55167 1 0 1 1 0 0 +EDGE2 8551 3090 -1.01043 0.0213429 1.56598 1 0 1 1 0 0 +EDGE2 8551 1130 -1.10351 0.0208776 -1.55663 1 0 1 1 0 0 +EDGE2 8551 1170 -0.993536 0.0291674 1.57527 1 0 1 1 0 0 +EDGE2 8551 1190 -1.01556 -0.031751 1.57164 1 0 1 1 0 0 +EDGE2 8551 3030 -0.966682 0.0427655 -1.56224 1 0 1 1 0 0 +EDGE2 8551 1150 -1.04946 -0.0375117 -1.59286 1 0 1 1 0 0 +EDGE2 8551 1110 -0.9995 0.0104117 -1.5734 1 0 1 1 0 0 +EDGE2 8551 5851 0.0440573 -0.0324123 0.0105736 1 0 1 1 0 0 +EDGE2 8551 8391 -0.0886928 0.103917 0.00606026 1 0 1 1 0 0 +EDGE2 8551 3052 1.04383 -0.0208667 0.00670444 1 0 1 1 0 0 +EDGE2 8551 1111 0.0191734 0.00778909 -0.00439866 1 0 1 1 0 0 +EDGE2 8551 3031 0.0282941 0.0138867 -0.00959096 1 0 1 1 0 0 +EDGE2 8551 3051 0.032966 0.035851 0.00903228 1 0 1 1 0 0 +EDGE2 8551 5791 0.0360027 -0.0708805 -0.00979741 1 0 1 1 0 0 +EDGE2 8551 1131 -0.0505211 0.0453837 -0.0100877 1 0 1 1 0 0 +EDGE2 8551 5852 1.03436 0.00340717 0.009546 1 0 1 1 0 0 +EDGE2 8551 8392 0.991953 0.0263912 -0.00583139 1 0 1 1 0 0 +EDGE2 8551 5792 1.03244 -0.00590424 0.00232594 1 0 1 1 0 0 +EDGE2 8551 1112 1.00737 -0.00241264 -0.0372707 1 0 1 1 0 0 +EDGE2 8551 1132 1.01959 0.0932999 -0.0126502 1 0 1 1 0 0 +EDGE2 8551 3032 1.00299 0.0407149 0.0270377 1 0 1 1 0 0 +EDGE2 8552 5851 -0.918932 0.027765 0.0179551 1 0 1 1 0 0 +EDGE2 8552 8551 -1.04494 0.0180021 -0.023472 1 0 1 1 0 0 +EDGE2 8552 8391 -1.01976 0.0520962 -0.00798945 1 0 1 1 0 0 +EDGE2 8552 1133 1.01174 -0.0108258 0.0200445 1 0 1 1 0 0 +EDGE2 8552 3052 -0.0456241 -0.0508078 -0.0367814 1 0 1 1 0 0 +EDGE2 8552 1111 -1.07672 -0.0152476 -0.0145822 1 0 1 1 0 0 +EDGE2 8552 3031 -0.971416 0.0206751 0.0215713 1 0 1 1 0 0 +EDGE2 8552 3051 -0.952946 -0.0665092 -0.00837405 1 0 1 1 0 0 +EDGE2 8552 5791 -1.10514 0.0484924 -0.017146 1 0 1 1 0 0 +EDGE2 8552 1131 -0.910893 0.042472 -0.011645 1 0 1 1 0 0 +EDGE2 8552 5852 0.0142883 -0.0279413 0.0417103 1 0 1 1 0 0 +EDGE2 8552 8392 0.00175438 0.0341456 0.00053029 1 0 1 1 0 0 +EDGE2 8552 5792 0.0229899 0.0301858 0.00821172 1 0 1 1 0 0 +EDGE2 8552 8393 1.18592 -0.025379 -0.0113949 1 0 1 1 0 0 +EDGE2 8552 1112 0.00878864 0.0276544 0.00356752 1 0 1 1 0 0 +EDGE2 8552 1132 0.0390098 -0.0824012 -0.00726672 1 0 1 1 0 0 +EDGE2 8552 3032 -0.0606075 0.00704091 0.0259294 1 0 1 1 0 0 +EDGE2 8552 3053 0.967024 0.0221096 0.0200085 1 0 1 1 0 0 +EDGE2 8552 5793 0.988524 0.0974079 -0.00453065 1 0 1 1 0 0 +EDGE2 8552 5853 1.04483 -0.0359293 -0.0208364 1 0 1 1 0 0 +EDGE2 8552 3033 0.982703 -0.00107796 -0.0367914 1 0 1 1 0 0 +EDGE2 8552 1113 1.00546 0.0657922 0.0148728 1 0 1 1 0 0 +EDGE2 8553 1133 0.0398459 -0.0608124 0.010296 1 0 1 1 0 0 +EDGE2 8553 3052 -0.942652 0.032114 0.000453464 1 0 1 1 0 0 +EDGE2 8553 5852 -0.995561 0.032075 0.0187238 1 0 1 1 0 0 +EDGE2 8553 8392 -1.00806 0.00941273 0.018005 1 0 1 1 0 0 +EDGE2 8553 8552 -1.05411 -0.0286602 -0.00471729 1 0 1 1 0 0 +EDGE2 8553 5792 -0.988657 -0.0361989 -0.0289192 1 0 1 1 0 0 +EDGE2 8553 8393 -0.0339881 -0.016905 0.0166535 1 0 1 1 0 0 +EDGE2 8553 1112 -0.950661 0.0320433 -0.00858845 1 0 1 1 0 0 +EDGE2 8553 1132 -1.00689 0.0713744 0.0228875 1 0 1 1 0 0 +EDGE2 8553 3032 -1.05088 -0.0633989 -0.016036 1 0 1 1 0 0 +EDGE2 8553 3053 0.0647382 -0.0686666 -0.0219394 1 0 1 1 0 0 +EDGE2 8553 5793 0.0372015 0.0184649 -0.00125685 1 0 1 1 0 0 +EDGE2 8553 5853 0.00893074 0.0150647 -0.0236552 1 0 1 1 0 0 +EDGE2 8553 3033 0.0249052 -0.0672263 0.00197087 1 0 1 1 0 0 +EDGE2 8553 5794 1.04445 0.046843 -0.0115315 1 0 1 1 0 0 +EDGE2 8553 8394 0.909066 -0.0525263 0.00524061 1 0 1 1 0 0 +EDGE2 8553 1113 -0.0507767 -0.0120534 0.000788387 1 0 1 1 0 0 +EDGE2 8553 5854 0.98978 0.0956324 0.0332375 1 0 1 1 0 0 +EDGE2 8553 1134 0.93402 -0.101042 0.00832551 1 0 1 1 0 0 +EDGE2 8553 3034 0.944224 -0.0141568 -0.0364058 1 0 1 1 0 0 +EDGE2 8553 3054 0.92978 0.0283936 0.0401606 1 0 1 1 0 0 +EDGE2 8553 1114 0.978584 -4.93268e-06 -0.0293708 1 0 1 1 0 0 +EDGE2 8554 5795 1.02404 0.107317 -0.0139341 1 0 1 1 0 0 +EDGE2 8554 1133 -0.958652 -0.0178261 -0.0182139 1 0 1 1 0 0 +EDGE2 8554 8393 -1.00384 -0.021613 -0.0312145 1 0 1 1 0 0 +EDGE2 8554 8553 -0.973579 -0.097048 0.0388574 1 0 1 1 0 0 +EDGE2 8554 3053 -0.977999 0.0214373 -0.0328374 1 0 1 1 0 0 +EDGE2 8554 5793 -1.00023 -0.0309347 0.0344933 1 0 1 1 0 0 +EDGE2 8554 5853 -0.918343 -0.0437575 0.00496773 1 0 1 1 0 0 +EDGE2 8554 3033 -1.01504 -0.0567443 -0.00854723 1 0 1 1 0 0 +EDGE2 8554 5794 -0.114249 -0.0215033 0.0105581 1 0 1 1 0 0 +EDGE2 8554 8394 0.0595165 -0.0345799 -0.0175788 1 0 1 1 0 0 +EDGE2 8554 1113 -1.00366 -0.0217978 -0.027922 1 0 1 1 0 0 +EDGE2 8554 5854 -0.0680695 0.0447798 0.00458041 1 0 1 1 0 0 +EDGE2 8554 1134 0.0439746 0.0359001 0.00313455 1 0 1 1 0 0 +EDGE2 8554 3034 0.0886411 0.010211 -0.0295758 1 0 1 1 0 0 +EDGE2 8554 3054 0.0293171 0.00340807 -0.0100302 1 0 1 1 0 0 +EDGE2 8554 1114 -0.0205991 -0.0307267 0.00575793 1 0 1 1 0 0 +EDGE2 8554 8395 0.978303 0.0394175 -0.00908822 1 0 1 1 0 0 +EDGE2 8554 8415 1.04817 -0.0985956 -3.12586 1 0 1 1 0 0 +EDGE2 8554 5875 1.01692 0.0652265 -3.13451 1 0 1 1 0 0 +EDGE2 8554 8355 1.0344 -0.00826833 -3.17865 1 0 1 1 0 0 +EDGE2 8554 5855 0.987215 -0.00379041 -0.00440699 1 0 1 1 0 0 +EDGE2 8554 3035 1.01918 -0.0111972 0.0241068 1 0 1 1 0 0 +EDGE2 8554 3055 0.960218 -0.0508476 -0.0346055 1 0 1 1 0 0 +EDGE2 8554 1095 0.987891 -0.0544112 -3.17555 1 0 1 1 0 0 +EDGE2 8554 1115 0.988595 0.0471398 -0.0221791 1 0 1 1 0 0 +EDGE2 8554 1135 1.06638 -0.0465148 -0.0102852 1 0 1 1 0 0 +EDGE2 8555 5795 -0.0163152 0.0616967 -0.0122326 1 0 1 1 0 0 +EDGE2 8555 8356 0.00895512 -0.961332 -1.54088 1 0 1 1 0 0 +EDGE2 8555 8416 0.0767657 -1.02453 -1.56599 1 0 1 1 0 0 +EDGE2 8555 8396 -0.0601421 -1.00854 -1.61763 1 0 1 1 0 0 +EDGE2 8555 5856 -0.0489347 -0.881435 -1.56008 1 0 1 1 0 0 +EDGE2 8555 5876 0.0594093 -1.01634 -1.5889 1 0 1 1 0 0 +EDGE2 8555 3056 -0.0642956 -0.960321 -1.57986 1 0 1 1 0 0 +EDGE2 8555 5794 -1.01185 -0.0576686 -0.0189203 1 0 1 1 0 0 +EDGE2 8555 8394 -0.990685 0.0378906 -0.0261597 1 0 1 1 0 0 +EDGE2 8555 8554 -1.05008 0.0147483 0.029545 1 0 1 1 0 0 +EDGE2 8555 5854 -1.01353 0.0158849 0.00342471 1 0 1 1 0 0 +EDGE2 8555 1134 -1.00523 0.00926111 -0.00695209 1 0 1 1 0 0 +EDGE2 8555 3034 -0.954412 0.0435718 -0.0136272 1 0 1 1 0 0 +EDGE2 8555 3054 -1.05191 -0.137484 0.0153261 1 0 1 1 0 0 +EDGE2 8555 1114 -1.00163 0.00818046 0.000471229 1 0 1 1 0 0 +EDGE2 8555 8395 0.0265377 -0.122795 -0.0211118 1 0 1 1 0 0 +EDGE2 8555 8415 0.0252872 0.00641434 -3.14592 1 0 1 1 0 0 +EDGE2 8555 5875 -0.114618 -0.0165183 -3.12522 1 0 1 1 0 0 +EDGE2 8555 8355 0.111062 -0.000947809 -3.15044 1 0 1 1 0 0 +EDGE2 8555 5855 0.0528625 -0.0522576 -0.00365156 1 0 1 1 0 0 +EDGE2 8555 3035 0.0664334 0.0729617 -0.0103243 1 0 1 1 0 0 +EDGE2 8555 3055 0.0141585 0.00382622 0.0215936 1 0 1 1 0 0 +EDGE2 8555 1095 0.0140722 0.00166457 -3.12558 1 0 1 1 0 0 +EDGE2 8555 1115 0.0164626 0.0509086 0.025856 1 0 1 1 0 0 +EDGE2 8555 1135 -0.0254286 -0.0810039 0.021974 1 0 1 1 0 0 +EDGE2 8555 1094 1.04969 0.0266411 -3.11939 1 0 1 1 0 0 +EDGE2 8555 8354 0.947974 0.0141895 -3.12476 1 0 1 1 0 0 +EDGE2 8555 8414 1.02037 -0.0077568 -3.10877 1 0 1 1 0 0 +EDGE2 8555 5874 0.976872 0.0832297 -3.19816 1 0 1 1 0 0 +EDGE2 8555 1116 -0.0285218 0.992926 1.57285 1 0 1 1 0 0 +EDGE2 8555 3036 0.0496876 0.958948 1.57314 1 0 1 1 0 0 +EDGE2 8555 5796 0.0655552 1.07767 1.55373 1 0 1 1 0 0 +EDGE2 8555 1136 0.0116029 1.03254 1.59591 1 0 1 1 0 0 +EDGE2 8555 1096 -0.0306067 1.06749 1.56439 1 0 1 1 0 0 +EDGE2 8556 5795 -0.985759 -0.00911503 -1.54889 1 0 1 1 0 0 +EDGE2 8556 8395 -0.959669 -0.00382095 -1.58217 1 0 1 1 0 0 +EDGE2 8556 8555 -1.06568 0.0684686 -1.58232 1 0 1 1 0 0 +EDGE2 8556 8415 -1.01753 -0.0346675 1.58837 1 0 1 1 0 0 +EDGE2 8556 5875 -0.933957 -0.0372538 1.6051 1 0 1 1 0 0 +EDGE2 8556 8355 -1.00203 -0.030966 1.57242 1 0 1 1 0 0 +EDGE2 8556 5855 -1.02171 0.0325394 -1.57758 1 0 1 1 0 0 +EDGE2 8556 3035 -1.01328 -0.0388173 -1.56353 1 0 1 1 0 0 +EDGE2 8556 3055 -1.06764 -0.00604877 -1.56562 1 0 1 1 0 0 +EDGE2 8556 1095 -1.05303 -0.0267598 1.53921 1 0 1 1 0 0 +EDGE2 8556 1115 -0.987673 0.0017965 -1.58723 1 0 1 1 0 0 +EDGE2 8556 1135 -0.990474 0.0409819 -1.54983 1 0 1 1 0 0 +EDGE2 8556 1116 0.0479328 -0.0537573 0.00598465 1 0 1 1 0 0 +EDGE2 8556 3036 -0.0425961 0.0410743 0.000245312 1 0 1 1 0 0 +EDGE2 8556 5796 0.0116277 0.0121288 0.00747163 1 0 1 1 0 0 +EDGE2 8556 1136 0.0541128 0.014579 -0.0203397 1 0 1 1 0 0 +EDGE2 8556 1096 -0.063157 -0.0519426 0.0132827 1 0 1 1 0 0 +EDGE2 8556 1097 0.982039 -0.0466627 0.00682656 1 0 1 1 0 0 +EDGE2 8556 1137 1.0014 0.00271997 -0.00862619 1 0 1 1 0 0 +EDGE2 8556 3037 1.00555 0.0201359 0.00744677 1 0 1 1 0 0 +EDGE2 8556 5797 1.10478 0.0387348 0.00989322 1 0 1 1 0 0 +EDGE2 8556 1117 1.04216 0.0803361 -6.16628e-05 1 0 1 1 0 0 +EDGE2 8557 1118 0.97997 0.0128879 0.0077669 1 0 1 1 0 0 +EDGE2 8557 1116 -0.979837 -0.0603778 0.00853534 1 0 1 1 0 0 +EDGE2 8557 3036 -1.11333 -0.155161 -0.00628057 1 0 1 1 0 0 +EDGE2 8557 5796 -1.00917 0.0508792 0.0158543 1 0 1 1 0 0 +EDGE2 8557 8556 -0.949 0.0969202 -0.000350549 1 0 1 1 0 0 +EDGE2 8557 1136 -0.948978 -0.0360288 -0.0050782 1 0 1 1 0 0 +EDGE2 8557 1096 -1.04079 -0.00777086 -0.00892365 1 0 1 1 0 0 +EDGE2 8557 1097 -0.031469 0.0773539 0.0030384 1 0 1 1 0 0 +EDGE2 8557 1137 -0.0321299 -0.0136198 -0.0117331 1 0 1 1 0 0 +EDGE2 8557 3037 0.0428638 -0.0747981 -0.0231154 1 0 1 1 0 0 +EDGE2 8557 5797 -0.0487533 -0.0511213 0.0162545 1 0 1 1 0 0 +EDGE2 8557 1117 -0.0432103 -0.0211231 -0.00175225 1 0 1 1 0 0 +EDGE2 8557 3038 1.03302 -0.071677 0.00884676 1 0 1 1 0 0 +EDGE2 8557 5798 0.949798 -0.0986827 -0.0092597 1 0 1 1 0 0 +EDGE2 8557 1138 0.963371 -0.0868321 0.0126955 1 0 1 1 0 0 +EDGE2 8557 1098 1.00251 -0.0755742 -0.0339412 1 0 1 1 0 0 +EDGE2 8558 1118 -0.00893193 -0.0407824 0.021992 1 0 1 1 0 0 +EDGE2 8558 8557 -1.06721 0.0160941 -0.0075535 1 0 1 1 0 0 +EDGE2 8558 1097 -0.993154 0.00319691 0.0132416 1 0 1 1 0 0 +EDGE2 8558 1137 -0.97516 -0.0893238 0.0202478 1 0 1 1 0 0 +EDGE2 8558 3037 -1.03531 0.0182565 0.0165407 1 0 1 1 0 0 +EDGE2 8558 5797 -0.94946 0.0125047 -0.000718849 1 0 1 1 0 0 +EDGE2 8558 1117 -1.03581 -0.00556742 -0.00834143 1 0 1 1 0 0 +EDGE2 8558 3038 -0.0485026 0.0160627 -0.00218717 1 0 1 1 0 0 +EDGE2 8558 5798 0.0183509 -0.00506771 -0.00694732 1 0 1 1 0 0 +EDGE2 8558 1138 0.0736236 0.0198241 -0.00489299 1 0 1 1 0 0 +EDGE2 8558 1139 1.06028 0.0495107 -0.00278315 1 0 1 1 0 0 +EDGE2 8558 5799 0.971027 -0.033332 0.0216608 1 0 1 1 0 0 +EDGE2 8558 1098 -0.00177384 -0.0216047 -0.0129161 1 0 1 1 0 0 +EDGE2 8558 3039 1.028 -0.0179026 -0.00763781 1 0 1 1 0 0 +EDGE2 8558 1099 1.1394 -0.0135643 0.0277393 1 0 1 1 0 0 +EDGE2 8558 1119 0.943414 -0.0917311 -0.0276358 1 0 1 1 0 0 +EDGE2 8559 5780 0.976157 -0.0218408 -3.18035 1 0 1 1 0 0 +EDGE2 8559 1118 -0.980815 0.00957904 -0.0383765 1 0 1 1 0 0 +EDGE2 8559 3038 -1.08022 0.0141098 0.021509 1 0 1 1 0 0 +EDGE2 8559 5798 -0.909365 -0.0213613 0.0318295 1 0 1 1 0 0 +EDGE2 8559 8558 -1.06258 -0.0226715 0.0126996 1 0 1 1 0 0 +EDGE2 8559 1138 -0.968146 0.0563384 0.00610908 1 0 1 1 0 0 +EDGE2 8559 1139 -0.00120483 0.0169954 -0.00677496 1 0 1 1 0 0 +EDGE2 8559 5799 -0.0624657 0.0314066 -0.0294906 1 0 1 1 0 0 +EDGE2 8559 1098 -0.989956 -0.000426049 -0.0398944 1 0 1 1 0 0 +EDGE2 8559 3039 0.0185536 -0.0543761 0.024075 1 0 1 1 0 0 +EDGE2 8559 1099 0.00209101 0.107746 0.018781 1 0 1 1 0 0 +EDGE2 8559 1119 -0.0310437 -0.00195088 0.0051169 1 0 1 1 0 0 +EDGE2 8559 5800 0.962128 -0.0178862 -0.00513912 1 0 1 1 0 0 +EDGE2 8559 1100 0.953363 -0.0268211 0.0136151 1 0 1 1 0 0 +EDGE2 8559 1140 1.06683 0.00854077 -0.00248535 1 0 1 1 0 0 +EDGE2 8559 3040 0.942801 -0.108252 -0.0242764 1 0 1 1 0 0 +EDGE2 8559 5660 0.955338 0.0949653 -3.10489 1 0 1 1 0 0 +EDGE2 8559 1120 1.11463 -0.0265721 -0.0098104 1 0 1 1 0 0 +EDGE2 8560 5780 -0.057794 -0.0188532 -3.16808 1 0 1 1 0 0 +EDGE2 8560 1139 -1.04288 0.0461383 -0.0292179 1 0 1 1 0 0 +EDGE2 8560 5799 -0.994373 0.0279104 0.00658569 1 0 1 1 0 0 +EDGE2 8560 8559 -1.10042 -0.0426768 -0.000301062 1 0 1 1 0 0 +EDGE2 8560 3039 -0.914611 0.00840254 -0.00975463 1 0 1 1 0 0 +EDGE2 8560 1099 -1.0863 -0.04814 0.0300661 1 0 1 1 0 0 +EDGE2 8560 1119 -0.991332 0.0031533 0.00763458 1 0 1 1 0 0 +EDGE2 8560 1121 0.0189906 0.987073 1.55165 1 0 1 1 0 0 +EDGE2 8560 3041 0.0592881 0.979012 1.5281 1 0 1 1 0 0 +EDGE2 8560 5781 0.00355937 0.998978 1.55362 1 0 1 1 0 0 +EDGE2 8560 5801 0.0526202 1.00464 1.58713 1 0 1 1 0 0 +EDGE2 8560 1141 -0.011527 0.994682 1.61499 1 0 1 1 0 0 +EDGE2 8560 1101 0.0250657 1.02785 1.578 1 0 1 1 0 0 +EDGE2 8560 5800 -0.0281613 0.04835 0.0316391 1 0 1 1 0 0 +EDGE2 8560 1100 0.0921456 0.0695683 0.017438 1 0 1 1 0 0 +EDGE2 8560 1140 -0.0241719 0.0638849 0.0150068 1 0 1 1 0 0 +EDGE2 8560 3040 0.0456759 -0.0417441 -0.00105114 1 0 1 1 0 0 +EDGE2 8560 5660 -0.0288081 -0.0192965 -3.16563 1 0 1 1 0 0 +EDGE2 8560 1120 -0.0734502 0.0657509 0.0213851 1 0 1 1 0 0 +EDGE2 8560 5661 0.0262121 -1.0325 -1.57454 1 0 1 1 0 0 +EDGE2 8560 5659 1.07018 0.0711309 -3.17642 1 0 1 1 0 0 +EDGE2 8560 5779 0.996523 0.0484331 -3.16122 1 0 1 1 0 0 +EDGE2 8561 5780 -0.964306 -0.005016 1.59933 1 0 1 1 0 0 +EDGE2 8561 3042 0.902462 0.0346429 0.00522305 1 0 1 1 0 0 +EDGE2 8561 5802 1.10594 0.088055 -0.0179437 1 0 1 1 0 0 +EDGE2 8561 5782 0.987611 0.0871572 0.0301796 1 0 1 1 0 0 +EDGE2 8561 1102 0.958741 -0.00182703 -0.00881996 1 0 1 1 0 0 +EDGE2 8561 1122 1.01334 -0.0295706 -0.0103057 1 0 1 1 0 0 +EDGE2 8561 1142 1.08001 0.112232 -0.00578742 1 0 1 1 0 0 +EDGE2 8561 1121 0.0343925 -0.0600783 0.015909 1 0 1 1 0 0 +EDGE2 8561 3041 0.0485805 -0.071739 -0.0498288 1 0 1 1 0 0 +EDGE2 8561 5781 -0.0327371 -0.00726107 0.0052218 1 0 1 1 0 0 +EDGE2 8561 5801 0.0254973 -0.00528934 -0.00281491 1 0 1 1 0 0 +EDGE2 8561 1141 0.0509195 -0.0614355 0.0149213 1 0 1 1 0 0 +EDGE2 8561 8560 -0.972433 0.0369116 -1.54123 1 0 1 1 0 0 +EDGE2 8561 1101 0.0251062 -0.000451556 0.00360081 1 0 1 1 0 0 +EDGE2 8561 5800 -1.00442 0.0460755 -1.56895 1 0 1 1 0 0 +EDGE2 8561 1100 -0.894562 -0.0559412 -1.59236 1 0 1 1 0 0 +EDGE2 8561 1140 -1.01354 -0.0188656 -1.57063 1 0 1 1 0 0 +EDGE2 8561 3040 -0.975305 -0.015569 -1.557 1 0 1 1 0 0 +EDGE2 8561 5660 -1.09088 -0.0199095 1.56498 1 0 1 1 0 0 +EDGE2 8561 1120 -0.97879 -0.0289009 -1.55454 1 0 1 1 0 0 +EDGE2 8562 1123 1.05211 0.049987 0.0052287 1 0 1 1 0 0 +EDGE2 8562 3043 1.12791 -0.0216964 0.00975291 1 0 1 1 0 0 +EDGE2 8562 5783 1.04673 0.0959645 0.0135681 1 0 1 1 0 0 +EDGE2 8562 5803 1.05713 -0.084653 0.0180248 1 0 1 1 0 0 +EDGE2 8562 1143 0.956886 0.01996 0.0194334 1 0 1 1 0 0 +EDGE2 8562 8561 -0.917036 0.0708259 -0.00203222 1 0 1 1 0 0 +EDGE2 8562 3042 -0.0430289 -0.0491576 0.0204983 1 0 1 1 0 0 +EDGE2 8562 5802 0.0226029 0.048418 -0.0091113 1 0 1 1 0 0 +EDGE2 8562 1103 0.974915 0.0295329 0.0272728 1 0 1 1 0 0 +EDGE2 8562 5782 -0.0512208 -0.0267614 0.0183358 1 0 1 1 0 0 +EDGE2 8562 1102 -0.0320942 0.0643087 0.0202948 1 0 1 1 0 0 +EDGE2 8562 1122 -0.00110776 -0.0267702 0.00701706 1 0 1 1 0 0 +EDGE2 8562 1142 -0.00968832 -0.0384591 -0.00516739 1 0 1 1 0 0 +EDGE2 8562 1121 -1.00475 -0.0129127 -0.0302535 1 0 1 1 0 0 +EDGE2 8562 3041 -1.18397 -0.066903 -0.00148529 1 0 1 1 0 0 +EDGE2 8562 5781 -1.08529 0.0567864 0.0207632 1 0 1 1 0 0 +EDGE2 8562 5801 -1.00727 -0.0204952 -0.0260053 1 0 1 1 0 0 +EDGE2 8562 1141 -1.03981 0.0170262 0.00814726 1 0 1 1 0 0 +EDGE2 8562 1101 -1.03711 -0.00230537 -0.0155251 1 0 1 1 0 0 +EDGE2 8563 1123 0.0156966 -0.0637656 -0.0136306 1 0 1 1 0 0 +EDGE2 8563 5784 1.04306 -0.0637162 -0.00225014 1 0 1 1 0 0 +EDGE2 8563 5804 0.951069 0.00876476 -0.0116055 1 0 1 1 0 0 +EDGE2 8563 1124 0.915487 0.0450759 0.00518138 1 0 1 1 0 0 +EDGE2 8563 1144 1.0163 0.0903808 -0.0306 1 0 1 1 0 0 +EDGE2 8563 3044 1.03136 0.0422556 -0.0190416 1 0 1 1 0 0 +EDGE2 8563 1104 0.965409 -0.0782994 -0.0144675 1 0 1 1 0 0 +EDGE2 8563 3043 0.0263091 0.0403863 0.00611275 1 0 1 1 0 0 +EDGE2 8563 5783 -0.0995715 0.039612 -0.00337832 1 0 1 1 0 0 +EDGE2 8563 5803 -0.00631308 0.0845932 0.0188831 1 0 1 1 0 0 +EDGE2 8563 1143 -0.0870871 0.0776488 -0.008824 1 0 1 1 0 0 +EDGE2 8563 3042 -1.01501 -0.024602 -0.0129368 1 0 1 1 0 0 +EDGE2 8563 5802 -1.0261 -0.00463978 -0.0188963 1 0 1 1 0 0 +EDGE2 8563 8562 -0.973833 0.00457665 0.0420642 1 0 1 1 0 0 +EDGE2 8563 1103 0.00622222 -0.0480168 -0.0307691 1 0 1 1 0 0 +EDGE2 8563 5782 -0.968775 0.0276422 -0.0126491 1 0 1 1 0 0 +EDGE2 8563 1102 -0.986474 -0.0158688 0.0217605 1 0 1 1 0 0 +EDGE2 8563 1122 -1.00698 -0.0826248 -0.00241408 1 0 1 1 0 0 +EDGE2 8563 1142 -0.977974 0.06953 -0.013499 1 0 1 1 0 0 +EDGE2 8564 5805 0.991566 -0.0433697 0.0250305 1 0 1 1 0 0 +EDGE2 8564 8545 0.970385 0.017268 -3.1217 1 0 1 1 0 0 +EDGE2 8564 1123 -0.891002 -0.0792577 0.0288352 1 0 1 1 0 0 +EDGE2 8564 5784 -0.00302025 0.093085 -0.0329032 1 0 1 1 0 0 +EDGE2 8564 1145 1.00533 0.0121962 0.0184158 1 0 1 1 0 0 +EDGE2 8564 3045 0.978223 0.0876204 0.00350297 1 0 1 1 0 0 +EDGE2 8564 3505 0.978532 -0.0056958 -3.16918 1 0 1 1 0 0 +EDGE2 8564 5785 1.0443 0.0701784 0.0314739 1 0 1 1 0 0 +EDGE2 8564 3025 1.08941 0.00332277 -3.10251 1 0 1 1 0 0 +EDGE2 8564 1105 1.00188 -0.00394369 0.0032284 1 0 1 1 0 0 +EDGE2 8564 1125 1.05428 0.0569528 -0.0137437 1 0 1 1 0 0 +EDGE2 8564 5804 -0.128755 -0.0162723 0.0216746 1 0 1 1 0 0 +EDGE2 8564 8563 -0.956562 0.0475169 -0.0431674 1 0 1 1 0 0 +EDGE2 8564 1124 0.00369722 -0.0537613 -0.0256537 1 0 1 1 0 0 +EDGE2 8564 1144 -0.0253125 -0.051172 -0.011763 1 0 1 1 0 0 +EDGE2 8564 3044 -0.00278229 -0.0832919 -0.033347 1 0 1 1 0 0 +EDGE2 8564 1104 -0.0206417 0.0790191 0.0170628 1 0 1 1 0 0 +EDGE2 8564 3043 -0.945732 -0.0150561 -0.0187557 1 0 1 1 0 0 +EDGE2 8564 5783 -0.916094 -0.0606868 -0.00215197 1 0 1 1 0 0 +EDGE2 8564 5803 -0.949752 -0.0401753 -0.00662248 1 0 1 1 0 0 +EDGE2 8564 1143 -1.0722 0.00489902 -0.0295269 1 0 1 1 0 0 +EDGE2 8564 1103 -0.935961 -0.0243723 -0.0289954 1 0 1 1 0 0 +EDGE2 8565 3504 0.943206 0.0555503 -3.15552 1 0 1 1 0 0 +EDGE2 8565 8544 0.953755 -0.00884781 -3.12179 1 0 1 1 0 0 +EDGE2 8565 3024 1.03601 -0.0477658 -3.1209 1 0 1 1 0 0 +EDGE2 8565 5805 -0.0013825 -0.0512123 0.0330344 1 0 1 1 0 0 +EDGE2 8565 3046 0.0221577 1.1023 1.54745 1 0 1 1 0 0 +EDGE2 8565 5806 -0.0552222 0.998299 1.54637 1 0 1 1 0 0 +EDGE2 8565 8546 -0.0338603 0.956252 1.59062 1 0 1 1 0 0 +EDGE2 8565 5786 -0.0646192 1.08861 1.58111 1 0 1 1 0 0 +EDGE2 8565 1126 0.0241836 1.01981 1.56991 1 0 1 1 0 0 +EDGE2 8565 1146 -0.0832888 0.952976 1.57602 1 0 1 1 0 0 +EDGE2 8565 3026 0.00433654 0.983269 1.55874 1 0 1 1 0 0 +EDGE2 8565 1106 -0.0219723 0.959627 1.56998 1 0 1 1 0 0 +EDGE2 8565 8545 0.0319945 0.0479018 -3.17444 1 0 1 1 0 0 +EDGE2 8565 5784 -0.962738 -0.0438261 0.0226417 1 0 1 1 0 0 +EDGE2 8565 1145 -0.0043139 0.0162808 0.0105171 1 0 1 1 0 0 +EDGE2 8565 3045 0.0268434 -0.0659611 0.0233293 1 0 1 1 0 0 +EDGE2 8565 3505 -0.0409379 -0.0116621 -3.12782 1 0 1 1 0 0 +EDGE2 8565 5785 0.0529929 -0.0198551 0.0394528 1 0 1 1 0 0 +EDGE2 8565 3025 0.0322142 0.0422557 -3.16023 1 0 1 1 0 0 +EDGE2 8565 8564 -1.06296 0.0330357 -0.0041127 1 0 1 1 0 0 +EDGE2 8565 1105 0.0129297 0.0339609 -0.00171382 1 0 1 1 0 0 +EDGE2 8565 1125 -0.020462 0.0515593 -0.00471971 1 0 1 1 0 0 +EDGE2 8565 5804 -1.09767 -0.0215392 0.00661523 1 0 1 1 0 0 +EDGE2 8565 1124 -0.999679 -0.0371649 0.0141077 1 0 1 1 0 0 +EDGE2 8565 1144 -1.04152 0.00330901 0.0114369 1 0 1 1 0 0 +EDGE2 8565 3044 -0.9521 -0.0749598 -0.021947 1 0 1 1 0 0 +EDGE2 8565 1104 -1.0263 0.0273272 0.0197987 1 0 1 1 0 0 +EDGE2 8565 3506 0.0480522 -0.962018 -1.57504 1 0 1 1 0 0 +EDGE2 8566 3027 0.970378 -0.0204859 -0.0117902 1 0 1 1 0 0 +EDGE2 8566 8547 1.02324 0.0052245 0.0115826 1 0 1 1 0 0 +EDGE2 8566 5787 0.955712 -0.0424752 0.0105307 1 0 1 1 0 0 +EDGE2 8566 5807 1.06012 -0.105438 0.00607127 1 0 1 1 0 0 +EDGE2 8566 3047 0.987225 0.00627324 0.0101971 1 0 1 1 0 0 +EDGE2 8566 5805 -0.968684 0.00542123 -1.56385 1 0 1 1 0 0 +EDGE2 8566 1127 0.977477 0.0859862 0.0015623 1 0 1 1 0 0 +EDGE2 8566 1147 1.0053 0.041206 -0.0174698 1 0 1 1 0 0 +EDGE2 8566 1107 0.992778 0.0140714 -0.0191068 1 0 1 1 0 0 +EDGE2 8566 8565 -1.00197 -0.00487857 -1.58179 1 0 1 1 0 0 +EDGE2 8566 3046 -0.0353845 -0.0612733 0.0230404 1 0 1 1 0 0 +EDGE2 8566 5806 -0.00439125 -0.0371708 0.00251826 1 0 1 1 0 0 +EDGE2 8566 8546 0.0275617 0.00611039 -0.00230922 1 0 1 1 0 0 +EDGE2 8566 5786 0.0213663 0.0113797 0.008572 1 0 1 1 0 0 +EDGE2 8566 1126 -0.00148746 -0.0237678 0.00204816 1 0 1 1 0 0 +EDGE2 8566 1146 -0.0445113 0.0266087 0.0212009 1 0 1 1 0 0 +EDGE2 8566 3026 -0.0438295 0.0759972 -0.0156514 1 0 1 1 0 0 +EDGE2 8566 1106 0.02089 -0.0168438 0.0269429 1 0 1 1 0 0 +EDGE2 8566 8545 -0.971922 -0.133526 1.57937 1 0 1 1 0 0 +EDGE2 8566 1145 -0.96977 -0.0530933 -1.56411 1 0 1 1 0 0 +EDGE2 8566 3045 -1.00415 0.00799119 -1.59452 1 0 1 1 0 0 +EDGE2 8566 3505 -1.04435 -0.0174256 1.57945 1 0 1 1 0 0 +EDGE2 8566 5785 -0.955515 -0.0311456 -1.56093 1 0 1 1 0 0 +EDGE2 8566 3025 -0.9763 -0.021461 1.54815 1 0 1 1 0 0 +EDGE2 8566 1105 -0.973467 0.115391 -1.55784 1 0 1 1 0 0 +EDGE2 8566 1125 -1.0289 -0.057838 -1.57076 1 0 1 1 0 0 +EDGE2 8567 3027 0.0274776 0.0392703 -0.00180233 1 0 1 1 0 0 +EDGE2 8567 3048 0.93361 0.0640328 0.0196503 1 0 1 1 0 0 +EDGE2 8567 5808 1.04002 0.0753603 0.000215974 1 0 1 1 0 0 +EDGE2 8567 8548 0.96829 0.0118653 0.0126562 1 0 1 1 0 0 +EDGE2 8567 5788 0.964899 -0.0549778 0.0147657 1 0 1 1 0 0 +EDGE2 8567 3028 1.06126 0.0878154 -0.0047951 1 0 1 1 0 0 +EDGE2 8567 8547 0.0621455 -0.0357261 -0.00169978 1 0 1 1 0 0 +EDGE2 8567 1108 0.919669 -0.0381528 -0.0147556 1 0 1 1 0 0 +EDGE2 8567 1128 0.899241 0.03086 -0.0237384 1 0 1 1 0 0 +EDGE2 8567 1148 1.05303 -0.00175251 0.0329052 1 0 1 1 0 0 +EDGE2 8567 5787 0.0441485 0.0155783 -0.0232438 1 0 1 1 0 0 +EDGE2 8567 5807 -0.0543764 0.00364144 0.00571249 1 0 1 1 0 0 +EDGE2 8567 3047 -0.0685559 -0.032819 -0.00391283 1 0 1 1 0 0 +EDGE2 8567 1127 -0.0569358 -0.0187297 0.00732713 1 0 1 1 0 0 +EDGE2 8567 1147 -0.00106696 0.0188566 0.00848572 1 0 1 1 0 0 +EDGE2 8567 1107 -0.0413356 0.0596183 -0.000842325 1 0 1 1 0 0 +EDGE2 8567 3046 -0.881667 -0.0456372 -0.0215181 1 0 1 1 0 0 +EDGE2 8567 5806 -1.02898 0.0573894 0.00745786 1 0 1 1 0 0 +EDGE2 8567 8546 -1.01926 -0.0165016 0.0124477 1 0 1 1 0 0 +EDGE2 8567 8566 -1.00094 0.0245632 0.0345289 1 0 1 1 0 0 +EDGE2 8567 5786 -0.98544 0.0138172 -0.0117942 1 0 1 1 0 0 +EDGE2 8567 1126 -1.00154 0.00821445 -0.0071707 1 0 1 1 0 0 +EDGE2 8567 1146 -1.04516 -0.0278554 -0.0020595 1 0 1 1 0 0 +EDGE2 8567 3026 -0.923578 -0.0333645 0.0204963 1 0 1 1 0 0 +EDGE2 8567 1106 -0.977656 0.0498244 -0.0104648 1 0 1 1 0 0 +EDGE2 8568 3027 -0.974793 0.0421167 -0.0031362 1 0 1 1 0 0 +EDGE2 8568 3048 0.00042496 -0.0494394 0.00982023 1 0 1 1 0 0 +EDGE2 8568 5789 1.01198 -0.0027497 -0.015804 1 0 1 1 0 0 +EDGE2 8568 8549 1.00712 -0.0251401 0.0353796 1 0 1 1 0 0 +EDGE2 8568 5809 1.00829 -0.0744874 -0.00599124 1 0 1 1 0 0 +EDGE2 8568 1109 0.98055 -0.00935898 -0.00965923 1 0 1 1 0 0 +EDGE2 8568 1149 0.983412 0.0514853 -0.0208584 1 0 1 1 0 0 +EDGE2 8568 3029 0.995671 0.0445476 0.0263965 1 0 1 1 0 0 +EDGE2 8568 3049 0.985312 0.0681573 0.00300435 1 0 1 1 0 0 +EDGE2 8568 1129 1.00954 0.0267633 0.0234286 1 0 1 1 0 0 +EDGE2 8568 5808 -0.0891336 0.037175 0.0179385 1 0 1 1 0 0 +EDGE2 8568 8548 -0.0070591 -0.045214 0.017617 1 0 1 1 0 0 +EDGE2 8568 5788 -0.0329847 0.000609831 -0.0156293 1 0 1 1 0 0 +EDGE2 8568 3028 -0.00313264 0.0372822 0.0156312 1 0 1 1 0 0 +EDGE2 8568 8547 -0.97975 -0.00211153 -0.0273011 1 0 1 1 0 0 +EDGE2 8568 1108 0.0934677 0.0172875 -0.00891871 1 0 1 1 0 0 +EDGE2 8568 1128 0.054634 0.0236895 -0.00877989 1 0 1 1 0 0 +EDGE2 8568 1148 0.0448052 -0.0861968 -0.00243962 1 0 1 1 0 0 +EDGE2 8568 8567 -1.01879 -0.0401251 0.0241288 1 0 1 1 0 0 +EDGE2 8568 5787 -1.02905 0.0464749 0.00542063 1 0 1 1 0 0 +EDGE2 8568 5807 -1.01265 0.0275694 -0.0235452 1 0 1 1 0 0 +EDGE2 8568 3047 -0.98229 0.0526238 0.0362833 1 0 1 1 0 0 +EDGE2 8568 1127 -0.965522 0.0704072 0.0193477 1 0 1 1 0 0 +EDGE2 8568 1147 -1.06609 -0.0163008 -0.0275528 1 0 1 1 0 0 +EDGE2 8568 1107 -0.958277 -0.0517303 -0.049876 1 0 1 1 0 0 +EDGE2 8569 3050 1.00947 0.0493102 -0.00347696 1 0 1 1 0 0 +EDGE2 8569 5850 0.960821 0.0846592 -3.1285 1 0 1 1 0 0 +EDGE2 8569 8490 1.04742 -0.0515638 -3.13541 1 0 1 1 0 0 +EDGE2 8569 8550 0.905423 -0.000790341 0.0220954 1 0 1 1 0 0 +EDGE2 8569 8390 0.972936 0.040279 -3.17194 1 0 1 1 0 0 +EDGE2 8569 3170 0.918359 0.0546959 -3.14672 1 0 1 1 0 0 +EDGE2 8569 5790 0.979597 0.0368806 0.0173837 1 0 1 1 0 0 +EDGE2 8569 5810 0.931134 0.0332899 -0.0189152 1 0 1 1 0 0 +EDGE2 8569 5830 1.00605 0.0193518 -3.14316 1 0 1 1 0 0 +EDGE2 8569 3490 1.00326 0.105519 -3.14852 1 0 1 1 0 0 +EDGE2 8569 3110 1.07313 -0.0201055 -3.11433 1 0 1 1 0 0 +EDGE2 8569 3130 1.05221 -0.0116489 -3.13616 1 0 1 1 0 0 +EDGE2 8569 3090 0.970599 -0.0227928 -3.12051 1 0 1 1 0 0 +EDGE2 8569 3048 -0.961689 0.0667626 -0.0156875 1 0 1 1 0 0 +EDGE2 8569 5789 -0.0458933 -0.0339875 0.0149738 1 0 1 1 0 0 +EDGE2 8569 1130 1.02604 0.00352189 1.97455e-05 1 0 1 1 0 0 +EDGE2 8569 1170 0.961581 -0.021288 -3.14258 1 0 1 1 0 0 +EDGE2 8569 1190 0.958252 -0.04698 -3.1618 1 0 1 1 0 0 +EDGE2 8569 3030 0.95575 -0.0444885 0.00834061 1 0 1 1 0 0 +EDGE2 8569 1150 1.01714 -0.0535254 0.00599714 1 0 1 1 0 0 +EDGE2 8569 8549 -0.0901658 -0.011565 0.00170869 1 0 1 1 0 0 +EDGE2 8569 1110 0.976311 0.0731466 0.0132186 1 0 1 1 0 0 +EDGE2 8569 5809 0.0577275 -0.0183557 0.00106381 1 0 1 1 0 0 +EDGE2 8569 1109 -0.0138384 -0.0722791 -0.00177261 1 0 1 1 0 0 +EDGE2 8569 1149 -0.0164018 -0.0434371 -0.00198148 1 0 1 1 0 0 +EDGE2 8569 3029 -0.00798249 -0.00372346 -0.0200564 1 0 1 1 0 0 +EDGE2 8569 3049 -0.00666976 0.0863783 -0.011914 1 0 1 1 0 0 +EDGE2 8569 1129 -0.041274 0.124613 -0.00215288 1 0 1 1 0 0 +EDGE2 8569 5808 -1.01552 0.132568 -0.020206 1 0 1 1 0 0 +EDGE2 8569 8548 -1.03321 0.0473237 -0.0143855 1 0 1 1 0 0 +EDGE2 8569 8568 -0.911495 -0.0414046 -0.013886 1 0 1 1 0 0 +EDGE2 8569 5788 -1.04809 0.0707754 -0.0050656 1 0 1 1 0 0 +EDGE2 8569 3028 -0.995753 -0.0549443 -0.000272405 1 0 1 1 0 0 +EDGE2 8569 1108 -1.02776 0.0206578 0.00798988 1 0 1 1 0 0 +EDGE2 8569 1128 -1.01927 -0.00754153 0.0295349 1 0 1 1 0 0 +EDGE2 8569 1148 -1.01346 -0.0164949 -0.00754541 1 0 1 1 0 0 +EDGE2 8570 5849 0.929715 -0.0188366 -3.13748 1 0 1 1 0 0 +EDGE2 8570 8489 0.974884 0.0177002 -3.12315 1 0 1 1 0 0 +EDGE2 8570 8389 0.985082 -0.072865 -3.11589 1 0 1 1 0 0 +EDGE2 8570 3109 1.07384 -0.0456077 -3.15208 1 0 1 1 0 0 +EDGE2 8570 3169 1.04122 0.00665254 -3.15509 1 0 1 1 0 0 +EDGE2 8570 3489 0.990937 0.0192521 -3.14644 1 0 1 1 0 0 +EDGE2 8570 5829 0.986124 -0.0880299 -3.15837 1 0 1 1 0 0 +EDGE2 8570 3129 1.07541 0.0061879 -3.15813 1 0 1 1 0 0 +EDGE2 8570 1189 1.01712 -0.0607251 -3.10868 1 0 1 1 0 0 +EDGE2 8570 3089 0.958366 -0.0574811 -3.11146 1 0 1 1 0 0 +EDGE2 8570 1169 1.02697 -0.00125845 -3.14622 1 0 1 1 0 0 +EDGE2 8570 3050 -0.0225021 0.0225792 0.0247633 1 0 1 1 0 0 +EDGE2 8570 3131 0.0368244 -1.07316 -1.62118 1 0 1 1 0 0 +EDGE2 8570 8491 0.0474539 -0.933739 -1.53989 1 0 1 1 0 0 +EDGE2 8570 3491 -0.0251013 -0.967256 -1.51871 1 0 1 1 0 0 +EDGE2 8570 5811 0.00805446 -0.907586 -1.55326 1 0 1 1 0 0 +EDGE2 8570 5831 0.0409766 -1.04038 -1.58114 1 0 1 1 0 0 +EDGE2 8570 3171 0.000799179 -0.981869 -1.56229 1 0 1 1 0 0 +EDGE2 8570 5850 -0.0204564 0.0536974 -3.11403 1 0 1 1 0 0 +EDGE2 8570 1151 -0.0719955 -0.954937 -1.59254 1 0 1 1 0 0 +EDGE2 8570 1191 -0.0190815 -0.957545 -1.57434 1 0 1 1 0 0 +EDGE2 8570 3091 -0.00705219 -1.05122 -1.56105 1 0 1 1 0 0 +EDGE2 8570 3111 0.0458814 -1.02573 -1.64471 1 0 1 1 0 0 +EDGE2 8570 1171 -0.043829 -1.01747 -1.56615 1 0 1 1 0 0 +EDGE2 8570 8490 -0.0856715 -0.044711 -3.08177 1 0 1 1 0 0 +EDGE2 8570 8550 0.0602352 0.0440243 0.0256116 1 0 1 1 0 0 +EDGE2 8570 8390 0.0545483 0.0232192 -3.15792 1 0 1 1 0 0 +EDGE2 8570 3170 0.0401039 -0.0645409 -3.13354 1 0 1 1 0 0 +EDGE2 8570 5790 -0.0140531 -0.00278616 0.0251686 1 0 1 1 0 0 +EDGE2 8570 5810 0.00574496 0.0882116 0.00183216 1 0 1 1 0 0 +EDGE2 8570 5830 0.00818461 -0.0116314 -3.14628 1 0 1 1 0 0 +EDGE2 8570 3490 -0.00400706 -0.012676 -3.14924 1 0 1 1 0 0 +EDGE2 8570 3110 0.0699707 -0.0514848 -3.10818 1 0 1 1 0 0 +EDGE2 8570 3130 0.0172888 -0.0151056 -3.14362 1 0 1 1 0 0 +EDGE2 8570 3090 -0.00385533 0.0427041 -3.12428 1 0 1 1 0 0 +EDGE2 8570 5789 -0.967963 -0.0216264 0.0108251 1 0 1 1 0 0 +EDGE2 8570 1130 -0.0222492 -0.0335822 0.0047008 1 0 1 1 0 0 +EDGE2 8570 1170 -0.0173452 -0.00741291 -3.14593 1 0 1 1 0 0 +EDGE2 8570 1190 0.0507859 0.0503832 -3.16544 1 0 1 1 0 0 +EDGE2 8570 3030 -0.00588426 -0.0835519 0.016368 1 0 1 1 0 0 +EDGE2 8570 1150 -0.0995339 -0.0107476 -0.0415674 1 0 1 1 0 0 +EDGE2 8570 8549 -1.06271 -0.057189 0.000817057 1 0 1 1 0 0 +EDGE2 8570 8569 -1.09013 0.0238131 0.0241011 1 0 1 1 0 0 +EDGE2 8570 1110 -0.0613912 -0.0534074 -0.00141881 1 0 1 1 0 0 +EDGE2 8570 5809 -1.0086 0.0561923 -0.0121084 1 0 1 1 0 0 +EDGE2 8570 1109 -0.870313 0.0542851 0.0157906 1 0 1 1 0 0 +EDGE2 8570 1149 -1.01754 0.0471038 -0.00441102 1 0 1 1 0 0 +EDGE2 8570 3029 -0.966655 0.100776 -0.019506 1 0 1 1 0 0 +EDGE2 8570 3049 -0.964807 0.0120897 -0.00749519 1 0 1 1 0 0 +EDGE2 8570 1129 -0.990033 0.0634439 0.0117207 1 0 1 1 0 0 +EDGE2 8570 5851 0.0470485 1.00878 1.58701 1 0 1 1 0 0 +EDGE2 8570 8551 -0.0799841 1.02353 1.57298 1 0 1 1 0 0 +EDGE2 8570 8391 -0.015953 0.983285 1.5222 1 0 1 1 0 0 +EDGE2 8570 1111 0.105781 0.976971 1.58355 1 0 1 1 0 0 +EDGE2 8570 3031 -0.0711255 0.982709 1.55024 1 0 1 1 0 0 +EDGE2 8570 3051 0.00274997 1.03191 1.5624 1 0 1 1 0 0 +EDGE2 8570 5791 -0.0165505 0.980073 1.59123 1 0 1 1 0 0 +EDGE2 8570 1131 -0.00704516 1.07224 1.57949 1 0 1 1 0 0 +EDGE2 8571 3050 -0.972607 -0.0184297 1.56333 1 0 1 1 0 0 +EDGE2 8571 3131 0.08408 -0.0133704 -0.0250245 1 0 1 1 0 0 +EDGE2 8571 3092 1.08757 0.0182902 0.0107205 1 0 1 1 0 0 +EDGE2 8571 5812 0.963137 0.0411587 0.00023847 1 0 1 1 0 0 +EDGE2 8571 8492 1.07416 -0.0105007 -0.012657 1 0 1 1 0 0 +EDGE2 8571 5832 0.993712 0.0500298 -0.0301579 1 0 1 1 0 0 +EDGE2 8571 3132 1.01655 0.0317516 0.0102566 1 0 1 1 0 0 +EDGE2 8571 3172 0.979923 -0.0532576 0.0306636 1 0 1 1 0 0 +EDGE2 8571 3492 1.03218 0.0974143 -0.0117834 1 0 1 1 0 0 +EDGE2 8571 3112 1.03024 0.110885 -0.00764552 1 0 1 1 0 0 +EDGE2 8571 8491 -0.071247 0.0411459 0.0106092 1 0 1 1 0 0 +EDGE2 8571 1152 0.991292 0.100381 -0.0182203 1 0 1 1 0 0 +EDGE2 8571 1172 1.07373 0.0648099 0.00373748 1 0 1 1 0 0 +EDGE2 8571 1192 0.984463 0.0383009 0.026496 1 0 1 1 0 0 +EDGE2 8571 3491 -0.0143056 0.0228424 -0.0274905 1 0 1 1 0 0 +EDGE2 8571 5811 -0.0115743 -0.00629611 -0.00319673 1 0 1 1 0 0 +EDGE2 8571 5831 0.0558585 0.0645084 -0.00917361 1 0 1 1 0 0 +EDGE2 8571 3171 -0.0585943 0.0392616 0.0433543 1 0 1 1 0 0 +EDGE2 8571 5850 -0.985771 0.0211271 -1.58795 1 0 1 1 0 0 +EDGE2 8571 1151 0.0778166 -0.0568518 -0.0289335 1 0 1 1 0 0 +EDGE2 8571 1191 0.0680629 -0.032453 0.0100807 1 0 1 1 0 0 +EDGE2 8571 3091 -0.0238427 0.0231131 -0.0259531 1 0 1 1 0 0 +EDGE2 8571 3111 0.0052294 -0.0802608 0.0133277 1 0 1 1 0 0 +EDGE2 8571 1171 -0.0160785 -0.111438 -0.0149485 1 0 1 1 0 0 +EDGE2 8571 8490 -1.00793 -0.0543341 -1.57922 1 0 1 1 0 0 +EDGE2 8571 8550 -0.905247 -0.0257169 1.60607 1 0 1 1 0 0 +EDGE2 8571 8570 -0.930645 -0.0276069 1.58077 1 0 1 1 0 0 +EDGE2 8571 8390 -1.00965 -0.0960041 -1.56112 1 0 1 1 0 0 +EDGE2 8571 3170 -1.02383 0.0986252 -1.5863 1 0 1 1 0 0 +EDGE2 8571 5790 -0.99683 -0.00186577 1.57593 1 0 1 1 0 0 +EDGE2 8571 5810 -0.906463 0.0160631 1.55466 1 0 1 1 0 0 +EDGE2 8571 5830 -1.04098 0.0247605 -1.56407 1 0 1 1 0 0 +EDGE2 8571 3490 -1.03178 0.00236575 -1.56977 1 0 1 1 0 0 +EDGE2 8571 3110 -1.01297 -0.0608037 -1.57679 1 0 1 1 0 0 +EDGE2 8571 3130 -0.99565 -0.0808131 -1.57039 1 0 1 1 0 0 +EDGE2 8571 3090 -0.93959 -0.0589965 -1.60381 1 0 1 1 0 0 +EDGE2 8571 1130 -1.10431 0.0564855 1.58568 1 0 1 1 0 0 +EDGE2 8571 1170 -1.08628 -0.0227811 -1.5605 1 0 1 1 0 0 +EDGE2 8571 1190 -1.0423 -0.0390989 -1.58066 1 0 1 1 0 0 +EDGE2 8571 3030 -1.03638 0.025513 1.58062 1 0 1 1 0 0 +EDGE2 8571 1150 -1.07559 -0.010248 1.56152 1 0 1 1 0 0 +EDGE2 8571 1110 -1.00073 0.0355921 1.58294 1 0 1 1 0 0 +EDGE2 8572 1173 0.977285 0.122434 -0.0163474 1 0 1 1 0 0 +EDGE2 8572 8493 1.01268 0.010456 0.0150643 1 0 1 1 0 0 +EDGE2 8572 3133 0.988118 0.110323 -0.00936875 1 0 1 1 0 0 +EDGE2 8572 3493 0.995205 0.0605143 -0.0211393 1 0 1 1 0 0 +EDGE2 8572 5813 1.01742 -0.0126933 0.00481305 1 0 1 1 0 0 +EDGE2 8572 5833 0.963608 0.0557912 0.0264738 1 0 1 1 0 0 +EDGE2 8572 3173 0.956217 -0.00130562 -0.00828276 1 0 1 1 0 0 +EDGE2 8572 3093 0.962414 0.0385597 0.0108794 1 0 1 1 0 0 +EDGE2 8572 3113 1.00028 0.0279878 0.0343633 1 0 1 1 0 0 +EDGE2 8572 1193 1.03045 -0.100094 0.011189 1 0 1 1 0 0 +EDGE2 8572 3131 -0.964792 0.0274823 0.0167199 1 0 1 1 0 0 +EDGE2 8572 3092 -0.00442453 -0.0791745 0.00517176 1 0 1 1 0 0 +EDGE2 8572 5812 0.0726694 -0.0727968 -0.0167432 1 0 1 1 0 0 +EDGE2 8572 8492 -0.0414795 -0.00424307 0.0266136 1 0 1 1 0 0 +EDGE2 8572 1153 1.08723 0.0364614 -0.00264515 1 0 1 1 0 0 +EDGE2 8572 5832 0.0552508 -0.0417031 0.010059 1 0 1 1 0 0 +EDGE2 8572 3132 -0.0322042 0.0660197 0.0234931 1 0 1 1 0 0 +EDGE2 8572 3172 -0.00124371 0.030658 -0.0250885 1 0 1 1 0 0 +EDGE2 8572 3492 -0.0996295 -0.0558916 -0.0455503 1 0 1 1 0 0 +EDGE2 8572 3112 -0.0169391 -0.0626113 0.0227643 1 0 1 1 0 0 +EDGE2 8572 8491 -0.867314 0.00229111 -0.000408445 1 0 1 1 0 0 +EDGE2 8572 1152 0.0106672 -0.0525048 -0.00846778 1 0 1 1 0 0 +EDGE2 8572 1172 -0.00276188 0.0762309 0.0156724 1 0 1 1 0 0 +EDGE2 8572 1192 0.00332893 0.0183372 0.0140538 1 0 1 1 0 0 +EDGE2 8572 8571 -0.962361 0.0028549 -0.0100717 1 0 1 1 0 0 +EDGE2 8572 3491 -1.03975 0.0121881 0.0240732 1 0 1 1 0 0 +EDGE2 8572 5811 -0.921122 0.106349 -0.000824396 1 0 1 1 0 0 +EDGE2 8572 5831 -1.05645 0.0475265 0.0354762 1 0 1 1 0 0 +EDGE2 8572 3171 -1.0319 -0.00747773 -0.00089803 1 0 1 1 0 0 +EDGE2 8572 1151 -0.972331 -0.00670719 0.0113007 1 0 1 1 0 0 +EDGE2 8572 1191 -1.05716 0.03087 -0.0223438 1 0 1 1 0 0 +EDGE2 8572 3091 -1.12915 0.0270653 0.000535863 1 0 1 1 0 0 +EDGE2 8572 3111 -1.02664 0.0193781 -0.0171118 1 0 1 1 0 0 +EDGE2 8572 1171 -0.952103 0.0557575 0.0227362 1 0 1 1 0 0 +EDGE2 8573 1173 -0.115817 -0.0657617 0.0256908 1 0 1 1 0 0 +EDGE2 8573 1174 0.951047 0.042135 -0.00681436 1 0 1 1 0 0 +EDGE2 8573 3174 0.958967 0.0790542 -0.00740837 1 0 1 1 0 0 +EDGE2 8573 5814 0.993038 0.00651821 0.0074069 1 0 1 1 0 0 +EDGE2 8573 5834 1.01019 -0.00603555 -0.0172018 1 0 1 1 0 0 +EDGE2 8573 8494 1.04026 -0.120023 -0.0230374 1 0 1 1 0 0 +EDGE2 8573 3494 1.02952 -0.00567617 0.0368488 1 0 1 1 0 0 +EDGE2 8573 3094 1.031 0.040961 -0.00351798 1 0 1 1 0 0 +EDGE2 8573 3114 1.05383 -0.0685544 -0.000100158 1 0 1 1 0 0 +EDGE2 8573 3134 1.0235 0.0288518 0.0101002 1 0 1 1 0 0 +EDGE2 8573 1194 0.922778 -0.0589279 0.0322524 1 0 1 1 0 0 +EDGE2 8573 8493 -0.0087585 0.0553629 -0.0173807 1 0 1 1 0 0 +EDGE2 8573 1154 0.970505 0.0228191 0.0282326 1 0 1 1 0 0 +EDGE2 8573 3133 0.0181535 -0.0250281 -0.0164052 1 0 1 1 0 0 +EDGE2 8573 3493 -0.0264645 0.10628 0.00424411 1 0 1 1 0 0 +EDGE2 8573 5813 -0.100462 0.0516759 -0.00204446 1 0 1 1 0 0 +EDGE2 8573 5833 0.0504246 -0.140602 0.0331278 1 0 1 1 0 0 +EDGE2 8573 3173 0.00277435 -0.0271602 -0.00602129 1 0 1 1 0 0 +EDGE2 8573 3093 -0.063997 0.0383046 -0.0113964 1 0 1 1 0 0 +EDGE2 8573 3113 -0.107703 0.0266436 0.00534152 1 0 1 1 0 0 +EDGE2 8573 1193 0.0140453 -0.00931854 0.0255473 1 0 1 1 0 0 +EDGE2 8573 3092 -1.03603 0.0235416 0.0129952 1 0 1 1 0 0 +EDGE2 8573 5812 -1.02488 0.082214 -0.00812597 1 0 1 1 0 0 +EDGE2 8573 8492 -1.01593 0.0198177 0.0234202 1 0 1 1 0 0 +EDGE2 8573 8572 -0.951801 -0.00486533 -0.00166864 1 0 1 1 0 0 +EDGE2 8573 1153 -0.0238073 0.0459464 0.0104667 1 0 1 1 0 0 +EDGE2 8573 5832 -1.03128 0.0140258 0.0324245 1 0 1 1 0 0 +EDGE2 8573 3132 -1.0392 0.0071152 -0.0274358 1 0 1 1 0 0 +EDGE2 8573 3172 -0.894812 -0.049089 -0.0271553 1 0 1 1 0 0 +EDGE2 8573 3492 -1.08329 0.0323126 0.0112076 1 0 1 1 0 0 +EDGE2 8573 3112 -1.03642 0.00122331 -0.0135071 1 0 1 1 0 0 +EDGE2 8573 1152 -1.02645 0.0112196 -0.0137982 1 0 1 1 0 0 +EDGE2 8573 1172 -1.10861 -0.0481689 0.00750656 1 0 1 1 0 0 +EDGE2 8573 1192 -1.13793 0.042421 -0.0225672 1 0 1 1 0 0 +EDGE2 8574 3495 1.00095 -0.00914792 -0.0237283 1 0 1 1 0 0 +EDGE2 8574 5835 0.959282 -0.12523 -0.0156952 1 0 1 1 0 0 +EDGE2 8574 8495 0.884192 0.093765 0.00780033 1 0 1 1 0 0 +EDGE2 8574 8515 1.05913 -0.0130802 -3.14251 1 0 1 1 0 0 +EDGE2 8574 5815 0.952283 0.0445215 0.0220422 1 0 1 1 0 0 +EDGE2 8574 1173 -1.00234 0.022384 -0.00245441 1 0 1 1 0 0 +EDGE2 8574 1174 0.0049976 0.0559274 -0.0308221 1 0 1 1 0 0 +EDGE2 8574 3115 1.01798 -0.0117263 -0.000737042 1 0 1 1 0 0 +EDGE2 8574 3175 1.03663 0.0363453 -0.00203816 1 0 1 1 0 0 +EDGE2 8574 3375 0.993105 0.086499 -3.123 1 0 1 1 0 0 +EDGE2 8574 3475 0.967686 0.0292769 -3.12019 1 0 1 1 0 0 +EDGE2 8574 3135 0.98613 -0.0356216 -0.0243116 1 0 1 1 0 0 +EDGE2 8574 1175 1.00125 -0.0589671 -0.00642881 1 0 1 1 0 0 +EDGE2 8574 1195 0.949852 -0.0302248 0.0222162 1 0 1 1 0 0 +EDGE2 8574 3095 0.899918 -0.0197855 0.00522832 1 0 1 1 0 0 +EDGE2 8574 1155 0.922627 0.0625975 0.00894196 1 0 1 1 0 0 +EDGE2 8574 3174 -0.0382137 -0.0633884 -0.0030764 1 0 1 1 0 0 +EDGE2 8574 5814 -0.0237167 0.0632583 -0.000882465 1 0 1 1 0 0 +EDGE2 8574 5834 -0.0666397 -0.0316828 0.015602 1 0 1 1 0 0 +EDGE2 8574 8494 -0.0697448 0.0548531 -0.0210157 1 0 1 1 0 0 +EDGE2 8574 3494 -0.0736675 0.0110037 0.0357135 1 0 1 1 0 0 +EDGE2 8574 3094 0.00340282 -0.0520147 -0.0131072 1 0 1 1 0 0 +EDGE2 8574 3114 0.0198072 0.0031635 0.00406198 1 0 1 1 0 0 +EDGE2 8574 3134 0.125319 0.00385376 -0.0118654 1 0 1 1 0 0 +EDGE2 8574 1194 0.0497429 0.0617806 -0.0210215 1 0 1 1 0 0 +EDGE2 8574 8493 -1.03225 -0.0527328 0.00575449 1 0 1 1 0 0 +EDGE2 8574 8573 -1.10395 0.0464356 -0.00599904 1 0 1 1 0 0 +EDGE2 8574 1154 0.0410301 0.000398798 -0.0154462 1 0 1 1 0 0 +EDGE2 8574 3133 -0.984147 -0.0657121 -0.0270055 1 0 1 1 0 0 +EDGE2 8574 3493 -1.02485 -0.0816726 -0.00576466 1 0 1 1 0 0 +EDGE2 8574 5813 -0.983947 0.0359385 -0.00492021 1 0 1 1 0 0 +EDGE2 8574 5833 -1.03269 -0.0158619 -0.0382008 1 0 1 1 0 0 +EDGE2 8574 3173 -0.989608 0.00418128 0.000222455 1 0 1 1 0 0 +EDGE2 8574 3093 -1.01894 0.0301373 -0.00033035 1 0 1 1 0 0 +EDGE2 8574 3113 -1.00128 -0.0262927 0.0130416 1 0 1 1 0 0 +EDGE2 8574 1193 -1.04872 0.04421 -0.0241699 1 0 1 1 0 0 +EDGE2 8574 1153 -1.01103 -0.0607628 -0.00873569 1 0 1 1 0 0 +EDGE2 8575 3495 0.0358982 0.00137743 -0.00249874 1 0 1 1 0 0 +EDGE2 8575 3474 1.04063 -0.0652102 -3.13969 1 0 1 1 0 0 +EDGE2 8575 8514 1.01791 -0.0767094 -3.15445 1 0 1 1 0 0 +EDGE2 8575 3374 1.02137 -0.0126639 -3.15914 1 0 1 1 0 0 +EDGE2 8575 1196 0.108109 1.03731 1.54835 1 0 1 1 0 0 +EDGE2 8575 3476 0.0383348 0.97921 1.56676 1 0 1 1 0 0 +EDGE2 8575 5836 0.0102327 1.00384 1.60675 1 0 1 1 0 0 +EDGE2 8575 8496 -0.00268785 0.932716 1.53902 1 0 1 1 0 0 +EDGE2 8575 5816 -0.00202847 0.966039 1.57388 1 0 1 1 0 0 +EDGE2 8575 3116 0.0154128 1.04551 1.57485 1 0 1 1 0 0 +EDGE2 8575 3136 0.0151336 0.991064 1.60331 1 0 1 1 0 0 +EDGE2 8575 3376 -0.0363063 0.955233 1.55958 1 0 1 1 0 0 +EDGE2 8575 3096 0.00214388 1.05455 1.58441 1 0 1 1 0 0 +EDGE2 8575 1156 -0.00183622 1.03668 1.53583 1 0 1 1 0 0 +EDGE2 8575 1176 0.0359553 0.891074 1.59857 1 0 1 1 0 0 +EDGE2 8575 5835 -0.0144968 -0.0677555 0.0166668 1 0 1 1 0 0 +EDGE2 8575 8495 0.021836 0.0331153 0.00403732 1 0 1 1 0 0 +EDGE2 8575 8515 0.00860292 -0.014733 -3.14046 1 0 1 1 0 0 +EDGE2 8575 5815 -0.0900499 -0.0646652 0.00750029 1 0 1 1 0 0 +EDGE2 8575 1174 -0.981684 0.0321139 0.0334728 1 0 1 1 0 0 +EDGE2 8575 8574 -0.99681 -0.022391 -0.00641769 1 0 1 1 0 0 +EDGE2 8575 3115 0.0111749 -0.0180021 -0.00157366 1 0 1 1 0 0 +EDGE2 8575 3175 0.114487 0.118166 -0.0135514 1 0 1 1 0 0 +EDGE2 8575 3375 0.00916542 -0.0456931 -3.12308 1 0 1 1 0 0 +EDGE2 8575 3475 0.0155624 0.0134918 -3.12376 1 0 1 1 0 0 +EDGE2 8575 3135 -0.00574465 0.0558422 -0.00814205 1 0 1 1 0 0 +EDGE2 8575 1175 0.0614591 -0.113651 -0.0127469 1 0 1 1 0 0 +EDGE2 8575 1195 0.0777886 0.0572084 0.0294661 1 0 1 1 0 0 +EDGE2 8575 3095 -0.00298917 -0.0229277 -0.0142162 1 0 1 1 0 0 +EDGE2 8575 1155 0.0283276 -0.0360102 0.0260004 1 0 1 1 0 0 +EDGE2 8575 3174 -0.87256 0.00992538 0.0230534 1 0 1 1 0 0 +EDGE2 8575 5814 -0.9418 0.0239555 0.0111468 1 0 1 1 0 0 +EDGE2 8575 5834 -1.00727 -0.00192125 0.0129839 1 0 1 1 0 0 +EDGE2 8575 8494 -1.05131 -0.0321333 -0.000552365 1 0 1 1 0 0 +EDGE2 8575 3494 -0.97977 -0.00142172 -0.0321007 1 0 1 1 0 0 +EDGE2 8575 3094 -0.999935 -0.00899597 -0.00413605 1 0 1 1 0 0 +EDGE2 8575 3114 -0.990582 -0.019603 -0.00416453 1 0 1 1 0 0 +EDGE2 8575 3134 -1.01727 -0.0188404 0.000233397 1 0 1 1 0 0 +EDGE2 8575 1194 -0.994172 -0.0156084 0.0200576 1 0 1 1 0 0 +EDGE2 8575 8516 0.0191853 -0.964099 -1.59297 1 0 1 1 0 0 +EDGE2 8575 1154 -1.03579 -0.0434396 0.0219726 1 0 1 1 0 0 +EDGE2 8575 3176 0.0303274 -0.964121 -1.56857 1 0 1 1 0 0 +EDGE2 8575 3496 0.0408363 -0.921416 -1.59274 1 0 1 1 0 0 +EDGE2 8576 3495 -1.00065 0.00763299 -1.55033 1 0 1 1 0 0 +EDGE2 8576 1197 0.941214 0.0981071 -0.0218187 1 0 1 1 0 0 +EDGE2 8576 3477 1.01871 -0.0795537 0.00302672 1 0 1 1 0 0 +EDGE2 8576 5837 1.00369 0.0744735 0.0172241 1 0 1 1 0 0 +EDGE2 8576 8497 1.00296 0.0780739 0.0357648 1 0 1 1 0 0 +EDGE2 8576 5817 1.04705 0.0533539 0.0127265 1 0 1 1 0 0 +EDGE2 8576 3117 0.988752 0.0314748 -0.0266853 1 0 1 1 0 0 +EDGE2 8576 3137 1.01774 0.00473461 -0.0102502 1 0 1 1 0 0 +EDGE2 8576 3377 0.991023 -0.032872 -0.00350263 1 0 1 1 0 0 +EDGE2 8576 3097 0.967396 -0.0390877 -0.0168083 1 0 1 1 0 0 +EDGE2 8576 1177 0.98996 0.0251357 0.0224551 1 0 1 1 0 0 +EDGE2 8576 1157 0.960648 0.0384357 0.0237552 1 0 1 1 0 0 +EDGE2 8576 1196 -0.0332949 0.0439697 0.014101 1 0 1 1 0 0 +EDGE2 8576 3476 0.0177124 -0.103602 0.0338671 1 0 1 1 0 0 +EDGE2 8576 5836 0.0162578 0.0360497 -0.00336861 1 0 1 1 0 0 +EDGE2 8576 8496 -0.0415836 -0.0960146 -0.00200959 1 0 1 1 0 0 +EDGE2 8576 5816 -0.0417968 0.0111512 -0.0194596 1 0 1 1 0 0 +EDGE2 8576 3116 -0.0692831 -0.0476569 -0.035897 1 0 1 1 0 0 +EDGE2 8576 3136 -0.0209814 0.0156711 -0.00811428 1 0 1 1 0 0 +EDGE2 8576 3376 -0.0189768 -0.0457965 0.00691339 1 0 1 1 0 0 +EDGE2 8576 3096 0.0466742 -0.00470076 -0.0158367 1 0 1 1 0 0 +EDGE2 8576 8575 -0.978283 -0.0348407 -1.59925 1 0 1 1 0 0 +EDGE2 8576 1156 0.013917 -0.0959989 0.0145086 1 0 1 1 0 0 +EDGE2 8576 1176 0.0125977 -0.00252002 -0.0111781 1 0 1 1 0 0 +EDGE2 8576 5835 -1.03555 0.0164813 -1.56103 1 0 1 1 0 0 +EDGE2 8576 8495 -0.950274 0.0726192 -1.53895 1 0 1 1 0 0 +EDGE2 8576 8515 -1.13098 -0.0674212 1.59084 1 0 1 1 0 0 +EDGE2 8576 5815 -1.04189 0.0156427 -1.60381 1 0 1 1 0 0 +EDGE2 8576 3115 -0.948985 -0.0940674 -1.63187 1 0 1 1 0 0 +EDGE2 8576 3175 -0.977612 0.0853183 -1.58624 1 0 1 1 0 0 +EDGE2 8576 3375 -1.07498 0.119375 1.54768 1 0 1 1 0 0 +EDGE2 8576 3475 -1.02025 0.0665508 1.58128 1 0 1 1 0 0 +EDGE2 8576 3135 -0.972097 0.0508577 -1.59757 1 0 1 1 0 0 +EDGE2 8576 1175 -1.01564 0.0951332 -1.56919 1 0 1 1 0 0 +EDGE2 8576 1195 -1.00023 0.00929513 -1.55159 1 0 1 1 0 0 +EDGE2 8576 3095 -0.965954 -0.0107587 -1.5564 1 0 1 1 0 0 +EDGE2 8576 1155 -0.988546 0.0635779 -1.58541 1 0 1 1 0 0 +EDGE2 8577 1197 0.000331197 -0.0249122 -0.0279702 1 0 1 1 0 0 +EDGE2 8577 5818 1.01496 0.0285424 0.0206004 1 0 1 1 0 0 +EDGE2 8577 5838 1.03307 0.0623328 -0.00419573 1 0 1 1 0 0 +EDGE2 8577 8498 1.10116 -0.0981267 0.0146024 1 0 1 1 0 0 +EDGE2 8577 3098 1.01716 0.00764475 0.0194579 1 0 1 1 0 0 +EDGE2 8577 3138 0.969366 0.011964 0.0124308 1 0 1 1 0 0 +EDGE2 8577 3378 1.03297 0.00165724 0.00601911 1 0 1 1 0 0 +EDGE2 8577 3478 0.983542 -0.0346403 0.00924219 1 0 1 1 0 0 +EDGE2 8577 3118 1.03966 -0.119459 -0.002682 1 0 1 1 0 0 +EDGE2 8577 1178 1.07602 0.078048 0.0229665 1 0 1 1 0 0 +EDGE2 8577 1198 1.00344 -0.077575 -0.00614056 1 0 1 1 0 0 +EDGE2 8577 1158 0.956035 0.0634051 -0.0399657 1 0 1 1 0 0 +EDGE2 8577 3477 -0.0013786 -0.0300228 -0.000300197 1 0 1 1 0 0 +EDGE2 8577 5837 0.105001 0.0344627 0.0127931 1 0 1 1 0 0 +EDGE2 8577 8497 -0.0553893 -0.045154 0.00759389 1 0 1 1 0 0 +EDGE2 8577 5817 -0.164153 0.0710378 -0.00740519 1 0 1 1 0 0 +EDGE2 8577 3117 -0.0522096 0.0784556 -0.0129634 1 0 1 1 0 0 +EDGE2 8577 3137 -0.0379991 -0.0290783 0.0135582 1 0 1 1 0 0 +EDGE2 8577 3377 -0.0317046 -0.023748 -0.00355466 1 0 1 1 0 0 +EDGE2 8577 3097 0.0244928 0.0840119 -0.00644605 1 0 1 1 0 0 +EDGE2 8577 1177 -0.00908056 -0.00782178 0.00160331 1 0 1 1 0 0 +EDGE2 8577 1157 -0.0949112 -0.00479084 -0.0485855 1 0 1 1 0 0 +EDGE2 8577 1196 -0.996229 -0.0555855 0.000454664 1 0 1 1 0 0 +EDGE2 8577 3476 -0.974397 0.0212837 0.00150482 1 0 1 1 0 0 +EDGE2 8577 5836 -0.957556 0.0797119 -0.0565578 1 0 1 1 0 0 +EDGE2 8577 8496 -1.0686 0.0517388 0.0389781 1 0 1 1 0 0 +EDGE2 8577 8576 -1.06958 0.080206 -0.00627566 1 0 1 1 0 0 +EDGE2 8577 5816 -0.957907 -0.0321265 -0.02702 1 0 1 1 0 0 +EDGE2 8577 3116 -1.02206 -0.0811107 -0.00773619 1 0 1 1 0 0 +EDGE2 8577 3136 -0.964762 -0.0538283 0.0163603 1 0 1 1 0 0 +EDGE2 8577 3376 -0.95543 0.0248342 -0.0330302 1 0 1 1 0 0 +EDGE2 8577 3096 -1.04325 0.0527816 0.00834914 1 0 1 1 0 0 +EDGE2 8577 1156 -1.0843 0.00839716 0.00169261 1 0 1 1 0 0 +EDGE2 8577 1176 -0.970583 -0.0280075 0.0225055 1 0 1 1 0 0 +EDGE2 8578 1197 -0.996403 0.0910695 0.0246827 1 0 1 1 0 0 +EDGE2 8578 5839 1.00638 0.0416701 -0.0171323 1 0 1 1 0 0 +EDGE2 8578 8499 0.986703 0.117064 0.0195745 1 0 1 1 0 0 +EDGE2 8578 3119 1.04647 0.0467404 0.0300986 1 0 1 1 0 0 +EDGE2 8578 3379 1.01708 -0.0716794 0.00917175 1 0 1 1 0 0 +EDGE2 8578 3479 1.067 -0.0735687 -0.00601124 1 0 1 1 0 0 +EDGE2 8578 5819 0.953139 -0.0472493 0.00395766 1 0 1 1 0 0 +EDGE2 8578 3139 1.1134 -0.0341773 0.0023219 1 0 1 1 0 0 +EDGE2 8578 1179 1.00295 0.0659086 -0.0301704 1 0 1 1 0 0 +EDGE2 8578 1199 1.07073 0.0830627 -0.000142794 1 0 1 1 0 0 +EDGE2 8578 3099 0.979432 -0.00952504 -0.0202448 1 0 1 1 0 0 +EDGE2 8578 1159 1.00203 0.0449484 -0.0299183 1 0 1 1 0 0 +EDGE2 8578 5818 -0.0214049 0.022307 0.0213154 1 0 1 1 0 0 +EDGE2 8578 5838 -0.0312324 0.0453221 -0.00825764 1 0 1 1 0 0 +EDGE2 8578 8498 0.0859149 0.0362767 -0.0487535 1 0 1 1 0 0 +EDGE2 8578 3098 -0.028799 0.0697894 -0.00697214 1 0 1 1 0 0 +EDGE2 8578 3138 0.00549043 -0.0611153 0.0294921 1 0 1 1 0 0 +EDGE2 8578 3378 -0.00427165 0.0156744 0.0190294 1 0 1 1 0 0 +EDGE2 8578 3478 0.00308364 -0.0862274 0.0193619 1 0 1 1 0 0 +EDGE2 8578 3118 -0.0132174 -0.0161602 0.0328016 1 0 1 1 0 0 +EDGE2 8578 1178 0.0894712 -0.127837 -0.0289459 1 0 1 1 0 0 +EDGE2 8578 1198 -0.112624 -0.039991 -0.0214369 1 0 1 1 0 0 +EDGE2 8578 1158 0.0375906 -0.0810504 -0.0262754 1 0 1 1 0 0 +EDGE2 8578 3477 -0.971655 0.106518 -0.0379509 1 0 1 1 0 0 +EDGE2 8578 5837 -1.06386 -0.0124813 0.00457027 1 0 1 1 0 0 +EDGE2 8578 8497 -1.06159 -0.0544124 -0.0286675 1 0 1 1 0 0 +EDGE2 8578 8577 -0.938461 -0.0187266 0.00909864 1 0 1 1 0 0 +EDGE2 8578 5817 -0.967888 0.0665868 -0.0145194 1 0 1 1 0 0 +EDGE2 8578 3117 -0.986301 -0.0102606 -0.025813 1 0 1 1 0 0 +EDGE2 8578 3137 -1.02173 0.00127079 0.0423036 1 0 1 1 0 0 +EDGE2 8578 3377 -1.06209 0.0803724 0.00388896 1 0 1 1 0 0 +EDGE2 8578 3097 -1.0256 -0.0411177 0.00636821 1 0 1 1 0 0 +EDGE2 8578 1177 -0.984246 0.0125055 -0.0118579 1 0 1 1 0 0 +EDGE2 8578 1157 -0.974101 -0.0414529 -0.0112788 1 0 1 1 0 0 +EDGE2 8579 5820 1.04728 0.0325222 0.0105939 1 0 1 1 0 0 +EDGE2 8579 8500 1.11649 -0.124303 -0.0166812 1 0 1 1 0 0 +EDGE2 8579 5840 0.935456 -0.0565033 -0.0294861 1 0 1 1 0 0 +EDGE2 8579 1160 0.980286 -0.0408745 -0.00487202 1 0 1 1 0 0 +EDGE2 8579 3140 1.06265 0.0634771 0.0163338 1 0 1 1 0 0 +EDGE2 8579 3420 0.975727 -0.00999801 -3.12691 1 0 1 1 0 0 +EDGE2 8579 3440 1.02455 0.00245617 -3.12988 1 0 1 1 0 0 +EDGE2 8579 3480 1.06813 0.00558325 0.0138921 1 0 1 1 0 0 +EDGE2 8579 3380 0.985655 -0.0182794 0.0142351 1 0 1 1 0 0 +EDGE2 8579 1200 1.05176 -0.0564598 0.00204817 1 0 1 1 0 0 +EDGE2 8579 3100 1.05819 0.0364911 0.0164837 1 0 1 1 0 0 +EDGE2 8579 3120 0.963073 -0.0439165 0.0118509 1 0 1 1 0 0 +EDGE2 8579 1180 1.00779 -0.0363012 -0.012533 1 0 1 1 0 0 +EDGE2 8579 900 1.03474 -0.0534603 -3.11534 1 0 1 1 0 0 +EDGE2 8579 840 1.03367 0.0172921 -3.11964 1 0 1 1 0 0 +EDGE2 8579 860 0.964265 0.114854 -3.1615 1 0 1 1 0 0 +EDGE2 8579 5839 -0.0120435 -0.0235696 0.0169398 1 0 1 1 0 0 +EDGE2 8579 8499 -0.0263579 -0.0400109 -0.0213159 1 0 1 1 0 0 +EDGE2 8579 3119 -0.017441 0.0243224 0.00517914 1 0 1 1 0 0 +EDGE2 8579 3379 0.0456835 0.0788519 -0.0507567 1 0 1 1 0 0 +EDGE2 8579 3479 -0.00895176 -0.0327235 -0.0073131 1 0 1 1 0 0 +EDGE2 8579 5819 -0.0835911 -0.0388126 -0.0179994 1 0 1 1 0 0 +EDGE2 8579 3139 0.0536575 -0.0677567 0.0180043 1 0 1 1 0 0 +EDGE2 8579 1179 0.0658991 0.0185765 0.0287708 1 0 1 1 0 0 +EDGE2 8579 1199 -0.0132579 0.0182284 -0.0185868 1 0 1 1 0 0 +EDGE2 8579 3099 -0.0798399 0.013802 0.0305843 1 0 1 1 0 0 +EDGE2 8579 1159 -0.0243996 0.00166773 -0.0220808 1 0 1 1 0 0 +EDGE2 8579 5818 -1.0099 0.0484439 -0.0250577 1 0 1 1 0 0 +EDGE2 8579 8578 -1.00955 -0.00591309 0.0128776 1 0 1 1 0 0 +EDGE2 8579 5838 -1.04278 -0.0330561 -0.00956599 1 0 1 1 0 0 +EDGE2 8579 8498 -1.09306 -0.043193 -0.0288293 1 0 1 1 0 0 +EDGE2 8579 3098 -1.02438 0.00399746 0.0150195 1 0 1 1 0 0 +EDGE2 8579 3138 -0.975378 0.0107308 0.0296369 1 0 1 1 0 0 +EDGE2 8579 3378 -0.97192 -0.116136 -0.00988798 1 0 1 1 0 0 +EDGE2 8579 3478 -1.04317 0.11054 0.0266201 1 0 1 1 0 0 +EDGE2 8579 3118 -0.91928 0.02836 0.0296009 1 0 1 1 0 0 +EDGE2 8579 1178 -0.979294 0.0600129 0.0108402 1 0 1 1 0 0 +EDGE2 8579 1198 -0.934355 0.0511521 0.00171708 1 0 1 1 0 0 +EDGE2 8579 1158 -1.01864 -0.0527784 -0.0305694 1 0 1 1 0 0 +EDGE2 8580 5820 0.105901 0.0449146 0.0178012 1 0 1 1 0 0 +EDGE2 8580 839 0.993634 0.0896185 -3.17148 1 0 1 1 0 0 +EDGE2 8580 899 0.922944 0.0278153 -3.13091 1 0 1 1 0 0 +EDGE2 8580 3419 0.960168 -0.0521928 -3.13818 1 0 1 1 0 0 +EDGE2 8580 3439 1.03793 -0.0551245 -3.13868 1 0 1 1 0 0 +EDGE2 8580 859 0.965961 0.0484409 -3.16308 1 0 1 1 0 0 +EDGE2 8580 3441 0.0303107 -0.956746 -1.5829 1 0 1 1 0 0 +EDGE2 8580 8501 0.0751206 -0.974087 -1.62275 1 0 1 1 0 0 +EDGE2 8580 841 -0.0555744 -1.00908 -1.54546 1 0 1 1 0 0 +EDGE2 8580 901 -0.0323767 -1.08128 -1.55998 1 0 1 1 0 0 +EDGE2 8580 1201 -0.0129355 -0.938513 -1.54684 1 0 1 1 0 0 +EDGE2 8580 3421 0.0365888 -1.08735 -1.56585 1 0 1 1 0 0 +EDGE2 8580 861 -0.0164315 -1.07102 -1.55357 1 0 1 1 0 0 +EDGE2 8580 8500 -0.0890739 -0.00294192 -0.0074194 1 0 1 1 0 0 +EDGE2 8580 5840 0.0104883 0.0414022 -0.00471156 1 0 1 1 0 0 +EDGE2 8580 5821 -0.0317627 1.02635 1.57859 1 0 1 1 0 0 +EDGE2 8580 1160 0.00935524 -0.00540538 -0.0168233 1 0 1 1 0 0 +EDGE2 8580 3140 0.0450344 0.0103624 -0.0136679 1 0 1 1 0 0 +EDGE2 8580 3420 -0.0378987 -0.0209393 -3.14825 1 0 1 1 0 0 +EDGE2 8580 3440 0.035608 0.00098112 -3.13074 1 0 1 1 0 0 +EDGE2 8580 3480 0.0752422 0.0474992 -0.00992351 1 0 1 1 0 0 +EDGE2 8580 3380 -0.0486208 0.0320099 -0.0116957 1 0 1 1 0 0 +EDGE2 8580 1200 0.0156326 0.00724343 0.0184854 1 0 1 1 0 0 +EDGE2 8580 3100 0.0351738 0.00533948 0.00572359 1 0 1 1 0 0 +EDGE2 8580 3120 -0.0280528 0.0606434 0.0528953 1 0 1 1 0 0 +EDGE2 8580 1180 -0.0333406 -0.153426 0.0254501 1 0 1 1 0 0 +EDGE2 8580 900 -0.0252808 -0.0475761 -3.17704 1 0 1 1 0 0 +EDGE2 8580 840 -0.010773 -0.0192179 -3.1374 1 0 1 1 0 0 +EDGE2 8580 860 -0.0176155 -0.0645064 -3.14469 1 0 1 1 0 0 +EDGE2 8580 5841 -0.0365352 0.999912 1.56937 1 0 1 1 0 0 +EDGE2 8580 3101 -0.00999684 1.04974 1.55234 1 0 1 1 0 0 +EDGE2 8580 3141 0.0222925 1.02355 1.60634 1 0 1 1 0 0 +EDGE2 8580 3381 -0.017198 1.02313 1.59872 1 0 1 1 0 0 +EDGE2 8580 3481 -0.00233959 0.991135 1.58755 1 0 1 1 0 0 +EDGE2 8580 3121 0.0299693 0.949383 1.56633 1 0 1 1 0 0 +EDGE2 8580 1161 0.0285178 1.11297 1.57167 1 0 1 1 0 0 +EDGE2 8580 1181 0.0821345 0.976012 1.58161 1 0 1 1 0 0 +EDGE2 8580 5839 -1.05136 -0.0129806 -0.000839408 1 0 1 1 0 0 +EDGE2 8580 8499 -0.924408 0.0420674 -0.0330471 1 0 1 1 0 0 +EDGE2 8580 8579 -0.975602 -0.0362715 -0.00374068 1 0 1 1 0 0 +EDGE2 8580 3119 -0.990803 -0.00096625 0.031763 1 0 1 1 0 0 +EDGE2 8580 3379 -0.961893 -0.0732719 0.0148733 1 0 1 1 0 0 +EDGE2 8580 3479 -1.02864 0.0301248 0.0350739 1 0 1 1 0 0 +EDGE2 8580 5819 -0.986554 -0.0161097 -0.0368831 1 0 1 1 0 0 +EDGE2 8580 3139 -0.953438 0.136565 -0.00737814 1 0 1 1 0 0 +EDGE2 8580 1179 -1.00494 0.062338 0.00414538 1 0 1 1 0 0 +EDGE2 8580 1199 -0.94447 0.00577035 0.00973444 1 0 1 1 0 0 +EDGE2 8580 3099 -1.05571 -0.0402343 0.00387775 1 0 1 1 0 0 +EDGE2 8580 1159 -1.01406 0.00406322 -0.0063066 1 0 1 1 0 0 +EDGE2 8581 5820 -0.995686 0.0206346 1.5981 1 0 1 1 0 0 +EDGE2 8581 3441 -0.00743757 0.0678778 0.0156022 1 0 1 1 0 0 +EDGE2 8581 902 1.07684 0.0640485 -0.0103575 1 0 1 1 0 0 +EDGE2 8581 3422 0.965302 -0.0543667 -0.0178992 1 0 1 1 0 0 +EDGE2 8581 3442 0.952713 -0.0599271 -0.0035221 1 0 1 1 0 0 +EDGE2 8581 8502 1.05727 -0.073113 0.00413624 1 0 1 1 0 0 +EDGE2 8581 1202 1.05559 -0.0954068 0.00233773 1 0 1 1 0 0 +EDGE2 8581 842 0.949821 -0.00138352 0.0106135 1 0 1 1 0 0 +EDGE2 8581 862 0.950411 0.0899299 -0.0204941 1 0 1 1 0 0 +EDGE2 8581 8501 0.05699 -0.100027 0.00740996 1 0 1 1 0 0 +EDGE2 8581 841 -0.0555674 -0.0536638 0.0102117 1 0 1 1 0 0 +EDGE2 8581 901 0.0354546 -0.0214002 0.0172242 1 0 1 1 0 0 +EDGE2 8581 1201 0.0341799 -0.0867713 -0.0225953 1 0 1 1 0 0 +EDGE2 8581 3421 -0.0726308 -0.0283918 -0.00118986 1 0 1 1 0 0 +EDGE2 8581 861 -0.0432323 -0.041475 0.0469305 1 0 1 1 0 0 +EDGE2 8581 8500 -0.928728 0.080099 1.55435 1 0 1 1 0 0 +EDGE2 8581 8580 -1.05565 -0.0211566 1.60313 1 0 1 1 0 0 +EDGE2 8581 5840 -1.03636 0.0213406 1.568 1 0 1 1 0 0 +EDGE2 8581 1160 -1.04835 -0.0463085 1.60075 1 0 1 1 0 0 +EDGE2 8581 3140 -0.989902 0.00818853 1.59217 1 0 1 1 0 0 +EDGE2 8581 3420 -0.999501 -0.127653 -1.57315 1 0 1 1 0 0 +EDGE2 8581 3440 -0.958779 -0.031168 -1.56196 1 0 1 1 0 0 +EDGE2 8581 3480 -1.03546 -0.0540221 1.56408 1 0 1 1 0 0 +EDGE2 8581 3380 -0.923836 -0.0065295 1.55932 1 0 1 1 0 0 +EDGE2 8581 1200 -0.990134 0.033399 1.5864 1 0 1 1 0 0 +EDGE2 8581 3100 -1.01018 -0.00180086 1.56367 1 0 1 1 0 0 +EDGE2 8581 3120 -1.04882 -0.0335641 1.5887 1 0 1 1 0 0 +EDGE2 8581 1180 -0.986738 -0.0973981 1.55363 1 0 1 1 0 0 +EDGE2 8581 900 -0.956976 -0.073165 -1.59528 1 0 1 1 0 0 +EDGE2 8581 840 -1.10685 -0.0302012 -1.55537 1 0 1 1 0 0 +EDGE2 8581 860 -0.942863 0.0102865 -1.56414 1 0 1 1 0 0 +EDGE2 8582 3423 1.06456 -0.046184 0.00657937 1 0 1 1 0 0 +EDGE2 8582 8503 1.00865 -0.0448469 -0.055731 1 0 1 1 0 0 +EDGE2 8582 3443 1.01017 0.0766785 0.00275605 1 0 1 1 0 0 +EDGE2 8582 863 0.986038 -0.135468 0.00287298 1 0 1 1 0 0 +EDGE2 8582 903 1.13287 -0.0329702 -0.0249071 1 0 1 1 0 0 +EDGE2 8582 1203 1.00253 -0.0225463 -0.0051631 1 0 1 1 0 0 +EDGE2 8582 843 0.99628 -0.0799428 0.00669335 1 0 1 1 0 0 +EDGE2 8582 3441 -0.958283 -0.139696 -0.0229443 1 0 1 1 0 0 +EDGE2 8582 902 -0.0739188 -0.118166 0.0234183 1 0 1 1 0 0 +EDGE2 8582 3422 -0.0395899 -0.0790188 -0.0214438 1 0 1 1 0 0 +EDGE2 8582 3442 0.018483 -0.116669 0.026441 1 0 1 1 0 0 +EDGE2 8582 8502 0.0153528 0.0411747 -0.00501554 1 0 1 1 0 0 +EDGE2 8582 1202 -0.057027 -0.0964029 -0.00345292 1 0 1 1 0 0 +EDGE2 8582 8581 -1.0365 -0.0257227 0.0161958 1 0 1 1 0 0 +EDGE2 8582 842 -0.0367116 -0.0154626 0.0163945 1 0 1 1 0 0 +EDGE2 8582 862 -0.0741228 0.0193737 0.00317398 1 0 1 1 0 0 +EDGE2 8582 8501 -0.976188 0.0490563 -0.000736964 1 0 1 1 0 0 +EDGE2 8582 841 -1.04277 0.0144775 0.00296093 1 0 1 1 0 0 +EDGE2 8582 901 -1.0272 0.0357266 -0.0397542 1 0 1 1 0 0 +EDGE2 8582 1201 -1.0013 -0.033316 -0.0221152 1 0 1 1 0 0 +EDGE2 8582 3421 -0.969413 -0.0315969 0.0137087 1 0 1 1 0 0 +EDGE2 8582 861 -1.05845 -0.0207855 -0.0357043 1 0 1 1 0 0 +EDGE2 8583 8582 -1.03554 -0.0628024 -0.0434501 1 0 1 1 0 0 +EDGE2 8583 864 0.965678 0.00253794 0.00365263 1 0 1 1 0 0 +EDGE2 8583 8504 1.13471 -0.0179421 0.0272173 1 0 1 1 0 0 +EDGE2 8583 1204 1.03767 -0.0662401 0.00953521 1 0 1 1 0 0 +EDGE2 8583 3424 0.986362 -0.0180526 0.00509146 1 0 1 1 0 0 +EDGE2 8583 3444 1.00083 -0.00653085 0.0209084 1 0 1 1 0 0 +EDGE2 8583 904 0.980669 0.0390316 -0.00193074 1 0 1 1 0 0 +EDGE2 8583 3423 0.0381706 -0.0122052 0.00932339 1 0 1 1 0 0 +EDGE2 8583 8503 -0.0134599 -0.0979853 0.0115497 1 0 1 1 0 0 +EDGE2 8583 844 1.01671 -0.0282493 -0.011062 1 0 1 1 0 0 +EDGE2 8583 3443 -0.0436569 -0.107708 0.017361 1 0 1 1 0 0 +EDGE2 8583 863 0.0416901 0.0170745 -0.0237707 1 0 1 1 0 0 +EDGE2 8583 903 -0.0492543 -0.00645989 0.012137 1 0 1 1 0 0 +EDGE2 8583 1203 0.0667791 -0.0572618 -0.014994 1 0 1 1 0 0 +EDGE2 8583 843 -0.0809854 -0.000963378 -0.0201635 1 0 1 1 0 0 +EDGE2 8583 902 -0.980714 0.0208191 0.0184706 1 0 1 1 0 0 +EDGE2 8583 3422 -1.03852 0.0207149 -0.00573122 1 0 1 1 0 0 +EDGE2 8583 3442 -1.00796 -0.0473562 -0.0268087 1 0 1 1 0 0 +EDGE2 8583 8502 -1.03824 -0.0247895 -0.0019836 1 0 1 1 0 0 +EDGE2 8583 1202 -1.01271 -0.0274461 -0.00712998 1 0 1 1 0 0 +EDGE2 8583 842 -1.02677 -0.0235811 0.014521 1 0 1 1 0 0 +EDGE2 8583 862 -0.985773 -0.0921655 -0.00726552 1 0 1 1 0 0 +EDGE2 8584 8505 0.95064 0.0665003 0.0262906 1 0 1 1 0 0 +EDGE2 8584 865 1.05659 -0.0344544 0.0234379 1 0 1 1 0 0 +EDGE2 8584 3225 0.986736 0.00593604 -3.11716 1 0 1 1 0 0 +EDGE2 8584 3425 0.928243 0.0870495 0.00707135 1 0 1 1 0 0 +EDGE2 8584 3445 0.941995 0.00458319 0.0293703 1 0 1 1 0 0 +EDGE2 8584 3465 0.971887 0.000942245 -3.13139 1 0 1 1 0 0 +EDGE2 8584 3365 1.00237 -0.0327046 -3.15545 1 0 1 1 0 0 +EDGE2 8584 1205 0.947135 -0.0863499 -0.0348979 1 0 1 1 0 0 +EDGE2 8584 3205 0.965745 0.00458541 -3.12687 1 0 1 1 0 0 +EDGE2 8584 905 1.01285 0.122691 0.0217155 1 0 1 1 0 0 +EDGE2 8584 864 -0.0288508 -0.0223898 -0.00240337 1 0 1 1 0 0 +EDGE2 8584 8504 0.0638962 0.0203514 0.0012751 1 0 1 1 0 0 +EDGE2 8584 705 1.05117 0.0380599 -3.1194 1 0 1 1 0 0 +EDGE2 8584 825 1.0076 0.0202185 -3.16754 1 0 1 1 0 0 +EDGE2 8584 845 0.99757 0.0689726 0.00594471 1 0 1 1 0 0 +EDGE2 8584 1204 -0.0142785 0.101887 0.0234118 1 0 1 1 0 0 +EDGE2 8584 3424 0.0475354 0.0587693 -0.0182081 1 0 1 1 0 0 +EDGE2 8584 3444 -0.0683275 -0.0119862 0.00506182 1 0 1 1 0 0 +EDGE2 8584 904 -0.113942 0.0053066 -0.00356095 1 0 1 1 0 0 +EDGE2 8584 3423 -1.0413 -0.0284104 -0.0329492 1 0 1 1 0 0 +EDGE2 8584 8503 -1.0434 -0.0215549 0.0161493 1 0 1 1 0 0 +EDGE2 8584 8583 -1.09394 -0.00972753 -0.00265359 1 0 1 1 0 0 +EDGE2 8584 844 0.00419562 -0.0246039 -0.0264832 1 0 1 1 0 0 +EDGE2 8584 3443 -0.99315 0.0223076 0.0134668 1 0 1 1 0 0 +EDGE2 8584 863 -0.93036 -0.0284983 0.00819313 1 0 1 1 0 0 +EDGE2 8584 903 -0.955923 0.00122628 0.034063 1 0 1 1 0 0 +EDGE2 8584 1203 -0.961512 0.0455208 -0.00869461 1 0 1 1 0 0 +EDGE2 8584 843 -1.03597 -0.0747804 0.01599 1 0 1 1 0 0 +EDGE2 8585 3364 1.01125 -0.0102504 -3.15239 1 0 1 1 0 0 +EDGE2 8585 3464 1.05534 -0.042124 -3.11616 1 0 1 1 0 0 +EDGE2 8585 824 1.00382 -0.00787872 -3.11571 1 0 1 1 0 0 +EDGE2 8585 3204 0.977499 0.0134399 -3.11292 1 0 1 1 0 0 +EDGE2 8585 3224 1.00319 -0.0444561 -3.12621 1 0 1 1 0 0 +EDGE2 8585 704 1.06117 -0.0305637 -3.1451 1 0 1 1 0 0 +EDGE2 8585 8506 0.0597373 -1.02655 -1.55477 1 0 1 1 0 0 +EDGE2 8585 8505 -0.0252972 -0.0203255 0.026747 1 0 1 1 0 0 +EDGE2 8585 865 -0.077158 0.0800323 -0.0242719 1 0 1 1 0 0 +EDGE2 8585 3446 -0.0068447 0.903881 1.54528 1 0 1 1 0 0 +EDGE2 8585 3225 0.0824635 0.0861401 -3.17852 1 0 1 1 0 0 +EDGE2 8585 826 0.0577188 0.896569 1.57731 1 0 1 1 0 0 +EDGE2 8585 866 0.0896444 0.987772 1.54407 1 0 1 1 0 0 +EDGE2 8585 906 0.0394539 1.01681 1.57798 1 0 1 1 0 0 +EDGE2 8585 3426 0.137246 0.988361 1.58856 1 0 1 1 0 0 +EDGE2 8585 846 0.0973101 0.98941 1.57991 1 0 1 1 0 0 +EDGE2 8585 3425 -0.0296946 -0.0883684 -0.00964052 1 0 1 1 0 0 +EDGE2 8585 3445 -0.0308553 0.023834 -0.0140378 1 0 1 1 0 0 +EDGE2 8585 3465 0.016865 -0.0034753 -3.10786 1 0 1 1 0 0 +EDGE2 8585 3365 0.0566891 0.029095 -3.1415 1 0 1 1 0 0 +EDGE2 8585 1205 0.0214911 0.00784549 0.0218403 1 0 1 1 0 0 +EDGE2 8585 3205 0.0438898 0.0215477 -3.10643 1 0 1 1 0 0 +EDGE2 8585 905 0.0498386 0.000823568 -0.0117696 1 0 1 1 0 0 +EDGE2 8585 864 -1.05351 -0.059348 -0.0435381 1 0 1 1 0 0 +EDGE2 8585 8504 -0.942861 0.0457675 -0.0188414 1 0 1 1 0 0 +EDGE2 8585 705 0.0286464 0.0173959 -3.1578 1 0 1 1 0 0 +EDGE2 8585 825 0.117607 0.0535318 -3.13897 1 0 1 1 0 0 +EDGE2 8585 845 0.0666997 -0.0858093 -0.0242756 1 0 1 1 0 0 +EDGE2 8585 8584 -1.02412 0.0241737 -0.00967382 1 0 1 1 0 0 +EDGE2 8585 1204 -0.97056 -0.0833829 0.00143108 1 0 1 1 0 0 +EDGE2 8585 3424 -1.01271 -0.0720683 0.00772423 1 0 1 1 0 0 +EDGE2 8585 3444 -0.978223 -0.00202903 0.0084492 1 0 1 1 0 0 +EDGE2 8585 904 -1.00368 0.0551704 0.012649 1 0 1 1 0 0 +EDGE2 8585 844 -1.05167 -0.0721294 -0.00806628 1 0 1 1 0 0 +EDGE2 8585 1206 0.02466 -1.01991 -1.55316 1 0 1 1 0 0 +EDGE2 8585 3226 0.0323145 -0.985376 -1.5478 1 0 1 1 0 0 +EDGE2 8585 3366 -0.0209749 -1.03071 -1.54912 1 0 1 1 0 0 +EDGE2 8585 3466 -0.021723 -0.911507 -1.58191 1 0 1 1 0 0 +EDGE2 8585 3206 -0.0666679 -1.00289 -1.57305 1 0 1 1 0 0 +EDGE2 8585 706 0.0435734 -0.945719 -1.55905 1 0 1 1 0 0 +EDGE2 8586 8585 -1.03451 0.0226424 -1.61639 1 0 1 1 0 0 +EDGE2 8586 8505 -0.922407 -0.066543 -1.5934 1 0 1 1 0 0 +EDGE2 8586 865 -1.03865 -0.0499047 -1.58201 1 0 1 1 0 0 +EDGE2 8586 3446 0.0871598 -0.0680907 0.00318812 1 0 1 1 0 0 +EDGE2 8586 3427 0.9971 0.0476486 0.0301987 1 0 1 1 0 0 +EDGE2 8586 3447 1.07071 -0.121675 0.011721 1 0 1 1 0 0 +EDGE2 8586 847 1.04758 -0.0714444 -0.0184127 1 0 1 1 0 0 +EDGE2 8586 867 0.986795 0.0095277 0.0220945 1 0 1 1 0 0 +EDGE2 8586 907 1.08818 -0.0151102 0.0250452 1 0 1 1 0 0 +EDGE2 8586 827 1.0345 -0.0259324 0.0102671 1 0 1 1 0 0 +EDGE2 8586 3225 -0.990448 -0.0557106 1.54953 1 0 1 1 0 0 +EDGE2 8586 826 0.0214537 -0.0462575 0.00348505 1 0 1 1 0 0 +EDGE2 8586 866 -0.00732531 -0.00379107 0.0219775 1 0 1 1 0 0 +EDGE2 8586 906 0.000531047 0.0740906 0.0464519 1 0 1 1 0 0 +EDGE2 8586 3426 0.0974696 0.0533631 -0.0348448 1 0 1 1 0 0 +EDGE2 8586 846 0.0403065 0.0210438 -0.0215692 1 0 1 1 0 0 +EDGE2 8586 3425 -0.929219 -0.0422608 -1.54895 1 0 1 1 0 0 +EDGE2 8586 3445 -0.962725 0.0336716 -1.58011 1 0 1 1 0 0 +EDGE2 8586 3465 -0.949373 -0.0852055 1.56199 1 0 1 1 0 0 +EDGE2 8586 3365 -1.03097 -0.0301648 1.55831 1 0 1 1 0 0 +EDGE2 8586 1205 -1.03253 -0.000930108 -1.5819 1 0 1 1 0 0 +EDGE2 8586 3205 -1.00284 -0.035793 1.57897 1 0 1 1 0 0 +EDGE2 8586 905 -0.943819 -0.0116761 -1.56868 1 0 1 1 0 0 +EDGE2 8586 705 -1.02864 -0.0530764 1.57667 1 0 1 1 0 0 +EDGE2 8586 825 -1.00658 -0.0361006 1.56684 1 0 1 1 0 0 +EDGE2 8586 845 -0.91042 -0.0126693 -1.54865 1 0 1 1 0 0 +EDGE2 8587 8586 -1.00967 0.0815568 -0.0088587 1 0 1 1 0 0 +EDGE2 8587 908 0.942283 0.00675747 -0.0306118 1 0 1 1 0 0 +EDGE2 8587 3448 0.955037 -0.0194051 -0.0327066 1 0 1 1 0 0 +EDGE2 8587 3428 0.982612 -0.0162442 0.0060037 1 0 1 1 0 0 +EDGE2 8587 3446 -0.975197 0.0678468 -0.0122772 1 0 1 1 0 0 +EDGE2 8587 3427 0.0350305 -0.00801295 0.00243384 1 0 1 1 0 0 +EDGE2 8587 828 0.942449 -0.0734858 0.00551657 1 0 1 1 0 0 +EDGE2 8587 848 0.962839 0.0401529 0.00827271 1 0 1 1 0 0 +EDGE2 8587 868 0.926758 0.0662003 0.00813438 1 0 1 1 0 0 +EDGE2 8587 3447 -0.0120572 0.0680521 -0.00458561 1 0 1 1 0 0 +EDGE2 8587 847 0.0237246 -0.102739 0.0107229 1 0 1 1 0 0 +EDGE2 8587 867 0.00667901 -0.0584045 0.0117845 1 0 1 1 0 0 +EDGE2 8587 907 0.0047225 -0.0268333 -0.00402278 1 0 1 1 0 0 +EDGE2 8587 827 -0.0457427 -0.0142464 -0.0194013 1 0 1 1 0 0 +EDGE2 8587 826 -0.933315 0.0335149 -0.00939276 1 0 1 1 0 0 +EDGE2 8587 866 -0.990413 0.0224677 -0.0277761 1 0 1 1 0 0 +EDGE2 8587 906 -1.02503 0.0548104 -0.0327976 1 0 1 1 0 0 +EDGE2 8587 3426 -0.939387 -0.0272476 -0.00537962 1 0 1 1 0 0 +EDGE2 8587 846 -1.00365 0.0170797 -0.0268206 1 0 1 1 0 0 +EDGE2 8588 8587 -0.995935 -0.0556471 0.0496873 1 0 1 1 0 0 +EDGE2 8588 908 0.0153575 0.0196575 -0.0299352 1 0 1 1 0 0 +EDGE2 8588 869 1.04462 0.0519392 -0.024845 1 0 1 1 0 0 +EDGE2 8588 3429 1.0237 -0.0318355 0.00401344 1 0 1 1 0 0 +EDGE2 8588 3449 0.898891 -0.0324701 -0.0128213 1 0 1 1 0 0 +EDGE2 8588 909 0.968692 0.0110417 0.00168546 1 0 1 1 0 0 +EDGE2 8588 3448 -0.015765 -0.0420756 0.0144429 1 0 1 1 0 0 +EDGE2 8588 829 1.00229 0.0157165 0.0165317 1 0 1 1 0 0 +EDGE2 8588 849 0.965592 0.0244475 0.00267436 1 0 1 1 0 0 +EDGE2 8588 3428 -0.0285186 0.112771 0.0016069 1 0 1 1 0 0 +EDGE2 8588 3427 -0.99625 -0.0576907 0.020881 1 0 1 1 0 0 +EDGE2 8588 828 0.0110903 -0.0538823 0.000317322 1 0 1 1 0 0 +EDGE2 8588 848 -0.0443182 0.0988413 -0.0254476 1 0 1 1 0 0 +EDGE2 8588 868 -0.0191907 0.0243521 -0.0350192 1 0 1 1 0 0 +EDGE2 8588 3447 -1.03479 -0.0427631 0.0116839 1 0 1 1 0 0 +EDGE2 8588 847 -1.08536 -0.0078966 0.00668404 1 0 1 1 0 0 +EDGE2 8588 867 -1.069 -0.034333 -0.0112512 1 0 1 1 0 0 +EDGE2 8588 907 -1.05687 0.0654805 0.00517791 1 0 1 1 0 0 +EDGE2 8588 827 -0.942431 -0.0217944 -0.00433492 1 0 1 1 0 0 +EDGE2 8589 5990 1.02427 0.0406171 -3.13166 1 0 1 1 0 0 +EDGE2 8589 5950 1.0166 -0.0716145 -3.11868 1 0 1 1 0 0 +EDGE2 8589 5970 1.04166 0.0492817 -3.12898 1 0 1 1 0 0 +EDGE2 8589 8588 -1.04554 -0.0669627 0.0342806 1 0 1 1 0 0 +EDGE2 8589 908 -1.03915 -0.0891778 -0.00141441 1 0 1 1 0 0 +EDGE2 8589 690 1.06757 -0.098729 -3.13216 1 0 1 1 0 0 +EDGE2 8589 910 1.011 0.0856704 0.000235916 1 0 1 1 0 0 +EDGE2 8589 3450 1.04654 -0.0951807 0.0125358 1 0 1 1 0 0 +EDGE2 8589 3430 1.0122 0.052465 -0.00763938 1 0 1 1 0 0 +EDGE2 8589 850 0.944649 0.0205424 0.0370965 1 0 1 1 0 0 +EDGE2 8589 870 0.938737 -0.0898591 -0.0127449 1 0 1 1 0 0 +EDGE2 8589 890 0.982084 -0.0505656 -3.1595 1 0 1 1 0 0 +EDGE2 8589 830 0.984169 0.00221136 -0.023714 1 0 1 1 0 0 +EDGE2 8589 869 -0.0734714 -0.0701531 0.0168647 1 0 1 1 0 0 +EDGE2 8589 3429 -0.0710827 -0.0189481 -0.0218512 1 0 1 1 0 0 +EDGE2 8589 3449 0.0479397 -0.0187987 -0.00837644 1 0 1 1 0 0 +EDGE2 8589 909 0.00527503 0.0527439 -0.0138703 1 0 1 1 0 0 +EDGE2 8589 3448 -0.994277 0.0475824 0.0152021 1 0 1 1 0 0 +EDGE2 8589 829 -0.0825488 -0.0706607 -0.0245587 1 0 1 1 0 0 +EDGE2 8589 849 0.0601716 -0.0325774 -0.0138498 1 0 1 1 0 0 +EDGE2 8589 3428 -1.02053 -0.00132447 -0.00931587 1 0 1 1 0 0 +EDGE2 8589 828 -1.0562 -0.0515699 -0.000973255 1 0 1 1 0 0 +EDGE2 8589 848 -1.06603 -0.0241935 0.0119918 1 0 1 1 0 0 +EDGE2 8589 868 -1.07021 0.0481972 0.0208219 1 0 1 1 0 0 +EDGE2 8590 5951 0.0366092 -1.04224 -1.58798 1 0 1 1 0 0 +EDGE2 8590 5969 0.975851 0.0307885 -3.14071 1 0 1 1 0 0 +EDGE2 8590 5989 0.917445 0.0476957 -3.11189 1 0 1 1 0 0 +EDGE2 8590 5949 0.910237 0.0172739 -3.1546 1 0 1 1 0 0 +EDGE2 8590 5991 -0.00792553 -1.09695 -1.58096 1 0 1 1 0 0 +EDGE2 8590 5971 0.019136 -1.03475 -1.56311 1 0 1 1 0 0 +EDGE2 8590 5990 0.0288584 -0.0100911 -3.14847 1 0 1 1 0 0 +EDGE2 8590 691 -0.01998 -1.06791 -1.55955 1 0 1 1 0 0 +EDGE2 8590 871 0.01213 -1.02981 -1.5859 1 0 1 1 0 0 +EDGE2 8590 3451 -7.34043e-05 -1.03017 -1.58724 1 0 1 1 0 0 +EDGE2 8590 8589 -0.954999 0.0201325 -0.0359613 1 0 1 1 0 0 +EDGE2 8590 5950 -0.0592549 -0.0364123 -3.15029 1 0 1 1 0 0 +EDGE2 8590 5970 0.0781234 0.000109144 -3.15159 1 0 1 1 0 0 +EDGE2 8590 690 0.0157565 0.00778389 -3.12195 1 0 1 1 0 0 +EDGE2 8590 910 0.0224895 0.0536685 -0.0272794 1 0 1 1 0 0 +EDGE2 8590 3450 0.112302 0.00761143 0.0165686 1 0 1 1 0 0 +EDGE2 8590 689 0.997419 -0.104479 -3.14836 1 0 1 1 0 0 +EDGE2 8590 889 1.01447 -0.0540854 -3.1309 1 0 1 1 0 0 +EDGE2 8590 3430 0.12067 -0.0817072 0.00113651 1 0 1 1 0 0 +EDGE2 8590 850 -0.0623319 0.0137835 0.00719275 1 0 1 1 0 0 +EDGE2 8590 870 0.0491291 -0.0342912 0.00355362 1 0 1 1 0 0 +EDGE2 8590 890 0.0378867 0.0442727 -3.16469 1 0 1 1 0 0 +EDGE2 8590 830 -0.0642901 0.0276017 -0.008762 1 0 1 1 0 0 +EDGE2 8590 851 0.00930024 1.02747 1.58556 1 0 1 1 0 0 +EDGE2 8590 911 -0.0104941 0.964557 1.55609 1 0 1 1 0 0 +EDGE2 8590 3431 0.0257533 1.02583 1.56087 1 0 1 1 0 0 +EDGE2 8590 891 0.0389746 1.03098 1.59515 1 0 1 1 0 0 +EDGE2 8590 831 -0.0795159 1.00019 1.58048 1 0 1 1 0 0 +EDGE2 8590 869 -1.09857 0.008781 -0.0159703 1 0 1 1 0 0 +EDGE2 8590 3429 -0.953577 0.0137918 -0.0193687 1 0 1 1 0 0 +EDGE2 8590 3449 -0.935968 -0.0844374 -0.00693459 1 0 1 1 0 0 +EDGE2 8590 909 -1.01173 -0.0535165 -0.00830757 1 0 1 1 0 0 +EDGE2 8590 829 -1.09091 0.0466642 0.00879501 1 0 1 1 0 0 +EDGE2 8590 849 -1.0233 -0.0609136 -0.032869 1 0 1 1 0 0 +EDGE2 8591 5990 -1.01398 0.0136881 1.53879 1 0 1 1 0 0 +EDGE2 8591 8590 -1.08025 -0.0278918 -1.54316 1 0 1 1 0 0 +EDGE2 8591 5950 -1.0078 0.0105714 1.56315 1 0 1 1 0 0 +EDGE2 8591 5970 -1.00316 -0.00633997 1.57034 1 0 1 1 0 0 +EDGE2 8591 690 -0.9467 0.0244661 1.52824 1 0 1 1 0 0 +EDGE2 8591 910 -0.972456 -0.00338812 -1.60191 1 0 1 1 0 0 +EDGE2 8591 3450 -0.979651 0.0464577 -1.56468 1 0 1 1 0 0 +EDGE2 8591 3430 -0.987611 0.0637419 -1.57938 1 0 1 1 0 0 +EDGE2 8591 850 -0.999754 -0.0803965 -1.60162 1 0 1 1 0 0 +EDGE2 8591 870 -1.00732 0.0294806 -1.55762 1 0 1 1 0 0 +EDGE2 8591 890 -1.01202 0.00178057 1.58754 1 0 1 1 0 0 +EDGE2 8591 830 -1.01045 -0.0426689 -1.56266 1 0 1 1 0 0 +EDGE2 8591 892 0.996028 -0.0608897 0.00575313 1 0 1 1 0 0 +EDGE2 8591 851 -0.00825748 0.0520212 0.00734871 1 0 1 1 0 0 +EDGE2 8591 911 0.00508116 0.0088337 0.00353706 1 0 1 1 0 0 +EDGE2 8591 3431 -0.031416 0.00886739 -0.0286634 1 0 1 1 0 0 +EDGE2 8591 891 0.040833 0.0111647 0.00819534 1 0 1 1 0 0 +EDGE2 8591 3432 1.0302 0.0249895 -0.00604994 1 0 1 1 0 0 +EDGE2 8591 831 0.0410281 0.0341696 -0.00043716 1 0 1 1 0 0 +EDGE2 8591 912 0.952987 -0.039487 -0.000713925 1 0 1 1 0 0 +EDGE2 8591 832 0.965542 0.0477926 0.00655082 1 0 1 1 0 0 +EDGE2 8591 852 0.972351 -0.00705069 0.0391355 1 0 1 1 0 0 +EDGE2 8592 892 0.130761 -0.0541609 -0.00663365 1 0 1 1 0 0 +EDGE2 8592 851 -0.999618 0.0959625 -0.0130793 1 0 1 1 0 0 +EDGE2 8592 911 -0.930289 -0.0444992 0.000867495 1 0 1 1 0 0 +EDGE2 8592 3431 -1.06327 -0.00875573 -0.0313195 1 0 1 1 0 0 +EDGE2 8592 8591 -0.956474 0.0102138 -0.0137297 1 0 1 1 0 0 +EDGE2 8592 891 -1.06325 -0.027742 -0.0183976 1 0 1 1 0 0 +EDGE2 8592 3432 0.0198715 0.02627 0.0173836 1 0 1 1 0 0 +EDGE2 8592 831 -1.00753 0.0196633 0.00105927 1 0 1 1 0 0 +EDGE2 8592 912 -0.00607951 -0.0408495 -0.00956011 1 0 1 1 0 0 +EDGE2 8592 913 1.01469 0.0401612 -0.0406138 1 0 1 1 0 0 +EDGE2 8592 832 -0.0238604 0.0111001 -0.0180563 1 0 1 1 0 0 +EDGE2 8592 852 0.0155269 -0.11305 0.00103452 1 0 1 1 0 0 +EDGE2 8592 3433 0.969941 -0.00410475 0.000410945 1 0 1 1 0 0 +EDGE2 8592 833 0.953003 0.0741795 -0.000562527 1 0 1 1 0 0 +EDGE2 8592 853 0.958412 0.0291955 0.000159638 1 0 1 1 0 0 +EDGE2 8592 893 1.02781 -0.0530667 0.00198526 1 0 1 1 0 0 +EDGE2 8593 3434 0.975664 -0.0181012 0.0070425 1 0 1 1 0 0 +EDGE2 8593 892 -1.09732 -0.053289 -0.0151723 1 0 1 1 0 0 +EDGE2 8593 3432 -0.968308 -0.0470342 0.0244051 1 0 1 1 0 0 +EDGE2 8593 8592 -1.0106 -0.0653252 -0.0275412 1 0 1 1 0 0 +EDGE2 8593 912 -0.988204 -0.0965079 0.0329633 1 0 1 1 0 0 +EDGE2 8593 913 -0.0766074 0.00590421 -0.00390251 1 0 1 1 0 0 +EDGE2 8593 832 -1.00162 0.0367833 0.00235231 1 0 1 1 0 0 +EDGE2 8593 852 -1.02345 -0.0733873 -0.00628049 1 0 1 1 0 0 +EDGE2 8593 3433 -0.0139632 0.00785963 -0.00783996 1 0 1 1 0 0 +EDGE2 8593 833 0.0641853 -0.0454201 -0.00818158 1 0 1 1 0 0 +EDGE2 8593 853 -0.0420544 -0.0390243 -0.0320001 1 0 1 1 0 0 +EDGE2 8593 893 -0.0419979 -0.00285137 -0.0403529 1 0 1 1 0 0 +EDGE2 8593 894 0.986883 -0.0294206 0.0114945 1 0 1 1 0 0 +EDGE2 8593 914 1.06226 -0.0359194 0.0236627 1 0 1 1 0 0 +EDGE2 8593 834 1.00832 -0.0525895 -0.00924292 1 0 1 1 0 0 +EDGE2 8593 854 0.979321 -0.00472478 0.00902401 1 0 1 1 0 0 +EDGE2 8594 3395 0.996735 -0.01487 -3.17962 1 0 1 1 0 0 +EDGE2 8594 3434 0.000167588 -0.0134454 0.00158693 1 0 1 1 0 0 +EDGE2 8594 913 -1.04394 0.0131313 0.0395704 1 0 1 1 0 0 +EDGE2 8594 8593 -1.01722 0.0546942 -0.0250064 1 0 1 1 0 0 +EDGE2 8594 3433 -0.926585 0.0162033 0.0185228 1 0 1 1 0 0 +EDGE2 8594 833 -1.04796 -0.0303979 -0.000444787 1 0 1 1 0 0 +EDGE2 8594 853 -0.938419 0.0428923 -0.0113515 1 0 1 1 0 0 +EDGE2 8594 893 -1.00176 -0.0124955 0.0158189 1 0 1 1 0 0 +EDGE2 8594 894 -0.0974603 -0.116381 -0.00348622 1 0 1 1 0 0 +EDGE2 8594 914 -0.0153391 -0.0172822 0.00419328 1 0 1 1 0 0 +EDGE2 8594 8435 1.0269 0.0238255 -3.14039 1 0 1 1 0 0 +EDGE2 8594 834 -0.0120136 -0.00350581 0.00279839 1 0 1 1 0 0 +EDGE2 8594 854 -0.0722644 -0.101782 0.000890816 1 0 1 1 0 0 +EDGE2 8594 3435 0.948693 0.0301533 0.0351734 1 0 1 1 0 0 +EDGE2 8594 5895 0.980254 -0.0777522 -3.13203 1 0 1 1 0 0 +EDGE2 8594 3415 1.00075 -0.0742548 -3.14962 1 0 1 1 0 0 +EDGE2 8594 855 1.00342 -0.063315 -0.000162893 1 0 1 1 0 0 +EDGE2 8594 895 0.929553 -0.0185325 -0.0144336 1 0 1 1 0 0 +EDGE2 8594 915 1.00717 -0.0168281 0.0234621 1 0 1 1 0 0 +EDGE2 8594 835 1.04899 0.0269094 -0.0265446 1 0 1 1 0 0 +EDGE2 8595 3395 -0.0448818 0.0153626 -3.14509 1 0 1 1 0 0 +EDGE2 8595 3396 0.0349622 -0.895739 -1.56168 1 0 1 1 0 0 +EDGE2 8595 5896 -0.0501067 -1.01334 -1.58026 1 0 1 1 0 0 +EDGE2 8595 8436 -0.0210885 -0.972119 -1.60085 1 0 1 1 0 0 +EDGE2 8595 916 -0.0130456 -1.00703 -1.55649 1 0 1 1 0 0 +EDGE2 8595 3434 -1.00928 0.0424677 0.0112674 1 0 1 1 0 0 +EDGE2 8595 8594 -0.921669 -0.00917784 0.0394485 1 0 1 1 0 0 +EDGE2 8595 894 -0.946395 0.0829533 -0.0204823 1 0 1 1 0 0 +EDGE2 8595 914 -0.993007 0.0580142 0.00934508 1 0 1 1 0 0 +EDGE2 8595 8435 -0.0153993 0.0886867 -3.16852 1 0 1 1 0 0 +EDGE2 8595 834 -1.04105 0.0227082 -0.00722525 1 0 1 1 0 0 +EDGE2 8595 854 -1.03397 0.00817387 -0.0115451 1 0 1 1 0 0 +EDGE2 8595 3435 -0.157738 0.0223567 -0.00410604 1 0 1 1 0 0 +EDGE2 8595 5895 -0.0340496 0.0980464 -3.1398 1 0 1 1 0 0 +EDGE2 8595 3415 -0.00428401 0.0137322 -3.11708 1 0 1 1 0 0 +EDGE2 8595 855 -0.0331297 0.0486395 -0.0171273 1 0 1 1 0 0 +EDGE2 8595 895 0.0169848 -0.027523 -0.0224163 1 0 1 1 0 0 +EDGE2 8595 915 -0.0140993 -0.0492046 0.00322135 1 0 1 1 0 0 +EDGE2 8595 835 -0.0322076 -0.0675266 -0.014883 1 0 1 1 0 0 +EDGE2 8595 3414 0.97852 0.0957642 -3.1108 1 0 1 1 0 0 +EDGE2 8595 5894 1.01341 -0.0875474 -3.13769 1 0 1 1 0 0 +EDGE2 8595 8434 1.05651 -0.0200211 -3.13429 1 0 1 1 0 0 +EDGE2 8595 3394 1.01792 0.00328723 -3.14877 1 0 1 1 0 0 +EDGE2 8595 3436 -0.102786 1.01532 1.55516 1 0 1 1 0 0 +EDGE2 8595 856 0.0469997 1.07654 1.57767 1 0 1 1 0 0 +EDGE2 8595 896 -0.031697 1.01356 1.57908 1 0 1 1 0 0 +EDGE2 8595 3416 -0.0921751 1.0292 1.57647 1 0 1 1 0 0 +EDGE2 8595 836 0.0994654 0.965523 1.57339 1 0 1 1 0 0 +EDGE2 8596 3395 -1.00299 0.0408906 -1.53699 1 0 1 1 0 0 +EDGE2 8596 8437 0.992219 -0.0120831 0.00917453 1 0 1 1 0 0 +EDGE2 8596 917 1.01344 0.0348309 0.00614558 1 0 1 1 0 0 +EDGE2 8596 3397 0.90094 0.0806176 -0.00139832 1 0 1 1 0 0 +EDGE2 8596 5897 0.974132 -0.0190167 0.0367195 1 0 1 1 0 0 +EDGE2 8596 3396 -0.0504632 -0.0277325 -0.036342 1 0 1 1 0 0 +EDGE2 8596 5896 -0.0061401 0.103605 -0.00702912 1 0 1 1 0 0 +EDGE2 8596 8436 0.0545496 -0.00800377 0.00941134 1 0 1 1 0 0 +EDGE2 8596 916 0.0115737 -0.0496783 0.0103531 1 0 1 1 0 0 +EDGE2 8596 8435 -1.02473 -0.00641881 -1.55778 1 0 1 1 0 0 +EDGE2 8596 8595 -1.08926 0.0734 1.55014 1 0 1 1 0 0 +EDGE2 8596 3435 -0.975666 0.0653303 1.54266 1 0 1 1 0 0 +EDGE2 8596 5895 -1.01412 -0.00611326 -1.58615 1 0 1 1 0 0 +EDGE2 8596 3415 -1.10607 0.0052081 -1.55301 1 0 1 1 0 0 +EDGE2 8596 855 -0.978831 0.0374433 1.57917 1 0 1 1 0 0 +EDGE2 8596 895 -0.919145 0.0533971 1.5761 1 0 1 1 0 0 +EDGE2 8596 915 -0.969875 0.0561765 1.56238 1 0 1 1 0 0 +EDGE2 8596 835 -1.02651 -0.0511749 1.56339 1 0 1 1 0 0 +EDGE2 8597 8438 0.896709 -0.0171701 0.0163208 1 0 1 1 0 0 +EDGE2 8597 918 1.01681 -0.0276393 0.0326623 1 0 1 1 0 0 +EDGE2 8597 3398 0.979649 0.0843351 -0.00831363 1 0 1 1 0 0 +EDGE2 8597 5898 1.03873 0.0140655 -0.00704568 1 0 1 1 0 0 +EDGE2 8597 8437 0.00857944 -0.0893859 -0.0188969 1 0 1 1 0 0 +EDGE2 8597 8596 -0.97902 0.0120473 0.0037059 1 0 1 1 0 0 +EDGE2 8597 917 -0.0388238 0.0258168 0.0229152 1 0 1 1 0 0 +EDGE2 8597 3397 -0.00127565 -0.0383383 -0.0110803 1 0 1 1 0 0 +EDGE2 8597 5897 0.0461566 0.00532147 -0.00208798 1 0 1 1 0 0 +EDGE2 8597 3396 -0.950911 0.0377701 -0.00624063 1 0 1 1 0 0 +EDGE2 8597 5896 -1.07047 -0.0483448 -0.0482087 1 0 1 1 0 0 +EDGE2 8597 8436 -0.939607 0.00643162 0.00429528 1 0 1 1 0 0 +EDGE2 8597 916 -1.03296 -0.0944963 0.0105438 1 0 1 1 0 0 +EDGE2 8598 8597 -0.945172 0.0227232 -0.000207757 1 0 1 1 0 0 +EDGE2 8598 5899 0.999403 -0.0287502 -0.0087552 1 0 1 1 0 0 +EDGE2 8598 8439 0.932331 -0.0386746 -0.0136164 1 0 1 1 0 0 +EDGE2 8598 8438 -0.0750378 0.0527681 -0.00707541 1 0 1 1 0 0 +EDGE2 8598 919 0.91443 0.0556999 -0.00452011 1 0 1 1 0 0 +EDGE2 8598 3399 0.934519 -0.0341606 -0.035037 1 0 1 1 0 0 +EDGE2 8598 918 0.0439534 -0.0218841 -0.000666214 1 0 1 1 0 0 +EDGE2 8598 3398 -0.0246663 -0.0108459 0.00278787 1 0 1 1 0 0 +EDGE2 8598 5898 0.013541 -0.00344677 0.0326471 1 0 1 1 0 0 +EDGE2 8598 8437 -0.925921 -0.0601155 -0.0113593 1 0 1 1 0 0 +EDGE2 8598 917 -1.01665 0.046805 0.0265101 1 0 1 1 0 0 +EDGE2 8598 3397 -0.96194 0.0691009 0.0154551 1 0 1 1 0 0 +EDGE2 8598 5897 -1.10194 -0.0156352 0.0201704 1 0 1 1 0 0 +EDGE2 8599 5900 0.98509 0.0342666 -0.0291293 1 0 1 1 0 0 +EDGE2 8599 8440 1.07136 0.0377408 0.029392 1 0 1 1 0 0 +EDGE2 8599 920 1.02687 0.0512125 0.0214333 1 0 1 1 0 0 +EDGE2 8599 3400 1.04938 0.0145448 0.0226846 1 0 1 1 0 0 +EDGE2 8599 680 0.985553 0.0527834 -3.12549 1 0 1 1 0 0 +EDGE2 8599 5899 -0.0809409 -0.118744 0.00521372 1 0 1 1 0 0 +EDGE2 8599 8439 -0.0181391 -0.0487762 0.000729139 1 0 1 1 0 0 +EDGE2 8599 8438 -1.05778 0.00589068 -0.0200951 1 0 1 1 0 0 +EDGE2 8599 919 -0.00281995 0.0400076 0.00495281 1 0 1 1 0 0 +EDGE2 8599 3399 -0.0535844 0.0249169 -0.00818835 1 0 1 1 0 0 +EDGE2 8599 8598 -0.96516 -0.0449132 -0.0479818 1 0 1 1 0 0 +EDGE2 8599 918 -0.987906 0.00514718 0.0380054 1 0 1 1 0 0 +EDGE2 8599 3398 -0.942858 0.0331147 0.004457 1 0 1 1 0 0 +EDGE2 8599 5898 -1.07858 -0.0011684 0.0229324 1 0 1 1 0 0 +EDGE2 8600 921 0.0256573 0.979985 1.5733 1 0 1 1 0 0 +EDGE2 8600 679 0.920003 0.0329287 -3.14499 1 0 1 1 0 0 +EDGE2 8600 681 0.012704 -1.12012 -1.58098 1 0 1 1 0 0 +EDGE2 8600 5901 -0.0237041 -0.959457 -1.56862 1 0 1 1 0 0 +EDGE2 8600 5900 0.0808251 -0.00235162 0.0189401 1 0 1 1 0 0 +EDGE2 8600 8440 0.0195978 0.043255 0.0022413 1 0 1 1 0 0 +EDGE2 8600 920 0.0784001 -0.024947 -0.000577032 1 0 1 1 0 0 +EDGE2 8600 3400 -0.0145637 0.0624632 0.0288109 1 0 1 1 0 0 +EDGE2 8600 680 0.0374055 0.0964581 -3.08444 1 0 1 1 0 0 +EDGE2 8600 8441 -0.0967527 0.979043 1.55336 1 0 1 1 0 0 +EDGE2 8600 3401 0.0356555 1.03311 1.5727 1 0 1 1 0 0 +EDGE2 8600 5899 -1.05645 0.0206722 -0.0145666 1 0 1 1 0 0 +EDGE2 8600 8439 -0.990849 -0.0428317 -0.00407527 1 0 1 1 0 0 +EDGE2 8600 8599 -1.02116 -0.0535425 0.00268385 1 0 1 1 0 0 +EDGE2 8600 919 -1.01559 0.0390209 -0.0038962 1 0 1 1 0 0 +EDGE2 8600 3399 -0.943299 0.00671004 -0.00647402 1 0 1 1 0 0 +EDGE2 8601 921 0.0588119 0.0256675 -0.0252705 1 0 1 1 0 0 +EDGE2 8601 5900 -1.00255 -0.0398945 -1.5739 1 0 1 1 0 0 +EDGE2 8601 8600 -1.03054 -0.0339093 -1.57969 1 0 1 1 0 0 +EDGE2 8601 8440 -1.03735 0.0129791 -1.56811 1 0 1 1 0 0 +EDGE2 8601 920 -1.01287 0.0274658 -1.55806 1 0 1 1 0 0 +EDGE2 8601 3400 -1.00025 0.0937684 -1.55044 1 0 1 1 0 0 +EDGE2 8601 680 -0.943671 -0.0471325 1.58596 1 0 1 1 0 0 +EDGE2 8601 8441 0.0294131 -0.0407288 0.0164219 1 0 1 1 0 0 +EDGE2 8601 3401 -0.0482844 0.0119343 -0.00362363 1 0 1 1 0 0 +EDGE2 8601 3402 0.957724 0.0832093 -0.0354503 1 0 1 1 0 0 +EDGE2 8601 8442 0.945223 0.00756315 0.0172772 1 0 1 1 0 0 +EDGE2 8601 922 0.954541 0.00569682 0.0413192 1 0 1 1 0 0 +EDGE2 8602 921 -1.00197 -0.0473455 -0.0159436 1 0 1 1 0 0 +EDGE2 8602 8441 -1.03127 -0.0872769 0.0334385 1 0 1 1 0 0 +EDGE2 8602 8601 -1.15236 0.0617278 0.0359251 1 0 1 1 0 0 +EDGE2 8602 3401 -1.01023 -0.101198 -0.0156934 1 0 1 1 0 0 +EDGE2 8602 3402 -0.00885615 0.0258213 -0.0126001 1 0 1 1 0 0 +EDGE2 8602 8442 0.0555519 -0.019043 0.0444553 1 0 1 1 0 0 +EDGE2 8602 922 -0.0423252 -0.00565503 -0.0100809 1 0 1 1 0 0 +EDGE2 8602 923 0.980725 -0.0349948 0.0843171 1 0 1 1 0 0 +EDGE2 8602 3403 0.992185 0.00616594 0.00917767 1 0 1 1 0 0 +EDGE2 8602 8443 1.07808 -0.00770883 -0.0135376 1 0 1 1 0 0 +EDGE2 8603 8444 0.977436 0.0110909 -0.0175305 1 0 1 1 0 0 +EDGE2 8603 3402 -0.985776 0.0537046 -0.0303443 1 0 1 1 0 0 +EDGE2 8603 8442 -0.978451 -0.0106762 -0.00186296 1 0 1 1 0 0 +EDGE2 8603 8602 -1.02628 0.0924632 0.0129064 1 0 1 1 0 0 +EDGE2 8603 922 -1.02101 -0.0214055 -0.00701558 1 0 1 1 0 0 +EDGE2 8603 923 -0.00503798 0.0707757 0.00473926 1 0 1 1 0 0 +EDGE2 8603 3403 0.0980945 -0.026581 -0.036487 1 0 1 1 0 0 +EDGE2 8603 8443 -0.0330668 -0.0265471 -0.0163201 1 0 1 1 0 0 +EDGE2 8603 924 0.994553 0.0267191 -0.00232653 1 0 1 1 0 0 +EDGE2 8603 3404 1.06933 -0.0578734 -0.00279577 1 0 1 1 0 0 +EDGE2 8604 8444 -0.0372689 0.0982281 -0.000731236 1 0 1 1 0 0 +EDGE2 8604 8603 -0.951867 0.0682229 0.00899754 1 0 1 1 0 0 +EDGE2 8604 923 -1.04257 0.0945535 0.0294453 1 0 1 1 0 0 +EDGE2 8604 3403 -1.03548 0.0319632 -0.0186841 1 0 1 1 0 0 +EDGE2 8604 8443 -1.05502 0.116644 0.0235262 1 0 1 1 0 0 +EDGE2 8604 8445 0.970371 -0.0504566 -0.0188435 1 0 1 1 0 0 +EDGE2 8604 924 0.0252521 -0.0574551 -0.000476866 1 0 1 1 0 0 +EDGE2 8604 3404 -0.0441646 -0.0839739 0.00381801 1 0 1 1 0 0 +EDGE2 8604 8465 1.00736 0.00727695 -3.1432 1 0 1 1 0 0 +EDGE2 8604 925 1.04381 -0.0589256 0.0184784 1 0 1 1 0 0 +EDGE2 8604 3405 0.965418 0.00639827 -0.0316913 1 0 1 1 0 0 +EDGE2 8605 8446 0.0158884 -1.03587 -1.54442 1 0 1 1 0 0 +EDGE2 8605 926 0.0102648 -0.944981 -1.57783 1 0 1 1 0 0 +EDGE2 8605 3406 0.0023123 0.983797 1.54178 1 0 1 1 0 0 +EDGE2 8605 8444 -1.00804 0.0468572 0.00275445 1 0 1 1 0 0 +EDGE2 8605 8604 -0.999968 0.0368041 -0.00149886 1 0 1 1 0 0 +EDGE2 8605 8445 0.049685 -0.0266296 -0.0153361 1 0 1 1 0 0 +EDGE2 8605 924 -1.03028 -0.000782863 0.0386025 1 0 1 1 0 0 +EDGE2 8605 3404 -1.0325 -0.0278204 0.012244 1 0 1 1 0 0 +EDGE2 8605 8465 -0.152311 -0.0715105 -3.1701 1 0 1 1 0 0 +EDGE2 8605 925 0.0211362 -0.025068 -0.0284388 1 0 1 1 0 0 +EDGE2 8605 3405 0.0163115 0.0247287 0.00764667 1 0 1 1 0 0 +EDGE2 8605 8466 -0.0428985 1.0163 1.5344 1 0 1 1 0 0 +EDGE2 8605 8464 1.02684 -0.0148299 -3.14389 1 0 1 1 0 0 +EDGE2 8606 3406 -0.0565871 0.10571 0.00638412 1 0 1 1 0 0 +EDGE2 8606 8445 -0.969119 0.00157449 -1.57694 1 0 1 1 0 0 +EDGE2 8606 8605 -0.990486 0.00147315 -1.55397 1 0 1 1 0 0 +EDGE2 8606 8465 -0.888014 0.00949554 1.57142 1 0 1 1 0 0 +EDGE2 8606 925 -0.942822 -0.0185914 -1.58821 1 0 1 1 0 0 +EDGE2 8606 3405 -0.997192 -0.0234998 -1.59729 1 0 1 1 0 0 +EDGE2 8606 8466 -0.0172155 -0.0770822 0.055137 1 0 1 1 0 0 +EDGE2 8606 3407 0.963166 -0.105305 -0.0308207 1 0 1 1 0 0 +EDGE2 8606 8467 0.972636 -0.0486908 -0.0230218 1 0 1 1 0 0 +EDGE2 8607 3406 -0.908173 0.0992088 0.0147072 1 0 1 1 0 0 +EDGE2 8607 8606 -0.937025 -0.000594197 -0.00201838 1 0 1 1 0 0 +EDGE2 8607 8466 -1.08277 -0.0386355 0.00660129 1 0 1 1 0 0 +EDGE2 8607 3408 0.959442 0.0290963 -0.00790547 1 0 1 1 0 0 +EDGE2 8607 3407 0.0577271 0.124644 8.93217e-06 1 0 1 1 0 0 +EDGE2 8607 8467 -0.0466306 0.0709383 0.0148988 1 0 1 1 0 0 +EDGE2 8607 8468 0.900097 0.00351652 0.0178161 1 0 1 1 0 0 +EDGE2 8608 8607 -1.04437 -0.0360401 -0.0457212 1 0 1 1 0 0 +EDGE2 8608 3408 0.0473203 0.0394105 -0.00421508 1 0 1 1 0 0 +EDGE2 8608 3407 -1.02501 -0.0224695 0.0180036 1 0 1 1 0 0 +EDGE2 8608 8467 -0.970048 0.051139 -0.0300485 1 0 1 1 0 0 +EDGE2 8608 8468 0.093239 -0.0119417 -0.0327109 1 0 1 1 0 0 +EDGE2 8608 8469 1.04417 0.0909635 0.0211668 1 0 1 1 0 0 +EDGE2 8608 3409 0.900104 -0.00783938 0.0252808 1 0 1 1 0 0 +EDGE2 8609 3408 -1.02117 0.101752 0.0127016 1 0 1 1 0 0 +EDGE2 8609 8608 -0.950699 0.0342377 -0.00617632 1 0 1 1 0 0 +EDGE2 8609 8468 -0.895367 -0.0369158 0.0149236 1 0 1 1 0 0 +EDGE2 8609 8469 0.0271185 -0.00490949 0.0255348 1 0 1 1 0 0 +EDGE2 8609 3409 -0.060779 0.0847465 -0.00687399 1 0 1 1 0 0 +EDGE2 8609 8370 0.959859 0.0271592 -3.12704 1 0 1 1 0 0 +EDGE2 8609 8470 1.05527 0.0314903 -0.0204517 1 0 1 1 0 0 +EDGE2 8609 8430 0.909493 -0.00877166 -3.15967 1 0 1 1 0 0 +EDGE2 8609 3070 0.992229 -0.028391 -3.15685 1 0 1 1 0 0 +EDGE2 8609 3390 1.04036 0.0427992 -3.11217 1 0 1 1 0 0 +EDGE2 8609 3410 1.00385 -0.0104098 -0.0273895 1 0 1 1 0 0 +EDGE2 8609 5890 1.06225 0.0308678 -3.12001 1 0 1 1 0 0 +EDGE2 8609 3150 1.02296 0.0373201 -3.124 1 0 1 1 0 0 +EDGE2 8610 8469 -0.995876 0.045819 -0.033584 1 0 1 1 0 0 +EDGE2 8610 8609 -0.968526 -0.020735 -0.0227357 1 0 1 1 0 0 +EDGE2 8610 3409 -0.988259 0.113488 -0.00315414 1 0 1 1 0 0 +EDGE2 8610 8370 0.0264877 0.0137168 -3.14138 1 0 1 1 0 0 +EDGE2 8610 3411 0.0130321 1.0359 1.5829 1 0 1 1 0 0 +EDGE2 8610 5891 0.0478553 0.953608 1.57437 1 0 1 1 0 0 +EDGE2 8610 8431 -0.0156827 0.949396 1.60885 1 0 1 1 0 0 +EDGE2 8610 3391 0.0148466 1.04719 1.54835 1 0 1 1 0 0 +EDGE2 8610 8470 -0.0182621 0.0234486 -0.0037074 1 0 1 1 0 0 +EDGE2 8610 8430 0.00217227 0.0151419 -3.1415 1 0 1 1 0 0 +EDGE2 8610 3070 -0.0773796 0.00207492 -3.1559 1 0 1 1 0 0 +EDGE2 8610 3390 0.010294 0.12957 -3.13553 1 0 1 1 0 0 +EDGE2 8610 3410 -0.000223914 0.10973 -0.0114576 1 0 1 1 0 0 +EDGE2 8610 5890 0.024152 -0.0323722 -3.15456 1 0 1 1 0 0 +EDGE2 8610 3150 -0.0881034 -0.0281026 -3.12863 1 0 1 1 0 0 +EDGE2 8610 5889 0.968699 -0.0967279 -3.11966 1 0 1 1 0 0 +EDGE2 8610 8429 1.01803 -0.0140372 -3.15147 1 0 1 1 0 0 +EDGE2 8610 8369 1.02724 -0.0914866 -3.14532 1 0 1 1 0 0 +EDGE2 8610 3149 0.973138 0.00458892 -3.1362 1 0 1 1 0 0 +EDGE2 8610 3389 0.990506 0.00322714 -3.16762 1 0 1 1 0 0 +EDGE2 8610 3069 1.08547 -0.0568144 -3.13639 1 0 1 1 0 0 +EDGE2 8610 3151 -0.0325781 -0.994623 -1.59176 1 0 1 1 0 0 +EDGE2 8610 8371 0.0638661 -0.999952 -1.60071 1 0 1 1 0 0 +EDGE2 8610 8471 0.0138538 -0.98373 -1.56527 1 0 1 1 0 0 +EDGE2 8610 3071 0.0323013 -1.013 -1.57153 1 0 1 1 0 0 +EDGE2 8611 8370 -1.01857 0.0319915 -1.56576 1 0 1 1 0 0 +EDGE2 8611 8470 -1.08926 0.0832418 1.55354 1 0 1 1 0 0 +EDGE2 8611 8610 -1.00652 -0.0292247 1.58875 1 0 1 1 0 0 +EDGE2 8611 8430 -1.04089 -0.0296356 -1.56886 1 0 1 1 0 0 +EDGE2 8611 3070 -0.881181 -0.032109 -1.57437 1 0 1 1 0 0 +EDGE2 8611 3390 -0.972601 -0.0179383 -1.57082 1 0 1 1 0 0 +EDGE2 8611 3410 -0.95432 -0.0301581 1.5687 1 0 1 1 0 0 +EDGE2 8611 5890 -0.965237 -0.0129623 -1.59167 1 0 1 1 0 0 +EDGE2 8611 3150 -1.01906 0.07287 -1.56608 1 0 1 1 0 0 +EDGE2 8611 3072 1.06616 0.161728 -0.00351737 1 0 1 1 0 0 +EDGE2 8611 3151 0.0632072 -0.0451872 0.00853052 1 0 1 1 0 0 +EDGE2 8611 8371 0.0341918 -0.00678242 0.0014237 1 0 1 1 0 0 +EDGE2 8611 8471 -0.0881218 -0.059776 -0.00014186 1 0 1 1 0 0 +EDGE2 8611 3071 -0.0127141 0.0532267 0.0217971 1 0 1 1 0 0 +EDGE2 8611 8372 1.01732 -0.00021984 0.00737922 1 0 1 1 0 0 +EDGE2 8611 8472 0.892172 0.0601286 0.0205378 1 0 1 1 0 0 +EDGE2 8611 3152 1.03463 -0.0502853 0.000158252 1 0 1 1 0 0 +EDGE2 8612 8611 -1.04092 0.0842418 -0.000917066 1 0 1 1 0 0 +EDGE2 8612 3072 -0.0478086 0.0760382 -0.0224804 1 0 1 1 0 0 +EDGE2 8612 3151 -1.00798 0.00627854 0.01222 1 0 1 1 0 0 +EDGE2 8612 8371 -1.01602 0.0539528 -0.0199192 1 0 1 1 0 0 +EDGE2 8612 8471 -1.01355 0.0467537 0.0255452 1 0 1 1 0 0 +EDGE2 8612 3071 -0.961641 -0.0220552 0.0242294 1 0 1 1 0 0 +EDGE2 8612 8372 0.00737357 0.0536157 0.0293822 1 0 1 1 0 0 +EDGE2 8612 8472 0.112346 0.0296004 0.00166839 1 0 1 1 0 0 +EDGE2 8612 3152 -0.0145402 0.02236 0.0511188 1 0 1 1 0 0 +EDGE2 8612 3153 1.08469 -0.0195216 -0.0101265 1 0 1 1 0 0 +EDGE2 8612 8473 1.01298 -0.108927 -0.0148194 1 0 1 1 0 0 +EDGE2 8612 8373 0.913349 -0.0502464 -0.0287657 1 0 1 1 0 0 +EDGE2 8612 3073 1.02385 0.136718 -0.0553739 1 0 1 1 0 0 +EDGE2 8613 8374 1.06113 0.0467976 0.0071371 1 0 1 1 0 0 +EDGE2 8613 3072 -1.0103 0.0252716 -0.0127692 1 0 1 1 0 0 +EDGE2 8613 8372 -1.00425 0.02688 -0.00576032 1 0 1 1 0 0 +EDGE2 8613 8472 -0.924722 0.0121596 0.00791079 1 0 1 1 0 0 +EDGE2 8613 8612 -1.05102 0.0124805 0.0130401 1 0 1 1 0 0 +EDGE2 8613 3152 -0.989299 -0.0450667 -0.0321853 1 0 1 1 0 0 +EDGE2 8613 3153 0.0286529 -0.0587663 -0.0234888 1 0 1 1 0 0 +EDGE2 8613 8473 -0.0593218 -0.0716708 0.0114017 1 0 1 1 0 0 +EDGE2 8613 8373 -0.0974012 -0.0248623 -0.0242248 1 0 1 1 0 0 +EDGE2 8613 3073 0.0255435 0.00297891 -0.00938286 1 0 1 1 0 0 +EDGE2 8613 8474 0.908008 -0.0351509 0.0177641 1 0 1 1 0 0 +EDGE2 8613 3074 0.955407 0.0243059 -0.0251169 1 0 1 1 0 0 +EDGE2 8613 3154 1.04171 -0.117266 -0.0217705 1 0 1 1 0 0 +EDGE2 8614 8374 0.0247652 0.0235957 0.0194901 1 0 1 1 0 0 +EDGE2 8614 3153 -0.973741 0.0378297 0.0130955 1 0 1 1 0 0 +EDGE2 8614 8473 -0.947313 0.0537989 0.034954 1 0 1 1 0 0 +EDGE2 8614 8613 -0.925664 0.0165414 -0.032018 1 0 1 1 0 0 +EDGE2 8614 8373 -1.00108 -0.0606784 0.0311743 1 0 1 1 0 0 +EDGE2 8614 3073 -0.933373 -0.0209483 0.00652232 1 0 1 1 0 0 +EDGE2 8614 8474 -0.0552701 0.0182519 0.0182191 1 0 1 1 0 0 +EDGE2 8614 1075 1.00473 -0.0060028 -3.12718 1 0 1 1 0 0 +EDGE2 8614 3074 0.0883355 0.0531579 -0.00537223 1 0 1 1 0 0 +EDGE2 8614 3154 0.0256759 -0.0867625 0.00436409 1 0 1 1 0 0 +EDGE2 8614 3155 1.03943 -0.032382 -0.000899133 1 0 1 1 0 0 +EDGE2 8614 8375 1.06652 -0.0111372 0.00239367 1 0 1 1 0 0 +EDGE2 8614 8475 1.00434 -0.000775922 -0.00923304 1 0 1 1 0 0 +EDGE2 8614 3075 0.968715 0.00237365 0.013877 1 0 1 1 0 0 +EDGE2 8614 995 0.963949 -0.0248579 -3.14288 1 0 1 1 0 0 +EDGE2 8614 1015 0.98082 0.00381867 -3.13423 1 0 1 1 0 0 +EDGE2 8614 1055 0.981183 -0.0228671 -3.12895 1 0 1 1 0 0 +EDGE2 8615 1016 0.0361141 -0.965796 -1.5526 1 0 1 1 0 0 +EDGE2 8615 1056 0.0439117 -0.923397 -1.56883 1 0 1 1 0 0 +EDGE2 8615 996 -0.0358146 -0.967535 -1.55751 1 0 1 1 0 0 +EDGE2 8615 8374 -1.03264 0.0019908 -0.0155136 1 0 1 1 0 0 +EDGE2 8615 8614 -0.962729 0.110952 0.0177652 1 0 1 1 0 0 +EDGE2 8615 8474 -1.00897 -0.0137821 -0.0375799 1 0 1 1 0 0 +EDGE2 8615 1075 -0.0390426 -0.0378829 -3.18253 1 0 1 1 0 0 +EDGE2 8615 3074 -0.988058 -0.0813935 0.00730329 1 0 1 1 0 0 +EDGE2 8615 3154 -0.897654 0.0113976 0.00905503 1 0 1 1 0 0 +EDGE2 8615 3155 -0.0194985 -0.0287961 0.000500446 1 0 1 1 0 0 +EDGE2 8615 8375 -0.000934588 0.0474772 0.0245027 1 0 1 1 0 0 +EDGE2 8615 8475 0.00863135 -0.030067 -0.0218884 1 0 1 1 0 0 +EDGE2 8615 3075 -0.023723 0.066593 -0.0452813 1 0 1 1 0 0 +EDGE2 8615 1074 1.06395 0.00817664 -3.1739 1 0 1 1 0 0 +EDGE2 8615 995 -0.00620975 -0.0326088 -3.16976 1 0 1 1 0 0 +EDGE2 8615 1015 -0.00509977 -0.0606233 -3.14687 1 0 1 1 0 0 +EDGE2 8615 1055 -0.0842923 0.000445939 -3.16733 1 0 1 1 0 0 +EDGE2 8615 1014 1.0255 -0.0373332 -3.1348 1 0 1 1 0 0 +EDGE2 8615 1054 1.05367 0.015909 -3.11074 1 0 1 1 0 0 +EDGE2 8615 994 1.07294 -0.0223713 -3.15028 1 0 1 1 0 0 +EDGE2 8615 3156 -0.013667 1.04421 1.56857 1 0 1 1 0 0 +EDGE2 8615 8476 -0.00436274 1.01918 1.56653 1 0 1 1 0 0 +EDGE2 8615 8376 0.03056 1.06474 1.56675 1 0 1 1 0 0 +EDGE2 8615 1076 0.121561 1.03632 1.56588 1 0 1 1 0 0 +EDGE2 8615 3076 -0.0291058 1.08618 1.53689 1 0 1 1 0 0 +EDGE2 8616 1075 -0.986042 -0.0337562 1.56279 1 0 1 1 0 0 +EDGE2 8616 8615 -0.963259 0.0202139 -1.56308 1 0 1 1 0 0 +EDGE2 8616 3155 -1.00658 0.0666347 -1.59548 1 0 1 1 0 0 +EDGE2 8616 8375 -0.944524 -0.0121787 -1.54594 1 0 1 1 0 0 +EDGE2 8616 8475 -0.939376 -0.00347369 -1.5364 1 0 1 1 0 0 +EDGE2 8616 3075 -1.01758 0.0527629 -1.54603 1 0 1 1 0 0 +EDGE2 8616 995 -1.01467 -0.0778384 1.57315 1 0 1 1 0 0 +EDGE2 8616 1015 -1.06252 -0.0451804 1.58309 1 0 1 1 0 0 +EDGE2 8616 1055 -0.963042 0.0354344 1.57367 1 0 1 1 0 0 +EDGE2 8616 8477 0.976416 0.0454998 0.00929761 1 0 1 1 0 0 +EDGE2 8616 3156 0.087713 -0.041354 0.0302604 1 0 1 1 0 0 +EDGE2 8616 8476 -0.0602916 -0.0542214 0.0026131 1 0 1 1 0 0 +EDGE2 8616 8376 0.0320451 -0.109024 -0.0146824 1 0 1 1 0 0 +EDGE2 8616 1076 -0.0266049 0.059879 0.0395434 1 0 1 1 0 0 +EDGE2 8616 3076 0.0130117 -0.0539819 -0.00181894 1 0 1 1 0 0 +EDGE2 8616 3077 1.0339 -0.0170491 0.0218465 1 0 1 1 0 0 +EDGE2 8616 3157 0.986596 0.0328383 -0.00633004 1 0 1 1 0 0 +EDGE2 8616 8377 1.09289 -0.0545397 0.00237321 1 0 1 1 0 0 +EDGE2 8616 1077 1.03191 0.00809018 -0.0104885 1 0 1 1 0 0 +EDGE2 8617 3078 1.01321 -0.0626724 -0.0419738 1 0 1 1 0 0 +EDGE2 8617 8477 -0.0927369 -0.101293 0.00171629 1 0 1 1 0 0 +EDGE2 8617 3156 -0.995189 -0.00977394 -0.0037757 1 0 1 1 0 0 +EDGE2 8617 8476 -0.966775 0.0470687 -0.00221908 1 0 1 1 0 0 +EDGE2 8617 8616 -0.94266 -0.122861 -0.0313693 1 0 1 1 0 0 +EDGE2 8617 8376 -0.958675 -0.0200785 0.0152714 1 0 1 1 0 0 +EDGE2 8617 1076 -1.00895 0.0349253 0.00215727 1 0 1 1 0 0 +EDGE2 8617 3076 -0.96107 -0.0517951 -0.013354 1 0 1 1 0 0 +EDGE2 8617 3077 0.0585315 0.0363395 0.025961 1 0 1 1 0 0 +EDGE2 8617 3157 0.0952032 -0.152933 -0.0107179 1 0 1 1 0 0 +EDGE2 8617 8377 0.0145006 -0.00470137 -0.0225992 1 0 1 1 0 0 +EDGE2 8617 1077 -0.115915 0.00303393 0.00699141 1 0 1 1 0 0 +EDGE2 8617 8378 1.00907 -0.019592 -0.035803 1 0 1 1 0 0 +EDGE2 8617 8478 0.974724 0.0787614 0.010008 1 0 1 1 0 0 +EDGE2 8617 3158 1.04794 -0.0196567 -0.00860796 1 0 1 1 0 0 +EDGE2 8617 1078 1.00322 -0.117524 -0.00305515 1 0 1 1 0 0 +EDGE2 8618 3078 -0.0388787 -0.00243526 0.0117692 1 0 1 1 0 0 +EDGE2 8618 8477 -1.0357 0.0820417 -0.00516055 1 0 1 1 0 0 +EDGE2 8618 8617 -1.13773 -0.0222605 0.0133194 1 0 1 1 0 0 +EDGE2 8618 3077 -0.990228 -0.0328824 -0.0110344 1 0 1 1 0 0 +EDGE2 8618 3157 -0.980571 -0.0218561 0.00729427 1 0 1 1 0 0 +EDGE2 8618 8377 -1.00502 -0.0125564 0.0270944 1 0 1 1 0 0 +EDGE2 8618 1077 -0.936832 -0.0520447 0.011504 1 0 1 1 0 0 +EDGE2 8618 8378 -0.0130946 0.0446002 -0.0149963 1 0 1 1 0 0 +EDGE2 8618 8478 -0.102267 0.0502402 -0.0226991 1 0 1 1 0 0 +EDGE2 8618 3158 0.0243609 0.00227071 0.0117991 1 0 1 1 0 0 +EDGE2 8618 8379 0.960961 -0.0443748 -0.012213 1 0 1 1 0 0 +EDGE2 8618 1078 0.0170629 0.000480051 -0.0175838 1 0 1 1 0 0 +EDGE2 8618 8479 0.921783 -0.00743041 0.000177785 1 0 1 1 0 0 +EDGE2 8618 3079 0.97481 -0.0193831 -0.0284641 1 0 1 1 0 0 +EDGE2 8618 3159 1.04541 0.0204067 0.00589725 1 0 1 1 0 0 +EDGE2 8618 1079 0.993006 -0.0890091 0.000163748 1 0 1 1 0 0 +EDGE2 8619 8360 1.0194 0.0124212 -3.18872 1 0 1 1 0 0 +EDGE2 8619 3078 -0.92393 0.0287453 0.00559149 1 0 1 1 0 0 +EDGE2 8619 8378 -1.01164 0.000366734 -0.0177954 1 0 1 1 0 0 +EDGE2 8619 8478 -1.08299 -0.00820416 -0.00158326 1 0 1 1 0 0 +EDGE2 8619 8618 -1.00618 -0.0341879 -0.0403613 1 0 1 1 0 0 +EDGE2 8619 3158 -1.00305 0.0505492 0.0172811 1 0 1 1 0 0 +EDGE2 8619 8379 0.0711896 0.107535 -0.0246504 1 0 1 1 0 0 +EDGE2 8619 1078 -1.00302 -0.0439649 0.0220734 1 0 1 1 0 0 +EDGE2 8619 8479 -0.0129644 0.0307801 0.00654602 1 0 1 1 0 0 +EDGE2 8619 3079 0.0590482 0.0112943 -0.0333217 1 0 1 1 0 0 +EDGE2 8619 3159 0.0438276 0.019845 -0.0104098 1 0 1 1 0 0 +EDGE2 8619 1079 -0.0195936 -0.0876945 0.0137117 1 0 1 1 0 0 +EDGE2 8619 8480 0.902856 0.0308569 0.0219751 1 0 1 1 0 0 +EDGE2 8619 8400 1.09991 0.0691436 -3.15493 1 0 1 1 0 0 +EDGE2 8619 8420 0.995328 0.00853467 -3.111 1 0 1 1 0 0 +EDGE2 8619 8380 0.864076 0.0456234 -0.0133125 1 0 1 1 0 0 +EDGE2 8619 3060 0.98288 0.0286848 -3.15451 1 0 1 1 0 0 +EDGE2 8619 3160 0.99901 -0.106087 0.0074713 1 0 1 1 0 0 +EDGE2 8619 5860 1.04135 0.044309 -3.13736 1 0 1 1 0 0 +EDGE2 8619 5880 1.02199 -0.00634135 -3.14835 1 0 1 1 0 0 +EDGE2 8619 3080 1.05837 -0.06359 -0.0118813 1 0 1 1 0 0 +EDGE2 8619 1080 1.01787 0.0615508 0.0304119 1 0 1 1 0 0 +EDGE2 8620 8360 0.0517235 -0.0398576 -3.13239 1 0 1 1 0 0 +EDGE2 8620 8379 -0.989228 -0.103128 0.0243239 1 0 1 1 0 0 +EDGE2 8620 8619 -0.983022 -0.0167376 -0.035282 1 0 1 1 0 0 +EDGE2 8620 8479 -0.979875 -0.125007 0.00558867 1 0 1 1 0 0 +EDGE2 8620 3079 -0.981519 0.0109648 -0.0128945 1 0 1 1 0 0 +EDGE2 8620 3159 -1.00338 -0.0473037 0.013338 1 0 1 1 0 0 +EDGE2 8620 1079 -1.04732 0.0269754 -0.0147305 1 0 1 1 0 0 +EDGE2 8620 8361 0.0349952 0.943879 1.56126 1 0 1 1 0 0 +EDGE2 8620 8421 -0.0399545 1.04814 1.58366 1 0 1 1 0 0 +EDGE2 8620 8481 0.0445638 1.03168 1.58269 1 0 1 1 0 0 +EDGE2 8620 8381 -0.124396 1.02621 1.57048 1 0 1 1 0 0 +EDGE2 8620 3081 0.00538682 0.949666 1.56866 1 0 1 1 0 0 +EDGE2 8620 3161 0.014775 0.939817 1.59477 1 0 1 1 0 0 +EDGE2 8620 5881 -0.0354254 0.923379 1.54715 1 0 1 1 0 0 +EDGE2 8620 3061 -0.0111561 0.974297 1.56163 1 0 1 1 0 0 +EDGE2 8620 8480 0.0522052 0.0294718 0.00523911 1 0 1 1 0 0 +EDGE2 8620 8400 0.0175252 -0.00916309 -3.15516 1 0 1 1 0 0 +EDGE2 8620 8420 0.0514936 -0.0428582 -3.1525 1 0 1 1 0 0 +EDGE2 8620 8380 0.0128294 -0.0649642 -0.0180333 1 0 1 1 0 0 +EDGE2 8620 8401 -0.0210074 -1.01427 -1.55499 1 0 1 1 0 0 +EDGE2 8620 3060 0.0909151 0.0551409 -3.16096 1 0 1 1 0 0 +EDGE2 8620 3160 0.0539935 0.0197569 0.00309941 1 0 1 1 0 0 +EDGE2 8620 5860 -0.00678271 0.0228625 -3.1048 1 0 1 1 0 0 +EDGE2 8620 5880 0.0289918 -0.015274 -3.12815 1 0 1 1 0 0 +EDGE2 8620 3080 0.0243226 -0.0165999 -0.038322 1 0 1 1 0 0 +EDGE2 8620 1080 -0.0542731 0.033815 0.00327534 1 0 1 1 0 0 +EDGE2 8620 1081 -0.0279573 -0.933075 -1.56726 1 0 1 1 0 0 +EDGE2 8620 5861 0.00808114 -1.05346 -1.5736 1 0 1 1 0 0 +EDGE2 8620 8399 0.981528 0.072824 -3.11488 1 0 1 1 0 0 +EDGE2 8620 8419 0.943572 -0.0265243 -3.12883 1 0 1 1 0 0 +EDGE2 8620 5859 0.946752 0.0358443 -3.15128 1 0 1 1 0 0 +EDGE2 8620 5879 1.01595 0.00873452 -3.15383 1 0 1 1 0 0 +EDGE2 8620 8359 0.932844 -0.0355655 -3.12436 1 0 1 1 0 0 +EDGE2 8620 3059 0.960192 -0.0453116 -3.18279 1 0 1 1 0 0 +EDGE2 8621 8360 -1.02919 -0.00842848 1.54265 1 0 1 1 0 0 +EDGE2 8621 8362 1.08109 -0.0349141 -0.00356878 1 0 1 1 0 0 +EDGE2 8621 8422 1.02479 0.0545869 -0.00296906 1 0 1 1 0 0 +EDGE2 8621 8482 0.939405 0.0339273 0.0255244 1 0 1 1 0 0 +EDGE2 8621 8382 1.06456 -0.0542661 0.0191988 1 0 1 1 0 0 +EDGE2 8621 3082 1.00037 -0.0106633 -0.0135482 1 0 1 1 0 0 +EDGE2 8621 3162 0.971482 0.0515975 0.0201616 1 0 1 1 0 0 +EDGE2 8621 5882 1.03087 0.0136283 -0.0112463 1 0 1 1 0 0 +EDGE2 8621 3062 1.04335 -0.00257851 -0.0312745 1 0 1 1 0 0 +EDGE2 8621 8361 -0.0125422 -0.0193824 -0.0178673 1 0 1 1 0 0 +EDGE2 8621 8421 -0.0470128 0.0340972 0.0255319 1 0 1 1 0 0 +EDGE2 8621 8481 -0.00441925 -0.0504547 0.00782811 1 0 1 1 0 0 +EDGE2 8621 8381 -0.0680625 0.00397242 -0.0153524 1 0 1 1 0 0 +EDGE2 8621 3081 0.0269896 0.0850637 0.00926132 1 0 1 1 0 0 +EDGE2 8621 3161 0.0615141 0.045926 -0.023263 1 0 1 1 0 0 +EDGE2 8621 5881 -0.00405834 -0.0272704 -0.00516935 1 0 1 1 0 0 +EDGE2 8621 3061 -0.0033387 0.0473253 -0.0153651 1 0 1 1 0 0 +EDGE2 8621 8480 -1.04825 -0.0315277 -1.5945 1 0 1 1 0 0 +EDGE2 8621 8620 -1.01918 -0.0318238 -1.56082 1 0 1 1 0 0 +EDGE2 8621 8400 -0.904634 -0.0321437 1.57659 1 0 1 1 0 0 +EDGE2 8621 8420 -0.957323 -0.0106374 1.57199 1 0 1 1 0 0 +EDGE2 8621 8380 -0.949381 -0.0431357 -1.58614 1 0 1 1 0 0 +EDGE2 8621 3060 -1.1088 0.0536234 1.60519 1 0 1 1 0 0 +EDGE2 8621 3160 -0.83431 0.0594136 -1.54029 1 0 1 1 0 0 +EDGE2 8621 5860 -1.04055 -0.00612166 1.57907 1 0 1 1 0 0 +EDGE2 8621 5880 -1.01677 0.0724088 1.57357 1 0 1 1 0 0 +EDGE2 8621 3080 -0.988472 -0.00308273 -1.60152 1 0 1 1 0 0 +EDGE2 8621 1080 -0.938863 -0.0198593 -1.5658 1 0 1 1 0 0 +EDGE2 8622 8363 1.02061 -0.00753055 -0.0344881 1 0 1 1 0 0 +EDGE2 8622 8423 1.04203 0.0284933 0.00452059 1 0 1 1 0 0 +EDGE2 8622 8483 0.991865 0.0120171 -0.0588864 1 0 1 1 0 0 +EDGE2 8622 8383 0.88869 -0.00703581 0.00945842 1 0 1 1 0 0 +EDGE2 8622 3083 1.01004 -0.0691104 0.000446456 1 0 1 1 0 0 +EDGE2 8622 3163 1.0292 -0.101771 -0.0100107 1 0 1 1 0 0 +EDGE2 8622 5883 0.984361 -0.00751618 -0.0104824 1 0 1 1 0 0 +EDGE2 8622 3063 0.90847 -0.0987287 -0.0062982 1 0 1 1 0 0 +EDGE2 8622 8362 0.0201376 -0.0320128 0.00510873 1 0 1 1 0 0 +EDGE2 8622 8422 -0.00914794 -0.0426594 -0.0136445 1 0 1 1 0 0 +EDGE2 8622 8482 -0.0172494 -0.0260081 -0.0146267 1 0 1 1 0 0 +EDGE2 8622 8382 0.0533151 0.0490673 -0.0230251 1 0 1 1 0 0 +EDGE2 8622 3082 0.0541095 -0.0149484 -0.0174195 1 0 1 1 0 0 +EDGE2 8622 3162 -0.0697766 -0.0231694 -0.0461809 1 0 1 1 0 0 +EDGE2 8622 5882 0.0538783 -0.0676412 -0.00854107 1 0 1 1 0 0 +EDGE2 8622 3062 0.056136 -0.0428776 0.0056326 1 0 1 1 0 0 +EDGE2 8622 8361 -0.993473 -0.0879244 0.015493 1 0 1 1 0 0 +EDGE2 8622 8421 -1.03765 0.0638358 -0.00912592 1 0 1 1 0 0 +EDGE2 8622 8481 -1.09355 0.0381809 0.0204287 1 0 1 1 0 0 +EDGE2 8622 8621 -0.971082 -0.00948919 -0.00880258 1 0 1 1 0 0 +EDGE2 8622 8381 -1.01041 0.00316615 0.010026 1 0 1 1 0 0 +EDGE2 8622 3081 -1.00266 0.0208556 0.0384126 1 0 1 1 0 0 +EDGE2 8622 3161 -1.06514 -0.0266891 0.0123939 1 0 1 1 0 0 +EDGE2 8622 5881 -1.06255 0.0556181 0.0456737 1 0 1 1 0 0 +EDGE2 8622 3061 -0.886445 -0.0740429 -0.00647562 1 0 1 1 0 0 +EDGE2 8623 3064 1.02222 0.0559398 -0.0103509 1 0 1 1 0 0 +EDGE2 8623 8384 1.04265 0.0328004 -0.00738023 1 0 1 1 0 0 +EDGE2 8623 8484 0.980905 -0.0425978 0.0148467 1 0 1 1 0 0 +EDGE2 8623 8424 1.03641 -0.0227512 -0.0171804 1 0 1 1 0 0 +EDGE2 8623 3164 1.04224 -0.0706026 0.0133181 1 0 1 1 0 0 +EDGE2 8623 5884 1.02796 0.000983184 -0.0311372 1 0 1 1 0 0 +EDGE2 8623 8364 0.951017 -0.0126635 0.00360611 1 0 1 1 0 0 +EDGE2 8623 3084 1.00525 -0.000564374 -0.000616038 1 0 1 1 0 0 +EDGE2 8623 8363 0.0530532 0.0408406 0.00442046 1 0 1 1 0 0 +EDGE2 8623 8423 0.0225106 -0.0262125 0.0147092 1 0 1 1 0 0 +EDGE2 8623 8483 0.0153725 -0.013687 -0.0314725 1 0 1 1 0 0 +EDGE2 8623 8383 -0.0239438 -0.0809421 0.0119807 1 0 1 1 0 0 +EDGE2 8623 3083 0.0611678 -0.0917636 -0.0074701 1 0 1 1 0 0 +EDGE2 8623 3163 -0.00100147 -0.0584342 -0.00312512 1 0 1 1 0 0 +EDGE2 8623 5883 0.0159257 -0.0727977 -0.0451724 1 0 1 1 0 0 +EDGE2 8623 3063 0.0213704 -0.0156063 -0.0073622 1 0 1 1 0 0 +EDGE2 8623 8362 -1.03367 0.00219538 -0.032983 1 0 1 1 0 0 +EDGE2 8623 8422 -1.04387 -0.00320521 0.0109448 1 0 1 1 0 0 +EDGE2 8623 8482 -1.02525 -0.0715422 0.00457943 1 0 1 1 0 0 +EDGE2 8623 8622 -1.13178 0.0865998 -0.0248914 1 0 1 1 0 0 +EDGE2 8623 8382 -0.962489 0.087445 0.00983289 1 0 1 1 0 0 +EDGE2 8623 3082 -0.991265 -0.0256926 -0.0015625 1 0 1 1 0 0 +EDGE2 8623 3162 -1.01258 -0.0547317 0.00263953 1 0 1 1 0 0 +EDGE2 8623 5882 -0.917199 0.0110297 -0.0246483 1 0 1 1 0 0 +EDGE2 8623 3062 -1.02569 -0.0481045 -0.00567358 1 0 1 1 0 0 +EDGE2 8624 8385 0.983224 0.0109352 0.00517517 1 0 1 1 0 0 +EDGE2 8624 8485 0.976628 -0.108039 0.00653843 1 0 1 1 0 0 +EDGE2 8624 8425 1.05085 0.0123431 -0.00279848 1 0 1 1 0 0 +EDGE2 8624 3105 1.09223 0.0432501 -3.13663 1 0 1 1 0 0 +EDGE2 8624 3485 1.00249 -0.00941563 -3.1329 1 0 1 1 0 0 +EDGE2 8624 5845 1.03424 -0.0343287 -3.13909 1 0 1 1 0 0 +EDGE2 8624 5885 1.101 0.0438089 0.0186114 1 0 1 1 0 0 +EDGE2 8624 8365 1.03992 -0.00823567 0.0238231 1 0 1 1 0 0 +EDGE2 8624 5825 1.04227 0.00715445 -3.17157 1 0 1 1 0 0 +EDGE2 8624 3145 1.22135 -0.0879678 -3.13581 1 0 1 1 0 0 +EDGE2 8624 3165 0.999968 -0.0173204 0.00470852 1 0 1 1 0 0 +EDGE2 8624 3385 1.00548 0.0229679 -3.13353 1 0 1 1 0 0 +EDGE2 8624 3125 1.03466 0.06724 -3.1458 1 0 1 1 0 0 +EDGE2 8624 1185 0.948075 -0.0627641 -3.12062 1 0 1 1 0 0 +EDGE2 8624 3065 0.994039 0.0919727 0.0171585 1 0 1 1 0 0 +EDGE2 8624 3085 1.06435 -0.0667844 0.00963671 1 0 1 1 0 0 +EDGE2 8624 1165 1.07867 -0.123384 -3.16414 1 0 1 1 0 0 +EDGE2 8624 3064 0.0810422 0.041899 -0.00143701 1 0 1 1 0 0 +EDGE2 8624 8384 -0.0183623 -0.012735 0.0083702 1 0 1 1 0 0 +EDGE2 8624 8484 -0.0220787 0.0677086 0.00373412 1 0 1 1 0 0 +EDGE2 8624 8424 0.0130549 0.00218929 0.0305964 1 0 1 1 0 0 +EDGE2 8624 3164 0.107228 -0.0648975 -0.0348328 1 0 1 1 0 0 +EDGE2 8624 5884 7.19662e-05 -0.0678049 -0.01435 1 0 1 1 0 0 +EDGE2 8624 8364 0.0151881 -0.0311115 -0.0292298 1 0 1 1 0 0 +EDGE2 8624 3084 -0.0626743 -0.0454624 -0.02964 1 0 1 1 0 0 +EDGE2 8624 8363 -1.0204 -0.0276981 0.0312645 1 0 1 1 0 0 +EDGE2 8624 8423 -1.04336 -0.0414291 0.016018 1 0 1 1 0 0 +EDGE2 8624 8483 -0.976429 -0.0355321 -0.0256754 1 0 1 1 0 0 +EDGE2 8624 8623 -1.0704 0.0275148 -0.0357873 1 0 1 1 0 0 +EDGE2 8624 8383 -0.94083 -0.0304695 0.0276885 1 0 1 1 0 0 +EDGE2 8624 3083 -0.884771 -0.0439194 -0.00914867 1 0 1 1 0 0 +EDGE2 8624 3163 -0.920766 0.0148661 0.0131493 1 0 1 1 0 0 +EDGE2 8624 5883 -0.986995 -0.0106497 -0.00430692 1 0 1 1 0 0 +EDGE2 8624 3063 -1.00437 -0.0270621 -0.0143628 1 0 1 1 0 0 +EDGE2 8625 8385 -0.0491411 0.0367396 -0.00869578 1 0 1 1 0 0 +EDGE2 8625 8366 -0.0213834 0.968151 1.57739 1 0 1 1 0 0 +EDGE2 8625 8426 -0.00397933 1.03524 1.58262 1 0 1 1 0 0 +EDGE2 8625 3146 0.0258948 0.983119 1.57955 1 0 1 1 0 0 +EDGE2 8625 3386 0.0194392 1.00284 1.58317 1 0 1 1 0 0 +EDGE2 8625 5886 0.0937867 1.01132 1.56704 1 0 1 1 0 0 +EDGE2 8625 3066 -0.0237333 1.01831 1.61137 1 0 1 1 0 0 +EDGE2 8625 3144 1.04893 0.0245751 -3.1178 1 0 1 1 0 0 +EDGE2 8625 3484 0.936152 -0.0571327 -3.13844 1 0 1 1 0 0 +EDGE2 8625 5824 0.931186 -0.104445 -3.13223 1 0 1 1 0 0 +EDGE2 8625 5844 1.00507 0.0386591 -3.12085 1 0 1 1 0 0 +EDGE2 8625 3384 1.03623 -0.0429332 -3.11 1 0 1 1 0 0 +EDGE2 8625 1184 1.1115 0.0054037 -3.14651 1 0 1 1 0 0 +EDGE2 8625 3104 1.05173 0.00819095 -3.11992 1 0 1 1 0 0 +EDGE2 8625 3124 0.973291 -0.00708489 -3.17215 1 0 1 1 0 0 +EDGE2 8625 1164 0.960549 0.0154337 -3.15116 1 0 1 1 0 0 +EDGE2 8625 8485 -0.0679138 0.102997 0.0173646 1 0 1 1 0 0 +EDGE2 8625 8425 -0.0318721 0.00865834 -0.00632155 1 0 1 1 0 0 +EDGE2 8625 3166 -0.12739 -0.976942 -1.56963 1 0 1 1 0 0 +EDGE2 8625 3105 -0.00518374 0.117261 -3.1493 1 0 1 1 0 0 +EDGE2 8625 3485 -0.0709058 0.0812583 -3.14599 1 0 1 1 0 0 +EDGE2 8625 5845 -0.0428118 0.0578355 -3.1558 1 0 1 1 0 0 +EDGE2 8625 5885 -0.012542 -0.0234529 0.0128624 1 0 1 1 0 0 +EDGE2 8625 8365 -0.039368 -0.048131 -0.0372359 1 0 1 1 0 0 +EDGE2 8625 5825 -0.0909516 -0.0395087 -3.12678 1 0 1 1 0 0 +EDGE2 8625 3145 0.0926874 0.0122781 -3.1459 1 0 1 1 0 0 +EDGE2 8625 3165 0.0292528 0.008527 -0.0114883 1 0 1 1 0 0 +EDGE2 8625 3385 0.0432813 -0.0309735 -3.17668 1 0 1 1 0 0 +EDGE2 8625 3125 -0.0547832 -0.0320626 -3.14449 1 0 1 1 0 0 +EDGE2 8625 8486 -0.00590479 -1.10013 -1.5487 1 0 1 1 0 0 +EDGE2 8625 1185 0.00643605 0.059329 -3.16653 1 0 1 1 0 0 +EDGE2 8625 3065 -0.0464494 -0.0643548 -0.000367216 1 0 1 1 0 0 +EDGE2 8625 3085 0.00747409 0.0071641 0.00309568 1 0 1 1 0 0 +EDGE2 8625 1165 -0.0259106 0.00177948 -3.14351 1 0 1 1 0 0 +EDGE2 8625 5826 -0.0105557 -1.00423 -1.57284 1 0 1 1 0 0 +EDGE2 8625 5846 -0.0781413 -0.922993 -1.5577 1 0 1 1 0 0 +EDGE2 8625 8386 0.0219037 -1.05966 -1.56528 1 0 1 1 0 0 +EDGE2 8625 3486 -0.00730542 -1.0252 -1.5738 1 0 1 1 0 0 +EDGE2 8625 1166 0.0357726 -1.04273 -1.57782 1 0 1 1 0 0 +EDGE2 8625 3086 0.102879 -0.950661 -1.59164 1 0 1 1 0 0 +EDGE2 8625 3106 -0.0132165 -0.959331 -1.58021 1 0 1 1 0 0 +EDGE2 8625 3126 -0.00300792 -1.05897 -1.56976 1 0 1 1 0 0 +EDGE2 8625 1186 -0.0410448 -1.00192 -1.60138 1 0 1 1 0 0 +EDGE2 8625 3064 -1.03598 -0.0276597 0.013492 1 0 1 1 0 0 +EDGE2 8625 8384 -1.01613 -0.0455667 -0.010469 1 0 1 1 0 0 +EDGE2 8625 8484 -0.996104 -0.045281 0.0130174 1 0 1 1 0 0 +EDGE2 8625 8624 -1.00519 0.0476884 0.02405 1 0 1 1 0 0 +EDGE2 8625 8424 -0.963434 0.0268515 0.0158497 1 0 1 1 0 0 +EDGE2 8625 3164 -0.976535 0.0380166 -0.0115473 1 0 1 1 0 0 +EDGE2 8625 5884 -0.928522 -0.0131173 -0.0346106 1 0 1 1 0 0 +EDGE2 8625 8364 -0.996607 0.0486311 0.00623416 1 0 1 1 0 0 +EDGE2 8625 3084 -1.08358 -0.00144825 0.000715801 1 0 1 1 0 0 +EDGE2 8626 8385 -0.995077 0.057315 -1.57568 1 0 1 1 0 0 +EDGE2 8626 8366 0.0124958 0.0219294 -0.012125 1 0 1 1 0 0 +EDGE2 8626 3147 0.889425 -0.025969 0.00995799 1 0 1 1 0 0 +EDGE2 8626 5887 1.01143 0.0134403 -0.00459973 1 0 1 1 0 0 +EDGE2 8626 8367 0.964469 0.0354734 0.00096089 1 0 1 1 0 0 +EDGE2 8626 8427 0.946705 -0.0304504 -0.0107832 1 0 1 1 0 0 +EDGE2 8626 3387 1.01355 -0.0981429 0.00477253 1 0 1 1 0 0 +EDGE2 8626 3067 1.17735 0.0191836 0.0179435 1 0 1 1 0 0 +EDGE2 8626 8426 0.00365166 -0.120823 0.00685243 1 0 1 1 0 0 +EDGE2 8626 3146 -0.040849 0.00819638 0.0390687 1 0 1 1 0 0 +EDGE2 8626 3386 -0.0211519 -0.0173366 0.014836 1 0 1 1 0 0 +EDGE2 8626 5886 -0.00428111 0.0403806 0.0413502 1 0 1 1 0 0 +EDGE2 8626 3066 -0.0654301 -0.0249299 0.0538196 1 0 1 1 0 0 +EDGE2 8626 8485 -1.00511 -0.0901746 -1.53984 1 0 1 1 0 0 +EDGE2 8626 8625 -1.04659 0.0129733 -1.5527 1 0 1 1 0 0 +EDGE2 8626 8425 -1.03556 -0.0222345 -1.55964 1 0 1 1 0 0 +EDGE2 8626 3105 -1.04392 -0.00686496 1.59201 1 0 1 1 0 0 +EDGE2 8626 3485 -1.09518 -0.0748555 1.55331 1 0 1 1 0 0 +EDGE2 8626 5845 -1.04635 -0.0427813 1.58769 1 0 1 1 0 0 +EDGE2 8626 5885 -0.980947 0.0132613 -1.61512 1 0 1 1 0 0 +EDGE2 8626 8365 -1.05299 -0.0390353 -1.54749 1 0 1 1 0 0 +EDGE2 8626 5825 -1.10355 0.18091 1.58668 1 0 1 1 0 0 +EDGE2 8626 3145 -0.958329 0.0395542 1.56144 1 0 1 1 0 0 +EDGE2 8626 3165 -1.05077 -0.0506511 -1.58948 1 0 1 1 0 0 +EDGE2 8626 3385 -0.946847 -0.0819166 1.57591 1 0 1 1 0 0 +EDGE2 8626 3125 -0.909245 -0.0179323 1.56956 1 0 1 1 0 0 +EDGE2 8626 1185 -0.986218 0.0177867 1.60094 1 0 1 1 0 0 +EDGE2 8626 3065 -0.995429 -0.0412991 -1.54009 1 0 1 1 0 0 +EDGE2 8626 3085 -1.10234 -0.0358353 -1.55419 1 0 1 1 0 0 +EDGE2 8626 1165 -1.08033 -0.0813855 1.53985 1 0 1 1 0 0 +EDGE2 8627 8366 -0.979483 0.0133778 0.0182882 1 0 1 1 0 0 +EDGE2 8627 5888 1.01473 -0.0676777 -0.000329026 1 0 1 1 0 0 +EDGE2 8627 8428 1.01894 0.0271939 -0.00376265 1 0 1 1 0 0 +EDGE2 8627 8368 1.08694 0.032879 -0.0116478 1 0 1 1 0 0 +EDGE2 8627 3068 0.973992 -0.0237065 0.00961314 1 0 1 1 0 0 +EDGE2 8627 3148 0.967046 -0.0353987 0.0103215 1 0 1 1 0 0 +EDGE2 8627 3388 1.01227 0.0855873 0.0205159 1 0 1 1 0 0 +EDGE2 8627 3147 -0.00415565 -0.066959 0.0242944 1 0 1 1 0 0 +EDGE2 8627 5887 0.0964242 0.0431502 -0.00551764 1 0 1 1 0 0 +EDGE2 8627 8367 -0.0481706 -0.0154817 -0.0392185 1 0 1 1 0 0 +EDGE2 8627 8427 -0.0940673 -0.0546838 -0.00409846 1 0 1 1 0 0 +EDGE2 8627 3387 -0.0161718 -0.00283018 0.0139655 1 0 1 1 0 0 +EDGE2 8627 8626 -0.927503 -0.0345048 0.0195463 1 0 1 1 0 0 +EDGE2 8627 3067 -0.0272753 -0.0185034 0.0457082 1 0 1 1 0 0 +EDGE2 8627 8426 -0.948521 0.0334974 -0.0184714 1 0 1 1 0 0 +EDGE2 8627 3146 -1.05866 -0.046623 0.0339767 1 0 1 1 0 0 +EDGE2 8627 3386 -0.980123 0.00925623 0.00545778 1 0 1 1 0 0 +EDGE2 8627 5886 -0.989291 0.093659 0.0136311 1 0 1 1 0 0 +EDGE2 8627 3066 -1.03725 -0.0490249 -0.0354289 1 0 1 1 0 0 +EDGE2 8628 5889 0.967136 0.060492 -0.0191323 1 0 1 1 0 0 +EDGE2 8628 8429 1.03201 -0.0408209 0.0175106 1 0 1 1 0 0 +EDGE2 8628 8369 0.921813 0.0743091 -0.00927377 1 0 1 1 0 0 +EDGE2 8628 3149 1.0331 -0.0448238 0.0114722 1 0 1 1 0 0 +EDGE2 8628 3389 0.972194 0.0843152 0.0139108 1 0 1 1 0 0 +EDGE2 8628 3069 0.967265 -0.0426103 -0.0233726 1 0 1 1 0 0 +EDGE2 8628 8627 -0.864402 -0.0142427 0.0566147 1 0 1 1 0 0 +EDGE2 8628 5888 -0.0204119 0.0262355 -0.0120002 1 0 1 1 0 0 +EDGE2 8628 8428 0.0301514 -0.0543725 -0.00275752 1 0 1 1 0 0 +EDGE2 8628 8368 0.0675736 -0.0298085 -0.03354 1 0 1 1 0 0 +EDGE2 8628 3068 -0.0972165 0.035661 0.0233141 1 0 1 1 0 0 +EDGE2 8628 3148 -0.0132541 -0.00995414 0.0340842 1 0 1 1 0 0 +EDGE2 8628 3388 0.00559914 -0.00220345 0.0283797 1 0 1 1 0 0 +EDGE2 8628 3147 -0.993713 0.146347 -0.00407999 1 0 1 1 0 0 +EDGE2 8628 5887 -1.05268 -0.0305421 0.00131828 1 0 1 1 0 0 +EDGE2 8628 8367 -0.995342 0.0849793 -0.0461181 1 0 1 1 0 0 +EDGE2 8628 8427 -0.90868 0.0629508 0.0182527 1 0 1 1 0 0 +EDGE2 8628 3387 -0.898056 0.00374038 0.0224904 1 0 1 1 0 0 +EDGE2 8628 3067 -1.05055 0.0215076 0.00900184 1 0 1 1 0 0 +EDGE2 8629 8370 0.937609 0.0695705 0.00713744 1 0 1 1 0 0 +EDGE2 8629 8470 0.924612 -0.0194708 -3.16131 1 0 1 1 0 0 +EDGE2 8629 8610 0.985349 -0.00277518 -3.17739 1 0 1 1 0 0 +EDGE2 8629 8430 0.97878 -0.0965429 -0.0255097 1 0 1 1 0 0 +EDGE2 8629 3070 1.07326 -0.0058991 0.0171917 1 0 1 1 0 0 +EDGE2 8629 3390 1.02061 0.0735762 0.0200041 1 0 1 1 0 0 +EDGE2 8629 3410 1.05278 0.0126749 -3.15744 1 0 1 1 0 0 +EDGE2 8629 5890 0.986985 0.052045 -0.0178855 1 0 1 1 0 0 +EDGE2 8629 3150 1.03124 -0.0535684 0.0150065 1 0 1 1 0 0 +EDGE2 8629 5889 0.0100474 -0.0291209 0.0236332 1 0 1 1 0 0 +EDGE2 8629 8429 -0.0378642 0.101894 -0.0237924 1 0 1 1 0 0 +EDGE2 8629 8369 -0.0136532 0.0193198 0.00439161 1 0 1 1 0 0 +EDGE2 8629 3149 0.118818 -0.0225393 -0.0052094 1 0 1 1 0 0 +EDGE2 8629 3389 0.00511947 0.0332527 -0.0141663 1 0 1 1 0 0 +EDGE2 8629 3069 0.0355801 0.0502994 0.0358348 1 0 1 1 0 0 +EDGE2 8629 5888 -0.998092 0.0382186 -0.0376133 1 0 1 1 0 0 +EDGE2 8629 8428 -0.982152 0.0385943 -0.0251119 1 0 1 1 0 0 +EDGE2 8629 8628 -0.939945 0.00175785 0.0329658 1 0 1 1 0 0 +EDGE2 8629 8368 -1.03551 0.00643816 -0.0109693 1 0 1 1 0 0 +EDGE2 8629 3068 -0.977137 0.014341 -0.0548322 1 0 1 1 0 0 +EDGE2 8629 3148 -0.958455 -0.00743618 -0.0150688 1 0 1 1 0 0 +EDGE2 8629 3388 -0.980499 -0.0325632 0.00616083 1 0 1 1 0 0 +EDGE2 8630 8469 0.93785 -0.0325641 -3.15139 1 0 1 1 0 0 +EDGE2 8630 8609 1.10472 0.0165093 -3.13215 1 0 1 1 0 0 +EDGE2 8630 3409 1.00514 0.0149027 -3.14683 1 0 1 1 0 0 +EDGE2 8630 8370 0.0347711 -0.0342941 -0.047027 1 0 1 1 0 0 +EDGE2 8630 3411 -0.00189386 -1.04549 -1.5637 1 0 1 1 0 0 +EDGE2 8630 5891 -0.0394539 -0.971513 -1.56349 1 0 1 1 0 0 +EDGE2 8630 8431 0.00381128 -0.921867 -1.55943 1 0 1 1 0 0 +EDGE2 8630 3391 -0.017319 -0.961041 -1.58771 1 0 1 1 0 0 +EDGE2 8630 8470 0.0728863 0.035075 -3.12632 1 0 1 1 0 0 +EDGE2 8630 8610 0.00720139 -0.0515316 -3.16361 1 0 1 1 0 0 +EDGE2 8630 8430 0.039594 0.0052371 -0.0495017 1 0 1 1 0 0 +EDGE2 8630 3070 -0.00987234 0.0213521 -0.0238286 1 0 1 1 0 0 +EDGE2 8630 3390 -0.108085 -0.0467458 0.0257965 1 0 1 1 0 0 +EDGE2 8630 3410 -0.0644202 -0.00886412 -3.18663 1 0 1 1 0 0 +EDGE2 8630 5890 -0.126716 0.00881494 -0.0219426 1 0 1 1 0 0 +EDGE2 8630 3150 -0.0279857 0.00702332 0.0151995 1 0 1 1 0 0 +EDGE2 8630 5889 -1.04213 0.0353711 -0.00327537 1 0 1 1 0 0 +EDGE2 8630 8429 -0.950532 -0.0388514 0.00739933 1 0 1 1 0 0 +EDGE2 8630 8629 -1.00619 0.0304947 0.00114525 1 0 1 1 0 0 +EDGE2 8630 8369 -1.02126 0.00669377 -0.019421 1 0 1 1 0 0 +EDGE2 8630 3149 -0.960008 0.0268891 -0.0102919 1 0 1 1 0 0 +EDGE2 8630 3389 -0.977559 -0.055726 -0.000830213 1 0 1 1 0 0 +EDGE2 8630 3069 -0.985836 -0.0797334 0.00958658 1 0 1 1 0 0 +EDGE2 8630 8611 0.00120246 0.988655 1.58179 1 0 1 1 0 0 +EDGE2 8630 3151 0.00388037 1.01582 1.59604 1 0 1 1 0 0 +EDGE2 8630 8371 -0.0797239 1.00746 1.59428 1 0 1 1 0 0 +EDGE2 8630 8471 -0.0413112 0.948799 1.56522 1 0 1 1 0 0 +EDGE2 8630 3071 -0.0666026 0.940285 1.52353 1 0 1 1 0 0 +EDGE2 8631 8370 -0.973477 0.0137009 -1.56773 1 0 1 1 0 0 +EDGE2 8631 8470 -1.02804 -0.000661462 1.59796 1 0 1 1 0 0 +EDGE2 8631 8610 -0.921408 0.0513643 1.55417 1 0 1 1 0 0 +EDGE2 8631 8630 -1.00069 -0.0192922 -1.54361 1 0 1 1 0 0 +EDGE2 8631 8430 -1.01387 -0.0594758 -1.59798 1 0 1 1 0 0 +EDGE2 8631 3070 -0.927147 -0.0038391 -1.59457 1 0 1 1 0 0 +EDGE2 8631 3390 -0.959703 -0.0999335 -1.54973 1 0 1 1 0 0 +EDGE2 8631 3410 -0.975836 0.0223147 1.5961 1 0 1 1 0 0 +EDGE2 8631 5890 -1.05112 -0.00814898 -1.59339 1 0 1 1 0 0 +EDGE2 8631 3150 -1.04939 0.0193938 -1.56396 1 0 1 1 0 0 +EDGE2 8631 8611 -0.0104126 0.0541093 -0.00138499 1 0 1 1 0 0 +EDGE2 8631 3072 0.93951 0.0663286 0.0061898 1 0 1 1 0 0 +EDGE2 8631 3151 0.0446214 0.00978229 -0.0103547 1 0 1 1 0 0 +EDGE2 8631 8371 -0.0983653 -0.0196911 0.00515849 1 0 1 1 0 0 +EDGE2 8631 8471 -0.164796 0.0953767 0.0344598 1 0 1 1 0 0 +EDGE2 8631 3071 0.118188 -0.0696157 -0.0126377 1 0 1 1 0 0 +EDGE2 8631 8372 1.05395 0.0741326 0.00867455 1 0 1 1 0 0 +EDGE2 8631 8472 0.997313 -0.0812555 -0.0178639 1 0 1 1 0 0 +EDGE2 8631 8612 1.06647 -0.0555172 0.00893331 1 0 1 1 0 0 +EDGE2 8631 3152 0.942174 -0.0378022 0.025064 1 0 1 1 0 0 +EDGE2 8632 8611 -1.01669 0.0285551 0.0139085 1 0 1 1 0 0 +EDGE2 8632 8631 -0.956206 0.0152758 -0.021737 1 0 1 1 0 0 +EDGE2 8632 3072 -0.0365678 0.0334084 -0.016059 1 0 1 1 0 0 +EDGE2 8632 3151 -1.0135 0.0206303 0.0164151 1 0 1 1 0 0 +EDGE2 8632 8371 -1.02726 0.105644 -0.0123671 1 0 1 1 0 0 +EDGE2 8632 8471 -1.02358 -0.0764919 -0.0111491 1 0 1 1 0 0 +EDGE2 8632 3071 -0.986188 0.0396676 3.49572e-05 1 0 1 1 0 0 +EDGE2 8632 8372 0.0578886 -0.0446397 -0.00365298 1 0 1 1 0 0 +EDGE2 8632 8472 -0.0357458 0.115822 0.00608878 1 0 1 1 0 0 +EDGE2 8632 8612 -0.0452006 -0.0157519 0.0326039 1 0 1 1 0 0 +EDGE2 8632 3152 0.0242631 -0.000347975 0.0194755 1 0 1 1 0 0 +EDGE2 8632 3153 1.00036 -0.0328545 0.00437556 1 0 1 1 0 0 +EDGE2 8632 8473 0.975295 -0.133837 -0.000608389 1 0 1 1 0 0 +EDGE2 8632 8613 1.04315 -0.0974791 0.0399631 1 0 1 1 0 0 +EDGE2 8632 8373 1.05015 -0.0219581 -0.0325492 1 0 1 1 0 0 +EDGE2 8632 3073 1.01269 0.0848079 -0.00473038 1 0 1 1 0 0 +EDGE2 8633 8374 1.08133 -0.0212818 0.000823478 1 0 1 1 0 0 +EDGE2 8633 3072 -0.988313 0.112756 -0.034345 1 0 1 1 0 0 +EDGE2 8633 8632 -1.03075 0.012873 -0.00606826 1 0 1 1 0 0 +EDGE2 8633 8372 -0.988077 0.0502904 -0.000433669 1 0 1 1 0 0 +EDGE2 8633 8472 -0.994782 -0.0830657 -0.0104441 1 0 1 1 0 0 +EDGE2 8633 8612 -1.05527 -0.000709513 -0.0153623 1 0 1 1 0 0 +EDGE2 8633 3152 -0.945274 -0.0686234 0.0151927 1 0 1 1 0 0 +EDGE2 8633 3153 -0.0217435 0.0172709 0.00996625 1 0 1 1 0 0 +EDGE2 8633 8473 0.0735851 -0.0269185 0.0346018 1 0 1 1 0 0 +EDGE2 8633 8613 0.00974509 0.00196901 -0.00560764 1 0 1 1 0 0 +EDGE2 8633 8373 -0.089376 0.0431797 0.00886605 1 0 1 1 0 0 +EDGE2 8633 8614 0.921354 -0.00365601 0.0034939 1 0 1 1 0 0 +EDGE2 8633 3073 0.0106689 -0.0336559 0.0124776 1 0 1 1 0 0 +EDGE2 8633 8474 1.03935 -0.0120982 0.0154049 1 0 1 1 0 0 +EDGE2 8633 3074 1.08688 0.107697 -0.00856523 1 0 1 1 0 0 +EDGE2 8633 3154 1.13395 -0.037359 -0.0417289 1 0 1 1 0 0 +EDGE2 8634 8374 -0.0548507 0.0888984 -0.0268626 1 0 1 1 0 0 +EDGE2 8634 3153 -1.07335 -0.050999 0.0080076 1 0 1 1 0 0 +EDGE2 8634 8473 -0.983714 0.0455831 -0.0370475 1 0 1 1 0 0 +EDGE2 8634 8613 -0.964864 -0.0284815 -0.0196938 1 0 1 1 0 0 +EDGE2 8634 8633 -1.00567 -0.0987754 -0.00619333 1 0 1 1 0 0 +EDGE2 8634 8373 -1.02409 -0.0424299 -0.0179084 1 0 1 1 0 0 +EDGE2 8634 8614 0.0215422 -0.0658156 -0.00544901 1 0 1 1 0 0 +EDGE2 8634 3073 -0.97334 -0.0280855 -0.015472 1 0 1 1 0 0 +EDGE2 8634 8474 0.0593017 0.0081886 0.0120239 1 0 1 1 0 0 +EDGE2 8634 1075 0.948008 -0.0274988 -3.14555 1 0 1 1 0 0 +EDGE2 8634 8615 0.995657 0.0767621 -0.00467231 1 0 1 1 0 0 +EDGE2 8634 3074 0.0535952 0.125092 -0.000716656 1 0 1 1 0 0 +EDGE2 8634 3154 -0.0963904 -0.0504829 -0.0147202 1 0 1 1 0 0 +EDGE2 8634 3155 0.975099 -0.0152643 -0.000829079 1 0 1 1 0 0 +EDGE2 8634 8375 1.0645 0.0229652 -0.0220964 1 0 1 1 0 0 +EDGE2 8634 8475 1.00281 -0.0825401 -0.0138308 1 0 1 1 0 0 +EDGE2 8634 3075 0.967419 0.0353147 -0.0329692 1 0 1 1 0 0 +EDGE2 8634 995 0.981641 0.0162006 -3.20028 1 0 1 1 0 0 +EDGE2 8634 1015 1.02168 0.0376926 -3.14196 1 0 1 1 0 0 +EDGE2 8634 1055 1.03019 -0.0322967 -3.16195 1 0 1 1 0 0 +EDGE2 8635 1016 0.0662251 -0.960874 -1.56278 1 0 1 1 0 0 +EDGE2 8635 1056 -0.023454 -1.04617 -1.55007 1 0 1 1 0 0 +EDGE2 8635 996 -0.00225529 -0.952024 -1.52438 1 0 1 1 0 0 +EDGE2 8635 8374 -0.957171 0.00630265 -0.0376233 1 0 1 1 0 0 +EDGE2 8635 8614 -0.964893 -0.0158643 -0.00960762 1 0 1 1 0 0 +EDGE2 8635 8634 -0.925415 0.0678733 -0.0352205 1 0 1 1 0 0 +EDGE2 8635 8474 -0.927218 -0.0595914 -0.00197932 1 0 1 1 0 0 +EDGE2 8635 1075 -0.0565213 -0.0253838 -3.1388 1 0 1 1 0 0 +EDGE2 8635 8615 0.0679723 -0.0011615 -0.0495506 1 0 1 1 0 0 +EDGE2 8635 3074 -0.982709 -0.0815158 0.0355867 1 0 1 1 0 0 +EDGE2 8635 3154 -0.940585 0.00116309 0.00706855 1 0 1 1 0 0 +EDGE2 8635 3155 0.136282 -0.0679182 -0.0105908 1 0 1 1 0 0 +EDGE2 8635 8375 0.00763126 -0.0612505 0.00118832 1 0 1 1 0 0 +EDGE2 8635 8475 -0.0234231 -0.0234792 -0.00846186 1 0 1 1 0 0 +EDGE2 8635 3075 -0.0215084 0.00673197 0.0119628 1 0 1 1 0 0 +EDGE2 8635 1074 1.09616 -0.0398897 -3.13222 1 0 1 1 0 0 +EDGE2 8635 995 -0.0680106 0.00623306 -3.10225 1 0 1 1 0 0 +EDGE2 8635 1015 0.0378841 -0.062453 -3.14219 1 0 1 1 0 0 +EDGE2 8635 1055 -0.0483093 0.0685157 -3.15639 1 0 1 1 0 0 +EDGE2 8635 1014 1.0347 0.0323165 -3.11784 1 0 1 1 0 0 +EDGE2 8635 1054 1.00415 -0.0195481 -3.16789 1 0 1 1 0 0 +EDGE2 8635 994 0.962105 0.0391411 -3.15396 1 0 1 1 0 0 +EDGE2 8635 3156 0.0216964 0.951136 1.58561 1 0 1 1 0 0 +EDGE2 8635 8476 -0.0314187 1.05324 1.58816 1 0 1 1 0 0 +EDGE2 8635 8616 -0.00580246 1.0504 1.55852 1 0 1 1 0 0 +EDGE2 8635 8376 -0.0617546 1.02077 1.60638 1 0 1 1 0 0 +EDGE2 8635 1076 0.0341812 1.0554 1.59935 1 0 1 1 0 0 +EDGE2 8635 3076 -0.0257172 0.972402 1.60739 1 0 1 1 0 0 +EDGE2 8636 997 1.0127 -0.0130399 0.0178519 1 0 1 1 0 0 +EDGE2 8636 1057 0.956582 -0.0166133 0.0058688 1 0 1 1 0 0 +EDGE2 8636 1017 0.974482 0.0058808 -0.0219149 1 0 1 1 0 0 +EDGE2 8636 1016 0.0998564 -0.0754843 -0.0126933 1 0 1 1 0 0 +EDGE2 8636 1056 -0.0605575 0.0712861 0.0218601 1 0 1 1 0 0 +EDGE2 8636 996 -0.0646424 -0.0143808 0.00176982 1 0 1 1 0 0 +EDGE2 8636 1075 -1.00278 -0.0226728 -1.56244 1 0 1 1 0 0 +EDGE2 8636 8615 -0.977504 -0.00301924 1.57721 1 0 1 1 0 0 +EDGE2 8636 8635 -0.92002 0.0172018 1.549 1 0 1 1 0 0 +EDGE2 8636 3155 -1.03259 0.0810636 1.60357 1 0 1 1 0 0 +EDGE2 8636 8375 -1.06077 -0.0121167 1.53571 1 0 1 1 0 0 +EDGE2 8636 8475 -1.00731 -0.0197602 1.57874 1 0 1 1 0 0 +EDGE2 8636 3075 -1.08487 0.00649215 1.54977 1 0 1 1 0 0 +EDGE2 8636 995 -0.972707 -0.00667377 -1.52217 1 0 1 1 0 0 +EDGE2 8636 1015 -1.01499 -0.01395 -1.57308 1 0 1 1 0 0 +EDGE2 8636 1055 -0.959439 0.0513357 -1.57962 1 0 1 1 0 0 +EDGE2 8637 998 1.00307 -0.0399632 0.012481 1 0 1 1 0 0 +EDGE2 8637 1018 0.990552 -0.0571277 0.0101664 1 0 1 1 0 0 +EDGE2 8637 1058 1.02784 -0.00307242 0.0235385 1 0 1 1 0 0 +EDGE2 8637 997 0.0152797 0.0717574 0.00611913 1 0 1 1 0 0 +EDGE2 8637 1057 -0.0482325 0.0561327 -0.0236627 1 0 1 1 0 0 +EDGE2 8637 1017 0.00239855 0.0326924 -0.00642051 1 0 1 1 0 0 +EDGE2 8637 1016 -0.909005 -0.0118009 0.0048718 1 0 1 1 0 0 +EDGE2 8637 1056 -1.05577 0.0371066 0.00183024 1 0 1 1 0 0 +EDGE2 8637 8636 -1.00888 -0.0293982 0.0067656 1 0 1 1 0 0 +EDGE2 8637 996 -1.03593 -0.0100117 0.0182232 1 0 1 1 0 0 +EDGE2 8638 8637 -1.01744 -0.0340301 0.00322239 1 0 1 1 0 0 +EDGE2 8638 1019 1.028 0.0326183 0.0247835 1 0 1 1 0 0 +EDGE2 8638 1059 0.977224 -0.0080031 -0.0122274 1 0 1 1 0 0 +EDGE2 8638 999 1.00032 0.0235604 0.0241703 1 0 1 1 0 0 +EDGE2 8638 998 0.00420296 -0.00246186 0.00311719 1 0 1 1 0 0 +EDGE2 8638 1018 0.0636927 -0.0867805 0.0319012 1 0 1 1 0 0 +EDGE2 8638 1058 -0.0437265 -0.0846544 0.0209951 1 0 1 1 0 0 +EDGE2 8638 997 -1.04438 -0.0136343 0.00392828 1 0 1 1 0 0 +EDGE2 8638 1057 -0.997395 0.0550544 0.0066463 1 0 1 1 0 0 +EDGE2 8638 1017 -0.965451 0.0548672 0.00152152 1 0 1 1 0 0 +EDGE2 8639 980 1.00547 0.0646226 -3.12879 1 0 1 1 0 0 +EDGE2 8639 1020 0.97368 0.0663287 -0.0122722 1 0 1 1 0 0 +EDGE2 8639 1060 0.949525 0.0253985 0.0228804 1 0 1 1 0 0 +EDGE2 8639 8460 0.951954 0.0535582 -3.13889 1 0 1 1 0 0 +EDGE2 8639 1000 0.967389 0.00597664 0.0122376 1 0 1 1 0 0 +EDGE2 8639 940 1.0352 -0.108239 -3.16931 1 0 1 1 0 0 +EDGE2 8639 8638 -1.08364 -0.064694 -0.0220607 1 0 1 1 0 0 +EDGE2 8639 1019 -0.0960061 -0.000820547 0.0160613 1 0 1 1 0 0 +EDGE2 8639 1059 0.0253295 -0.0670177 -0.0599007 1 0 1 1 0 0 +EDGE2 8639 999 -0.0458368 -0.0410501 -0.0234514 1 0 1 1 0 0 +EDGE2 8639 998 -0.990224 -0.0154816 0.0100794 1 0 1 1 0 0 +EDGE2 8639 1018 -1.01433 -0.0551052 -0.0181077 1 0 1 1 0 0 +EDGE2 8639 1058 -1.02346 0.0158022 -0.011161 1 0 1 1 0 0 +EDGE2 8640 979 0.99939 -0.0759134 -3.13807 1 0 1 1 0 0 +EDGE2 8640 8459 0.952256 0.0743173 -3.15789 1 0 1 1 0 0 +EDGE2 8640 939 0.947925 -0.113531 -3.11938 1 0 1 1 0 0 +EDGE2 8640 980 -0.0449995 0.00808751 -3.16123 1 0 1 1 0 0 +EDGE2 8640 8461 -0.00991974 -0.96963 -1.60455 1 0 1 1 0 0 +EDGE2 8640 1020 -0.00775078 0.0140935 -0.00710334 1 0 1 1 0 0 +EDGE2 8640 1060 0.0133988 0.0363757 -0.0179466 1 0 1 1 0 0 +EDGE2 8640 8460 0.0135577 0.015572 -3.14989 1 0 1 1 0 0 +EDGE2 8640 1000 0.066091 -0.056152 0.0167414 1 0 1 1 0 0 +EDGE2 8640 1001 -0.0382322 1.0315 1.61319 1 0 1 1 0 0 +EDGE2 8640 1061 0.0649735 1.04314 1.60872 1 0 1 1 0 0 +EDGE2 8640 940 0.02911 -0.000846997 -3.14942 1 0 1 1 0 0 +EDGE2 8640 1021 -0.0167139 1.05114 1.57055 1 0 1 1 0 0 +EDGE2 8640 941 -0.00104195 0.984567 1.59175 1 0 1 1 0 0 +EDGE2 8640 981 0.0439469 1.02871 1.5841 1 0 1 1 0 0 +EDGE2 8640 1019 -0.927988 -0.079529 0.00166053 1 0 1 1 0 0 +EDGE2 8640 1059 -1.03689 0.0435349 0.00475845 1 0 1 1 0 0 +EDGE2 8640 8639 -1.12416 0.0543218 -0.00789646 1 0 1 1 0 0 +EDGE2 8640 999 -0.959561 -0.064603 0.0044755 1 0 1 1 0 0 +EDGE2 8641 942 0.960366 0.000799948 0.00556291 1 0 1 1 0 0 +EDGE2 8641 1022 0.966097 -0.0382164 -0.000760271 1 0 1 1 0 0 +EDGE2 8641 980 -0.936314 -0.00256006 1.58615 1 0 1 1 0 0 +EDGE2 8641 8640 -1.06909 0.0521303 -1.578 1 0 1 1 0 0 +EDGE2 8641 1020 -1.0128 0.0283044 -1.59504 1 0 1 1 0 0 +EDGE2 8641 1060 -1.06947 0.0459101 -1.55542 1 0 1 1 0 0 +EDGE2 8641 8460 -0.905919 -0.0135852 1.54584 1 0 1 1 0 0 +EDGE2 8641 1000 -0.998329 0.0418658 -1.58335 1 0 1 1 0 0 +EDGE2 8641 1001 0.00645707 -0.0353553 0.00165529 1 0 1 1 0 0 +EDGE2 8641 1061 -0.0426168 -0.0163458 -0.0120445 1 0 1 1 0 0 +EDGE2 8641 940 -1.01033 -0.0234337 1.58729 1 0 1 1 0 0 +EDGE2 8641 1021 0.0498655 0.0474489 0.0126919 1 0 1 1 0 0 +EDGE2 8641 941 0.000665174 0.0364013 0.00695651 1 0 1 1 0 0 +EDGE2 8641 981 -0.0174153 -0.0291527 -0.0109027 1 0 1 1 0 0 +EDGE2 8641 1062 1.08531 -0.101165 -0.00947209 1 0 1 1 0 0 +EDGE2 8641 982 0.923441 0.00258334 -0.0342264 1 0 1 1 0 0 +EDGE2 8641 1002 1.06273 -0.0089642 0.00048691 1 0 1 1 0 0 +EDGE2 8642 942 -0.117503 -0.00919339 0.00116313 1 0 1 1 0 0 +EDGE2 8642 1022 0.00561576 -0.0309177 0.000619824 1 0 1 1 0 0 +EDGE2 8642 1001 -1.04933 -0.108102 0.00770362 1 0 1 1 0 0 +EDGE2 8642 1061 -0.977404 0.000794728 0.0128425 1 0 1 1 0 0 +EDGE2 8642 8641 -0.993313 0.00326377 0.0428302 1 0 1 1 0 0 +EDGE2 8642 1021 -0.948099 -0.00875375 0.0382358 1 0 1 1 0 0 +EDGE2 8642 941 -1.02761 -0.00778194 0.0455878 1 0 1 1 0 0 +EDGE2 8642 981 -0.90454 0.0232208 -0.0021821 1 0 1 1 0 0 +EDGE2 8642 1062 0.0612105 0.022218 -0.0169479 1 0 1 1 0 0 +EDGE2 8642 982 -0.0311824 0.0403967 0.0181 1 0 1 1 0 0 +EDGE2 8642 1002 -0.0489065 0.00343633 0.0329637 1 0 1 1 0 0 +EDGE2 8642 983 1.01507 0.0237812 -0.00832142 1 0 1 1 0 0 +EDGE2 8642 1023 1.05104 0.0231963 -0.0157184 1 0 1 1 0 0 +EDGE2 8642 1063 1.07271 0.0471243 0.0179557 1 0 1 1 0 0 +EDGE2 8642 1003 0.986361 -0.0510042 0.0225597 1 0 1 1 0 0 +EDGE2 8642 943 1.03876 -0.0141976 -0.021823 1 0 1 1 0 0 +EDGE2 8643 942 -0.99461 0.0426513 0.00303911 1 0 1 1 0 0 +EDGE2 8643 1022 -1.03121 -0.0653861 0.00526227 1 0 1 1 0 0 +EDGE2 8643 8642 -1.01875 -0.0817885 -0.0102181 1 0 1 1 0 0 +EDGE2 8643 1062 -0.979686 0.0274603 0.00191052 1 0 1 1 0 0 +EDGE2 8643 982 -1.02121 0.00509323 0.0289939 1 0 1 1 0 0 +EDGE2 8643 1002 -0.95232 0.0313451 0.0163895 1 0 1 1 0 0 +EDGE2 8643 1004 0.971516 0.0405285 -0.0422578 1 0 1 1 0 0 +EDGE2 8643 983 -0.0504903 -0.0781045 0.0368042 1 0 1 1 0 0 +EDGE2 8643 1023 -0.0558148 0.0488531 -0.00291571 1 0 1 1 0 0 +EDGE2 8643 1063 -0.0230949 -0.0257221 -0.0171922 1 0 1 1 0 0 +EDGE2 8643 1003 -0.00124933 -0.0382475 0.00891218 1 0 1 1 0 0 +EDGE2 8643 1064 0.932611 -0.0120448 0.00316018 1 0 1 1 0 0 +EDGE2 8643 943 0.0171564 -0.071958 0.00609487 1 0 1 1 0 0 +EDGE2 8643 1024 1.03682 -0.0398522 -0.0103314 1 0 1 1 0 0 +EDGE2 8643 944 1.01781 -0.0159491 -0.0331609 1 0 1 1 0 0 +EDGE2 8643 984 1.06198 -0.00913894 5.1889e-05 1 0 1 1 0 0 +EDGE2 8644 1004 -0.0923997 0.0940295 -0.0112413 1 0 1 1 0 0 +EDGE2 8644 983 -1.02335 -0.0684384 -0.0277923 1 0 1 1 0 0 +EDGE2 8644 1023 -1.01332 -0.002003 -0.0364391 1 0 1 1 0 0 +EDGE2 8644 1063 -0.996828 -0.045269 0.0028217 1 0 1 1 0 0 +EDGE2 8644 8643 -0.978079 -0.0268055 0.0293425 1 0 1 1 0 0 +EDGE2 8644 1003 -1.08348 0.030257 0.022866 1 0 1 1 0 0 +EDGE2 8644 1064 -0.00670324 -0.0861663 -0.00765348 1 0 1 1 0 0 +EDGE2 8644 943 -1.00283 0.0210667 -0.0079418 1 0 1 1 0 0 +EDGE2 8644 1024 -0.0624356 -0.110824 0.0198336 1 0 1 1 0 0 +EDGE2 8644 1025 1.05215 -0.0289753 -0.0292866 1 0 1 1 0 0 +EDGE2 8644 944 -0.00131281 -0.00774058 -0.0148446 1 0 1 1 0 0 +EDGE2 8644 984 -0.00303274 -0.0728298 -0.0231616 1 0 1 1 0 0 +EDGE2 8644 1065 1.00091 0.00593664 0.0117867 1 0 1 1 0 0 +EDGE2 8644 945 0.930762 0.00671343 0.00479279 1 0 1 1 0 0 +EDGE2 8644 985 1.04438 -0.0371681 -0.0231633 1 0 1 1 0 0 +EDGE2 8644 1005 1.00554 0.0242121 0.0302571 1 0 1 1 0 0 +EDGE2 8645 946 0.0379439 -1.0956 -1.51632 1 0 1 1 0 0 +EDGE2 8645 1004 -1.09243 0.118674 -0.0182623 1 0 1 1 0 0 +EDGE2 8645 1064 -0.966123 0.021076 -0.0291328 1 0 1 1 0 0 +EDGE2 8645 8644 -0.999358 -0.0144789 -0.0267494 1 0 1 1 0 0 +EDGE2 8645 1024 -0.892087 -0.0241312 0.018447 1 0 1 1 0 0 +EDGE2 8645 1025 0.0365753 -0.015568 -0.0119274 1 0 1 1 0 0 +EDGE2 8645 944 -1.04255 -0.0700747 0.0297164 1 0 1 1 0 0 +EDGE2 8645 984 -0.96323 -0.0764992 0.0329612 1 0 1 1 0 0 +EDGE2 8645 1065 0.0389162 -0.0557345 0.0168372 1 0 1 1 0 0 +EDGE2 8645 945 -0.0466457 0.0469765 -0.0197391 1 0 1 1 0 0 +EDGE2 8645 985 -0.0526623 0.000191703 0.0139321 1 0 1 1 0 0 +EDGE2 8645 1005 -0.0426747 0.0407039 0.0217296 1 0 1 1 0 0 +EDGE2 8645 986 0.0014424 0.918373 1.56171 1 0 1 1 0 0 +EDGE2 8645 1026 0.125472 1.07275 1.5493 1 0 1 1 0 0 +EDGE2 8645 1066 0.0250625 0.959194 1.56785 1 0 1 1 0 0 +EDGE2 8645 1006 0.0152703 0.994325 1.5984 1 0 1 1 0 0 +EDGE2 8646 1025 -1.0013 -0.0434933 -1.56689 1 0 1 1 0 0 +EDGE2 8646 8645 -1.03269 -0.0135152 -1.54105 1 0 1 1 0 0 +EDGE2 8646 1065 -0.988625 -0.0251875 -1.59303 1 0 1 1 0 0 +EDGE2 8646 945 -1.005 0.0100667 -1.57292 1 0 1 1 0 0 +EDGE2 8646 985 -0.967056 0.00993807 -1.56502 1 0 1 1 0 0 +EDGE2 8646 1005 -1.02335 -0.00416863 -1.60154 1 0 1 1 0 0 +EDGE2 8646 987 1.00481 -0.0846769 0.0323929 1 0 1 1 0 0 +EDGE2 8646 986 -0.0873915 -0.0722094 0.0106415 1 0 1 1 0 0 +EDGE2 8646 1026 -0.00328936 0.101051 0.00266867 1 0 1 1 0 0 +EDGE2 8646 1066 0.0277646 0.0191032 0.005491 1 0 1 1 0 0 +EDGE2 8646 1006 0.11122 -0.0418994 -0.0218691 1 0 1 1 0 0 +EDGE2 8646 1027 1.01736 0.0275104 -0.0144692 1 0 1 1 0 0 +EDGE2 8646 1067 0.993474 0.00482123 -0.00127806 1 0 1 1 0 0 +EDGE2 8646 1007 1.03965 0.0284129 -0.0106141 1 0 1 1 0 0 +EDGE2 8647 1028 1.07342 0.0565834 0.0172402 1 0 1 1 0 0 +EDGE2 8647 987 -0.0817027 0.0035745 -0.0211387 1 0 1 1 0 0 +EDGE2 8647 986 -0.954255 0.0976298 -0.0071373 1 0 1 1 0 0 +EDGE2 8647 1026 -0.979295 0.00228207 -0.0204399 1 0 1 1 0 0 +EDGE2 8647 1066 -0.971204 0.0247211 0.0208922 1 0 1 1 0 0 +EDGE2 8647 8646 -1.03848 -0.0237539 -0.0213134 1 0 1 1 0 0 +EDGE2 8647 1006 -1.03435 -0.0769411 -0.00685846 1 0 1 1 0 0 +EDGE2 8647 1027 0.00914691 0.0345795 0.0277505 1 0 1 1 0 0 +EDGE2 8647 1067 0.0286385 -0.105507 0.0227174 1 0 1 1 0 0 +EDGE2 8647 1007 0.0555508 0.129598 0.0217499 1 0 1 1 0 0 +EDGE2 8647 1068 0.953037 0.0835753 -0.0151389 1 0 1 1 0 0 +EDGE2 8647 988 0.904712 -0.0326406 0.0228842 1 0 1 1 0 0 +EDGE2 8647 1008 0.969302 0.0196282 -0.00726333 1 0 1 1 0 0 +EDGE2 8648 1028 0.0476796 -0.0430575 -0.0217677 1 0 1 1 0 0 +EDGE2 8648 987 -0.903906 0.039176 0.0232495 1 0 1 1 0 0 +EDGE2 8648 1027 -0.945386 0.00103393 0.0271722 1 0 1 1 0 0 +EDGE2 8648 1067 -0.999721 -0.0174479 0.0173563 1 0 1 1 0 0 +EDGE2 8648 8647 -0.920173 0.0205087 0.0149204 1 0 1 1 0 0 +EDGE2 8648 1007 -0.956645 -0.111587 0.00190468 1 0 1 1 0 0 +EDGE2 8648 1068 0.0720543 -0.0114558 -0.0630183 1 0 1 1 0 0 +EDGE2 8648 1069 1.03494 0.0209983 -0.0124481 1 0 1 1 0 0 +EDGE2 8648 988 -0.0889928 -0.0152989 -0.00943341 1 0 1 1 0 0 +EDGE2 8648 1008 -0.0121722 0.00754888 -0.00616417 1 0 1 1 0 0 +EDGE2 8648 989 1.04113 0.019749 0.0218833 1 0 1 1 0 0 +EDGE2 8648 1009 0.958044 0.033569 0.0123351 1 0 1 1 0 0 +EDGE2 8648 1029 0.968685 -0.027533 -0.0425903 1 0 1 1 0 0 +EDGE2 8649 1028 -0.924593 0.0237285 -0.0170627 1 0 1 1 0 0 +EDGE2 8649 8648 -1.02184 -0.0128907 -0.0137048 1 0 1 1 0 0 +EDGE2 8649 1068 -1.03766 0.0892094 0.0122551 1 0 1 1 0 0 +EDGE2 8649 1069 -0.0573279 -0.00191674 -0.018577 1 0 1 1 0 0 +EDGE2 8649 988 -0.953741 0.0300024 0.024703 1 0 1 1 0 0 +EDGE2 8649 1008 -1.08225 0.00494327 0.00221166 1 0 1 1 0 0 +EDGE2 8649 989 -0.0923402 -0.0308803 -0.00891305 1 0 1 1 0 0 +EDGE2 8649 1009 -0.0144877 0.0111746 -0.00191863 1 0 1 1 0 0 +EDGE2 8649 1029 0.0207772 -0.0616881 -0.0162449 1 0 1 1 0 0 +EDGE2 8649 1010 0.99604 -0.0355129 0.0057443 1 0 1 1 0 0 +EDGE2 8649 1050 0.97215 0.00494894 -3.13851 1 0 1 1 0 0 +EDGE2 8649 1070 1.03952 -0.0613062 -0.00126479 1 0 1 1 0 0 +EDGE2 8649 1030 1.02968 -0.00211821 -0.011577 1 0 1 1 0 0 +EDGE2 8649 990 0.960497 0.0828184 0.00624522 1 0 1 1 0 0 +EDGE2 8650 1069 -1.07079 0.105444 -0.010817 1 0 1 1 0 0 +EDGE2 8650 8649 -0.991638 -0.0487716 -0.00129499 1 0 1 1 0 0 +EDGE2 8650 989 -0.99772 0.03534 0.0171719 1 0 1 1 0 0 +EDGE2 8650 1009 -0.967314 0.00527911 -0.0146681 1 0 1 1 0 0 +EDGE2 8650 1029 -0.890877 -0.047487 0.012424 1 0 1 1 0 0 +EDGE2 8650 1010 0.101271 -0.051554 -0.0159056 1 0 1 1 0 0 +EDGE2 8650 1011 0.00564926 1.02943 1.58639 1 0 1 1 0 0 +EDGE2 8650 1051 0.0706797 0.918104 1.61303 1 0 1 1 0 0 +EDGE2 8650 1071 -0.0523507 1.04048 1.57752 1 0 1 1 0 0 +EDGE2 8650 991 -0.00956687 1.00685 1.57652 1 0 1 1 0 0 +EDGE2 8650 1050 -0.0246547 -0.130275 -3.17177 1 0 1 1 0 0 +EDGE2 8650 1070 -0.0858604 -0.0239694 -0.000590691 1 0 1 1 0 0 +EDGE2 8650 1030 -0.0415932 0.045253 -0.00299492 1 0 1 1 0 0 +EDGE2 8650 1031 0.0564122 -0.953624 -1.58622 1 0 1 1 0 0 +EDGE2 8650 990 -0.0116451 0.0512141 0.00604203 1 0 1 1 0 0 +EDGE2 8650 1049 0.942399 0.00912906 -3.13579 1 0 1 1 0 0 +EDGE2 8651 992 1.01263 0.00983179 -0.013044 1 0 1 1 0 0 +EDGE2 8651 1052 0.990591 -0.0285421 0.000543137 1 0 1 1 0 0 +EDGE2 8651 1072 0.953802 -0.0658105 0.0122489 1 0 1 1 0 0 +EDGE2 8651 1012 1.02118 0.0141463 -0.0266081 1 0 1 1 0 0 +EDGE2 8651 1010 -1.11961 -0.0443925 -1.5719 1 0 1 1 0 0 +EDGE2 8651 1011 -0.0319281 -0.0325892 -0.00394876 1 0 1 1 0 0 +EDGE2 8651 1051 0.0252234 0.0290437 0.0315215 1 0 1 1 0 0 +EDGE2 8651 1071 -0.0594701 0.0314047 -0.00211125 1 0 1 1 0 0 +EDGE2 8651 991 -0.00467801 0.0139845 0.0216719 1 0 1 1 0 0 +EDGE2 8651 1050 -0.942144 -0.0250497 1.57418 1 0 1 1 0 0 +EDGE2 8651 1070 -1.03457 -0.0102039 -1.58871 1 0 1 1 0 0 +EDGE2 8651 8650 -1.02565 -0.0867335 -1.63259 1 0 1 1 0 0 +EDGE2 8651 1030 -0.963634 -0.0402786 -1.57991 1 0 1 1 0 0 +EDGE2 8651 990 -0.912904 -0.0639251 -1.57764 1 0 1 1 0 0 +EDGE2 8652 8651 -1.03117 0.173772 -0.00175097 1 0 1 1 0 0 +EDGE2 8652 992 0.0977647 -0.0391416 -0.031892 1 0 1 1 0 0 +EDGE2 8652 993 1.04375 0.0552954 -0.0362967 1 0 1 1 0 0 +EDGE2 8652 1053 1.05354 -0.0777569 0.0165534 1 0 1 1 0 0 +EDGE2 8652 1073 0.95153 0.0456309 -0.0338029 1 0 1 1 0 0 +EDGE2 8652 1013 0.997143 0.047811 0.000461688 1 0 1 1 0 0 +EDGE2 8652 1052 -0.0067105 0.0138433 -0.00393873 1 0 1 1 0 0 +EDGE2 8652 1072 0.0193976 -0.0207392 -0.0146849 1 0 1 1 0 0 +EDGE2 8652 1012 0.0107866 -0.0625871 -0.0197426 1 0 1 1 0 0 +EDGE2 8652 1011 -0.969328 0.0482971 0.0125439 1 0 1 1 0 0 +EDGE2 8652 1051 -0.932681 0.0120603 -0.0270219 1 0 1 1 0 0 +EDGE2 8652 1071 -0.946053 0.0759119 -0.000560102 1 0 1 1 0 0 +EDGE2 8652 991 -1.02358 -0.0909352 0.0134079 1 0 1 1 0 0 +EDGE2 8653 1074 1.02068 0.00990611 0.00376361 1 0 1 1 0 0 +EDGE2 8653 1014 0.956174 -0.047462 0.0200103 1 0 1 1 0 0 +EDGE2 8653 1054 0.995777 -0.0160168 0.0148676 1 0 1 1 0 0 +EDGE2 8653 994 1.01312 0.0580702 -0.0224055 1 0 1 1 0 0 +EDGE2 8653 992 -1.13898 -0.0355488 0.0401166 1 0 1 1 0 0 +EDGE2 8653 993 -0.0319443 0.0587895 -0.0198945 1 0 1 1 0 0 +EDGE2 8653 1053 0.0394798 -0.00984956 -0.0369146 1 0 1 1 0 0 +EDGE2 8653 1073 0.0604957 -0.0493224 0.0108746 1 0 1 1 0 0 +EDGE2 8653 1013 0.0730875 -0.0339558 -0.0579814 1 0 1 1 0 0 +EDGE2 8653 1052 -1.0261 0.0379131 -0.00523103 1 0 1 1 0 0 +EDGE2 8653 1072 -1.05182 0.0744774 0.00888176 1 0 1 1 0 0 +EDGE2 8653 8652 -1.00692 0.0441333 0.00352063 1 0 1 1 0 0 +EDGE2 8653 1012 -1.0213 0.0151483 -0.00908955 1 0 1 1 0 0 +EDGE2 8654 1075 0.920358 -0.086734 -0.00457312 1 0 1 1 0 0 +EDGE2 8654 8615 0.912408 -0.0293062 -3.15708 1 0 1 1 0 0 +EDGE2 8654 8635 0.90323 0.0235106 -3.13978 1 0 1 1 0 0 +EDGE2 8654 3155 0.970439 0.0524955 -3.18039 1 0 1 1 0 0 +EDGE2 8654 8375 1.00716 -0.0844129 -3.18179 1 0 1 1 0 0 +EDGE2 8654 8475 1.01144 -0.134438 -3.13035 1 0 1 1 0 0 +EDGE2 8654 3075 1.01092 0.0250739 -3.12947 1 0 1 1 0 0 +EDGE2 8654 1074 0.0173245 0.0431243 -0.00014331 1 0 1 1 0 0 +EDGE2 8654 995 1.01267 0.000700998 -0.00836543 1 0 1 1 0 0 +EDGE2 8654 1015 0.970315 0.00606814 -0.0354735 1 0 1 1 0 0 +EDGE2 8654 1055 0.985395 0.0147204 -0.0392384 1 0 1 1 0 0 +EDGE2 8654 1014 -0.0790717 -0.0311431 -0.016181 1 0 1 1 0 0 +EDGE2 8654 1054 0.0130497 0.025383 0.018318 1 0 1 1 0 0 +EDGE2 8654 994 -0.0499005 -0.030276 -0.014124 1 0 1 1 0 0 +EDGE2 8654 993 -0.918192 -0.0138582 -0.00466415 1 0 1 1 0 0 +EDGE2 8654 1053 -1.01165 0.0219844 0.0238243 1 0 1 1 0 0 +EDGE2 8654 1073 -1.01675 0.0529222 -0.0062253 1 0 1 1 0 0 +EDGE2 8654 8653 -1.04047 0.0604347 0.0127817 1 0 1 1 0 0 +EDGE2 8654 1013 -0.963855 -0.0383987 0.0229875 1 0 1 1 0 0 +EDGE2 8655 1016 -0.0145563 1.037 1.55958 1 0 1 1 0 0 +EDGE2 8655 1056 0.00659404 0.967377 1.56504 1 0 1 1 0 0 +EDGE2 8655 8636 -0.0468856 1.01957 1.54861 1 0 1 1 0 0 +EDGE2 8655 996 -0.00267748 1.0241 1.51416 1 0 1 1 0 0 +EDGE2 8655 8374 1.05469 0.00672181 -3.15196 1 0 1 1 0 0 +EDGE2 8655 8614 1.06156 -0.149103 -3.14694 1 0 1 1 0 0 +EDGE2 8655 8634 1.04321 0.0765109 -3.16982 1 0 1 1 0 0 +EDGE2 8655 8474 1.04472 -0.0591409 -3.15588 1 0 1 1 0 0 +EDGE2 8655 1075 -0.00151843 0.0654325 -0.00123023 1 0 1 1 0 0 +EDGE2 8655 8615 -0.0125512 -0.0267346 -3.13895 1 0 1 1 0 0 +EDGE2 8655 3074 0.996217 -0.0152296 -3.178 1 0 1 1 0 0 +EDGE2 8655 3154 1.02737 -0.125713 -3.14354 1 0 1 1 0 0 +EDGE2 8655 8635 -0.020388 -0.035632 -3.13336 1 0 1 1 0 0 +EDGE2 8655 3155 0.015142 -0.087488 -3.14968 1 0 1 1 0 0 +EDGE2 8655 8375 0.0638227 -0.0407357 -3.12281 1 0 1 1 0 0 +EDGE2 8655 8475 0.00154944 -0.0708383 -3.17134 1 0 1 1 0 0 +EDGE2 8655 3075 -0.0785564 0.0262512 -3.11763 1 0 1 1 0 0 +EDGE2 8655 1074 -0.990645 0.0338962 -0.0136217 1 0 1 1 0 0 +EDGE2 8655 995 0.0314409 0.03829 -0.00423028 1 0 1 1 0 0 +EDGE2 8655 1015 0.0307408 0.0254306 0.0341389 1 0 1 1 0 0 +EDGE2 8655 1055 -0.0434199 0.0369388 -0.0169544 1 0 1 1 0 0 +EDGE2 8655 8654 -1.06101 0.000451438 0.0105986 1 0 1 1 0 0 +EDGE2 8655 1014 -0.963453 0.0174709 0.00866504 1 0 1 1 0 0 +EDGE2 8655 1054 -0.959458 -0.0567017 -0.00250715 1 0 1 1 0 0 +EDGE2 8655 994 -0.99252 -0.0880609 -0.00493253 1 0 1 1 0 0 +EDGE2 8655 3156 -0.00943572 -0.924905 -1.5596 1 0 1 1 0 0 +EDGE2 8655 8476 0.0279258 -1.02518 -1.57898 1 0 1 1 0 0 +EDGE2 8655 8616 0.0395267 -1.00642 -1.60354 1 0 1 1 0 0 +EDGE2 8655 8376 -0.0254362 -1.02154 -1.55885 1 0 1 1 0 0 +EDGE2 8655 1076 0.0308095 -1.00569 -1.56384 1 0 1 1 0 0 +EDGE2 8655 3076 -0.06123 -1.0302 -1.60257 1 0 1 1 0 0 +EDGE2 8656 1075 -1.03359 -0.0375735 1.54256 1 0 1 1 0 0 +EDGE2 8656 8615 -1.03808 -0.122094 -1.58349 1 0 1 1 0 0 +EDGE2 8656 8655 -0.947086 -0.092086 1.59531 1 0 1 1 0 0 +EDGE2 8656 8635 -1.0768 0.0220101 -1.57192 1 0 1 1 0 0 +EDGE2 8656 3155 -0.980135 0.0605171 -1.54448 1 0 1 1 0 0 +EDGE2 8656 8375 -0.98855 -0.035948 -1.58296 1 0 1 1 0 0 +EDGE2 8656 8475 -1.09135 -0.022663 -1.55118 1 0 1 1 0 0 +EDGE2 8656 3075 -0.935899 -0.0271705 -1.56565 1 0 1 1 0 0 +EDGE2 8656 995 -1.05269 0.122922 1.60838 1 0 1 1 0 0 +EDGE2 8656 1015 -1.04579 0.0632806 1.57502 1 0 1 1 0 0 +EDGE2 8656 1055 -1.0632 0.0571291 1.59834 1 0 1 1 0 0 +EDGE2 8656 8477 1.02926 -0.107975 -0.0167574 1 0 1 1 0 0 +EDGE2 8656 3156 -0.0417289 0.035028 -0.00498782 1 0 1 1 0 0 +EDGE2 8656 8476 -0.0637965 0.0716703 0.0151989 1 0 1 1 0 0 +EDGE2 8656 8616 -0.0105838 0.0402635 0.0139556 1 0 1 1 0 0 +EDGE2 8656 8376 0.078144 0.0800655 0.0167033 1 0 1 1 0 0 +EDGE2 8656 1076 -0.0614281 0.00874995 -0.0231066 1 0 1 1 0 0 +EDGE2 8656 3076 0.0329928 0.0907684 0.00879762 1 0 1 1 0 0 +EDGE2 8656 8617 1.04579 0.01206 0.00067917 1 0 1 1 0 0 +EDGE2 8656 3077 1.03448 -0.026492 -0.0145061 1 0 1 1 0 0 +EDGE2 8656 3157 1.0046 0.0370253 0.0120485 1 0 1 1 0 0 +EDGE2 8656 8377 1.02802 -0.0130887 0.0515066 1 0 1 1 0 0 +EDGE2 8656 1077 1.01842 0.0678887 -0.0306068 1 0 1 1 0 0 +EDGE2 8657 3078 1.00415 -0.0102655 -0.0255725 1 0 1 1 0 0 +EDGE2 8657 8477 -0.0167133 0.0227455 0.0489648 1 0 1 1 0 0 +EDGE2 8657 3156 -1.05097 0.00996036 0.00765945 1 0 1 1 0 0 +EDGE2 8657 8476 -0.971682 -0.0159663 -0.00588455 1 0 1 1 0 0 +EDGE2 8657 8616 -1.01738 -0.0477137 -0.0205308 1 0 1 1 0 0 +EDGE2 8657 8656 -0.94751 -0.000155073 -0.00111123 1 0 1 1 0 0 +EDGE2 8657 8376 -0.995829 0.0437947 0.00990083 1 0 1 1 0 0 +EDGE2 8657 1076 -1.00142 0.0361481 0.0335182 1 0 1 1 0 0 +EDGE2 8657 3076 -0.970721 0.0442564 -0.00425313 1 0 1 1 0 0 +EDGE2 8657 8617 -0.0359161 0.0117324 0.00543749 1 0 1 1 0 0 +EDGE2 8657 3077 -0.0194827 -0.00432152 0.00790907 1 0 1 1 0 0 +EDGE2 8657 3157 0.00572938 0.0592937 -0.00537008 1 0 1 1 0 0 +EDGE2 8657 8377 0.0211033 0.0525032 0.0289643 1 0 1 1 0 0 +EDGE2 8657 1077 0.00481438 -0.0794441 -0.00896667 1 0 1 1 0 0 +EDGE2 8657 8378 1.03823 -0.0246582 -0.011557 1 0 1 1 0 0 +EDGE2 8657 8478 1.01908 -0.00838736 -0.00906478 1 0 1 1 0 0 +EDGE2 8657 8618 1.03019 -0.000545141 0.00498639 1 0 1 1 0 0 +EDGE2 8657 3158 0.988996 -0.0435178 0.0084898 1 0 1 1 0 0 +EDGE2 8657 1078 1.0584 0.00809888 0.0157489 1 0 1 1 0 0 +EDGE2 8658 3078 -0.0144373 -0.0248439 0.0134495 1 0 1 1 0 0 +EDGE2 8658 8477 -1.0031 0.0460238 -0.019209 1 0 1 1 0 0 +EDGE2 8658 8657 -0.905896 -0.0731454 0.0102141 1 0 1 1 0 0 +EDGE2 8658 8617 -1.04923 0.0246928 0.0025373 1 0 1 1 0 0 +EDGE2 8658 3077 -1.04076 0.0112146 -0.00389825 1 0 1 1 0 0 +EDGE2 8658 3157 -0.994843 -0.0679763 -0.000168197 1 0 1 1 0 0 +EDGE2 8658 8377 -0.937621 0.0297356 -0.00258422 1 0 1 1 0 0 +EDGE2 8658 1077 -1.06401 -0.0430775 -0.00249517 1 0 1 1 0 0 +EDGE2 8658 8378 0.0159081 0.0568076 -0.049006 1 0 1 1 0 0 +EDGE2 8658 8478 -0.0236479 0.0925501 0.0327269 1 0 1 1 0 0 +EDGE2 8658 8618 0.00838924 0.0281514 0.00622493 1 0 1 1 0 0 +EDGE2 8658 3158 -0.0328044 -0.0497922 -0.0077414 1 0 1 1 0 0 +EDGE2 8658 8379 1.00362 -0.0548801 0.0182244 1 0 1 1 0 0 +EDGE2 8658 8619 1.03153 -0.0563318 -0.0195484 1 0 1 1 0 0 +EDGE2 8658 1078 -0.00321324 0.00649236 0.0218539 1 0 1 1 0 0 +EDGE2 8658 8479 0.929275 -0.102598 -0.00119983 1 0 1 1 0 0 +EDGE2 8658 3079 1.01572 0.0423756 -0.00225446 1 0 1 1 0 0 +EDGE2 8658 3159 0.944081 -0.0646272 -0.0222024 1 0 1 1 0 0 +EDGE2 8658 1079 1.07213 -0.123513 0.0396975 1 0 1 1 0 0 +EDGE2 8659 8360 0.969886 0.0183122 -3.15448 1 0 1 1 0 0 +EDGE2 8659 3078 -0.974224 0.0423371 0.00334538 1 0 1 1 0 0 +EDGE2 8659 8658 -1.05514 0.0160417 -0.0135314 1 0 1 1 0 0 +EDGE2 8659 8378 -0.933175 -0.0140481 -0.0424565 1 0 1 1 0 0 +EDGE2 8659 8478 -1.03406 -0.044692 -0.00607986 1 0 1 1 0 0 +EDGE2 8659 8618 -0.998893 0.0205875 0.000123882 1 0 1 1 0 0 +EDGE2 8659 3158 -0.979441 -0.0564683 0.0354465 1 0 1 1 0 0 +EDGE2 8659 8379 -0.00144579 -0.112091 0.0135322 1 0 1 1 0 0 +EDGE2 8659 8619 -0.0702007 -0.0196198 0.0240726 1 0 1 1 0 0 +EDGE2 8659 1078 -1.0048 -0.145134 0.0485808 1 0 1 1 0 0 +EDGE2 8659 8479 0.110152 -0.027565 0.0040972 1 0 1 1 0 0 +EDGE2 8659 3079 -0.0727673 0.0858553 -0.00919861 1 0 1 1 0 0 +EDGE2 8659 3159 0.0615981 -0.0422824 0.00942434 1 0 1 1 0 0 +EDGE2 8659 1079 -0.0447242 0.0233856 0.00701723 1 0 1 1 0 0 +EDGE2 8659 8480 1.0295 0.0413323 0.0146394 1 0 1 1 0 0 +EDGE2 8659 8620 1.0275 -0.00817354 -0.0192568 1 0 1 1 0 0 +EDGE2 8659 8400 0.939166 -0.103122 -3.15976 1 0 1 1 0 0 +EDGE2 8659 8420 0.973156 0.0210988 -3.1345 1 0 1 1 0 0 +EDGE2 8659 8380 0.961094 -0.0142742 0.00714259 1 0 1 1 0 0 +EDGE2 8659 3060 1.00856 -0.046992 -3.12557 1 0 1 1 0 0 +EDGE2 8659 3160 0.965706 0.0642527 0.0147991 1 0 1 1 0 0 +EDGE2 8659 5860 0.926414 -0.036049 -3.14886 1 0 1 1 0 0 +EDGE2 8659 5880 0.962259 0.113597 -3.14314 1 0 1 1 0 0 +EDGE2 8659 3080 0.949615 0.0325053 0.0160703 1 0 1 1 0 0 +EDGE2 8659 1080 0.946888 -0.0499644 -0.00506951 1 0 1 1 0 0 +EDGE2 8660 8360 -0.0247568 0.0951908 -3.16533 1 0 1 1 0 0 +EDGE2 8660 8379 -1.00596 -0.0168791 0.00863368 1 0 1 1 0 0 +EDGE2 8660 8619 -0.967318 0.0385121 0.0124112 1 0 1 1 0 0 +EDGE2 8660 8659 -0.990903 -0.0715289 0.0193943 1 0 1 1 0 0 +EDGE2 8660 8479 -1.04812 -0.0622184 0.027943 1 0 1 1 0 0 +EDGE2 8660 3079 -1.01306 -0.0133934 -0.0218946 1 0 1 1 0 0 +EDGE2 8660 3159 -0.91183 0.0803138 -0.0225131 1 0 1 1 0 0 +EDGE2 8660 1079 -0.998207 0.0589104 0.0310772 1 0 1 1 0 0 +EDGE2 8660 8361 -0.0206268 0.92962 1.58759 1 0 1 1 0 0 +EDGE2 8660 8421 0.00989161 0.971681 1.59557 1 0 1 1 0 0 +EDGE2 8660 8481 0.0340961 0.971966 1.58636 1 0 1 1 0 0 +EDGE2 8660 8621 0.0361016 0.993299 1.5893 1 0 1 1 0 0 +EDGE2 8660 8381 -0.0110147 0.999205 1.55267 1 0 1 1 0 0 +EDGE2 8660 3081 -0.00262681 0.983036 1.57371 1 0 1 1 0 0 +EDGE2 8660 3161 0.0132703 1.00323 1.56465 1 0 1 1 0 0 +EDGE2 8660 5881 0.00196987 0.995179 1.5896 1 0 1 1 0 0 +EDGE2 8660 3061 -0.0653189 1.01524 1.58098 1 0 1 1 0 0 +EDGE2 8660 8480 0.00511143 0.0496784 0.0182316 1 0 1 1 0 0 +EDGE2 8660 8620 0.0411185 0.0147949 0.0296748 1 0 1 1 0 0 +EDGE2 8660 8400 0.0525952 0.0355335 -3.12949 1 0 1 1 0 0 +EDGE2 8660 8420 -0.00964299 -0.0333135 -3.12725 1 0 1 1 0 0 +EDGE2 8660 8380 0.0169161 0.0565414 -0.0153092 1 0 1 1 0 0 +EDGE2 8660 8401 -0.0702879 -1.04408 -1.58076 1 0 1 1 0 0 +EDGE2 8660 3060 0.0392332 0.068906 -3.13689 1 0 1 1 0 0 +EDGE2 8660 3160 -0.0692964 0.0312892 0.00435614 1 0 1 1 0 0 +EDGE2 8660 5860 -0.031912 -0.0543691 -3.17861 1 0 1 1 0 0 +EDGE2 8660 5880 0.0655861 0.0246057 -3.15453 1 0 1 1 0 0 +EDGE2 8660 3080 0.0981126 0.0480913 -0.0111538 1 0 1 1 0 0 +EDGE2 8660 1080 -0.00342165 0.0421252 3.70378e-05 1 0 1 1 0 0 +EDGE2 8660 1081 0.0746491 -0.998937 -1.56196 1 0 1 1 0 0 +EDGE2 8660 5861 0.0425552 -1.00698 -1.58637 1 0 1 1 0 0 +EDGE2 8660 8399 0.986951 -0.0117995 -3.15134 1 0 1 1 0 0 +EDGE2 8660 8419 1.02135 0.0932902 -3.15056 1 0 1 1 0 0 +EDGE2 8660 5859 1.00462 -0.049012 -3.13601 1 0 1 1 0 0 +EDGE2 8660 5879 1.03969 -0.0410563 -3.11532 1 0 1 1 0 0 +EDGE2 8660 8359 1.06106 0.0704168 -3.16609 1 0 1 1 0 0 +EDGE2 8660 3059 0.980012 0.00175431 -3.15663 1 0 1 1 0 0 +EDGE2 8661 8360 -1.02111 -0.00389364 -1.57862 1 0 1 1 0 0 +EDGE2 8661 8480 -1.03568 0.0174973 1.54768 1 0 1 1 0 0 +EDGE2 8661 8660 -0.988186 0.0420453 1.56125 1 0 1 1 0 0 +EDGE2 8661 8620 -1.09876 0.0183499 1.51594 1 0 1 1 0 0 +EDGE2 8661 8400 -1.01341 -0.00458292 -1.59574 1 0 1 1 0 0 +EDGE2 8661 8420 -0.911942 0.00920036 -1.56397 1 0 1 1 0 0 +EDGE2 8661 8380 -0.985872 0.0401716 1.55672 1 0 1 1 0 0 +EDGE2 8661 5862 0.967999 0.0565095 -0.00708232 1 0 1 1 0 0 +EDGE2 8661 8401 0.0402401 -0.047378 0.00478709 1 0 1 1 0 0 +EDGE2 8661 3060 -1.03066 0.0155954 -1.52783 1 0 1 1 0 0 +EDGE2 8661 3160 -1.10669 -0.0410866 1.56952 1 0 1 1 0 0 +EDGE2 8661 5860 -1.073 -0.0204317 -1.55461 1 0 1 1 0 0 +EDGE2 8661 5880 -1.02796 -0.0376011 -1.5712 1 0 1 1 0 0 +EDGE2 8661 3080 -0.969653 -0.0210321 1.54833 1 0 1 1 0 0 +EDGE2 8661 1080 -1.01889 -0.0321987 1.58751 1 0 1 1 0 0 +EDGE2 8661 1081 0.0952913 -0.0599649 0.0396814 1 0 1 1 0 0 +EDGE2 8661 5861 0.0573348 0.0216289 -0.0123934 1 0 1 1 0 0 +EDGE2 8661 8402 1.0361 0.0504877 0.00238848 1 0 1 1 0 0 +EDGE2 8661 1082 1.05854 0.065883 -0.00760657 1 0 1 1 0 0 +EDGE2 8662 5862 -0.0343893 -0.0517407 -0.0139156 1 0 1 1 0 0 +EDGE2 8662 8401 -1.02003 -0.0498627 0.0171351 1 0 1 1 0 0 +EDGE2 8662 8661 -1.02245 0.0373854 0.0242296 1 0 1 1 0 0 +EDGE2 8662 1081 -0.978925 -0.0317568 0.0110618 1 0 1 1 0 0 +EDGE2 8662 5861 -0.915796 -0.00249021 -0.00685557 1 0 1 1 0 0 +EDGE2 8662 8402 0.11548 0.0201385 -0.00639069 1 0 1 1 0 0 +EDGE2 8662 8403 0.991941 -0.050224 -0.00987171 1 0 1 1 0 0 +EDGE2 8662 1082 -0.105137 -0.0128632 -0.0392467 1 0 1 1 0 0 +EDGE2 8662 1083 1.00276 -0.0408801 -0.01654 1 0 1 1 0 0 +EDGE2 8662 5863 1.07142 -0.0624586 0.0100593 1 0 1 1 0 0 +EDGE2 8663 5862 -0.962972 0.0607836 0.00516986 1 0 1 1 0 0 +EDGE2 8663 8662 -1.00899 0.00983789 0.0219857 1 0 1 1 0 0 +EDGE2 8663 8402 -0.924817 0.0153674 -0.0132548 1 0 1 1 0 0 +EDGE2 8663 8403 -0.0598351 -0.0521848 -0.01262 1 0 1 1 0 0 +EDGE2 8663 1082 -0.95721 0.0446756 0.00272594 1 0 1 1 0 0 +EDGE2 8663 1083 0.0894842 -0.0177362 -0.00721596 1 0 1 1 0 0 +EDGE2 8663 5863 -0.00766674 -0.0490349 -0.00363367 1 0 1 1 0 0 +EDGE2 8663 1084 1.03164 -0.0288117 0.026478 1 0 1 1 0 0 +EDGE2 8663 5864 0.984907 -0.0463532 -0.0273407 1 0 1 1 0 0 +EDGE2 8663 8404 1.02348 -0.019064 0.00698221 1 0 1 1 0 0 +EDGE2 8664 8345 1.02146 -0.0678517 -3.14033 1 0 1 1 0 0 +EDGE2 8664 8403 -0.977874 -0.00819319 -0.0348105 1 0 1 1 0 0 +EDGE2 8664 8663 -0.925423 0.0765996 0.00874854 1 0 1 1 0 0 +EDGE2 8664 1083 -0.949346 -0.0542122 0.0284348 1 0 1 1 0 0 +EDGE2 8664 5863 -1.09988 0.0529576 -0.00220862 1 0 1 1 0 0 +EDGE2 8664 1084 0.0120012 0.0601542 -0.0146175 1 0 1 1 0 0 +EDGE2 8664 5864 0.000289276 -0.044807 -0.00597745 1 0 1 1 0 0 +EDGE2 8664 8404 0.0013291 0.112399 -0.0154167 1 0 1 1 0 0 +EDGE2 8664 8405 1.01945 -0.0230903 0.0102694 1 0 1 1 0 0 +EDGE2 8664 1045 0.989675 -0.0466838 -3.14649 1 0 1 1 0 0 +EDGE2 8664 1085 1.05675 -0.0385164 -0.0219366 1 0 1 1 0 0 +EDGE2 8664 5865 0.908253 -0.034443 -0.00951453 1 0 1 1 0 0 +EDGE2 8665 8345 0.00601241 -0.0489584 -3.12324 1 0 1 1 0 0 +EDGE2 8665 1046 0.0305283 -0.990942 -1.59153 1 0 1 1 0 0 +EDGE2 8665 8664 -0.959433 -0.0322602 -0.0218737 1 0 1 1 0 0 +EDGE2 8665 1084 -1.01687 0.0642903 0.0107934 1 0 1 1 0 0 +EDGE2 8665 5864 -0.986699 -0.0777048 -0.0144984 1 0 1 1 0 0 +EDGE2 8665 8404 -0.917651 -0.129623 0.0208717 1 0 1 1 0 0 +EDGE2 8665 8405 0.0830258 -0.00104551 0.00472933 1 0 1 1 0 0 +EDGE2 8665 8344 1.01466 -0.00590752 -3.14455 1 0 1 1 0 0 +EDGE2 8665 1045 0.0300214 -0.0443516 -3.16311 1 0 1 1 0 0 +EDGE2 8665 1085 -0.128684 -0.0382857 0.00655317 1 0 1 1 0 0 +EDGE2 8665 5865 -0.0254055 -0.0100206 0.00982522 1 0 1 1 0 0 +EDGE2 8665 1044 1.00961 0.0326755 -3.13839 1 0 1 1 0 0 +EDGE2 8665 8346 0.0364064 0.960228 1.55592 1 0 1 1 0 0 +EDGE2 8665 8406 -0.0455239 0.96449 1.59825 1 0 1 1 0 0 +EDGE2 8665 1086 -0.0182682 0.96837 1.56956 1 0 1 1 0 0 +EDGE2 8665 5866 -0.00401807 0.951477 1.57276 1 0 1 1 0 0 +EDGE2 8666 8345 -1.04416 0.0847168 1.54347 1 0 1 1 0 0 +EDGE2 8666 8665 -0.975659 -0.0714613 -1.55045 1 0 1 1 0 0 +EDGE2 8666 8405 -0.943823 0.0654974 -1.57817 1 0 1 1 0 0 +EDGE2 8666 1045 -1.00564 -0.0926224 1.58543 1 0 1 1 0 0 +EDGE2 8666 1085 -0.957318 0.0307599 -1.61059 1 0 1 1 0 0 +EDGE2 8666 5865 -0.922554 -0.0462082 -1.55571 1 0 1 1 0 0 +EDGE2 8666 8346 0.0780755 0.0485698 0.0334326 1 0 1 1 0 0 +EDGE2 8666 8406 -0.0637105 0.0198265 -0.0166247 1 0 1 1 0 0 +EDGE2 8666 1086 0.0504931 0.0472037 0.0221526 1 0 1 1 0 0 +EDGE2 8666 5866 0.0110571 0.0109689 0.0240234 1 0 1 1 0 0 +EDGE2 8666 8407 0.88697 0.0110608 -0.0316682 1 0 1 1 0 0 +EDGE2 8666 5867 0.990216 -0.0429031 -0.0135127 1 0 1 1 0 0 +EDGE2 8666 8347 1.07102 0.0242725 0.0123204 1 0 1 1 0 0 +EDGE2 8666 1087 0.978879 -0.0269195 -0.0315629 1 0 1 1 0 0 +EDGE2 8667 8346 -1.01068 -0.00992992 -0.0093134 1 0 1 1 0 0 +EDGE2 8667 8666 -1.02359 -0.0434794 -0.01484 1 0 1 1 0 0 +EDGE2 8667 8406 -0.958326 0.109946 -0.00703301 1 0 1 1 0 0 +EDGE2 8667 1086 -1.00229 0.0221837 -0.0198508 1 0 1 1 0 0 +EDGE2 8667 5866 -0.940239 -0.00814675 -0.00141658 1 0 1 1 0 0 +EDGE2 8667 8407 0.017306 0.00158407 -0.0245734 1 0 1 1 0 0 +EDGE2 8667 5867 -0.0310672 -0.0356365 0.0310162 1 0 1 1 0 0 +EDGE2 8667 8347 -0.00479729 0.0659536 -0.00616442 1 0 1 1 0 0 +EDGE2 8667 1087 0.0128386 0.0132987 -0.0036707 1 0 1 1 0 0 +EDGE2 8667 8348 0.948881 0.0228776 0.000439271 1 0 1 1 0 0 +EDGE2 8667 8408 1.01024 -0.0919343 0.0147089 1 0 1 1 0 0 +EDGE2 8667 1088 0.996165 -0.0269776 -0.00347783 1 0 1 1 0 0 +EDGE2 8667 5868 0.915491 -0.0289456 0.00894192 1 0 1 1 0 0 +EDGE2 8668 8667 -0.971149 -0.0549876 -0.00253182 1 0 1 1 0 0 +EDGE2 8668 8407 -1.01363 -0.0116425 -0.0154606 1 0 1 1 0 0 +EDGE2 8668 5867 -1.059 -0.00732717 0.0120837 1 0 1 1 0 0 +EDGE2 8668 8347 -0.991051 0.0439996 -0.0126554 1 0 1 1 0 0 +EDGE2 8668 1087 -0.983005 -0.037992 -0.000612363 1 0 1 1 0 0 +EDGE2 8668 8348 -0.0148247 0.000811109 0.00861789 1 0 1 1 0 0 +EDGE2 8668 8408 -0.00354019 0.00585202 -0.00973866 1 0 1 1 0 0 +EDGE2 8668 1088 -0.0254822 -0.061071 -0.0334351 1 0 1 1 0 0 +EDGE2 8668 5868 -0.111588 -0.0406755 -0.0104475 1 0 1 1 0 0 +EDGE2 8668 5869 0.970676 0.0665056 -0.00326478 1 0 1 1 0 0 +EDGE2 8668 8349 0.888177 0.0209438 -0.024563 1 0 1 1 0 0 +EDGE2 8668 8409 0.987301 -0.0422578 0.0182996 1 0 1 1 0 0 +EDGE2 8668 1089 0.937742 -0.0326192 -0.0230852 1 0 1 1 0 0 +EDGE2 8669 8348 -1.07242 0.00244659 -0.0144515 1 0 1 1 0 0 +EDGE2 8669 8408 -0.995439 -0.0143516 -0.00773926 1 0 1 1 0 0 +EDGE2 8669 8668 -0.986804 -0.00684027 0.00341603 1 0 1 1 0 0 +EDGE2 8669 1088 -0.94356 -0.0205028 -0.0240477 1 0 1 1 0 0 +EDGE2 8669 5868 -0.961095 0.0616003 0.0329332 1 0 1 1 0 0 +EDGE2 8669 5869 -0.034781 -0.0373553 -0.00432485 1 0 1 1 0 0 +EDGE2 8669 8349 -0.0467479 0.0749094 -0.037867 1 0 1 1 0 0 +EDGE2 8669 8409 0.0229782 -0.0597144 -0.00454022 1 0 1 1 0 0 +EDGE2 8669 1089 0.0345183 0.0254074 0.0173524 1 0 1 1 0 0 +EDGE2 8669 5870 0.949621 0.0321263 0.00123429 1 0 1 1 0 0 +EDGE2 8669 8350 0.993035 -0.0324432 -0.0320136 1 0 1 1 0 0 +EDGE2 8669 8410 1.00067 -0.0431958 0.0072657 1 0 1 1 0 0 +EDGE2 8669 1090 1.02255 -0.0182436 -0.0521237 1 0 1 1 0 0 +EDGE2 8670 8669 -0.995028 0.0497609 -0.00790541 1 0 1 1 0 0 +EDGE2 8670 5869 -1.09271 -0.0479395 -0.0240186 1 0 1 1 0 0 +EDGE2 8670 8349 -0.958162 0.0302474 -0.00486826 1 0 1 1 0 0 +EDGE2 8670 8409 -0.947039 0.0226465 -0.0233778 1 0 1 1 0 0 +EDGE2 8670 1089 -1.02084 0.0181679 -0.0125417 1 0 1 1 0 0 +EDGE2 8670 8351 0.0342834 0.994723 1.56659 1 0 1 1 0 0 +EDGE2 8670 8411 0.0270697 1.05272 1.56839 1 0 1 1 0 0 +EDGE2 8670 1091 0.00562736 1.00141 1.54348 1 0 1 1 0 0 +EDGE2 8670 5871 -0.0523167 1.04295 1.59469 1 0 1 1 0 0 +EDGE2 8670 5870 -0.0305403 -0.0466319 0.00505118 1 0 1 1 0 0 +EDGE2 8670 8350 0.00640876 0.0182744 -0.00441257 1 0 1 1 0 0 +EDGE2 8670 8410 0.0394892 0.0220218 0.0310662 1 0 1 1 0 0 +EDGE2 8670 1090 0.0100382 0.0409532 -0.00402283 1 0 1 1 0 0 +EDGE2 8671 1092 1.11526 -0.0896042 -0.00117304 1 0 1 1 0 0 +EDGE2 8671 8352 1.00706 -0.0632729 -0.0188392 1 0 1 1 0 0 +EDGE2 8671 8412 1.02018 -0.079677 0.0101734 1 0 1 1 0 0 +EDGE2 8671 5872 0.998243 0.0341971 0.00262171 1 0 1 1 0 0 +EDGE2 8671 8670 -0.985526 -0.00158188 -1.5596 1 0 1 1 0 0 +EDGE2 8671 8351 -0.0234472 0.0567466 -0.0109267 1 0 1 1 0 0 +EDGE2 8671 8411 0.0449632 -0.04198 0.00441498 1 0 1 1 0 0 +EDGE2 8671 1091 -0.12382 0.0611003 0.0166119 1 0 1 1 0 0 +EDGE2 8671 5871 0.0203746 -0.0251181 -0.0143531 1 0 1 1 0 0 +EDGE2 8671 5870 -1.1236 0.032347 -1.59262 1 0 1 1 0 0 +EDGE2 8671 8350 -1.03517 0.110726 -1.57238 1 0 1 1 0 0 +EDGE2 8671 8410 -0.937227 0.00649923 -1.58991 1 0 1 1 0 0 +EDGE2 8671 1090 -0.962872 0.0250178 -1.56804 1 0 1 1 0 0 +EDGE2 8672 1092 0.108367 -0.0476395 0.0149967 1 0 1 1 0 0 +EDGE2 8672 8353 1.00945 -0.0317453 0.000963425 1 0 1 1 0 0 +EDGE2 8672 8413 0.976444 0.00901509 -0.00370865 1 0 1 1 0 0 +EDGE2 8672 1093 0.999464 0.00539345 -0.0199911 1 0 1 1 0 0 +EDGE2 8672 5873 1.07505 0.0281558 0.0151342 1 0 1 1 0 0 +EDGE2 8672 8352 0.0486236 0.0499595 -0.00401671 1 0 1 1 0 0 +EDGE2 8672 8412 -0.0533661 -0.0709725 0.0216086 1 0 1 1 0 0 +EDGE2 8672 5872 0.0952005 -0.0333942 -0.0087746 1 0 1 1 0 0 +EDGE2 8672 8351 -1.00605 -0.0199837 0.0458934 1 0 1 1 0 0 +EDGE2 8672 8671 -0.982117 -0.058865 0.034744 1 0 1 1 0 0 +EDGE2 8672 8411 -1.04546 -0.0329344 -0.00500848 1 0 1 1 0 0 +EDGE2 8672 1091 -1.06623 0.0124634 -0.041825 1 0 1 1 0 0 +EDGE2 8672 5871 -1.02802 0.0150012 -0.0297981 1 0 1 1 0 0 +EDGE2 8673 1092 -0.969302 0.0615006 0.0147885 1 0 1 1 0 0 +EDGE2 8673 8353 0.00451715 -0.0483302 0.0300622 1 0 1 1 0 0 +EDGE2 8673 1094 0.965662 -0.00925273 -0.0162806 1 0 1 1 0 0 +EDGE2 8673 8354 1.00668 0.0319439 0.00309096 1 0 1 1 0 0 +EDGE2 8673 8414 1.01439 0.0579702 -0.0105982 1 0 1 1 0 0 +EDGE2 8673 5874 0.994575 0.063493 0.00955239 1 0 1 1 0 0 +EDGE2 8673 8413 -0.0205208 -0.0780773 0.0149177 1 0 1 1 0 0 +EDGE2 8673 8672 -0.944701 0.00675588 -0.00527546 1 0 1 1 0 0 +EDGE2 8673 1093 0.0115216 -0.033931 -0.0306041 1 0 1 1 0 0 +EDGE2 8673 5873 -0.0324133 0.0486038 -0.00371871 1 0 1 1 0 0 +EDGE2 8673 8352 -1.04093 0.0368312 -0.0157277 1 0 1 1 0 0 +EDGE2 8673 8412 -1.03045 0.0186454 0.0239454 1 0 1 1 0 0 +EDGE2 8673 5872 -1.0137 0.0433413 0.0176572 1 0 1 1 0 0 +EDGE2 8674 5795 0.944323 -0.0163294 -3.12197 1 0 1 1 0 0 +EDGE2 8674 8395 0.973109 -0.00756145 -3.16497 1 0 1 1 0 0 +EDGE2 8674 8555 1.07567 0.0319487 -3.12985 1 0 1 1 0 0 +EDGE2 8674 8415 0.962908 -0.0308134 -0.00598607 1 0 1 1 0 0 +EDGE2 8674 5875 1.00239 -0.0579046 0.0283162 1 0 1 1 0 0 +EDGE2 8674 8355 1.00575 0.019494 -0.0113579 1 0 1 1 0 0 +EDGE2 8674 5855 1.04949 -0.0211018 -3.1552 1 0 1 1 0 0 +EDGE2 8674 3035 0.982523 0.0269886 -3.13257 1 0 1 1 0 0 +EDGE2 8674 3055 0.969695 0.0183935 -3.15421 1 0 1 1 0 0 +EDGE2 8674 1095 1.02806 -0.0203295 0.0377502 1 0 1 1 0 0 +EDGE2 8674 1115 0.957573 -0.0954115 -3.16469 1 0 1 1 0 0 +EDGE2 8674 1135 0.996344 0.0756823 -3.14104 1 0 1 1 0 0 +EDGE2 8674 8353 -0.948287 -0.100329 0.00950797 1 0 1 1 0 0 +EDGE2 8674 1094 0.0217459 0.109564 0.000444123 1 0 1 1 0 0 +EDGE2 8674 8354 0.0543405 0.00980078 0.0133725 1 0 1 1 0 0 +EDGE2 8674 8414 -0.0239198 -0.0197207 0.0178687 1 0 1 1 0 0 +EDGE2 8674 5874 -0.0569308 -0.0782755 -0.0035485 1 0 1 1 0 0 +EDGE2 8674 8673 -1.0087 -0.0607192 -0.0313855 1 0 1 1 0 0 +EDGE2 8674 8413 -0.930551 0.0174464 0.00631727 1 0 1 1 0 0 +EDGE2 8674 1093 -0.988331 -0.0148227 -0.00417738 1 0 1 1 0 0 +EDGE2 8674 5873 -0.991304 -0.0086594 0.0275682 1 0 1 1 0 0 +EDGE2 8675 5795 -0.00643 0.019035 -3.13324 1 0 1 1 0 0 +EDGE2 8675 8356 -0.0102562 1.12843 1.56008 1 0 1 1 0 0 +EDGE2 8675 8416 0.0660352 1.08286 1.56117 1 0 1 1 0 0 +EDGE2 8675 8396 -0.0106391 1.06288 1.58322 1 0 1 1 0 0 +EDGE2 8675 5856 -0.0708215 0.982413 1.577 1 0 1 1 0 0 +EDGE2 8675 5876 0.0893302 0.957856 1.56737 1 0 1 1 0 0 +EDGE2 8675 3056 0.0155259 1.02492 1.60496 1 0 1 1 0 0 +EDGE2 8675 5794 0.987345 -0.0915482 -3.125 1 0 1 1 0 0 +EDGE2 8675 8394 0.943959 -0.0298505 -3.16367 1 0 1 1 0 0 +EDGE2 8675 8554 0.984434 -0.0072416 -3.12806 1 0 1 1 0 0 +EDGE2 8675 5854 0.957977 -0.0333698 -3.174 1 0 1 1 0 0 +EDGE2 8675 1134 0.947835 0.0142505 -3.10841 1 0 1 1 0 0 +EDGE2 8675 3034 1.06007 -0.0404698 -3.11093 1 0 1 1 0 0 +EDGE2 8675 3054 1.03736 -0.0286652 -3.12215 1 0 1 1 0 0 +EDGE2 8675 1114 0.920189 -0.0746565 -3.14665 1 0 1 1 0 0 +EDGE2 8675 8395 0.0549277 0.0224909 -3.15181 1 0 1 1 0 0 +EDGE2 8675 8555 -0.00217951 0.0860913 -3.12946 1 0 1 1 0 0 +EDGE2 8675 8415 -0.0386913 0.0244744 -0.00320067 1 0 1 1 0 0 +EDGE2 8675 5875 0.046028 0.0055111 -0.00926935 1 0 1 1 0 0 +EDGE2 8675 8355 -0.0555584 -0.00626255 -0.00486404 1 0 1 1 0 0 +EDGE2 8675 5855 0.0205619 0.0417374 -3.14263 1 0 1 1 0 0 +EDGE2 8675 3035 0.0316738 0.0727162 -3.14856 1 0 1 1 0 0 +EDGE2 8675 3055 0.0357943 0.0806687 -3.11354 1 0 1 1 0 0 +EDGE2 8675 1095 -0.00987551 -0.00778635 -0.0335983 1 0 1 1 0 0 +EDGE2 8675 1115 -0.00434324 -0.0206968 -3.10389 1 0 1 1 0 0 +EDGE2 8675 1135 -0.0121817 -0.0116013 -3.15393 1 0 1 1 0 0 +EDGE2 8675 1094 -1.06839 -0.0276031 -0.00620182 1 0 1 1 0 0 +EDGE2 8675 8354 -1.00026 0.0101356 0.0203362 1 0 1 1 0 0 +EDGE2 8675 8414 -1.02469 0.0318187 -0.0115499 1 0 1 1 0 0 +EDGE2 8675 8674 -0.945927 0.0134548 -0.0229929 1 0 1 1 0 0 +EDGE2 8675 5874 -1.02652 0.0289514 -0.0387325 1 0 1 1 0 0 +EDGE2 8675 1116 -0.00857773 -0.982613 -1.55927 1 0 1 1 0 0 +EDGE2 8675 3036 0.0407036 -0.996256 -1.62716 1 0 1 1 0 0 +EDGE2 8675 5796 0.00546384 -1.04156 -1.55085 1 0 1 1 0 0 +EDGE2 8675 8556 0.0113767 -0.900461 -1.55294 1 0 1 1 0 0 +EDGE2 8675 1136 0.0940353 -0.956113 -1.54615 1 0 1 1 0 0 +EDGE2 8675 1096 0.0533135 -1.07572 -1.54338 1 0 1 1 0 0 +EDGE2 8676 5795 -0.991012 -0.0456164 1.59544 1 0 1 1 0 0 +EDGE2 8676 5877 1.00901 0.0205305 -0.0178573 1 0 1 1 0 0 +EDGE2 8676 8397 1.05937 0.103619 -0.0111558 1 0 1 1 0 0 +EDGE2 8676 8417 1.03871 -0.109957 -0.0150958 1 0 1 1 0 0 +EDGE2 8676 8357 1.02807 -0.00708727 0.0243705 1 0 1 1 0 0 +EDGE2 8676 3057 1.03752 -0.0501909 0.0207947 1 0 1 1 0 0 +EDGE2 8676 5857 0.914887 0.0497314 -0.0295159 1 0 1 1 0 0 +EDGE2 8676 8356 0.0412015 0.0147506 0.00439761 1 0 1 1 0 0 +EDGE2 8676 8416 -0.00843355 0.0510868 -0.00300022 1 0 1 1 0 0 +EDGE2 8676 8396 -0.020661 -0.00673843 0.0211511 1 0 1 1 0 0 +EDGE2 8676 5856 -0.0649993 0.00899946 0.00644552 1 0 1 1 0 0 +EDGE2 8676 5876 0.0114693 -0.032335 0.0158382 1 0 1 1 0 0 +EDGE2 8676 3056 0.0235596 0.0169655 0.00299026 1 0 1 1 0 0 +EDGE2 8676 8395 -1.08004 0.0226024 1.58169 1 0 1 1 0 0 +EDGE2 8676 8555 -0.875321 -0.090699 1.55898 1 0 1 1 0 0 +EDGE2 8676 8675 -0.996125 0.0380392 -1.60278 1 0 1 1 0 0 +EDGE2 8676 8415 -1.03844 0.076831 -1.52088 1 0 1 1 0 0 +EDGE2 8676 5875 -1.06444 0.0303882 -1.56609 1 0 1 1 0 0 +EDGE2 8676 8355 -0.986594 0.0145359 -1.5788 1 0 1 1 0 0 +EDGE2 8676 5855 -1.00707 -0.0436139 1.54951 1 0 1 1 0 0 +EDGE2 8676 3035 -1.02267 -0.135915 1.56216 1 0 1 1 0 0 +EDGE2 8676 3055 -1.01479 -0.0316844 1.58457 1 0 1 1 0 0 +EDGE2 8676 1095 -0.978233 0.0161868 -1.58788 1 0 1 1 0 0 +EDGE2 8676 1115 -0.936749 0.01189 1.60139 1 0 1 1 0 0 +EDGE2 8676 1135 -1.05219 -0.0436404 1.58056 1 0 1 1 0 0 +EDGE2 8677 8358 0.937067 -0.0762761 0.0124597 1 0 1 1 0 0 +EDGE2 8677 8418 0.939431 0.0510587 -0.0130121 1 0 1 1 0 0 +EDGE2 8677 8398 0.95834 0.0474702 -0.016013 1 0 1 1 0 0 +EDGE2 8677 3058 0.976231 0.0314456 -0.0269308 1 0 1 1 0 0 +EDGE2 8677 5858 0.956525 -0.0170722 -0.0160169 1 0 1 1 0 0 +EDGE2 8677 5878 0.923113 -0.0563325 -0.0151158 1 0 1 1 0 0 +EDGE2 8677 5877 -0.0762878 0.0953659 -0.0109121 1 0 1 1 0 0 +EDGE2 8677 8397 0.0226582 -0.0052441 0.00856735 1 0 1 1 0 0 +EDGE2 8677 8417 -0.0213012 0.0141562 -0.0215006 1 0 1 1 0 0 +EDGE2 8677 8357 0.00578571 0.0642354 -0.0318759 1 0 1 1 0 0 +EDGE2 8677 3057 0.0553868 -0.0155618 -0.0102388 1 0 1 1 0 0 +EDGE2 8677 5857 -0.00987178 0.033901 0.0137696 1 0 1 1 0 0 +EDGE2 8677 8356 -0.937223 0.0313176 0.0590518 1 0 1 1 0 0 +EDGE2 8677 8416 -1.02245 -0.00326691 -0.0146639 1 0 1 1 0 0 +EDGE2 8677 8676 -0.917582 0.0300099 -0.016759 1 0 1 1 0 0 +EDGE2 8677 8396 -1.03937 -0.0111102 -0.0299886 1 0 1 1 0 0 +EDGE2 8677 5856 -0.989267 -0.00333438 0.0174298 1 0 1 1 0 0 +EDGE2 8677 5876 -1.00749 0.0357287 -0.0254688 1 0 1 1 0 0 +EDGE2 8677 3056 -1.04744 -0.065115 0.0156527 1 0 1 1 0 0 +EDGE2 8678 8399 1.03143 -0.0465933 -0.0309736 1 0 1 1 0 0 +EDGE2 8678 8419 0.969595 -0.0445794 0.00385626 1 0 1 1 0 0 +EDGE2 8678 5859 1.0289 -0.0258796 0.00226607 1 0 1 1 0 0 +EDGE2 8678 5879 1.01948 0.0299485 0.0226186 1 0 1 1 0 0 +EDGE2 8678 8359 0.999765 0.0540511 -0.00518425 1 0 1 1 0 0 +EDGE2 8678 3059 0.969456 0.0255714 0.0346834 1 0 1 1 0 0 +EDGE2 8678 8358 -0.0322552 -0.0383463 0.000399095 1 0 1 1 0 0 +EDGE2 8678 8418 -0.00884274 0.00573412 -0.0110796 1 0 1 1 0 0 +EDGE2 8678 8398 -0.00220655 0.103427 0.0260091 1 0 1 1 0 0 +EDGE2 8678 3058 -0.057927 0.0316951 -0.0209797 1 0 1 1 0 0 +EDGE2 8678 5858 0.0312163 0.106859 -0.00204022 1 0 1 1 0 0 +EDGE2 8678 5878 0.024157 0.0230771 -0.00485954 1 0 1 1 0 0 +EDGE2 8678 5877 -1.09326 0.0201901 0.0158555 1 0 1 1 0 0 +EDGE2 8678 8397 -0.975222 -0.0792856 0.00507643 1 0 1 1 0 0 +EDGE2 8678 8417 -0.911722 0.120521 -0.0364044 1 0 1 1 0 0 +EDGE2 8678 8677 -1.03156 -0.0123226 -0.000203376 1 0 1 1 0 0 +EDGE2 8678 8357 -1.04343 0.0639512 -0.0149016 1 0 1 1 0 0 +EDGE2 8678 3057 -0.987655 -0.0374139 0.0221141 1 0 1 1 0 0 +EDGE2 8678 5857 -0.950423 0.0262046 -0.0107968 1 0 1 1 0 0 +EDGE2 8679 8360 0.99078 -0.0325125 0.000722444 1 0 1 1 0 0 +EDGE2 8679 8480 0.998364 -0.0262597 -3.16709 1 0 1 1 0 0 +EDGE2 8679 8660 1.01923 0.0416611 -3.14568 1 0 1 1 0 0 +EDGE2 8679 8620 1.01338 -0.00566466 -3.15952 1 0 1 1 0 0 +EDGE2 8679 8400 0.977802 -0.00432477 -0.0281779 1 0 1 1 0 0 +EDGE2 8679 8420 0.995715 0.0279384 -0.00995215 1 0 1 1 0 0 +EDGE2 8679 8380 1.05473 -0.0580356 -3.16659 1 0 1 1 0 0 +EDGE2 8679 3060 1.01023 -0.0516945 0.0110519 1 0 1 1 0 0 +EDGE2 8679 3160 0.940389 -0.00387823 -3.16471 1 0 1 1 0 0 +EDGE2 8679 5860 0.906182 0.0417243 -0.0226097 1 0 1 1 0 0 +EDGE2 8679 5880 0.969829 0.00293945 0.0313028 1 0 1 1 0 0 +EDGE2 8679 3080 0.873526 0.125623 -3.15678 1 0 1 1 0 0 +EDGE2 8679 1080 0.999901 -0.0101474 -3.13137 1 0 1 1 0 0 +EDGE2 8679 8399 -0.00246628 -0.00749612 -0.0130332 1 0 1 1 0 0 +EDGE2 8679 8419 0.0605604 0.0103036 -0.00866561 1 0 1 1 0 0 +EDGE2 8679 5859 0.0253686 0.0169838 0.0059805 1 0 1 1 0 0 +EDGE2 8679 5879 -0.00451734 0.000216647 0.0265174 1 0 1 1 0 0 +EDGE2 8679 8359 -0.0172303 0.0667629 -0.00662456 1 0 1 1 0 0 +EDGE2 8679 3059 0.0208408 0.0848784 0.0209801 1 0 1 1 0 0 +EDGE2 8679 8358 -1.04044 -0.0420395 0.0194426 1 0 1 1 0 0 +EDGE2 8679 8418 -1.04742 0.107237 -0.0352017 1 0 1 1 0 0 +EDGE2 8679 8678 -0.962678 -0.0329793 0.0047836 1 0 1 1 0 0 +EDGE2 8679 8398 -1.00783 0.0462533 0.011052 1 0 1 1 0 0 +EDGE2 8679 3058 -1.02535 0.0525 -0.0158094 1 0 1 1 0 0 +EDGE2 8679 5858 -1.00799 0.154325 0.000789783 1 0 1 1 0 0 +EDGE2 8679 5878 -0.973586 -0.0231426 -0.0201507 1 0 1 1 0 0 +EDGE2 8680 8360 -0.0249488 0.0331028 -0.0242877 1 0 1 1 0 0 +EDGE2 8680 8379 1.02107 -0.0481311 -3.14295 1 0 1 1 0 0 +EDGE2 8680 8619 0.988708 -0.0037716 -3.13626 1 0 1 1 0 0 +EDGE2 8680 8659 0.9645 -0.0448737 -3.15141 1 0 1 1 0 0 +EDGE2 8680 8479 0.93981 -0.0075805 -3.14423 1 0 1 1 0 0 +EDGE2 8680 3079 1.00656 0.0941744 -3.16938 1 0 1 1 0 0 +EDGE2 8680 3159 1.05308 -0.0323737 -3.1552 1 0 1 1 0 0 +EDGE2 8680 1079 1.006 -0.00550094 -3.14386 1 0 1 1 0 0 +EDGE2 8680 8361 0.110995 -1.02764 -1.5755 1 0 1 1 0 0 +EDGE2 8680 8421 -0.0236438 -0.978101 -1.57423 1 0 1 1 0 0 +EDGE2 8680 8481 -0.00346751 -1.00147 -1.59617 1 0 1 1 0 0 +EDGE2 8680 8621 0.0674381 -1.09536 -1.5679 1 0 1 1 0 0 +EDGE2 8680 8381 0.0181558 -0.981148 -1.58977 1 0 1 1 0 0 +EDGE2 8680 3081 -0.0476641 -0.973311 -1.56688 1 0 1 1 0 0 +EDGE2 8680 3161 -0.03724 -1.0343 -1.56295 1 0 1 1 0 0 +EDGE2 8680 5881 0.134833 -1.00254 -1.55839 1 0 1 1 0 0 +EDGE2 8680 3061 -0.0902497 -1.02246 -1.5616 1 0 1 1 0 0 +EDGE2 8680 8480 -0.1027 -0.00737719 -3.14299 1 0 1 1 0 0 +EDGE2 8680 8660 -0.0697648 0.0377184 -3.1364 1 0 1 1 0 0 +EDGE2 8680 8620 0.105182 0.0378925 -3.11145 1 0 1 1 0 0 +EDGE2 8680 8400 0.0563501 0.0358187 -0.0195076 1 0 1 1 0 0 +EDGE2 8680 8420 -0.140261 -0.0374499 -0.00775688 1 0 1 1 0 0 +EDGE2 8680 8380 -0.0571017 -0.0709058 -3.15313 1 0 1 1 0 0 +EDGE2 8680 8401 0.0298096 0.961326 1.55329 1 0 1 1 0 0 +EDGE2 8680 3060 0.0130983 0.00986643 0.00163029 1 0 1 1 0 0 +EDGE2 8680 3160 0.0118367 0.0610549 -3.11339 1 0 1 1 0 0 +EDGE2 8680 5860 -0.024198 -0.0406551 -0.036094 1 0 1 1 0 0 +EDGE2 8680 5880 0.0328516 -0.0284314 0.0233302 1 0 1 1 0 0 +EDGE2 8680 3080 0.0257454 0.0183839 -3.13526 1 0 1 1 0 0 +EDGE2 8680 1080 -0.0116535 0.00932485 -3.1041 1 0 1 1 0 0 +EDGE2 8680 8661 -0.096396 0.934725 1.5945 1 0 1 1 0 0 +EDGE2 8680 1081 -0.0192612 0.99172 1.55222 1 0 1 1 0 0 +EDGE2 8680 5861 -0.0100264 0.938295 1.57645 1 0 1 1 0 0 +EDGE2 8680 8399 -1.06242 -0.00890595 -0.0616247 1 0 1 1 0 0 +EDGE2 8680 8679 -1.03922 -0.113234 0.0113016 1 0 1 1 0 0 +EDGE2 8680 8419 -1.02045 0.0116388 0.00379935 1 0 1 1 0 0 +EDGE2 8680 5859 -0.933598 -0.0312406 -0.00556956 1 0 1 1 0 0 +EDGE2 8680 5879 -1.01059 0.0131818 0.0167112 1 0 1 1 0 0 +EDGE2 8680 8359 -1.00043 -0.0706215 0.00870121 1 0 1 1 0 0 +EDGE2 8680 3059 -1.00354 0.0533587 0.0205779 1 0 1 1 0 0 +EDGE2 8681 8360 -0.951702 0.00549719 -1.5541 1 0 1 1 0 0 +EDGE2 8681 8480 -0.958743 0.00504462 1.585 1 0 1 1 0 0 +EDGE2 8681 8660 -1.01793 -0.0601223 1.56919 1 0 1 1 0 0 +EDGE2 8681 8680 -1.05137 0.0614413 -1.54181 1 0 1 1 0 0 +EDGE2 8681 8620 -1.07283 0.0520841 1.57337 1 0 1 1 0 0 +EDGE2 8681 8400 -0.954244 0.0296538 -1.59447 1 0 1 1 0 0 +EDGE2 8681 8420 -0.83247 -0.0820667 -1.57166 1 0 1 1 0 0 +EDGE2 8681 8380 -1.02593 0.0118719 1.54829 1 0 1 1 0 0 +EDGE2 8681 5862 1.08512 -0.0242632 -0.0200681 1 0 1 1 0 0 +EDGE2 8681 8401 -0.0343272 0.0568011 0.00135161 1 0 1 1 0 0 +EDGE2 8681 3060 -0.966018 -0.0162025 -1.55488 1 0 1 1 0 0 +EDGE2 8681 3160 -1.01454 -0.00978732 1.5811 1 0 1 1 0 0 +EDGE2 8681 5860 -0.963302 0.00513199 -1.53374 1 0 1 1 0 0 +EDGE2 8681 5880 -0.889944 -0.0833515 -1.57257 1 0 1 1 0 0 +EDGE2 8681 3080 -0.922155 -0.0051192 1.59287 1 0 1 1 0 0 +EDGE2 8681 1080 -0.934633 -0.0663232 1.56525 1 0 1 1 0 0 +EDGE2 8681 8661 -0.0689438 -0.0158775 -0.00426542 1 0 1 1 0 0 +EDGE2 8681 1081 0.0894416 -0.0021032 0.0374876 1 0 1 1 0 0 +EDGE2 8681 5861 0.0826818 -0.0443672 0.0296664 1 0 1 1 0 0 +EDGE2 8681 8662 0.952418 -0.0351075 -0.0116507 1 0 1 1 0 0 +EDGE2 8681 8402 0.981993 -0.0394568 0.0230588 1 0 1 1 0 0 +EDGE2 8681 1082 1.02618 -0.0744685 -0.0180613 1 0 1 1 0 0 +EDGE2 8682 5862 0.0854552 0.028036 -0.0181829 1 0 1 1 0 0 +EDGE2 8682 8401 -1.02153 -0.0402216 0.0117494 1 0 1 1 0 0 +EDGE2 8682 8681 -0.955535 -0.00120591 0.0426342 1 0 1 1 0 0 +EDGE2 8682 8661 -0.957861 -0.0642899 0.0357292 1 0 1 1 0 0 +EDGE2 8682 1081 -1.04967 -0.00659043 -0.0377313 1 0 1 1 0 0 +EDGE2 8682 5861 -1.00127 0.0237379 0.00260722 1 0 1 1 0 0 +EDGE2 8682 8662 1.35284e-05 0.0127463 0.0322529 1 0 1 1 0 0 +EDGE2 8682 8402 -0.0249807 0.0148517 -0.0188752 1 0 1 1 0 0 +EDGE2 8682 8403 0.972965 -0.0951519 -0.00743281 1 0 1 1 0 0 +EDGE2 8682 1082 0.018957 0.0490048 -0.0206792 1 0 1 1 0 0 +EDGE2 8682 8663 1.07785 0.0118923 -0.00231802 1 0 1 1 0 0 +EDGE2 8682 1083 1.00108 0.00754659 0.00222297 1 0 1 1 0 0 +EDGE2 8682 5863 0.980469 0.0626042 -0.0162978 1 0 1 1 0 0 +EDGE2 8683 5862 -0.978883 0.0142826 -0.0129962 1 0 1 1 0 0 +EDGE2 8683 8662 -1.02342 0.0346723 -0.0173033 1 0 1 1 0 0 +EDGE2 8683 8682 -0.969041 -0.0168322 -0.0448851 1 0 1 1 0 0 +EDGE2 8683 8402 -1.07887 -3.16657e-05 0.045597 1 0 1 1 0 0 +EDGE2 8683 8664 1.01615 -0.00780805 -0.0549114 1 0 1 1 0 0 +EDGE2 8683 8403 0.0831639 -0.0660409 0.0220445 1 0 1 1 0 0 +EDGE2 8683 1082 -1.05313 -0.107087 -0.01448 1 0 1 1 0 0 +EDGE2 8683 8663 -0.0899515 0.0912776 -0.00509895 1 0 1 1 0 0 +EDGE2 8683 1083 0.0283749 -0.0110959 0.0187824 1 0 1 1 0 0 +EDGE2 8683 5863 0.0190762 0.0157857 0.0289639 1 0 1 1 0 0 +EDGE2 8683 1084 1.05638 -0.0482498 -0.0148514 1 0 1 1 0 0 +EDGE2 8683 5864 0.979478 -0.030454 -0.0511408 1 0 1 1 0 0 +EDGE2 8683 8404 1.00907 0.044921 -0.0143775 1 0 1 1 0 0 +EDGE2 8684 8345 1.01509 0.00342058 -3.13771 1 0 1 1 0 0 +EDGE2 8684 8664 0.0688215 -0.0148066 0.0155827 1 0 1 1 0 0 +EDGE2 8684 8403 -0.977442 -0.0480266 0.000546333 1 0 1 1 0 0 +EDGE2 8684 8683 -0.970388 -0.00307332 -0.0210192 1 0 1 1 0 0 +EDGE2 8684 8663 -0.947449 0.0616436 0.0147085 1 0 1 1 0 0 +EDGE2 8684 1083 -1.10176 -0.0362939 -0.00287187 1 0 1 1 0 0 +EDGE2 8684 5863 -0.9963 -0.00804616 -0.0124188 1 0 1 1 0 0 +EDGE2 8684 1084 -0.0218656 0.0436841 0.00359018 1 0 1 1 0 0 +EDGE2 8684 5864 0.018873 -0.0206577 -0.00967113 1 0 1 1 0 0 +EDGE2 8684 8404 0.00299361 -0.0714452 -0.00354783 1 0 1 1 0 0 +EDGE2 8684 8665 1.01499 0.0864002 -0.0138452 1 0 1 1 0 0 +EDGE2 8684 8405 1.05394 0.00611191 0.0220706 1 0 1 1 0 0 +EDGE2 8684 1045 0.982445 0.0687804 -3.13098 1 0 1 1 0 0 +EDGE2 8684 1085 1.11362 -0.00278732 0.00819894 1 0 1 1 0 0 +EDGE2 8684 5865 1.01234 0.113563 0.00624557 1 0 1 1 0 0 +EDGE2 8685 8345 0.0393019 0.0882159 -3.1233 1 0 1 1 0 0 +EDGE2 8685 1046 -0.0555632 -1.01246 -1.59274 1 0 1 1 0 0 +EDGE2 8685 8664 -1.03085 -0.165653 0.0161406 1 0 1 1 0 0 +EDGE2 8685 8684 -1.03616 0.0233433 -0.0255464 1 0 1 1 0 0 +EDGE2 8685 1084 -1.03329 0.0602875 -0.0107501 1 0 1 1 0 0 +EDGE2 8685 5864 -0.901531 -0.0262108 6.47152e-05 1 0 1 1 0 0 +EDGE2 8685 8404 -1.0412 0.0172342 0.00658561 1 0 1 1 0 0 +EDGE2 8685 8665 0.0275245 -0.0646234 0.00599655 1 0 1 1 0 0 +EDGE2 8685 8405 -0.00945826 0.037904 0.000567561 1 0 1 1 0 0 +EDGE2 8685 8344 1.00802 0.00452191 -3.16043 1 0 1 1 0 0 +EDGE2 8685 1045 -0.0239337 0.0180068 -3.13459 1 0 1 1 0 0 +EDGE2 8685 1085 0.000999615 -0.0728769 0.00724973 1 0 1 1 0 0 +EDGE2 8685 5865 0.0441078 -0.0205206 0.00222928 1 0 1 1 0 0 +EDGE2 8685 1044 0.932673 0.00232387 -3.13105 1 0 1 1 0 0 +EDGE2 8685 8346 0.00293429 1.0124 1.55881 1 0 1 1 0 0 +EDGE2 8685 8666 -0.0037442 0.947388 1.54415 1 0 1 1 0 0 +EDGE2 8685 8406 0.00208984 0.967872 1.57271 1 0 1 1 0 0 +EDGE2 8685 1086 0.079724 0.952031 1.56131 1 0 1 1 0 0 +EDGE2 8685 5866 -0.0134478 1.04853 1.55144 1 0 1 1 0 0 +EDGE2 8686 8345 -1.04437 -0.0505574 -1.59021 1 0 1 1 0 0 +EDGE2 8686 1047 1.04458 0.0233468 0.00210206 1 0 1 1 0 0 +EDGE2 8686 1046 -0.0361662 -0.0348279 -0.0152111 1 0 1 1 0 0 +EDGE2 8686 8665 -0.978888 8.63154e-05 1.57594 1 0 1 1 0 0 +EDGE2 8686 8685 -1.04705 0.000709601 1.54248 1 0 1 1 0 0 +EDGE2 8686 8405 -1.04878 -0.0627599 1.54257 1 0 1 1 0 0 +EDGE2 8686 1045 -0.958331 0.0627476 -1.56718 1 0 1 1 0 0 +EDGE2 8686 1085 -1.02194 -0.0714198 1.56114 1 0 1 1 0 0 +EDGE2 8686 5865 -1.04905 0.02283 1.59023 1 0 1 1 0 0 +EDGE2 8687 1048 1.0528 0.00749992 -0.0110416 1 0 1 1 0 0 +EDGE2 8687 8686 -0.909989 0.0970025 -0.00962926 1 0 1 1 0 0 +EDGE2 8687 1047 -0.034013 -0.0630297 0.0146491 1 0 1 1 0 0 +EDGE2 8687 1046 -1.08764 -0.0176569 -0.00796079 1 0 1 1 0 0 +EDGE2 8688 1049 1.12719 0.0379235 0.0163555 1 0 1 1 0 0 +EDGE2 8688 1048 0.00987823 0.120193 0.00436189 1 0 1 1 0 0 +EDGE2 8688 1047 -1.04801 0.0220604 -0.00209499 1 0 1 1 0 0 +EDGE2 8688 8687 -1.03829 0.0214387 -0.0221212 1 0 1 1 0 0 +EDGE2 8689 1010 1.03059 0.0687263 -3.17563 1 0 1 1 0 0 +EDGE2 8689 1050 1.04007 -0.0143965 0.0173645 1 0 1 1 0 0 +EDGE2 8689 1070 1.00736 -0.0422578 -3.13622 1 0 1 1 0 0 +EDGE2 8689 8650 0.950862 -0.0363258 -3.14322 1 0 1 1 0 0 +EDGE2 8689 1030 1.00031 -0.00538852 -3.09939 1 0 1 1 0 0 +EDGE2 8689 990 1.00196 -0.00720068 -3.14362 1 0 1 1 0 0 +EDGE2 8689 1049 0.0460281 -0.0201308 0.00584999 1 0 1 1 0 0 +EDGE2 8689 1048 -1.01949 0.0177215 0.0300136 1 0 1 1 0 0 +EDGE2 8689 8688 -0.968739 0.0132613 -0.00498994 1 0 1 1 0 0 +EDGE2 8690 8651 -0.0890825 -1.05058 -1.55783 1 0 1 1 0 0 +EDGE2 8690 1069 0.947928 -0.0139796 -3.10501 1 0 1 1 0 0 +EDGE2 8690 8649 1.07064 0.0351268 -3.15101 1 0 1 1 0 0 +EDGE2 8690 989 0.959801 0.0200615 -3.09243 1 0 1 1 0 0 +EDGE2 8690 1009 0.95836 -0.0259311 -3.1369 1 0 1 1 0 0 +EDGE2 8690 1029 1.06071 0.017388 -3.13544 1 0 1 1 0 0 +EDGE2 8690 1010 0.0267043 -0.0292835 -3.12746 1 0 1 1 0 0 +EDGE2 8690 1011 -0.0636572 -1.09037 -1.55058 1 0 1 1 0 0 +EDGE2 8690 1051 0.000110638 -1.05319 -1.56518 1 0 1 1 0 0 +EDGE2 8690 1071 0.0124423 -1.03193 -1.60265 1 0 1 1 0 0 +EDGE2 8690 991 -0.0262372 -0.997669 -1.57266 1 0 1 1 0 0 +EDGE2 8690 1050 -0.000823581 0.0271751 -0.00369826 1 0 1 1 0 0 +EDGE2 8690 1070 0.00594445 0.0923767 -3.13621 1 0 1 1 0 0 +EDGE2 8690 8650 -0.0644698 -0.00315715 -3.12389 1 0 1 1 0 0 +EDGE2 8690 1030 0.00458994 -0.0395076 -3.16514 1 0 1 1 0 0 +EDGE2 8690 1031 0.0740617 1.00837 1.56504 1 0 1 1 0 0 +EDGE2 8690 990 -0.0700831 0.0102415 -3.13708 1 0 1 1 0 0 +EDGE2 8690 8689 -0.985133 0.022386 0.0109631 1 0 1 1 0 0 +EDGE2 8690 1049 -0.9682 0.0375608 -0.0138247 1 0 1 1 0 0 +EDGE2 8691 1010 -1.00533 0.0284477 1.5662 1 0 1 1 0 0 +EDGE2 8691 8690 -1.0482 -0.0108509 -1.56078 1 0 1 1 0 0 +EDGE2 8691 1050 -0.888176 -0.0507248 -1.57398 1 0 1 1 0 0 +EDGE2 8691 1070 -1.02156 -0.00577215 1.50338 1 0 1 1 0 0 +EDGE2 8691 8650 -1.03593 0.014016 1.57824 1 0 1 1 0 0 +EDGE2 8691 1030 -0.98796 0.00972631 1.59461 1 0 1 1 0 0 +EDGE2 8691 1032 1.02858 0.0138017 0.00119859 1 0 1 1 0 0 +EDGE2 8691 1031 0.0194108 -0.0309309 -0.00362639 1 0 1 1 0 0 +EDGE2 8691 990 -1.03002 -0.0219098 1.57517 1 0 1 1 0 0 +EDGE2 8692 1032 -0.00911722 0.0586392 0.0212691 1 0 1 1 0 0 +EDGE2 8692 1031 -1.01956 -0.0485457 0.0267373 1 0 1 1 0 0 +EDGE2 8692 8691 -0.999839 0.0751974 -0.00835363 1 0 1 1 0 0 +EDGE2 8692 1033 1.10154 -0.00723186 -0.025837 1 0 1 1 0 0 +EDGE2 8693 1034 1.02856 -0.0422936 -0.0346841 1 0 1 1 0 0 +EDGE2 8693 1032 -0.930814 0.0429669 -0.00835654 1 0 1 1 0 0 +EDGE2 8693 8692 -1.01201 -0.0265444 0.0158573 1 0 1 1 0 0 +EDGE2 8693 1033 -0.0795763 -0.0159145 -0.00633855 1 0 1 1 0 0 +EDGE2 8694 1034 -0.00169233 0.0336981 0.0271629 1 0 1 1 0 0 +EDGE2 8694 1033 -0.911359 -0.00581761 0.00234232 1 0 1 1 0 0 +EDGE2 8694 8693 -0.884172 -0.088236 0.00355013 1 0 1 1 0 0 +EDGE2 8694 1035 1.01631 -0.0305177 0.00537588 1 0 1 1 0 0 +EDGE2 8694 8335 1.01485 0.0566668 -3.13574 1 0 1 1 0 0 +EDGE2 8695 1034 -0.992932 0.0676261 0.0165025 1 0 1 1 0 0 +EDGE2 8695 8694 -1.06632 -0.00456331 0.0129672 1 0 1 1 0 0 +EDGE2 8695 1035 0.0533857 0.00120085 0.010251 1 0 1 1 0 0 +EDGE2 8695 8335 -0.0947366 0.0457454 -3.14019 1 0 1 1 0 0 +EDGE2 8695 8334 0.998418 -0.0218044 -3.15239 1 0 1 1 0 0 +EDGE2 8695 8336 0.00773942 1.09496 1.56391 1 0 1 1 0 0 +EDGE2 8695 1036 -0.0783695 1.01313 1.58734 1 0 1 1 0 0 +EDGE2 8696 1035 -0.952597 0.0938533 -1.56799 1 0 1 1 0 0 +EDGE2 8696 8335 -1.08966 -0.0205559 1.56791 1 0 1 1 0 0 +EDGE2 8696 8695 -0.922508 0.047909 -1.577 1 0 1 1 0 0 +EDGE2 8696 8336 0.0299195 0.133199 -0.0229634 1 0 1 1 0 0 +EDGE2 8696 1036 0.0692025 -0.0122166 0.0158764 1 0 1 1 0 0 +EDGE2 8696 1037 1.06215 0.0593584 -0.020129 1 0 1 1 0 0 +EDGE2 8696 8337 0.892179 0.0184596 -0.010448 1 0 1 1 0 0 +EDGE2 8697 8336 -0.996715 0.0292294 0.00964896 1 0 1 1 0 0 +EDGE2 8697 8696 -0.978928 0.0157489 0.0217943 1 0 1 1 0 0 +EDGE2 8697 1036 -1.04432 0.0917233 -0.0338792 1 0 1 1 0 0 +EDGE2 8697 1037 -0.0721696 -0.00763506 -0.0156693 1 0 1 1 0 0 +EDGE2 8697 8337 -0.00895529 0.0232684 -0.0309589 1 0 1 1 0 0 +EDGE2 8697 1038 0.963722 -0.0128611 0.0506514 1 0 1 1 0 0 +EDGE2 8697 8338 0.946901 0.0799445 0.0109886 1 0 1 1 0 0 +EDGE2 8698 8339 0.917196 -0.00300614 -0.0137668 1 0 1 1 0 0 +EDGE2 8698 1037 -0.985831 -0.00411628 0.000651581 1 0 1 1 0 0 +EDGE2 8698 8697 -1.02442 -0.104466 0.0083126 1 0 1 1 0 0 +EDGE2 8698 8337 -1.00051 0.0291826 0.0162053 1 0 1 1 0 0 +EDGE2 8698 1038 -0.0143782 -0.0741043 0.0264295 1 0 1 1 0 0 +EDGE2 8698 8338 0.0365628 -0.0447491 0.0303466 1 0 1 1 0 0 +EDGE2 8698 1039 1.05456 0.0293511 0.0239486 1 0 1 1 0 0 +EDGE2 8699 8339 -0.111491 -0.0774598 -0.00657011 1 0 1 1 0 0 +EDGE2 8699 8698 -1.05938 -0.0371559 -0.032572 1 0 1 1 0 0 +EDGE2 8699 1038 -0.991735 0.0139916 0.0263729 1 0 1 1 0 0 +EDGE2 8699 8338 -1.04451 -0.0698543 0.00143169 1 0 1 1 0 0 +EDGE2 8699 1039 -0.0432111 0.0418977 0.0152205 1 0 1 1 0 0 +EDGE2 8699 1040 0.982165 -0.048243 -0.0126076 1 0 1 1 0 0 +EDGE2 8699 8340 0.934927 0.0347193 0.0183013 1 0 1 1 0 0 +EDGE2 8700 8339 -0.964121 0.00882382 0.0271535 1 0 1 1 0 0 +EDGE2 8700 8699 -0.993064 -0.0387361 -0.0281699 1 0 1 1 0 0 +EDGE2 8700 1039 -0.996159 0.0277999 0.00895483 1 0 1 1 0 0 +EDGE2 8700 1041 -0.00315802 1.04196 1.58134 1 0 1 1 0 0 +EDGE2 8700 8341 -0.0354057 0.926367 1.57355 1 0 1 1 0 0 +EDGE2 8700 1040 -0.0236207 -0.0757114 -0.0315887 1 0 1 1 0 0 +EDGE2 8700 8340 -0.0573426 0.000647286 -0.00287637 1 0 1 1 0 0 +EDGE2 8701 1041 0.0194351 -0.00317432 0.0334132 1 0 1 1 0 0 +EDGE2 8701 1042 0.977664 0.013328 0.0501086 1 0 1 1 0 0 +EDGE2 8701 8342 0.972437 -0.0301688 0.0207697 1 0 1 1 0 0 +EDGE2 8701 8341 0.0579526 -0.0256981 -0.00823831 1 0 1 1 0 0 +EDGE2 8701 1040 -0.988376 -0.0227795 -1.59879 1 0 1 1 0 0 +EDGE2 8701 8340 -0.996701 -0.00077912 -1.56279 1 0 1 1 0 0 +EDGE2 8701 8700 -0.989722 0.0859987 -1.58881 1 0 1 1 0 0 +EDGE2 8702 8343 0.947704 0.075021 -0.0194735 1 0 1 1 0 0 +EDGE2 8702 1043 0.997612 0.0443389 -0.00382501 1 0 1 1 0 0 +EDGE2 8702 1041 -0.940691 0.0137346 0.0174444 1 0 1 1 0 0 +EDGE2 8702 8701 -1.03564 0.0638074 0.000166642 1 0 1 1 0 0 +EDGE2 8702 1042 -0.0575115 -0.0489821 -0.0162379 1 0 1 1 0 0 +EDGE2 8702 8342 -0.0184577 0.0405258 -0.00561458 1 0 1 1 0 0 +EDGE2 8702 8341 -1.00898 0.0834386 0.0520716 1 0 1 1 0 0 +EDGE2 8703 8702 -1.10926 0.0253352 -0.00413004 1 0 1 1 0 0 +EDGE2 8703 8344 1.05417 0.00711261 0.0070106 1 0 1 1 0 0 +EDGE2 8703 8343 -0.0488074 -0.0904379 0.00351181 1 0 1 1 0 0 +EDGE2 8703 1044 1.03261 -0.073762 -0.0197866 1 0 1 1 0 0 +EDGE2 8703 1043 -0.0465501 0.0360666 -0.0362473 1 0 1 1 0 0 +EDGE2 8703 1042 -0.986261 0.0884628 0.0264032 1 0 1 1 0 0 +EDGE2 8703 8342 -1.08459 0.0765073 0.024847 1 0 1 1 0 0 +EDGE2 8704 8345 0.947517 0.0115063 -0.00685106 1 0 1 1 0 0 +EDGE2 8704 8665 1.00098 0.0220296 -3.13755 1 0 1 1 0 0 +EDGE2 8704 8685 1.07413 0.0388913 -3.14699 1 0 1 1 0 0 +EDGE2 8704 8405 1.00812 0.0142601 -3.13622 1 0 1 1 0 0 +EDGE2 8704 8344 -0.0439595 -0.120814 0.0215686 1 0 1 1 0 0 +EDGE2 8704 1045 1.09434 0.0102148 0.00646206 1 0 1 1 0 0 +EDGE2 8704 1085 0.895532 0.0319151 -3.21217 1 0 1 1 0 0 +EDGE2 8704 5865 0.942751 0.0456334 -3.15243 1 0 1 1 0 0 +EDGE2 8704 8343 -0.982133 0.0573522 0.00334895 1 0 1 1 0 0 +EDGE2 8704 8703 -1.01024 0.0197534 -0.0311223 1 0 1 1 0 0 +EDGE2 8704 1044 0.0318279 0.052433 -0.0360545 1 0 1 1 0 0 +EDGE2 8704 1043 -0.971937 0.0148785 -0.0295979 1 0 1 1 0 0 +EDGE2 8705 8345 0.0085778 -0.0304957 0.0208763 1 0 1 1 0 0 +EDGE2 8705 8686 -0.0741864 0.973388 1.55749 1 0 1 1 0 0 +EDGE2 8705 1046 -0.0327971 0.987894 1.58022 1 0 1 1 0 0 +EDGE2 8705 8664 1.01371 0.0576678 -3.12035 1 0 1 1 0 0 +EDGE2 8705 8684 1.01999 0.0149614 -3.1546 1 0 1 1 0 0 +EDGE2 8705 1084 1.01337 -0.0165928 -3.13217 1 0 1 1 0 0 +EDGE2 8705 5864 1.0119 0.0262091 -3.15045 1 0 1 1 0 0 +EDGE2 8705 8404 1.00697 -0.0707445 -3.13173 1 0 1 1 0 0 +EDGE2 8705 8665 -0.00586476 0.00195827 -3.11902 1 0 1 1 0 0 +EDGE2 8705 8685 0.0549462 -0.0540941 -3.09928 1 0 1 1 0 0 +EDGE2 8705 8405 0.0516614 0.0397909 -3.1457 1 0 1 1 0 0 +EDGE2 8705 8344 -1.03461 -0.0631473 -0.0244423 1 0 1 1 0 0 +EDGE2 8705 1045 -0.015501 0.0611363 0.00997073 1 0 1 1 0 0 +EDGE2 8705 1085 -0.0628812 0.052428 -3.13152 1 0 1 1 0 0 +EDGE2 8705 5865 0.0201051 -0.0637188 -3.17886 1 0 1 1 0 0 +EDGE2 8705 8704 -1.13492 0.00374351 0.0109569 1 0 1 1 0 0 +EDGE2 8705 1044 -1.02708 -0.0812658 0.0392873 1 0 1 1 0 0 +EDGE2 8705 8346 0.0121762 -0.945271 -1.56981 1 0 1 1 0 0 +EDGE2 8705 8666 0.0106606 -0.956718 -1.54727 1 0 1 1 0 0 +EDGE2 8705 8406 0.0180503 -0.964095 -1.60106 1 0 1 1 0 0 +EDGE2 8705 1086 -0.018081 -1.01442 -1.6045 1 0 1 1 0 0 +EDGE2 8705 5866 -0.0211005 -1.06388 -1.5745 1 0 1 1 0 0 +EDGE2 8706 8345 -0.956936 0.0877365 1.57057 1 0 1 1 0 0 +EDGE2 8706 8705 -1.04935 0.00092246 1.56343 1 0 1 1 0 0 +EDGE2 8706 8665 -1.00203 -0.0237601 -1.55778 1 0 1 1 0 0 +EDGE2 8706 8685 -1.02425 0.0234143 -1.55234 1 0 1 1 0 0 +EDGE2 8706 8405 -0.913836 0.0453249 -1.58357 1 0 1 1 0 0 +EDGE2 8706 1045 -0.850943 -0.0354465 1.55569 1 0 1 1 0 0 +EDGE2 8706 1085 -1.05284 -0.0289426 -1.57941 1 0 1 1 0 0 +EDGE2 8706 5865 -0.981535 -0.0221611 -1.5667 1 0 1 1 0 0 +EDGE2 8706 8667 1.0023 -0.0155695 0.0136054 1 0 1 1 0 0 +EDGE2 8706 8346 0.00576556 0.0164555 -0.0234292 1 0 1 1 0 0 +EDGE2 8706 8666 -0.0502093 0.0100824 -0.00873461 1 0 1 1 0 0 +EDGE2 8706 8406 -0.0315012 0.0513953 0.00832083 1 0 1 1 0 0 +EDGE2 8706 1086 0.00342352 0.00345537 -0.00473698 1 0 1 1 0 0 +EDGE2 8706 5866 0.0134301 0.0442709 0.00240399 1 0 1 1 0 0 +EDGE2 8706 8407 0.955015 -0.0349962 0.00260898 1 0 1 1 0 0 +EDGE2 8706 5867 0.963105 -0.023772 0.0163276 1 0 1 1 0 0 +EDGE2 8706 8347 1.09667 0.0363674 -0.0250773 1 0 1 1 0 0 +EDGE2 8706 1087 0.990842 -0.0282959 -0.0199152 1 0 1 1 0 0 +EDGE2 8707 8667 -0.0348681 -0.046791 -0.00755297 1 0 1 1 0 0 +EDGE2 8707 8346 -0.997051 -0.0773153 -0.0174743 1 0 1 1 0 0 +EDGE2 8707 8666 -0.969629 0.0275169 0.0382175 1 0 1 1 0 0 +EDGE2 8707 8706 -1.04816 0.0311893 -0.0232122 1 0 1 1 0 0 +EDGE2 8707 8406 -0.993757 0.0908657 0.0243017 1 0 1 1 0 0 +EDGE2 8707 1086 -0.924261 0.0125363 -0.000430107 1 0 1 1 0 0 +EDGE2 8707 5866 -0.985652 -0.0258872 -0.0431209 1 0 1 1 0 0 +EDGE2 8707 8407 -0.0835402 0.0835011 0.0615931 1 0 1 1 0 0 +EDGE2 8707 5867 0.0362701 0.00349151 -0.017222 1 0 1 1 0 0 +EDGE2 8707 8347 -0.0401889 -0.0482514 0.0026409 1 0 1 1 0 0 +EDGE2 8707 1087 -0.0721473 0.0544695 0.0202961 1 0 1 1 0 0 +EDGE2 8707 8348 1.07331 -0.035467 0.0173399 1 0 1 1 0 0 +EDGE2 8707 8408 0.927027 -0.0206192 0.009298 1 0 1 1 0 0 +EDGE2 8707 8668 1.07811 0.00116105 -0.0178211 1 0 1 1 0 0 +EDGE2 8707 1088 1.03815 -0.0540115 0.00248801 1 0 1 1 0 0 +EDGE2 8707 5868 0.978257 0.101995 -0.00738245 1 0 1 1 0 0 +EDGE2 8708 8667 -1.03682 -0.019003 -0.00478842 1 0 1 1 0 0 +EDGE2 8708 8707 -1.06601 -0.00467032 -0.0600297 1 0 1 1 0 0 +EDGE2 8708 8407 -0.950286 -0.0326324 0.0419815 1 0 1 1 0 0 +EDGE2 8708 5867 -0.980112 0.012431 0.00476083 1 0 1 1 0 0 +EDGE2 8708 8347 -0.999136 -0.0376564 0.0299496 1 0 1 1 0 0 +EDGE2 8708 1087 -0.923867 0.00543283 -0.018137 1 0 1 1 0 0 +EDGE2 8708 8348 -0.0624748 -0.0381516 -0.0159238 1 0 1 1 0 0 +EDGE2 8708 8408 0.0780111 -0.089931 0.0030081 1 0 1 1 0 0 +EDGE2 8708 8668 0.0313258 0.00736383 -0.0058283 1 0 1 1 0 0 +EDGE2 8708 8669 0.967743 0.0173294 -0.00432954 1 0 1 1 0 0 +EDGE2 8708 1088 0.0337382 -0.0460167 0.00318384 1 0 1 1 0 0 +EDGE2 8708 5868 -0.0517212 -0.0312536 -0.000917074 1 0 1 1 0 0 +EDGE2 8708 5869 1.0408 -0.0254759 -0.0114939 1 0 1 1 0 0 +EDGE2 8708 8349 1.02566 -0.00371595 -0.0366818 1 0 1 1 0 0 +EDGE2 8708 8409 1.03723 0.0373983 -0.0262161 1 0 1 1 0 0 +EDGE2 8708 1089 1.00747 -0.0765834 0.0153197 1 0 1 1 0 0 +EDGE2 8709 8348 -0.955811 -0.00689905 0.0307425 1 0 1 1 0 0 +EDGE2 8709 8408 -0.939248 0.00296044 0.0101994 1 0 1 1 0 0 +EDGE2 8709 8668 -1.08992 0.0640626 0.012219 1 0 1 1 0 0 +EDGE2 8709 8708 -1.0092 0.00189891 0.0240417 1 0 1 1 0 0 +EDGE2 8709 8669 -0.0359869 0.0846039 -0.015545 1 0 1 1 0 0 +EDGE2 8709 1088 -0.994492 -0.0222425 0.00314094 1 0 1 1 0 0 +EDGE2 8709 5868 -1.02168 -0.0279898 -0.0476505 1 0 1 1 0 0 +EDGE2 8709 5869 0.0584615 -0.00490764 0.0197058 1 0 1 1 0 0 +EDGE2 8709 8349 -0.0386723 -0.0411224 0.013372 1 0 1 1 0 0 +EDGE2 8709 8409 0.0506342 -0.111691 0.0175734 1 0 1 1 0 0 +EDGE2 8709 1089 -0.014087 -0.00137561 -0.0322311 1 0 1 1 0 0 +EDGE2 8709 8670 1.09472 0.011193 -0.0164629 1 0 1 1 0 0 +EDGE2 8709 5870 1.0299 -0.0334662 0.000549293 1 0 1 1 0 0 +EDGE2 8709 8350 1.03496 0.0101702 0.0329268 1 0 1 1 0 0 +EDGE2 8709 8410 1.04253 -0.0556998 -0.0113737 1 0 1 1 0 0 +EDGE2 8709 1090 0.969917 0.0152848 -0.0422648 1 0 1 1 0 0 +EDGE2 8710 8669 -1.0287 0.00204943 0.0148661 1 0 1 1 0 0 +EDGE2 8710 8709 -0.955655 0.0786743 0.00553691 1 0 1 1 0 0 +EDGE2 8710 5869 -0.944526 -0.088345 0.0312209 1 0 1 1 0 0 +EDGE2 8710 8349 -1.03286 0.0516366 -0.00653846 1 0 1 1 0 0 +EDGE2 8710 8409 -1.0216 -0.0142079 0.00110131 1 0 1 1 0 0 +EDGE2 8710 1089 -1.10309 0.000211392 -0.0217253 1 0 1 1 0 0 +EDGE2 8710 8670 -0.00855077 0.067776 -0.00260327 1 0 1 1 0 0 +EDGE2 8710 8351 0.0994047 1.07772 1.54257 1 0 1 1 0 0 +EDGE2 8710 8671 0.0151113 1.00243 1.56955 1 0 1 1 0 0 +EDGE2 8710 8411 -0.0405603 1.03991 1.61402 1 0 1 1 0 0 +EDGE2 8710 1091 0.0260501 1.03984 1.61831 1 0 1 1 0 0 +EDGE2 8710 5871 0.0207518 1.0463 1.55173 1 0 1 1 0 0 +EDGE2 8710 5870 0.0137589 -0.0372586 -0.0212871 1 0 1 1 0 0 +EDGE2 8710 8350 0.0837314 -0.0197585 -0.0226663 1 0 1 1 0 0 +EDGE2 8710 8410 0.0434762 0.0330819 -0.0223977 1 0 1 1 0 0 +EDGE2 8710 1090 0.0398498 0.0176788 -0.00738306 1 0 1 1 0 0 +EDGE2 8711 1092 0.952287 -0.114814 -0.0246262 1 0 1 1 0 0 +EDGE2 8711 8672 1.06166 0.0310348 -0.0040634 1 0 1 1 0 0 +EDGE2 8711 8352 0.943066 -0.00944182 -0.00423625 1 0 1 1 0 0 +EDGE2 8711 8412 1.0359 -0.0203852 0.00698652 1 0 1 1 0 0 +EDGE2 8711 5872 0.965275 0.0139794 0.00438067 1 0 1 1 0 0 +EDGE2 8711 8670 -0.964455 -0.09077 -1.55856 1 0 1 1 0 0 +EDGE2 8711 8351 0.0171326 0.0317578 -0.0125871 1 0 1 1 0 0 +EDGE2 8711 8671 0.0166107 -0.0538884 0.0216664 1 0 1 1 0 0 +EDGE2 8711 8411 -0.0424653 -0.0608791 0.019209 1 0 1 1 0 0 +EDGE2 8711 1091 -0.00549915 -0.0346439 -0.0377347 1 0 1 1 0 0 +EDGE2 8711 5871 -0.0464707 -0.0444829 -0.00285122 1 0 1 1 0 0 +EDGE2 8711 8710 -0.977182 -0.0123889 -1.57404 1 0 1 1 0 0 +EDGE2 8711 5870 -1.03999 -0.00322327 -1.60158 1 0 1 1 0 0 +EDGE2 8711 8350 -1.01946 0.0246375 -1.6001 1 0 1 1 0 0 +EDGE2 8711 8410 -1.00668 0.000692886 -1.54754 1 0 1 1 0 0 +EDGE2 8711 1090 -0.949914 0.0562874 -1.55283 1 0 1 1 0 0 +EDGE2 8712 1092 0.0177236 0.0498854 0.016739 1 0 1 1 0 0 +EDGE2 8712 8353 0.992028 0.00206567 -0.0151694 1 0 1 1 0 0 +EDGE2 8712 8673 1.03731 -0.0153754 0.0401 1 0 1 1 0 0 +EDGE2 8712 8413 0.949441 -0.0360641 -0.0153917 1 0 1 1 0 0 +EDGE2 8712 8672 -0.0197483 -0.00437719 0.0039941 1 0 1 1 0 0 +EDGE2 8712 1093 0.982102 0.0116266 0.01583 1 0 1 1 0 0 +EDGE2 8712 5873 1.01389 -0.043345 -0.0112187 1 0 1 1 0 0 +EDGE2 8712 8352 -0.0251251 0.0695135 0.0305787 1 0 1 1 0 0 +EDGE2 8712 8412 -0.0483473 -0.0123806 0.0100394 1 0 1 1 0 0 +EDGE2 8712 5872 -0.0312714 0.00171246 0.00513595 1 0 1 1 0 0 +EDGE2 8712 8351 -1.09256 0.00907444 -0.0321752 1 0 1 1 0 0 +EDGE2 8712 8671 -0.930906 0.0772332 -0.00325907 1 0 1 1 0 0 +EDGE2 8712 8711 -0.991164 -0.030895 0.00954475 1 0 1 1 0 0 +EDGE2 8712 8411 -0.964796 0.00983977 0.0201823 1 0 1 1 0 0 +EDGE2 8712 1091 -1.04002 0.00897877 -0.00857867 1 0 1 1 0 0 +EDGE2 8712 5871 -1.08389 -0.00214198 -0.00913524 1 0 1 1 0 0 +EDGE2 8713 1092 -1.04119 -0.00530192 0.000203928 1 0 1 1 0 0 +EDGE2 8713 8353 -0.107441 -0.128397 0.00827898 1 0 1 1 0 0 +EDGE2 8713 1094 1.03766 0.0226105 -0.0166624 1 0 1 1 0 0 +EDGE2 8713 8354 1.01283 -0.0949208 -0.0192556 1 0 1 1 0 0 +EDGE2 8713 8414 0.953432 -0.094465 -0.0204594 1 0 1 1 0 0 +EDGE2 8713 8674 1.04451 -0.00976936 -0.00170237 1 0 1 1 0 0 +EDGE2 8713 5874 1.02975 -0.0449079 -0.00589994 1 0 1 1 0 0 +EDGE2 8713 8673 -0.0759618 -0.0492352 -0.0315004 1 0 1 1 0 0 +EDGE2 8713 8413 0.00728696 -0.0730304 -0.0176952 1 0 1 1 0 0 +EDGE2 8713 8672 -0.980213 -0.0132651 -0.0119856 1 0 1 1 0 0 +EDGE2 8713 1093 0.00548208 -0.0536688 0.00817622 1 0 1 1 0 0 +EDGE2 8713 5873 0.0590549 -0.043258 -0.0137146 1 0 1 1 0 0 +EDGE2 8713 8712 -0.920754 0.00759397 -0.0132543 1 0 1 1 0 0 +EDGE2 8713 8352 -1.02117 -0.0973645 0.00192398 1 0 1 1 0 0 +EDGE2 8713 8412 -1.02608 0.0636359 -0.00336035 1 0 1 1 0 0 +EDGE2 8713 5872 -1.07581 -0.032208 0.0160528 1 0 1 1 0 0 +EDGE2 8714 5795 0.994263 0.0109072 -3.13104 1 0 1 1 0 0 +EDGE2 8714 8395 0.973937 -0.0731843 -3.16035 1 0 1 1 0 0 +EDGE2 8714 8555 1.05612 0.00759047 -3.14955 1 0 1 1 0 0 +EDGE2 8714 8675 0.955512 0.00125457 -0.0142276 1 0 1 1 0 0 +EDGE2 8714 8415 0.93573 0.0648849 -0.00739749 1 0 1 1 0 0 +EDGE2 8714 5875 0.963108 -0.0782423 -0.00934613 1 0 1 1 0 0 +EDGE2 8714 8355 1.03715 -0.00489387 -0.00689343 1 0 1 1 0 0 +EDGE2 8714 5855 1.07704 -0.00318368 -3.16173 1 0 1 1 0 0 +EDGE2 8714 3035 1.00643 -0.0387888 -3.14752 1 0 1 1 0 0 +EDGE2 8714 3055 0.937932 0.103692 -3.13157 1 0 1 1 0 0 +EDGE2 8714 1095 1.01295 0.0840411 0.00669988 1 0 1 1 0 0 +EDGE2 8714 1115 1.02509 0.0212171 -3.11457 1 0 1 1 0 0 +EDGE2 8714 1135 1.05759 -0.0114608 -3.14926 1 0 1 1 0 0 +EDGE2 8714 8353 -0.997559 0.0281063 -0.0114141 1 0 1 1 0 0 +EDGE2 8714 1094 -0.0301346 -0.00202841 0.0187761 1 0 1 1 0 0 +EDGE2 8714 8354 -0.00615301 -0.0114898 0.010245 1 0 1 1 0 0 +EDGE2 8714 8414 -0.0254805 -0.00887486 -0.0150048 1 0 1 1 0 0 +EDGE2 8714 8674 0.00501393 -0.0149687 0.000260196 1 0 1 1 0 0 +EDGE2 8714 5874 0.0275523 0.0909346 0.00273125 1 0 1 1 0 0 +EDGE2 8714 8673 -0.999923 0.000885586 -0.0107178 1 0 1 1 0 0 +EDGE2 8714 8713 -0.982146 -0.0343016 -0.00241732 1 0 1 1 0 0 +EDGE2 8714 8413 -0.969714 -0.0201837 0.0064177 1 0 1 1 0 0 +EDGE2 8714 1093 -0.944191 -0.00182885 0.00729893 1 0 1 1 0 0 +EDGE2 8714 5873 -1.05653 0.0109639 0.0126532 1 0 1 1 0 0 +EDGE2 8715 5795 -0.0346831 -0.0040748 -3.14813 1 0 1 1 0 0 +EDGE2 8715 8356 -0.0217823 0.944952 1.56047 1 0 1 1 0 0 +EDGE2 8715 8416 0.00390218 1.0208 1.56496 1 0 1 1 0 0 +EDGE2 8715 8676 -0.0726877 1.06202 1.57513 1 0 1 1 0 0 +EDGE2 8715 8396 -0.0147967 1.00711 1.60455 1 0 1 1 0 0 +EDGE2 8715 5856 0.0643821 1.00762 1.58044 1 0 1 1 0 0 +EDGE2 8715 5876 0.0538104 1.02639 1.57435 1 0 1 1 0 0 +EDGE2 8715 3056 0.0236184 0.950463 1.58528 1 0 1 1 0 0 +EDGE2 8715 5794 1.0504 -0.0405477 -3.17921 1 0 1 1 0 0 +EDGE2 8715 8394 0.941321 -0.0037846 -3.15 1 0 1 1 0 0 +EDGE2 8715 8554 1.05382 0.0553084 -3.13446 1 0 1 1 0 0 +EDGE2 8715 5854 0.988412 0.0182671 -3.16177 1 0 1 1 0 0 +EDGE2 8715 1134 1.05745 -0.0180051 -3.12263 1 0 1 1 0 0 +EDGE2 8715 3034 0.992619 0.0427781 -3.16399 1 0 1 1 0 0 +EDGE2 8715 3054 1.01632 0.0351186 -3.16863 1 0 1 1 0 0 +EDGE2 8715 1114 0.971097 0.044872 -3.12822 1 0 1 1 0 0 +EDGE2 8715 8395 -0.0261517 0.0408305 -3.11293 1 0 1 1 0 0 +EDGE2 8715 8555 -0.00513805 0.0297262 -3.14041 1 0 1 1 0 0 +EDGE2 8715 8675 -0.0489703 0.0258428 -0.00523276 1 0 1 1 0 0 +EDGE2 8715 8415 -0.0316873 -0.0425676 0.00156208 1 0 1 1 0 0 +EDGE2 8715 5875 0.0205133 -0.00739923 -0.0242957 1 0 1 1 0 0 +EDGE2 8715 8355 -0.0414653 0.0212512 -0.000406129 1 0 1 1 0 0 +EDGE2 8715 5855 -0.0166206 0.0518636 -3.15718 1 0 1 1 0 0 +EDGE2 8715 8714 -1.03634 0.0369944 0.014358 1 0 1 1 0 0 +EDGE2 8715 3035 0.0335625 -0.0582724 -3.14154 1 0 1 1 0 0 +EDGE2 8715 3055 0.0106944 0.0409574 -3.14788 1 0 1 1 0 0 +EDGE2 8715 1095 0.044438 0.0794339 0.0101159 1 0 1 1 0 0 +EDGE2 8715 1115 0.047996 0.0206643 -3.16871 1 0 1 1 0 0 +EDGE2 8715 1135 -0.00557782 0.0157569 -3.14721 1 0 1 1 0 0 +EDGE2 8715 1094 -0.958542 -0.0641298 0.0104506 1 0 1 1 0 0 +EDGE2 8715 8354 -0.967654 0.0333328 0.00702198 1 0 1 1 0 0 +EDGE2 8715 8414 -1.02905 0.0155102 -0.0184743 1 0 1 1 0 0 +EDGE2 8715 8674 -1.06991 -0.0186338 -0.0254639 1 0 1 1 0 0 +EDGE2 8715 5874 -1.03531 0.0640386 -0.0127336 1 0 1 1 0 0 +EDGE2 8715 1116 -0.0824898 -1.09402 -1.57257 1 0 1 1 0 0 +EDGE2 8715 3036 -0.00804158 -1.06248 -1.53841 1 0 1 1 0 0 +EDGE2 8715 5796 -0.00308501 -1.01072 -1.58659 1 0 1 1 0 0 +EDGE2 8715 8556 0.027632 -0.938806 -1.58917 1 0 1 1 0 0 +EDGE2 8715 1136 -0.0035592 -1.05023 -1.55276 1 0 1 1 0 0 +EDGE2 8715 1096 0.0841399 -1.01638 -1.54807 1 0 1 1 0 0 +EDGE2 8716 5795 -1.01603 -0.00885934 1.57368 1 0 1 1 0 0 +EDGE2 8716 5877 1.01186 0.0186189 0.014156 1 0 1 1 0 0 +EDGE2 8716 8397 0.989253 -0.0565052 0.00964636 1 0 1 1 0 0 +EDGE2 8716 8417 0.971801 -0.0314282 -0.00569509 1 0 1 1 0 0 +EDGE2 8716 8677 0.938826 0.0189593 0.00478837 1 0 1 1 0 0 +EDGE2 8716 8357 0.983525 -0.0355875 0.0219149 1 0 1 1 0 0 +EDGE2 8716 3057 1.01263 0.0923618 -0.021864 1 0 1 1 0 0 +EDGE2 8716 5857 1.05508 0.0448134 0.0293192 1 0 1 1 0 0 +EDGE2 8716 8356 0.00334529 -0.00634109 0.00506205 1 0 1 1 0 0 +EDGE2 8716 8416 -0.0339145 -0.053478 -0.0190023 1 0 1 1 0 0 +EDGE2 8716 8676 -0.0120652 -0.0429045 -0.00183031 1 0 1 1 0 0 +EDGE2 8716 8396 0.0409882 0.119659 -0.0169471 1 0 1 1 0 0 +EDGE2 8716 5856 0.0125549 -0.0571789 0.0438779 1 0 1 1 0 0 +EDGE2 8716 5876 -0.114571 -0.0273233 0.0230483 1 0 1 1 0 0 +EDGE2 8716 3056 0.0438671 0.0470948 0.0112771 1 0 1 1 0 0 +EDGE2 8716 8395 -1.06923 0.00767195 1.60556 1 0 1 1 0 0 +EDGE2 8716 8555 -0.990068 0.0615746 1.53677 1 0 1 1 0 0 +EDGE2 8716 8675 -1.1246 0.00863408 -1.55992 1 0 1 1 0 0 +EDGE2 8716 8715 -1.0149 0.0407546 -1.57413 1 0 1 1 0 0 +EDGE2 8716 8415 -0.977817 -0.0278843 -1.5641 1 0 1 1 0 0 +EDGE2 8716 5875 -0.967576 -0.0279092 -1.56606 1 0 1 1 0 0 +EDGE2 8716 8355 -1.02866 0.0517219 -1.57407 1 0 1 1 0 0 +EDGE2 8716 5855 -0.991621 0.00428316 1.5547 1 0 1 1 0 0 +EDGE2 8716 3035 -1.00736 0.00296489 1.56027 1 0 1 1 0 0 +EDGE2 8716 3055 -1.00279 0.0288645 1.58271 1 0 1 1 0 0 +EDGE2 8716 1095 -1.11653 0.0461612 -1.562 1 0 1 1 0 0 +EDGE2 8716 1115 -0.911716 -0.0147516 1.5681 1 0 1 1 0 0 +EDGE2 8716 1135 -1.00477 -0.0455286 1.59742 1 0 1 1 0 0 +EDGE2 8717 8358 1.06298 -0.0360038 -0.0183322 1 0 1 1 0 0 +EDGE2 8717 8418 1.03016 0.0137791 0.0108052 1 0 1 1 0 0 +EDGE2 8717 8678 0.935703 -0.0318973 -0.0433098 1 0 1 1 0 0 +EDGE2 8717 8398 0.948146 0.0111615 0.00186868 1 0 1 1 0 0 +EDGE2 8717 3058 1.0308 0.0687384 -0.0228595 1 0 1 1 0 0 +EDGE2 8717 5858 1.03327 0.0431967 0.0257647 1 0 1 1 0 0 +EDGE2 8717 5878 0.993075 -0.0714233 -3.1989e-05 1 0 1 1 0 0 +EDGE2 8717 5877 0.0162021 0.0212795 0.025728 1 0 1 1 0 0 +EDGE2 8717 8397 -0.0156753 0.000895227 0.0102312 1 0 1 1 0 0 +EDGE2 8717 8417 -0.00656134 -0.0300822 0.0314252 1 0 1 1 0 0 +EDGE2 8717 8677 0.0492749 0.0488941 -0.0427843 1 0 1 1 0 0 +EDGE2 8717 8357 -0.0369343 0.0336045 0.0388981 1 0 1 1 0 0 +EDGE2 8717 3057 -0.0125606 -0.0679411 0.00611615 1 0 1 1 0 0 +EDGE2 8717 5857 0.0233706 0.0146872 -0.0199279 1 0 1 1 0 0 +EDGE2 8717 8356 -0.990925 0.00851864 0.00980415 1 0 1 1 0 0 +EDGE2 8717 8416 -1.01331 0.0427231 -0.0315345 1 0 1 1 0 0 +EDGE2 8717 8676 -1.07009 -0.00907646 0.0244554 1 0 1 1 0 0 +EDGE2 8717 8716 -0.994299 -0.0254018 -0.00232979 1 0 1 1 0 0 +EDGE2 8717 8396 -1.02649 -0.0304007 -0.00450648 1 0 1 1 0 0 +EDGE2 8717 5856 -1.0008 -0.0725776 0.00396707 1 0 1 1 0 0 +EDGE2 8717 5876 -1.08247 0.0298591 -0.00518145 1 0 1 1 0 0 +EDGE2 8717 3056 -1.04174 0.0683052 -0.00395634 1 0 1 1 0 0 +EDGE2 8718 8717 -0.930106 0.0191669 0.0218522 1 0 1 1 0 0 +EDGE2 8718 8399 1.01059 0.0570856 -0.0455413 1 0 1 1 0 0 +EDGE2 8718 8679 0.943374 0.0623114 -0.0107089 1 0 1 1 0 0 +EDGE2 8718 8419 0.94922 0.087092 0.00365589 1 0 1 1 0 0 +EDGE2 8718 5859 0.959656 0.0955224 0.0598974 1 0 1 1 0 0 +EDGE2 8718 5879 1.0338 -0.0571788 0.0104902 1 0 1 1 0 0 +EDGE2 8718 8359 1.02592 -0.000679962 -0.0183837 1 0 1 1 0 0 +EDGE2 8718 3059 1.02795 -0.0371661 -0.0243374 1 0 1 1 0 0 +EDGE2 8718 8358 -0.0285947 -0.036808 -0.00116151 1 0 1 1 0 0 +EDGE2 8718 8418 -0.0689437 -0.0364814 0.012775 1 0 1 1 0 0 +EDGE2 8718 8678 -0.0203427 -0.00863814 -0.0113008 1 0 1 1 0 0 +EDGE2 8718 8398 -0.0050217 0.0352372 -0.00164 1 0 1 1 0 0 +EDGE2 8718 3058 -0.0392854 0.0363502 0.0300064 1 0 1 1 0 0 +EDGE2 8718 5858 -0.0522049 -0.0207118 -0.00712736 1 0 1 1 0 0 +EDGE2 8718 5878 -0.0531695 0.000997709 -0.00685037 1 0 1 1 0 0 +EDGE2 8718 5877 -1.05576 -0.00933082 -0.000101011 1 0 1 1 0 0 +EDGE2 8718 8397 -0.991493 -0.0625791 0.00727386 1 0 1 1 0 0 +EDGE2 8718 8417 -0.97445 0.0297139 0.010998 1 0 1 1 0 0 +EDGE2 8718 8677 -0.891269 -0.00439178 0.0178933 1 0 1 1 0 0 +EDGE2 8718 8357 -1.01934 -0.0967916 0.0325449 1 0 1 1 0 0 +EDGE2 8718 3057 -0.974784 0.00426966 -0.0030798 1 0 1 1 0 0 +EDGE2 8718 5857 -0.981184 -0.0633683 -0.00736042 1 0 1 1 0 0 +EDGE2 8719 8360 1.03621 -0.0321909 0.00559429 1 0 1 1 0 0 +EDGE2 8719 8480 0.954378 -0.0272819 -3.15379 1 0 1 1 0 0 +EDGE2 8719 8660 0.989635 0.0146422 -3.12835 1 0 1 1 0 0 +EDGE2 8719 8680 1.01729 0.0104124 0.00922867 1 0 1 1 0 0 +EDGE2 8719 8620 1.00245 0.0354444 -3.14315 1 0 1 1 0 0 +EDGE2 8719 8400 1.02692 -0.00484631 -0.0240551 1 0 1 1 0 0 +EDGE2 8719 8420 0.979991 -0.0570159 0.0145257 1 0 1 1 0 0 +EDGE2 8719 8380 1.02896 -0.0177379 -3.1776 1 0 1 1 0 0 +EDGE2 8719 3060 0.978992 -0.0136113 0.0205376 1 0 1 1 0 0 +EDGE2 8719 3160 0.956524 0.0158108 -3.1168 1 0 1 1 0 0 +EDGE2 8719 5860 0.920046 -0.0641848 0.0142429 1 0 1 1 0 0 +EDGE2 8719 5880 1.04959 -0.0557107 0.00894344 1 0 1 1 0 0 +EDGE2 8719 3080 1.04706 -0.0505159 -3.12858 1 0 1 1 0 0 +EDGE2 8719 1080 1.01113 -0.0129861 -3.1216 1 0 1 1 0 0 +EDGE2 8719 8399 0.0462257 -0.000667885 0.0154317 1 0 1 1 0 0 +EDGE2 8719 8679 0.0303579 -0.0418427 0.0158777 1 0 1 1 0 0 +EDGE2 8719 8419 -0.0513776 -0.0475828 0.0205146 1 0 1 1 0 0 +EDGE2 8719 5859 -0.00701307 0.00827502 -0.0347805 1 0 1 1 0 0 +EDGE2 8719 5879 0.0237306 0.0110725 0.0215156 1 0 1 1 0 0 +EDGE2 8719 8359 -0.0971624 -0.00993081 0.0204311 1 0 1 1 0 0 +EDGE2 8719 3059 0.0314165 -0.0217714 0.0194098 1 0 1 1 0 0 +EDGE2 8719 8358 -1.08392 0.0564785 -0.0154535 1 0 1 1 0 0 +EDGE2 8719 8418 -0.968454 -0.0314793 -0.011343 1 0 1 1 0 0 +EDGE2 8719 8678 -1.03494 -0.0339759 -0.0187475 1 0 1 1 0 0 +EDGE2 8719 8718 -0.984037 0.0116333 0.0137005 1 0 1 1 0 0 +EDGE2 8719 8398 -0.954634 0.0317788 0.0460893 1 0 1 1 0 0 +EDGE2 8719 3058 -0.998054 -0.0224069 0.003423 1 0 1 1 0 0 +EDGE2 8719 5858 -0.945529 -0.0112327 0.0172383 1 0 1 1 0 0 +EDGE2 8719 5878 -1.09051 0.0518331 -0.0174612 1 0 1 1 0 0 +EDGE2 8720 8360 0.0275385 0.0174321 0.0121524 1 0 1 1 0 0 +EDGE2 8720 8379 1.0016 0.0307087 -3.11977 1 0 1 1 0 0 +EDGE2 8720 8619 1.02896 -0.0307343 -3.15118 1 0 1 1 0 0 +EDGE2 8720 8659 0.986773 -0.0467496 -3.1365 1 0 1 1 0 0 +EDGE2 8720 8479 0.986519 -0.0152927 -3.13485 1 0 1 1 0 0 +EDGE2 8720 3079 0.935712 0.0967879 -3.14333 1 0 1 1 0 0 +EDGE2 8720 3159 1.03977 -0.0552194 -3.15663 1 0 1 1 0 0 +EDGE2 8720 1079 0.985939 -0.0152424 -3.12451 1 0 1 1 0 0 +EDGE2 8720 8361 -0.0456679 -0.937277 -1.57919 1 0 1 1 0 0 +EDGE2 8720 8421 -0.0167824 -0.997197 -1.58612 1 0 1 1 0 0 +EDGE2 8720 8481 0.0564728 -0.975749 -1.54675 1 0 1 1 0 0 +EDGE2 8720 8621 0.0781951 -0.986008 -1.58722 1 0 1 1 0 0 +EDGE2 8720 8381 0.0058636 -0.991847 -1.57569 1 0 1 1 0 0 +EDGE2 8720 3081 -0.0686823 -1.00918 -1.58819 1 0 1 1 0 0 +EDGE2 8720 3161 -0.0331936 -0.944772 -1.54016 1 0 1 1 0 0 +EDGE2 8720 5881 0.0179173 -1.02197 -1.57876 1 0 1 1 0 0 +EDGE2 8720 3061 0.149253 -0.972161 -1.56901 1 0 1 1 0 0 +EDGE2 8720 8480 0.0790088 -0.0328717 -3.12544 1 0 1 1 0 0 +EDGE2 8720 8660 0.0337588 0.0222537 -3.14371 1 0 1 1 0 0 +EDGE2 8720 8680 0.0409306 0.0479648 -0.0263369 1 0 1 1 0 0 +EDGE2 8720 8620 0.0481948 -0.0460204 -3.14358 1 0 1 1 0 0 +EDGE2 8720 8400 -0.0976163 -0.0248923 0.0230213 1 0 1 1 0 0 +EDGE2 8720 8420 -0.0197729 0.0578602 0.00131137 1 0 1 1 0 0 +EDGE2 8720 8380 0.00856841 0.0317061 -3.13943 1 0 1 1 0 0 +EDGE2 8720 8401 -0.0159398 1.07435 1.5483 1 0 1 1 0 0 +EDGE2 8720 3060 0.124469 0.00696632 -0.0236606 1 0 1 1 0 0 +EDGE2 8720 3160 -0.0682938 -0.0140974 -3.13926 1 0 1 1 0 0 +EDGE2 8720 5860 0.0720601 -0.0175476 0.00851228 1 0 1 1 0 0 +EDGE2 8720 5880 0.0614569 -0.0144492 -0.0168214 1 0 1 1 0 0 +EDGE2 8720 3080 -0.00748511 0.0389152 -3.13478 1 0 1 1 0 0 +EDGE2 8720 8681 0.0751635 0.972388 1.557 1 0 1 1 0 0 +EDGE2 8720 1080 -0.0243828 0.0126356 -3.16897 1 0 1 1 0 0 +EDGE2 8720 8661 -0.0266841 0.981465 1.5588 1 0 1 1 0 0 +EDGE2 8720 1081 0.0191684 0.972158 1.57964 1 0 1 1 0 0 +EDGE2 8720 5861 -0.0380845 1.08283 1.59321 1 0 1 1 0 0 +EDGE2 8720 8399 -1.03857 0.0738109 -0.000815573 1 0 1 1 0 0 +EDGE2 8720 8679 -0.964623 0.0930261 0.0646604 1 0 1 1 0 0 +EDGE2 8720 8719 -0.969898 0.0284554 -0.00792341 1 0 1 1 0 0 +EDGE2 8720 8419 -0.943534 0.123964 0.01206 1 0 1 1 0 0 +EDGE2 8720 5859 -0.983398 -0.0601515 0.0139518 1 0 1 1 0 0 +EDGE2 8720 5879 -0.970095 0.0930828 0.018831 1 0 1 1 0 0 +EDGE2 8720 8359 -1.04501 0.0272762 -0.0314617 1 0 1 1 0 0 +EDGE2 8720 3059 -1.13472 -0.00644214 0.0240288 1 0 1 1 0 0 +EDGE2 8721 8360 -0.960899 -0.0269682 -1.56131 1 0 1 1 0 0 +EDGE2 8721 8480 -0.988106 -0.0285075 1.54712 1 0 1 1 0 0 +EDGE2 8721 8660 -0.980186 -0.0211226 1.5963 1 0 1 1 0 0 +EDGE2 8721 8680 -0.984976 0.014657 -1.57074 1 0 1 1 0 0 +EDGE2 8721 8720 -0.997307 -0.00996309 -1.61684 1 0 1 1 0 0 +EDGE2 8721 8620 -1.02368 0.052322 1.58481 1 0 1 1 0 0 +EDGE2 8721 8400 -0.962238 0.0656822 -1.5465 1 0 1 1 0 0 +EDGE2 8721 8420 -1.00127 -0.106562 -1.55801 1 0 1 1 0 0 +EDGE2 8721 8380 -1.04822 -0.0259186 1.57369 1 0 1 1 0 0 +EDGE2 8721 5862 1.05998 0.0441736 0.0143633 1 0 1 1 0 0 +EDGE2 8721 8401 -0.0038251 -0.100037 0.00185209 1 0 1 1 0 0 +EDGE2 8721 3060 -0.910932 0.0293996 -1.58018 1 0 1 1 0 0 +EDGE2 8721 3160 -1.04829 -0.0374319 1.61377 1 0 1 1 0 0 +EDGE2 8721 5860 -0.921646 0.0422802 -1.53662 1 0 1 1 0 0 +EDGE2 8721 5880 -1.0129 0.0343843 -1.57848 1 0 1 1 0 0 +EDGE2 8721 3080 -0.987344 0.025999 1.55392 1 0 1 1 0 0 +EDGE2 8721 8681 -0.00305689 -0.0170339 -0.0027727 1 0 1 1 0 0 +EDGE2 8721 1080 -1.00687 -0.0404534 1.56352 1 0 1 1 0 0 +EDGE2 8721 8661 0.0100585 -0.0272991 -0.0231658 1 0 1 1 0 0 +EDGE2 8721 1081 0.0662647 0.0161878 0.000391106 1 0 1 1 0 0 +EDGE2 8721 5861 0.0438121 -0.0722846 -0.00890161 1 0 1 1 0 0 +EDGE2 8721 8662 1.00424 -0.00514743 0.0158795 1 0 1 1 0 0 +EDGE2 8721 8682 1.05646 0.0215362 0.0191599 1 0 1 1 0 0 +EDGE2 8721 8402 0.960915 -0.0308481 0.00865666 1 0 1 1 0 0 +EDGE2 8721 1082 0.911466 0.0105945 -0.0134086 1 0 1 1 0 0 +EDGE2 8722 5862 -0.0734879 0.0106955 0.00174448 1 0 1 1 0 0 +EDGE2 8722 8401 -1.05032 0.0345091 -0.0136041 1 0 1 1 0 0 +EDGE2 8722 8681 -1.02398 -0.0710047 -0.010535 1 0 1 1 0 0 +EDGE2 8722 8721 -1.01228 -0.155695 0.00225172 1 0 1 1 0 0 +EDGE2 8722 8661 -1.0198 0.0287938 0.0318773 1 0 1 1 0 0 +EDGE2 8722 1081 -1.01518 0.0455218 -0.0232241 1 0 1 1 0 0 +EDGE2 8722 5861 -0.91782 -0.00282703 0.00872936 1 0 1 1 0 0 +EDGE2 8722 8662 -0.0238089 0.0146813 0.0184751 1 0 1 1 0 0 +EDGE2 8722 8682 0.00442288 0.0337029 -0.0363944 1 0 1 1 0 0 +EDGE2 8722 8402 0.0660268 -0.0480928 0.0140326 1 0 1 1 0 0 +EDGE2 8722 8403 1.00774 -0.00380159 -0.0309301 1 0 1 1 0 0 +EDGE2 8722 8683 1.0535 0.0121301 0.0124746 1 0 1 1 0 0 +EDGE2 8722 1082 -0.013658 -0.0425449 0.0100562 1 0 1 1 0 0 +EDGE2 8722 8663 1.0155 -0.0731258 0.0115035 1 0 1 1 0 0 +EDGE2 8722 1083 0.905926 0.0294376 0.0445925 1 0 1 1 0 0 +EDGE2 8722 5863 1.05116 0.0603436 0.00686601 1 0 1 1 0 0 +EDGE2 8723 5862 -0.999494 -0.0263772 -0.00451362 1 0 1 1 0 0 +EDGE2 8723 8662 -0.897285 -0.0322607 -0.00111644 1 0 1 1 0 0 +EDGE2 8723 8682 -1.05056 -0.0433198 0.00687167 1 0 1 1 0 0 +EDGE2 8723 8722 -1.06722 -0.0795769 -0.00661178 1 0 1 1 0 0 +EDGE2 8723 8402 -1.04044 -0.0724083 0.0101958 1 0 1 1 0 0 +EDGE2 8723 8664 1.0151 -0.0164437 0.00133954 1 0 1 1 0 0 +EDGE2 8723 8403 0.0414734 0.0341503 0.0111538 1 0 1 1 0 0 +EDGE2 8723 8683 -0.0570633 0.0046914 0.00418291 1 0 1 1 0 0 +EDGE2 8723 1082 -0.94713 0.00526343 -0.0140672 1 0 1 1 0 0 +EDGE2 8723 8663 0.0373038 0.0117743 0.00694962 1 0 1 1 0 0 +EDGE2 8723 1083 0.0524242 -0.0297458 0.0165255 1 0 1 1 0 0 +EDGE2 8723 5863 0.0271604 0.0709627 0.018459 1 0 1 1 0 0 +EDGE2 8723 8684 0.944887 0.0774206 -0.00450193 1 0 1 1 0 0 +EDGE2 8723 1084 0.963099 -0.0508267 0.00911974 1 0 1 1 0 0 +EDGE2 8723 5864 0.948078 -0.00389145 -0.02287 1 0 1 1 0 0 +EDGE2 8723 8404 1.05494 0.0316865 -0.0162002 1 0 1 1 0 0 +EDGE2 8724 8345 0.979034 0.0801881 -3.11168 1 0 1 1 0 0 +EDGE2 8724 8664 -0.0636869 0.0236089 0.014047 1 0 1 1 0 0 +EDGE2 8724 8403 -0.964062 0.0320219 0.00965572 1 0 1 1 0 0 +EDGE2 8724 8683 -1.04651 -0.0316606 0.0236794 1 0 1 1 0 0 +EDGE2 8724 8723 -0.986071 -0.0830746 -0.00500001 1 0 1 1 0 0 +EDGE2 8724 8663 -1.02072 -0.124372 -6.82711e-06 1 0 1 1 0 0 +EDGE2 8724 1083 -1.0084 -0.0777177 0.00579377 1 0 1 1 0 0 +EDGE2 8724 5863 -1.02124 -0.097534 0.0283273 1 0 1 1 0 0 +EDGE2 8724 8684 0.00329872 -0.00762293 -0.0167357 1 0 1 1 0 0 +EDGE2 8724 8705 1.05981 0.11166 -3.13057 1 0 1 1 0 0 +EDGE2 8724 1084 -0.0130813 -0.0463504 -0.0203707 1 0 1 1 0 0 +EDGE2 8724 5864 0.0516739 0.0424704 -0.0247854 1 0 1 1 0 0 +EDGE2 8724 8404 0.0553637 -0.030001 0.0276142 1 0 1 1 0 0 +EDGE2 8724 8665 0.97767 0.022206 -0.00567851 1 0 1 1 0 0 +EDGE2 8724 8685 0.993778 0.0728674 -0.00601916 1 0 1 1 0 0 +EDGE2 8724 8405 0.987597 0.00585754 -0.000534131 1 0 1 1 0 0 +EDGE2 8724 1045 0.955356 0.055802 -3.15315 1 0 1 1 0 0 +EDGE2 8724 1085 1.02823 -0.0299442 0.0424768 1 0 1 1 0 0 +EDGE2 8724 5865 1.02855 0.0326554 -0.0127988 1 0 1 1 0 0 +EDGE2 8725 8345 0.0440557 -0.00702242 -3.15203 1 0 1 1 0 0 +EDGE2 8725 8686 -0.0310623 -0.994651 -1.54089 1 0 1 1 0 0 +EDGE2 8725 1046 -0.0216031 -0.978964 -1.57385 1 0 1 1 0 0 +EDGE2 8725 8664 -1.05415 0.0110295 -0.000268309 1 0 1 1 0 0 +EDGE2 8725 8724 -0.940513 0.0234657 -0.00867318 1 0 1 1 0 0 +EDGE2 8725 8684 -0.980628 -0.0363531 -0.00558977 1 0 1 1 0 0 +EDGE2 8725 8705 0.035831 0.00585028 -3.19841 1 0 1 1 0 0 +EDGE2 8725 1084 -1.06791 -0.0501133 -0.00752658 1 0 1 1 0 0 +EDGE2 8725 5864 -0.958205 0.0154088 0.0187763 1 0 1 1 0 0 +EDGE2 8725 8404 -1.0183 -0.0618351 -0.0476926 1 0 1 1 0 0 +EDGE2 8725 8665 0.0110812 0.0978505 -0.0409054 1 0 1 1 0 0 +EDGE2 8725 8685 0.118719 -0.0251949 -0.0151225 1 0 1 1 0 0 +EDGE2 8725 8405 -0.0226505 0.0653852 -0.00783251 1 0 1 1 0 0 +EDGE2 8725 8344 1.0931 0.034593 -3.18275 1 0 1 1 0 0 +EDGE2 8725 1045 0.0168352 -0.0177502 -3.15954 1 0 1 1 0 0 +EDGE2 8725 1085 0.122642 0.0984167 -0.00409957 1 0 1 1 0 0 +EDGE2 8725 5865 0.0453878 0.0382629 -0.043484 1 0 1 1 0 0 +EDGE2 8725 8704 1.01978 -0.0194679 -3.12991 1 0 1 1 0 0 +EDGE2 8725 1044 1.0612 -0.0137845 -3.12714 1 0 1 1 0 0 +EDGE2 8725 8346 -0.0522229 1.04077 1.59726 1 0 1 1 0 0 +EDGE2 8725 8666 -0.0519623 0.988648 1.56111 1 0 1 1 0 0 +EDGE2 8725 8706 0.018527 1.07341 1.56054 1 0 1 1 0 0 +EDGE2 8725 8406 -0.0487035 0.958406 1.57899 1 0 1 1 0 0 +EDGE2 8725 1086 0.0779125 1.07328 1.59043 1 0 1 1 0 0 +EDGE2 8725 5866 -0.0287078 1.09705 1.56474 1 0 1 1 0 0 +EDGE2 8726 8345 -0.976558 0.0412765 1.56353 1 0 1 1 0 0 +EDGE2 8726 8705 -1.02029 -0.0734255 1.56622 1 0 1 1 0 0 +EDGE2 8726 8725 -0.907732 0.040727 -1.56887 1 0 1 1 0 0 +EDGE2 8726 8665 -0.977645 -0.00458995 -1.56171 1 0 1 1 0 0 +EDGE2 8726 8685 -1.08192 0.0377972 -1.53192 1 0 1 1 0 0 +EDGE2 8726 8405 -0.989926 0.0330944 -1.59123 1 0 1 1 0 0 +EDGE2 8726 1045 -1.04419 -0.0221346 1.52264 1 0 1 1 0 0 +EDGE2 8726 1085 -0.99088 0.0277797 -1.54366 1 0 1 1 0 0 +EDGE2 8726 5865 -1.03938 -0.0120709 -1.56142 1 0 1 1 0 0 +EDGE2 8726 8667 1.04113 -0.00292776 -0.0350236 1 0 1 1 0 0 +EDGE2 8726 8346 -0.0172569 0.0223459 0.0109796 1 0 1 1 0 0 +EDGE2 8726 8666 -0.0303735 -0.0048171 -0.00661698 1 0 1 1 0 0 +EDGE2 8726 8706 0.0143007 0.0186978 0.0312904 1 0 1 1 0 0 +EDGE2 8726 8406 0.0719057 -0.0216172 -0.0355167 1 0 1 1 0 0 +EDGE2 8726 1086 -0.0654067 0.0840256 -0.0216717 1 0 1 1 0 0 +EDGE2 8726 5866 0.0110319 0.016566 0.0130662 1 0 1 1 0 0 +EDGE2 8726 8707 0.977806 0.00352884 0.022567 1 0 1 1 0 0 +EDGE2 8726 8407 0.950371 -0.0569954 -0.000301716 1 0 1 1 0 0 +EDGE2 8726 5867 0.942967 -0.0918936 -0.00909427 1 0 1 1 0 0 +EDGE2 8726 8347 1.03823 0.0372494 0.00617889 1 0 1 1 0 0 +EDGE2 8726 1087 1.05109 0.0753736 -0.00346284 1 0 1 1 0 0 +EDGE2 8727 8667 -0.0514534 0.052478 0.0263196 1 0 1 1 0 0 +EDGE2 8727 8346 -0.96195 -0.0651261 -0.0236958 1 0 1 1 0 0 +EDGE2 8727 8666 -1.00053 0.0106222 0.00923566 1 0 1 1 0 0 +EDGE2 8727 8706 -1.05408 -0.0708718 0.0106512 1 0 1 1 0 0 +EDGE2 8727 8726 -0.935386 0.0993095 -0.0218283 1 0 1 1 0 0 +EDGE2 8727 8406 -0.946158 0.0141887 -0.0124178 1 0 1 1 0 0 +EDGE2 8727 1086 -0.990686 -0.0135775 0.0136516 1 0 1 1 0 0 +EDGE2 8727 5866 -1.01699 0.00403138 0.010501 1 0 1 1 0 0 +EDGE2 8727 8707 -0.0379376 -0.0436246 0.0375625 1 0 1 1 0 0 +EDGE2 8727 8407 -0.0365163 0.000479439 -0.0185444 1 0 1 1 0 0 +EDGE2 8727 5867 -0.0145296 0.00584888 -0.0186403 1 0 1 1 0 0 +EDGE2 8727 8347 -0.0232579 -0.0572376 -0.00307913 1 0 1 1 0 0 +EDGE2 8727 1087 -0.0445595 -0.0253486 0.00726232 1 0 1 1 0 0 +EDGE2 8727 8348 1.09175 -0.126615 -0.0406298 1 0 1 1 0 0 +EDGE2 8727 8408 0.950647 -0.00354579 -0.0238138 1 0 1 1 0 0 +EDGE2 8727 8668 1.01317 0.0164651 -0.0260286 1 0 1 1 0 0 +EDGE2 8727 8708 0.95386 -0.0762901 0.0196368 1 0 1 1 0 0 +EDGE2 8727 1088 0.95792 0.0503167 -0.0279289 1 0 1 1 0 0 +EDGE2 8727 5868 1.03806 0.0177452 -0.0131963 1 0 1 1 0 0 +EDGE2 8728 8667 -1.00356 0.0444112 -0.0265788 1 0 1 1 0 0 +EDGE2 8728 8727 -1.08221 -0.0536793 -0.0224017 1 0 1 1 0 0 +EDGE2 8728 8707 -1.03132 0.0476883 0.0297252 1 0 1 1 0 0 +EDGE2 8728 8407 -0.951928 -0.0802337 -0.0133249 1 0 1 1 0 0 +EDGE2 8728 5867 -0.999269 -0.107695 -0.00588288 1 0 1 1 0 0 +EDGE2 8728 8347 -1.06251 -0.0702032 0.0235899 1 0 1 1 0 0 +EDGE2 8728 1087 -0.924627 -0.0811994 0.00949201 1 0 1 1 0 0 +EDGE2 8728 8348 -0.0056407 -0.03495 0.0133946 1 0 1 1 0 0 +EDGE2 8728 8408 -0.0205004 0.0559948 0.0646358 1 0 1 1 0 0 +EDGE2 8728 8668 -0.0563949 0.0404282 0.0245067 1 0 1 1 0 0 +EDGE2 8728 8708 -0.0898076 -0.068902 -0.0253471 1 0 1 1 0 0 +EDGE2 8728 8669 0.963839 0.0436654 -0.00444527 1 0 1 1 0 0 +EDGE2 8728 1088 -0.0164618 -0.0468884 -0.0222471 1 0 1 1 0 0 +EDGE2 8728 5868 0.0352889 0.0608026 0.011909 1 0 1 1 0 0 +EDGE2 8728 8709 1.03649 0.0023287 0.0228334 1 0 1 1 0 0 +EDGE2 8728 5869 0.967114 -0.0509686 0.0223786 1 0 1 1 0 0 +EDGE2 8728 8349 0.973633 0.0988258 0.0128886 1 0 1 1 0 0 +EDGE2 8728 8409 1.06383 -0.0248312 -0.00673911 1 0 1 1 0 0 +EDGE2 8728 1089 1.07954 -0.0271166 -0.0226558 1 0 1 1 0 0 +EDGE2 8729 8728 -0.989394 -0.0160823 -0.0385244 1 0 1 1 0 0 +EDGE2 8729 8348 -1.01177 0.056661 -0.0355805 1 0 1 1 0 0 +EDGE2 8729 8408 -1.04163 0.0690355 0.0143431 1 0 1 1 0 0 +EDGE2 8729 8668 -0.902863 0.0278173 -0.0079177 1 0 1 1 0 0 +EDGE2 8729 8708 -0.945718 -0.0407195 0.0016544 1 0 1 1 0 0 +EDGE2 8729 8669 -0.00963247 0.0159661 0.00426977 1 0 1 1 0 0 +EDGE2 8729 1088 -1.00133 0.00986639 0.00969845 1 0 1 1 0 0 +EDGE2 8729 5868 -0.949598 -0.0287965 -0.0347965 1 0 1 1 0 0 +EDGE2 8729 8709 0.00515487 0.0718402 -0.0265811 1 0 1 1 0 0 +EDGE2 8729 5869 -0.120153 0.0583001 0.0285877 1 0 1 1 0 0 +EDGE2 8729 8349 -0.0128593 -0.0213572 -0.00516339 1 0 1 1 0 0 +EDGE2 8729 8409 -0.0141803 0.0546717 -0.0328349 1 0 1 1 0 0 +EDGE2 8729 1089 -0.0784657 0.0359813 0.00411769 1 0 1 1 0 0 +EDGE2 8729 8670 1.07003 0.03112 -0.0123691 1 0 1 1 0 0 +EDGE2 8729 8710 0.982593 -0.0915572 -0.000643422 1 0 1 1 0 0 +EDGE2 8729 5870 1.0525 -0.0444115 0.0142683 1 0 1 1 0 0 +EDGE2 8729 8350 0.902851 -0.0275585 0.00613179 1 0 1 1 0 0 +EDGE2 8729 8410 1.05839 0.06409 0.038265 1 0 1 1 0 0 +EDGE2 8729 1090 0.980619 -0.049058 -0.0222735 1 0 1 1 0 0 +EDGE2 8730 8669 -0.978807 -0.105979 -0.00344468 1 0 1 1 0 0 +EDGE2 8730 8729 -1.02877 0.00982355 0.00416325 1 0 1 1 0 0 +EDGE2 8730 8709 -0.964439 -0.000137208 0.0534252 1 0 1 1 0 0 +EDGE2 8730 5869 -1.03853 0.0849703 -0.0130334 1 0 1 1 0 0 +EDGE2 8730 8349 -0.927917 0.0244393 0.000405313 1 0 1 1 0 0 +EDGE2 8730 8409 -0.920463 -0.0266859 -0.00662902 1 0 1 1 0 0 +EDGE2 8730 1089 -0.972385 0.115316 0.0197293 1 0 1 1 0 0 +EDGE2 8730 8670 -0.000863004 0.0870962 0.0313004 1 0 1 1 0 0 +EDGE2 8730 8351 0.0647374 0.987896 1.57012 1 0 1 1 0 0 +EDGE2 8730 8671 0.0274554 0.882068 1.50911 1 0 1 1 0 0 +EDGE2 8730 8711 0.0188118 0.987781 1.59305 1 0 1 1 0 0 +EDGE2 8730 8411 -0.0217741 0.944217 1.54082 1 0 1 1 0 0 +EDGE2 8730 1091 0.0154285 1.04313 1.59632 1 0 1 1 0 0 +EDGE2 8730 5871 0.0514477 1.04205 1.572 1 0 1 1 0 0 +EDGE2 8730 8710 -0.0761094 0.00437911 -0.00104931 1 0 1 1 0 0 +EDGE2 8730 5870 -0.0389592 -0.0150221 -0.0582816 1 0 1 1 0 0 +EDGE2 8730 8350 -0.00515658 -0.0529769 0.0146573 1 0 1 1 0 0 +EDGE2 8730 8410 -0.0673983 -0.0442255 -0.0130589 1 0 1 1 0 0 +EDGE2 8730 1090 0.00272208 -0.0871281 -0.00356653 1 0 1 1 0 0 +EDGE2 8731 1092 1.0199 -0.0757484 0.014702 1 0 1 1 0 0 +EDGE2 8731 8672 0.953913 0.0985459 -0.00498642 1 0 1 1 0 0 +EDGE2 8731 8712 0.92231 -0.0129483 0.042048 1 0 1 1 0 0 +EDGE2 8731 8352 1.01167 0.0274513 0.00333371 1 0 1 1 0 0 +EDGE2 8731 8412 0.957289 0.0437611 -0.00341245 1 0 1 1 0 0 +EDGE2 8731 5872 1.05874 -0.0135591 0.0302884 1 0 1 1 0 0 +EDGE2 8731 8670 -1.02013 0.0585793 -1.52619 1 0 1 1 0 0 +EDGE2 8731 8351 -0.0681812 0.0360368 0.0488626 1 0 1 1 0 0 +EDGE2 8731 8671 0.0649478 0.0268893 0.0252611 1 0 1 1 0 0 +EDGE2 8731 8711 -0.037736 -0.125376 0.000472248 1 0 1 1 0 0 +EDGE2 8731 8411 -0.00291203 -0.010662 0.0135797 1 0 1 1 0 0 +EDGE2 8731 8730 -0.964796 -0.0817691 -1.58335 1 0 1 1 0 0 +EDGE2 8731 1091 -0.0163487 -0.00219497 -0.000254279 1 0 1 1 0 0 +EDGE2 8731 5871 0.0213134 0.0413317 -0.0118783 1 0 1 1 0 0 +EDGE2 8731 8710 -0.99908 0.0445732 -1.55393 1 0 1 1 0 0 +EDGE2 8731 5870 -0.996923 -0.0561148 -1.57276 1 0 1 1 0 0 +EDGE2 8731 8350 -1.01312 -0.0228093 -1.57446 1 0 1 1 0 0 +EDGE2 8731 8410 -0.910697 -0.0536795 -1.58309 1 0 1 1 0 0 +EDGE2 8731 1090 -1.02026 -0.0319382 -1.55871 1 0 1 1 0 0 +EDGE2 8732 1092 0.0503963 0.00790755 -0.0179953 1 0 1 1 0 0 +EDGE2 8732 8353 0.953284 0.00850205 0.0212074 1 0 1 1 0 0 +EDGE2 8732 8673 0.975754 0.047975 -0.00504938 1 0 1 1 0 0 +EDGE2 8732 8713 1.03779 0.0378202 -0.00600689 1 0 1 1 0 0 +EDGE2 8732 8413 0.979379 -0.00617697 0.00191815 1 0 1 1 0 0 +EDGE2 8732 8672 -0.0256121 0.0267113 0.00691959 1 0 1 1 0 0 +EDGE2 8732 1093 0.91494 -0.0257244 0.000582382 1 0 1 1 0 0 +EDGE2 8732 5873 1.03112 0.0140738 -0.0069585 1 0 1 1 0 0 +EDGE2 8732 8712 0.0327465 -0.0159753 -0.00706061 1 0 1 1 0 0 +EDGE2 8732 8352 -0.0843323 -0.0437076 -0.00371779 1 0 1 1 0 0 +EDGE2 8732 8412 0.0354857 0.0309693 0.0123366 1 0 1 1 0 0 +EDGE2 8732 5872 -0.036185 -0.117012 -0.00300696 1 0 1 1 0 0 +EDGE2 8732 8351 -1.09867 0.0609592 0.000791157 1 0 1 1 0 0 +EDGE2 8732 8671 -1.05639 -0.0200641 0.0168965 1 0 1 1 0 0 +EDGE2 8732 8711 -0.942911 0.0840136 0.011863 1 0 1 1 0 0 +EDGE2 8732 8731 -0.884768 -0.0767096 -0.0259731 1 0 1 1 0 0 +EDGE2 8732 8411 -1.03209 -0.0274552 0.0231026 1 0 1 1 0 0 +EDGE2 8732 1091 -1.00404 0.0414418 0.00575404 1 0 1 1 0 0 +EDGE2 8732 5871 -1.00493 -0.0153644 0.0100262 1 0 1 1 0 0 +EDGE2 8733 1092 -1.03819 -0.0599658 -0.0296539 1 0 1 1 0 0 +EDGE2 8733 8714 1.0177 0.076532 -0.0192949 1 0 1 1 0 0 +EDGE2 8733 8353 -0.0609162 -0.0262483 0.0153829 1 0 1 1 0 0 +EDGE2 8733 1094 0.988054 -0.0127403 -0.00621495 1 0 1 1 0 0 +EDGE2 8733 8354 1.06818 0.0253319 0.00414335 1 0 1 1 0 0 +EDGE2 8733 8414 1.02006 0.11422 0.0244132 1 0 1 1 0 0 +EDGE2 8733 8674 0.993031 -0.0333694 0.00618719 1 0 1 1 0 0 +EDGE2 8733 5874 0.93606 0.0512555 -0.0096268 1 0 1 1 0 0 +EDGE2 8733 8673 0.00289594 0.044672 0.0137456 1 0 1 1 0 0 +EDGE2 8733 8713 -0.0573413 0.000126819 0.00341886 1 0 1 1 0 0 +EDGE2 8733 8413 0.0371132 -0.012496 -0.03897 1 0 1 1 0 0 +EDGE2 8733 8672 -0.9847 -0.0222279 0.0128128 1 0 1 1 0 0 +EDGE2 8733 8732 -1.06819 -0.0308539 0.00896922 1 0 1 1 0 0 +EDGE2 8733 1093 -0.0320245 0.0309169 0.0272451 1 0 1 1 0 0 +EDGE2 8733 5873 -0.0402771 0.00951834 -0.0178766 1 0 1 1 0 0 +EDGE2 8733 8712 -1.01863 -0.0445469 -0.032648 1 0 1 1 0 0 +EDGE2 8733 8352 -0.916372 0.0291215 0.012447 1 0 1 1 0 0 +EDGE2 8733 8412 -1.05316 -0.0390323 -0.0175775 1 0 1 1 0 0 +EDGE2 8733 5872 -0.965191 0.0481603 0.00838738 1 0 1 1 0 0 +EDGE2 8734 5795 0.956508 -0.0175338 -3.15594 1 0 1 1 0 0 +EDGE2 8734 8395 0.979785 0.0430654 -3.12621 1 0 1 1 0 0 +EDGE2 8734 8555 1.06349 -0.00357291 -3.13173 1 0 1 1 0 0 +EDGE2 8734 8675 0.99515 -0.0463332 -0.00841605 1 0 1 1 0 0 +EDGE2 8734 8715 1.01581 0.0806789 -0.014045 1 0 1 1 0 0 +EDGE2 8734 8415 0.965605 0.091689 -0.0340424 1 0 1 1 0 0 +EDGE2 8734 5875 0.96344 -0.0368116 0.00497598 1 0 1 1 0 0 +EDGE2 8734 8355 1.08341 -0.0414301 0.00751215 1 0 1 1 0 0 +EDGE2 8734 5855 1.05596 0.0332204 -3.1375 1 0 1 1 0 0 +EDGE2 8734 8714 -0.0360699 -0.00656287 0.0181385 1 0 1 1 0 0 +EDGE2 8734 3035 0.921531 -0.0162716 -3.13262 1 0 1 1 0 0 +EDGE2 8734 3055 0.933696 0.0309397 -3.12953 1 0 1 1 0 0 +EDGE2 8734 1095 0.97857 0.00335161 -0.000570068 1 0 1 1 0 0 +EDGE2 8734 1115 0.878949 -0.062213 -3.12375 1 0 1 1 0 0 +EDGE2 8734 1135 1.01968 -0.0397287 -3.10666 1 0 1 1 0 0 +EDGE2 8734 8353 -0.956938 -0.0656011 0.000489867 1 0 1 1 0 0 +EDGE2 8734 1094 -0.00970921 -0.0395799 -0.00188625 1 0 1 1 0 0 +EDGE2 8734 8354 -0.0813668 -0.0103875 0.00216081 1 0 1 1 0 0 +EDGE2 8734 8414 -0.0108292 0.0353425 0.0108622 1 0 1 1 0 0 +EDGE2 8734 8674 -0.0223491 -0.00568241 -0.00378632 1 0 1 1 0 0 +EDGE2 8734 5874 0.0214545 0.0523275 0.00206474 1 0 1 1 0 0 +EDGE2 8734 8673 -0.984451 0.0300208 -0.0129681 1 0 1 1 0 0 +EDGE2 8734 8713 -1.00571 0.0568661 0.0121869 1 0 1 1 0 0 +EDGE2 8734 8733 -1.05545 -0.0224417 0.0188706 1 0 1 1 0 0 +EDGE2 8734 8413 -1.02107 -0.0487596 0.00902927 1 0 1 1 0 0 +EDGE2 8734 1093 -1.01085 0.00229146 -0.0306778 1 0 1 1 0 0 +EDGE2 8734 5873 -1.04106 0.000996503 0.0108351 1 0 1 1 0 0 +EDGE2 8735 5795 0.0183887 0.0651357 -3.13717 1 0 1 1 0 0 +EDGE2 8735 8356 0.06304 1.03044 1.56844 1 0 1 1 0 0 +EDGE2 8735 8416 0.0645474 0.963054 1.56606 1 0 1 1 0 0 +EDGE2 8735 8676 -0.0722097 0.977964 1.6074 1 0 1 1 0 0 +EDGE2 8735 8716 0.0768603 1.04326 1.54732 1 0 1 1 0 0 +EDGE2 8735 8396 -0.0346629 1.01535 1.57729 1 0 1 1 0 0 +EDGE2 8735 5856 0.0320851 0.995669 1.58306 1 0 1 1 0 0 +EDGE2 8735 5876 -0.00782513 0.965185 1.56514 1 0 1 1 0 0 +EDGE2 8735 3056 -0.0696996 1.00515 1.56273 1 0 1 1 0 0 +EDGE2 8735 5794 1.08294 -0.0274541 -3.14346 1 0 1 1 0 0 +EDGE2 8735 8394 1.06682 0.0159215 -3.11488 1 0 1 1 0 0 +EDGE2 8735 8554 1.10141 0.00170841 -3.14218 1 0 1 1 0 0 +EDGE2 8735 5854 0.908623 0.0401438 -3.11496 1 0 1 1 0 0 +EDGE2 8735 1134 0.999095 -0.00448467 -3.10737 1 0 1 1 0 0 +EDGE2 8735 3034 0.94258 0.109882 -3.11447 1 0 1 1 0 0 +EDGE2 8735 3054 0.925004 -0.050805 -3.12992 1 0 1 1 0 0 +EDGE2 8735 1114 1.02883 -0.0215197 -3.16734 1 0 1 1 0 0 +EDGE2 8735 8395 -0.0668591 -0.000710397 -3.12342 1 0 1 1 0 0 +EDGE2 8735 8555 -0.000285763 0.0177942 -3.18167 1 0 1 1 0 0 +EDGE2 8735 8675 -0.00687475 0.0336788 -0.01813 1 0 1 1 0 0 +EDGE2 8735 8715 0.0107813 -0.01973 0.0115928 1 0 1 1 0 0 +EDGE2 8735 8415 -0.0294374 0.0570965 0.045926 1 0 1 1 0 0 +EDGE2 8735 5875 0.0348909 -0.0427496 -0.0275356 1 0 1 1 0 0 +EDGE2 8735 8355 0.0658004 -0.0348076 0.00675516 1 0 1 1 0 0 +EDGE2 8735 5855 0.0577788 -0.0606847 -3.16914 1 0 1 1 0 0 +EDGE2 8735 8714 -1.00087 -0.093687 -0.0114845 1 0 1 1 0 0 +EDGE2 8735 3035 -0.0084136 -0.0470862 -3.10773 1 0 1 1 0 0 +EDGE2 8735 3055 -0.0280262 -0.0102793 -3.15926 1 0 1 1 0 0 +EDGE2 8735 1095 0.114953 -0.00662194 0.0346836 1 0 1 1 0 0 +EDGE2 8735 1115 -0.0934843 0.0429042 -3.13058 1 0 1 1 0 0 +EDGE2 8735 1135 -0.0175829 -0.0503401 -3.11378 1 0 1 1 0 0 +EDGE2 8735 8734 -1.05687 0.00684711 0.00695912 1 0 1 1 0 0 +EDGE2 8735 1094 -0.991565 -0.0416462 -0.00592141 1 0 1 1 0 0 +EDGE2 8735 8354 -1.01894 -0.00689746 -0.00200725 1 0 1 1 0 0 +EDGE2 8735 8414 -0.950375 -0.0220876 -0.0108399 1 0 1 1 0 0 +EDGE2 8735 8674 -1.13971 -0.0666732 0.00796323 1 0 1 1 0 0 +EDGE2 8735 5874 -1.08484 0.0120323 -0.0177446 1 0 1 1 0 0 +EDGE2 8735 1116 0.0618193 -0.980482 -1.54362 1 0 1 1 0 0 +EDGE2 8735 3036 0.03565 -1.04264 -1.54803 1 0 1 1 0 0 +EDGE2 8735 5796 0.0944069 -0.949837 -1.58487 1 0 1 1 0 0 +EDGE2 8735 8556 0.0366209 -1.01738 -1.54981 1 0 1 1 0 0 +EDGE2 8735 1136 0.00238656 -1.00516 -1.573 1 0 1 1 0 0 +EDGE2 8735 1096 0.00522038 -0.920311 -1.54292 1 0 1 1 0 0 +EDGE2 8736 5795 -1.04714 0.0244776 1.54337 1 0 1 1 0 0 +EDGE2 8736 8717 1.03634 0.00637266 -0.0167381 1 0 1 1 0 0 +EDGE2 8736 5877 0.981809 0.149324 0.0169932 1 0 1 1 0 0 +EDGE2 8736 8397 1.03937 0.0317992 -0.0296147 1 0 1 1 0 0 +EDGE2 8736 8417 1.04661 0.107741 -0.00795404 1 0 1 1 0 0 +EDGE2 8736 8677 0.982185 0.0266198 0.0039116 1 0 1 1 0 0 +EDGE2 8736 8357 1.05871 0.0537941 0.0194094 1 0 1 1 0 0 +EDGE2 8736 3057 0.954772 0.00298122 0.0150247 1 0 1 1 0 0 +EDGE2 8736 5857 0.970601 -0.0140964 0.0173636 1 0 1 1 0 0 +EDGE2 8736 8356 -0.0519445 -0.0153299 -0.0064489 1 0 1 1 0 0 +EDGE2 8736 8416 -0.00365962 0.041971 -0.000880362 1 0 1 1 0 0 +EDGE2 8736 8676 0.075667 0.00368084 0.0267334 1 0 1 1 0 0 +EDGE2 8736 8716 0.0352591 -0.0194096 0.0108536 1 0 1 1 0 0 +EDGE2 8736 8396 0.0257686 0.0321811 0.00141764 1 0 1 1 0 0 +EDGE2 8736 5856 0.0371107 0.0723096 0.0286765 1 0 1 1 0 0 +EDGE2 8736 5876 0.0408266 0.0787231 -0.00698136 1 0 1 1 0 0 +EDGE2 8736 3056 -0.043697 -0.0226342 -0.0224377 1 0 1 1 0 0 +EDGE2 8736 8735 -0.968486 0.0157387 -1.59028 1 0 1 1 0 0 +EDGE2 8736 8395 -0.9924 -0.0141287 1.57634 1 0 1 1 0 0 +EDGE2 8736 8555 -1.01775 -0.0895992 1.55264 1 0 1 1 0 0 +EDGE2 8736 8675 -1.00981 -0.0267649 -1.57956 1 0 1 1 0 0 +EDGE2 8736 8715 -1.02783 0.0777066 -1.55624 1 0 1 1 0 0 +EDGE2 8736 8415 -1.01494 0.0597032 -1.54408 1 0 1 1 0 0 +EDGE2 8736 5875 -1.02979 0.0606239 -1.59968 1 0 1 1 0 0 +EDGE2 8736 8355 -1.00051 0.0689827 -1.54699 1 0 1 1 0 0 +EDGE2 8736 5855 -0.972697 -0.0296896 1.56859 1 0 1 1 0 0 +EDGE2 8736 3035 -0.979544 -0.00815212 1.56803 1 0 1 1 0 0 +EDGE2 8736 3055 -0.99579 0.0133785 1.5443 1 0 1 1 0 0 +EDGE2 8736 1095 -0.97099 -0.061115 -1.54529 1 0 1 1 0 0 +EDGE2 8736 1115 -1.05834 0.00928713 1.59351 1 0 1 1 0 0 +EDGE2 8736 1135 -0.919239 -0.023065 1.54333 1 0 1 1 0 0 +EDGE2 8737 8717 -0.0122762 0.0609458 0.0301537 1 0 1 1 0 0 +EDGE2 8737 8358 1.09455 -0.00683652 0.00459001 1 0 1 1 0 0 +EDGE2 8737 8418 0.974988 -0.0613902 -0.015764 1 0 1 1 0 0 +EDGE2 8737 8678 1.03751 0.0671566 0.0252138 1 0 1 1 0 0 +EDGE2 8737 8718 1.03725 0.0796277 -0.00694011 1 0 1 1 0 0 +EDGE2 8737 8398 0.996633 -0.0745708 -0.015209 1 0 1 1 0 0 +EDGE2 8737 3058 0.995959 0.00783815 0.0232711 1 0 1 1 0 0 +EDGE2 8737 5858 1.0595 -0.0511207 0.0474198 1 0 1 1 0 0 +EDGE2 8737 5878 0.931656 0.0202417 -0.0198097 1 0 1 1 0 0 +EDGE2 8737 8736 -1.00942 -0.0192478 0.00925203 1 0 1 1 0 0 +EDGE2 8737 5877 -0.181949 -0.049907 -0.0119007 1 0 1 1 0 0 +EDGE2 8737 8397 0.00257683 -0.0245134 0.0425304 1 0 1 1 0 0 +EDGE2 8737 8417 -0.0558846 -0.0306224 -0.0704965 1 0 1 1 0 0 +EDGE2 8737 8677 -0.050439 0.0204826 0.0194486 1 0 1 1 0 0 +EDGE2 8737 8357 -0.011961 0.0614744 0.0179471 1 0 1 1 0 0 +EDGE2 8737 3057 -0.0193142 -0.0846476 0.004521 1 0 1 1 0 0 +EDGE2 8737 5857 -0.0739325 0.0557037 0.000408016 1 0 1 1 0 0 +EDGE2 8737 8356 -0.932857 0.00966011 -0.0135237 1 0 1 1 0 0 +EDGE2 8737 8416 -1.02118 -0.00766717 -0.0118106 1 0 1 1 0 0 +EDGE2 8737 8676 -1.03693 -0.0186518 0.0058742 1 0 1 1 0 0 +EDGE2 8737 8716 -0.940799 0.0590568 -0.00877596 1 0 1 1 0 0 +EDGE2 8737 8396 -0.973062 0.0207752 -0.00210354 1 0 1 1 0 0 +EDGE2 8737 5856 -1.02061 0.0213376 0.0479132 1 0 1 1 0 0 +EDGE2 8737 5876 -0.979684 -0.024331 -0.0121606 1 0 1 1 0 0 +EDGE2 8737 3056 -0.959157 -0.0682167 0.00984321 1 0 1 1 0 0 +EDGE2 8738 8717 -0.934862 0.0167364 -0.0235168 1 0 1 1 0 0 +EDGE2 8738 8399 1.03387 -0.0137059 -0.0117486 1 0 1 1 0 0 +EDGE2 8738 8679 1.0168 -0.0490608 -0.00152359 1 0 1 1 0 0 +EDGE2 8738 8719 0.933027 0.0638944 0.0190215 1 0 1 1 0 0 +EDGE2 8738 8419 0.94374 0.0192703 0.00861445 1 0 1 1 0 0 +EDGE2 8738 5859 0.920642 0.0644214 0.00397498 1 0 1 1 0 0 +EDGE2 8738 5879 0.948768 0.0437102 -0.0113655 1 0 1 1 0 0 +EDGE2 8738 8359 0.987486 0.0211822 0.017354 1 0 1 1 0 0 +EDGE2 8738 3059 0.947681 -0.00499581 -0.00872012 1 0 1 1 0 0 +EDGE2 8738 8358 -0.00295309 0.0228929 -0.0132619 1 0 1 1 0 0 +EDGE2 8738 8418 -0.0339252 -0.123951 -0.0101133 1 0 1 1 0 0 +EDGE2 8738 8678 -0.000674399 -0.0348279 0.0223401 1 0 1 1 0 0 +EDGE2 8738 8718 -0.0610079 -0.130906 0.0163607 1 0 1 1 0 0 +EDGE2 8738 8398 -0.00999955 -0.0360454 0.020402 1 0 1 1 0 0 +EDGE2 8738 3058 -0.0360012 0.00875724 0.0217489 1 0 1 1 0 0 +EDGE2 8738 5858 -0.0322902 -0.00793521 0.0221032 1 0 1 1 0 0 +EDGE2 8738 5878 0.0248453 0.0734362 -0.0196803 1 0 1 1 0 0 +EDGE2 8738 8737 -1.02923 -0.0200371 0.000852412 1 0 1 1 0 0 +EDGE2 8738 5877 -1.10496 -0.0332245 0.00325659 1 0 1 1 0 0 +EDGE2 8738 8397 -0.965155 0.0218811 -0.0218052 1 0 1 1 0 0 +EDGE2 8738 8417 -0.983391 0.0202382 0.00254049 1 0 1 1 0 0 +EDGE2 8738 8677 -1.01386 0.0400522 0.0262598 1 0 1 1 0 0 +EDGE2 8738 8357 -0.968202 0.0657203 -0.036518 1 0 1 1 0 0 +EDGE2 8738 3057 -1.05095 -0.0205881 0.0162407 1 0 1 1 0 0 +EDGE2 8738 5857 -0.895139 0.0707485 -0.0012197 1 0 1 1 0 0 +EDGE2 8739 8360 1.12154 -0.0556718 -0.00545467 1 0 1 1 0 0 +EDGE2 8739 8480 0.909176 0.0528741 -3.1379 1 0 1 1 0 0 +EDGE2 8739 8660 0.91378 0.0363516 -3.13063 1 0 1 1 0 0 +EDGE2 8739 8680 0.992598 -0.0853169 -0.0135015 1 0 1 1 0 0 +EDGE2 8739 8720 0.987852 0.0574884 -0.0092003 1 0 1 1 0 0 +EDGE2 8739 8620 0.939579 -0.0381914 -3.15795 1 0 1 1 0 0 +EDGE2 8739 8400 0.999563 0.0241337 -0.0128808 1 0 1 1 0 0 +EDGE2 8739 8420 1.00236 0.0754673 -0.0201819 1 0 1 1 0 0 +EDGE2 8739 8380 0.99653 0.00575784 -3.14604 1 0 1 1 0 0 +EDGE2 8739 3060 1.08492 -0.0101885 0.011001 1 0 1 1 0 0 +EDGE2 8739 3160 0.986518 -0.0190852 -3.11824 1 0 1 1 0 0 +EDGE2 8739 5860 0.948288 -0.00237395 0.0254208 1 0 1 1 0 0 +EDGE2 8739 5880 0.995242 0.0368201 -6.6613e-05 1 0 1 1 0 0 +EDGE2 8739 3080 0.951066 -0.00966158 -3.14118 1 0 1 1 0 0 +EDGE2 8739 1080 0.981166 0.0698868 -3.11966 1 0 1 1 0 0 +EDGE2 8739 8738 -1.01144 0.0178077 0.00480349 1 0 1 1 0 0 +EDGE2 8739 8399 -0.111026 0.0681765 -0.0145019 1 0 1 1 0 0 +EDGE2 8739 8679 -0.0650703 -0.0254957 -0.0128552 1 0 1 1 0 0 +EDGE2 8739 8719 0.0185653 -0.033914 0.00725778 1 0 1 1 0 0 +EDGE2 8739 8419 -0.0549256 -0.105884 -0.0111215 1 0 1 1 0 0 +EDGE2 8739 5859 0.0607394 -0.0261928 -0.0109185 1 0 1 1 0 0 +EDGE2 8739 5879 0.0456602 -0.0248477 -0.00122432 1 0 1 1 0 0 +EDGE2 8739 8359 -0.0725223 -0.00623593 0.0322274 1 0 1 1 0 0 +EDGE2 8739 3059 0.0406328 -0.00300686 0.00239514 1 0 1 1 0 0 +EDGE2 8739 8358 -1.05537 -0.0448646 0.00414576 1 0 1 1 0 0 +EDGE2 8739 8418 -0.969406 0.0217209 -0.0255901 1 0 1 1 0 0 +EDGE2 8739 8678 -1.00585 0.0144143 0.0106287 1 0 1 1 0 0 +EDGE2 8739 8718 -1.02291 0.0195256 -0.0460885 1 0 1 1 0 0 +EDGE2 8739 8398 -1.07247 -0.00141874 0.0330561 1 0 1 1 0 0 +EDGE2 8739 3058 -1.01372 0.0205305 0.0132998 1 0 1 1 0 0 +EDGE2 8739 5858 -0.999482 0.0168246 0.0030592 1 0 1 1 0 0 +EDGE2 8739 5878 -1.10835 -0.0571284 0.0460746 1 0 1 1 0 0 +EDGE2 8740 8360 -0.0231535 -0.0407244 -0.0182094 1 0 1 1 0 0 +EDGE2 8740 8379 1.03367 0.0233728 -3.14229 1 0 1 1 0 0 +EDGE2 8740 8619 0.932011 -0.0163677 -3.14284 1 0 1 1 0 0 +EDGE2 8740 8659 0.969667 -0.101709 -3.15875 1 0 1 1 0 0 +EDGE2 8740 8479 0.986149 0.0198013 -3.15877 1 0 1 1 0 0 +EDGE2 8740 3079 1.06617 -0.0684912 -3.145 1 0 1 1 0 0 +EDGE2 8740 3159 0.949658 0.0457723 -3.15644 1 0 1 1 0 0 +EDGE2 8740 1079 1.0579 -0.0833709 -3.15887 1 0 1 1 0 0 +EDGE2 8740 8361 0.0546786 -0.988996 -1.55743 1 0 1 1 0 0 +EDGE2 8740 8421 -0.0974284 -0.94125 -1.59717 1 0 1 1 0 0 +EDGE2 8740 8481 -0.0405126 -1.0291 -1.58715 1 0 1 1 0 0 +EDGE2 8740 8621 -0.038232 -0.836864 -1.55901 1 0 1 1 0 0 +EDGE2 8740 8381 -0.0311944 -0.96447 -1.5819 1 0 1 1 0 0 +EDGE2 8740 3081 -0.0335755 -0.949331 -1.55939 1 0 1 1 0 0 +EDGE2 8740 3161 0.116254 -0.996602 -1.53831 1 0 1 1 0 0 +EDGE2 8740 5881 0.0134536 -1.1273 -1.57759 1 0 1 1 0 0 +EDGE2 8740 3061 0.0319852 -0.9823 -1.55518 1 0 1 1 0 0 +EDGE2 8740 8480 0.08792 -0.0148277 -3.12543 1 0 1 1 0 0 +EDGE2 8740 8660 -0.00633493 0.0235002 -3.08693 1 0 1 1 0 0 +EDGE2 8740 8680 -0.00353396 -0.109178 -0.00617348 1 0 1 1 0 0 +EDGE2 8740 8720 -0.0729781 0.0146172 -0.0154311 1 0 1 1 0 0 +EDGE2 8740 8620 -0.0417638 -0.0944364 -3.10185 1 0 1 1 0 0 +EDGE2 8740 8400 0.0246844 -0.0725225 0.0320487 1 0 1 1 0 0 +EDGE2 8740 8420 0.0718243 0.00442908 -0.0152892 1 0 1 1 0 0 +EDGE2 8740 8380 -0.058002 0.101589 -3.1719 1 0 1 1 0 0 +EDGE2 8740 8401 0.0198504 1.01577 1.57136 1 0 1 1 0 0 +EDGE2 8740 3060 0.0316657 -0.048509 0.0252784 1 0 1 1 0 0 +EDGE2 8740 3160 0.0185754 0.0409554 -3.11817 1 0 1 1 0 0 +EDGE2 8740 5860 0.0593818 0.00750887 0.0123897 1 0 1 1 0 0 +EDGE2 8740 5880 -0.00189095 -0.00780656 -0.0180918 1 0 1 1 0 0 +EDGE2 8740 3080 0.0805188 -0.0530743 -3.1617 1 0 1 1 0 0 +EDGE2 8740 8681 0.04667 0.957059 1.56002 1 0 1 1 0 0 +EDGE2 8740 8721 0.0394859 1.04626 1.57358 1 0 1 1 0 0 +EDGE2 8740 1080 0.0456573 0.0398442 -3.15285 1 0 1 1 0 0 +EDGE2 8740 8661 0.0191997 1.01458 1.54791 1 0 1 1 0 0 +EDGE2 8740 1081 0.0754737 0.951493 1.57285 1 0 1 1 0 0 +EDGE2 8740 5861 0.0167871 0.991619 1.58538 1 0 1 1 0 0 +EDGE2 8740 8399 -0.975623 0.0475076 0.0055914 1 0 1 1 0 0 +EDGE2 8740 8679 -1.02542 0.0735709 -0.0154221 1 0 1 1 0 0 +EDGE2 8740 8719 -0.982085 -0.0181173 -0.021168 1 0 1 1 0 0 +EDGE2 8740 8739 -0.98462 -0.0665815 -0.0322206 1 0 1 1 0 0 +EDGE2 8740 8419 -1.05351 0.022667 0.0120347 1 0 1 1 0 0 +EDGE2 8740 5859 -0.955706 -0.0182119 0.0214007 1 0 1 1 0 0 +EDGE2 8740 5879 -1.0328 -0.0230552 0.00722232 1 0 1 1 0 0 +EDGE2 8740 8359 -0.963302 -0.0312987 -0.0266371 1 0 1 1 0 0 +EDGE2 8740 3059 -0.973083 0.0210795 -0.0144508 1 0 1 1 0 0 +EDGE2 8741 8360 -0.973677 -0.137417 1.54193 1 0 1 1 0 0 +EDGE2 8741 8362 0.963045 -0.0518665 0.0348274 1 0 1 1 0 0 +EDGE2 8741 8422 1.00175 0.0308579 0.0328118 1 0 1 1 0 0 +EDGE2 8741 8482 0.885677 -0.0471807 -0.0113344 1 0 1 1 0 0 +EDGE2 8741 8622 1.01846 0.0203423 0.0204824 1 0 1 1 0 0 +EDGE2 8741 8382 1.04306 0.0187948 0.000958958 1 0 1 1 0 0 +EDGE2 8741 3082 1.02614 0.0609309 -0.0125388 1 0 1 1 0 0 +EDGE2 8741 3162 1.00553 0.0432214 0.00194509 1 0 1 1 0 0 +EDGE2 8741 5882 0.994304 -0.0849646 -0.0100276 1 0 1 1 0 0 +EDGE2 8741 3062 1.03042 0.0129888 0.0307451 1 0 1 1 0 0 +EDGE2 8741 8740 -0.985051 -0.0917118 1.54645 1 0 1 1 0 0 +EDGE2 8741 8361 0.0102789 0.00674192 -0.0152526 1 0 1 1 0 0 +EDGE2 8741 8421 -0.0184974 0.0815227 -0.0114937 1 0 1 1 0 0 +EDGE2 8741 8481 -0.107423 0.0319569 -0.0305624 1 0 1 1 0 0 +EDGE2 8741 8621 0.0629694 -0.047016 -0.0149191 1 0 1 1 0 0 +EDGE2 8741 8381 0.0275389 -0.0744423 -0.00740275 1 0 1 1 0 0 +EDGE2 8741 3081 0.0080089 0.0292911 -0.000594632 1 0 1 1 0 0 +EDGE2 8741 3161 -0.0221185 -0.00514759 -0.0115574 1 0 1 1 0 0 +EDGE2 8741 5881 0.0576032 -0.0303147 -0.0157869 1 0 1 1 0 0 +EDGE2 8741 3061 -0.0208353 0.0184254 0.00331843 1 0 1 1 0 0 +EDGE2 8741 8480 -0.934533 0.0277172 -1.5626 1 0 1 1 0 0 +EDGE2 8741 8660 -1.0546 0.0892133 -1.58439 1 0 1 1 0 0 +EDGE2 8741 8680 -0.849652 -0.0087491 1.56254 1 0 1 1 0 0 +EDGE2 8741 8720 -0.909346 0.0280477 1.55203 1 0 1 1 0 0 +EDGE2 8741 8620 -1.05513 -0.0113805 -1.5845 1 0 1 1 0 0 +EDGE2 8741 8400 -0.958623 -0.105824 1.57847 1 0 1 1 0 0 +EDGE2 8741 8420 -0.993719 0.0258603 1.59821 1 0 1 1 0 0 +EDGE2 8741 8380 -1.0182 0.0174594 -1.60177 1 0 1 1 0 0 +EDGE2 8741 3060 -0.973484 0.0193115 1.58938 1 0 1 1 0 0 +EDGE2 8741 3160 -0.942276 0.0638053 -1.57754 1 0 1 1 0 0 +EDGE2 8741 5860 -0.903012 -0.0510875 1.57543 1 0 1 1 0 0 +EDGE2 8741 5880 -0.961678 0.0416003 1.54995 1 0 1 1 0 0 +EDGE2 8741 3080 -0.939817 0.0588482 -1.60303 1 0 1 1 0 0 +EDGE2 8741 1080 -1.02029 0.0577333 -1.54642 1 0 1 1 0 0 +EDGE2 8742 8741 -0.971688 -0.0546589 -0.0118752 1 0 1 1 0 0 +EDGE2 8742 8363 0.938315 0.0149393 -0.0108152 1 0 1 1 0 0 +EDGE2 8742 8423 0.968408 -0.0185531 0.00741879 1 0 1 1 0 0 +EDGE2 8742 8483 0.960431 0.00567444 0.000744039 1 0 1 1 0 0 +EDGE2 8742 8623 0.977145 -0.000971187 -0.0181469 1 0 1 1 0 0 +EDGE2 8742 8383 1.03463 -0.0179225 0.0105292 1 0 1 1 0 0 +EDGE2 8742 3083 1.0055 -0.0901656 -0.0248788 1 0 1 1 0 0 +EDGE2 8742 3163 1.06648 -0.0838992 -0.0106663 1 0 1 1 0 0 +EDGE2 8742 5883 0.975882 -0.0262694 -0.0156595 1 0 1 1 0 0 +EDGE2 8742 3063 0.987421 -0.0592807 0.00488615 1 0 1 1 0 0 +EDGE2 8742 8362 -0.0525859 -0.00527315 -0.0157846 1 0 1 1 0 0 +EDGE2 8742 8422 -0.0813057 -0.0514819 -0.00961306 1 0 1 1 0 0 +EDGE2 8742 8482 -0.0442145 -0.00355591 -0.00217014 1 0 1 1 0 0 +EDGE2 8742 8622 0.03849 -0.0136688 0.0123003 1 0 1 1 0 0 +EDGE2 8742 8382 0.035918 0.0300385 0.0174009 1 0 1 1 0 0 +EDGE2 8742 3082 0.0119923 0.0696122 0.00565882 1 0 1 1 0 0 +EDGE2 8742 3162 -0.000757423 -0.03378 -0.0232115 1 0 1 1 0 0 +EDGE2 8742 5882 0.0624895 0.086619 -0.0254008 1 0 1 1 0 0 +EDGE2 8742 3062 0.0527639 -0.0249519 0.0145855 1 0 1 1 0 0 +EDGE2 8742 8361 -1.0191 0.0213621 -0.0264759 1 0 1 1 0 0 +EDGE2 8742 8421 -0.961195 -0.0482118 -0.0177609 1 0 1 1 0 0 +EDGE2 8742 8481 -0.966502 -0.0241072 -0.000185369 1 0 1 1 0 0 +EDGE2 8742 8621 -0.991888 -0.0484341 0.0104738 1 0 1 1 0 0 +EDGE2 8742 8381 -0.999772 0.00861795 -0.000862973 1 0 1 1 0 0 +EDGE2 8742 3081 -0.960494 -0.0677801 0.00136306 1 0 1 1 0 0 +EDGE2 8742 3161 -0.979552 0.0518323 -0.00747348 1 0 1 1 0 0 +EDGE2 8742 5881 -0.985162 -0.0878261 0.0119656 1 0 1 1 0 0 +EDGE2 8742 3061 -1.0512 -0.0110934 -0.0152284 1 0 1 1 0 0 +EDGE2 8743 3064 1.00786 -0.0321905 0.0154591 1 0 1 1 0 0 +EDGE2 8743 8384 1.01847 0.0629925 -0.0187356 1 0 1 1 0 0 +EDGE2 8743 8484 1.01698 0.0547266 0.0271996 1 0 1 1 0 0 +EDGE2 8743 8624 0.991841 0.0356187 0.0141688 1 0 1 1 0 0 +EDGE2 8743 8424 0.98696 0.0514051 0.0164342 1 0 1 1 0 0 +EDGE2 8743 3164 0.953133 0.0529792 0.00761959 1 0 1 1 0 0 +EDGE2 8743 5884 0.903082 -0.0237696 0.0198994 1 0 1 1 0 0 +EDGE2 8743 8364 0.986591 -0.0960873 0.0058979 1 0 1 1 0 0 +EDGE2 8743 3084 0.975017 -0.0196839 0.0236383 1 0 1 1 0 0 +EDGE2 8743 8742 -1.01491 -0.0447194 -0.0143027 1 0 1 1 0 0 +EDGE2 8743 8363 -0.0626094 0.0282895 0.00320595 1 0 1 1 0 0 +EDGE2 8743 8423 0.00286867 -0.0119299 0.0143648 1 0 1 1 0 0 +EDGE2 8743 8483 -0.0400886 0.00311025 -0.0204763 1 0 1 1 0 0 +EDGE2 8743 8623 0.102806 0.0663935 0.0225197 1 0 1 1 0 0 +EDGE2 8743 8383 -0.0702112 -0.0364548 -0.00658716 1 0 1 1 0 0 +EDGE2 8743 3083 0.0288739 -0.0342616 -0.0117412 1 0 1 1 0 0 +EDGE2 8743 3163 -0.00923501 -0.0431358 -0.0220247 1 0 1 1 0 0 +EDGE2 8743 5883 -0.0426812 -0.0318725 0.0362809 1 0 1 1 0 0 +EDGE2 8743 3063 0.0455673 0.0394244 -0.023343 1 0 1 1 0 0 +EDGE2 8743 8362 -1.07344 0.0502664 -0.00202237 1 0 1 1 0 0 +EDGE2 8743 8422 -0.999722 0.0380697 0.0230339 1 0 1 1 0 0 +EDGE2 8743 8482 -0.867939 -0.0558973 0.0243802 1 0 1 1 0 0 +EDGE2 8743 8622 -0.918447 0.0507365 0.0141837 1 0 1 1 0 0 +EDGE2 8743 8382 -0.968597 -0.0569394 0.00364205 1 0 1 1 0 0 +EDGE2 8743 3082 -0.995537 -0.0527006 -0.00588798 1 0 1 1 0 0 +EDGE2 8743 3162 -1.0257 0.0525229 -0.0244943 1 0 1 1 0 0 +EDGE2 8743 5882 -1.05191 0.0244166 0.00420392 1 0 1 1 0 0 +EDGE2 8743 3062 -1.02011 -0.0804022 0.00865553 1 0 1 1 0 0 +EDGE2 8744 8385 1.0356 -0.0188069 0.0118497 1 0 1 1 0 0 +EDGE2 8744 8485 0.941464 -0.0106402 -0.00699917 1 0 1 1 0 0 +EDGE2 8744 8625 1.01153 -0.0615191 -0.0166065 1 0 1 1 0 0 +EDGE2 8744 8425 1.0194 -0.0179664 0.0227132 1 0 1 1 0 0 +EDGE2 8744 3105 1.0357 -0.107152 -3.16334 1 0 1 1 0 0 +EDGE2 8744 3485 0.958589 -0.0847553 -3.12413 1 0 1 1 0 0 +EDGE2 8744 5845 1.06015 0.0438324 -3.16111 1 0 1 1 0 0 +EDGE2 8744 5885 1.02175 0.0434209 -0.00629731 1 0 1 1 0 0 +EDGE2 8744 8365 0.933276 -0.0589134 0.00358418 1 0 1 1 0 0 +EDGE2 8744 5825 1.0116 0.0139352 -3.15832 1 0 1 1 0 0 +EDGE2 8744 3145 0.950202 0.138085 -3.14496 1 0 1 1 0 0 +EDGE2 8744 3165 1.03962 -0.0409128 -0.0065882 1 0 1 1 0 0 +EDGE2 8744 3385 1.07316 0.034492 -3.14127 1 0 1 1 0 0 +EDGE2 8744 3125 0.976179 -0.0267719 -3.17881 1 0 1 1 0 0 +EDGE2 8744 1185 1.00997 -0.0772791 -3.15459 1 0 1 1 0 0 +EDGE2 8744 3065 0.983187 0.0513126 -0.0245023 1 0 1 1 0 0 +EDGE2 8744 3085 1.04418 0.0243759 -0.0131543 1 0 1 1 0 0 +EDGE2 8744 1165 1.04742 0.0351461 -3.13183 1 0 1 1 0 0 +EDGE2 8744 8743 -1.06604 0.0223763 -0.0297007 1 0 1 1 0 0 +EDGE2 8744 3064 -0.0877465 -0.0265566 0.0195937 1 0 1 1 0 0 +EDGE2 8744 8384 -0.0153545 -0.00232462 0.00497111 1 0 1 1 0 0 +EDGE2 8744 8484 -0.0636118 0.0804277 -0.000828672 1 0 1 1 0 0 +EDGE2 8744 8624 0.000711907 0.0651919 -0.00661343 1 0 1 1 0 0 +EDGE2 8744 8424 0.0285662 0.0746757 -0.01992 1 0 1 1 0 0 +EDGE2 8744 3164 0.0136518 0.130745 -0.0547967 1 0 1 1 0 0 +EDGE2 8744 5884 0.00481613 -0.0472794 0.0157073 1 0 1 1 0 0 +EDGE2 8744 8364 0.00315874 0.0241652 0.0151656 1 0 1 1 0 0 +EDGE2 8744 3084 0.0136552 -0.0169273 0.0189426 1 0 1 1 0 0 +EDGE2 8744 8363 -0.979975 -0.0576515 -0.0188475 1 0 1 1 0 0 +EDGE2 8744 8423 -1.01644 0.0451399 0.0360131 1 0 1 1 0 0 +EDGE2 8744 8483 -0.969875 0.0606719 0.0244752 1 0 1 1 0 0 +EDGE2 8744 8623 -1.0829 0.0236286 -0.00271498 1 0 1 1 0 0 +EDGE2 8744 8383 -0.9667 -0.00904538 -0.0242453 1 0 1 1 0 0 +EDGE2 8744 3083 -0.953977 0.00652073 0.0134821 1 0 1 1 0 0 +EDGE2 8744 3163 -1.08866 -0.0513736 -0.00628555 1 0 1 1 0 0 +EDGE2 8744 5883 -0.89996 0.0606134 0.0132137 1 0 1 1 0 0 +EDGE2 8744 3063 -0.974999 -0.0625425 -0.0301307 1 0 1 1 0 0 +EDGE2 8745 8385 -0.113058 -0.00395999 0.0337753 1 0 1 1 0 0 +EDGE2 8745 8366 0.0345197 1.00416 1.54871 1 0 1 1 0 0 +EDGE2 8745 8626 0.0667811 0.994721 1.57925 1 0 1 1 0 0 +EDGE2 8745 8426 -0.0361337 1.00751 1.59042 1 0 1 1 0 0 +EDGE2 8745 3146 0.0498715 1.06614 1.53913 1 0 1 1 0 0 +EDGE2 8745 3386 -0.0787121 1.01248 1.58632 1 0 1 1 0 0 +EDGE2 8745 5886 0.00534954 1.01941 1.54952 1 0 1 1 0 0 +EDGE2 8745 3066 0.124692 0.919241 1.55875 1 0 1 1 0 0 +EDGE2 8745 3144 0.971758 0.0270995 -3.14032 1 0 1 1 0 0 +EDGE2 8745 3484 1.00851 -0.0259846 -3.16209 1 0 1 1 0 0 +EDGE2 8745 5824 0.971268 0.00285359 -3.13366 1 0 1 1 0 0 +EDGE2 8745 5844 0.968123 0.0322823 -3.12068 1 0 1 1 0 0 +EDGE2 8745 3384 0.880284 -0.00222594 -3.11033 1 0 1 1 0 0 +EDGE2 8745 1184 0.867194 0.0191072 -3.17262 1 0 1 1 0 0 +EDGE2 8745 3104 0.953079 -0.0100987 -3.15268 1 0 1 1 0 0 +EDGE2 8745 3124 1.01938 -0.0154905 -3.13321 1 0 1 1 0 0 +EDGE2 8745 1164 0.997084 -0.0849864 -3.14574 1 0 1 1 0 0 +EDGE2 8745 8485 -0.0528364 -0.0329783 0.000804652 1 0 1 1 0 0 +EDGE2 8745 8625 -0.029074 -0.0221557 -0.0265291 1 0 1 1 0 0 +EDGE2 8745 8425 -0.0433092 0.00664874 0.0301603 1 0 1 1 0 0 +EDGE2 8745 3166 0.0310812 -0.883037 -1.59801 1 0 1 1 0 0 +EDGE2 8745 3105 -0.151735 -0.0207315 -3.16537 1 0 1 1 0 0 +EDGE2 8745 3485 -0.0340025 -0.00577503 -3.1436 1 0 1 1 0 0 +EDGE2 8745 5845 -0.00661164 -0.0456449 -3.13744 1 0 1 1 0 0 +EDGE2 8745 5885 0.0893246 -0.0721372 0.023986 1 0 1 1 0 0 +EDGE2 8745 8365 -0.0849936 -0.0193452 0.0102503 1 0 1 1 0 0 +EDGE2 8745 5825 0.037844 0.0148368 -3.12573 1 0 1 1 0 0 +EDGE2 8745 3145 0.128484 -0.0962025 -3.12585 1 0 1 1 0 0 +EDGE2 8745 3165 0.027872 -0.103066 0.022317 1 0 1 1 0 0 +EDGE2 8745 3385 -0.00457297 0.0101977 -3.1126 1 0 1 1 0 0 +EDGE2 8745 3125 0.084385 -0.0394885 -3.11888 1 0 1 1 0 0 +EDGE2 8745 8486 -0.0348698 -1.01947 -1.58312 1 0 1 1 0 0 +EDGE2 8745 1185 -0.0706992 0.00227762 -3.16561 1 0 1 1 0 0 +EDGE2 8745 3065 -0.017249 0.127684 0.0118932 1 0 1 1 0 0 +EDGE2 8745 3085 -0.0998856 0.00397208 -0.00526737 1 0 1 1 0 0 +EDGE2 8745 1165 0.0674698 -0.0133774 -3.12622 1 0 1 1 0 0 +EDGE2 8745 5826 0.0196793 -1.00659 -1.58436 1 0 1 1 0 0 +EDGE2 8745 5846 -0.0360836 -0.950666 -1.5612 1 0 1 1 0 0 +EDGE2 8745 8386 0.021521 -0.963809 -1.56249 1 0 1 1 0 0 +EDGE2 8745 3486 -0.0561439 -1.05905 -1.58277 1 0 1 1 0 0 +EDGE2 8745 1166 0.0281029 -0.962333 -1.57491 1 0 1 1 0 0 +EDGE2 8745 3086 0.0235506 -0.963205 -1.55015 1 0 1 1 0 0 +EDGE2 8745 3106 -0.00452614 -0.992098 -1.58749 1 0 1 1 0 0 +EDGE2 8745 3126 0.0612801 -0.973702 -1.55934 1 0 1 1 0 0 +EDGE2 8745 1186 -0.000864608 -1.10378 -1.5749 1 0 1 1 0 0 +EDGE2 8745 3064 -0.968663 0.0200908 -0.0277433 1 0 1 1 0 0 +EDGE2 8745 8384 -1.03579 0.010321 0.0224326 1 0 1 1 0 0 +EDGE2 8745 8484 -0.967589 0.0477636 0.00811149 1 0 1 1 0 0 +EDGE2 8745 8624 -1.06528 -0.0490093 -0.0253453 1 0 1 1 0 0 +EDGE2 8745 8744 -1.10093 -0.0428931 0.00710344 1 0 1 1 0 0 +EDGE2 8745 8424 -0.974863 0.0467544 -0.0219225 1 0 1 1 0 0 +EDGE2 8745 3164 -1.01181 0.123375 -0.0230768 1 0 1 1 0 0 +EDGE2 8745 5884 -1.05 0.0687689 -0.00510288 1 0 1 1 0 0 +EDGE2 8745 8364 -0.947058 0.0241819 0.0101846 1 0 1 1 0 0 +EDGE2 8745 3084 -1.06495 0.0685237 0.0144331 1 0 1 1 0 0 +EDGE2 8746 8385 -1.03417 0.0502338 -1.55425 1 0 1 1 0 0 +EDGE2 8746 8366 -0.0331994 -0.0344298 -0.0167194 1 0 1 1 0 0 +EDGE2 8746 8627 1.04368 0.0542513 0.0128638 1 0 1 1 0 0 +EDGE2 8746 3147 0.979648 0.0150722 -0.0125737 1 0 1 1 0 0 +EDGE2 8746 5887 0.995282 -0.0607003 0.0279779 1 0 1 1 0 0 +EDGE2 8746 8367 0.992213 -0.035235 0.0207846 1 0 1 1 0 0 +EDGE2 8746 8427 1.11577 0.0529408 -0.00560991 1 0 1 1 0 0 +EDGE2 8746 3387 1.01229 0.00299899 -0.0128123 1 0 1 1 0 0 +EDGE2 8746 8626 -0.104671 0.050484 -0.0406385 1 0 1 1 0 0 +EDGE2 8746 3067 1.04186 0.0251245 -0.012686 1 0 1 1 0 0 +EDGE2 8746 8426 0.043766 -0.0423469 0.00101307 1 0 1 1 0 0 +EDGE2 8746 3146 0.0189216 0.0968951 0.01667 1 0 1 1 0 0 +EDGE2 8746 3386 -0.0382292 0.0306686 2.70869e-05 1 0 1 1 0 0 +EDGE2 8746 5886 0.0762492 -0.0245333 -0.0180903 1 0 1 1 0 0 +EDGE2 8746 3066 -0.00985041 0.0167968 0.00851456 1 0 1 1 0 0 +EDGE2 8746 8745 -1.02183 -0.000947744 -1.58184 1 0 1 1 0 0 +EDGE2 8746 8485 -0.95553 0.0781946 -1.56085 1 0 1 1 0 0 +EDGE2 8746 8625 -1.03306 -0.0945544 -1.55471 1 0 1 1 0 0 +EDGE2 8746 8425 -0.999328 -0.0385095 -1.58723 1 0 1 1 0 0 +EDGE2 8746 3105 -0.994074 -0.0602395 1.55157 1 0 1 1 0 0 +EDGE2 8746 3485 -0.947836 -0.00471991 1.591 1 0 1 1 0 0 +EDGE2 8746 5845 -0.990199 0.0781805 1.60038 1 0 1 1 0 0 +EDGE2 8746 5885 -0.974747 -0.100297 -1.55101 1 0 1 1 0 0 +EDGE2 8746 8365 -0.903847 0.0161184 -1.56837 1 0 1 1 0 0 +EDGE2 8746 5825 -1.08281 0.108588 1.57272 1 0 1 1 0 0 +EDGE2 8746 3145 -1.01025 -0.0202279 1.6007 1 0 1 1 0 0 +EDGE2 8746 3165 -0.912883 -0.00191336 -1.54985 1 0 1 1 0 0 +EDGE2 8746 3385 -0.988953 -0.0696106 1.54968 1 0 1 1 0 0 +EDGE2 8746 3125 -0.955122 -0.0196993 1.57447 1 0 1 1 0 0 +EDGE2 8746 1185 -0.99917 -0.0101416 1.58567 1 0 1 1 0 0 +EDGE2 8746 3065 -1.10483 0.034097 -1.57071 1 0 1 1 0 0 +EDGE2 8746 3085 -0.992826 -0.00376433 -1.55982 1 0 1 1 0 0 +EDGE2 8746 1165 -0.969397 0.0487869 1.56498 1 0 1 1 0 0 +EDGE2 8747 8366 -1.03897 0.0868762 -0.0197752 1 0 1 1 0 0 +EDGE2 8747 8627 0.0574402 -0.0593805 -0.013833 1 0 1 1 0 0 +EDGE2 8747 5888 1.03567 -0.00269972 -0.0128829 1 0 1 1 0 0 +EDGE2 8747 8428 0.967853 -0.0381265 0.00239181 1 0 1 1 0 0 +EDGE2 8747 8628 0.996651 0.0220687 0.0127406 1 0 1 1 0 0 +EDGE2 8747 8368 1.01542 0.0411053 0.00265554 1 0 1 1 0 0 +EDGE2 8747 3068 1.01474 -0.0688631 -0.0102329 1 0 1 1 0 0 +EDGE2 8747 3148 1.00312 -0.0568947 0.000269944 1 0 1 1 0 0 +EDGE2 8747 3388 1.01787 0.0458185 0.0163154 1 0 1 1 0 0 +EDGE2 8747 3147 0.0442039 0.0697625 -0.000335001 1 0 1 1 0 0 +EDGE2 8747 5887 -0.0481997 0.0671458 -0.00649673 1 0 1 1 0 0 +EDGE2 8747 8367 -0.00689524 -0.00340441 0.0269969 1 0 1 1 0 0 +EDGE2 8747 8427 0.0131076 0.0421132 0.0107728 1 0 1 1 0 0 +EDGE2 8747 3387 -0.0294554 0.0713127 0.00850305 1 0 1 1 0 0 +EDGE2 8747 8626 -0.985016 0.0110652 -0.0108546 1 0 1 1 0 0 +EDGE2 8747 8746 -1.02257 0.0117285 -0.00463163 1 0 1 1 0 0 +EDGE2 8747 3067 0.00638412 -0.00627898 -0.0113758 1 0 1 1 0 0 +EDGE2 8747 8426 -1.05673 -0.0378694 -0.00250921 1 0 1 1 0 0 +EDGE2 8747 3146 -0.966233 -0.0219055 -0.0334391 1 0 1 1 0 0 +EDGE2 8747 3386 -1.03845 0.0168996 0.00209882 1 0 1 1 0 0 +EDGE2 8747 5886 -0.965459 0.0535937 -0.0306499 1 0 1 1 0 0 +EDGE2 8747 3066 -0.943881 0.0532982 0.0281819 1 0 1 1 0 0 +EDGE2 8748 5889 0.98429 0.0881427 -0.0550597 1 0 1 1 0 0 +EDGE2 8748 8429 1.00152 -0.0265489 -0.0137358 1 0 1 1 0 0 +EDGE2 8748 8629 0.994332 -0.0913149 0.016245 1 0 1 1 0 0 +EDGE2 8748 8369 1.03057 0.0379651 -0.0259549 1 0 1 1 0 0 +EDGE2 8748 3149 0.954631 0.0575454 -0.0245102 1 0 1 1 0 0 +EDGE2 8748 3389 0.995076 -0.03687 0.0227933 1 0 1 1 0 0 +EDGE2 8748 3069 0.967172 0.0133928 -0.0410118 1 0 1 1 0 0 +EDGE2 8748 8627 -1.0174 0.022316 0.010791 1 0 1 1 0 0 +EDGE2 8748 5888 -0.0534511 -0.0647777 0.00969024 1 0 1 1 0 0 +EDGE2 8748 8428 -0.00560048 -0.0595708 0.00257547 1 0 1 1 0 0 +EDGE2 8748 8628 0.00351087 0.0596897 0.0141068 1 0 1 1 0 0 +EDGE2 8748 8368 -0.0304327 0.0260681 -0.0297544 1 0 1 1 0 0 +EDGE2 8748 3068 -0.0323201 0.00811154 -0.0084432 1 0 1 1 0 0 +EDGE2 8748 3148 -0.00381808 -0.0325196 -0.038685 1 0 1 1 0 0 +EDGE2 8748 3388 0.0624639 -0.0396477 -0.00675369 1 0 1 1 0 0 +EDGE2 8748 8747 -1.09902 -0.0484298 0.0125597 1 0 1 1 0 0 +EDGE2 8748 3147 -0.962809 -0.0574332 -0.0362281 1 0 1 1 0 0 +EDGE2 8748 5887 -1.0114 0.0219893 -0.00126928 1 0 1 1 0 0 +EDGE2 8748 8367 -1.05052 -0.0101965 -0.0107877 1 0 1 1 0 0 +EDGE2 8748 8427 -0.983232 -0.0430329 -0.00126068 1 0 1 1 0 0 +EDGE2 8748 3387 -1.01864 0.0325631 0.0416222 1 0 1 1 0 0 +EDGE2 8748 3067 -0.943616 0.0583238 -0.0185721 1 0 1 1 0 0 +EDGE2 8749 8370 1.02786 -0.00684604 0.0411076 1 0 1 1 0 0 +EDGE2 8749 8470 1.00899 0.0141927 -3.13447 1 0 1 1 0 0 +EDGE2 8749 8610 1.1014 -0.174012 -3.14926 1 0 1 1 0 0 +EDGE2 8749 8630 0.946588 -0.0288562 0.0412781 1 0 1 1 0 0 +EDGE2 8749 8430 1.01825 0.00124591 -0.0176287 1 0 1 1 0 0 +EDGE2 8749 3070 1.0313 -0.10977 0.00813907 1 0 1 1 0 0 +EDGE2 8749 3390 1.00657 0.0467799 -0.0126935 1 0 1 1 0 0 +EDGE2 8749 3410 0.950234 -0.0127144 -3.13263 1 0 1 1 0 0 +EDGE2 8749 5890 1.00904 -0.0554674 -0.0132588 1 0 1 1 0 0 +EDGE2 8749 3150 0.981644 -0.0340394 -0.0169237 1 0 1 1 0 0 +EDGE2 8749 5889 0.0532168 -0.106964 -0.00129761 1 0 1 1 0 0 +EDGE2 8749 8429 -0.0114951 -0.0290234 -0.00261851 1 0 1 1 0 0 +EDGE2 8749 8629 -0.0235752 -0.0190707 -0.0246557 1 0 1 1 0 0 +EDGE2 8749 8369 -0.0768486 0.0590853 0.0522102 1 0 1 1 0 0 +EDGE2 8749 3149 0.0343309 -0.021226 -0.0050993 1 0 1 1 0 0 +EDGE2 8749 3389 0.0439917 -0.0285385 0.00990864 1 0 1 1 0 0 +EDGE2 8749 3069 0.0272848 0.0248346 -0.0158668 1 0 1 1 0 0 +EDGE2 8749 5888 -1.02148 0.0825552 0.0433152 1 0 1 1 0 0 +EDGE2 8749 8428 -1.00892 -0.0534012 0.00793507 1 0 1 1 0 0 +EDGE2 8749 8628 -1.12634 0.0891451 -0.0014568 1 0 1 1 0 0 +EDGE2 8749 8748 -0.943463 0.0413117 -0.0256753 1 0 1 1 0 0 +EDGE2 8749 8368 -0.953332 -0.0896948 0.0472815 1 0 1 1 0 0 +EDGE2 8749 3068 -1.00677 0.0288513 -0.0248134 1 0 1 1 0 0 +EDGE2 8749 3148 -1.06083 0.051815 -0.0330018 1 0 1 1 0 0 +EDGE2 8749 3388 -1.02373 -0.110498 0.0122601 1 0 1 1 0 0 +EDGE2 8750 8469 1.00175 0.00758719 -3.14604 1 0 1 1 0 0 +EDGE2 8750 8609 0.960319 -0.0130702 -3.15498 1 0 1 1 0 0 +EDGE2 8750 3409 1.05491 0.0828218 -3.16077 1 0 1 1 0 0 +EDGE2 8750 8370 -0.0894173 0.106141 -0.0152319 1 0 1 1 0 0 +EDGE2 8750 3411 -0.0427898 -1.09986 -1.57018 1 0 1 1 0 0 +EDGE2 8750 5891 0.0178981 -0.94329 -1.55458 1 0 1 1 0 0 +EDGE2 8750 8431 0.077006 -0.915487 -1.56086 1 0 1 1 0 0 +EDGE2 8750 3391 0.062817 -1.05815 -1.60095 1 0 1 1 0 0 +EDGE2 8750 8470 -0.073493 -0.0160706 -3.15499 1 0 1 1 0 0 +EDGE2 8750 8610 -0.0463165 -0.015165 -3.1715 1 0 1 1 0 0 +EDGE2 8750 8630 -0.0489456 0.0281497 0.010184 1 0 1 1 0 0 +EDGE2 8750 8430 -0.00288997 -0.0106927 0.0176096 1 0 1 1 0 0 +EDGE2 8750 3070 0.0406423 -0.0463761 -0.0159862 1 0 1 1 0 0 +EDGE2 8750 3390 -0.0856796 0.0283797 -0.0202812 1 0 1 1 0 0 +EDGE2 8750 3410 0.0142747 -0.0489941 -3.12588 1 0 1 1 0 0 +EDGE2 8750 5890 -0.0376471 -0.0680999 0.000901731 1 0 1 1 0 0 +EDGE2 8750 3150 0.108574 0.0430627 -0.0190598 1 0 1 1 0 0 +EDGE2 8750 5889 -1.00793 0.0985815 0.0285911 1 0 1 1 0 0 +EDGE2 8750 8429 -0.990587 -0.0422057 -0.0285819 1 0 1 1 0 0 +EDGE2 8750 8629 -0.987909 0.0307454 0.0373161 1 0 1 1 0 0 +EDGE2 8750 8749 -1.00319 0.00511571 -0.00141566 1 0 1 1 0 0 +EDGE2 8750 8369 -0.972344 0.0057795 0.00561794 1 0 1 1 0 0 +EDGE2 8750 3149 -0.988745 -0.0245401 -0.00328785 1 0 1 1 0 0 +EDGE2 8750 3389 -1.0516 0.00149187 0.017314 1 0 1 1 0 0 +EDGE2 8750 3069 -0.952873 0.0670986 -0.0271435 1 0 1 1 0 0 +EDGE2 8750 8611 0.0454278 0.920909 1.55877 1 0 1 1 0 0 +EDGE2 8750 8631 -0.0164121 0.922409 1.59233 1 0 1 1 0 0 +EDGE2 8750 3151 0.00648961 0.924987 1.57994 1 0 1 1 0 0 +EDGE2 8750 8371 -0.0345043 0.974528 1.56453 1 0 1 1 0 0 +EDGE2 8750 8471 -0.0296785 0.984115 1.51756 1 0 1 1 0 0 +EDGE2 8750 3071 -0.0283554 0.989429 1.57452 1 0 1 1 0 0 +EDGE2 8751 8370 -0.990877 0.0121168 1.57949 1 0 1 1 0 0 +EDGE2 8751 3412 0.999005 -0.0134054 0.0208575 1 0 1 1 0 0 +EDGE2 8751 5892 1.06391 0.0551137 0.0167533 1 0 1 1 0 0 +EDGE2 8751 8432 1.04893 0.0457909 0.00795945 1 0 1 1 0 0 +EDGE2 8751 3392 0.891454 -0.0598954 0.0057801 1 0 1 1 0 0 +EDGE2 8751 8750 -1.05094 0.0757078 1.54309 1 0 1 1 0 0 +EDGE2 8751 3411 0.0159051 0.0137777 -0.00311331 1 0 1 1 0 0 +EDGE2 8751 5891 0.000864125 0.0182773 -0.0215017 1 0 1 1 0 0 +EDGE2 8751 8431 0.0466495 0.0493951 0.0179833 1 0 1 1 0 0 +EDGE2 8751 3391 0.00711354 -0.0731618 -0.0130372 1 0 1 1 0 0 +EDGE2 8751 8470 -1.00673 0.00262072 -1.58124 1 0 1 1 0 0 +EDGE2 8751 8610 -1.03065 0.0511529 -1.56764 1 0 1 1 0 0 +EDGE2 8751 8630 -0.979077 -0.0127526 1.53917 1 0 1 1 0 0 +EDGE2 8751 8430 -0.932903 -0.0218691 1.5541 1 0 1 1 0 0 +EDGE2 8751 3070 -1.04899 -0.0364538 1.56277 1 0 1 1 0 0 +EDGE2 8751 3390 -1.00694 -0.00277568 1.60124 1 0 1 1 0 0 +EDGE2 8751 3410 -0.982752 -0.0581779 -1.56619 1 0 1 1 0 0 +EDGE2 8751 5890 -1.00452 0.0238836 1.58766 1 0 1 1 0 0 +EDGE2 8751 3150 -1.03025 -0.00134315 1.56173 1 0 1 1 0 0 +EDGE2 8752 8751 -1.02572 0.0247064 0.00683846 1 0 1 1 0 0 +EDGE2 8752 3413 1.09909 -0.0214072 0.0111871 1 0 1 1 0 0 +EDGE2 8752 5893 0.971544 0.0300796 -0.0205499 1 0 1 1 0 0 +EDGE2 8752 8433 0.992686 0.0312781 -0.0119715 1 0 1 1 0 0 +EDGE2 8752 3393 0.994328 0.0638871 -0.0175794 1 0 1 1 0 0 +EDGE2 8752 3412 -0.0119768 0.000411927 0.0460244 1 0 1 1 0 0 +EDGE2 8752 5892 -0.144416 -0.0676023 -0.014277 1 0 1 1 0 0 +EDGE2 8752 8432 -0.0610242 -0.0325594 -0.00162012 1 0 1 1 0 0 +EDGE2 8752 3392 -0.000288306 -0.0269869 -0.00515667 1 0 1 1 0 0 +EDGE2 8752 3411 -0.915607 0.0228394 -0.038258 1 0 1 1 0 0 +EDGE2 8752 5891 -0.992941 0.0100393 0.00438708 1 0 1 1 0 0 +EDGE2 8752 8431 -0.98671 -0.0926857 0.0152626 1 0 1 1 0 0 +EDGE2 8752 3391 -0.925986 0.0281482 0.0305246 1 0 1 1 0 0 +EDGE2 8753 3414 0.990283 0.034605 0.0132379 1 0 1 1 0 0 +EDGE2 8753 5894 0.901876 -0.0654712 -0.00789672 1 0 1 1 0 0 +EDGE2 8753 8434 1.02658 -0.0101649 0.00308832 1 0 1 1 0 0 +EDGE2 8753 3394 1.05606 0.171946 -0.00706869 1 0 1 1 0 0 +EDGE2 8753 8752 -0.994768 -0.0142375 -0.00302066 1 0 1 1 0 0 +EDGE2 8753 3413 -0.00526298 -0.0398581 -0.0102251 1 0 1 1 0 0 +EDGE2 8753 5893 -0.0618638 -0.035622 -0.0106406 1 0 1 1 0 0 +EDGE2 8753 8433 -0.00831133 -0.00836817 0.0300195 1 0 1 1 0 0 +EDGE2 8753 3393 -0.00787988 -0.0352962 -0.0260054 1 0 1 1 0 0 +EDGE2 8753 3412 -1.02466 0.060138 -0.0175406 1 0 1 1 0 0 +EDGE2 8753 5892 -1.02977 0.0481385 -0.024129 1 0 1 1 0 0 +EDGE2 8753 8432 -0.997062 0.0532673 0.00228838 1 0 1 1 0 0 +EDGE2 8753 3392 -0.968438 0.0205496 0.00952311 1 0 1 1 0 0 +EDGE2 8754 3395 0.992587 -0.0261535 0.020798 1 0 1 1 0 0 +EDGE2 8754 8435 1.01543 -0.0492051 0.0184017 1 0 1 1 0 0 +EDGE2 8754 8595 1.05266 0.023746 -3.12264 1 0 1 1 0 0 +EDGE2 8754 3435 1.0536 -0.0279194 -3.14548 1 0 1 1 0 0 +EDGE2 8754 5895 0.934921 0.0216095 -0.0270705 1 0 1 1 0 0 +EDGE2 8754 3415 1.12323 -0.0424703 -0.0155376 1 0 1 1 0 0 +EDGE2 8754 8753 -0.977111 0.0284637 -0.00249909 1 0 1 1 0 0 +EDGE2 8754 855 0.957624 0.000173114 -3.14669 1 0 1 1 0 0 +EDGE2 8754 895 1.03102 -0.0146365 -3.1231 1 0 1 1 0 0 +EDGE2 8754 915 1.05044 -0.0279198 -3.1394 1 0 1 1 0 0 +EDGE2 8754 835 0.991277 -0.0990212 -3.17504 1 0 1 1 0 0 +EDGE2 8754 3414 -0.0501137 0.00714659 0.0199551 1 0 1 1 0 0 +EDGE2 8754 5894 -0.0687311 0.0177114 0.0225369 1 0 1 1 0 0 +EDGE2 8754 8434 -0.0362536 0.0627979 -0.0306116 1 0 1 1 0 0 +EDGE2 8754 3394 0.0585514 -0.0374976 0.0123488 1 0 1 1 0 0 +EDGE2 8754 3413 -0.952882 0.00727012 -0.0188377 1 0 1 1 0 0 +EDGE2 8754 5893 -1.07062 -0.0376823 -0.0320223 1 0 1 1 0 0 +EDGE2 8754 8433 -1.13926 0.0441389 -0.00819448 1 0 1 1 0 0 +EDGE2 8754 3393 -1.00977 0.0395584 0.0330785 1 0 1 1 0 0 +EDGE2 8755 3395 -0.0326994 -0.0360447 0.00539422 1 0 1 1 0 0 +EDGE2 8755 8596 0.00614568 0.938023 1.55901 1 0 1 1 0 0 +EDGE2 8755 3396 0.0052628 0.915769 1.54702 1 0 1 1 0 0 +EDGE2 8755 5896 -0.0703429 1.00075 1.59129 1 0 1 1 0 0 +EDGE2 8755 8436 0.0230864 0.962214 1.54533 1 0 1 1 0 0 +EDGE2 8755 916 0.0355261 1.01525 1.59945 1 0 1 1 0 0 +EDGE2 8755 3434 0.983052 0.024799 -3.13914 1 0 1 1 0 0 +EDGE2 8755 8594 1.03378 -0.0670796 -3.19963 1 0 1 1 0 0 +EDGE2 8755 894 1.01613 -0.116504 -3.1508 1 0 1 1 0 0 +EDGE2 8755 914 0.945657 -0.0357108 -3.14031 1 0 1 1 0 0 +EDGE2 8755 8435 -0.00135993 0.00605203 0.00288511 1 0 1 1 0 0 +EDGE2 8755 834 0.978834 -0.00538311 -3.11714 1 0 1 1 0 0 +EDGE2 8755 854 0.977813 0.0653807 -3.14806 1 0 1 1 0 0 +EDGE2 8755 8595 -0.000766045 -0.0169836 -3.12761 1 0 1 1 0 0 +EDGE2 8755 3435 0.018981 -0.00371776 -3.1356 1 0 1 1 0 0 +EDGE2 8755 5895 0.0276172 0.0139417 0.0262763 1 0 1 1 0 0 +EDGE2 8755 3415 -0.0187844 -0.0292682 -0.00119588 1 0 1 1 0 0 +EDGE2 8755 8754 -1.05498 0.00359241 -0.012227 1 0 1 1 0 0 +EDGE2 8755 855 0.0369637 0.0576828 -3.17143 1 0 1 1 0 0 +EDGE2 8755 895 -0.0484719 0.0384152 -3.14898 1 0 1 1 0 0 +EDGE2 8755 915 0.0212611 -0.0415347 -3.12539 1 0 1 1 0 0 +EDGE2 8755 835 0.0108416 -0.0468031 -3.12633 1 0 1 1 0 0 +EDGE2 8755 3414 -1.05598 0.013407 0.0286472 1 0 1 1 0 0 +EDGE2 8755 5894 -0.950604 -0.0322334 0.0179961 1 0 1 1 0 0 +EDGE2 8755 8434 -0.957338 0.0013278 0.000594918 1 0 1 1 0 0 +EDGE2 8755 3394 -0.917591 -0.0468153 0.0125106 1 0 1 1 0 0 +EDGE2 8755 3436 -0.0475867 -1.0088 -1.57719 1 0 1 1 0 0 +EDGE2 8755 856 0.0506369 -0.984711 -1.53982 1 0 1 1 0 0 +EDGE2 8755 896 0.0380968 -0.973654 -1.55156 1 0 1 1 0 0 +EDGE2 8755 3416 -0.0448634 -0.985907 -1.55961 1 0 1 1 0 0 +EDGE2 8755 836 0.0160953 -1.01864 -1.56371 1 0 1 1 0 0 +EDGE2 8756 3395 -0.994775 -0.0653151 -1.54553 1 0 1 1 0 0 +EDGE2 8756 8597 1.03139 0.0337132 0.0273075 1 0 1 1 0 0 +EDGE2 8756 8437 0.966671 0.0231774 0.0422126 1 0 1 1 0 0 +EDGE2 8756 8596 0.0319429 -0.0325863 -0.0164523 1 0 1 1 0 0 +EDGE2 8756 917 1.0381 0.00218241 -0.0193289 1 0 1 1 0 0 +EDGE2 8756 3397 1.03859 -0.113778 -0.00389793 1 0 1 1 0 0 +EDGE2 8756 5897 1.06843 0.0328478 0.019724 1 0 1 1 0 0 +EDGE2 8756 3396 -0.012756 0.0158557 -0.0436446 1 0 1 1 0 0 +EDGE2 8756 5896 0.0325908 0.00447224 0.00652677 1 0 1 1 0 0 +EDGE2 8756 8436 0.109724 -0.000997822 0.0256452 1 0 1 1 0 0 +EDGE2 8756 916 -0.00630218 0.0129192 -0.0237593 1 0 1 1 0 0 +EDGE2 8756 8435 -1.01167 -0.0138788 -1.53003 1 0 1 1 0 0 +EDGE2 8756 8755 -1.04664 -0.0124784 -1.56631 1 0 1 1 0 0 +EDGE2 8756 8595 -1.0665 0.0647208 1.58252 1 0 1 1 0 0 +EDGE2 8756 3435 -0.998022 0.00569056 1.57474 1 0 1 1 0 0 +EDGE2 8756 5895 -1.09032 -0.0283945 -1.56605 1 0 1 1 0 0 +EDGE2 8756 3415 -0.988659 -0.0509944 -1.53972 1 0 1 1 0 0 +EDGE2 8756 855 -0.968608 0.0236431 1.56307 1 0 1 1 0 0 +EDGE2 8756 895 -1.01266 -0.0572952 1.5753 1 0 1 1 0 0 +EDGE2 8756 915 -1.06 0.00536135 1.56651 1 0 1 1 0 0 +EDGE2 8756 835 -0.912268 0.00389724 1.56333 1 0 1 1 0 0 +EDGE2 8757 8597 -0.013213 -0.0205372 -0.0547786 1 0 1 1 0 0 +EDGE2 8757 8438 1.03014 0.0871044 -0.00785557 1 0 1 1 0 0 +EDGE2 8757 8598 0.991457 0.0025718 -0.0262078 1 0 1 1 0 0 +EDGE2 8757 918 0.925224 0.01906 0.0283842 1 0 1 1 0 0 +EDGE2 8757 3398 1.01705 -0.023827 0.0187235 1 0 1 1 0 0 +EDGE2 8757 5898 1.0732 -0.0145269 0.0279725 1 0 1 1 0 0 +EDGE2 8757 8437 -0.0188355 -0.0103067 -0.00527145 1 0 1 1 0 0 +EDGE2 8757 8596 -1.02371 0.0542372 0.00199717 1 0 1 1 0 0 +EDGE2 8757 917 -0.00360017 -0.0125759 0.0311176 1 0 1 1 0 0 +EDGE2 8757 3397 -0.0269394 -0.027182 -0.0127628 1 0 1 1 0 0 +EDGE2 8757 5897 0.0738976 0.0819677 0.024977 1 0 1 1 0 0 +EDGE2 8757 8756 -1.06236 0.109009 0.0201187 1 0 1 1 0 0 +EDGE2 8757 3396 -0.964384 0.0453933 -0.0233173 1 0 1 1 0 0 +EDGE2 8757 5896 -1.04214 -0.0086724 0.0391737 1 0 1 1 0 0 +EDGE2 8757 8436 -0.967894 -0.0452201 0.0281431 1 0 1 1 0 0 +EDGE2 8757 916 -0.942334 0.0806635 -0.00276533 1 0 1 1 0 0 +EDGE2 8758 8597 -1.00059 0.069218 -0.0170448 1 0 1 1 0 0 +EDGE2 8758 5899 0.986569 -0.032713 0.00147946 1 0 1 1 0 0 +EDGE2 8758 8439 0.959775 -0.075427 -0.00650809 1 0 1 1 0 0 +EDGE2 8758 8599 0.979979 0.00100298 0.00212361 1 0 1 1 0 0 +EDGE2 8758 8438 0.0323961 0.0921645 0.0174306 1 0 1 1 0 0 +EDGE2 8758 919 0.974968 -0.021762 0.0273986 1 0 1 1 0 0 +EDGE2 8758 3399 0.993602 0.0263682 0.00686395 1 0 1 1 0 0 +EDGE2 8758 8598 -0.0142417 0.00652419 -0.0142713 1 0 1 1 0 0 +EDGE2 8758 918 -0.0346273 -0.0494436 -0.0257312 1 0 1 1 0 0 +EDGE2 8758 3398 -0.00290932 0.019457 0.0190262 1 0 1 1 0 0 +EDGE2 8758 5898 -0.0487294 0.0236121 -0.0147264 1 0 1 1 0 0 +EDGE2 8758 8757 -0.949301 -0.0371494 0.00387902 1 0 1 1 0 0 +EDGE2 8758 8437 -1.01352 0.0714362 -0.00293349 1 0 1 1 0 0 +EDGE2 8758 917 -0.932028 -0.0988655 -0.017597 1 0 1 1 0 0 +EDGE2 8758 3397 -0.974048 -0.0376599 0.00807979 1 0 1 1 0 0 +EDGE2 8758 5897 -0.915664 0.0626672 -0.0322464 1 0 1 1 0 0 +EDGE2 8759 5900 1.00125 0.00928406 0.0250714 1 0 1 1 0 0 +EDGE2 8759 8600 0.97884 0.0401643 -0.00360505 1 0 1 1 0 0 +EDGE2 8759 8440 1.01575 0.0336907 0.0115984 1 0 1 1 0 0 +EDGE2 8759 920 1.06533 -0.0170188 -0.00908505 1 0 1 1 0 0 +EDGE2 8759 3400 0.995581 0.031975 0.0452082 1 0 1 1 0 0 +EDGE2 8759 680 1.03972 -0.0368764 -3.11048 1 0 1 1 0 0 +EDGE2 8759 5899 -0.0395321 -0.00459964 0.0190233 1 0 1 1 0 0 +EDGE2 8759 8439 -0.00635761 -0.0261679 0.0100415 1 0 1 1 0 0 +EDGE2 8759 8599 -0.0429761 0.0465718 0.0353693 1 0 1 1 0 0 +EDGE2 8759 8438 -1.00003 -0.0781063 0.0102729 1 0 1 1 0 0 +EDGE2 8759 8758 -0.887949 0.0432296 0.0094738 1 0 1 1 0 0 +EDGE2 8759 919 0.0453512 0.0735079 0.00221787 1 0 1 1 0 0 +EDGE2 8759 3399 -0.0363036 -0.0213855 0.0180162 1 0 1 1 0 0 +EDGE2 8759 8598 -0.93102 -0.111608 -0.00894173 1 0 1 1 0 0 +EDGE2 8759 918 -1.05491 0.0249408 0.0192274 1 0 1 1 0 0 +EDGE2 8759 3398 -0.967525 -0.0470028 -0.0130193 1 0 1 1 0 0 +EDGE2 8759 5898 -0.954762 0.0235373 0.012806 1 0 1 1 0 0 +EDGE2 8760 921 0.029951 0.973767 1.57873 1 0 1 1 0 0 +EDGE2 8760 679 0.982562 0.00510649 -3.14957 1 0 1 1 0 0 +EDGE2 8760 681 -0.0569578 -0.976402 -1.56835 1 0 1 1 0 0 +EDGE2 8760 5901 -0.0788644 -1.03251 -1.58466 1 0 1 1 0 0 +EDGE2 8760 5900 -0.0145933 0.0027746 -0.0134484 1 0 1 1 0 0 +EDGE2 8760 8600 -0.0771517 -0.0337136 -0.0044282 1 0 1 1 0 0 +EDGE2 8760 8440 -0.0246703 0.00680106 -0.0148908 1 0 1 1 0 0 +EDGE2 8760 920 -0.0388367 -0.0332352 -0.0218057 1 0 1 1 0 0 +EDGE2 8760 3400 -0.0642562 0.0569877 0.00525305 1 0 1 1 0 0 +EDGE2 8760 680 0.00945497 0.0664316 -3.12162 1 0 1 1 0 0 +EDGE2 8760 8441 -0.0194332 1.04587 1.58039 1 0 1 1 0 0 +EDGE2 8760 8601 0.0185029 1.05774 1.55448 1 0 1 1 0 0 +EDGE2 8760 3401 0.0649459 1.10459 1.55866 1 0 1 1 0 0 +EDGE2 8760 5899 -1.02494 -0.0266521 0.0187502 1 0 1 1 0 0 +EDGE2 8760 8439 -1.12334 -0.0184494 0.0233565 1 0 1 1 0 0 +EDGE2 8760 8759 -0.9815 0.0311081 -0.000872428 1 0 1 1 0 0 +EDGE2 8760 8599 -0.979437 -0.0313199 0.0303868 1 0 1 1 0 0 +EDGE2 8760 919 -0.949844 -0.0705041 -0.0130987 1 0 1 1 0 0 +EDGE2 8760 3399 -0.99717 0.0250246 0.00500722 1 0 1 1 0 0 +EDGE2 8761 681 0.0624124 -0.0144335 -0.0132755 1 0 1 1 0 0 +EDGE2 8761 5902 1.00957 0.00678744 -0.015243 1 0 1 1 0 0 +EDGE2 8761 682 0.994275 0.111609 0.00504329 1 0 1 1 0 0 +EDGE2 8761 5901 0.0248026 0.0140815 0.0265024 1 0 1 1 0 0 +EDGE2 8761 5900 -0.991059 -0.00307389 1.55117 1 0 1 1 0 0 +EDGE2 8761 8600 -0.914388 0.0670404 1.5503 1 0 1 1 0 0 +EDGE2 8761 8760 -0.988155 0.0513703 1.56026 1 0 1 1 0 0 +EDGE2 8761 8440 -1.03007 -0.0648208 1.54324 1 0 1 1 0 0 +EDGE2 8761 920 -1.07434 -0.0116714 1.58061 1 0 1 1 0 0 +EDGE2 8761 3400 -0.958245 0.00205826 1.56582 1 0 1 1 0 0 +EDGE2 8761 680 -1.08801 0.0167638 -1.57714 1 0 1 1 0 0 +EDGE2 8762 681 -0.912356 0.00948011 -0.00933489 1 0 1 1 0 0 +EDGE2 8762 5902 -0.0163623 -0.0326818 -0.0135145 1 0 1 1 0 0 +EDGE2 8762 683 1.01836 0.0754369 0.0183523 1 0 1 1 0 0 +EDGE2 8762 5903 0.955129 0.0833787 0.00529101 1 0 1 1 0 0 +EDGE2 8762 8761 -0.993065 0.101881 0.0287386 1 0 1 1 0 0 +EDGE2 8762 682 -0.0103342 -0.050568 -0.0142876 1 0 1 1 0 0 +EDGE2 8762 5901 -1.02898 0.0781597 0.00977181 1 0 1 1 0 0 +EDGE2 8763 684 0.993988 0.0209741 0.0076115 1 0 1 1 0 0 +EDGE2 8763 5904 0.89256 0.00347708 0.00515641 1 0 1 1 0 0 +EDGE2 8763 5902 -1.08225 -0.0359952 -0.00381 1 0 1 1 0 0 +EDGE2 8763 683 -0.0743058 0.0277845 0.0106362 1 0 1 1 0 0 +EDGE2 8763 5903 -0.0665781 0.149623 0.0344098 1 0 1 1 0 0 +EDGE2 8763 8762 -1.05846 0.0161447 -0.0142497 1 0 1 1 0 0 +EDGE2 8763 682 -1.1178 -0.00175731 -0.00826346 1 0 1 1 0 0 +EDGE2 8764 5945 0.835438 0.0200776 -3.13087 1 0 1 1 0 0 +EDGE2 8764 5985 0.968093 -0.0483643 -3.102 1 0 1 1 0 0 +EDGE2 8764 5965 1.09413 0.0393837 -3.14964 1 0 1 1 0 0 +EDGE2 8764 5905 1.02142 0.0280493 -0.0159743 1 0 1 1 0 0 +EDGE2 8764 8763 -0.943902 0.0253442 0.00887254 1 0 1 1 0 0 +EDGE2 8764 885 0.991542 0.0487327 -3.13634 1 0 1 1 0 0 +EDGE2 8764 685 0.956324 0.0815397 -0.00340746 1 0 1 1 0 0 +EDGE2 8764 684 -0.0430821 0.0197307 0.000277863 1 0 1 1 0 0 +EDGE2 8764 5904 -0.0258542 -0.0441979 -0.00334199 1 0 1 1 0 0 +EDGE2 8764 683 -0.897461 0.025616 0.00389393 1 0 1 1 0 0 +EDGE2 8764 5903 -1.00242 0.0253778 0.0172234 1 0 1 1 0 0 +EDGE2 8765 884 1.05965 -0.0068907 -3.12215 1 0 1 1 0 0 +EDGE2 8765 5906 0.053437 1.04009 1.55805 1 0 1 1 0 0 +EDGE2 8765 5964 1.03833 0.0811869 -3.12156 1 0 1 1 0 0 +EDGE2 8765 5984 1.06085 0.00772498 -3.14195 1 0 1 1 0 0 +EDGE2 8765 5944 1.06641 -0.0229499 -3.13303 1 0 1 1 0 0 +EDGE2 8765 5946 -0.047408 -1.04662 -1.54995 1 0 1 1 0 0 +EDGE2 8765 5945 0.0439846 0.00735034 -3.15598 1 0 1 1 0 0 +EDGE2 8765 5985 0.0451924 -0.0349684 -3.13186 1 0 1 1 0 0 +EDGE2 8765 5965 0.0391377 0.0349922 -3.14586 1 0 1 1 0 0 +EDGE2 8765 5966 0.0880209 -1.0905 -1.56081 1 0 1 1 0 0 +EDGE2 8765 5986 -0.00354247 -0.9526 -1.57315 1 0 1 1 0 0 +EDGE2 8765 5905 0.0247548 0.0188074 -0.00120372 1 0 1 1 0 0 +EDGE2 8765 885 -0.0546122 -0.0173797 -3.15689 1 0 1 1 0 0 +EDGE2 8765 685 -0.00827896 -0.00563724 -0.0188035 1 0 1 1 0 0 +EDGE2 8765 684 -0.993976 0.10094 -0.00640918 1 0 1 1 0 0 +EDGE2 8765 5904 -1.00739 0.0344699 0.0348575 1 0 1 1 0 0 +EDGE2 8765 8764 -1.01301 0.0259644 0.0220447 1 0 1 1 0 0 +EDGE2 8765 686 0.00212059 -1.04785 -1.57179 1 0 1 1 0 0 +EDGE2 8765 886 0.062528 -1.02193 -1.58516 1 0 1 1 0 0 +EDGE2 8766 5906 -0.0429469 -0.0832892 0.0290837 1 0 1 1 0 0 +EDGE2 8766 5907 0.91864 0.0428946 0.00548904 1 0 1 1 0 0 +EDGE2 8766 5945 -1.05982 0.00320544 1.5816 1 0 1 1 0 0 +EDGE2 8766 5985 -1.02449 -0.022048 1.60252 1 0 1 1 0 0 +EDGE2 8766 8765 -0.978968 0.0130983 -1.55813 1 0 1 1 0 0 +EDGE2 8766 5965 -0.947257 -0.0180525 1.51902 1 0 1 1 0 0 +EDGE2 8766 5905 -0.941171 -0.0112192 -1.57846 1 0 1 1 0 0 +EDGE2 8766 885 -1.04372 0.00855803 1.60363 1 0 1 1 0 0 +EDGE2 8766 685 -1.01804 -0.021434 -1.56005 1 0 1 1 0 0 +EDGE2 8767 5908 1.02147 0.0587131 0.00643883 1 0 1 1 0 0 +EDGE2 8767 5906 -1.03754 -0.124672 -0.025457 1 0 1 1 0 0 +EDGE2 8767 5907 -0.0186062 -0.0379534 0.027272 1 0 1 1 0 0 +EDGE2 8767 8766 -1.09433 0.07166 0.0161014 1 0 1 1 0 0 +EDGE2 8768 5909 1.02277 0.0852402 -0.00411909 1 0 1 1 0 0 +EDGE2 8768 5908 0.000931185 0.0409152 -0.0262546 1 0 1 1 0 0 +EDGE2 8768 5907 -1.11281 0.0451341 0.027016 1 0 1 1 0 0 +EDGE2 8768 8767 -1.02521 -0.0386632 0.034376 1 0 1 1 0 0 +EDGE2 8769 5910 0.974879 -0.0664878 0.0022901 1 0 1 1 0 0 +EDGE2 8769 5930 1.01651 0.0516122 -3.11351 1 0 1 1 0 0 +EDGE2 8769 8768 -1.00749 0.11021 -0.000447186 1 0 1 1 0 0 +EDGE2 8769 5909 -0.020569 0.02193 -0.0249205 1 0 1 1 0 0 +EDGE2 8769 5908 -0.970902 -0.023681 -0.0194031 1 0 1 1 0 0 +EDGE2 8770 5929 0.987833 0.0290399 -3.10313 1 0 1 1 0 0 +EDGE2 8770 5911 0.0328107 -1.02438 -1.56622 1 0 1 1 0 0 +EDGE2 8770 5931 -0.132496 -0.906363 -1.56726 1 0 1 1 0 0 +EDGE2 8770 8769 -1.03918 -0.0304844 0.0234707 1 0 1 1 0 0 +EDGE2 8770 5910 0.0205429 0.0397196 0.0167263 1 0 1 1 0 0 +EDGE2 8770 5930 -0.00235443 -0.0149752 -3.12031 1 0 1 1 0 0 +EDGE2 8770 5909 -0.981619 0.0767424 -0.0130205 1 0 1 1 0 0 +EDGE2 8771 5910 -0.900864 0.100463 -1.56134 1 0 1 1 0 0 +EDGE2 8771 5930 -1.01533 -0.0162373 1.54489 1 0 1 1 0 0 +EDGE2 8771 8770 -0.955002 0.0173406 -1.56362 1 0 1 1 0 0 +EDGE2 8772 8771 -0.997623 -0.0221775 0.0368363 1 0 1 1 0 0 +EDGE2 8773 8772 -0.989608 0.0496173 -0.0304556 1 0 1 1 0 0 +EDGE2 8774 8773 -0.931389 0.028125 0.0089132 1 0 1 1 0 0 +EDGE2 8774 675 0.980436 -0.0413077 -3.12635 1 0 1 1 0 0 +EDGE2 8775 8774 -1.05813 -0.00810717 -0.0109874 1 0 1 1 0 0 +EDGE2 8775 676 -0.0350486 1.01664 1.55984 1 0 1 1 0 0 +EDGE2 8775 675 0.003417 0.0129895 -3.15622 1 0 1 1 0 0 +EDGE2 8775 674 0.977069 0.0663511 -3.14078 1 0 1 1 0 0 +EDGE2 8776 8775 -1.02413 -0.0306016 -1.60195 1 0 1 1 0 0 +EDGE2 8776 677 0.95226 0.0442071 -0.00530904 1 0 1 1 0 0 +EDGE2 8776 676 0.0370758 0.0381829 0.00730045 1 0 1 1 0 0 +EDGE2 8776 675 -0.991057 -0.0179915 1.5623 1 0 1 1 0 0 +EDGE2 8777 677 0.0665266 0.0252071 -0.0282609 1 0 1 1 0 0 +EDGE2 8777 676 -0.958731 0.0104326 0.0276599 1 0 1 1 0 0 +EDGE2 8777 8776 -1.00178 -0.034693 0.0135393 1 0 1 1 0 0 +EDGE2 8777 678 1.04849 -0.0213965 0.0227348 1 0 1 1 0 0 +EDGE2 8778 677 -1.02636 -0.0655557 0.00793274 1 0 1 1 0 0 +EDGE2 8778 8777 -1.00595 -0.128698 -0.0245699 1 0 1 1 0 0 +EDGE2 8778 678 0.0511054 0.0139125 0.0112826 1 0 1 1 0 0 +EDGE2 8778 679 0.980662 -0.041849 -0.017994 1 0 1 1 0 0 +EDGE2 8779 678 -0.987094 -0.00490021 -0.00905138 1 0 1 1 0 0 +EDGE2 8779 8778 -0.942064 -0.0248184 -0.0226892 1 0 1 1 0 0 +EDGE2 8779 679 -0.0312091 -0.0528152 0.00260719 1 0 1 1 0 0 +EDGE2 8779 5900 1.02679 0.0443313 -3.14048 1 0 1 1 0 0 +EDGE2 8779 8600 0.94206 0.0111907 -3.17495 1 0 1 1 0 0 +EDGE2 8779 8760 0.996659 0.0392665 -3.1191 1 0 1 1 0 0 +EDGE2 8779 8440 1.0755 -0.0372526 -3.0949 1 0 1 1 0 0 +EDGE2 8779 920 0.978475 0.0347493 -3.11603 1 0 1 1 0 0 +EDGE2 8779 3400 0.933404 -0.00719539 -3.15015 1 0 1 1 0 0 +EDGE2 8779 680 0.961954 0.0514845 -0.00858513 1 0 1 1 0 0 +EDGE2 8780 921 -0.112203 -1.08237 -1.58979 1 0 1 1 0 0 +EDGE2 8780 8779 -0.956294 -0.0453944 -0.0186264 1 0 1 1 0 0 +EDGE2 8780 679 -0.98986 0.0488958 0.0327795 1 0 1 1 0 0 +EDGE2 8780 681 0.00509408 1.0751 1.56004 1 0 1 1 0 0 +EDGE2 8780 8761 -0.0743648 1.01501 1.59022 1 0 1 1 0 0 +EDGE2 8780 5901 -0.144636 1.08989 1.58764 1 0 1 1 0 0 +EDGE2 8780 5900 -0.0434599 0.157601 -3.15784 1 0 1 1 0 0 +EDGE2 8780 8600 0.0424898 -0.0385502 -3.147 1 0 1 1 0 0 +EDGE2 8780 8760 -0.0155053 -0.00393264 -3.14716 1 0 1 1 0 0 +EDGE2 8780 8440 -0.0378164 -0.0317718 -3.12727 1 0 1 1 0 0 +EDGE2 8780 920 0.0140799 -0.00388663 -3.15256 1 0 1 1 0 0 +EDGE2 8780 3400 -0.0675535 0.0153103 -3.13651 1 0 1 1 0 0 +EDGE2 8780 680 -0.0250525 0.120406 0.0217861 1 0 1 1 0 0 +EDGE2 8780 8441 0.0101312 -0.938691 -1.55561 1 0 1 1 0 0 +EDGE2 8780 8601 -0.0575269 -0.848828 -1.57762 1 0 1 1 0 0 +EDGE2 8780 3401 -0.0471603 -0.986566 -1.60055 1 0 1 1 0 0 +EDGE2 8780 5899 1.09656 0.0282806 -3.11763 1 0 1 1 0 0 +EDGE2 8780 8439 1.01985 -0.0125254 -3.16536 1 0 1 1 0 0 +EDGE2 8780 8759 1.00593 0.0557402 -3.17232 1 0 1 1 0 0 +EDGE2 8780 8599 1.03632 -0.0269818 -3.17561 1 0 1 1 0 0 +EDGE2 8780 919 1.10617 -0.0820653 -3.16417 1 0 1 1 0 0 +EDGE2 8780 3399 0.96216 0.00247188 -3.15167 1 0 1 1 0 0 +EDGE2 8781 681 0.0129085 -0.0669757 0.00446954 1 0 1 1 0 0 +EDGE2 8781 5902 1.03658 -0.0598778 0.0101037 1 0 1 1 0 0 +EDGE2 8781 8762 1.09243 0.082674 -0.0456452 1 0 1 1 0 0 +EDGE2 8781 8761 0.146078 0.00751155 0.0293689 1 0 1 1 0 0 +EDGE2 8781 682 1.01532 -0.0671405 0.0104581 1 0 1 1 0 0 +EDGE2 8781 5901 -0.0432664 0.00344238 0.0067704 1 0 1 1 0 0 +EDGE2 8781 5900 -0.991247 0.0288581 1.59792 1 0 1 1 0 0 +EDGE2 8781 8600 -1.08162 0.00278046 1.54332 1 0 1 1 0 0 +EDGE2 8781 8760 -0.944172 0.00070369 1.59968 1 0 1 1 0 0 +EDGE2 8781 8780 -1.0252 -0.0767149 -1.55145 1 0 1 1 0 0 +EDGE2 8781 8440 -1.01629 0.00411912 1.57417 1 0 1 1 0 0 +EDGE2 8781 920 -1.03173 -0.0387005 1.56318 1 0 1 1 0 0 +EDGE2 8781 3400 -0.926742 -0.0131461 1.55313 1 0 1 1 0 0 +EDGE2 8781 680 -1.09224 -0.0205541 -1.56561 1 0 1 1 0 0 +EDGE2 8782 8763 1.0594 -0.0240679 0.0116859 1 0 1 1 0 0 +EDGE2 8782 681 -1.02993 -0.00916981 -0.0325591 1 0 1 1 0 0 +EDGE2 8782 5902 -0.0533817 -0.0690613 0.0111007 1 0 1 1 0 0 +EDGE2 8782 683 1.04883 -0.0446807 0.00320192 1 0 1 1 0 0 +EDGE2 8782 5903 1.02473 -0.0219968 -0.0241514 1 0 1 1 0 0 +EDGE2 8782 8762 -0.0332895 0.0517873 -0.0324838 1 0 1 1 0 0 +EDGE2 8782 8761 -1.08102 0.0692114 0.0425367 1 0 1 1 0 0 +EDGE2 8782 8781 -0.983919 0.00129308 -0.0554639 1 0 1 1 0 0 +EDGE2 8782 682 -0.02036 -0.0354638 -0.00457814 1 0 1 1 0 0 +EDGE2 8782 5901 -1.03408 0.0889382 -0.0186439 1 0 1 1 0 0 +EDGE2 8783 8763 0.0489573 0.0205626 0.00726252 1 0 1 1 0 0 +EDGE2 8783 684 1.02917 -0.0597404 0.024381 1 0 1 1 0 0 +EDGE2 8783 5904 0.984908 0.0365414 -0.0115512 1 0 1 1 0 0 +EDGE2 8783 8764 1.08442 0.0513126 0.0138326 1 0 1 1 0 0 +EDGE2 8783 5902 -1.05729 0.0480865 0.0278733 1 0 1 1 0 0 +EDGE2 8783 8782 -0.980627 -0.076763 0.0173824 1 0 1 1 0 0 +EDGE2 8783 683 0.0404897 0.0691019 -0.0081292 1 0 1 1 0 0 +EDGE2 8783 5903 0.0243639 0.0130403 -0.0348644 1 0 1 1 0 0 +EDGE2 8783 8762 -0.947884 -0.0402587 0.0311897 1 0 1 1 0 0 +EDGE2 8783 682 -0.9279 0.052885 0.00382118 1 0 1 1 0 0 +EDGE2 8784 5945 0.914424 0.0420671 -3.11019 1 0 1 1 0 0 +EDGE2 8784 5985 0.959117 0.0278739 -3.14192 1 0 1 1 0 0 +EDGE2 8784 8765 0.987576 -0.111774 -0.0241114 1 0 1 1 0 0 +EDGE2 8784 5965 0.880057 -0.0227811 -3.11812 1 0 1 1 0 0 +EDGE2 8784 5905 1.02425 0.0117095 -0.00414061 1 0 1 1 0 0 +EDGE2 8784 8763 -0.955966 -0.0431423 -0.0123041 1 0 1 1 0 0 +EDGE2 8784 885 0.969739 -0.0257642 -3.14352 1 0 1 1 0 0 +EDGE2 8784 685 0.95653 0.0243779 0.00802156 1 0 1 1 0 0 +EDGE2 8784 684 -0.00996054 -0.0382554 -0.0308117 1 0 1 1 0 0 +EDGE2 8784 5904 0.032994 0.0179631 -0.0270623 1 0 1 1 0 0 +EDGE2 8784 8764 0.00188975 0.0573465 -0.00274156 1 0 1 1 0 0 +EDGE2 8784 8783 -0.951546 -0.0168487 0.0366982 1 0 1 1 0 0 +EDGE2 8784 683 -0.993042 0.0424315 0.0231411 1 0 1 1 0 0 +EDGE2 8784 5903 -1.03616 -0.133189 0.015007 1 0 1 1 0 0 +EDGE2 8785 884 0.921579 0.0688304 -3.14211 1 0 1 1 0 0 +EDGE2 8785 5906 -0.0116614 1.07443 1.57895 1 0 1 1 0 0 +EDGE2 8785 8766 -0.00276616 1.05439 1.60532 1 0 1 1 0 0 +EDGE2 8785 5964 1.0542 0.0491769 -3.11568 1 0 1 1 0 0 +EDGE2 8785 5984 1.05296 -0.0123729 -3.14971 1 0 1 1 0 0 +EDGE2 8785 5944 1.04429 0.0190562 -3.13681 1 0 1 1 0 0 +EDGE2 8785 5946 -0.0241421 -1.024 -1.52521 1 0 1 1 0 0 +EDGE2 8785 5945 -0.0237137 -0.0125332 -3.13918 1 0 1 1 0 0 +EDGE2 8785 5985 -0.0452402 0.0501527 -3.11313 1 0 1 1 0 0 +EDGE2 8785 8765 0.0151921 -0.0364053 0.0169417 1 0 1 1 0 0 +EDGE2 8785 5965 0.0243102 -0.0126892 -3.13623 1 0 1 1 0 0 +EDGE2 8785 5966 0.0661004 -1.03346 -1.55849 1 0 1 1 0 0 +EDGE2 8785 5986 0.0116197 -0.913698 -1.55572 1 0 1 1 0 0 +EDGE2 8785 5905 -0.132421 0.000678129 6.88421e-05 1 0 1 1 0 0 +EDGE2 8785 8784 -0.998375 0.0132009 0.00532053 1 0 1 1 0 0 +EDGE2 8785 885 0.0328452 -0.076037 -3.14343 1 0 1 1 0 0 +EDGE2 8785 685 0.085831 -0.0640011 0.0143237 1 0 1 1 0 0 +EDGE2 8785 684 -1.08511 -0.0165332 0.022196 1 0 1 1 0 0 +EDGE2 8785 5904 -1.1112 -0.0599736 0.0424237 1 0 1 1 0 0 +EDGE2 8785 8764 -0.944359 0.020682 -0.0135197 1 0 1 1 0 0 +EDGE2 8785 686 0.0595953 -0.940429 -1.61213 1 0 1 1 0 0 +EDGE2 8785 886 -0.0754361 -0.995565 -1.54688 1 0 1 1 0 0 +EDGE2 8786 5906 -0.0703486 -0.0551247 -0.0132544 1 0 1 1 0 0 +EDGE2 8786 5907 0.991665 0.0417315 0.0181582 1 0 1 1 0 0 +EDGE2 8786 8767 0.989993 0.0311863 -0.00664003 1 0 1 1 0 0 +EDGE2 8786 8766 0.0450058 0.0227443 0.0193568 1 0 1 1 0 0 +EDGE2 8786 5945 -0.933937 0.0814406 1.53483 1 0 1 1 0 0 +EDGE2 8786 5985 -1.0744 -0.070696 1.56919 1 0 1 1 0 0 +EDGE2 8786 8765 -1.04199 -0.0106392 -1.58287 1 0 1 1 0 0 +EDGE2 8786 8785 -1.00784 -0.0396708 -1.57021 1 0 1 1 0 0 +EDGE2 8786 5965 -0.929195 -0.0704046 1.58099 1 0 1 1 0 0 +EDGE2 8786 5905 -1.02286 0.000466025 -1.5653 1 0 1 1 0 0 +EDGE2 8786 885 -1.00537 -0.0829455 1.55324 1 0 1 1 0 0 +EDGE2 8786 685 -1.06009 -0.028926 -1.58507 1 0 1 1 0 0 +EDGE2 8787 8768 0.999059 0.0401614 0.032029 1 0 1 1 0 0 +EDGE2 8787 5908 0.987243 0.0862897 0.00458678 1 0 1 1 0 0 +EDGE2 8787 5906 -1.02252 -0.0414101 -0.0198021 1 0 1 1 0 0 +EDGE2 8787 8786 -1.03415 -0.0329855 0.00126521 1 0 1 1 0 0 +EDGE2 8787 5907 -0.0117515 0.00312266 -0.0278172 1 0 1 1 0 0 +EDGE2 8787 8767 0.0554077 -0.0507673 0.00832148 1 0 1 1 0 0 +EDGE2 8787 8766 -0.980283 -0.114306 0.0234464 1 0 1 1 0 0 +EDGE2 8788 8787 -0.934757 -0.0195121 0.00733391 1 0 1 1 0 0 +EDGE2 8788 8769 0.987883 0.0440865 -0.0448505 1 0 1 1 0 0 +EDGE2 8788 8768 0.034747 0.0807861 0.00989523 1 0 1 1 0 0 +EDGE2 8788 5909 0.941152 -0.0183798 -0.0251304 1 0 1 1 0 0 +EDGE2 8788 5908 0.0442955 0.0246086 0.00912649 1 0 1 1 0 0 +EDGE2 8788 5907 -0.993463 -0.0601837 -0.0335063 1 0 1 1 0 0 +EDGE2 8788 8767 -1.07942 -0.0255224 0.035125 1 0 1 1 0 0 +EDGE2 8789 8769 -0.0430438 0.0832867 0.0249378 1 0 1 1 0 0 +EDGE2 8789 5910 0.968576 0.026517 -0.03059 1 0 1 1 0 0 +EDGE2 8789 5930 1.0485 0.000395288 -3.13106 1 0 1 1 0 0 +EDGE2 8789 8770 1.04936 0.0625132 0.0221943 1 0 1 1 0 0 +EDGE2 8789 8768 -1.02146 0.0153455 0.0298045 1 0 1 1 0 0 +EDGE2 8789 8788 -0.958687 0.0490185 -0.0357132 1 0 1 1 0 0 +EDGE2 8789 5909 0.00944632 -0.127447 0.0247701 1 0 1 1 0 0 +EDGE2 8789 5908 -1.09887 0.000417813 -0.0168951 1 0 1 1 0 0 +EDGE2 8790 5929 0.980245 0.00784705 -3.11587 1 0 1 1 0 0 +EDGE2 8790 5911 -0.0305115 -0.980373 -1.56933 1 0 1 1 0 0 +EDGE2 8790 5931 -0.0172599 -1.10998 -1.55947 1 0 1 1 0 0 +EDGE2 8790 8769 -1.00251 0.100909 0.0122339 1 0 1 1 0 0 +EDGE2 8790 5910 0.10594 0.0198092 0.0149957 1 0 1 1 0 0 +EDGE2 8790 5930 0.0620225 0.0738922 -3.13105 1 0 1 1 0 0 +EDGE2 8790 8770 -0.0561361 0.009259 0.00152299 1 0 1 1 0 0 +EDGE2 8790 8789 -0.940268 -0.0321209 -0.0334635 1 0 1 1 0 0 +EDGE2 8790 5909 -0.962087 0.0194622 -0.000327561 1 0 1 1 0 0 +EDGE2 8790 8771 -0.0561959 0.942835 1.57676 1 0 1 1 0 0 +EDGE2 8791 8790 -0.981827 -0.0127976 -1.52483 1 0 1 1 0 0 +EDGE2 8791 5910 -0.992301 -0.000889374 -1.58482 1 0 1 1 0 0 +EDGE2 8791 5930 -1.10077 0.0147718 1.5932 1 0 1 1 0 0 +EDGE2 8791 8770 -1.01546 0.0318383 -1.56727 1 0 1 1 0 0 +EDGE2 8791 8771 -0.0463411 0.0803248 -0.0366914 1 0 1 1 0 0 +EDGE2 8791 8772 0.945226 0.0144746 -0.019015 1 0 1 1 0 0 +EDGE2 8792 8791 -0.962629 0.0224006 -0.0431985 1 0 1 1 0 0 +EDGE2 8792 8771 -0.876516 0.0924441 0.0120654 1 0 1 1 0 0 +EDGE2 8792 8773 0.986514 0.0408216 -0.0369407 1 0 1 1 0 0 +EDGE2 8792 8772 0.012498 -0.00806864 -0.00657171 1 0 1 1 0 0 +EDGE2 8793 8774 0.932898 0.00798118 0.00172274 1 0 1 1 0 0 +EDGE2 8793 8792 -0.974936 -0.00506497 0.0129389 1 0 1 1 0 0 +EDGE2 8793 8773 0.029986 -0.0375969 -0.0389764 1 0 1 1 0 0 +EDGE2 8793 8772 -0.951472 0.0135639 -0.00016691 1 0 1 1 0 0 +EDGE2 8794 8774 -0.0630356 -0.00217885 -0.0191199 1 0 1 1 0 0 +EDGE2 8794 8773 -1.0193 -0.0428607 -0.0141676 1 0 1 1 0 0 +EDGE2 8794 8793 -1.00215 0.0227885 -0.034428 1 0 1 1 0 0 +EDGE2 8794 8775 0.978306 0.0827321 -0.0111717 1 0 1 1 0 0 +EDGE2 8794 675 0.972401 -0.0281305 -3.12404 1 0 1 1 0 0 +EDGE2 8795 8774 -1.05963 -0.0956129 -0.0323959 1 0 1 1 0 0 +EDGE2 8795 8794 -1.00787 0.0264497 0.0267757 1 0 1 1 0 0 +EDGE2 8795 8775 0.0817271 0.111548 -0.0106444 1 0 1 1 0 0 +EDGE2 8795 676 0.0538677 0.940656 1.57644 1 0 1 1 0 0 +EDGE2 8795 8776 0.0240789 0.923297 1.56808 1 0 1 1 0 0 +EDGE2 8795 675 -0.0159891 -0.00631307 -3.11346 1 0 1 1 0 0 +EDGE2 8795 674 0.951124 -0.0150127 -3.10433 1 0 1 1 0 0 +EDGE2 8796 8775 -0.973114 -0.0894211 1.6049 1 0 1 1 0 0 +EDGE2 8796 8795 -0.990031 -0.0347554 1.54266 1 0 1 1 0 0 +EDGE2 8796 675 -0.995207 0.0237466 -1.59982 1 0 1 1 0 0 +EDGE2 8797 8796 -0.959509 -0.0598501 -0.00430242 1 0 1 1 0 0 +EDGE2 8798 8797 -0.958264 0.00822611 0.00135568 1 0 1 1 0 0 +EDGE2 8799 640 0.96048 0.0508928 -3.12853 1 0 1 1 0 0 +EDGE2 8799 660 1.02258 -0.0171846 -3.14955 1 0 1 1 0 0 +EDGE2 8799 8798 -0.932364 -0.0448232 -0.0306798 1 0 1 1 0 0 +EDGE2 8800 661 -0.00467918 0.932749 1.59807 1 0 1 1 0 0 +EDGE2 8800 639 0.892495 -0.0099259 -3.15999 1 0 1 1 0 0 +EDGE2 8800 659 1.07445 -0.000381946 -3.12417 1 0 1 1 0 0 +EDGE2 8800 641 -0.0369329 -1.01977 -1.54002 1 0 1 1 0 0 +EDGE2 8800 640 -0.00461585 0.00952965 -3.16282 1 0 1 1 0 0 +EDGE2 8800 660 -0.0077433 -0.108549 -3.15733 1 0 1 1 0 0 +EDGE2 8800 8799 -1.03853 0.031422 -0.00202238 1 0 1 1 0 0 +EDGE2 8801 661 0.00232528 0.063398 0.0358184 1 0 1 1 0 0 +EDGE2 8801 8800 -0.926321 0.0766208 -1.57977 1 0 1 1 0 0 +EDGE2 8801 640 -1.07001 0.0293327 1.56309 1 0 1 1 0 0 +EDGE2 8801 660 -0.960217 0.00896471 1.59538 1 0 1 1 0 0 +EDGE2 8801 662 0.94804 -0.0510754 0.0157534 1 0 1 1 0 0 +EDGE2 8802 661 -1.03068 0.0759005 0.029593 1 0 1 1 0 0 +EDGE2 8802 8801 -0.934708 0.0028857 0.0259337 1 0 1 1 0 0 +EDGE2 8802 662 0.0308669 0.0788753 -0.0344949 1 0 1 1 0 0 +EDGE2 8802 663 0.948882 -0.0715991 -0.0286746 1 0 1 1 0 0 +EDGE2 8803 662 -1.0249 -0.023588 0.00669181 1 0 1 1 0 0 +EDGE2 8803 8802 -1.00881 -0.0692195 -0.00928044 1 0 1 1 0 0 +EDGE2 8803 663 -0.049125 0.0378463 0.0128518 1 0 1 1 0 0 +EDGE2 8803 664 0.94725 -0.0374386 -0.0411124 1 0 1 1 0 0 +EDGE2 8804 8803 -1.04632 -0.00163147 -0.0318201 1 0 1 1 0 0 +EDGE2 8804 663 -0.972568 0.0148705 0.0124403 1 0 1 1 0 0 +EDGE2 8804 665 0.979078 0.137407 -0.0132673 1 0 1 1 0 0 +EDGE2 8804 664 -0.00443962 0.0415998 -0.00993633 1 0 1 1 0 0 +EDGE2 8805 666 -0.0145275 1.06073 1.58924 1 0 1 1 0 0 +EDGE2 8805 8804 -1.08797 0.0601047 0.014358 1 0 1 1 0 0 +EDGE2 8805 665 0.0193247 -0.0446192 -0.00788535 1 0 1 1 0 0 +EDGE2 8805 664 -1.05456 -0.0511747 0.0121454 1 0 1 1 0 0 +EDGE2 8806 666 -0.00954047 0.0360442 -0.0311443 1 0 1 1 0 0 +EDGE2 8806 665 -0.987853 0.0177677 -1.58096 1 0 1 1 0 0 +EDGE2 8806 8805 -0.940186 0.0736002 -1.61761 1 0 1 1 0 0 +EDGE2 8806 667 1.06556 -0.0189668 -0.0125608 1 0 1 1 0 0 +EDGE2 8807 668 1.03091 -0.0253324 -0.00651965 1 0 1 1 0 0 +EDGE2 8807 666 -1.04822 -0.0829303 0.00116024 1 0 1 1 0 0 +EDGE2 8807 8806 -1.095 -0.00715541 -0.017198 1 0 1 1 0 0 +EDGE2 8807 667 -0.0578461 0.0144616 -0.00295499 1 0 1 1 0 0 +EDGE2 8808 668 -0.035571 -0.087578 -0.00714556 1 0 1 1 0 0 +EDGE2 8808 667 -1.04242 -0.0240793 0.00980469 1 0 1 1 0 0 +EDGE2 8808 8807 -0.986157 -0.0810496 -0.00966734 1 0 1 1 0 0 +EDGE2 8808 669 0.972587 0.00258664 -0.0228378 1 0 1 1 0 0 +EDGE2 8809 668 -0.951965 0.0663023 -0.0298475 1 0 1 1 0 0 +EDGE2 8809 8808 -0.958327 -0.0348236 0.0305294 1 0 1 1 0 0 +EDGE2 8809 669 0.000435708 -0.0422887 -0.0106213 1 0 1 1 0 0 +EDGE2 8809 930 1.11673 0.0299692 -3.15288 1 0 1 1 0 0 +EDGE2 8809 8450 1.04864 0.00355668 -3.14653 1 0 1 1 0 0 +EDGE2 8809 670 0.974047 -0.0545859 -0.0182568 1 0 1 1 0 0 +EDGE2 8810 669 -1.05153 -0.0406363 0.021263 1 0 1 1 0 0 +EDGE2 8810 8809 -1.00785 -0.0482468 0.0059952 1 0 1 1 0 0 +EDGE2 8810 671 -0.0920665 0.985367 1.58077 1 0 1 1 0 0 +EDGE2 8810 930 0.0642058 0.0200092 -3.15092 1 0 1 1 0 0 +EDGE2 8810 8450 -0.04116 -0.0215947 -3.13732 1 0 1 1 0 0 +EDGE2 8810 8451 -0.0413579 -1.02162 -1.53787 1 0 1 1 0 0 +EDGE2 8810 670 0.000617355 -0.0180671 0.0308282 1 0 1 1 0 0 +EDGE2 8810 931 -0.0409071 -0.972855 -1.57017 1 0 1 1 0 0 +EDGE2 8810 8449 0.930226 0.00555848 -3.15002 1 0 1 1 0 0 +EDGE2 8810 929 1.08236 -0.0401705 -3.14808 1 0 1 1 0 0 +EDGE2 8811 672 0.93777 -0.000430452 0.0172229 1 0 1 1 0 0 +EDGE2 8811 671 0.0394104 0.0163131 -0.0205761 1 0 1 1 0 0 +EDGE2 8811 930 -1.03632 0.076544 1.56706 1 0 1 1 0 0 +EDGE2 8811 8810 -1.03598 0.0620053 -1.57618 1 0 1 1 0 0 +EDGE2 8811 8450 -1.09157 0.089391 1.61652 1 0 1 1 0 0 +EDGE2 8811 670 -1.02335 -0.110733 -1.54951 1 0 1 1 0 0 +EDGE2 8812 673 1.00484 -0.00159906 -0.019145 1 0 1 1 0 0 +EDGE2 8812 8811 -1.14353 0.0542487 -0.00738155 1 0 1 1 0 0 +EDGE2 8812 672 -0.00835427 -0.0351225 -0.020485 1 0 1 1 0 0 +EDGE2 8812 671 -1.0519 -0.0198788 0.0348823 1 0 1 1 0 0 +EDGE2 8813 673 0.00731001 0.0440487 -3.43585e-05 1 0 1 1 0 0 +EDGE2 8813 674 1.10247 -0.0745742 0.0132763 1 0 1 1 0 0 +EDGE2 8813 672 -0.961163 -0.00268757 -0.0131199 1 0 1 1 0 0 +EDGE2 8813 8812 -0.990476 0.00779916 0.0433206 1 0 1 1 0 0 +EDGE2 8814 8775 1.02989 0.00736152 -3.18137 1 0 1 1 0 0 +EDGE2 8814 8795 1.00576 -0.028811 -3.17469 1 0 1 1 0 0 +EDGE2 8814 675 1.03708 0.0225704 0.029937 1 0 1 1 0 0 +EDGE2 8814 673 -1.05441 -0.0146651 0.011774 1 0 1 1 0 0 +EDGE2 8814 674 -0.0189362 -0.0719661 0.00977401 1 0 1 1 0 0 +EDGE2 8814 8813 -1.07349 -0.0226992 -0.0413399 1 0 1 1 0 0 +EDGE2 8815 8774 1.05258 -0.000473792 -3.15531 1 0 1 1 0 0 +EDGE2 8815 8794 0.952194 -0.0123817 -3.16016 1 0 1 1 0 0 +EDGE2 8815 8796 0.0120766 1.00074 1.57659 1 0 1 1 0 0 +EDGE2 8815 8775 -0.032509 0.0285817 -3.12946 1 0 1 1 0 0 +EDGE2 8815 8795 0.014134 -0.0849765 -3.12263 1 0 1 1 0 0 +EDGE2 8815 676 -0.0159264 -0.978436 -1.60181 1 0 1 1 0 0 +EDGE2 8815 8776 -0.0139293 -1.0132 -1.5476 1 0 1 1 0 0 +EDGE2 8815 675 0.0581101 0.00135164 -0.0219615 1 0 1 1 0 0 +EDGE2 8815 674 -1.09491 0.0189211 0.0106576 1 0 1 1 0 0 +EDGE2 8815 8814 -1.0567 -0.0165271 0.031053 1 0 1 1 0 0 +EDGE2 8816 8797 0.950169 0.0553449 -0.0443953 1 0 1 1 0 0 +EDGE2 8816 8796 0.024123 -0.0324177 0.00976829 1 0 1 1 0 0 +EDGE2 8816 8775 -0.98213 -0.0394083 1.57301 1 0 1 1 0 0 +EDGE2 8816 8795 -1.0429 -0.00410569 1.53772 1 0 1 1 0 0 +EDGE2 8816 8815 -1.03295 0.00651531 -1.5592 1 0 1 1 0 0 +EDGE2 8816 675 -0.873615 -0.0181802 -1.53644 1 0 1 1 0 0 +EDGE2 8817 8798 0.96638 0.108491 0.0190197 1 0 1 1 0 0 +EDGE2 8817 8816 -1.06993 -0.079431 0.0308162 1 0 1 1 0 0 +EDGE2 8817 8797 -0.0138833 0.0767232 -0.00480277 1 0 1 1 0 0 +EDGE2 8817 8796 -0.986865 -0.0560603 0.0336208 1 0 1 1 0 0 +EDGE2 8818 8817 -0.987196 0.0451113 -0.0235543 1 0 1 1 0 0 +EDGE2 8818 8799 1.02141 -0.0399737 -0.00547808 1 0 1 1 0 0 +EDGE2 8818 8798 0.0531107 0.046634 -0.0238635 1 0 1 1 0 0 +EDGE2 8818 8797 -1.06167 -0.125679 -0.0129159 1 0 1 1 0 0 +EDGE2 8819 8800 1.08206 0.0500993 -0.00657208 1 0 1 1 0 0 +EDGE2 8819 640 1.06223 0.0863494 -3.12547 1 0 1 1 0 0 +EDGE2 8819 660 0.984452 -0.0480359 -3.17525 1 0 1 1 0 0 +EDGE2 8819 8818 -0.970405 -0.0251611 -0.0211802 1 0 1 1 0 0 +EDGE2 8819 8799 -0.0290235 -0.0309364 0.0284444 1 0 1 1 0 0 +EDGE2 8819 8798 -0.991188 0.0023586 0.0405669 1 0 1 1 0 0 +EDGE2 8820 661 0.131666 1.01865 1.54386 1 0 1 1 0 0 +EDGE2 8820 8800 0.0595432 0.0587665 0.00201286 1 0 1 1 0 0 +EDGE2 8820 639 1.08 0.0297046 -3.15331 1 0 1 1 0 0 +EDGE2 8820 659 0.936254 -0.0119985 -3.133 1 0 1 1 0 0 +EDGE2 8820 641 -0.069148 -1.06654 -1.55814 1 0 1 1 0 0 +EDGE2 8820 8819 -0.984612 -0.0683312 -0.0111409 1 0 1 1 0 0 +EDGE2 8820 640 -0.0157794 -0.0337049 -3.12595 1 0 1 1 0 0 +EDGE2 8820 660 0.0863844 -0.10536 -3.14081 1 0 1 1 0 0 +EDGE2 8820 8801 -0.0586712 1.00518 1.5618 1 0 1 1 0 0 +EDGE2 8820 8799 -1.00363 0.0585322 -0.00302934 1 0 1 1 0 0 +EDGE2 8821 8800 -0.948216 0.0538611 1.57027 1 0 1 1 0 0 +EDGE2 8821 642 0.995918 -0.00652362 0.0184706 1 0 1 1 0 0 +EDGE2 8821 641 -0.0881319 0.0812302 -0.0187071 1 0 1 1 0 0 +EDGE2 8821 8820 -1.00385 -0.0745415 1.60499 1 0 1 1 0 0 +EDGE2 8821 640 -0.913504 0.0025168 -1.57198 1 0 1 1 0 0 +EDGE2 8821 660 -0.997681 -0.067067 -1.55709 1 0 1 1 0 0 +EDGE2 8822 643 0.969387 0.0616316 -0.0312366 1 0 1 1 0 0 +EDGE2 8822 642 -0.0765882 0.0516194 -0.0130637 1 0 1 1 0 0 +EDGE2 8822 641 -1.05908 -0.0625142 0.0280054 1 0 1 1 0 0 +EDGE2 8822 8821 -0.945815 -0.0232328 0.00691378 1 0 1 1 0 0 +EDGE2 8823 8822 -0.965101 0.0120043 -0.00347666 1 0 1 1 0 0 +EDGE2 8823 644 1.01696 0.0305847 -0.0267106 1 0 1 1 0 0 +EDGE2 8823 643 -0.0217378 -0.00302553 -0.0285465 1 0 1 1 0 0 +EDGE2 8823 642 -0.967582 -0.0591546 0.000770187 1 0 1 1 0 0 +EDGE2 8824 5925 0.969519 0.017946 -3.11833 1 0 1 1 0 0 +EDGE2 8824 644 -0.0120553 -0.0511983 -0.0327752 1 0 1 1 0 0 +EDGE2 8824 625 0.998215 0.0258761 -3.18343 1 0 1 1 0 0 +EDGE2 8824 645 1.07967 0.0761234 -0.0130068 1 0 1 1 0 0 +EDGE2 8824 643 -0.981211 0.0524969 0.00353394 1 0 1 1 0 0 +EDGE2 8824 8823 -1.0054 0.0262878 -0.020988 1 0 1 1 0 0 +EDGE2 8825 5924 0.960578 0.0644166 -3.14086 1 0 1 1 0 0 +EDGE2 8825 624 1.09639 0.0216285 -3.12946 1 0 1 1 0 0 +EDGE2 8825 5925 0.0256127 -0.0867491 -3.12542 1 0 1 1 0 0 +EDGE2 8825 5926 -0.0201319 -1.03764 -1.57957 1 0 1 1 0 0 +EDGE2 8825 626 -0.0776856 1.00314 1.55867 1 0 1 1 0 0 +EDGE2 8825 646 0.0134652 0.990757 1.57907 1 0 1 1 0 0 +EDGE2 8825 644 -1.06882 -0.0498824 0.0491334 1 0 1 1 0 0 +EDGE2 8825 625 -0.00621894 0.0301337 -3.12026 1 0 1 1 0 0 +EDGE2 8825 645 -0.0169676 -0.0289875 0.0535675 1 0 1 1 0 0 +EDGE2 8825 8824 -1.00075 0.013984 -0.0342547 1 0 1 1 0 0 +EDGE2 8826 5925 -1.09663 -0.0495262 1.56399 1 0 1 1 0 0 +EDGE2 8826 8825 -0.950383 -0.0886174 -1.59662 1 0 1 1 0 0 +EDGE2 8826 626 -0.0314345 -0.0525461 0.00978099 1 0 1 1 0 0 +EDGE2 8826 627 1.00151 -0.0100062 0.0145878 1 0 1 1 0 0 +EDGE2 8826 647 0.860864 -0.0162214 -0.0219507 1 0 1 1 0 0 +EDGE2 8826 646 -0.0147335 -0.00520973 0.0264834 1 0 1 1 0 0 +EDGE2 8826 625 -1.06458 -0.100804 1.59461 1 0 1 1 0 0 +EDGE2 8826 645 -1.08759 0.0073362 -1.5752 1 0 1 1 0 0 +EDGE2 8827 8826 -0.952486 -0.0633696 0.0106699 1 0 1 1 0 0 +EDGE2 8827 626 -1.00148 -0.0576253 0.0353817 1 0 1 1 0 0 +EDGE2 8827 648 1.13029 0.0228147 -0.0283596 1 0 1 1 0 0 +EDGE2 8827 627 0.0858334 -0.00144403 -0.00441185 1 0 1 1 0 0 +EDGE2 8827 647 -0.0611185 -0.0170687 0.0100693 1 0 1 1 0 0 +EDGE2 8827 628 0.971792 0.0337664 -0.0055168 1 0 1 1 0 0 +EDGE2 8827 646 -0.992541 -0.0681564 0.031421 1 0 1 1 0 0 +EDGE2 8828 8827 -1.07167 -0.0128856 -0.0253365 1 0 1 1 0 0 +EDGE2 8828 648 -0.0754227 -0.0244511 -0.00538126 1 0 1 1 0 0 +EDGE2 8828 649 0.978622 -0.0474778 0.000676325 1 0 1 1 0 0 +EDGE2 8828 629 1.08165 0.00746876 -0.00556452 1 0 1 1 0 0 +EDGE2 8828 627 -0.993771 0.0717923 0.0233952 1 0 1 1 0 0 +EDGE2 8828 647 -1.00166 0.0689214 0.00453912 1 0 1 1 0 0 +EDGE2 8828 628 -0.00337475 0.000934069 -0.000312408 1 0 1 1 0 0 +EDGE2 8829 8828 -1.06774 -0.00411853 0.0118183 1 0 1 1 0 0 +EDGE2 8829 630 1.02472 -0.0278788 -0.0293475 1 0 1 1 0 0 +EDGE2 8829 650 0.974104 -0.105867 0.00511618 1 0 1 1 0 0 +EDGE2 8829 648 -1.01059 -0.0865766 0.0135304 1 0 1 1 0 0 +EDGE2 8829 649 0.0161031 -0.00445479 0.000733179 1 0 1 1 0 0 +EDGE2 8829 629 0.00639865 0.0347823 0.00101358 1 0 1 1 0 0 +EDGE2 8829 628 -1.07165 -0.0459414 0.021545 1 0 1 1 0 0 +EDGE2 8830 8829 -0.95964 0.123309 0.0171507 1 0 1 1 0 0 +EDGE2 8830 651 0.00773176 1.01042 1.55163 1 0 1 1 0 0 +EDGE2 8830 630 0.0870395 -0.0205182 -0.0126844 1 0 1 1 0 0 +EDGE2 8830 650 0.00754203 -0.026512 0.0191298 1 0 1 1 0 0 +EDGE2 8830 631 -0.0129053 0.981196 1.57721 1 0 1 1 0 0 +EDGE2 8830 649 -0.936552 -0.0767502 0.000619819 1 0 1 1 0 0 +EDGE2 8830 629 -1.03972 -0.0793409 0.0241979 1 0 1 1 0 0 +EDGE2 8831 8830 -0.847732 0.0346448 -1.58596 1 0 1 1 0 0 +EDGE2 8831 651 -0.0356289 -0.000359819 0.0140673 1 0 1 1 0 0 +EDGE2 8831 630 -1.00147 -0.0621014 -1.56429 1 0 1 1 0 0 +EDGE2 8831 650 -1.04375 -0.0211221 -1.57223 1 0 1 1 0 0 +EDGE2 8831 652 1.00774 -0.0222735 0.00413638 1 0 1 1 0 0 +EDGE2 8831 631 0.101227 -0.10963 -0.01984 1 0 1 1 0 0 +EDGE2 8831 632 0.926016 0.0176665 -0.0353085 1 0 1 1 0 0 +EDGE2 8832 651 -0.965428 0.000446272 0.00819561 1 0 1 1 0 0 +EDGE2 8832 8831 -0.999699 -0.0341787 -0.00114228 1 0 1 1 0 0 +EDGE2 8832 652 -0.0230139 0.0372512 0.0140952 1 0 1 1 0 0 +EDGE2 8832 631 -1.09084 -0.000278104 -0.017338 1 0 1 1 0 0 +EDGE2 8832 632 -0.0103931 0.0962354 -0.00913168 1 0 1 1 0 0 +EDGE2 8832 633 0.968858 0.092549 0.0130639 1 0 1 1 0 0 +EDGE2 8832 653 0.949226 -0.125185 0.0607669 1 0 1 1 0 0 +EDGE2 8833 652 -1.01314 -0.059029 0.0287845 1 0 1 1 0 0 +EDGE2 8833 8832 -0.988745 -0.0128745 0.0313454 1 0 1 1 0 0 +EDGE2 8833 632 -0.988672 -0.0381311 0.0245443 1 0 1 1 0 0 +EDGE2 8833 633 0.00887262 0.0216345 0.00263346 1 0 1 1 0 0 +EDGE2 8833 653 -0.0338783 -0.0565635 0.0308557 1 0 1 1 0 0 +EDGE2 8833 634 1.10227 -0.066843 -0.00540908 1 0 1 1 0 0 +EDGE2 8833 654 0.976628 -0.0120396 -0.0174305 1 0 1 1 0 0 +EDGE2 8834 8833 -1.03535 0.0474939 0.0142819 1 0 1 1 0 0 +EDGE2 8834 633 -1.07984 -0.0296428 -0.0285861 1 0 1 1 0 0 +EDGE2 8834 653 -0.952864 0.0423575 -0.0170114 1 0 1 1 0 0 +EDGE2 8834 635 1.07408 0.0370578 0.023947 1 0 1 1 0 0 +EDGE2 8834 634 0.0076289 0.0527037 0.0161867 1 0 1 1 0 0 +EDGE2 8834 654 -0.0060322 -0.02103 -0.00138963 1 0 1 1 0 0 +EDGE2 8834 655 0.964005 -0.012328 0.0138075 1 0 1 1 0 0 +EDGE2 8835 8834 -0.975799 0.0512727 0.0281426 1 0 1 1 0 0 +EDGE2 8835 635 0.0748361 0.013302 0.00217862 1 0 1 1 0 0 +EDGE2 8835 634 -1.06884 -0.0801483 0.0313975 1 0 1 1 0 0 +EDGE2 8835 654 -0.931264 -0.00511984 0.00570688 1 0 1 1 0 0 +EDGE2 8835 655 -0.0448231 0.0316787 -0.0126363 1 0 1 1 0 0 +EDGE2 8835 656 -0.0103266 1.01454 1.58299 1 0 1 1 0 0 +EDGE2 8835 636 0.165995 1.03123 1.56112 1 0 1 1 0 0 +EDGE2 8836 635 -0.892274 0.0241952 -1.57918 1 0 1 1 0 0 +EDGE2 8836 8835 -0.982969 0.0248724 -1.59873 1 0 1 1 0 0 +EDGE2 8836 655 -1.00838 -0.0189371 -1.59549 1 0 1 1 0 0 +EDGE2 8836 656 0.0494668 -0.0211264 -0.0628087 1 0 1 1 0 0 +EDGE2 8836 636 -0.0110819 -0.0189986 0.00317885 1 0 1 1 0 0 +EDGE2 8836 657 1.03845 0.0245907 0.00856933 1 0 1 1 0 0 +EDGE2 8836 637 1.02743 -0.0977941 0.0241368 1 0 1 1 0 0 +EDGE2 8837 656 -0.957315 -0.0325531 -0.0365018 1 0 1 1 0 0 +EDGE2 8837 8836 -0.996027 -0.0114907 0.0417516 1 0 1 1 0 0 +EDGE2 8837 636 -0.975529 -0.00734614 -0.00182122 1 0 1 1 0 0 +EDGE2 8837 657 0.0398463 -0.078906 0.00491256 1 0 1 1 0 0 +EDGE2 8837 658 0.986833 0.0906754 -0.00844918 1 0 1 1 0 0 +EDGE2 8837 637 0.0650355 0.0556983 -0.00839948 1 0 1 1 0 0 +EDGE2 8837 638 1.05533 -0.035543 0.0490542 1 0 1 1 0 0 +EDGE2 8838 8837 -1.03744 0.121992 0.00789138 1 0 1 1 0 0 +EDGE2 8838 657 -0.958963 0.0318123 0.00662812 1 0 1 1 0 0 +EDGE2 8838 658 -0.0197123 0.0164904 0.00135717 1 0 1 1 0 0 +EDGE2 8838 637 -0.969204 0.0737657 0.0362055 1 0 1 1 0 0 +EDGE2 8838 638 0.013111 -0.00103223 -0.00521081 1 0 1 1 0 0 +EDGE2 8838 639 0.963087 -0.0242012 -0.00696999 1 0 1 1 0 0 +EDGE2 8838 659 0.916881 0.0203199 0.0138577 1 0 1 1 0 0 +EDGE2 8839 658 -0.979205 -0.0808389 0.0110862 1 0 1 1 0 0 +EDGE2 8839 8838 -1.01828 -0.0185643 -0.0239371 1 0 1 1 0 0 +EDGE2 8839 638 -1.04505 -0.0138938 -0.00342457 1 0 1 1 0 0 +EDGE2 8839 8800 0.993507 -0.0858405 -3.12001 1 0 1 1 0 0 +EDGE2 8839 639 0.00394004 -0.0682622 0.00799425 1 0 1 1 0 0 +EDGE2 8839 659 0.0715741 0.0219648 -0.00941954 1 0 1 1 0 0 +EDGE2 8839 8820 0.988293 -0.0117406 -3.13608 1 0 1 1 0 0 +EDGE2 8839 640 1.02157 -0.00628002 0.0372722 1 0 1 1 0 0 +EDGE2 8839 660 1.02319 -0.0158262 0.0126657 1 0 1 1 0 0 +EDGE2 8840 661 0.0550762 -1.01646 -1.54561 1 0 1 1 0 0 +EDGE2 8840 8800 0.0339002 0.0180087 -3.13276 1 0 1 1 0 0 +EDGE2 8840 639 -1.03468 -0.0445193 -0.00479547 1 0 1 1 0 0 +EDGE2 8840 659 -1.01305 0.056493 0.0102029 1 0 1 1 0 0 +EDGE2 8840 8839 -0.975938 -0.0489164 0.00354803 1 0 1 1 0 0 +EDGE2 8840 641 -0.0157838 1.03917 1.56872 1 0 1 1 0 0 +EDGE2 8840 8821 -0.00781923 0.966019 1.59776 1 0 1 1 0 0 +EDGE2 8840 8820 -0.0561023 -0.0149885 -3.14161 1 0 1 1 0 0 +EDGE2 8840 8819 1.00992 0.0201984 -3.13178 1 0 1 1 0 0 +EDGE2 8840 640 -0.0190562 0.0142729 0.0447168 1 0 1 1 0 0 +EDGE2 8840 660 -0.0216612 -0.0641493 0.000998556 1 0 1 1 0 0 +EDGE2 8840 8801 0.01614 -0.919859 -1.59387 1 0 1 1 0 0 +EDGE2 8840 8799 1.05546 0.0636096 -3.08612 1 0 1 1 0 0 +EDGE2 8841 8800 -1.10306 0.0596135 1.58613 1 0 1 1 0 0 +EDGE2 8841 8822 1.03133 -0.0297379 0.00365194 1 0 1 1 0 0 +EDGE2 8841 642 0.966769 -0.0634654 0.01281 1 0 1 1 0 0 +EDGE2 8841 8840 -1.03327 -0.0293937 -1.56057 1 0 1 1 0 0 +EDGE2 8841 641 0.0991843 0.0157913 -0.00548247 1 0 1 1 0 0 +EDGE2 8841 8821 0.066885 0.0131801 -0.00225974 1 0 1 1 0 0 +EDGE2 8841 8820 -1.0077 0.0777439 1.59585 1 0 1 1 0 0 +EDGE2 8841 640 -0.931824 -0.0589431 -1.57979 1 0 1 1 0 0 +EDGE2 8841 660 -0.969582 0.0302149 -1.58643 1 0 1 1 0 0 +EDGE2 8842 8822 -0.0428653 -0.0147803 -0.0108115 1 0 1 1 0 0 +EDGE2 8842 643 1.00683 -0.0518813 0.0340028 1 0 1 1 0 0 +EDGE2 8842 8823 0.96764 -0.0316645 -0.0301728 1 0 1 1 0 0 +EDGE2 8842 8841 -1.07912 -0.0108184 0.018969 1 0 1 1 0 0 +EDGE2 8842 642 0.111993 0.0665363 -0.0139091 1 0 1 1 0 0 +EDGE2 8842 641 -1.03174 0.0243495 -0.0267155 1 0 1 1 0 0 +EDGE2 8842 8821 -0.979768 -0.0617516 -0.0266279 1 0 1 1 0 0 +EDGE2 8843 8822 -0.984612 0.038327 -0.0134229 1 0 1 1 0 0 +EDGE2 8843 644 1.05382 -0.0169509 -0.00105161 1 0 1 1 0 0 +EDGE2 8843 8824 1.01918 -0.075503 -0.0074152 1 0 1 1 0 0 +EDGE2 8843 643 -0.103215 -0.0541878 0.00435529 1 0 1 1 0 0 +EDGE2 8843 8823 0.014384 0.0592716 -0.0267682 1 0 1 1 0 0 +EDGE2 8843 8842 -0.978298 0.104907 -0.0208242 1 0 1 1 0 0 +EDGE2 8843 642 -1.02313 0.0105119 0.00342077 1 0 1 1 0 0 +EDGE2 8844 5925 0.968074 0.0119832 -3.15614 1 0 1 1 0 0 +EDGE2 8844 8825 1.01713 -0.0152918 -0.0176517 1 0 1 1 0 0 +EDGE2 8844 644 0.0165517 0.0986071 -0.0075816 1 0 1 1 0 0 +EDGE2 8844 625 1.02981 0.0768167 -3.17051 1 0 1 1 0 0 +EDGE2 8844 645 0.93088 0.0210369 -0.000772157 1 0 1 1 0 0 +EDGE2 8844 8824 -0.116821 -0.0978111 0.00289051 1 0 1 1 0 0 +EDGE2 8844 643 -0.973143 -0.0428226 -0.0272296 1 0 1 1 0 0 +EDGE2 8844 8823 -1.0107 -0.0462504 0.0472086 1 0 1 1 0 0 +EDGE2 8844 8843 -1.00211 0.0898367 -0.0324759 1 0 1 1 0 0 +EDGE2 8845 8826 -0.0352523 1.03315 1.60905 1 0 1 1 0 0 +EDGE2 8845 5924 1.01125 -0.0565177 -3.11741 1 0 1 1 0 0 +EDGE2 8845 624 0.969179 -0.00653676 -3.12161 1 0 1 1 0 0 +EDGE2 8845 5925 0.0384612 -0.00210213 -3.16406 1 0 1 1 0 0 +EDGE2 8845 8825 0.00619816 0.00701069 0.0285937 1 0 1 1 0 0 +EDGE2 8845 5926 -0.0625625 -1.00803 -1.53079 1 0 1 1 0 0 +EDGE2 8845 626 -0.0226029 0.974751 1.56878 1 0 1 1 0 0 +EDGE2 8845 646 0.0217668 0.969892 1.59681 1 0 1 1 0 0 +EDGE2 8845 644 -0.970167 0.0454259 -0.0141688 1 0 1 1 0 0 +EDGE2 8845 8844 -1.06682 0.0664012 -0.0244122 1 0 1 1 0 0 +EDGE2 8845 625 0.00474448 0.0413653 -3.169 1 0 1 1 0 0 +EDGE2 8845 645 0.0949514 0.0558255 -0.0306858 1 0 1 1 0 0 +EDGE2 8845 8824 -1.00032 -0.00458004 0.00539373 1 0 1 1 0 0 +EDGE2 8846 8845 -1.02908 0.0340224 1.57904 1 0 1 1 0 0 +EDGE2 8846 5925 -0.951681 -0.0161857 -1.53126 1 0 1 1 0 0 +EDGE2 8846 8825 -1.06918 0.00872005 1.57152 1 0 1 1 0 0 +EDGE2 8846 5926 -0.0515336 -0.0449351 0.0415912 1 0 1 1 0 0 +EDGE2 8846 5927 0.987196 0.0066803 0.0302843 1 0 1 1 0 0 +EDGE2 8846 625 -0.899702 -0.131753 -1.56375 1 0 1 1 0 0 +EDGE2 8846 645 -0.942179 -0.0588736 1.56855 1 0 1 1 0 0 +EDGE2 8847 8846 -0.979222 -0.0635904 -0.0158954 1 0 1 1 0 0 +EDGE2 8847 5926 -1.03916 -0.0485473 -0.0270984 1 0 1 1 0 0 +EDGE2 8847 5928 0.995576 0.020472 -0.010907 1 0 1 1 0 0 +EDGE2 8847 5927 0.0276964 -0.0845452 -0.000540233 1 0 1 1 0 0 +EDGE2 8848 8847 -0.923265 0.0185089 0.0370893 1 0 1 1 0 0 +EDGE2 8848 5929 0.975826 0.000309111 -0.0173558 1 0 1 1 0 0 +EDGE2 8848 5928 -0.0425627 -0.053129 0.0321709 1 0 1 1 0 0 +EDGE2 8848 5927 -1.0532 -0.0137447 0.000643055 1 0 1 1 0 0 +EDGE2 8849 5929 0.016994 -0.106678 0.0095146 1 0 1 1 0 0 +EDGE2 8849 5928 -0.947111 -0.0280904 -0.0616536 1 0 1 1 0 0 +EDGE2 8849 8848 -0.969099 0.00717135 -0.0153887 1 0 1 1 0 0 +EDGE2 8849 8790 0.979158 -0.0118167 -3.14716 1 0 1 1 0 0 +EDGE2 8849 5910 0.991498 0.0161117 -3.13997 1 0 1 1 0 0 +EDGE2 8849 5930 1.04775 -0.0637572 -0.00662584 1 0 1 1 0 0 +EDGE2 8849 8770 1.01181 0.13073 -3.14654 1 0 1 1 0 0 +EDGE2 8850 5929 -1.03014 0.0252467 0.00551003 1 0 1 1 0 0 +EDGE2 8850 8849 -0.931686 0.037679 0.00565666 1 0 1 1 0 0 +EDGE2 8850 8790 0.0100218 -0.0434658 -3.13061 1 0 1 1 0 0 +EDGE2 8850 5911 0.0443991 1.02368 1.5664 1 0 1 1 0 0 +EDGE2 8850 5931 0.0952483 0.973475 1.60458 1 0 1 1 0 0 +EDGE2 8850 8769 1.07498 -0.0336326 -3.13497 1 0 1 1 0 0 +EDGE2 8850 5910 -0.00274251 -0.11863 -3.12574 1 0 1 1 0 0 +EDGE2 8850 5930 -0.00292913 0.127303 0.0321688 1 0 1 1 0 0 +EDGE2 8850 8770 0.0215043 0.0741434 -3.12329 1 0 1 1 0 0 +EDGE2 8850 8789 1.07749 0.0248021 -3.16395 1 0 1 1 0 0 +EDGE2 8850 5909 1.01137 0.037295 -3.12719 1 0 1 1 0 0 +EDGE2 8850 8791 0.019263 -0.938689 -1.58218 1 0 1 1 0 0 +EDGE2 8850 8771 -0.0100179 -1.04549 -1.57607 1 0 1 1 0 0 +EDGE2 8851 8790 -0.932303 -0.0477567 1.57498 1 0 1 1 0 0 +EDGE2 8851 5912 0.915923 0.0151549 -0.0068921 1 0 1 1 0 0 +EDGE2 8851 5932 1.02321 0.0115849 -0.00454309 1 0 1 1 0 0 +EDGE2 8851 5911 -0.0236584 0.0101025 0.0434599 1 0 1 1 0 0 +EDGE2 8851 5931 -0.156799 0.0625899 0.0185542 1 0 1 1 0 0 +EDGE2 8851 8850 -1.0246 0.0435162 -1.57229 1 0 1 1 0 0 +EDGE2 8851 5910 -0.971649 -0.0506092 1.57381 1 0 1 1 0 0 +EDGE2 8851 5930 -0.938798 -0.0657674 -1.57181 1 0 1 1 0 0 +EDGE2 8851 8770 -0.942071 -0.0197861 1.61387 1 0 1 1 0 0 +EDGE2 8852 5912 0.0360787 0.0529322 -0.00295116 1 0 1 1 0 0 +EDGE2 8852 5913 0.958767 0.0644138 -0.0408044 1 0 1 1 0 0 +EDGE2 8852 5933 0.964645 0.0969969 0.0171094 1 0 1 1 0 0 +EDGE2 8852 5932 0.0443114 -0.0576464 -0.0080167 1 0 1 1 0 0 +EDGE2 8852 5911 -0.949302 0.0568459 -0.0418753 1 0 1 1 0 0 +EDGE2 8852 5931 -0.993668 -0.0436136 0.0275085 1 0 1 1 0 0 +EDGE2 8852 8851 -0.993836 0.0301995 0.0282138 1 0 1 1 0 0 +EDGE2 8853 5934 1.00793 -0.0902148 -0.0155405 1 0 1 1 0 0 +EDGE2 8853 5914 0.990602 -0.0733642 0.00629177 1 0 1 1 0 0 +EDGE2 8853 5912 -1.09668 -0.0388747 -0.0195455 1 0 1 1 0 0 +EDGE2 8853 8852 -0.959133 -0.0294885 -0.00718805 1 0 1 1 0 0 +EDGE2 8853 5913 -0.00186012 0.0834069 0.00337642 1 0 1 1 0 0 +EDGE2 8853 5933 -0.0362398 -0.0325377 -0.0274299 1 0 1 1 0 0 +EDGE2 8853 5932 -0.994827 -0.00887504 0.000700339 1 0 1 1 0 0 +EDGE2 8854 8853 -1.07669 -0.0646184 -0.0019524 1 0 1 1 0 0 +EDGE2 8854 5915 0.9736 -0.0271405 -0.0274519 1 0 1 1 0 0 +EDGE2 8854 6015 1.04174 -0.126338 -3.13476 1 0 1 1 0 0 +EDGE2 8854 5935 0.985206 -0.0330322 -0.033116 1 0 1 1 0 0 +EDGE2 8854 5934 0.0226387 -0.0141784 0.00605569 1 0 1 1 0 0 +EDGE2 8854 5914 0.0289007 0.000790611 0.0193773 1 0 1 1 0 0 +EDGE2 8854 5913 -1.01866 -0.0380237 0.00398046 1 0 1 1 0 0 +EDGE2 8854 5933 -1.08151 -0.0203212 -0.0205572 1 0 1 1 0 0 +EDGE2 8855 6014 0.942279 0.0997382 -3.16145 1 0 1 1 0 0 +EDGE2 8855 5915 0.0708184 -0.0642607 0.00212323 1 0 1 1 0 0 +EDGE2 8855 6016 -0.0208542 1.06336 1.53469 1 0 1 1 0 0 +EDGE2 8855 6015 -0.0429902 -0.0099348 -3.14413 1 0 1 1 0 0 +EDGE2 8855 5916 -0.0273694 0.987503 1.56262 1 0 1 1 0 0 +EDGE2 8855 5935 0.0400156 -0.00565517 0.0036821 1 0 1 1 0 0 +EDGE2 8855 5934 -1.02115 -0.028625 0.0215614 1 0 1 1 0 0 +EDGE2 8855 8854 -0.909278 0.0273731 -0.021636 1 0 1 1 0 0 +EDGE2 8855 5914 -0.942804 -0.0744692 -0.0127314 1 0 1 1 0 0 +EDGE2 8855 5936 -0.0600142 -1.03037 -1.55291 1 0 1 1 0 0 +EDGE2 8856 5915 -0.955146 0.0411858 -1.58298 1 0 1 1 0 0 +EDGE2 8856 6016 -0.00599941 -0.0703916 -0.0102587 1 0 1 1 0 0 +EDGE2 8856 5917 0.979265 0.0515922 0.00622151 1 0 1 1 0 0 +EDGE2 8856 6017 1.02161 -0.0254032 -0.00632106 1 0 1 1 0 0 +EDGE2 8856 6015 -1.01291 -0.0108755 1.57136 1 0 1 1 0 0 +EDGE2 8856 8855 -1.00675 0.0238598 -1.5554 1 0 1 1 0 0 +EDGE2 8856 5916 -0.0563029 0.0127229 -0.0225831 1 0 1 1 0 0 +EDGE2 8856 5935 -0.987015 0.0754806 -1.56618 1 0 1 1 0 0 +EDGE2 8857 6018 0.964551 0.00186822 -0.0179233 1 0 1 1 0 0 +EDGE2 8857 5918 0.951929 -0.004923 0.00775095 1 0 1 1 0 0 +EDGE2 8857 6016 -0.994779 -0.049269 0.00204541 1 0 1 1 0 0 +EDGE2 8857 5917 -0.00367942 0.0677582 -0.0258992 1 0 1 1 0 0 +EDGE2 8857 6017 0.0528222 -0.0234616 -0.0157872 1 0 1 1 0 0 +EDGE2 8857 8856 -1.02243 -0.0420716 -0.017112 1 0 1 1 0 0 +EDGE2 8857 5916 -1.0622 0.0269585 -0.0472986 1 0 1 1 0 0 +EDGE2 8858 6019 0.979108 -0.0349121 0.0183141 1 0 1 1 0 0 +EDGE2 8858 6018 -0.0325734 0.0287204 0.0118384 1 0 1 1 0 0 +EDGE2 8858 5919 0.96994 -0.085144 0.0103951 1 0 1 1 0 0 +EDGE2 8858 5918 -0.0818477 -0.0261873 0.00295781 1 0 1 1 0 0 +EDGE2 8858 5917 -1.07068 -0.0404805 -0.00950278 1 0 1 1 0 0 +EDGE2 8858 6017 -0.958777 -0.0736991 -0.0295424 1 0 1 1 0 0 +EDGE2 8858 8857 -0.993581 0.0245423 -0.00567528 1 0 1 1 0 0 +EDGE2 8859 620 1.01357 -0.00840823 -3.1854 1 0 1 1 0 0 +EDGE2 8859 6020 0.98229 -0.0780198 0.00480293 1 0 1 1 0 0 +EDGE2 8859 5920 0.973738 -0.0215971 0.0260804 1 0 1 1 0 0 +EDGE2 8859 6019 -0.00862277 0.0112792 0.0306606 1 0 1 1 0 0 +EDGE2 8859 6018 -0.990783 0.0402287 -0.00999386 1 0 1 1 0 0 +EDGE2 8859 8858 -0.923965 -0.00446295 -0.03014 1 0 1 1 0 0 +EDGE2 8859 5919 0.049229 0.0213059 0.00406564 1 0 1 1 0 0 +EDGE2 8859 5918 -0.967951 0.0248155 -0.0251608 1 0 1 1 0 0 +EDGE2 8860 6021 -0.0367793 -1.00823 -1.565 1 0 1 1 0 0 +EDGE2 8860 620 0.0247245 0.0498964 -3.13059 1 0 1 1 0 0 +EDGE2 8860 6020 0.028444 -0.0760959 0.0383047 1 0 1 1 0 0 +EDGE2 8860 619 1.05073 -0.0513368 -3.15059 1 0 1 1 0 0 +EDGE2 8860 5920 0.160905 0.0567057 0.0118501 1 0 1 1 0 0 +EDGE2 8860 6019 -1.04009 0.0276322 0.0354573 1 0 1 1 0 0 +EDGE2 8860 621 -0.0206359 0.905468 1.53475 1 0 1 1 0 0 +EDGE2 8860 5921 0.0336057 0.925477 1.54792 1 0 1 1 0 0 +EDGE2 8860 8859 -0.981655 -0.0162209 0.0148096 1 0 1 1 0 0 +EDGE2 8860 5919 -1.03345 0.00594317 0.00266829 1 0 1 1 0 0 +EDGE2 8861 6021 0.052931 0.0538789 -0.00782789 1 0 1 1 0 0 +EDGE2 8861 6022 0.934826 0.0028638 0.0187964 1 0 1 1 0 0 +EDGE2 8861 620 -1.01124 -0.0160888 -1.59528 1 0 1 1 0 0 +EDGE2 8861 6020 -0.945817 0.058718 1.57117 1 0 1 1 0 0 +EDGE2 8861 8860 -0.948936 0.0335066 1.56916 1 0 1 1 0 0 +EDGE2 8861 5920 -1.00137 -0.05088 1.5731 1 0 1 1 0 0 +EDGE2 8862 6021 -0.924125 0.00681308 0.0209422 1 0 1 1 0 0 +EDGE2 8862 6022 -0.0945713 0.0513161 0.000517664 1 0 1 1 0 0 +EDGE2 8862 6023 1.06802 0.0391759 -0.00273734 1 0 1 1 0 0 +EDGE2 8862 8861 -0.969404 -0.0431648 0.0451401 1 0 1 1 0 0 +EDGE2 8863 6024 1.01206 -0.0548264 0.000716381 1 0 1 1 0 0 +EDGE2 8863 6022 -0.993567 0.00979811 -0.00602818 1 0 1 1 0 0 +EDGE2 8863 8862 -1.09351 -0.0125464 0.0177807 1 0 1 1 0 0 +EDGE2 8863 6023 -0.162319 0.0637094 0.00617981 1 0 1 1 0 0 +EDGE2 8864 8863 -0.930324 0.0410128 0.016301 1 0 1 1 0 0 +EDGE2 8864 6025 0.969812 -0.0369181 -0.0110599 1 0 1 1 0 0 +EDGE2 8864 6024 -0.0296867 -0.034637 -0.010746 1 0 1 1 0 0 +EDGE2 8864 6023 -0.983536 -0.0204291 0.00320014 1 0 1 1 0 0 +EDGE2 8865 6025 0.0371648 -0.025345 0.00889251 1 0 1 1 0 0 +EDGE2 8865 6026 0.0368628 1.03931 1.56983 1 0 1 1 0 0 +EDGE2 8865 6024 -1.07933 0.0647467 0.00988289 1 0 1 1 0 0 +EDGE2 8865 8864 -1.05419 0.0676592 -0.0230489 1 0 1 1 0 0 +EDGE2 8866 6025 -1.07602 0.00431145 -1.55456 1 0 1 1 0 0 +EDGE2 8866 6026 0.0541759 -0.0370229 -0.0340244 1 0 1 1 0 0 +EDGE2 8866 6027 0.997785 -0.0211849 0.0292633 1 0 1 1 0 0 +EDGE2 8866 8865 -1.06849 0.0333555 -1.58657 1 0 1 1 0 0 +EDGE2 8867 6028 0.955231 0.0569164 -0.00676735 1 0 1 1 0 0 +EDGE2 8867 6026 -0.97095 -0.0940172 0.0153378 1 0 1 1 0 0 +EDGE2 8867 8866 -0.961079 0.092317 0.0112918 1 0 1 1 0 0 +EDGE2 8867 6027 -0.0139585 -0.0573366 -0.000129361 1 0 1 1 0 0 +EDGE2 8868 8867 -0.915981 0.0476482 0.0281086 1 0 1 1 0 0 +EDGE2 8868 6029 1.03535 0.111423 -0.02528 1 0 1 1 0 0 +EDGE2 8868 6028 -0.0149971 -0.0590827 0.00127438 1 0 1 1 0 0 +EDGE2 8868 6027 -1.06052 -0.0116858 0.0222953 1 0 1 1 0 0 +EDGE2 8869 8868 -1.03887 -0.0168818 -0.00358396 1 0 1 1 0 0 +EDGE2 8869 6050 1.05931 -0.00409477 -3.15706 1 0 1 1 0 0 +EDGE2 8869 6090 0.983294 0.00892482 -3.16586 1 0 1 1 0 0 +EDGE2 8869 6250 0.991024 0.0221085 -3.1587 1 0 1 1 0 0 +EDGE2 8869 6070 1.0375 0.0768343 -3.17573 1 0 1 1 0 0 +EDGE2 8869 610 1.10068 0.0107391 -3.12988 1 0 1 1 0 0 +EDGE2 8869 6030 1.01255 0.0117991 0.0337573 1 0 1 1 0 0 +EDGE2 8869 6029 -0.0509516 0.0207861 -0.0222722 1 0 1 1 0 0 +EDGE2 8869 6028 -1.07394 -0.0395037 -0.0205155 1 0 1 1 0 0 +EDGE2 8870 6251 0.0654677 -1.01296 -1.56362 1 0 1 1 0 0 +EDGE2 8870 6051 0.0897156 -0.984212 -1.53975 1 0 1 1 0 0 +EDGE2 8870 6071 -0.020935 -1.05187 -1.55499 1 0 1 1 0 0 +EDGE2 8870 6091 -0.00872567 -1.05401 -1.57515 1 0 1 1 0 0 +EDGE2 8870 6031 0.0648094 -0.946218 -1.50877 1 0 1 1 0 0 +EDGE2 8870 6089 1.11347 0.013087 -3.14913 1 0 1 1 0 0 +EDGE2 8870 6249 1.00847 -0.0568927 -3.15085 1 0 1 1 0 0 +EDGE2 8870 6049 1.03604 -0.0421081 -3.09987 1 0 1 1 0 0 +EDGE2 8870 6069 1.06578 -0.0339155 -3.15082 1 0 1 1 0 0 +EDGE2 8870 609 1.02341 -0.0529504 -3.09669 1 0 1 1 0 0 +EDGE2 8870 6050 -0.00804496 -0.0428191 -3.13978 1 0 1 1 0 0 +EDGE2 8870 6090 -0.000938467 -0.0415484 -3.14163 1 0 1 1 0 0 +EDGE2 8870 6250 0.00170376 0.00537426 -3.12283 1 0 1 1 0 0 +EDGE2 8870 6070 0.0399536 0.0125359 -3.09741 1 0 1 1 0 0 +EDGE2 8870 8869 -0.970899 0.0206475 -0.0380525 1 0 1 1 0 0 +EDGE2 8870 610 -0.0698656 0.0382187 -3.1714 1 0 1 1 0 0 +EDGE2 8870 6030 -0.030784 0.00148197 -0.015503 1 0 1 1 0 0 +EDGE2 8870 6029 -1.05885 -0.0289366 -0.0152509 1 0 1 1 0 0 +EDGE2 8870 611 -0.042158 0.971298 1.5577 1 0 1 1 0 0 +EDGE2 8871 6050 -0.899577 -0.0128171 1.56401 1 0 1 1 0 0 +EDGE2 8871 6090 -1.08431 -0.00361726 1.54421 1 0 1 1 0 0 +EDGE2 8871 6250 -1.05528 0.0720503 1.60872 1 0 1 1 0 0 +EDGE2 8871 8870 -0.991538 -0.0271793 -1.5717 1 0 1 1 0 0 +EDGE2 8871 6070 -0.994313 0.00729878 1.59423 1 0 1 1 0 0 +EDGE2 8871 610 -1.01712 0.0386993 1.61258 1 0 1 1 0 0 +EDGE2 8871 6030 -1.02867 -0.000478469 -1.58889 1 0 1 1 0 0 +EDGE2 8871 611 -0.0515022 0.0964739 -0.0223826 1 0 1 1 0 0 +EDGE2 8871 612 1.00429 -0.0594123 -0.0204452 1 0 1 1 0 0 +EDGE2 8872 611 -1.00998 0.035822 0.00975157 1 0 1 1 0 0 +EDGE2 8872 8871 -0.960704 -0.020415 -0.0296868 1 0 1 1 0 0 +EDGE2 8872 612 0.0436728 -0.0979967 -0.0062168 1 0 1 1 0 0 +EDGE2 8872 613 0.997448 0.0489547 0.0198045 1 0 1 1 0 0 +EDGE2 8873 8872 -1.02771 0.108842 -0.00617297 1 0 1 1 0 0 +EDGE2 8873 612 -0.999293 0.0744702 -0.0277732 1 0 1 1 0 0 +EDGE2 8873 614 0.928911 0.0816182 0.00383405 1 0 1 1 0 0 +EDGE2 8873 613 -0.0208888 -0.0718771 -0.0216559 1 0 1 1 0 0 +EDGE2 8874 8873 -1.03981 0.0136882 -0.00985514 1 0 1 1 0 0 +EDGE2 8874 614 0.0732515 -0.0682717 0.00279503 1 0 1 1 0 0 +EDGE2 8874 613 -0.996609 0.061817 0.012192 1 0 1 1 0 0 +EDGE2 8874 615 0.952845 0.0180733 -0.00341767 1 0 1 1 0 0 +EDGE2 8875 614 -0.990425 0.0050304 -0.00325318 1 0 1 1 0 0 +EDGE2 8875 8874 -1.10539 -0.075401 -0.0119807 1 0 1 1 0 0 +EDGE2 8875 616 0.00416058 0.988053 1.59125 1 0 1 1 0 0 +EDGE2 8875 615 -0.0115399 -0.0633268 0.00631626 1 0 1 1 0 0 +EDGE2 8876 8875 -1.0801 -0.133064 1.54827 1 0 1 1 0 0 +EDGE2 8876 615 -1.01217 -0.0676309 1.58214 1 0 1 1 0 0 +EDGE2 8877 8876 -1.07138 -0.0642089 0.00947403 1 0 1 1 0 0 +EDGE2 8878 8877 -1.00445 -0.0797714 -0.00124037 1 0 1 1 0 0 +EDGE2 8879 6240 0.912824 0.0462286 -3.16303 1 0 1 1 0 0 +EDGE2 8879 600 1.0064 0.0552342 -3.1561 1 0 1 1 0 0 +EDGE2 8879 8878 -0.97839 -0.0670233 -0.00889963 1 0 1 1 0 0 +EDGE2 8880 6239 1.02687 -0.0293587 -3.1377 1 0 1 1 0 0 +EDGE2 8880 599 0.990576 -0.00219963 -3.13716 1 0 1 1 0 0 +EDGE2 8880 6240 -0.0297998 0.049494 -3.12521 1 0 1 1 0 0 +EDGE2 8880 601 -0.00185804 -1.07374 -1.59587 1 0 1 1 0 0 +EDGE2 8880 6241 0.0868071 -0.970042 -1.57025 1 0 1 1 0 0 +EDGE2 8880 8879 -0.986353 -0.0936257 -0.0406131 1 0 1 1 0 0 +EDGE2 8880 600 0.0321876 0.0514789 -3.14494 1 0 1 1 0 0 +EDGE2 8881 6240 -1.03069 0.121293 1.559 1 0 1 1 0 0 +EDGE2 8881 8880 -0.932285 0.0962817 -1.61902 1 0 1 1 0 0 +EDGE2 8881 600 -1.1114 0.0353014 1.58943 1 0 1 1 0 0 +EDGE2 8882 8881 -1.06714 0.0202611 -0.0252441 1 0 1 1 0 0 +EDGE2 8883 8882 -0.97291 0.0300569 -0.0446191 1 0 1 1 0 0 +EDGE2 8884 8883 -0.941216 0.0509698 0.00108338 1 0 1 1 0 0 +EDGE2 8885 8884 -0.987477 -0.00117077 -0.0304706 1 0 1 1 0 0 +EDGE2 8886 8885 -1.07359 -0.0402816 1.57904 1 0 1 1 0 0 +EDGE2 8887 8886 -0.941394 -0.0335693 0.00601116 1 0 1 1 0 0 +EDGE2 8888 8887 -0.910037 -0.0550159 0.0247858 1 0 1 1 0 0 +EDGE2 8889 6310 0.968761 0.010513 -3.10464 1 0 1 1 0 0 +EDGE2 8889 8888 -0.984283 -0.0798621 0.020157 1 0 1 1 0 0 +EDGE2 8890 6309 0.923775 -0.0453597 -3.15821 1 0 1 1 0 0 +EDGE2 8890 6311 0.0176433 -0.969208 -1.55126 1 0 1 1 0 0 +EDGE2 8890 6310 0.0562381 0.135117 -3.13195 1 0 1 1 0 0 +EDGE2 8890 8889 -0.949622 -0.013259 -0.0279628 1 0 1 1 0 0 +EDGE2 8891 6310 -1.00613 -0.0573845 1.6 1 0 1 1 0 0 +EDGE2 8891 8890 -0.949821 0.00650656 -1.57321 1 0 1 1 0 0 +EDGE2 8892 8891 -0.919151 -0.0236428 -0.00281108 1 0 1 1 0 0 +EDGE2 8893 8892 -0.948592 0.0150039 -0.0091355 1 0 1 1 0 0 +EDGE2 8894 8893 -1.09798 0.00324437 -0.0153126 1 0 1 1 0 0 +EDGE2 8894 8135 0.952808 0.0481844 -3.14991 1 0 1 1 0 0 +EDGE2 8894 8155 0.986493 -0.136802 -3.12082 1 0 1 1 0 0 +EDGE2 8895 8156 0.0073469 -0.972599 -1.5676 1 0 1 1 0 0 +EDGE2 8895 8136 0.0125465 -0.967515 -1.54765 1 0 1 1 0 0 +EDGE2 8895 8894 -1.08103 0.0831662 -0.0278932 1 0 1 1 0 0 +EDGE2 8895 8135 0.0840105 0.037097 -3.16099 1 0 1 1 0 0 +EDGE2 8895 8155 0.0226264 0.0581858 -3.1991 1 0 1 1 0 0 +EDGE2 8895 8134 1.02066 -0.0812431 -3.16492 1 0 1 1 0 0 +EDGE2 8895 8154 0.938925 0.0457326 -3.10938 1 0 1 1 0 0 +EDGE2 8896 8135 -1.05105 -0.00990444 1.53614 1 0 1 1 0 0 +EDGE2 8896 8895 -0.961167 -0.0600944 -1.58169 1 0 1 1 0 0 +EDGE2 8896 8155 -0.980109 0.00445781 1.56535 1 0 1 1 0 0 +EDGE2 8897 8896 -0.972067 0.0567775 0.0129886 1 0 1 1 0 0 +EDGE2 8898 8897 -1.027 0.0817583 0.00212128 1 0 1 1 0 0 +EDGE2 8899 8898 -0.991623 0.0370531 0.0055656 1 0 1 1 0 0 +EDGE2 8900 8899 -0.987713 -0.0880586 -0.0353507 1 0 1 1 0 0 +EDGE2 8901 8900 -1.07043 -0.0468947 -1.55797 1 0 1 1 0 0 +EDGE2 8902 8901 -0.959226 -0.11642 0.0119671 1 0 1 1 0 0 +EDGE2 8903 8902 -0.965998 -0.0271496 0.0119816 1 0 1 1 0 0 +EDGE2 8904 8885 1.04272 0.00112688 -3.13257 1 0 1 1 0 0 +EDGE2 8904 8903 -0.998781 -0.0412862 0.0364609 1 0 1 1 0 0 +EDGE2 8905 8886 0.0220438 1.00412 1.56308 1 0 1 1 0 0 +EDGE2 8905 8884 1.02623 0.00881562 -3.12063 1 0 1 1 0 0 +EDGE2 8905 8885 -0.00143977 0.0939864 -3.14831 1 0 1 1 0 0 +EDGE2 8905 8904 -1.10016 -0.0178415 0.00880259 1 0 1 1 0 0 +EDGE2 8906 8887 1.04331 -0.00481944 0.033365 1 0 1 1 0 0 +EDGE2 8906 8886 -0.10539 0.017902 -0.00327472 1 0 1 1 0 0 +EDGE2 8906 8885 -0.950143 0.00539975 1.59659 1 0 1 1 0 0 +EDGE2 8906 8905 -0.934901 -0.0543863 -1.57345 1 0 1 1 0 0 +EDGE2 8907 8888 0.98395 0.0140893 -0.0424363 1 0 1 1 0 0 +EDGE2 8907 8887 -0.0701518 0.0557075 0.0252802 1 0 1 1 0 0 +EDGE2 8907 8906 -0.99063 0.00926232 0.0220688 1 0 1 1 0 0 +EDGE2 8907 8886 -0.961021 -0.0149686 -0.0342953 1 0 1 1 0 0 +EDGE2 8908 8889 1.03658 0.0513644 0.0256392 1 0 1 1 0 0 +EDGE2 8908 8888 -0.0369773 0.0357356 0.0109958 1 0 1 1 0 0 +EDGE2 8908 8907 -0.976515 0.0478603 -0.0351788 1 0 1 1 0 0 +EDGE2 8908 8887 -1.07211 -0.0356577 -0.0143909 1 0 1 1 0 0 +EDGE2 8909 6310 0.979941 0.0308798 -3.17963 1 0 1 1 0 0 +EDGE2 8909 8890 0.847493 0.0645566 0.000832993 1 0 1 1 0 0 +EDGE2 8909 8889 0.0326649 -0.0547398 0.0321416 1 0 1 1 0 0 +EDGE2 8909 8888 -1.08437 0.0726052 -0.00276206 1 0 1 1 0 0 +EDGE2 8909 8908 -1.02788 0.056535 0.0459635 1 0 1 1 0 0 +EDGE2 8910 6309 1.08782 -0.0838632 -3.15755 1 0 1 1 0 0 +EDGE2 8910 6311 -0.0785145 -0.977144 -1.57739 1 0 1 1 0 0 +EDGE2 8910 6310 0.00116311 -0.0140036 -3.17904 1 0 1 1 0 0 +EDGE2 8910 8890 0.0299531 0.0173161 -0.0403237 1 0 1 1 0 0 +EDGE2 8910 8909 -0.968587 -0.0237787 -0.0343496 1 0 1 1 0 0 +EDGE2 8910 8889 -1.08209 0.0049654 0.00502285 1 0 1 1 0 0 +EDGE2 8910 8891 -0.0389246 0.979089 1.60423 1 0 1 1 0 0 +EDGE2 8911 6310 -1.0435 -0.0403774 1.55515 1 0 1 1 0 0 +EDGE2 8911 8910 -0.891021 0.0913722 -1.5845 1 0 1 1 0 0 +EDGE2 8911 8890 -0.9977 -0.000795204 -1.56483 1 0 1 1 0 0 +EDGE2 8911 8892 1.02564 -0.0338428 0.0328194 1 0 1 1 0 0 +EDGE2 8911 8891 0.0142938 -0.0373273 0.0131327 1 0 1 1 0 0 +EDGE2 8912 8892 0.0305459 -0.0245344 0.0246769 1 0 1 1 0 0 +EDGE2 8912 8891 -0.9532 0.0203957 0.0161164 1 0 1 1 0 0 +EDGE2 8912 8911 -0.974606 -0.0138677 0.00623882 1 0 1 1 0 0 +EDGE2 8912 8893 0.934608 -0.000839985 -0.0221272 1 0 1 1 0 0 +EDGE2 8913 8892 -1.01017 -0.0322879 0.0187013 1 0 1 1 0 0 +EDGE2 8913 8912 -1.10055 -0.0937776 -0.0118512 1 0 1 1 0 0 +EDGE2 8913 8893 -0.0838593 -0.00200435 -0.016748 1 0 1 1 0 0 +EDGE2 8913 8894 0.911766 -0.0275262 -0.0224314 1 0 1 1 0 0 +EDGE2 8914 8893 -1.08434 0.0158171 -0.0238787 1 0 1 1 0 0 +EDGE2 8914 8913 -1.04818 -0.0300658 -0.01729 1 0 1 1 0 0 +EDGE2 8914 8894 -0.0399568 -0.0466252 -0.00707058 1 0 1 1 0 0 +EDGE2 8914 8135 1.0293 -0.00394628 -3.14565 1 0 1 1 0 0 +EDGE2 8914 8895 0.880782 0.0873797 -0.0132014 1 0 1 1 0 0 +EDGE2 8914 8155 0.985512 -0.0595591 -3.16674 1 0 1 1 0 0 +EDGE2 8915 8914 -1.01347 0.0483593 -0.0161227 1 0 1 1 0 0 +EDGE2 8915 8156 0.00640736 -1.01977 -1.5891 1 0 1 1 0 0 +EDGE2 8915 8136 0.101883 -0.9343 -1.59249 1 0 1 1 0 0 +EDGE2 8915 8894 -1.04233 -0.0291471 0.0319463 1 0 1 1 0 0 +EDGE2 8915 8135 0.0217445 -0.137065 -3.17466 1 0 1 1 0 0 +EDGE2 8915 8895 -0.0680645 0.00281777 -0.00778944 1 0 1 1 0 0 +EDGE2 8915 8155 -0.0535062 0.0217252 -3.13033 1 0 1 1 0 0 +EDGE2 8915 8896 -0.0421274 0.982774 1.56811 1 0 1 1 0 0 +EDGE2 8915 8134 0.956927 -0.0132649 -3.13768 1 0 1 1 0 0 +EDGE2 8915 8154 0.868297 -0.0134201 -3.11901 1 0 1 1 0 0 +EDGE2 8916 8135 -1.07597 0.0442707 1.55142 1 0 1 1 0 0 +EDGE2 8916 8895 -1.09138 0.0365182 -1.58856 1 0 1 1 0 0 +EDGE2 8916 8915 -1.03447 -0.0164648 -1.57819 1 0 1 1 0 0 +EDGE2 8916 8155 -0.992806 -0.0128978 1.52276 1 0 1 1 0 0 +EDGE2 8916 8896 0.016239 -0.00715695 0.0184213 1 0 1 1 0 0 +EDGE2 8916 8897 1.06562 -0.00243943 -0.00314916 1 0 1 1 0 0 +EDGE2 8917 8916 -1.00635 -0.0262263 0.0193669 1 0 1 1 0 0 +EDGE2 8917 8896 -1.00086 0.00328281 0.0583392 1 0 1 1 0 0 +EDGE2 8917 8897 -0.0291595 0.0215633 0.023189 1 0 1 1 0 0 +EDGE2 8917 8898 0.957364 0.0500711 0.0228399 1 0 1 1 0 0 +EDGE2 8918 8917 -1.01291 0.0632155 -0.0365266 1 0 1 1 0 0 +EDGE2 8918 8897 -0.930794 -0.084066 0.0514443 1 0 1 1 0 0 +EDGE2 8918 8898 -0.133686 -0.0581712 -0.00326209 1 0 1 1 0 0 +EDGE2 8918 8899 0.910574 -0.0770748 -0.00301453 1 0 1 1 0 0 +EDGE2 8919 8898 -1.01519 0.00191608 -0.00454254 1 0 1 1 0 0 +EDGE2 8919 8918 -1.01374 -0.0138709 -0.00427925 1 0 1 1 0 0 +EDGE2 8919 8899 -0.0109567 -0.0194392 0.0102377 1 0 1 1 0 0 +EDGE2 8919 8900 1.01611 -0.115165 0.0326477 1 0 1 1 0 0 +EDGE2 8920 8919 -0.979613 -0.0474289 0.000880524 1 0 1 1 0 0 +EDGE2 8920 8899 -0.988862 -0.0663148 0.0126197 1 0 1 1 0 0 +EDGE2 8920 8901 0.0372083 1.06754 1.56972 1 0 1 1 0 0 +EDGE2 8920 8900 0.0278144 0.0254912 0.0110678 1 0 1 1 0 0 +EDGE2 8921 8902 0.892224 -0.0751226 0.017251 1 0 1 1 0 0 +EDGE2 8921 8901 0.0268496 -0.0186322 0.00645595 1 0 1 1 0 0 +EDGE2 8921 8920 -0.930949 0.0213347 -1.54708 1 0 1 1 0 0 +EDGE2 8921 8900 -1.0178 -0.0742577 -1.59463 1 0 1 1 0 0 +EDGE2 8922 8903 1.03648 0.0190714 -0.0191589 1 0 1 1 0 0 +EDGE2 8922 8902 0.0713928 -0.018157 -0.0211845 1 0 1 1 0 0 +EDGE2 8922 8921 -0.971042 -0.100925 -0.0201863 1 0 1 1 0 0 +EDGE2 8922 8901 -0.998661 -0.0613732 -0.017097 1 0 1 1 0 0 +EDGE2 8923 8904 0.98181 0.0258363 0.0107231 1 0 1 1 0 0 +EDGE2 8923 8903 0.0399851 -0.0146768 0.0206762 1 0 1 1 0 0 +EDGE2 8923 8902 -1.0844 -0.0840527 0.0162668 1 0 1 1 0 0 +EDGE2 8923 8922 -0.993404 -0.131086 -0.0175865 1 0 1 1 0 0 +EDGE2 8924 8885 1.05634 0.0451649 -3.11795 1 0 1 1 0 0 +EDGE2 8924 8905 1.00869 0.0722835 0.0012619 1 0 1 1 0 0 +EDGE2 8924 8904 0.0172412 0.0669523 0.0199382 1 0 1 1 0 0 +EDGE2 8924 8903 -0.997385 -0.0816878 -0.0180845 1 0 1 1 0 0 +EDGE2 8924 8923 -0.998971 0.0267575 -0.0500454 1 0 1 1 0 0 +EDGE2 8925 8906 0.0357793 0.871677 1.56895 1 0 1 1 0 0 +EDGE2 8925 8886 0.0274822 0.90229 1.56894 1 0 1 1 0 0 +EDGE2 8925 8884 0.982604 -0.0166986 -3.11936 1 0 1 1 0 0 +EDGE2 8925 8885 -0.00289378 0.0149418 -3.1517 1 0 1 1 0 0 +EDGE2 8925 8905 -0.00432138 0.0549459 -0.0102781 1 0 1 1 0 0 +EDGE2 8925 8924 -1.08169 0.0520956 0.0067541 1 0 1 1 0 0 +EDGE2 8925 8904 -1.04891 -0.0605953 -0.0101489 1 0 1 1 0 0 +EDGE2 8926 8885 -0.95005 0.0529829 -1.58097 1 0 1 1 0 0 +EDGE2 8926 8925 -1.01223 0.00055698 1.55339 1 0 1 1 0 0 +EDGE2 8926 8905 -1.1253 -0.013165 1.60923 1 0 1 1 0 0 +EDGE2 8927 8926 -0.978398 -0.0346112 0.0144112 1 0 1 1 0 0 +EDGE2 8928 8927 -0.974839 -0.0157144 0.00375635 1 0 1 1 0 0 +EDGE2 8929 8928 -0.969002 0.0199823 -0.0384359 1 0 1 1 0 0 +EDGE2 8929 8830 1.01047 0.0399012 -3.16684 1 0 1 1 0 0 +EDGE2 8929 630 0.92964 0.0775916 -3.13447 1 0 1 1 0 0 +EDGE2 8929 650 0.903942 -0.0799483 -3.15772 1 0 1 1 0 0 +EDGE2 8930 8929 -0.967677 0.0316049 -0.011864 1 0 1 1 0 0 +EDGE2 8930 8829 0.947544 0.0727969 -3.12166 1 0 1 1 0 0 +EDGE2 8930 8830 0.0827411 0.0606762 -3.13965 1 0 1 1 0 0 +EDGE2 8930 651 0.0233458 -1.03545 -1.57173 1 0 1 1 0 0 +EDGE2 8930 630 -0.0134177 0.0123427 -3.13908 1 0 1 1 0 0 +EDGE2 8930 650 -0.0328304 -0.0402222 -3.14624 1 0 1 1 0 0 +EDGE2 8930 8831 -0.0351844 -0.949135 -1.56754 1 0 1 1 0 0 +EDGE2 8930 631 0.00878316 -1.02279 -1.57167 1 0 1 1 0 0 +EDGE2 8930 649 0.973341 0.0527435 -3.14285 1 0 1 1 0 0 +EDGE2 8930 629 1.00824 0.112999 -3.17295 1 0 1 1 0 0 +EDGE2 8931 8930 -0.940555 0.0780622 -1.56827 1 0 1 1 0 0 +EDGE2 8931 8830 -1.06543 -0.0263753 1.58213 1 0 1 1 0 0 +EDGE2 8931 630 -1.00864 0.0699011 1.57692 1 0 1 1 0 0 +EDGE2 8931 650 -1.06927 0.022504 1.53819 1 0 1 1 0 0 +EDGE2 8932 8931 -1.09506 0.0166517 0.00951717 1 0 1 1 0 0 +EDGE2 8933 8932 -0.923925 0.0798839 0.00870498 1 0 1 1 0 0 +EDGE2 8934 8875 0.916007 0.0190404 -3.1475 1 0 1 1 0 0 +EDGE2 8934 8933 -1.0172 -0.00640602 -0.0191055 1 0 1 1 0 0 +EDGE2 8934 615 0.985254 0.073038 -3.13186 1 0 1 1 0 0 +EDGE2 8935 614 0.910035 -0.0526176 -3.13848 1 0 1 1 0 0 +EDGE2 8935 8874 0.969128 -0.0851503 -3.12929 1 0 1 1 0 0 +EDGE2 8935 8875 0.0285674 -0.0150525 -3.12198 1 0 1 1 0 0 +EDGE2 8935 8876 0.0210389 1.09257 1.56403 1 0 1 1 0 0 +EDGE2 8935 616 -0.0288834 -1.04101 -1.56193 1 0 1 1 0 0 +EDGE2 8935 8934 -0.995212 0.0341243 0.00297776 1 0 1 1 0 0 +EDGE2 8935 615 0.00901856 -0.00786103 -3.14687 1 0 1 1 0 0 +EDGE2 8936 8875 -0.992074 -0.063305 1.57193 1 0 1 1 0 0 +EDGE2 8936 8876 0.0435967 -0.0733225 0.00380613 1 0 1 1 0 0 +EDGE2 8936 8877 1.02983 0.0100621 0.00152784 1 0 1 1 0 0 +EDGE2 8936 8935 -0.960792 0.0537265 -1.56964 1 0 1 1 0 0 +EDGE2 8936 615 -0.987122 -0.0115687 1.58873 1 0 1 1 0 0 +EDGE2 8937 8878 1.0766 0.0212536 0.00120769 1 0 1 1 0 0 +EDGE2 8937 8876 -1.04337 -0.0159466 0.0242246 1 0 1 1 0 0 +EDGE2 8937 8936 -1.05153 0.0813818 -0.00377483 1 0 1 1 0 0 +EDGE2 8937 8877 -0.00319189 0.0295204 0.0286565 1 0 1 1 0 0 +EDGE2 8938 8879 0.967455 0.030491 -0.0227066 1 0 1 1 0 0 +EDGE2 8938 8937 -0.954116 0.0550681 -0.00536944 1 0 1 1 0 0 +EDGE2 8938 8878 -0.0106601 0.0329086 0.0102723 1 0 1 1 0 0 +EDGE2 8938 8877 -0.993972 0.0380624 -0.00348218 1 0 1 1 0 0 +EDGE2 8939 8938 -1.01362 0.00553692 -0.0251405 1 0 1 1 0 0 +EDGE2 8939 6240 0.970792 -0.00234318 -3.12541 1 0 1 1 0 0 +EDGE2 8939 8880 1.01846 -0.0175375 -0.0278429 1 0 1 1 0 0 +EDGE2 8939 8879 -0.0520655 0.0097711 0.0325463 1 0 1 1 0 0 +EDGE2 8939 600 0.975558 0.030067 -3.13823 1 0 1 1 0 0 +EDGE2 8939 8878 -0.991331 -0.0139889 0.0119553 1 0 1 1 0 0 +EDGE2 8940 6239 1.0905 -0.0251881 -3.1479 1 0 1 1 0 0 +EDGE2 8940 599 0.970821 -0.102695 -3.10684 1 0 1 1 0 0 +EDGE2 8940 6240 -0.0334934 0.0591496 -3.14279 1 0 1 1 0 0 +EDGE2 8940 601 0.0371414 -0.887426 -1.58658 1 0 1 1 0 0 +EDGE2 8940 6241 -0.0372587 -1.04812 -1.61604 1 0 1 1 0 0 +EDGE2 8940 8880 -0.0362059 -0.0298305 -0.0220261 1 0 1 1 0 0 +EDGE2 8940 8879 -1.08491 0.000943054 -0.0121916 1 0 1 1 0 0 +EDGE2 8940 8939 -1.00801 -0.0451887 0.0271669 1 0 1 1 0 0 +EDGE2 8940 600 0.0430882 0.0391984 -3.14248 1 0 1 1 0 0 +EDGE2 8940 8881 -0.0160029 1.02704 1.58401 1 0 1 1 0 0 +EDGE2 8941 6242 0.985044 0.0329559 -0.0102471 1 0 1 1 0 0 +EDGE2 8941 602 0.998559 0.0182064 -0.007359 1 0 1 1 0 0 +EDGE2 8941 6240 -1.03906 0.0164813 -1.58087 1 0 1 1 0 0 +EDGE2 8941 8940 -1.08804 0.0275514 1.55752 1 0 1 1 0 0 +EDGE2 8941 601 0.0333526 0.0959715 -0.0246528 1 0 1 1 0 0 +EDGE2 8941 6241 -0.103444 0.018642 0.00145564 1 0 1 1 0 0 +EDGE2 8941 8880 -0.998302 0.0209422 1.54579 1 0 1 1 0 0 +EDGE2 8941 600 -1.02987 -0.0611347 -1.56956 1 0 1 1 0 0 +EDGE2 8942 8941 -1.01607 0.087815 0.00618994 1 0 1 1 0 0 +EDGE2 8942 603 1.0608 0.10358 0.00778287 1 0 1 1 0 0 +EDGE2 8942 6243 1.00024 0.082225 -0.00892784 1 0 1 1 0 0 +EDGE2 8942 6242 0.1861 -0.0487981 0.00794393 1 0 1 1 0 0 +EDGE2 8942 602 0.0195862 -0.00268053 -0.0103467 1 0 1 1 0 0 +EDGE2 8942 601 -0.971633 -0.0649204 0.0096811 1 0 1 1 0 0 +EDGE2 8942 6241 -0.974914 0.0492485 -0.0187886 1 0 1 1 0 0 +EDGE2 8943 603 0.0362798 0.00280125 -0.00373739 1 0 1 1 0 0 +EDGE2 8943 604 1.02722 -0.0262779 -0.0213804 1 0 1 1 0 0 +EDGE2 8943 6244 0.860969 -0.125714 0.0186167 1 0 1 1 0 0 +EDGE2 8943 6243 0.0356671 0.0037882 -0.0216094 1 0 1 1 0 0 +EDGE2 8943 6242 -0.976064 0.0244039 -0.00497088 1 0 1 1 0 0 +EDGE2 8943 8942 -0.933057 -0.02229 -0.022642 1 0 1 1 0 0 +EDGE2 8943 602 -0.970718 -0.0649614 -0.0238028 1 0 1 1 0 0 +EDGE2 8944 6225 1.00367 -0.0149202 -3.1504 1 0 1 1 0 0 +EDGE2 8944 6265 0.958499 0.0948402 -3.13824 1 0 1 1 0 0 +EDGE2 8944 6245 1.05729 -0.082487 -0.0343707 1 0 1 1 0 0 +EDGE2 8944 6045 1.02419 -0.0241908 -3.17592 1 0 1 1 0 0 +EDGE2 8944 6065 1.10198 0.0411989 -3.12291 1 0 1 1 0 0 +EDGE2 8944 6085 0.990472 0.0657986 -3.16036 1 0 1 1 0 0 +EDGE2 8944 605 1.08493 -0.0186546 0.02796 1 0 1 1 0 0 +EDGE2 8944 603 -0.994799 -0.0815758 0.00346439 1 0 1 1 0 0 +EDGE2 8944 8943 -1.05667 0.0254123 -0.00235356 1 0 1 1 0 0 +EDGE2 8944 604 -0.00337501 -0.0698161 -0.0204639 1 0 1 1 0 0 +EDGE2 8944 6244 -0.0333924 0.0212203 0.033284 1 0 1 1 0 0 +EDGE2 8944 6243 -1.00419 -0.00155335 -0.00174714 1 0 1 1 0 0 +EDGE2 8945 6044 0.958882 0.0997554 -3.13212 1 0 1 1 0 0 +EDGE2 8945 6084 0.971824 -0.0296542 -3.15998 1 0 1 1 0 0 +EDGE2 8945 6224 1.03524 -0.0590227 -3.14182 1 0 1 1 0 0 +EDGE2 8945 6264 1.01901 -0.0217459 -3.12866 1 0 1 1 0 0 +EDGE2 8945 6064 1.05427 0.0477933 -3.12637 1 0 1 1 0 0 +EDGE2 8945 6266 0.0212639 1.00271 1.56721 1 0 1 1 0 0 +EDGE2 8945 6226 0.0246991 1.06131 1.57568 1 0 1 1 0 0 +EDGE2 8945 8944 -0.961494 0.039131 -0.0278268 1 0 1 1 0 0 +EDGE2 8945 6225 -0.0557467 -0.0529636 -3.14718 1 0 1 1 0 0 +EDGE2 8945 6265 0.100639 0.00904099 -3.12046 1 0 1 1 0 0 +EDGE2 8945 6245 0.0136598 0.0817314 0.0485616 1 0 1 1 0 0 +EDGE2 8945 6045 -0.068583 -0.0280851 -3.15576 1 0 1 1 0 0 +EDGE2 8945 6065 0.0623423 -0.0254919 -3.09878 1 0 1 1 0 0 +EDGE2 8945 6085 0.136322 -0.163629 -3.09587 1 0 1 1 0 0 +EDGE2 8945 605 -0.0849295 0.0532855 -0.0130408 1 0 1 1 0 0 +EDGE2 8945 604 -0.960126 -0.0496652 -0.0209156 1 0 1 1 0 0 +EDGE2 8945 6244 -0.945094 0.0194603 -0.02284 1 0 1 1 0 0 +EDGE2 8945 6046 0.0124317 -0.985057 -1.59773 1 0 1 1 0 0 +EDGE2 8945 6086 -0.0446732 -0.986594 -1.58903 1 0 1 1 0 0 +EDGE2 8945 6246 0.0164513 -0.984288 -1.57613 1 0 1 1 0 0 +EDGE2 8945 6066 -0.012602 -1.05177 -1.59867 1 0 1 1 0 0 +EDGE2 8945 606 -0.0142351 -1.03284 -1.6023 1 0 1 1 0 0 +EDGE2 8946 6225 -0.962965 -0.0222067 -1.57228 1 0 1 1 0 0 +EDGE2 8946 6265 -0.88795 0.0444707 -1.56748 1 0 1 1 0 0 +EDGE2 8946 8945 -0.987621 -0.030531 1.57524 1 0 1 1 0 0 +EDGE2 8946 6245 -1.0507 -0.0227281 1.60885 1 0 1 1 0 0 +EDGE2 8946 6045 -0.996161 0.0166396 -1.58041 1 0 1 1 0 0 +EDGE2 8946 6065 -0.99207 0.0850198 -1.5649 1 0 1 1 0 0 +EDGE2 8946 6085 -1.05083 -0.00725262 -1.55207 1 0 1 1 0 0 +EDGE2 8946 605 -1.06064 0.0622787 1.59151 1 0 1 1 0 0 +EDGE2 8946 607 1.00737 0.0446859 0.0227676 1 0 1 1 0 0 +EDGE2 8946 6067 1.00294 0.0192194 0.0100252 1 0 1 1 0 0 +EDGE2 8946 6046 0.0851443 -0.0204087 -0.0417659 1 0 1 1 0 0 +EDGE2 8946 6086 0.0143388 -0.0806918 0.00847425 1 0 1 1 0 0 +EDGE2 8946 6246 -0.0530797 0.0642878 -0.0287726 1 0 1 1 0 0 +EDGE2 8946 6066 0.00653015 0.011963 0.0104403 1 0 1 1 0 0 +EDGE2 8946 6247 1.04684 0.0207579 0.0116969 1 0 1 1 0 0 +EDGE2 8946 606 -0.00803562 -0.00773163 0.0350823 1 0 1 1 0 0 +EDGE2 8946 6087 0.994964 -0.0191044 0.0123002 1 0 1 1 0 0 +EDGE2 8946 6047 1.01188 0.0512343 -0.0105295 1 0 1 1 0 0 +EDGE2 8947 607 0.0838545 0.0275489 -0.017361 1 0 1 1 0 0 +EDGE2 8947 6067 0.0763725 0.0246436 0.00186654 1 0 1 1 0 0 +EDGE2 8947 6046 -1.05999 0.139146 -0.00368398 1 0 1 1 0 0 +EDGE2 8947 6086 -0.988431 0.00399749 -0.0146881 1 0 1 1 0 0 +EDGE2 8947 6246 -1.07446 0.074815 0.00174159 1 0 1 1 0 0 +EDGE2 8947 8946 -1.07863 0.0300395 0.00139367 1 0 1 1 0 0 +EDGE2 8947 6066 -1.00697 -0.0059092 0.00132982 1 0 1 1 0 0 +EDGE2 8947 6247 -0.0584046 0.0735058 -0.0235688 1 0 1 1 0 0 +EDGE2 8947 606 -0.982591 -0.0595212 0.00182926 1 0 1 1 0 0 +EDGE2 8947 6087 -0.0376172 0.0999095 -0.0129555 1 0 1 1 0 0 +EDGE2 8947 6047 0.011033 0.0254018 -0.0238362 1 0 1 1 0 0 +EDGE2 8947 6068 0.927623 0.0203279 -0.000929785 1 0 1 1 0 0 +EDGE2 8947 6088 1.13088 -0.00971268 -0.0179911 1 0 1 1 0 0 +EDGE2 8947 6248 0.96626 -0.0664526 0.0234426 1 0 1 1 0 0 +EDGE2 8947 608 1.0052 -0.0155336 0.0137449 1 0 1 1 0 0 +EDGE2 8947 6048 1.00715 -0.0422205 -0.00139008 1 0 1 1 0 0 +EDGE2 8948 607 -1.08232 -0.0150769 0.00769964 1 0 1 1 0 0 +EDGE2 8948 6067 -0.955367 0.0300806 -0.030586 1 0 1 1 0 0 +EDGE2 8948 6247 -1.0039 -0.00667492 0.00761538 1 0 1 1 0 0 +EDGE2 8948 8947 -1.07299 0.0448506 -0.0205844 1 0 1 1 0 0 +EDGE2 8948 6087 -0.970545 0.067525 -0.0511992 1 0 1 1 0 0 +EDGE2 8948 6047 -1.05413 0.0593789 -0.00865034 1 0 1 1 0 0 +EDGE2 8948 6068 0.0866102 -0.0441804 0.000493821 1 0 1 1 0 0 +EDGE2 8948 6088 -0.0776584 0.0156794 0.028653 1 0 1 1 0 0 +EDGE2 8948 6248 -0.0531297 0.0550107 0.00540249 1 0 1 1 0 0 +EDGE2 8948 6089 1.00141 -0.0684419 0.00494093 1 0 1 1 0 0 +EDGE2 8948 608 -0.0459279 -0.0758939 0.00834526 1 0 1 1 0 0 +EDGE2 8948 6048 0.0341931 0.0913775 -0.0133035 1 0 1 1 0 0 +EDGE2 8948 6249 1.04085 0.0426986 0.00391186 1 0 1 1 0 0 +EDGE2 8948 6049 0.962542 0.0256943 -0.0111567 1 0 1 1 0 0 +EDGE2 8948 6069 0.979119 0.0718156 0.0157926 1 0 1 1 0 0 +EDGE2 8948 609 0.959666 0.0737207 -0.0111776 1 0 1 1 0 0 +EDGE2 8949 6068 -0.966937 0.0206536 -0.00159717 1 0 1 1 0 0 +EDGE2 8949 6088 -0.992414 -0.0444319 -0.0124302 1 0 1 1 0 0 +EDGE2 8949 6248 -0.961448 -0.0219766 -0.00356032 1 0 1 1 0 0 +EDGE2 8949 8948 -1.02147 -0.0625057 0.000381971 1 0 1 1 0 0 +EDGE2 8949 6089 -0.0122212 -0.0118941 0.0061354 1 0 1 1 0 0 +EDGE2 8949 608 -1.01853 -0.00436446 -0.00320203 1 0 1 1 0 0 +EDGE2 8949 6048 -1.08626 0.0234546 0.00200724 1 0 1 1 0 0 +EDGE2 8949 6249 0.0148294 -0.0145629 -0.048913 1 0 1 1 0 0 +EDGE2 8949 6049 0.0260613 0.0288665 -0.00136348 1 0 1 1 0 0 +EDGE2 8949 6069 -0.0422059 -0.0272198 -0.0231392 1 0 1 1 0 0 +EDGE2 8949 609 -0.089848 0.022803 0.0176125 1 0 1 1 0 0 +EDGE2 8949 6050 0.95898 0.0261306 0.0104021 1 0 1 1 0 0 +EDGE2 8949 6090 1.10567 -0.0196733 0.0212829 1 0 1 1 0 0 +EDGE2 8949 6250 0.943235 -0.0809683 -0.0318399 1 0 1 1 0 0 +EDGE2 8949 8870 1.03661 0.0719343 -3.16645 1 0 1 1 0 0 +EDGE2 8949 6070 1.04505 -0.0159594 0.0106541 1 0 1 1 0 0 +EDGE2 8949 610 0.979318 0.00995184 -0.00473194 1 0 1 1 0 0 +EDGE2 8949 6030 0.932035 -0.0317437 -3.17185 1 0 1 1 0 0 +EDGE2 8950 6251 -0.0770249 0.96314 1.61703 1 0 1 1 0 0 +EDGE2 8950 6051 -0.0887751 1.00045 1.55824 1 0 1 1 0 0 +EDGE2 8950 6071 0.016833 0.950726 1.61323 1 0 1 1 0 0 +EDGE2 8950 6091 -0.018995 1.0467 1.55358 1 0 1 1 0 0 +EDGE2 8950 6031 0.023809 1.02192 1.5377 1 0 1 1 0 0 +EDGE2 8950 6089 -1.00378 -0.00961377 -0.0227752 1 0 1 1 0 0 +EDGE2 8950 8949 -0.941002 -0.0153974 -0.0374302 1 0 1 1 0 0 +EDGE2 8950 6249 -1.05133 -0.00260468 -0.00423292 1 0 1 1 0 0 +EDGE2 8950 6049 -1.01878 0.0780291 -0.029549 1 0 1 1 0 0 +EDGE2 8950 6069 -0.958069 0.0950364 -0.0223757 1 0 1 1 0 0 +EDGE2 8950 609 -0.994588 0.0259306 0.0208205 1 0 1 1 0 0 +EDGE2 8950 6050 -0.0670612 -0.00217004 0.0162753 1 0 1 1 0 0 +EDGE2 8950 6090 -0.0792154 0.00766915 -0.00939096 1 0 1 1 0 0 +EDGE2 8950 6250 0.0602804 0.0400566 -0.00956351 1 0 1 1 0 0 +EDGE2 8950 8870 -0.0107412 0.0733768 -3.12806 1 0 1 1 0 0 +EDGE2 8950 6070 0.0283361 0.0135037 0.0044129 1 0 1 1 0 0 +EDGE2 8950 8869 1.00293 -0.0888175 -3.15083 1 0 1 1 0 0 +EDGE2 8950 610 0.0618242 0.0375624 0.0377493 1 0 1 1 0 0 +EDGE2 8950 6030 0.0182725 -0.0413073 -3.15641 1 0 1 1 0 0 +EDGE2 8950 6029 1.02484 -0.0680093 -3.12558 1 0 1 1 0 0 +EDGE2 8950 611 0.0290324 -1.0291 -1.55763 1 0 1 1 0 0 +EDGE2 8950 8871 0.021185 -0.990264 -1.58809 1 0 1 1 0 0 +EDGE2 8951 6032 0.976146 -0.00991861 0.0336777 1 0 1 1 0 0 +EDGE2 8951 6252 1.02986 0.028854 0.00433981 1 0 1 1 0 0 +EDGE2 8951 6072 1.06167 0.0540585 -0.00229609 1 0 1 1 0 0 +EDGE2 8951 6092 1.01532 0.058077 0.000363286 1 0 1 1 0 0 +EDGE2 8951 6052 0.951872 -0.0321257 0.000261572 1 0 1 1 0 0 +EDGE2 8951 8950 -1.01345 0.051637 -1.57225 1 0 1 1 0 0 +EDGE2 8951 6251 0.0403756 0.0439944 -0.0298808 1 0 1 1 0 0 +EDGE2 8951 6051 0.0515467 0.00911371 0.0465763 1 0 1 1 0 0 +EDGE2 8951 6071 -0.0455795 -0.0512162 0.00751661 1 0 1 1 0 0 +EDGE2 8951 6091 0.0654944 -0.0125303 0.0181364 1 0 1 1 0 0 +EDGE2 8951 6031 -0.00767488 -0.0665828 0.0496941 1 0 1 1 0 0 +EDGE2 8951 6050 -1.05305 0.0421583 -1.56374 1 0 1 1 0 0 +EDGE2 8951 6090 -0.986977 -0.0140691 -1.55633 1 0 1 1 0 0 +EDGE2 8951 6250 -0.928187 0.0280362 -1.55082 1 0 1 1 0 0 +EDGE2 8951 8870 -1.05803 -0.00745018 1.55337 1 0 1 1 0 0 +EDGE2 8951 6070 -1.01099 -0.0174603 -1.58133 1 0 1 1 0 0 +EDGE2 8951 610 -0.954179 0.0271539 -1.5667 1 0 1 1 0 0 +EDGE2 8951 6030 -0.983808 -0.0255149 1.59618 1 0 1 1 0 0 +EDGE2 8952 6032 0.0228814 -0.0109996 -0.00807632 1 0 1 1 0 0 +EDGE2 8952 6093 0.962562 -0.0146852 0.000687847 1 0 1 1 0 0 +EDGE2 8952 6253 1.00927 -0.0276943 0.0206535 1 0 1 1 0 0 +EDGE2 8952 6252 0.00317599 0.0212897 -3.03141e-05 1 0 1 1 0 0 +EDGE2 8952 6033 1.04185 0.0639365 -0.00655131 1 0 1 1 0 0 +EDGE2 8952 6053 0.992417 -0.0379671 0.00641209 1 0 1 1 0 0 +EDGE2 8952 6073 1.0744 -0.0166277 0.00432908 1 0 1 1 0 0 +EDGE2 8952 6072 -0.0148233 -0.00124038 -0.00548684 1 0 1 1 0 0 +EDGE2 8952 6092 0.0197531 -0.0493777 0.00380797 1 0 1 1 0 0 +EDGE2 8952 6052 0.0240634 0.0287713 -0.00211724 1 0 1 1 0 0 +EDGE2 8952 6251 -1.02325 0.0723604 -0.0187438 1 0 1 1 0 0 +EDGE2 8952 8951 -1.01126 0.0899276 -0.0148681 1 0 1 1 0 0 +EDGE2 8952 6051 -0.978238 0.027678 0.00615835 1 0 1 1 0 0 +EDGE2 8952 6071 -0.922397 -0.0138495 0.00839162 1 0 1 1 0 0 +EDGE2 8952 6091 -0.972322 0.079252 0.00608109 1 0 1 1 0 0 +EDGE2 8952 6031 -1.02791 -0.0270334 -0.0155497 1 0 1 1 0 0 +EDGE2 8953 6032 -1.04449 0.0588473 -0.00907568 1 0 1 1 0 0 +EDGE2 8953 6094 0.912598 0.016816 -0.0320592 1 0 1 1 0 0 +EDGE2 8953 6254 1.00077 -0.0606489 -0.00687653 1 0 1 1 0 0 +EDGE2 8953 6093 0.0424491 -0.011143 -0.01868 1 0 1 1 0 0 +EDGE2 8953 6253 0.0560998 -0.0153259 0.00639372 1 0 1 1 0 0 +EDGE2 8953 6034 0.974139 0.0543471 -0.0104091 1 0 1 1 0 0 +EDGE2 8953 6054 0.97978 0.0439003 -0.00277605 1 0 1 1 0 0 +EDGE2 8953 6074 0.99758 -0.0600117 -0.00294841 1 0 1 1 0 0 +EDGE2 8953 6252 -1.03024 0.0395923 -0.0158659 1 0 1 1 0 0 +EDGE2 8953 6033 -0.0100606 -0.122424 -0.0186503 1 0 1 1 0 0 +EDGE2 8953 6053 0.0233078 0.0146469 0.0181302 1 0 1 1 0 0 +EDGE2 8953 6073 -0.00398614 0.0258749 -0.031996 1 0 1 1 0 0 +EDGE2 8953 8952 -1.01112 0.0287253 0.00936248 1 0 1 1 0 0 +EDGE2 8953 6072 -0.995335 -0.062396 0.0122388 1 0 1 1 0 0 +EDGE2 8953 6092 -0.991247 -0.00915944 0.0132789 1 0 1 1 0 0 +EDGE2 8953 6052 -0.95467 0.0428794 0.030868 1 0 1 1 0 0 +EDGE2 8954 6094 -0.00679751 0.0582662 0.00208052 1 0 1 1 0 0 +EDGE2 8954 6075 0.958066 0.0360821 -0.0469285 1 0 1 1 0 0 +EDGE2 8954 6255 0.93976 -0.0209498 -0.0150768 1 0 1 1 0 0 +EDGE2 8954 6095 0.961106 0.0157663 -0.00464708 1 0 1 1 0 0 +EDGE2 8954 6035 0.873103 -0.076497 -0.00264503 1 0 1 1 0 0 +EDGE2 8954 6055 0.954692 0.10067 0.0178145 1 0 1 1 0 0 +EDGE2 8954 6254 0.0674331 -0.0348109 0.00992262 1 0 1 1 0 0 +EDGE2 8954 6093 -1.02022 0.0578339 0.0146623 1 0 1 1 0 0 +EDGE2 8954 6253 -1.03238 -0.0252397 -0.0277555 1 0 1 1 0 0 +EDGE2 8954 6034 -0.0433269 -0.0816685 -0.0161771 1 0 1 1 0 0 +EDGE2 8954 6054 -0.0735326 0.0655509 0.0202039 1 0 1 1 0 0 +EDGE2 8954 6074 -0.0102611 -0.0120516 0.0112511 1 0 1 1 0 0 +EDGE2 8954 8953 -0.91012 -0.0408736 0.011877 1 0 1 1 0 0 +EDGE2 8954 6033 -0.993113 -0.00419254 -0.0246631 1 0 1 1 0 0 +EDGE2 8954 6053 -0.999034 -0.101905 -0.0482332 1 0 1 1 0 0 +EDGE2 8954 6073 -1.0437 -0.0525386 -0.00230823 1 0 1 1 0 0 +EDGE2 8955 6094 -0.973782 0.0679561 -0.0240951 1 0 1 1 0 0 +EDGE2 8955 6056 0.0398097 0.918429 1.59287 1 0 1 1 0 0 +EDGE2 8955 6096 0.0552728 1.0551 1.56491 1 0 1 1 0 0 +EDGE2 8955 6256 -0.0314784 1.08597 1.54359 1 0 1 1 0 0 +EDGE2 8955 6076 0.0823255 0.996786 1.58089 1 0 1 1 0 0 +EDGE2 8955 6075 0.0173975 0.0254279 -0.0168771 1 0 1 1 0 0 +EDGE2 8955 6255 -0.0472782 0.033145 0.0247472 1 0 1 1 0 0 +EDGE2 8955 6036 -0.0501698 1.05277 1.56193 1 0 1 1 0 0 +EDGE2 8955 6095 -0.0181408 0.0174007 0.0200312 1 0 1 1 0 0 +EDGE2 8955 8954 -0.919808 -0.000369347 -0.0367727 1 0 1 1 0 0 +EDGE2 8955 6035 -0.0451254 -0.0489023 -0.00358052 1 0 1 1 0 0 +EDGE2 8955 6055 -0.0112218 -0.0644217 0.00715736 1 0 1 1 0 0 +EDGE2 8955 6254 -0.960497 0.010385 -0.0211225 1 0 1 1 0 0 +EDGE2 8955 6034 -1.00774 0.10017 -0.0146731 1 0 1 1 0 0 +EDGE2 8955 6054 -0.99438 0.0686503 -0.0226759 1 0 1 1 0 0 +EDGE2 8955 6074 -1.04165 -0.0361591 0.0119847 1 0 1 1 0 0 +EDGE2 8956 6056 -0.0509442 0.0162614 -0.0372776 1 0 1 1 0 0 +EDGE2 8956 6037 0.948649 0.00793995 0.0204295 1 0 1 1 0 0 +EDGE2 8956 6077 1.00464 0.022524 -0.0456276 1 0 1 1 0 0 +EDGE2 8956 6097 1.0062 -0.0297221 -0.0098581 1 0 1 1 0 0 +EDGE2 8956 6257 1.03614 -0.0183236 0.00210467 1 0 1 1 0 0 +EDGE2 8956 6057 0.95917 -0.0734065 -0.023522 1 0 1 1 0 0 +EDGE2 8956 6096 -0.0693216 -0.0135159 0.0142689 1 0 1 1 0 0 +EDGE2 8956 6256 0.00439266 -0.0230227 0.00217557 1 0 1 1 0 0 +EDGE2 8956 6076 0.00546042 0.0569537 0.0207915 1 0 1 1 0 0 +EDGE2 8956 6075 -1.05155 -0.0672301 -1.58577 1 0 1 1 0 0 +EDGE2 8956 6255 -1.02713 -0.0455442 -1.59703 1 0 1 1 0 0 +EDGE2 8956 8955 -1.04971 -0.097272 -1.56665 1 0 1 1 0 0 +EDGE2 8956 6036 0.0893066 -0.018437 0.0187522 1 0 1 1 0 0 +EDGE2 8956 6095 -1.0257 0.0387064 -1.5459 1 0 1 1 0 0 +EDGE2 8956 6035 -1.01516 -0.0608009 -1.57882 1 0 1 1 0 0 +EDGE2 8956 6055 -0.960636 0.0277114 -1.56585 1 0 1 1 0 0 +EDGE2 8957 6078 0.958695 -0.1197 0.0190041 1 0 1 1 0 0 +EDGE2 8957 6258 1.00878 0.0598244 0.0347701 1 0 1 1 0 0 +EDGE2 8957 6098 1.09007 0.0301377 0.023301 1 0 1 1 0 0 +EDGE2 8957 6058 1.00983 0.0538296 0.00546089 1 0 1 1 0 0 +EDGE2 8957 6038 0.944321 -0.00121651 0.0180059 1 0 1 1 0 0 +EDGE2 8957 6056 -1.03704 0.0248212 0.0207626 1 0 1 1 0 0 +EDGE2 8957 6037 -0.00708898 0.0529176 -0.00432702 1 0 1 1 0 0 +EDGE2 8957 6077 0.0681759 0.0375526 -0.0174154 1 0 1 1 0 0 +EDGE2 8957 6097 -0.00431406 0.00254906 0.0202688 1 0 1 1 0 0 +EDGE2 8957 6257 0.0236198 0.0566442 0.036319 1 0 1 1 0 0 +EDGE2 8957 6057 0.015537 0.0503735 0.00115872 1 0 1 1 0 0 +EDGE2 8957 6096 -1.03096 0.00323549 -0.00604476 1 0 1 1 0 0 +EDGE2 8957 6256 -1.03676 0.108158 0.00934004 1 0 1 1 0 0 +EDGE2 8957 8956 -0.977284 0.027473 -0.0150695 1 0 1 1 0 0 +EDGE2 8957 6076 -0.977 0.0402676 0.00965991 1 0 1 1 0 0 +EDGE2 8957 6036 -1.10004 -0.0693579 -0.00571936 1 0 1 1 0 0 +EDGE2 8958 8957 -0.915919 -0.0470013 0.00786651 1 0 1 1 0 0 +EDGE2 8958 6078 -0.0358764 0.0290601 0.00667111 1 0 1 1 0 0 +EDGE2 8958 6059 1.01043 0.0589037 0.0430723 1 0 1 1 0 0 +EDGE2 8958 6099 0.968817 0.00897962 0.0143816 1 0 1 1 0 0 +EDGE2 8958 6259 1.02208 -0.0243426 0.0113009 1 0 1 1 0 0 +EDGE2 8958 6079 0.93641 -0.0646443 0.0128672 1 0 1 1 0 0 +EDGE2 8958 6258 0.00929575 -0.0588373 0.00714427 1 0 1 1 0 0 +EDGE2 8958 6039 1.01233 0.00943129 -0.0300298 1 0 1 1 0 0 +EDGE2 8958 6098 0.0220965 -0.021737 -0.01908 1 0 1 1 0 0 +EDGE2 8958 6058 -0.0149786 -0.038739 0.0101223 1 0 1 1 0 0 +EDGE2 8958 6038 -0.0280385 -0.0914307 0.0301665 1 0 1 1 0 0 +EDGE2 8958 6037 -1.08261 -0.0694746 0.0250199 1 0 1 1 0 0 +EDGE2 8958 6077 -0.91942 -0.0197731 -0.0267363 1 0 1 1 0 0 +EDGE2 8958 6097 -0.940455 -0.0624655 -0.0242078 1 0 1 1 0 0 +EDGE2 8958 6257 -1.00686 -0.0500379 0.0270715 1 0 1 1 0 0 +EDGE2 8958 6057 -0.955565 0.0281104 -0.0217654 1 0 1 1 0 0 +EDGE2 8959 6100 1.02041 0.0166076 0.0162858 1 0 1 1 0 0 +EDGE2 8959 6220 0.94568 0.0718679 -3.15426 1 0 1 1 0 0 +EDGE2 8959 6260 1.11046 -0.0155843 0.0107925 1 0 1 1 0 0 +EDGE2 8959 6200 0.949446 -0.0232991 -3.15757 1 0 1 1 0 0 +EDGE2 8959 6040 0.993981 -0.0191418 -0.01822 1 0 1 1 0 0 +EDGE2 8959 6060 1.01567 0.0113538 0.00367977 1 0 1 1 0 0 +EDGE2 8959 6080 1.05553 -0.126233 -0.0422527 1 0 1 1 0 0 +EDGE2 8959 6078 -1.0008 -0.0197693 0.0251848 1 0 1 1 0 0 +EDGE2 8959 6059 0.013029 -0.0172917 0.0200282 1 0 1 1 0 0 +EDGE2 8959 6099 -0.0546491 0.0120604 -0.0207868 1 0 1 1 0 0 +EDGE2 8959 6259 0.0320443 0.0511811 0.0313782 1 0 1 1 0 0 +EDGE2 8959 6079 0.0347639 -0.046449 -0.00185055 1 0 1 1 0 0 +EDGE2 8959 6258 -0.990388 0.010755 0.0145635 1 0 1 1 0 0 +EDGE2 8959 8958 -1.01564 -0.018666 0.00371418 1 0 1 1 0 0 +EDGE2 8959 6039 0.0177404 0.0841086 -0.0417399 1 0 1 1 0 0 +EDGE2 8959 6098 -0.984241 0.0391512 -0.00887217 1 0 1 1 0 0 +EDGE2 8959 6058 -0.978832 0.0400442 0.0142735 1 0 1 1 0 0 +EDGE2 8959 6038 -1.14432 0.0765999 -0.0243461 1 0 1 1 0 0 +EDGE2 8960 6101 0.0226711 -0.948185 -1.57318 1 0 1 1 0 0 +EDGE2 8960 6199 0.950292 0.0598262 -3.1303 1 0 1 1 0 0 +EDGE2 8960 6219 0.964448 0.0355389 -3.17719 1 0 1 1 0 0 +EDGE2 8960 6201 0.09295 -0.998431 -1.54716 1 0 1 1 0 0 +EDGE2 8960 6261 -0.000231991 0.966409 1.56075 1 0 1 1 0 0 +EDGE2 8960 6100 -0.0355768 0.047922 0.0183336 1 0 1 1 0 0 +EDGE2 8960 6220 0.00948125 0.032732 -3.16212 1 0 1 1 0 0 +EDGE2 8960 6260 -0.0130383 -0.00560244 0.00233575 1 0 1 1 0 0 +EDGE2 8960 6200 -0.0825753 -0.0278132 -3.12179 1 0 1 1 0 0 +EDGE2 8960 6040 -0.0165188 0.030386 0.00782505 1 0 1 1 0 0 +EDGE2 8960 6060 0.0252501 0.0479341 0.0194406 1 0 1 1 0 0 +EDGE2 8960 6080 -0.0792434 -0.0799838 0.00710314 1 0 1 1 0 0 +EDGE2 8960 6061 -0.0533039 1.00576 1.555 1 0 1 1 0 0 +EDGE2 8960 6081 0.0224955 0.992182 1.56884 1 0 1 1 0 0 +EDGE2 8960 6221 -0.0315448 0.977165 1.58311 1 0 1 1 0 0 +EDGE2 8960 6041 0.0639997 0.976621 1.56035 1 0 1 1 0 0 +EDGE2 8960 6059 -0.969626 0.0296256 -0.0337928 1 0 1 1 0 0 +EDGE2 8960 6099 -0.942273 -0.00619382 0.0226894 1 0 1 1 0 0 +EDGE2 8960 6259 -1.02444 0.0138199 0.0295862 1 0 1 1 0 0 +EDGE2 8960 8959 -0.965912 -0.00276171 -0.0338966 1 0 1 1 0 0 +EDGE2 8960 6079 -1.04145 -0.018392 -0.0281499 1 0 1 1 0 0 +EDGE2 8960 6039 -0.985715 -0.017799 -0.0141892 1 0 1 1 0 0 +EDGE2 8961 6042 0.969433 -0.0739184 -0.0107976 1 0 1 1 0 0 +EDGE2 8961 6261 -0.0454599 -0.016671 -0.00950161 1 0 1 1 0 0 +EDGE2 8961 6100 -0.999882 -0.0750078 -1.54874 1 0 1 1 0 0 +EDGE2 8961 6220 -1.02939 -0.112656 1.54254 1 0 1 1 0 0 +EDGE2 8961 6260 -1.01581 -0.00280097 -1.56393 1 0 1 1 0 0 +EDGE2 8961 8960 -1.05656 0.0484386 -1.54015 1 0 1 1 0 0 +EDGE2 8961 6200 -0.99512 -0.0196346 1.56238 1 0 1 1 0 0 +EDGE2 8961 6040 -0.99232 -0.0173998 -1.57643 1 0 1 1 0 0 +EDGE2 8961 6060 -1.03277 0.000713709 -1.55258 1 0 1 1 0 0 +EDGE2 8961 6080 -0.932683 -0.032906 -1.58239 1 0 1 1 0 0 +EDGE2 8961 6061 -0.060704 0.069351 0.00800104 1 0 1 1 0 0 +EDGE2 8961 6081 0.0348163 -0.0707002 0.0138872 1 0 1 1 0 0 +EDGE2 8961 6221 0.037746 -0.0525678 -0.0299563 1 0 1 1 0 0 +EDGE2 8961 6041 -0.0291302 -0.0439324 0.0193923 1 0 1 1 0 0 +EDGE2 8961 6082 1.02383 -0.0374384 -0.0183861 1 0 1 1 0 0 +EDGE2 8961 6222 0.975872 0.000864184 -0.0565484 1 0 1 1 0 0 +EDGE2 8961 6262 0.996184 -0.0746352 -0.0153011 1 0 1 1 0 0 +EDGE2 8961 6062 0.985858 -0.0203465 0.00850661 1 0 1 1 0 0 +EDGE2 8962 6042 -0.0189787 0.0519001 0.0406136 1 0 1 1 0 0 +EDGE2 8962 6261 -1.15755 -0.0696211 0.0267406 1 0 1 1 0 0 +EDGE2 8962 8961 -1.02318 -0.0205912 -0.000991937 1 0 1 1 0 0 +EDGE2 8962 6061 -0.990107 0.0387082 -0.029042 1 0 1 1 0 0 +EDGE2 8962 6081 -1.02988 -0.0682257 -0.016253 1 0 1 1 0 0 +EDGE2 8962 6221 -0.977344 -0.00916884 0.000852269 1 0 1 1 0 0 +EDGE2 8962 6041 -0.987207 0.0277359 -0.0100087 1 0 1 1 0 0 +EDGE2 8962 6082 -0.0952519 0.0158914 0.0276624 1 0 1 1 0 0 +EDGE2 8962 6222 0.00470281 -0.00621851 -0.019331 1 0 1 1 0 0 +EDGE2 8962 6262 0.070442 0.00747588 -0.00771662 1 0 1 1 0 0 +EDGE2 8962 6062 0.0290738 -0.0448667 -0.00807864 1 0 1 1 0 0 +EDGE2 8962 6063 1.07948 0.142132 0.0300174 1 0 1 1 0 0 +EDGE2 8962 6223 1.0504 -0.0138151 -0.0307972 1 0 1 1 0 0 +EDGE2 8962 6263 0.997588 0.0692003 -0.00138568 1 0 1 1 0 0 +EDGE2 8962 6083 0.946715 0.0135494 -0.00542219 1 0 1 1 0 0 +EDGE2 8962 6043 1.03161 0.0577539 -0.0136561 1 0 1 1 0 0 +EDGE2 8963 6042 -1.05277 -0.0195927 -0.0219065 1 0 1 1 0 0 +EDGE2 8963 8962 -0.911096 0.0255517 0.0105473 1 0 1 1 0 0 +EDGE2 8963 6082 -0.958433 -0.0152251 0.0190058 1 0 1 1 0 0 +EDGE2 8963 6222 -0.984606 -0.00457436 -0.0129318 1 0 1 1 0 0 +EDGE2 8963 6262 -0.919649 -0.0171975 -0.00448767 1 0 1 1 0 0 +EDGE2 8963 6062 -0.934176 0.0452855 -0.0281098 1 0 1 1 0 0 +EDGE2 8963 6063 0.0529395 0.0367915 0.00504897 1 0 1 1 0 0 +EDGE2 8963 6223 -0.104366 0.00668236 -0.0123874 1 0 1 1 0 0 +EDGE2 8963 6263 0.0625113 -0.0798308 0.0164898 1 0 1 1 0 0 +EDGE2 8963 6083 -0.0504742 0.0633349 0.0226545 1 0 1 1 0 0 +EDGE2 8963 6043 0.0432568 -0.00579065 -0.0191984 1 0 1 1 0 0 +EDGE2 8963 6044 0.970399 -0.095089 -0.0115844 1 0 1 1 0 0 +EDGE2 8963 6084 1.00818 0.0256136 -0.0115348 1 0 1 1 0 0 +EDGE2 8963 6224 0.979905 -0.0570609 0.0255775 1 0 1 1 0 0 +EDGE2 8963 6264 1.08861 0.0449114 0.0231021 1 0 1 1 0 0 +EDGE2 8963 6064 0.98872 -0.017844 -0.0348278 1 0 1 1 0 0 +EDGE2 8964 6063 -0.93107 -0.0463223 -0.0108068 1 0 1 1 0 0 +EDGE2 8964 6223 -0.982202 -0.0217207 0.0174507 1 0 1 1 0 0 +EDGE2 8964 6263 -0.928469 -0.0126232 -0.032087 1 0 1 1 0 0 +EDGE2 8964 8963 -1.03171 -0.046253 -0.0146013 1 0 1 1 0 0 +EDGE2 8964 6083 -0.980581 0.0411601 -0.0199084 1 0 1 1 0 0 +EDGE2 8964 6043 -1.04254 0.0326246 -0.0124419 1 0 1 1 0 0 +EDGE2 8964 6044 -0.00703111 0.0650887 0.0457169 1 0 1 1 0 0 +EDGE2 8964 6084 0.116225 -0.0326238 -0.0342271 1 0 1 1 0 0 +EDGE2 8964 6224 0.00530982 -0.0245979 -0.000600631 1 0 1 1 0 0 +EDGE2 8964 6264 -0.198932 0.035849 0.00501696 1 0 1 1 0 0 +EDGE2 8964 6064 -0.0219319 0.00492938 -0.0155722 1 0 1 1 0 0 +EDGE2 8964 6225 0.959407 0.0190735 0.00502082 1 0 1 1 0 0 +EDGE2 8964 6265 1.07004 -0.00338564 -0.0111345 1 0 1 1 0 0 +EDGE2 8964 8945 0.982434 0.0583308 -3.14854 1 0 1 1 0 0 +EDGE2 8964 6245 0.969251 0.0557997 -3.08002 1 0 1 1 0 0 +EDGE2 8964 6045 0.960041 -0.0346111 0.000860459 1 0 1 1 0 0 +EDGE2 8964 6065 0.962063 0.00542332 -0.00634457 1 0 1 1 0 0 +EDGE2 8964 6085 0.945989 0.0152721 -0.00661305 1 0 1 1 0 0 +EDGE2 8964 605 0.957413 0.033293 -3.16655 1 0 1 1 0 0 +EDGE2 8965 6044 -0.997574 0.0892799 0.0187339 1 0 1 1 0 0 +EDGE2 8965 8964 -0.96496 0.0321768 0.026778 1 0 1 1 0 0 +EDGE2 8965 6084 -1.08448 -0.0406051 -0.0102538 1 0 1 1 0 0 +EDGE2 8965 6224 -1.01835 0.0591054 -0.0072314 1 0 1 1 0 0 +EDGE2 8965 6264 -0.947595 -0.0500462 -0.0131168 1 0 1 1 0 0 +EDGE2 8965 6064 -0.981326 -0.0497987 -0.0447954 1 0 1 1 0 0 +EDGE2 8965 6266 0.0326996 -1.08702 -1.53396 1 0 1 1 0 0 +EDGE2 8965 6226 -0.0746482 -1.02539 -1.55677 1 0 1 1 0 0 +EDGE2 8965 8944 1.08781 0.0303371 -3.14225 1 0 1 1 0 0 +EDGE2 8965 6225 -0.0463255 0.0702551 0.0269722 1 0 1 1 0 0 +EDGE2 8965 6265 -0.0693752 -0.0444994 0.00662317 1 0 1 1 0 0 +EDGE2 8965 8945 -0.0494657 -0.0309039 -3.16019 1 0 1 1 0 0 +EDGE2 8965 6245 -0.0634653 -0.0194086 -3.13551 1 0 1 1 0 0 +EDGE2 8965 6045 -0.0442752 0.0699613 0.0100174 1 0 1 1 0 0 +EDGE2 8965 6065 0.0821632 -0.0600417 0.0109082 1 0 1 1 0 0 +EDGE2 8965 6085 -0.0132971 -0.0635026 -0.00800486 1 0 1 1 0 0 +EDGE2 8965 605 -0.00264316 0.081237 -3.11639 1 0 1 1 0 0 +EDGE2 8965 604 1.03299 0.0318923 -3.13376 1 0 1 1 0 0 +EDGE2 8965 6244 0.980514 0.0198365 -3.12269 1 0 1 1 0 0 +EDGE2 8965 6046 0.0218677 1.04623 1.56357 1 0 1 1 0 0 +EDGE2 8965 6086 0.00150013 1.03624 1.55286 1 0 1 1 0 0 +EDGE2 8965 6246 -0.0828861 1.0218 1.54359 1 0 1 1 0 0 +EDGE2 8965 8946 -0.0806343 1.08505 1.56818 1 0 1 1 0 0 +EDGE2 8965 6066 -0.0344678 0.959443 1.58026 1 0 1 1 0 0 +EDGE2 8965 606 0.00276044 1.0365 1.566 1 0 1 1 0 0 +EDGE2 8966 6267 1.00119 -0.0348948 0.0112328 1 0 1 1 0 0 +EDGE2 8966 6266 -0.00541254 -0.0418968 0.00510777 1 0 1 1 0 0 +EDGE2 8966 6227 1.01959 -0.0169571 0.00416545 1 0 1 1 0 0 +EDGE2 8966 6226 0.00220809 0.0258745 0.00405597 1 0 1 1 0 0 +EDGE2 8966 6225 -1.00161 0.0651155 1.54357 1 0 1 1 0 0 +EDGE2 8966 6265 -1.04098 0.00216337 1.57242 1 0 1 1 0 0 +EDGE2 8966 8945 -1.06535 -0.0808982 -1.56713 1 0 1 1 0 0 +EDGE2 8966 8965 -1.09575 -0.00319614 1.58409 1 0 1 1 0 0 +EDGE2 8966 6245 -1.02952 0.0353446 -1.57601 1 0 1 1 0 0 +EDGE2 8966 6045 -0.99437 0.00593085 1.59059 1 0 1 1 0 0 +EDGE2 8966 6065 -0.933845 -0.121518 1.53965 1 0 1 1 0 0 +EDGE2 8966 6085 -1.04404 -0.00273184 1.56747 1 0 1 1 0 0 +EDGE2 8966 605 -1.05411 0.00770263 -1.56252 1 0 1 1 0 0 +EDGE2 8967 6268 1.05402 -0.0100966 0.00492586 1 0 1 1 0 0 +EDGE2 8967 6267 0.0552975 -0.00415551 -0.00977802 1 0 1 1 0 0 +EDGE2 8967 6228 1.08274 0.0613305 0.0107063 1 0 1 1 0 0 +EDGE2 8967 6266 -0.906333 -0.00262572 0.0292365 1 0 1 1 0 0 +EDGE2 8967 8966 -1.04343 0.0103296 0.0116991 1 0 1 1 0 0 +EDGE2 8967 6227 0.0492554 -0.0452385 0.010418 1 0 1 1 0 0 +EDGE2 8967 6226 -1.02814 0.135673 0.0124474 1 0 1 1 0 0 +EDGE2 8968 6268 -0.046993 0.0108672 0.00281304 1 0 1 1 0 0 +EDGE2 8968 6229 1.04612 0.0312991 0.0601583 1 0 1 1 0 0 +EDGE2 8968 6269 0.938683 0.0411929 -0.00423995 1 0 1 1 0 0 +EDGE2 8968 6267 -1.01281 0.0271513 0.0228971 1 0 1 1 0 0 +EDGE2 8968 6228 -0.0114288 -0.0250306 0.0291987 1 0 1 1 0 0 +EDGE2 8968 8967 -0.999802 0.0118298 0.0348535 1 0 1 1 0 0 +EDGE2 8968 6227 -0.958719 -0.0504706 0.01906 1 0 1 1 0 0 +EDGE2 8969 6230 0.999668 -0.0740294 -0.0211325 1 0 1 1 0 0 +EDGE2 8969 6270 1.03371 0.0278846 -0.0382708 1 0 1 1 0 0 +EDGE2 8969 590 1.03509 -0.0169945 -3.11296 1 0 1 1 0 0 +EDGE2 8969 6268 -0.985162 -0.0309143 0.0247582 1 0 1 1 0 0 +EDGE2 8969 6229 0.0515066 0.00368088 -0.0232057 1 0 1 1 0 0 +EDGE2 8969 6269 -0.103796 -0.0463118 0.0203734 1 0 1 1 0 0 +EDGE2 8969 8968 -1.02021 0.00433054 -0.0123723 1 0 1 1 0 0 +EDGE2 8969 6228 -0.875636 0.0276449 0.00431117 1 0 1 1 0 0 +EDGE2 8970 591 -0.0669284 0.984891 1.57029 1 0 1 1 0 0 +EDGE2 8970 6230 0.0286631 0.000754022 0.000546151 1 0 1 1 0 0 +EDGE2 8970 589 1.05032 -0.030882 -3.16028 1 0 1 1 0 0 +EDGE2 8970 6270 -0.10052 0.0803865 -0.0162914 1 0 1 1 0 0 +EDGE2 8970 6231 -0.00656857 0.932743 1.56265 1 0 1 1 0 0 +EDGE2 8970 6271 0.0117102 1.03737 1.55111 1 0 1 1 0 0 +EDGE2 8970 590 0.0331427 0.0186005 -3.14983 1 0 1 1 0 0 +EDGE2 8970 6229 -1.01711 -0.050244 -0.0149638 1 0 1 1 0 0 +EDGE2 8970 6269 -0.990068 -0.0370312 -0.00522256 1 0 1 1 0 0 +EDGE2 8970 8969 -1.03353 -0.105412 -0.0244086 1 0 1 1 0 0 +EDGE2 8971 592 1.02663 0.0533494 0.0159702 1 0 1 1 0 0 +EDGE2 8971 591 0.119696 0.0236179 0.00150436 1 0 1 1 0 0 +EDGE2 8971 6230 -0.924769 0.0114153 -1.5797 1 0 1 1 0 0 +EDGE2 8971 8970 -1.02296 0.0500767 -1.56878 1 0 1 1 0 0 +EDGE2 8971 6270 -0.968612 0.0562112 -1.59056 1 0 1 1 0 0 +EDGE2 8971 6231 -0.0643489 -0.0110729 0.0393497 1 0 1 1 0 0 +EDGE2 8971 6271 -0.0195577 0.0308357 -0.0642089 1 0 1 1 0 0 +EDGE2 8971 590 -1.08983 -0.0944651 1.59946 1 0 1 1 0 0 +EDGE2 8971 6232 0.994978 0.08738 0.0268427 1 0 1 1 0 0 +EDGE2 8971 6272 1.04627 -0.0897095 -0.00851607 1 0 1 1 0 0 +EDGE2 8972 592 0.0224971 0.0528192 0.00697977 1 0 1 1 0 0 +EDGE2 8972 591 -0.977166 -0.0232674 -0.0104667 1 0 1 1 0 0 +EDGE2 8972 6231 -0.935231 -0.0252172 0.013796 1 0 1 1 0 0 +EDGE2 8972 6271 -1.08244 0.00483875 -0.0115897 1 0 1 1 0 0 +EDGE2 8972 8971 -1.06424 -0.0815266 -0.0259834 1 0 1 1 0 0 +EDGE2 8972 6273 0.899719 0.00744047 0.0169008 1 0 1 1 0 0 +EDGE2 8972 6232 -0.00615612 -0.0102417 -0.0165424 1 0 1 1 0 0 +EDGE2 8972 6272 0.0215996 -0.00331185 -0.0132959 1 0 1 1 0 0 +EDGE2 8972 6233 1.02433 -0.0315189 -0.00905593 1 0 1 1 0 0 +EDGE2 8972 593 1.06555 0.00325254 0.0203474 1 0 1 1 0 0 +EDGE2 8973 592 -1.01723 0.0418822 -0.029749 1 0 1 1 0 0 +EDGE2 8973 6273 -0.0764181 -0.00891052 -0.00246146 1 0 1 1 0 0 +EDGE2 8973 6232 -0.943308 -0.0333192 0.0151704 1 0 1 1 0 0 +EDGE2 8973 6272 -1.04233 -0.0650142 0.0175277 1 0 1 1 0 0 +EDGE2 8973 8972 -1.00453 0.04127 0.0248356 1 0 1 1 0 0 +EDGE2 8973 6274 1.01999 -0.0227083 -0.0417385 1 0 1 1 0 0 +EDGE2 8973 6233 0.00612671 0.0483229 0.0306042 1 0 1 1 0 0 +EDGE2 8973 6234 1.03719 -0.0190664 0.0241535 1 0 1 1 0 0 +EDGE2 8973 594 1.05919 -0.0299377 0.0357438 1 0 1 1 0 0 +EDGE2 8973 593 0.0142004 -0.0213322 0.0414964 1 0 1 1 0 0 +EDGE2 8974 6273 -1.00361 -0.0578319 0.00854992 1 0 1 1 0 0 +EDGE2 8974 8973 -1.02706 0.029833 -0.0211608 1 0 1 1 0 0 +EDGE2 8974 6274 0.0316141 -0.0686636 -3.9855e-07 1 0 1 1 0 0 +EDGE2 8974 6233 -1.04588 0.00767111 0.0184996 1 0 1 1 0 0 +EDGE2 8974 6234 -0.0834578 -0.0429018 0.0193322 1 0 1 1 0 0 +EDGE2 8974 594 -0.0224544 0.0494867 -0.0265955 1 0 1 1 0 0 +EDGE2 8974 593 -0.948892 -0.0344301 0.0242524 1 0 1 1 0 0 +EDGE2 8974 6315 0.935806 0.0315023 -3.11079 1 0 1 1 0 0 +EDGE2 8974 6235 1.03726 -0.0318082 0.00460862 1 0 1 1 0 0 +EDGE2 8974 6275 0.984346 0.0128828 0.00625362 1 0 1 1 0 0 +EDGE2 8974 595 1.01769 -0.0743957 0.0129909 1 0 1 1 0 0 +EDGE2 8975 6274 -0.95781 -0.0739552 -0.0193438 1 0 1 1 0 0 +EDGE2 8975 8974 -1.09338 -0.070909 -0.0161129 1 0 1 1 0 0 +EDGE2 8975 6234 -0.941365 -0.0116949 -0.0291419 1 0 1 1 0 0 +EDGE2 8975 594 -1.06256 0.06167 0.016726 1 0 1 1 0 0 +EDGE2 8975 6316 -0.0563545 -0.974238 -1.54042 1 0 1 1 0 0 +EDGE2 8975 6276 -0.000326516 -0.964913 -1.55705 1 0 1 1 0 0 +EDGE2 8975 596 0.00188954 0.961559 1.54892 1 0 1 1 0 0 +EDGE2 8975 6314 0.956092 -0.0285627 -3.14024 1 0 1 1 0 0 +EDGE2 8975 6315 0.00907147 0.0729677 -3.16228 1 0 1 1 0 0 +EDGE2 8975 6235 0.00853209 -0.0259021 0.0208538 1 0 1 1 0 0 +EDGE2 8975 6275 0.0158359 0.0409839 -0.0279784 1 0 1 1 0 0 +EDGE2 8975 595 0.0538444 0.0768153 0.0261829 1 0 1 1 0 0 +EDGE2 8975 6236 0.0659195 0.985141 1.60029 1 0 1 1 0 0 +EDGE2 8976 8975 -0.901923 0.0414171 1.57905 1 0 1 1 0 0 +EDGE2 8976 6316 0.063444 0.0266826 -0.00709571 1 0 1 1 0 0 +EDGE2 8976 6317 1.02538 -0.0229276 0.00409647 1 0 1 1 0 0 +EDGE2 8976 6277 0.952382 0.00273741 0.0217118 1 0 1 1 0 0 +EDGE2 8976 6276 -0.0443875 0.0672991 -0.00863339 1 0 1 1 0 0 +EDGE2 8976 6315 -0.977308 -0.0181241 -1.58117 1 0 1 1 0 0 +EDGE2 8976 6235 -0.9962 0.0119214 1.57672 1 0 1 1 0 0 +EDGE2 8976 6275 -0.989996 -0.0169604 1.59481 1 0 1 1 0 0 +EDGE2 8976 595 -0.922396 0.0401036 1.56885 1 0 1 1 0 0 +EDGE2 8977 6316 -0.967778 -0.0208307 -0.011391 1 0 1 1 0 0 +EDGE2 8977 6278 0.998529 -0.0201707 0.00458142 1 0 1 1 0 0 +EDGE2 8977 6318 1.03974 0.0620749 -0.00248354 1 0 1 1 0 0 +EDGE2 8977 8976 -0.939063 -0.0258127 -0.022406 1 0 1 1 0 0 +EDGE2 8977 6317 -0.0187229 0.0143249 0.00589132 1 0 1 1 0 0 +EDGE2 8977 6277 0.0849283 0.0695145 0.0325149 1 0 1 1 0 0 +EDGE2 8977 6276 -1.02579 0.0249148 -0.00758853 1 0 1 1 0 0 +EDGE2 8978 6279 1.00165 -0.0116567 -0.0192383 1 0 1 1 0 0 +EDGE2 8978 8977 -1.00969 -0.054487 0.00175148 1 0 1 1 0 0 +EDGE2 8978 6278 -0.0429395 -0.0874533 -0.00651069 1 0 1 1 0 0 +EDGE2 8978 6319 0.979944 0.0266244 -0.0249866 1 0 1 1 0 0 +EDGE2 8978 6318 0.0874528 -0.0406851 -0.00474188 1 0 1 1 0 0 +EDGE2 8978 6317 -1.05099 -0.0320357 0.014654 1 0 1 1 0 0 +EDGE2 8978 6277 -1.02783 -0.0834704 -0.0293771 1 0 1 1 0 0 +EDGE2 8979 6279 0.0299965 0.0514588 -0.0141138 1 0 1 1 0 0 +EDGE2 8979 6300 1.00912 0.041721 -3.1601 1 0 1 1 0 0 +EDGE2 8979 6280 0.956675 0.088588 -0.00482048 1 0 1 1 0 0 +EDGE2 8979 6320 1.07841 -0.00510319 0.00256908 1 0 1 1 0 0 +EDGE2 8979 6278 -1.00196 -0.0641012 0.01483 1 0 1 1 0 0 +EDGE2 8979 8978 -0.950632 0.0237131 0.00795033 1 0 1 1 0 0 +EDGE2 8979 6319 -0.0235252 -0.0396067 0.00288571 1 0 1 1 0 0 +EDGE2 8979 6318 -1.02509 -0.00903484 -0.00646025 1 0 1 1 0 0 +EDGE2 8980 6299 1.01254 0.0841873 -3.12721 1 0 1 1 0 0 +EDGE2 8980 6281 -0.0271319 -1.13181 -1.60146 1 0 1 1 0 0 +EDGE2 8980 6321 0.0549912 -1.10647 -1.56939 1 0 1 1 0 0 +EDGE2 8980 6279 -1.05625 0.000371497 0.00153191 1 0 1 1 0 0 +EDGE2 8980 6300 -0.0302967 -0.0207838 -3.13896 1 0 1 1 0 0 +EDGE2 8980 6280 0.0604948 0.0265463 -0.0132948 1 0 1 1 0 0 +EDGE2 8980 6320 -0.00452004 -0.0217425 0.011131 1 0 1 1 0 0 +EDGE2 8980 6301 0.0671474 1.00594 1.54264 1 0 1 1 0 0 +EDGE2 8980 8979 -1.0859 0.115897 0.0140778 1 0 1 1 0 0 +EDGE2 8980 6319 -1.07159 -0.0203226 0.00359219 1 0 1 1 0 0 +EDGE2 8981 6300 -1.02156 -0.00551191 1.55337 1 0 1 1 0 0 +EDGE2 8981 8980 -1.0025 0.00988433 -1.61812 1 0 1 1 0 0 +EDGE2 8981 6280 -0.98127 0.0959942 -1.56488 1 0 1 1 0 0 +EDGE2 8981 6320 -0.989761 -0.0310611 -1.56666 1 0 1 1 0 0 +EDGE2 8981 6302 0.921838 -0.000902391 0.0195301 1 0 1 1 0 0 +EDGE2 8981 6301 0.0148925 -0.112601 0.025943 1 0 1 1 0 0 +EDGE2 8982 8981 -1.01575 -0.0156551 -0.0217918 1 0 1 1 0 0 +EDGE2 8982 6302 0.0086533 -0.162807 0.00585314 1 0 1 1 0 0 +EDGE2 8982 6301 -0.985779 0.0796664 0.0054602 1 0 1 1 0 0 +EDGE2 8982 6303 1.03074 0.0765913 0.000674592 1 0 1 1 0 0 +EDGE2 8983 8982 -1.06462 0.0143619 -0.0331612 1 0 1 1 0 0 +EDGE2 8983 6302 -0.925016 0.0365318 -0.021638 1 0 1 1 0 0 +EDGE2 8983 6304 0.984802 0.0282225 0.0122503 1 0 1 1 0 0 +EDGE2 8983 6303 -0.00280514 0.0647876 -0.0232428 1 0 1 1 0 0 +EDGE2 8984 8983 -0.961227 -0.0220982 -0.00307038 1 0 1 1 0 0 +EDGE2 8984 6505 1.03571 -0.00286283 -3.14337 1 0 1 1 0 0 +EDGE2 8984 6485 0.942857 -0.0136021 -3.13982 1 0 1 1 0 0 +EDGE2 8984 6304 -0.0939699 -0.00179012 0.00841276 1 0 1 1 0 0 +EDGE2 8984 6303 -1.00853 -0.0177567 -0.00697244 1 0 1 1 0 0 +EDGE2 8984 6305 0.991554 0.0915716 -0.00822946 1 0 1 1 0 0 +EDGE2 8985 8984 -0.959279 -0.0017703 0.00137714 1 0 1 1 0 0 +EDGE2 8985 6505 -0.0204644 -0.0325608 -3.13141 1 0 1 1 0 0 +EDGE2 8985 6486 -0.0630853 -1.01227 -1.54921 1 0 1 1 0 0 +EDGE2 8985 6506 -0.0290076 -0.977685 -1.54649 1 0 1 1 0 0 +EDGE2 8985 6485 0.00532751 0.0118187 -3.15098 1 0 1 1 0 0 +EDGE2 8985 6304 -0.972411 -0.00244988 -0.00351946 1 0 1 1 0 0 +EDGE2 8985 6305 -0.014183 -0.049375 0.00713024 1 0 1 1 0 0 +EDGE2 8985 6306 0.0615944 0.968753 1.55329 1 0 1 1 0 0 +EDGE2 8985 6484 0.969707 -0.000190624 -3.13878 1 0 1 1 0 0 +EDGE2 8985 6504 0.963863 -0.0326227 -3.15657 1 0 1 1 0 0 +EDGE2 8986 6505 -1.0043 -0.0228065 1.57934 1 0 1 1 0 0 +EDGE2 8986 6485 -0.919405 -0.0791168 1.58333 1 0 1 1 0 0 +EDGE2 8986 8985 -1.00631 -0.0893891 -1.59956 1 0 1 1 0 0 +EDGE2 8986 6305 -0.977639 0.0121242 -1.60723 1 0 1 1 0 0 +EDGE2 8986 6306 -0.100674 0.0321543 -0.012205 1 0 1 1 0 0 +EDGE2 8986 6307 1.05127 0.0164717 -0.0225122 1 0 1 1 0 0 +EDGE2 8987 6306 -0.945636 -0.0208559 -0.00439268 1 0 1 1 0 0 +EDGE2 8987 8986 -1.03704 0.0826675 0.0198677 1 0 1 1 0 0 +EDGE2 8987 6307 -0.124801 -0.0632002 -0.0216683 1 0 1 1 0 0 +EDGE2 8987 6308 1.01119 0.0223493 0.0287093 1 0 1 1 0 0 +EDGE2 8988 8987 -1.01766 0.0370403 0.00228351 1 0 1 1 0 0 +EDGE2 8988 6307 -1.00062 -0.0723308 -0.00525145 1 0 1 1 0 0 +EDGE2 8988 6308 0.0199624 -0.0391204 0.00898333 1 0 1 1 0 0 +EDGE2 8988 6309 0.990995 0.0209723 0.0164714 1 0 1 1 0 0 +EDGE2 8989 8988 -0.989678 -0.0232857 -0.0263772 1 0 1 1 0 0 +EDGE2 8989 6308 -1.00232 -0.0247608 0.00715122 1 0 1 1 0 0 +EDGE2 8989 6309 -0.0547881 0.0246428 -0.0247022 1 0 1 1 0 0 +EDGE2 8989 6310 1.06233 0.0316511 -0.018068 1 0 1 1 0 0 +EDGE2 8989 8910 0.958497 0.022719 -3.17472 1 0 1 1 0 0 +EDGE2 8989 8890 0.986552 0.0475707 -3.15876 1 0 1 1 0 0 +EDGE2 8990 8989 -0.897658 -0.0535031 0.00676966 1 0 1 1 0 0 +EDGE2 8990 6309 -1.10726 -0.104578 -0.0152093 1 0 1 1 0 0 +EDGE2 8990 6311 0.04479 1.03351 1.56988 1 0 1 1 0 0 +EDGE2 8990 6310 -0.0610887 -0.0123572 0.002666 1 0 1 1 0 0 +EDGE2 8990 8910 -0.00924542 -0.00819219 -3.09743 1 0 1 1 0 0 +EDGE2 8990 8890 0.0673903 0.0541714 -3.15655 1 0 1 1 0 0 +EDGE2 8990 8909 0.950502 0.0110789 -3.12781 1 0 1 1 0 0 +EDGE2 8990 8889 0.959209 -0.0678045 -3.11173 1 0 1 1 0 0 +EDGE2 8990 8891 0.011127 -0.990858 -1.58924 1 0 1 1 0 0 +EDGE2 8990 8911 -0.0845236 -0.98945 -1.56096 1 0 1 1 0 0 +EDGE2 8991 6310 -0.964616 -0.013013 1.57185 1 0 1 1 0 0 +EDGE2 8991 8910 -0.926372 0.0478759 -1.60604 1 0 1 1 0 0 +EDGE2 8991 8990 -1.04323 0.0238461 1.57595 1 0 1 1 0 0 +EDGE2 8991 8890 -1.01388 -0.0675191 -1.5537 1 0 1 1 0 0 +EDGE2 8991 8892 0.94144 -0.0149901 0.0353792 1 0 1 1 0 0 +EDGE2 8991 8891 0.0252262 0.000861412 -0.00965177 1 0 1 1 0 0 +EDGE2 8991 8911 0.049692 0.0602754 0.00132541 1 0 1 1 0 0 +EDGE2 8991 8912 0.936523 -0.0241434 -0.0340883 1 0 1 1 0 0 +EDGE2 8992 8892 -0.0127027 0.0106138 -0.0315942 1 0 1 1 0 0 +EDGE2 8992 8891 -0.991597 -0.0161899 -0.00306432 1 0 1 1 0 0 +EDGE2 8992 8991 -0.971106 -0.00982299 -0.015194 1 0 1 1 0 0 +EDGE2 8992 8911 -0.995939 0.00326744 -0.0169175 1 0 1 1 0 0 +EDGE2 8992 8912 0.0713738 0.0544613 -0.0128476 1 0 1 1 0 0 +EDGE2 8992 8893 0.923647 0.000545619 -0.00288452 1 0 1 1 0 0 +EDGE2 8992 8913 0.956733 -0.0304854 -0.0217693 1 0 1 1 0 0 +EDGE2 8993 8914 0.964706 -0.0714841 0.0231676 1 0 1 1 0 0 +EDGE2 8993 8892 -0.95627 0.065273 0.00583684 1 0 1 1 0 0 +EDGE2 8993 8992 -1.00387 -0.0409678 -0.00636186 1 0 1 1 0 0 +EDGE2 8993 8912 -1.01808 0.0154968 -0.00783348 1 0 1 1 0 0 +EDGE2 8993 8893 -0.0662016 -0.116785 -0.0338679 1 0 1 1 0 0 +EDGE2 8993 8913 -0.0959884 -0.0134107 -0.0531127 1 0 1 1 0 0 +EDGE2 8993 8894 0.974339 0.0166438 -0.00516905 1 0 1 1 0 0 +EDGE2 8994 8914 0.0191597 0.0340697 -0.0242472 1 0 1 1 0 0 +EDGE2 8994 8893 -0.929582 -0.025033 -0.0375534 1 0 1 1 0 0 +EDGE2 8994 8993 -0.938041 0.00647282 -0.0157857 1 0 1 1 0 0 +EDGE2 8994 8913 -0.948501 -0.050088 0.0119346 1 0 1 1 0 0 +EDGE2 8994 8894 0.0449725 0.0126178 0.0292863 1 0 1 1 0 0 +EDGE2 8994 8135 0.974674 0.0271679 -3.1534 1 0 1 1 0 0 +EDGE2 8994 8895 0.983725 -0.0143968 0.0293694 1 0 1 1 0 0 +EDGE2 8994 8915 0.986452 0.0588808 -0.0118122 1 0 1 1 0 0 +EDGE2 8994 8155 0.981179 -0.0283744 -3.17286 1 0 1 1 0 0 +EDGE2 8995 8914 -1.17727 -0.0122108 0.0127791 1 0 1 1 0 0 +EDGE2 8995 8156 -0.0451259 -1.02302 -1.58446 1 0 1 1 0 0 +EDGE2 8995 8136 -0.0865099 -0.936561 -1.58778 1 0 1 1 0 0 +EDGE2 8995 8994 -1.01914 -0.0223783 0.000580117 1 0 1 1 0 0 +EDGE2 8995 8894 -1.10578 -0.0151888 -0.0271497 1 0 1 1 0 0 +EDGE2 8995 8135 0.0374081 0.0551302 -3.14044 1 0 1 1 0 0 +EDGE2 8995 8895 -0.0347621 -0.0235566 -0.0327708 1 0 1 1 0 0 +EDGE2 8995 8915 0.0529715 -0.0373916 -0.0176378 1 0 1 1 0 0 +EDGE2 8995 8155 0.0140258 -0.0150538 -3.1366 1 0 1 1 0 0 +EDGE2 8995 8916 0.0373785 0.967977 1.55596 1 0 1 1 0 0 +EDGE2 8995 8896 -0.0193118 0.892756 1.59111 1 0 1 1 0 0 +EDGE2 8995 8134 1.02917 0.0624991 -3.14423 1 0 1 1 0 0 +EDGE2 8995 8154 1.00398 -0.0526038 -3.13565 1 0 1 1 0 0 +EDGE2 8996 8156 -0.0100308 -0.00447137 -0.0195187 1 0 1 1 0 0 +EDGE2 8996 8157 1.01366 -0.00222144 0.00320558 1 0 1 1 0 0 +EDGE2 8996 8137 1.00355 -0.0233097 0.0102246 1 0 1 1 0 0 +EDGE2 8996 8136 -0.0518446 0.0328921 -0.0257181 1 0 1 1 0 0 +EDGE2 8996 8995 -0.967572 -0.00933951 1.56446 1 0 1 1 0 0 +EDGE2 8996 8135 -1.01234 -0.00381429 -1.55666 1 0 1 1 0 0 +EDGE2 8996 8895 -0.99534 0.0242192 1.57312 1 0 1 1 0 0 +EDGE2 8996 8915 -0.967771 0.0773016 1.56833 1 0 1 1 0 0 +EDGE2 8996 8155 -1.01006 -0.00809943 -1.56944 1 0 1 1 0 0 +EDGE2 8997 8156 -1.00018 0.0353401 -0.0343949 1 0 1 1 0 0 +EDGE2 8997 8157 0.0118046 -0.0591347 -0.00226602 1 0 1 1 0 0 +EDGE2 8997 8158 1.07233 -0.00439767 -0.000629587 1 0 1 1 0 0 +EDGE2 8997 8138 0.921321 0.00218051 0.0235964 1 0 1 1 0 0 +EDGE2 8997 8137 0.056019 -0.0535519 0.0224717 1 0 1 1 0 0 +EDGE2 8997 8996 -1.08747 0.0406377 -0.0206634 1 0 1 1 0 0 +EDGE2 8997 8136 -0.948917 -0.100856 0.0102957 1 0 1 1 0 0 +EDGE2 8998 8157 -1.0549 -0.00463955 0.00116108 1 0 1 1 0 0 +EDGE2 8998 8139 0.879088 0.00271431 -0.00552128 1 0 1 1 0 0 +EDGE2 8998 8159 1.02805 0.0538543 -0.0222505 1 0 1 1 0 0 +EDGE2 8998 8997 -0.966678 0.0292429 0.0304782 1 0 1 1 0 0 +EDGE2 8998 8158 0.18799 -0.0841998 -0.0116492 1 0 1 1 0 0 +EDGE2 8998 8138 -0.0812203 0.0134054 0.0362721 1 0 1 1 0 0 +EDGE2 8998 8137 -1.0306 -0.0565882 -0.0101589 1 0 1 1 0 0 +EDGE2 8999 8140 0.953918 -0.0811026 -0.00908308 1 0 1 1 0 0 +EDGE2 8999 6480 0.979459 -0.121212 -3.17417 1 0 1 1 0 0 +EDGE2 8999 8100 1.02303 0.0841061 -3.16261 1 0 1 1 0 0 +EDGE2 8999 6500 1.08524 0.0593741 -3.13375 1 0 1 1 0 0 +EDGE2 8999 8998 -1.06327 0.0241814 0.00411482 1 0 1 1 0 0 +EDGE2 8999 8139 0.0198806 -0.0291699 -0.000743957 1 0 1 1 0 0 +EDGE2 8999 8160 0.98233 0.000492103 -0.0116192 1 0 1 1 0 0 +EDGE2 8999 8159 -0.0172762 0.00480211 -0.0178863 1 0 1 1 0 0 +EDGE2 8999 8158 -1.00825 -0.00749727 -0.00816431 1 0 1 1 0 0 +EDGE2 8999 8138 -1.06162 0.0334179 0.0135113 1 0 1 1 0 0 +EDGE2 9000 8140 0.0381542 0.0621401 -0.00168847 1 0 1 1 0 0 +EDGE2 9000 8099 1.03429 0.0168824 -3.16822 1 0 1 1 0 0 +EDGE2 9000 6479 1.01885 -0.00884564 -3.16644 1 0 1 1 0 0 +EDGE2 9000 6499 0.957906 -0.0849657 -3.15271 1 0 1 1 0 0 +EDGE2 9000 6480 0.0754137 0.0114871 -3.18662 1 0 1 1 0 0 +EDGE2 9000 6501 0.0215988 -0.993869 -1.51156 1 0 1 1 0 0 +EDGE2 9000 8100 -0.0286652 -0.0509063 -3.17005 1 0 1 1 0 0 +EDGE2 9000 6481 -0.00062993 -1.02141 -1.56134 1 0 1 1 0 0 +EDGE2 9000 6500 -0.0463545 0.164022 -3.11279 1 0 1 1 0 0 +EDGE2 9000 8101 0.0257614 0.974021 1.56459 1 0 1 1 0 0 +EDGE2 9000 8141 0.0775969 1.0712 1.57694 1 0 1 1 0 0 +EDGE2 9000 8139 -0.991408 -0.032703 0.0160361 1 0 1 1 0 0 +EDGE2 9000 8999 -1.0454 -0.0210055 0.0108429 1 0 1 1 0 0 +EDGE2 9000 8160 0.0591007 0.00169847 -0.019478 1 0 1 1 0 0 +EDGE2 9000 8159 -1.02255 0.0234225 0.0258671 1 0 1 1 0 0 +EDGE2 9000 8161 -0.0882989 0.897046 1.56408 1 0 1 1 0 0 +EDGE2 9001 8140 -0.999878 -0.056242 -1.58772 1 0 1 1 0 0 +EDGE2 9001 6480 -0.941263 -0.161365 1.56271 1 0 1 1 0 0 +EDGE2 9001 8100 -0.997056 0.0166578 1.53565 1 0 1 1 0 0 +EDGE2 9001 9000 -0.962773 -0.0180152 -1.55807 1 0 1 1 0 0 +EDGE2 9001 6500 -1.00744 0.0423079 1.58705 1 0 1 1 0 0 +EDGE2 9001 8101 0.00643397 -0.00883756 0.00983651 1 0 1 1 0 0 +EDGE2 9001 8102 1.02356 -0.0514883 0.0132426 1 0 1 1 0 0 +EDGE2 9001 8141 0.0448174 -0.00955807 0.0182664 1 0 1 1 0 0 +EDGE2 9001 8160 -0.957845 -0.0424537 -1.58479 1 0 1 1 0 0 +EDGE2 9001 8162 1.04506 -0.0268106 0.011148 1 0 1 1 0 0 +EDGE2 9001 8142 0.981572 0.0342838 -0.0330936 1 0 1 1 0 0 +EDGE2 9001 8161 0.0519241 0.029973 -0.00523135 1 0 1 1 0 0 +EDGE2 9002 9001 -1.05973 0.0349805 -0.00579666 1 0 1 1 0 0 +EDGE2 9002 8101 -0.962126 0.0405939 -0.027796 1 0 1 1 0 0 +EDGE2 9002 8102 -0.0100177 0.0311716 0.0503791 1 0 1 1 0 0 +EDGE2 9002 8103 0.948297 -0.0212822 -0.0159372 1 0 1 1 0 0 +EDGE2 9002 8141 -1.01792 -0.0647598 0.000195867 1 0 1 1 0 0 +EDGE2 9002 8162 -0.000918057 0.0151053 0.0081096 1 0 1 1 0 0 +EDGE2 9002 8143 0.984552 -0.0907163 0.0199621 1 0 1 1 0 0 +EDGE2 9002 8142 0.0287217 0.0447546 -0.000486676 1 0 1 1 0 0 +EDGE2 9002 8161 -1.02369 0.00250282 -0.0144094 1 0 1 1 0 0 +EDGE2 9002 8163 1.00138 -0.104182 -0.0193916 1 0 1 1 0 0 +EDGE2 9003 9002 -0.930527 0.00835523 0.037175 1 0 1 1 0 0 +EDGE2 9003 8102 -1.08594 -0.0721886 0.00551332 1 0 1 1 0 0 +EDGE2 9003 8104 0.989365 -0.0131458 -0.0222055 1 0 1 1 0 0 +EDGE2 9003 8103 -0.0142198 -0.0357568 0.00737841 1 0 1 1 0 0 +EDGE2 9003 8162 -1.04667 -0.0726184 -0.0223036 1 0 1 1 0 0 +EDGE2 9003 8144 1.01023 -0.0409471 -0.0460208 1 0 1 1 0 0 +EDGE2 9003 8143 0.0354949 0.0701946 -0.043489 1 0 1 1 0 0 +EDGE2 9003 8142 -1.01508 -0.0588931 -0.0102842 1 0 1 1 0 0 +EDGE2 9003 8164 0.99867 0.0583549 -0.00439495 1 0 1 1 0 0 +EDGE2 9003 8163 0.0544678 -0.00608962 -0.052258 1 0 1 1 0 0 +EDGE2 9004 9003 -1.00785 -0.0267614 0.0231902 1 0 1 1 0 0 +EDGE2 9004 8104 -1.50385e-05 -0.0687345 0.00161025 1 0 1 1 0 0 +EDGE2 9004 8103 -0.955569 -0.0441062 0.015372 1 0 1 1 0 0 +EDGE2 9004 8144 0.0547976 -0.0370327 -0.0114966 1 0 1 1 0 0 +EDGE2 9004 8143 -1.09517 0.0139653 -0.0176398 1 0 1 1 0 0 +EDGE2 9004 8164 0.0285632 -0.0742599 -0.0270521 1 0 1 1 0 0 +EDGE2 9004 8163 -0.969949 0.0638221 -0.0200338 1 0 1 1 0 0 +EDGE2 9004 8125 1.0046 0.0748436 -3.14081 1 0 1 1 0 0 +EDGE2 9004 8105 0.917671 0.0385709 -0.0196581 1 0 1 1 0 0 +EDGE2 9004 8165 1.02815 0.03697 -0.00835366 1 0 1 1 0 0 +EDGE2 9004 8145 0.918865 0.000788165 0.00304052 1 0 1 1 0 0 +EDGE2 9005 8106 -0.0378397 -1.07077 -1.56182 1 0 1 1 0 0 +EDGE2 9005 9004 -1.05729 -0.0762914 -0.00803114 1 0 1 1 0 0 +EDGE2 9005 8104 -0.956152 0.0216383 0.0100581 1 0 1 1 0 0 +EDGE2 9005 8144 -1.08319 -0.0921806 -0.0286465 1 0 1 1 0 0 +EDGE2 9005 8164 -1.08001 0.0031662 0.0455698 1 0 1 1 0 0 +EDGE2 9005 8125 0.00164203 0.033865 -3.16936 1 0 1 1 0 0 +EDGE2 9005 8105 -0.0528203 0.00648925 0.0139911 1 0 1 1 0 0 +EDGE2 9005 8124 0.986706 -0.0682847 -3.16397 1 0 1 1 0 0 +EDGE2 9005 8146 -0.0806619 1.05435 1.57699 1 0 1 1 0 0 +EDGE2 9005 8165 -0.00103449 -0.0436045 -0.0227015 1 0 1 1 0 0 +EDGE2 9005 8145 -0.0466234 -0.140092 -0.0431497 1 0 1 1 0 0 +EDGE2 9005 8126 0.0253459 0.985672 1.57222 1 0 1 1 0 0 +EDGE2 9005 8166 -0.0220975 1.02522 1.55273 1 0 1 1 0 0 +EDGE2 9006 9005 -1.01101 -0.0652678 -1.54901 1 0 1 1 0 0 +EDGE2 9006 8125 -1.00043 -0.00265829 1.57507 1 0 1 1 0 0 +EDGE2 9006 8105 -0.926167 -0.00115963 -1.59628 1 0 1 1 0 0 +EDGE2 9006 8167 1.05104 -0.0636203 0.0172009 1 0 1 1 0 0 +EDGE2 9006 8146 -0.0366906 0.0853374 -0.00718653 1 0 1 1 0 0 +EDGE2 9006 8165 -1.02183 0.0205721 -1.57657 1 0 1 1 0 0 +EDGE2 9006 8145 -1.06502 -0.0721734 -1.5923 1 0 1 1 0 0 +EDGE2 9006 8126 -0.0170059 0.00789696 -0.00686117 1 0 1 1 0 0 +EDGE2 9006 8127 0.924765 -0.0207992 -0.02166 1 0 1 1 0 0 +EDGE2 9006 8166 0.0263222 0.0509363 0.01759 1 0 1 1 0 0 +EDGE2 9006 8147 1.02251 0.00529138 -0.0010441 1 0 1 1 0 0 +EDGE2 9007 8167 -0.0300164 0.000991683 0.018431 1 0 1 1 0 0 +EDGE2 9007 8146 -0.994946 -0.0132149 0.0358717 1 0 1 1 0 0 +EDGE2 9007 9006 -1.04146 -0.00595664 -0.0139871 1 0 1 1 0 0 +EDGE2 9007 8126 -1.09648 -0.0253245 -0.0201074 1 0 1 1 0 0 +EDGE2 9007 8127 -0.0391565 0.00641316 -0.00805246 1 0 1 1 0 0 +EDGE2 9007 8166 -0.975478 0.0839764 -0.0122543 1 0 1 1 0 0 +EDGE2 9007 8147 -0.0284579 -0.0672368 -0.00430374 1 0 1 1 0 0 +EDGE2 9007 8168 0.9115 -0.0349151 -0.00241725 1 0 1 1 0 0 +EDGE2 9007 8128 0.987042 -0.070202 0.0160837 1 0 1 1 0 0 +EDGE2 9007 8148 1.04532 -0.0524722 -0.00800075 1 0 1 1 0 0 +EDGE2 9008 8167 -0.922408 -0.0837874 0.0143379 1 0 1 1 0 0 +EDGE2 9008 8127 -1.00207 -0.0190321 0.0045033 1 0 1 1 0 0 +EDGE2 9008 9007 -1.01729 0.0249324 -0.0206445 1 0 1 1 0 0 +EDGE2 9008 8147 -1.03997 -0.0195653 0.00449278 1 0 1 1 0 0 +EDGE2 9008 8168 -0.0423257 -0.021898 -0.00083365 1 0 1 1 0 0 +EDGE2 9008 8128 -0.0642672 0.00378705 -0.00111648 1 0 1 1 0 0 +EDGE2 9008 8148 0.00331646 -0.0136387 -0.000961113 1 0 1 1 0 0 +EDGE2 9008 8169 1.0206 0.00620365 -0.00315054 1 0 1 1 0 0 +EDGE2 9008 8129 0.929738 -0.143353 -0.01012 1 0 1 1 0 0 +EDGE2 9008 8149 1.04686 -0.00503083 0.0051578 1 0 1 1 0 0 +EDGE2 9009 8168 -1.02887 0.0568307 0.0269613 1 0 1 1 0 0 +EDGE2 9009 8128 -0.95627 -0.00481157 -0.0188207 1 0 1 1 0 0 +EDGE2 9009 9008 -1.08486 0.0384433 0.0128424 1 0 1 1 0 0 +EDGE2 9009 8148 -1.04512 0.129266 -0.00800942 1 0 1 1 0 0 +EDGE2 9009 8169 0.0536404 -0.0175004 2.44043e-05 1 0 1 1 0 0 +EDGE2 9009 8129 0.0037226 0.0963582 -0.0332108 1 0 1 1 0 0 +EDGE2 9009 8149 0.0225568 -0.00430611 0.00181529 1 0 1 1 0 0 +EDGE2 9009 8170 1.00895 -0.0821391 -0.0317663 1 0 1 1 0 0 +EDGE2 9009 8130 0.987573 0.0169392 0.00369643 1 0 1 1 0 0 +EDGE2 9009 8150 1.03071 0.0692983 -0.00255145 1 0 1 1 0 0 +EDGE2 9010 8169 -1.05578 0.0367262 0.0108916 1 0 1 1 0 0 +EDGE2 9010 8129 -0.979949 -0.0151984 0.0291901 1 0 1 1 0 0 +EDGE2 9010 9009 -0.92667 0.0614883 -0.0364346 1 0 1 1 0 0 +EDGE2 9010 8149 -0.941856 -0.00227194 0.0469842 1 0 1 1 0 0 +EDGE2 9010 8171 -0.0812348 -0.986173 -1.53381 1 0 1 1 0 0 +EDGE2 9010 8170 -0.0290571 0.00958619 -0.0288987 1 0 1 1 0 0 +EDGE2 9010 8130 0.027553 -0.00651465 -0.0218679 1 0 1 1 0 0 +EDGE2 9010 8131 -0.0405103 0.99246 1.55907 1 0 1 1 0 0 +EDGE2 9010 8151 -0.0242429 0.975724 1.54714 1 0 1 1 0 0 +EDGE2 9010 8150 0.0442165 -0.0156228 0.00766844 1 0 1 1 0 0 +EDGE2 9011 9010 -1.02259 -0.052162 -1.56357 1 0 1 1 0 0 +EDGE2 9011 8170 -1.04123 0.0742644 -1.5731 1 0 1 1 0 0 +EDGE2 9011 8130 -0.941473 -0.0539933 -1.57805 1 0 1 1 0 0 +EDGE2 9011 8132 1.00468 -0.00702643 -0.0346121 1 0 1 1 0 0 +EDGE2 9011 8131 -0.0144191 -0.0238272 -0.0231865 1 0 1 1 0 0 +EDGE2 9011 8152 0.979332 -0.0353561 0.042486 1 0 1 1 0 0 +EDGE2 9011 8151 0.0282752 -0.0108129 0.00974476 1 0 1 1 0 0 +EDGE2 9011 8150 -0.998067 -0.0959893 -1.58823 1 0 1 1 0 0 +EDGE2 9012 9011 -0.97674 -0.105504 0.000719989 1 0 1 1 0 0 +EDGE2 9012 8132 -0.0361901 0.0118548 -0.0118436 1 0 1 1 0 0 +EDGE2 9012 8133 0.944393 0.0144981 -0.0170456 1 0 1 1 0 0 +EDGE2 9012 8131 -1.09598 -0.0822214 -0.028253 1 0 1 1 0 0 +EDGE2 9012 8152 0.0938036 0.0467455 -0.00198043 1 0 1 1 0 0 +EDGE2 9012 8153 1.04582 0.0226755 0.0353958 1 0 1 1 0 0 +EDGE2 9012 8151 -1.02936 -0.0407648 -0.0236898 1 0 1 1 0 0 +EDGE2 9013 9012 -0.98384 -0.000418642 -0.0244406 1 0 1 1 0 0 +EDGE2 9013 8132 -1.12837 -0.01855 0.0105814 1 0 1 1 0 0 +EDGE2 9013 8133 -0.0545218 0.05874 -0.0131989 1 0 1 1 0 0 +EDGE2 9013 8134 0.990622 0.0564852 0.0142568 1 0 1 1 0 0 +EDGE2 9013 8152 -0.985397 -0.00722141 -0.00729741 1 0 1 1 0 0 +EDGE2 9013 8153 -0.110452 0.0253549 0.00029331 1 0 1 1 0 0 +EDGE2 9013 8154 0.940848 -0.0195396 -0.0324531 1 0 1 1 0 0 +EDGE2 9014 8995 1.00378 0.0434357 -3.17628 1 0 1 1 0 0 +EDGE2 9014 8135 1.04571 0.0427696 0.024114 1 0 1 1 0 0 +EDGE2 9014 8895 1.03493 0.0214647 -3.14095 1 0 1 1 0 0 +EDGE2 9014 8915 1.0218 -0.00375999 -3.16475 1 0 1 1 0 0 +EDGE2 9014 8155 0.968448 0.0135498 0.0126887 1 0 1 1 0 0 +EDGE2 9014 9013 -0.988446 0.0481054 0.0252133 1 0 1 1 0 0 +EDGE2 9014 8133 -0.924723 -0.133044 0.00126519 1 0 1 1 0 0 +EDGE2 9014 8134 -0.038361 -0.0628147 -0.0101415 1 0 1 1 0 0 +EDGE2 9014 8153 -1.00095 0.0133417 -0.0158685 1 0 1 1 0 0 +EDGE2 9014 8154 -0.0121464 0.029442 0.0216063 1 0 1 1 0 0 +EDGE2 9015 8914 0.891552 0.0302155 -3.11913 1 0 1 1 0 0 +EDGE2 9015 8156 0.073629 0.991397 1.59037 1 0 1 1 0 0 +EDGE2 9015 8996 -0.0139758 0.999433 1.57061 1 0 1 1 0 0 +EDGE2 9015 8136 0.0580918 0.961173 1.54615 1 0 1 1 0 0 +EDGE2 9015 8994 0.989469 -0.0105348 -3.15803 1 0 1 1 0 0 +EDGE2 9015 8995 0.0272554 0.0620183 -3.16652 1 0 1 1 0 0 +EDGE2 9015 8894 0.951699 0.0707746 -3.15067 1 0 1 1 0 0 +EDGE2 9015 8135 -0.0878798 0.0538561 0.0442682 1 0 1 1 0 0 +EDGE2 9015 8895 0.0686108 -0.0207898 -3.15496 1 0 1 1 0 0 +EDGE2 9015 8915 0.0576576 -0.0385406 -3.12334 1 0 1 1 0 0 +EDGE2 9015 8155 -0.0289798 -0.0297977 0.0225106 1 0 1 1 0 0 +EDGE2 9015 8916 0.0567361 -0.95183 -1.56618 1 0 1 1 0 0 +EDGE2 9015 8896 -0.0129684 -0.984214 -1.54479 1 0 1 1 0 0 +EDGE2 9015 9014 -1.00217 -0.0649098 -0.0116227 1 0 1 1 0 0 +EDGE2 9015 8134 -0.915607 0.0324944 0.026631 1 0 1 1 0 0 +EDGE2 9015 8154 -1.05233 0.0458601 -0.0185766 1 0 1 1 0 0 +EDGE2 9016 8995 -1.10778 -0.145673 -1.52933 1 0 1 1 0 0 +EDGE2 9016 9015 -1.02999 0.0390559 1.5841 1 0 1 1 0 0 +EDGE2 9016 8135 -0.972079 -0.0129362 1.56206 1 0 1 1 0 0 +EDGE2 9016 8895 -1.01287 -0.00875444 -1.599 1 0 1 1 0 0 +EDGE2 9016 8915 -1.0244 -0.0769243 -1.56514 1 0 1 1 0 0 +EDGE2 9016 8155 -1.14721 -0.0447405 1.53752 1 0 1 1 0 0 +EDGE2 9016 8916 0.0249473 0.0436518 0.0443469 1 0 1 1 0 0 +EDGE2 9016 8896 0.000611828 0.00174887 -0.00505909 1 0 1 1 0 0 +EDGE2 9016 8917 1.0117 0.00310836 0.0161916 1 0 1 1 0 0 +EDGE2 9016 8897 0.960405 -0.0427069 -0.00987502 1 0 1 1 0 0 +EDGE2 9017 8916 -0.88742 -0.0130343 -0.0148603 1 0 1 1 0 0 +EDGE2 9017 9016 -1.03405 0.0442184 0.0305625 1 0 1 1 0 0 +EDGE2 9017 8896 -1.06439 0.0798186 -0.0236228 1 0 1 1 0 0 +EDGE2 9017 8917 0.0952165 0.0592583 -0.00570597 1 0 1 1 0 0 +EDGE2 9017 8897 0.0428253 0.0142475 -0.0363077 1 0 1 1 0 0 +EDGE2 9017 8898 0.949847 -0.0794369 0.0300685 1 0 1 1 0 0 +EDGE2 9017 8918 0.942841 -0.0126437 0.000995721 1 0 1 1 0 0 +EDGE2 9018 8917 -1.02879 -0.0186652 -0.00862055 1 0 1 1 0 0 +EDGE2 9018 9017 -0.995063 -0.0832703 0.0125317 1 0 1 1 0 0 +EDGE2 9018 8897 -0.901025 0.0329976 -0.0111068 1 0 1 1 0 0 +EDGE2 9018 8898 0.0569542 -0.0346526 0.0395185 1 0 1 1 0 0 +EDGE2 9018 8918 0.0386271 0.0840399 -0.0253101 1 0 1 1 0 0 +EDGE2 9018 8919 1.03641 -0.0346356 -0.0046423 1 0 1 1 0 0 +EDGE2 9018 8899 1.00856 0.000350979 0.000583233 1 0 1 1 0 0 +EDGE2 9019 8898 -1.04771 0.00201627 6.5336e-05 1 0 1 1 0 0 +EDGE2 9019 8918 -1.04837 -0.00479265 -0.00202641 1 0 1 1 0 0 +EDGE2 9019 9018 -0.995035 -0.0228545 -0.0393 1 0 1 1 0 0 +EDGE2 9019 8919 0.0384807 -0.0232474 -0.0216114 1 0 1 1 0 0 +EDGE2 9019 8899 -0.0583053 0.00933195 -0.00862118 1 0 1 1 0 0 +EDGE2 9019 8920 1.07025 -0.0215846 0.0161051 1 0 1 1 0 0 +EDGE2 9019 8900 1.068 -0.0132113 0.0154779 1 0 1 1 0 0 +EDGE2 9020 8919 -0.976719 0.0212961 -0.00383105 1 0 1 1 0 0 +EDGE2 9020 9019 -1.01499 -0.00252234 -0.0150529 1 0 1 1 0 0 +EDGE2 9020 8899 -1.10259 0.0384456 -0.00198522 1 0 1 1 0 0 +EDGE2 9020 8921 -0.0675934 1.08467 1.58945 1 0 1 1 0 0 +EDGE2 9020 8901 -0.00666704 1.08224 1.60196 1 0 1 1 0 0 +EDGE2 9020 8920 -0.100776 -0.0114161 -0.0180113 1 0 1 1 0 0 +EDGE2 9020 8900 -0.0346523 -0.0328989 0.00807959 1 0 1 1 0 0 +EDGE2 9021 8902 0.984688 -0.129402 0.0137145 1 0 1 1 0 0 +EDGE2 9021 8922 0.953382 0.00931842 0.0170772 1 0 1 1 0 0 +EDGE2 9021 8921 0.0255453 0.0405213 0.0549629 1 0 1 1 0 0 +EDGE2 9021 8901 -0.0204094 0.0184261 -0.0480102 1 0 1 1 0 0 +EDGE2 9021 8920 -1.00802 0.0235559 -1.57222 1 0 1 1 0 0 +EDGE2 9021 9020 -0.976602 0.0205382 -1.57772 1 0 1 1 0 0 +EDGE2 9021 8900 -1.02637 0.0566543 -1.53486 1 0 1 1 0 0 +EDGE2 9022 8903 0.961731 0.049295 -0.0242065 1 0 1 1 0 0 +EDGE2 9022 8923 0.968536 -0.0452321 -0.00118446 1 0 1 1 0 0 +EDGE2 9022 8902 -0.00647013 -0.0594086 -0.00956556 1 0 1 1 0 0 +EDGE2 9022 8922 -0.070988 0.0495742 -0.028349 1 0 1 1 0 0 +EDGE2 9022 8921 -1.01823 0.0451571 0.00977459 1 0 1 1 0 0 +EDGE2 9022 9021 -0.958736 0.0751437 -0.0292434 1 0 1 1 0 0 +EDGE2 9022 8901 -1.01113 -0.0823466 -0.0326034 1 0 1 1 0 0 +EDGE2 9023 9022 -1.04637 0.0104567 -0.0307509 1 0 1 1 0 0 +EDGE2 9023 8924 0.967073 -0.0115456 -0.00437097 1 0 1 1 0 0 +EDGE2 9023 8904 0.978075 -0.0131851 0.0490949 1 0 1 1 0 0 +EDGE2 9023 8903 0.0421772 -0.0784496 -0.0231362 1 0 1 1 0 0 +EDGE2 9023 8923 -0.0443071 0.0154109 0.0403921 1 0 1 1 0 0 +EDGE2 9023 8902 -0.956584 -0.0695727 -0.0104415 1 0 1 1 0 0 +EDGE2 9023 8922 -1.02057 -0.0688048 0.0061832 1 0 1 1 0 0 +EDGE2 9024 8885 0.988317 -0.00485988 -3.13592 1 0 1 1 0 0 +EDGE2 9024 8925 0.991283 -0.0226837 -0.00918349 1 0 1 1 0 0 +EDGE2 9024 8905 1.12435 0.0180649 -0.0235911 1 0 1 1 0 0 +EDGE2 9024 8924 -0.0858528 -0.0120256 0.0260811 1 0 1 1 0 0 +EDGE2 9024 8904 -0.0384409 -0.0902923 -0.0255005 1 0 1 1 0 0 +EDGE2 9024 8903 -1.03005 0.0147331 -0.0335193 1 0 1 1 0 0 +EDGE2 9024 8923 -1.0042 -0.0468509 0.0327129 1 0 1 1 0 0 +EDGE2 9024 9023 -1.00599 0.0097475 -0.0393574 1 0 1 1 0 0 +EDGE2 9025 8906 0.00691912 1.01145 1.53642 1 0 1 1 0 0 +EDGE2 9025 8886 -0.113835 1.01541 1.5764 1 0 1 1 0 0 +EDGE2 9025 8884 1.02648 0.0613026 -3.1093 1 0 1 1 0 0 +EDGE2 9025 8885 -0.00419092 -0.101111 -3.10482 1 0 1 1 0 0 +EDGE2 9025 8925 -0.00653893 0.103413 0.0254878 1 0 1 1 0 0 +EDGE2 9025 8905 -0.025609 0.0283941 0.0063358 1 0 1 1 0 0 +EDGE2 9025 8926 -0.0485632 -1.01969 -1.55241 1 0 1 1 0 0 +EDGE2 9025 8924 -0.957637 -0.0253352 0.0105401 1 0 1 1 0 0 +EDGE2 9025 9024 -0.994024 0.00387097 0.00927478 1 0 1 1 0 0 +EDGE2 9025 8904 -1.06501 -0.00487897 0.00573098 1 0 1 1 0 0 +EDGE2 9026 8907 1.02392 0.0694881 -0.0087613 1 0 1 1 0 0 +EDGE2 9026 8887 0.893317 0.0201362 0.0224138 1 0 1 1 0 0 +EDGE2 9026 8906 0.00375045 0.103972 0.00471258 1 0 1 1 0 0 +EDGE2 9026 8886 -0.0558554 0.0247533 0.0404079 1 0 1 1 0 0 +EDGE2 9026 8885 -0.962423 0.0121223 1.5901 1 0 1 1 0 0 +EDGE2 9026 8925 -1.01769 -0.0534594 -1.5403 1 0 1 1 0 0 +EDGE2 9026 9025 -0.895432 0.0134392 -1.56121 1 0 1 1 0 0 +EDGE2 9026 8905 -0.990453 -0.0260535 -1.58898 1 0 1 1 0 0 +EDGE2 9027 8888 1.08932 -0.0358875 -0.00669337 1 0 1 1 0 0 +EDGE2 9027 8908 1.07286 0.0380941 -0.0133317 1 0 1 1 0 0 +EDGE2 9027 8907 0.060594 0.0155701 0.0461214 1 0 1 1 0 0 +EDGE2 9027 8887 -0.0947967 -0.0613449 0.00323992 1 0 1 1 0 0 +EDGE2 9027 8906 -1.0995 0.0240531 -0.0138868 1 0 1 1 0 0 +EDGE2 9027 9026 -0.959316 0.00734023 0.0121956 1 0 1 1 0 0 +EDGE2 9027 8886 -1.02153 -0.0679803 -0.0213867 1 0 1 1 0 0 +EDGE2 9028 8909 0.946499 0.0407965 -0.0229311 1 0 1 1 0 0 +EDGE2 9028 8889 0.964823 0.0719002 -0.0246239 1 0 1 1 0 0 +EDGE2 9028 8888 -0.0220948 0.031729 0.00211172 1 0 1 1 0 0 +EDGE2 9028 8908 0.0338151 0.0200024 -0.00708757 1 0 1 1 0 0 +EDGE2 9028 8907 -1.02648 -0.015869 0.014229 1 0 1 1 0 0 +EDGE2 9028 9027 -1.03358 0.0732455 -0.000485833 1 0 1 1 0 0 +EDGE2 9028 8887 -1.02373 -0.00176614 -0.0141499 1 0 1 1 0 0 +EDGE2 9029 6310 0.977215 0.0246975 -3.11388 1 0 1 1 0 0 +EDGE2 9029 8910 0.979875 0.0545581 0.0340512 1 0 1 1 0 0 +EDGE2 9029 8990 0.98825 -0.0628302 -3.18278 1 0 1 1 0 0 +EDGE2 9029 8890 1.0482 -0.00537739 -0.02349 1 0 1 1 0 0 +EDGE2 9029 8909 0.0295136 -0.0154865 -0.0198748 1 0 1 1 0 0 +EDGE2 9029 8889 -0.0173613 -0.00740836 -0.0269364 1 0 1 1 0 0 +EDGE2 9029 8888 -1.04109 0.0428853 -0.00773677 1 0 1 1 0 0 +EDGE2 9029 9028 -1.02645 0.0754056 0.0187909 1 0 1 1 0 0 +EDGE2 9029 8908 -1.0701 -0.06621 -0.00151741 1 0 1 1 0 0 +EDGE2 9030 8989 0.975565 -0.0665861 -3.14209 1 0 1 1 0 0 +EDGE2 9030 6309 0.928145 0.00116731 -3.14609 1 0 1 1 0 0 +EDGE2 9030 6311 -0.0385604 -1.04621 -1.53515 1 0 1 1 0 0 +EDGE2 9030 6310 -0.000597382 0.0194642 -3.17083 1 0 1 1 0 0 +EDGE2 9030 8910 0.0593741 -0.00238658 0.00523427 1 0 1 1 0 0 +EDGE2 9030 8990 -0.0480915 0.0275103 -3.14721 1 0 1 1 0 0 +EDGE2 9030 8890 -0.0574 -0.059188 0.00987089 1 0 1 1 0 0 +EDGE2 9030 8909 -0.967541 -0.0402767 -0.0227846 1 0 1 1 0 0 +EDGE2 9030 9029 -0.942059 -0.0190372 -0.0249791 1 0 1 1 0 0 +EDGE2 9030 8889 -1.00396 0.0397081 -0.00722062 1 0 1 1 0 0 +EDGE2 9030 8891 0.000259619 1.01055 1.55722 1 0 1 1 0 0 +EDGE2 9030 8991 -0.0789551 1.01015 1.56587 1 0 1 1 0 0 +EDGE2 9030 8911 -0.0372481 0.945469 1.58874 1 0 1 1 0 0 +EDGE2 9031 6310 -0.966028 0.0121308 1.57423 1 0 1 1 0 0 +EDGE2 9031 8910 -0.909624 -0.0181238 -1.54739 1 0 1 1 0 0 +EDGE2 9031 8990 -0.939865 -0.0960982 1.54153 1 0 1 1 0 0 +EDGE2 9031 9030 -1.06103 -0.0516194 -1.55909 1 0 1 1 0 0 +EDGE2 9031 8890 -0.998529 -0.036496 -1.55208 1 0 1 1 0 0 +EDGE2 9031 8892 1.02 0.0094873 -0.00436867 1 0 1 1 0 0 +EDGE2 9031 8891 -0.024758 0.0367152 0.0325534 1 0 1 1 0 0 +EDGE2 9031 8991 -0.0275532 0.0521993 0.0370621 1 0 1 1 0 0 +EDGE2 9031 8911 0.00284574 -0.0322154 -0.00487619 1 0 1 1 0 0 +EDGE2 9031 8992 0.983581 0.069994 -0.0183838 1 0 1 1 0 0 +EDGE2 9031 8912 0.926621 0.033133 0.0250108 1 0 1 1 0 0 +EDGE2 9032 8892 -0.00814378 0.0624927 0.0327913 1 0 1 1 0 0 +EDGE2 9032 8891 -0.94329 -0.0242639 0.00135983 1 0 1 1 0 0 +EDGE2 9032 8991 -0.960864 0.0492454 0.000464717 1 0 1 1 0 0 +EDGE2 9032 9031 -0.998949 -0.0333229 0.0138338 1 0 1 1 0 0 +EDGE2 9032 8911 -1.05493 -0.0435828 0.0296561 1 0 1 1 0 0 +EDGE2 9032 8992 0.116992 -0.0644742 -0.0125554 1 0 1 1 0 0 +EDGE2 9032 8912 -0.011125 -0.0156143 0.0260069 1 0 1 1 0 0 +EDGE2 9032 8893 0.974811 -0.0415557 -0.0148253 1 0 1 1 0 0 +EDGE2 9032 8993 0.941619 0.100883 -0.0360175 1 0 1 1 0 0 +EDGE2 9032 8913 0.976219 -0.0890862 0.0120382 1 0 1 1 0 0 +EDGE2 9033 8914 0.970459 -0.0354601 0.0128881 1 0 1 1 0 0 +EDGE2 9033 8892 -1.01699 -0.0146329 0.00194138 1 0 1 1 0 0 +EDGE2 9033 8992 -0.932751 0.0130603 0.0251997 1 0 1 1 0 0 +EDGE2 9033 9032 -0.936576 0.0321525 -0.0163021 1 0 1 1 0 0 +EDGE2 9033 8912 -1.03851 0.0846557 -0.00762129 1 0 1 1 0 0 +EDGE2 9033 8893 0.00573587 0.0606851 -0.00986577 1 0 1 1 0 0 +EDGE2 9033 8993 -0.0289972 0.0290414 0.0209918 1 0 1 1 0 0 +EDGE2 9033 8913 0.0821716 -0.0106731 -0.0275638 1 0 1 1 0 0 +EDGE2 9033 8994 1.07556 0.00829051 0.0489171 1 0 1 1 0 0 +EDGE2 9033 8894 0.931219 0.0212342 0.00912825 1 0 1 1 0 0 +EDGE2 9034 8914 0.075402 -0.00288823 0.0127783 1 0 1 1 0 0 +EDGE2 9034 8893 -0.983359 -0.0852592 0.0098269 1 0 1 1 0 0 +EDGE2 9034 8993 -1.02327 -0.060344 0.023751 1 0 1 1 0 0 +EDGE2 9034 9033 -0.998986 0.00734273 -0.0170726 1 0 1 1 0 0 +EDGE2 9034 8913 -1.03222 0.0111325 -0.00207117 1 0 1 1 0 0 +EDGE2 9034 8994 -0.0107436 0.00692038 0.0289609 1 0 1 1 0 0 +EDGE2 9034 8995 1.0262 0.0146718 -0.0358487 1 0 1 1 0 0 +EDGE2 9034 8894 -0.00065678 0.0774103 -0.0257349 1 0 1 1 0 0 +EDGE2 9034 9015 1.01932 0.0110408 -3.16168 1 0 1 1 0 0 +EDGE2 9034 8135 0.937871 -0.0333767 -3.14048 1 0 1 1 0 0 +EDGE2 9034 8895 1.02666 -0.0131883 -0.0449307 1 0 1 1 0 0 +EDGE2 9034 8915 0.980646 0.0304144 0.0249436 1 0 1 1 0 0 +EDGE2 9034 8155 1.00783 -0.00810819 -3.13304 1 0 1 1 0 0 +EDGE2 9035 8914 -1.01738 -0.0659051 -0.0181657 1 0 1 1 0 0 +EDGE2 9035 8156 -0.025033 -1.1087 -1.5436 1 0 1 1 0 0 +EDGE2 9035 8996 -0.00683153 -1.03834 -1.56095 1 0 1 1 0 0 +EDGE2 9035 8136 -0.0238499 -0.974711 -1.5483 1 0 1 1 0 0 +EDGE2 9035 9034 -0.969814 0.0339048 -0.0293516 1 0 1 1 0 0 +EDGE2 9035 8994 -1.03671 0.0616153 0.00868374 1 0 1 1 0 0 +EDGE2 9035 8995 -0.0319959 -0.00242981 -0.00938729 1 0 1 1 0 0 +EDGE2 9035 8894 -0.9779 0.0170913 -0.0212278 1 0 1 1 0 0 +EDGE2 9035 9015 0.0204487 -0.062584 -3.14073 1 0 1 1 0 0 +EDGE2 9035 8135 0.0108376 0.0141559 -3.1526 1 0 1 1 0 0 +EDGE2 9035 8895 0.0414778 -0.0243949 -0.023536 1 0 1 1 0 0 +EDGE2 9035 8915 0.0201664 -0.0908397 -0.0267166 1 0 1 1 0 0 +EDGE2 9035 8155 0.0226664 -0.0294876 -3.11025 1 0 1 1 0 0 +EDGE2 9035 8916 -0.061008 1.01534 1.57415 1 0 1 1 0 0 +EDGE2 9035 9016 -0.0475975 1.07111 1.55552 1 0 1 1 0 0 +EDGE2 9035 8896 0.0144223 1.05307 1.56495 1 0 1 1 0 0 +EDGE2 9035 9014 1.05054 -0.0125561 -3.14881 1 0 1 1 0 0 +EDGE2 9035 8134 1.04715 -0.0530913 -3.16193 1 0 1 1 0 0 +EDGE2 9035 8154 0.992885 0.0764064 -3.17738 1 0 1 1 0 0 +EDGE2 9036 8995 -0.997067 0.0268328 -1.59534 1 0 1 1 0 0 +EDGE2 9036 9035 -0.96099 0.0952661 -1.58399 1 0 1 1 0 0 +EDGE2 9036 9015 -0.94156 -0.0200947 1.54955 1 0 1 1 0 0 +EDGE2 9036 8135 -1.06943 0.00977096 1.54998 1 0 1 1 0 0 +EDGE2 9036 8895 -0.994778 0.00283432 -1.5627 1 0 1 1 0 0 +EDGE2 9036 8915 -1.00798 0.0156672 -1.56811 1 0 1 1 0 0 +EDGE2 9036 8155 -1.01602 -0.00672007 1.59117 1 0 1 1 0 0 +EDGE2 9036 8916 0.0158146 0.0796027 -0.0204811 1 0 1 1 0 0 +EDGE2 9036 9016 0.0616598 -0.0256615 0.00157441 1 0 1 1 0 0 +EDGE2 9036 8896 0.0194545 0.0598367 0.000830205 1 0 1 1 0 0 +EDGE2 9036 8917 0.985685 -0.0162529 0.00471359 1 0 1 1 0 0 +EDGE2 9036 9017 1.03064 -0.0586322 0.00882646 1 0 1 1 0 0 +EDGE2 9036 8897 1.06526 -0.0184288 0.0256842 1 0 1 1 0 0 +EDGE2 9037 8916 -1.06965 -0.00205845 -0.00849368 1 0 1 1 0 0 +EDGE2 9037 9016 -0.987671 -0.0349259 0.00602902 1 0 1 1 0 0 +EDGE2 9037 9036 -0.913566 0.0515566 0.0334498 1 0 1 1 0 0 +EDGE2 9037 8896 -1.16042 0.0376425 -0.0049694 1 0 1 1 0 0 +EDGE2 9037 8917 -0.00661438 0.0578482 0.0483786 1 0 1 1 0 0 +EDGE2 9037 9017 0.0780415 -0.0233741 -0.000274265 1 0 1 1 0 0 +EDGE2 9037 8897 0.0358067 0.0251336 0.00125557 1 0 1 1 0 0 +EDGE2 9037 8898 1.09161 0.034811 0.0170025 1 0 1 1 0 0 +EDGE2 9037 8918 0.937613 0.0579391 -0.0131471 1 0 1 1 0 0 +EDGE2 9037 9018 1.03252 0.0228026 0.0274692 1 0 1 1 0 0 +EDGE2 9038 8917 -0.990322 0.053043 0.015086 1 0 1 1 0 0 +EDGE2 9038 9017 -1.046 -0.0298653 0.0116123 1 0 1 1 0 0 +EDGE2 9038 9037 -1.02482 -0.00650053 0.00850453 1 0 1 1 0 0 +EDGE2 9038 8897 -0.892159 -0.0479508 -0.0216954 1 0 1 1 0 0 +EDGE2 9038 8898 0.0288886 0.080558 -0.00844908 1 0 1 1 0 0 +EDGE2 9038 8918 0.0140619 -0.0816821 0.000906457 1 0 1 1 0 0 +EDGE2 9038 9018 0.0351472 -0.013195 0.0142787 1 0 1 1 0 0 +EDGE2 9038 8919 0.959632 -0.0332934 0.000375909 1 0 1 1 0 0 +EDGE2 9038 9019 0.917081 0.126988 0.00889042 1 0 1 1 0 0 +EDGE2 9038 8899 1.02061 0.0348261 0.0047738 1 0 1 1 0 0 +EDGE2 9039 9038 -1.04884 -0.00651082 0.0126483 1 0 1 1 0 0 +EDGE2 9039 8898 -0.934683 0.0859685 0.00665546 1 0 1 1 0 0 +EDGE2 9039 8918 -1.07041 0.0427013 -0.00292833 1 0 1 1 0 0 +EDGE2 9039 9018 -0.943154 -0.0599105 -0.000164123 1 0 1 1 0 0 +EDGE2 9039 8919 -0.0278999 0.0308014 -0.0223486 1 0 1 1 0 0 +EDGE2 9039 9019 0.110981 -0.036764 0.0221711 1 0 1 1 0 0 +EDGE2 9039 8899 0.0274402 -0.0155171 -0.0142294 1 0 1 1 0 0 +EDGE2 9039 8920 0.975016 0.0304527 0.0221943 1 0 1 1 0 0 +EDGE2 9039 9020 1.04994 -0.014995 -0.0349282 1 0 1 1 0 0 +EDGE2 9039 8900 1.06115 -0.0155773 0.0343078 1 0 1 1 0 0 +EDGE2 9040 9039 -0.977864 0.0435018 -0.0243009 1 0 1 1 0 0 +EDGE2 9040 8919 -1.01705 3.98352e-05 0.0103934 1 0 1 1 0 0 +EDGE2 9040 9019 -1.00728 0.00322145 0.0296298 1 0 1 1 0 0 +EDGE2 9040 8899 -0.991088 -0.0583355 0.0257617 1 0 1 1 0 0 +EDGE2 9040 8921 -0.0082774 1.02392 1.56776 1 0 1 1 0 0 +EDGE2 9040 9021 -0.0216132 1.03911 1.54674 1 0 1 1 0 0 +EDGE2 9040 8901 -0.0701371 0.97572 1.57614 1 0 1 1 0 0 +EDGE2 9040 8920 0.0842434 -0.0135944 0.000466788 1 0 1 1 0 0 +EDGE2 9040 9020 0.0733548 -0.066016 -0.00228011 1 0 1 1 0 0 +EDGE2 9040 8900 0.0343878 0.0526916 -0.00431256 1 0 1 1 0 0 +EDGE2 9041 9022 0.975266 -0.10704 -0.00234403 1 0 1 1 0 0 +EDGE2 9041 8902 0.993948 -0.005842 -0.0491666 1 0 1 1 0 0 +EDGE2 9041 8922 0.919798 -0.152776 -0.0220302 1 0 1 1 0 0 +EDGE2 9041 8921 -0.0638997 0.128045 0.0220261 1 0 1 1 0 0 +EDGE2 9041 9021 0.00536029 0.00719709 -0.0159517 1 0 1 1 0 0 +EDGE2 9041 8901 0.0614031 0.00409598 -0.000221374 1 0 1 1 0 0 +EDGE2 9041 8920 -0.91964 -0.0625286 -1.56754 1 0 1 1 0 0 +EDGE2 9041 9020 -1.01963 -0.0469572 -1.56818 1 0 1 1 0 0 +EDGE2 9041 9040 -0.92182 -0.0333907 -1.55041 1 0 1 1 0 0 +EDGE2 9041 8900 -0.964295 0.0037522 -1.59846 1 0 1 1 0 0 +EDGE2 9042 9022 -0.0149592 -0.0222516 -0.0136641 1 0 1 1 0 0 +EDGE2 9042 8903 0.930846 -0.0475986 -0.0114457 1 0 1 1 0 0 +EDGE2 9042 8923 1.01137 -0.0215492 0.00377534 1 0 1 1 0 0 +EDGE2 9042 9023 1.04822 0.0300124 -0.0100834 1 0 1 1 0 0 +EDGE2 9042 8902 -0.00532647 0.0659196 0.00667012 1 0 1 1 0 0 +EDGE2 9042 8922 0.047223 0.0112368 -0.0279043 1 0 1 1 0 0 +EDGE2 9042 8921 -1.07016 0.0237954 0.0300177 1 0 1 1 0 0 +EDGE2 9042 9021 -0.985749 0.0744628 0.0146193 1 0 1 1 0 0 +EDGE2 9042 9041 -0.955594 -0.010546 0.00853258 1 0 1 1 0 0 +EDGE2 9042 8901 -1.10469 0.0176765 -0.00298831 1 0 1 1 0 0 +EDGE2 9043 9022 -0.971517 0.00961347 -0.0098216 1 0 1 1 0 0 +EDGE2 9043 8924 0.977531 -0.0480814 -0.00285843 1 0 1 1 0 0 +EDGE2 9043 9024 1.07086 -0.048537 0.0342431 1 0 1 1 0 0 +EDGE2 9043 8904 1.00368 -0.0226735 0.0168236 1 0 1 1 0 0 +EDGE2 9043 8903 0.0277656 0.0449717 0.00403786 1 0 1 1 0 0 +EDGE2 9043 8923 -0.0272169 -0.0709954 -0.000489231 1 0 1 1 0 0 +EDGE2 9043 9023 0.0258647 0.0249276 -0.014639 1 0 1 1 0 0 +EDGE2 9043 9042 -0.968302 0.0437964 0.000586445 1 0 1 1 0 0 +EDGE2 9043 8902 -0.993151 0.00516849 0.0157637 1 0 1 1 0 0 +EDGE2 9043 8922 -0.9955 -0.0693241 0.00251024 1 0 1 1 0 0 +EDGE2 9044 8885 0.995102 0.129558 -3.16084 1 0 1 1 0 0 +EDGE2 9044 8925 1.0155 0.015769 0.0206293 1 0 1 1 0 0 +EDGE2 9044 9025 0.953425 -0.0381123 0.0105678 1 0 1 1 0 0 +EDGE2 9044 8905 1.02645 8.92146e-05 0.061155 1 0 1 1 0 0 +EDGE2 9044 9043 -1.04897 0.0233462 -0.0209651 1 0 1 1 0 0 +EDGE2 9044 8924 -0.0374778 0.0299844 -0.0497156 1 0 1 1 0 0 +EDGE2 9044 9024 0.0226444 0.079807 0.000180556 1 0 1 1 0 0 +EDGE2 9044 8904 0.00230901 0.0385507 0.0117864 1 0 1 1 0 0 +EDGE2 9044 8903 -1.03162 -0.0798594 0.0380141 1 0 1 1 0 0 +EDGE2 9044 8923 -1.06288 -0.00391525 0.00258722 1 0 1 1 0 0 +EDGE2 9044 9023 -0.90301 0.0351309 -0.0174479 1 0 1 1 0 0 +EDGE2 9045 8906 -0.071696 1.0711 1.54704 1 0 1 1 0 0 +EDGE2 9045 9026 -0.0310417 1.0162 1.56937 1 0 1 1 0 0 +EDGE2 9045 8886 0.0465976 1.01074 1.58394 1 0 1 1 0 0 +EDGE2 9045 8884 0.961625 0.0917679 -3.14249 1 0 1 1 0 0 +EDGE2 9045 8885 -0.0196397 -0.027906 -3.14856 1 0 1 1 0 0 +EDGE2 9045 8925 0.0207616 0.017539 -0.00265948 1 0 1 1 0 0 +EDGE2 9045 9025 -0.0208713 -0.0288805 0.00121822 1 0 1 1 0 0 +EDGE2 9045 8905 0.0363828 0.0700948 0.00481598 1 0 1 1 0 0 +EDGE2 9045 8926 -0.0537821 -1.07356 -1.57493 1 0 1 1 0 0 +EDGE2 9045 8924 -1.00221 0.00886177 0.000579266 1 0 1 1 0 0 +EDGE2 9045 9024 -1.03282 0.0495401 -0.0176194 1 0 1 1 0 0 +EDGE2 9045 9044 -0.979901 -0.0550841 0.0269769 1 0 1 1 0 0 +EDGE2 9045 8904 -1.04514 -0.00602552 0.0105617 1 0 1 1 0 0 +EDGE2 9046 8907 1.0477 -0.0256383 -0.0205194 1 0 1 1 0 0 +EDGE2 9046 9027 1.00117 -0.0425413 -0.00762071 1 0 1 1 0 0 +EDGE2 9046 8887 1.03578 0.0323447 0.0167916 1 0 1 1 0 0 +EDGE2 9046 8906 0.113911 0.0328918 0.0213992 1 0 1 1 0 0 +EDGE2 9046 9026 -0.048001 0.034031 -0.0100145 1 0 1 1 0 0 +EDGE2 9046 8886 0.0561392 0.0130088 -0.00213797 1 0 1 1 0 0 +EDGE2 9046 8885 -0.899985 0.0662178 1.58358 1 0 1 1 0 0 +EDGE2 9046 8925 -1.01271 0.0199499 -1.56018 1 0 1 1 0 0 +EDGE2 9046 9025 -0.986147 -0.0338985 -1.5802 1 0 1 1 0 0 +EDGE2 9046 9045 -1.04826 0.00973877 -1.55284 1 0 1 1 0 0 +EDGE2 9046 8905 -1.03198 0.0531728 -1.57054 1 0 1 1 0 0 +EDGE2 9047 8888 0.977624 -0.128954 0.00691572 1 0 1 1 0 0 +EDGE2 9047 9028 0.958999 0.0250223 -0.00191369 1 0 1 1 0 0 +EDGE2 9047 8908 1.03634 -0.00455217 0.00931833 1 0 1 1 0 0 +EDGE2 9047 9046 -1.00133 0.000996911 0.0156027 1 0 1 1 0 0 +EDGE2 9047 8907 -0.00439402 0.0531666 0.0156161 1 0 1 1 0 0 +EDGE2 9047 9027 0.0425322 0.0232832 -0.034785 1 0 1 1 0 0 +EDGE2 9047 8887 -0.0478591 0.00856681 0.00824376 1 0 1 1 0 0 +EDGE2 9047 8906 -0.94086 0.0562664 -0.0231409 1 0 1 1 0 0 +EDGE2 9047 9026 -0.934753 -0.0157902 0.00764356 1 0 1 1 0 0 +EDGE2 9047 8886 -0.974247 0.00400593 0.0113678 1 0 1 1 0 0 +EDGE2 9048 8909 1.00312 0.0821515 -0.0174782 1 0 1 1 0 0 +EDGE2 9048 9029 0.952213 0.000154897 0.0486473 1 0 1 1 0 0 +EDGE2 9048 8889 1.00537 0.0266607 -0.00366315 1 0 1 1 0 0 +EDGE2 9048 8888 -0.0105021 0.00972088 0.0185625 1 0 1 1 0 0 +EDGE2 9048 9028 0.0682303 -0.0345499 -0.00569699 1 0 1 1 0 0 +EDGE2 9048 8908 0.0294919 0.0204476 0.0209668 1 0 1 1 0 0 +EDGE2 9048 8907 -1.02412 0.0405543 0.0117753 1 0 1 1 0 0 +EDGE2 9048 9027 -1.08454 0.011817 0.0121984 1 0 1 1 0 0 +EDGE2 9048 9047 -1.0236 -0.00286327 -0.00674095 1 0 1 1 0 0 +EDGE2 9048 8887 -0.993904 -0.0228585 0.0194555 1 0 1 1 0 0 +EDGE2 9049 6310 0.990675 0.0230298 -3.15536 1 0 1 1 0 0 +EDGE2 9049 8910 1.04163 0.0141159 -0.0052347 1 0 1 1 0 0 +EDGE2 9049 8990 1.06469 -0.0348509 -3.11003 1 0 1 1 0 0 +EDGE2 9049 9030 1.04999 0.0311673 -0.0160684 1 0 1 1 0 0 +EDGE2 9049 8890 0.966787 0.0652437 0.00925234 1 0 1 1 0 0 +EDGE2 9049 8909 0.0216846 0.016774 -0.0114455 1 0 1 1 0 0 +EDGE2 9049 9029 0.0256326 0.0298675 0.0205666 1 0 1 1 0 0 +EDGE2 9049 8889 0.0291991 0.082559 0.0028304 1 0 1 1 0 0 +EDGE2 9049 8888 -1.1072 0.0192955 -0.0129316 1 0 1 1 0 0 +EDGE2 9049 9028 -1.06103 0.0585613 0.0102022 1 0 1 1 0 0 +EDGE2 9049 9048 -1.11143 0.00666775 0.0469697 1 0 1 1 0 0 +EDGE2 9049 8908 -0.913129 0.0598566 0.00768497 1 0 1 1 0 0 +EDGE2 9050 8989 0.971673 -0.110199 -3.12705 1 0 1 1 0 0 +EDGE2 9050 6309 0.957403 0.0280076 -3.11257 1 0 1 1 0 0 +EDGE2 9050 6311 0.0131466 -0.98761 -1.62096 1 0 1 1 0 0 +EDGE2 9050 6310 0.0350982 0.00884065 -3.09688 1 0 1 1 0 0 +EDGE2 9050 8910 -0.0436119 -0.0516461 0.00233096 1 0 1 1 0 0 +EDGE2 9050 8990 -0.0863327 0.0427157 -3.14678 1 0 1 1 0 0 +EDGE2 9050 9030 0.0410275 -0.0225573 -0.00358559 1 0 1 1 0 0 +EDGE2 9050 8890 0.00103191 -0.0985356 0.0088549 1 0 1 1 0 0 +EDGE2 9050 8909 -0.950341 0.0449392 -0.00832175 1 0 1 1 0 0 +EDGE2 9050 9029 -0.986533 -0.0257323 0.00783888 1 0 1 1 0 0 +EDGE2 9050 9049 -0.958219 0.0914156 0.00472566 1 0 1 1 0 0 +EDGE2 9050 8889 -1.05576 -0.056073 -0.0112676 1 0 1 1 0 0 +EDGE2 9050 8891 0.0695308 1.06856 1.56062 1 0 1 1 0 0 +EDGE2 9050 8991 -0.0584295 1.0875 1.57045 1 0 1 1 0 0 +EDGE2 9050 9031 0.0191264 1.01483 1.58956 1 0 1 1 0 0 +EDGE2 9050 8911 -0.0987221 1.02053 1.57286 1 0 1 1 0 0 +EDGE2 9051 9050 -0.961857 0.125797 -1.57642 1 0 1 1 0 0 +EDGE2 9051 6310 -1.02549 0.0423323 1.57915 1 0 1 1 0 0 +EDGE2 9051 8910 -0.999664 -0.032719 -1.61915 1 0 1 1 0 0 +EDGE2 9051 8990 -0.957697 0.0103455 1.58312 1 0 1 1 0 0 +EDGE2 9051 9030 -0.984181 0.000179794 -1.60461 1 0 1 1 0 0 +EDGE2 9051 8890 -0.950711 0.0454703 -1.56367 1 0 1 1 0 0 +EDGE2 9051 8892 0.928294 0.0261573 -0.0175839 1 0 1 1 0 0 +EDGE2 9051 8891 -0.0326742 -0.136341 0.0143829 1 0 1 1 0 0 +EDGE2 9051 8991 -0.0354581 -0.0620254 -0.0462004 1 0 1 1 0 0 +EDGE2 9051 9031 0.0237924 0.00951752 0.00434995 1 0 1 1 0 0 +EDGE2 9051 8911 0.0110923 -0.0294393 -0.00865175 1 0 1 1 0 0 +EDGE2 9051 8992 0.962848 -0.00324377 -0.0595089 1 0 1 1 0 0 +EDGE2 9051 9032 1.0547 0.00987657 -0.00254913 1 0 1 1 0 0 +EDGE2 9051 8912 1.03288 0.0177176 -0.00982982 1 0 1 1 0 0 +EDGE2 9052 8892 -0.0118758 0.107208 -0.0074595 1 0 1 1 0 0 +EDGE2 9052 8891 -0.950137 -0.05468 0.00944818 1 0 1 1 0 0 +EDGE2 9052 8991 -0.915838 0.0486774 -0.0167548 1 0 1 1 0 0 +EDGE2 9052 9031 -0.996602 0.00555898 -0.014195 1 0 1 1 0 0 +EDGE2 9052 9051 -1.1315 0.0102365 -0.0013026 1 0 1 1 0 0 +EDGE2 9052 8911 -1.00091 -0.0111306 -0.0243646 1 0 1 1 0 0 +EDGE2 9052 8992 0.0893758 -0.0830404 0.0587747 1 0 1 1 0 0 +EDGE2 9052 9032 -0.00943754 0.0797881 0.0317666 1 0 1 1 0 0 +EDGE2 9052 8912 -0.0263426 0.0192916 -0.00463198 1 0 1 1 0 0 +EDGE2 9052 8893 1.04737 -0.0639527 0.0119472 1 0 1 1 0 0 +EDGE2 9052 8993 0.999784 0.0521204 0.0408578 1 0 1 1 0 0 +EDGE2 9052 9033 0.959202 -0.0136562 0.0305742 1 0 1 1 0 0 +EDGE2 9052 8913 1.00005 -0.113218 0.0133776 1 0 1 1 0 0 +EDGE2 9053 8914 1.01484 0.00205783 -0.00224215 1 0 1 1 0 0 +EDGE2 9053 8892 -0.994854 0.0154625 -0.0029312 1 0 1 1 0 0 +EDGE2 9053 8992 -0.970006 0.0382062 -0.0162776 1 0 1 1 0 0 +EDGE2 9053 9032 -1.10295 0.0148684 -0.0268257 1 0 1 1 0 0 +EDGE2 9053 9052 -0.990073 -0.0218827 0.0187728 1 0 1 1 0 0 +EDGE2 9053 8912 -0.983823 0.116784 0.00183397 1 0 1 1 0 0 +EDGE2 9053 8893 -0.0195252 -0.0381568 -0.000131099 1 0 1 1 0 0 +EDGE2 9053 8993 -0.0142037 0.00639932 -0.00834941 1 0 1 1 0 0 +EDGE2 9053 9033 0.0549606 -0.000636001 -0.00115102 1 0 1 1 0 0 +EDGE2 9053 8913 0.00500361 0.0884681 0.00336165 1 0 1 1 0 0 +EDGE2 9053 9034 0.993686 -0.0137235 0.00194475 1 0 1 1 0 0 +EDGE2 9053 8994 1.04245 -0.0215406 0.0160683 1 0 1 1 0 0 +EDGE2 9053 8894 1.01825 -0.017036 -0.0214004 1 0 1 1 0 0 +EDGE2 9054 8914 0.00443473 0.0607785 0.00898744 1 0 1 1 0 0 +EDGE2 9054 8893 -1.03574 -0.0339906 -0.00870153 1 0 1 1 0 0 +EDGE2 9054 8993 -1.04993 -0.046986 -0.00712556 1 0 1 1 0 0 +EDGE2 9054 9033 -1.01996 -0.0240788 0.0208892 1 0 1 1 0 0 +EDGE2 9054 9053 -1.01231 -0.0113686 -0.0272574 1 0 1 1 0 0 +EDGE2 9054 8913 -0.923945 0.0386029 -0.00053008 1 0 1 1 0 0 +EDGE2 9054 9034 -0.0460798 0.0155272 -0.00292443 1 0 1 1 0 0 +EDGE2 9054 8994 -0.0262786 0.0459004 -0.0213345 1 0 1 1 0 0 +EDGE2 9054 8995 1.04929 0.0804775 0.00120681 1 0 1 1 0 0 +EDGE2 9054 9035 0.932171 -0.0833939 0.00229328 1 0 1 1 0 0 +EDGE2 9054 8894 -0.00236389 -0.013354 -0.00943413 1 0 1 1 0 0 +EDGE2 9054 9015 1.03526 -0.0629847 -3.13902 1 0 1 1 0 0 +EDGE2 9054 8135 1.03071 0.0590382 -3.13761 1 0 1 1 0 0 +EDGE2 9054 8895 1.01588 0.0776746 0.00244644 1 0 1 1 0 0 +EDGE2 9054 8915 0.961159 0.0722372 -0.0411719 1 0 1 1 0 0 +EDGE2 9054 8155 1.01791 -0.146568 -3.14245 1 0 1 1 0 0 +EDGE2 9055 8914 -0.955551 0.0308141 0.0212951 1 0 1 1 0 0 +EDGE2 9055 8156 0.0144315 -1.07923 -1.5626 1 0 1 1 0 0 +EDGE2 9055 8996 -0.0222504 -1.01501 -1.63141 1 0 1 1 0 0 +EDGE2 9055 8136 -0.00210484 -1.02831 -1.53021 1 0 1 1 0 0 +EDGE2 9055 9034 -1.0644 0.00719255 -0.0337299 1 0 1 1 0 0 +EDGE2 9055 9054 -0.992684 0.0221831 -0.00452636 1 0 1 1 0 0 +EDGE2 9055 8994 -1.0191 -0.0258496 -0.00780817 1 0 1 1 0 0 +EDGE2 9055 8995 0.0868206 0.000771732 0.0472812 1 0 1 1 0 0 +EDGE2 9055 9035 0.0609246 0.00934736 -0.00462726 1 0 1 1 0 0 +EDGE2 9055 8894 -1.05463 -0.0350143 0.0119978 1 0 1 1 0 0 +EDGE2 9055 9015 -0.0520871 -0.0375108 -3.15413 1 0 1 1 0 0 +EDGE2 9055 8135 -0.0322167 0.000724729 -3.16557 1 0 1 1 0 0 +EDGE2 9055 8895 -0.0263278 0.0302512 0.0104459 1 0 1 1 0 0 +EDGE2 9055 8915 0.0230065 -0.0282526 0.010552 1 0 1 1 0 0 +EDGE2 9055 8155 -0.011825 -0.0465366 -3.14063 1 0 1 1 0 0 +EDGE2 9055 8916 0.0563967 1.01636 1.56925 1 0 1 1 0 0 +EDGE2 9055 9016 -0.00437351 0.896626 1.58365 1 0 1 1 0 0 +EDGE2 9055 9036 -0.0116948 1.01886 1.54381 1 0 1 1 0 0 +EDGE2 9055 8896 -0.0108203 1.0151 1.61079 1 0 1 1 0 0 +EDGE2 9055 9014 1.02576 0.00123567 -3.13202 1 0 1 1 0 0 +EDGE2 9055 8134 1.03619 0.0247953 -3.16235 1 0 1 1 0 0 +EDGE2 9055 8154 0.883753 -0.00147871 -3.14 1 0 1 1 0 0 +EDGE2 9056 8995 -0.976819 0.139324 -1.57702 1 0 1 1 0 0 +EDGE2 9056 9035 -0.979614 -0.0206888 -1.56811 1 0 1 1 0 0 +EDGE2 9056 9055 -0.934269 -0.0700268 -1.5487 1 0 1 1 0 0 +EDGE2 9056 9015 -0.979537 0.0393191 1.56224 1 0 1 1 0 0 +EDGE2 9056 8135 -1.08923 -0.0305782 1.59019 1 0 1 1 0 0 +EDGE2 9056 8895 -0.995651 -0.0581192 -1.57285 1 0 1 1 0 0 +EDGE2 9056 8915 -1.01761 -0.0329588 -1.59588 1 0 1 1 0 0 +EDGE2 9056 8155 -1.0484 -0.100143 1.57107 1 0 1 1 0 0 +EDGE2 9056 8916 -0.0855353 0.0395156 0.0084343 1 0 1 1 0 0 +EDGE2 9056 9016 -0.00213463 -0.0399066 -0.0180464 1 0 1 1 0 0 +EDGE2 9056 9036 0.0721335 -0.01358 0.00434547 1 0 1 1 0 0 +EDGE2 9056 8896 0.00127264 0.00401881 -0.028481 1 0 1 1 0 0 +EDGE2 9056 8917 0.991142 -0.132978 0.00178347 1 0 1 1 0 0 +EDGE2 9056 9017 0.953401 0.00888072 0.041806 1 0 1 1 0 0 +EDGE2 9056 9037 0.996974 -0.0642943 0.0358834 1 0 1 1 0 0 +EDGE2 9056 8897 1.00449 0.00145671 -0.00261536 1 0 1 1 0 0 +EDGE2 9057 9056 -0.855627 -0.0332217 0.0501624 1 0 1 1 0 0 +EDGE2 9057 8916 -1.06271 0.0268566 -0.0146119 1 0 1 1 0 0 +EDGE2 9057 9016 -1.04855 -0.0287605 -0.0140709 1 0 1 1 0 0 +EDGE2 9057 9036 -0.953436 0.0474825 0.00111024 1 0 1 1 0 0 +EDGE2 9057 8896 -1.08873 0.0407377 0.00162543 1 0 1 1 0 0 +EDGE2 9057 8917 -0.0244589 0.0203366 0.00237569 1 0 1 1 0 0 +EDGE2 9057 9017 0.00890428 0.00580587 -0.0170006 1 0 1 1 0 0 +EDGE2 9057 9037 -0.0854687 0.0527773 -0.0249995 1 0 1 1 0 0 +EDGE2 9057 8897 0.0132644 0.00730635 -0.00785538 1 0 1 1 0 0 +EDGE2 9057 9038 1.05363 0.0801713 0.017974 1 0 1 1 0 0 +EDGE2 9057 8898 0.991543 -0.0548958 0.0186532 1 0 1 1 0 0 +EDGE2 9057 8918 0.983872 -0.076378 -0.00786752 1 0 1 1 0 0 +EDGE2 9057 9018 0.987026 -0.0173521 -0.00340313 1 0 1 1 0 0 +EDGE2 9058 9057 -1.02759 0.0411444 -0.014435 1 0 1 1 0 0 +EDGE2 9058 8917 -1.0357 -0.07782 0.0220394 1 0 1 1 0 0 +EDGE2 9058 9017 -0.99273 -0.116277 0.0299315 1 0 1 1 0 0 +EDGE2 9058 9037 -0.983441 -0.00396076 -0.00882994 1 0 1 1 0 0 +EDGE2 9058 8897 -0.905517 -0.0185252 0.0230702 1 0 1 1 0 0 +EDGE2 9058 9038 -0.0186022 -0.0135979 0.00728216 1 0 1 1 0 0 +EDGE2 9058 9039 0.997221 -0.020636 0.0216996 1 0 1 1 0 0 +EDGE2 9058 8898 0.0568511 -0.0170705 0.0211305 1 0 1 1 0 0 +EDGE2 9058 8918 0.0665759 -0.00428304 -0.0304497 1 0 1 1 0 0 +EDGE2 9058 9018 0.0269665 0.075932 0.00647718 1 0 1 1 0 0 +EDGE2 9058 8919 1.02216 -0.00486118 -0.0417089 1 0 1 1 0 0 +EDGE2 9058 9019 1.11551 -0.0304963 0.0400766 1 0 1 1 0 0 +EDGE2 9058 8899 0.972375 0.000251072 0.00338773 1 0 1 1 0 0 +EDGE2 9059 9058 -0.994894 0.0411225 0.00517601 1 0 1 1 0 0 +EDGE2 9059 9038 -0.98469 -0.102291 0.0196879 1 0 1 1 0 0 +EDGE2 9059 9039 -0.0155409 0.0996619 -0.0169466 1 0 1 1 0 0 +EDGE2 9059 8898 -0.993893 0.0315203 -0.0107638 1 0 1 1 0 0 +EDGE2 9059 8918 -1.03182 0.0513012 -0.00824058 1 0 1 1 0 0 +EDGE2 9059 9018 -1.03713 0.00122022 0.0416784 1 0 1 1 0 0 +EDGE2 9059 8919 -0.0205451 -0.10489 -0.0148862 1 0 1 1 0 0 +EDGE2 9059 9019 -0.0528062 -0.0460584 -0.000763492 1 0 1 1 0 0 +EDGE2 9059 8899 0.0019166 0.0576936 0.000611378 1 0 1 1 0 0 +EDGE2 9059 8920 1.04195 0.0187575 -0.00713303 1 0 1 1 0 0 +EDGE2 9059 9020 1.05648 -0.0285817 -0.0242565 1 0 1 1 0 0 +EDGE2 9059 9040 1.07805 0.0166099 -0.000901011 1 0 1 1 0 0 +EDGE2 9059 8900 1.06601 0.0260126 0.0206999 1 0 1 1 0 0 +EDGE2 9060 9039 -0.965912 -0.0186194 -0.000637771 1 0 1 1 0 0 +EDGE2 9060 9059 -0.95962 -0.0323267 0.0222652 1 0 1 1 0 0 +EDGE2 9060 8919 -1.01541 -0.00197987 0.0254504 1 0 1 1 0 0 +EDGE2 9060 9019 -0.948056 0.122517 -0.0182015 1 0 1 1 0 0 +EDGE2 9060 8899 -1.09083 0.0515461 -0.0178467 1 0 1 1 0 0 +EDGE2 9060 8921 0.120687 1.05042 1.51577 1 0 1 1 0 0 +EDGE2 9060 9021 -0.0222664 0.932264 1.58871 1 0 1 1 0 0 +EDGE2 9060 9041 -0.0793392 1.02887 1.55135 1 0 1 1 0 0 +EDGE2 9060 8901 -0.0787652 0.926265 1.58238 1 0 1 1 0 0 +EDGE2 9060 8920 -0.0194744 0.0433982 0.0126013 1 0 1 1 0 0 +EDGE2 9060 9020 -0.0918462 0.0706471 -0.0202273 1 0 1 1 0 0 +EDGE2 9060 9040 -0.118011 -0.0159193 -0.0243364 1 0 1 1 0 0 +EDGE2 9060 8900 0.0470918 -0.0367434 -0.0317639 1 0 1 1 0 0 +EDGE2 9061 9060 -0.970567 0.00182471 1.57499 1 0 1 1 0 0 +EDGE2 9061 8920 -1.08087 -0.036464 1.58173 1 0 1 1 0 0 +EDGE2 9061 9020 -0.972305 -0.0334374 1.58461 1 0 1 1 0 0 +EDGE2 9061 9040 -1.0509 0.0319641 1.58412 1 0 1 1 0 0 +EDGE2 9061 8900 -1.06806 0.0224727 1.55764 1 0 1 1 0 0 +EDGE2 9062 9061 -0.983786 -0.109896 -0.0074462 1 0 1 1 0 0 +EDGE2 9063 9062 -0.962198 -0.0645144 -0.0128496 1 0 1 1 0 0 +EDGE2 9064 9063 -0.987127 -0.0889908 0.00299064 1 0 1 1 0 0 +EDGE2 9065 9064 -1.00575 -0.0167768 0.022415 1 0 1 1 0 0 +EDGE2 9066 9065 -1.07 0.0523769 1.54935 1 0 1 1 0 0 +EDGE2 9067 9066 -0.982243 0.0817366 0.0231866 1 0 1 1 0 0 +EDGE2 9068 9067 -0.955042 0.0017555 -0.0330128 1 0 1 1 0 0 +EDGE2 9069 9010 0.936137 0.0221527 -3.13308 1 0 1 1 0 0 +EDGE2 9069 8170 0.907693 -0.0563832 -3.11332 1 0 1 1 0 0 +EDGE2 9069 8130 1.04342 0.00830579 -3.16752 1 0 1 1 0 0 +EDGE2 9069 8150 0.945284 0.00626885 -3.14959 1 0 1 1 0 0 +EDGE2 9069 9068 -0.953875 0.0611644 0.0309272 1 0 1 1 0 0 +EDGE2 9070 8169 1.02591 -0.0464261 -3.14091 1 0 1 1 0 0 +EDGE2 9070 8129 0.971499 -0.0361745 -3.14826 1 0 1 1 0 0 +EDGE2 9070 9009 0.932948 0.0574931 -3.12868 1 0 1 1 0 0 +EDGE2 9070 8149 0.967759 0.0323385 -3.1719 1 0 1 1 0 0 +EDGE2 9070 8171 -0.00250609 0.994087 1.57949 1 0 1 1 0 0 +EDGE2 9070 9011 -0.0673396 -0.941478 -1.61297 1 0 1 1 0 0 +EDGE2 9070 9010 0.00904554 0.0182842 -3.12136 1 0 1 1 0 0 +EDGE2 9070 8170 0.0277848 -0.00948953 -3.12927 1 0 1 1 0 0 +EDGE2 9070 8130 -0.0293313 -0.0516682 -3.18444 1 0 1 1 0 0 +EDGE2 9070 8131 -0.0429931 -0.931707 -1.55722 1 0 1 1 0 0 +EDGE2 9070 8151 0.0559349 -0.96041 -1.5945 1 0 1 1 0 0 +EDGE2 9070 8150 0.00471404 -0.0401281 -3.17468 1 0 1 1 0 0 +EDGE2 9070 9069 -1.02476 0.0228768 -0.0144038 1 0 1 1 0 0 +EDGE2 9071 8171 -0.0622612 0.0239271 -0.00939734 1 0 1 1 0 0 +EDGE2 9071 9070 -1.02406 -0.0389907 -1.55294 1 0 1 1 0 0 +EDGE2 9071 9010 -1.09051 0.0624794 1.58208 1 0 1 1 0 0 +EDGE2 9071 8170 -1.04236 -0.0156197 1.53709 1 0 1 1 0 0 +EDGE2 9071 8130 -1.09443 -0.0330555 1.55346 1 0 1 1 0 0 +EDGE2 9071 8150 -1.02275 -0.0373379 1.55415 1 0 1 1 0 0 +EDGE2 9071 8172 0.99173 -0.0670865 -0.0305777 1 0 1 1 0 0 +EDGE2 9072 8171 -0.902018 0.0991496 -0.00309054 1 0 1 1 0 0 +EDGE2 9072 9071 -1.04683 -0.0785643 0.00862761 1 0 1 1 0 0 +EDGE2 9072 8172 0.0229325 -0.0421096 0.00561268 1 0 1 1 0 0 +EDGE2 9072 8173 0.956365 0.00532632 0.00761737 1 0 1 1 0 0 +EDGE2 9073 9072 -1.06785 0.0211122 -0.00834079 1 0 1 1 0 0 +EDGE2 9073 8172 -0.949073 0.036956 0.00696691 1 0 1 1 0 0 +EDGE2 9073 8174 1.02241 0.0262931 -0.0190285 1 0 1 1 0 0 +EDGE2 9073 8173 0.0366684 0.0328618 0.00237302 1 0 1 1 0 0 +EDGE2 9074 9073 -1.00798 0.00131185 0.00782188 1 0 1 1 0 0 +EDGE2 9074 8175 0.932766 0.0377979 -0.035862 1 0 1 1 0 0 +EDGE2 9074 8174 0.0234655 -0.0790669 1.11623e-05 1 0 1 1 0 0 +EDGE2 9074 8173 -1.00045 0.0517292 0.0401042 1 0 1 1 0 0 +EDGE2 9075 9074 -0.964597 0.00538844 -0.00394904 1 0 1 1 0 0 +EDGE2 9075 8175 0.0260555 0.00796019 -0.023735 1 0 1 1 0 0 +EDGE2 9075 8174 -0.979966 -0.062322 0.0224059 1 0 1 1 0 0 +EDGE2 9075 8176 0.0513012 0.959874 1.56514 1 0 1 1 0 0 +EDGE2 9076 9075 -0.965407 0.08217 1.60594 1 0 1 1 0 0 +EDGE2 9076 8175 -0.919858 0.0313346 1.57446 1 0 1 1 0 0 +EDGE2 9077 9076 -1.03395 -0.00863375 -0.00133483 1 0 1 1 0 0 +EDGE2 9078 9077 -0.986865 -0.0645778 -0.0183781 1 0 1 1 0 0 +EDGE2 9079 8120 0.997037 -0.0324931 -3.14522 1 0 1 1 0 0 +EDGE2 9079 9078 -1.03534 -0.0107139 0.0043489 1 0 1 1 0 0 +EDGE2 9080 8120 0.00567266 0.0250141 -3.13089 1 0 1 1 0 0 +EDGE2 9080 8119 0.989229 0.00687936 -3.11814 1 0 1 1 0 0 +EDGE2 9080 8121 -0.00296248 -1.00406 -1.58182 1 0 1 1 0 0 +EDGE2 9080 9079 -0.887477 0.0465254 0.00600947 1 0 1 1 0 0 +EDGE2 9081 8120 -1.02387 -0.0335451 1.58304 1 0 1 1 0 0 +EDGE2 9081 9080 -0.992735 -0.0302823 -1.59336 1 0 1 1 0 0 +EDGE2 9082 9081 -1.01673 0.039245 -0.0210808 1 0 1 1 0 0 +EDGE2 9083 9082 -0.995307 0.018482 0.0332745 1 0 1 1 0 0 +EDGE2 9084 9083 -0.997095 0.0454083 -0.01004 1 0 1 1 0 0 +EDGE2 9085 9084 -1.03352 -0.0868721 -0.0284617 1 0 1 1 0 0 +EDGE2 9086 9085 -1.0227 -9.92693e-05 -1.55026 1 0 1 1 0 0 +EDGE2 9087 9086 -0.970608 -0.00682637 -0.0513108 1 0 1 1 0 0 +EDGE2 9088 9087 -0.979238 -0.0483449 0.00899507 1 0 1 1 0 0 +EDGE2 9089 9088 -1.0305 0.0563565 -0.00689117 1 0 1 1 0 0 +EDGE2 9090 9089 -1.00634 -0.00444385 0.0123417 1 0 1 1 0 0 +EDGE2 9091 9090 -1.00113 -0.0811776 -1.57079 1 0 1 1 0 0 +EDGE2 9092 9091 -0.927797 -0.0155406 0.00360807 1 0 1 1 0 0 +EDGE2 9093 9092 -0.98485 0.0295746 0.0371126 1 0 1 1 0 0 +EDGE2 9094 9075 0.907911 -0.0548126 -3.19085 1 0 1 1 0 0 +EDGE2 9094 9093 -0.963282 -0.0611483 0.00135874 1 0 1 1 0 0 +EDGE2 9094 8175 1.04664 0.0370089 -3.11522 1 0 1 1 0 0 +EDGE2 9095 9076 -0.0737243 0.941281 1.57327 1 0 1 1 0 0 +EDGE2 9095 9074 1.01461 0.0247389 -3.13637 1 0 1 1 0 0 +EDGE2 9095 9075 0.0161631 0.0048263 -3.12167 1 0 1 1 0 0 +EDGE2 9095 9094 -0.973093 0.0173378 -0.0117331 1 0 1 1 0 0 +EDGE2 9095 8175 0.0423495 0.0722137 -3.1375 1 0 1 1 0 0 +EDGE2 9095 8174 1.08944 0.0144182 -3.15036 1 0 1 1 0 0 +EDGE2 9095 8176 0.0766336 -1.03809 -1.5527 1 0 1 1 0 0 +EDGE2 9096 9077 1.08454 -0.0220295 0.00424214 1 0 1 1 0 0 +EDGE2 9096 9076 0.0897651 0.0606326 -0.00797454 1 0 1 1 0 0 +EDGE2 9096 9075 -0.957795 0.00704206 1.60837 1 0 1 1 0 0 +EDGE2 9096 9095 -1.01678 0.0785464 -1.55871 1 0 1 1 0 0 +EDGE2 9096 8175 -0.990715 0.0318684 1.5659 1 0 1 1 0 0 +EDGE2 9097 9078 0.962506 -0.0214998 -0.0021616 1 0 1 1 0 0 +EDGE2 9097 9077 -0.057968 0.0175731 0.0348813 1 0 1 1 0 0 +EDGE2 9097 9096 -0.983463 0.0605031 0.0105938 1 0 1 1 0 0 +EDGE2 9097 9076 -1.02456 -0.0776311 0.0112919 1 0 1 1 0 0 +EDGE2 9098 9079 1.07282 0.00193115 -0.0055824 1 0 1 1 0 0 +EDGE2 9098 9078 0.0181425 -0.00428084 0.0119051 1 0 1 1 0 0 +EDGE2 9098 9077 -1.06829 -0.0642756 0.00887418 1 0 1 1 0 0 +EDGE2 9098 9097 -0.997312 -0.0563655 0.00370476 1 0 1 1 0 0 +EDGE2 9099 8120 1.03448 -0.08703 -3.10416 1 0 1 1 0 0 +EDGE2 9099 9080 1.0251 -0.00493324 0.0194871 1 0 1 1 0 0 +EDGE2 9099 9079 0.026756 -0.0682926 -0.00747276 1 0 1 1 0 0 +EDGE2 9099 9098 -0.919795 -0.082264 0.016225 1 0 1 1 0 0 +EDGE2 9099 9078 -1.02412 -0.0158273 -0.0243331 1 0 1 1 0 0 +EDGE2 9100 8120 -0.0126476 0.0549201 -3.1737 1 0 1 1 0 0 +EDGE2 9100 8119 0.880833 0.0302282 -3.13323 1 0 1 1 0 0 +EDGE2 9100 9081 -0.0465634 1.03999 1.56819 1 0 1 1 0 0 +EDGE2 9100 9080 -0.0336721 0.0699097 0.0262761 1 0 1 1 0 0 +EDGE2 9100 8121 -0.0676603 -0.881629 -1.56608 1 0 1 1 0 0 +EDGE2 9100 9099 -1.07242 -0.0626619 0.00408028 1 0 1 1 0 0 +EDGE2 9100 9079 -1.01587 0.0284628 -0.00261203 1 0 1 1 0 0 +EDGE2 9101 8120 -0.995704 -0.0167389 1.58572 1 0 1 1 0 0 +EDGE2 9101 9081 -0.043066 0.0598027 0.0135393 1 0 1 1 0 0 +EDGE2 9101 9080 -0.872789 0.022976 -1.59229 1 0 1 1 0 0 +EDGE2 9101 9100 -0.953222 -0.0221282 -1.60701 1 0 1 1 0 0 +EDGE2 9101 9082 1.02578 0.0728623 0.0339593 1 0 1 1 0 0 +EDGE2 9102 9081 -1.02967 -0.0801642 -0.0117925 1 0 1 1 0 0 +EDGE2 9102 9101 -1.01968 0.0685701 -0.0301783 1 0 1 1 0 0 +EDGE2 9102 9082 0.0153964 -0.0226994 0.0342049 1 0 1 1 0 0 +EDGE2 9102 9083 1.00593 0.0113724 -0.0281587 1 0 1 1 0 0 +EDGE2 9103 9082 -1.00672 0.0205118 -0.00543728 1 0 1 1 0 0 +EDGE2 9103 9102 -0.957527 0.0824024 -0.00777626 1 0 1 1 0 0 +EDGE2 9103 9083 -0.000521946 0.0172641 0.0606939 1 0 1 1 0 0 +EDGE2 9103 9084 1.00572 0.0906687 0.00795843 1 0 1 1 0 0 +EDGE2 9104 9103 -0.968393 -0.0437553 -0.0130832 1 0 1 1 0 0 +EDGE2 9104 9083 -1.04424 0.0237253 0.0282467 1 0 1 1 0 0 +EDGE2 9104 9085 1.00815 0.0989222 -0.0350636 1 0 1 1 0 0 +EDGE2 9104 9084 -0.0504517 0.0322774 -0.0210999 1 0 1 1 0 0 +EDGE2 9105 9085 0.0296512 -0.0606206 -0.00647873 1 0 1 1 0 0 +EDGE2 9105 9084 -1.00316 0.039959 -0.01996 1 0 1 1 0 0 +EDGE2 9105 9104 -1.04187 -0.0478089 0.0137023 1 0 1 1 0 0 +EDGE2 9105 9086 0.0296133 0.98293 1.56845 1 0 1 1 0 0 +EDGE2 9106 9085 -1.13532 -0.0232596 1.57401 1 0 1 1 0 0 +EDGE2 9106 9105 -0.957346 0.0502701 1.55453 1 0 1 1 0 0 +EDGE2 9107 9106 -0.994952 -0.00215993 0.0166999 1 0 1 1 0 0 +EDGE2 9108 9107 -1.03177 0.00816902 0.0236493 1 0 1 1 0 0 +EDGE2 9109 9108 -0.980688 -0.0498374 -0.0175952 1 0 1 1 0 0 +EDGE2 9110 9109 -1.00303 0.0169646 -0.00938213 1 0 1 1 0 0 +EDGE2 9111 9110 -0.947682 0.0313 -1.55966 1 0 1 1 0 0 +EDGE2 9112 9111 -1.05179 -0.0835672 -0.00173209 1 0 1 1 0 0 +EDGE2 9113 9112 -1.00818 0.00999802 -0.0245837 1 0 1 1 0 0 +EDGE2 9114 9113 -0.956015 0.0689923 -0.0872822 1 0 1 1 0 0 +EDGE2 9115 9114 -0.966644 0.0562027 -0.0335025 1 0 1 1 0 0 +EDGE2 9116 9115 -0.971501 0.0017512 1.57298 1 0 1 1 0 0 +EDGE2 9117 9116 -1.08858 -0.0238587 -0.0113402 1 0 1 1 0 0 +EDGE2 9118 9117 -1.06695 0.0281446 0.0306551 1 0 1 1 0 0 +EDGE2 9119 6560 0.921666 0.0620897 -3.11542 1 0 1 1 0 0 +EDGE2 9119 6580 1.0265 0.00162423 -3.11401 1 0 1 1 0 0 +EDGE2 9119 9118 -0.992637 0.0336324 -0.0144968 1 0 1 1 0 0 +EDGE2 9120 6579 0.967304 -0.0325203 -3.11424 1 0 1 1 0 0 +EDGE2 9120 6559 0.890096 -0.00542472 -3.14728 1 0 1 1 0 0 +EDGE2 9120 6560 0.0662824 -0.00264605 -3.11209 1 0 1 1 0 0 +EDGE2 9120 6561 -0.095268 -0.992345 -1.57801 1 0 1 1 0 0 +EDGE2 9120 6581 0.00529377 -1.03494 -1.56073 1 0 1 1 0 0 +EDGE2 9120 6580 0.0449194 0.0131269 -3.13321 1 0 1 1 0 0 +EDGE2 9120 9119 -1.0018 -0.00415515 0.0434868 1 0 1 1 0 0 +EDGE2 9121 6560 -1.00188 0.0454087 1.59148 1 0 1 1 0 0 +EDGE2 9121 9120 -0.935117 0.0253071 -1.59855 1 0 1 1 0 0 +EDGE2 9121 6580 -0.963586 -0.0540957 1.57577 1 0 1 1 0 0 +EDGE2 9122 9121 -0.944835 0.0271711 -0.00907785 1 0 1 1 0 0 +EDGE2 9123 9122 -1.01846 -0.0141809 0.00713058 1 0 1 1 0 0 +EDGE2 9124 9123 -0.984912 0.00520205 -0.00489122 1 0 1 1 0 0 +EDGE2 9125 9124 -1.05254 0.0433906 -0.012057 1 0 1 1 0 0 +EDGE2 9126 9125 -0.93177 0.0329427 -1.53524 1 0 1 1 0 0 +EDGE2 9127 9126 -1.00232 -0.0829151 0.00594923 1 0 1 1 0 0 +EDGE2 9128 9127 -1.02995 -0.0220644 0.00322348 1 0 1 1 0 0 +EDGE2 9129 9128 -0.989384 -0.0209966 -0.0250698 1 0 1 1 0 0 +EDGE2 9130 9129 -0.933943 0.0234256 0.00983103 1 0 1 1 0 0 +EDGE2 9131 9130 -0.997782 -0.0255816 1.56297 1 0 1 1 0 0 +EDGE2 9132 9131 -0.963632 -0.0217058 0.0103374 1 0 1 1 0 0 +EDGE2 9133 9132 -1.02158 0.0121149 -0.0206818 1 0 1 1 0 0 +EDGE2 9134 9133 -0.932831 0.035291 -0.00700133 1 0 1 1 0 0 +EDGE2 9135 9134 -0.980772 -0.00584497 -0.00188594 1 0 1 1 0 0 +EDGE2 9136 9135 -1.0239 -0.097066 -1.56773 1 0 1 1 0 0 +EDGE2 9137 9136 -1.00977 0.00286906 -0.014884 1 0 1 1 0 0 +EDGE2 9138 9137 -1.02056 -0.0234424 -0.0196023 1 0 1 1 0 0 +EDGE2 9139 9138 -1.0091 -0.0722562 0.0136575 1 0 1 1 0 0 +EDGE2 9140 9139 -1.03097 0.0511319 0.0340867 1 0 1 1 0 0 +EDGE2 9141 9140 -0.961095 0.117667 1.58587 1 0 1 1 0 0 +EDGE2 9142 9141 -1.04045 -0.0875409 -0.00117807 1 0 1 1 0 0 +EDGE2 9143 9142 -0.953048 0.0553946 -0.0259988 1 0 1 1 0 0 +EDGE2 9144 9143 -0.963396 0.0211156 -0.0248283 1 0 1 1 0 0 +EDGE2 9145 9144 -1.02959 -0.0441053 0.0347765 1 0 1 1 0 0 +EDGE2 9146 9145 -1.14492 -0.00224111 -1.57044 1 0 1 1 0 0 +EDGE2 9147 9146 -0.993637 -0.0939479 0.0314225 1 0 1 1 0 0 +EDGE2 9148 9147 -1.00061 0.0234419 -0.00989295 1 0 1 1 0 0 +EDGE2 9149 9148 -0.957919 0.0605087 -0.042793 1 0 1 1 0 0 +EDGE2 9150 9149 -0.964058 -0.0368748 0.00565274 1 0 1 1 0 0 +EDGE2 9151 9150 -0.987836 0.083566 -1.54132 1 0 1 1 0 0 +EDGE2 9152 9151 -1.00198 0.00566272 0.0261687 1 0 1 1 0 0 +EDGE2 9153 9152 -0.917407 0.0567459 -0.00822599 1 0 1 1 0 0 +EDGE2 9154 9153 -1.03068 0.0580372 -0.014801 1 0 1 1 0 0 +EDGE2 9155 9154 -0.892297 0.0663915 -0.0172804 1 0 1 1 0 0 +EDGE2 9156 9155 -1.01678 0.040587 1.55328 1 0 1 1 0 0 +EDGE2 9157 9156 -1.03235 0.0399526 -0.00787007 1 0 1 1 0 0 +EDGE2 9158 9157 -1.11657 -0.0252283 -0.00407897 1 0 1 1 0 0 +EDGE2 9159 9158 -1.07904 0.00185199 -0.00763656 1 0 1 1 0 0 +EDGE2 9160 9159 -0.992176 -0.117342 0.00316356 1 0 1 1 0 0 +EDGE2 9161 9160 -0.972718 -0.0783158 -1.58825 1 0 1 1 0 0 +EDGE2 9162 9161 -1.00675 -0.0166092 0.00695352 1 0 1 1 0 0 +EDGE2 9163 9162 -0.972615 0.0065956 -0.0102515 1 0 1 1 0 0 +EDGE2 9164 9163 -0.927898 -0.0575097 -0.0289888 1 0 1 1 0 0 +EDGE2 9165 9164 -1.00153 0.036179 -0.012712 1 0 1 1 0 0 +EDGE2 9166 9165 -1.08038 0.0148838 -1.58264 1 0 1 1 0 0 +EDGE2 9167 9166 -0.986829 0.067831 0.00796219 1 0 1 1 0 0 +EDGE2 9168 9167 -1.08215 0.012851 -0.0160282 1 0 1 1 0 0 +EDGE2 9169 9168 -1.06843 -0.105051 0.0106849 1 0 1 1 0 0 +EDGE2 9170 9169 -0.946037 -0.0708706 -0.00667633 1 0 1 1 0 0 +EDGE2 9171 9170 -1.06358 -0.0645115 1.56215 1 0 1 1 0 0 +EDGE2 9172 9171 -0.980371 -0.00181963 0.00221091 1 0 1 1 0 0 +EDGE2 9173 9172 -1.09234 -0.0457752 -0.000806765 1 0 1 1 0 0 +EDGE2 9174 9173 -0.969264 0.0288708 0.0206026 1 0 1 1 0 0 +EDGE2 9175 9174 -1.01059 -0.0642732 0.0102713 1 0 1 1 0 0 +EDGE2 9176 9175 -0.913895 0.00903393 -1.54279 1 0 1 1 0 0 +EDGE2 9177 9176 -0.976613 -0.0278445 -0.0168232 1 0 1 1 0 0 +EDGE2 9178 9177 -1.02022 -0.0683934 -0.0125025 1 0 1 1 0 0 +EDGE2 9179 9178 -0.987226 -0.0302377 0.0139352 1 0 1 1 0 0 +EDGE2 9180 9179 -1.02226 0.0415302 0.00126 1 0 1 1 0 0 +EDGE2 9181 9180 -1.02182 -0.0423883 -1.59438 1 0 1 1 0 0 +EDGE2 9182 9181 -1.01677 -0.0429495 -0.00412613 1 0 1 1 0 0 +EDGE2 9183 9182 -1.04832 -0.0739093 0.0122546 1 0 1 1 0 0 +EDGE2 9184 9183 -1.05188 0.00799076 -0.0122626 1 0 1 1 0 0 +EDGE2 9185 9184 -0.954591 -0.0744943 0.0319715 1 0 1 1 0 0 +EDGE2 9186 9185 -1.15792 0.0338819 -1.55493 1 0 1 1 0 0 +EDGE2 9187 9186 -0.986206 0.0616289 0.00831754 1 0 1 1 0 0 +EDGE2 9188 9187 -1.1188 0.0624141 0.0132599 1 0 1 1 0 0 +EDGE2 9189 9188 -1.01944 -0.06503 -0.03282 1 0 1 1 0 0 +EDGE2 9189 9170 0.992546 0.0529559 -3.14672 1 0 1 1 0 0 +EDGE2 9190 9189 -0.882694 -0.0597499 0.0179486 1 0 1 1 0 0 +EDGE2 9190 9170 0.00603088 0.0478082 -3.14823 1 0 1 1 0 0 +EDGE2 9190 9171 0.0823476 0.971426 1.58244 1 0 1 1 0 0 +EDGE2 9190 9169 1.04394 -0.0218458 -3.12002 1 0 1 1 0 0 +EDGE2 9191 9172 1.00921 0.00160349 0.00217965 1 0 1 1 0 0 +EDGE2 9191 9170 -0.963051 -0.0210244 1.57639 1 0 1 1 0 0 +EDGE2 9191 9171 -0.0658879 -0.0500487 0.00744481 1 0 1 1 0 0 +EDGE2 9191 9190 -1.01134 0.0360904 -1.55946 1 0 1 1 0 0 +EDGE2 9192 9173 0.922265 0.0967282 0.00877169 1 0 1 1 0 0 +EDGE2 9192 9172 0.00608693 0.0853488 -0.0298873 1 0 1 1 0 0 +EDGE2 9192 9171 -0.97216 -0.0212288 -0.0160932 1 0 1 1 0 0 +EDGE2 9192 9191 -0.991989 -0.0338353 -0.00030292 1 0 1 1 0 0 +EDGE2 9193 9173 -0.0713601 0.0395119 -0.0439626 1 0 1 1 0 0 +EDGE2 9193 9174 0.927884 -0.00781141 -0.0178372 1 0 1 1 0 0 +EDGE2 9193 9192 -1.0076 0.0122029 0.0211604 1 0 1 1 0 0 +EDGE2 9193 9172 -1.04086 -0.102248 -0.00959246 1 0 1 1 0 0 +EDGE2 9194 9173 -1.04283 -0.0878096 -0.00758116 1 0 1 1 0 0 +EDGE2 9194 9175 0.966337 -0.09598 -0.00241988 1 0 1 1 0 0 +EDGE2 9194 9174 -0.0455891 -0.0808551 0.0158375 1 0 1 1 0 0 +EDGE2 9194 9193 -1.00307 -0.0499687 0.0164634 1 0 1 1 0 0 +EDGE2 9195 9176 -0.0146499 0.972097 1.5705 1 0 1 1 0 0 +EDGE2 9195 9175 -0.0313987 -0.00123347 0.00265931 1 0 1 1 0 0 +EDGE2 9195 9174 -1.10892 0.0175204 0.012448 1 0 1 1 0 0 +EDGE2 9195 9194 -0.949778 0.0141131 0.0211137 1 0 1 1 0 0 +EDGE2 9196 9195 -0.910649 0.0127312 1.53878 1 0 1 1 0 0 +EDGE2 9196 9175 -1.0175 0.0212756 1.59681 1 0 1 1 0 0 +EDGE2 9197 9196 -1.04214 -0.0464891 0.011082 1 0 1 1 0 0 +EDGE2 9198 9197 -1.03041 0.0692327 0.0262751 1 0 1 1 0 0 +EDGE2 9199 9198 -1.00003 0.0209892 0.0191607 1 0 1 1 0 0 +EDGE2 9200 9199 -1.01566 -0.0578284 0.00964944 1 0 1 1 0 0 +EDGE2 9201 9200 -1.02409 -0.0554013 -1.56655 1 0 1 1 0 0 +EDGE2 9202 9201 -1.006 0.0199369 -0.0161073 1 0 1 1 0 0 +EDGE2 9203 9202 -1.03526 -0.0507723 -0.0240116 1 0 1 1 0 0 +EDGE2 9204 8185 0.983076 -0.0512076 -3.15372 1 0 1 1 0 0 +EDGE2 9204 9203 -0.970894 0.0110777 -0.0206568 1 0 1 1 0 0 +EDGE2 9205 8184 0.901301 -0.101331 -3.15256 1 0 1 1 0 0 +EDGE2 9205 8186 -0.0663998 -1.02407 -1.59116 1 0 1 1 0 0 +EDGE2 9205 8185 -0.0028206 -0.0686419 -3.13257 1 0 1 1 0 0 +EDGE2 9205 9204 -1.07698 -0.0233763 -0.0108813 1 0 1 1 0 0 +EDGE2 9206 8187 0.994075 -0.0804281 -0.0106977 1 0 1 1 0 0 +EDGE2 9206 9205 -0.960677 -0.0911039 1.56641 1 0 1 1 0 0 +EDGE2 9206 8186 0.0335962 0.00384202 0.0112457 1 0 1 1 0 0 +EDGE2 9206 8185 -1.02435 0.0574228 -1.54426 1 0 1 1 0 0 +EDGE2 9207 8187 -0.0148327 0.100952 0.0197758 1 0 1 1 0 0 +EDGE2 9207 8186 -0.951629 0.0858934 0.00149355 1 0 1 1 0 0 +EDGE2 9207 9206 -1.05555 0.0213626 0.0308079 1 0 1 1 0 0 +EDGE2 9207 8188 0.979119 0.102171 -0.00637182 1 0 1 1 0 0 +EDGE2 9208 8189 0.941544 0.0457507 0.0111928 1 0 1 1 0 0 +EDGE2 9208 8187 -0.993574 -0.0304983 0.00401802 1 0 1 1 0 0 +EDGE2 9208 9207 -1.03219 0.00515106 0.0536484 1 0 1 1 0 0 +EDGE2 9208 8188 -0.000435529 -0.100403 -0.0146613 1 0 1 1 0 0 +EDGE2 9209 8189 -0.0469967 0.0299383 0.0163489 1 0 1 1 0 0 +EDGE2 9209 8188 -1.10415 -0.0139679 0.00136265 1 0 1 1 0 0 +EDGE2 9209 9208 -0.962483 -0.00146608 -0.00815259 1 0 1 1 0 0 +EDGE2 9209 8190 0.977852 -0.0357401 0.0126048 1 0 1 1 0 0 +EDGE2 9210 8189 -1.05503 0.00399388 0.00348412 1 0 1 1 0 0 +EDGE2 9210 9209 -1.0434 0.0316936 -0.0317212 1 0 1 1 0 0 +EDGE2 9210 8190 -0.0513881 0.03505 -0.0222665 1 0 1 1 0 0 +EDGE2 9210 8191 -0.126388 -0.970041 -1.57792 1 0 1 1 0 0 +EDGE2 9211 8190 -1.03119 -0.0413195 -1.57065 1 0 1 1 0 0 +EDGE2 9211 9210 -0.96172 -0.0388778 -1.55344 1 0 1 1 0 0 +EDGE2 9212 9211 -0.964036 0.0327801 -0.00820195 1 0 1 1 0 0 +EDGE2 9213 9212 -0.9948 -0.082239 0.0133666 1 0 1 1 0 0 +EDGE2 9214 9213 -1.06049 -0.023977 0.0167492 1 0 1 1 0 0 +EDGE2 9215 9214 -0.997283 -0.00245533 0.0177648 1 0 1 1 0 0 +EDGE2 9216 9215 -0.968886 0.0845216 -1.58161 1 0 1 1 0 0 +EDGE2 9217 9216 -1.0444 0.013236 0.00873868 1 0 1 1 0 0 +EDGE2 9218 9217 -0.968898 0.0727705 -0.0138051 1 0 1 1 0 0 +EDGE2 9219 9218 -0.988894 -0.0388215 -1.70234e-05 1 0 1 1 0 0 +EDGE2 9219 8180 1.02102 -0.0231625 -3.17038 1 0 1 1 0 0 +EDGE2 9220 8179 1.07054 0.079115 -3.15683 1 0 1 1 0 0 +EDGE2 9220 9219 -1.07321 -0.0140788 -0.0214856 1 0 1 1 0 0 +EDGE2 9220 8180 0.0808536 -0.0726619 -3.11468 1 0 1 1 0 0 +EDGE2 9220 8181 0.0114378 1.01901 1.57768 1 0 1 1 0 0 +EDGE2 9221 9220 -0.985244 0.00454203 -1.57274 1 0 1 1 0 0 +EDGE2 9221 8180 -0.985355 0.0489705 1.57553 1 0 1 1 0 0 +EDGE2 9221 8182 1.03591 0.0251554 0.0392931 1 0 1 1 0 0 +EDGE2 9221 8181 0.0759134 -0.00921517 -0.0186098 1 0 1 1 0 0 +EDGE2 9222 9221 -1.06641 -0.00801989 0.0239334 1 0 1 1 0 0 +EDGE2 9222 8182 -0.004966 0.0246527 0.0152731 1 0 1 1 0 0 +EDGE2 9222 8181 -1.01958 -0.00668339 0.0140227 1 0 1 1 0 0 +EDGE2 9222 8183 0.940879 -0.0140248 -0.00737372 1 0 1 1 0 0 +EDGE2 9223 9222 -1.01837 0.00281528 0.0298278 1 0 1 1 0 0 +EDGE2 9223 8182 -1.02408 -0.0674928 -0.00416862 1 0 1 1 0 0 +EDGE2 9223 8183 0.0143518 0.0786878 0.005577 1 0 1 1 0 0 +EDGE2 9223 8184 1.01081 -0.00191352 -0.0164578 1 0 1 1 0 0 +EDGE2 9224 9223 -0.91993 0.0458316 -0.017136 1 0 1 1 0 0 +EDGE2 9224 8183 -1.02906 -0.0630464 -0.00901181 1 0 1 1 0 0 +EDGE2 9224 8184 0.0155833 0.105447 -0.00982288 1 0 1 1 0 0 +EDGE2 9224 9205 1.05671 0.0538936 -3.13783 1 0 1 1 0 0 +EDGE2 9224 8185 0.954532 -0.0039349 0.022974 1 0 1 1 0 0 +EDGE2 9225 8184 -0.930601 -0.0374878 -0.0150891 1 0 1 1 0 0 +EDGE2 9225 9224 -1.01247 -0.0646376 0.0357442 1 0 1 1 0 0 +EDGE2 9225 9205 -0.0335541 0.0478513 -3.17151 1 0 1 1 0 0 +EDGE2 9225 8186 -0.0492306 1.12839 1.55888 1 0 1 1 0 0 +EDGE2 9225 9206 -0.00958803 0.989597 1.58784 1 0 1 1 0 0 +EDGE2 9225 8185 0.0392415 0.00369831 -0.0453889 1 0 1 1 0 0 +EDGE2 9225 9204 0.991513 0.0363273 -3.10961 1 0 1 1 0 0 +EDGE2 9226 9225 -1.00243 -0.0120104 1.57541 1 0 1 1 0 0 +EDGE2 9226 9205 -0.918635 0.0403202 -1.5702 1 0 1 1 0 0 +EDGE2 9226 8185 -1.04394 0.0122097 1.59304 1 0 1 1 0 0 +EDGE2 9227 9226 -1.05334 0.00248263 -0.00661228 1 0 1 1 0 0 +EDGE2 9228 9227 -0.995608 -0.0714066 -0.0140827 1 0 1 1 0 0 +EDGE2 9229 9090 1.09075 -0.0701545 -3.13791 1 0 1 1 0 0 +EDGE2 9229 9228 -0.903393 -0.0732148 0.0125541 1 0 1 1 0 0 +EDGE2 9230 9089 1.01041 -0.00073514 -3.13663 1 0 1 1 0 0 +EDGE2 9230 9229 -1.0084 0.0300643 -0.0169026 1 0 1 1 0 0 +EDGE2 9230 9091 -0.0206498 -0.971004 -1.5329 1 0 1 1 0 0 +EDGE2 9230 9090 0.019086 -0.0341532 -3.14259 1 0 1 1 0 0 +EDGE2 9231 9230 -1.06169 -0.0190139 -1.57521 1 0 1 1 0 0 +EDGE2 9231 9090 -0.992024 0.0137898 1.59856 1 0 1 1 0 0 +EDGE2 9232 9231 -0.963065 0.00611891 -0.0322057 1 0 1 1 0 0 +EDGE2 9233 9232 -0.929442 -0.0378418 0.0362021 1 0 1 1 0 0 +EDGE2 9234 9233 -1.00134 0.0347968 -0.00837599 1 0 1 1 0 0 +EDGE2 9234 9195 0.936539 0.0900551 -3.14584 1 0 1 1 0 0 +EDGE2 9234 9175 0.911034 0.036752 -3.17904 1 0 1 1 0 0 +EDGE2 9235 9176 -0.0124388 -0.982163 -1.59357 1 0 1 1 0 0 +EDGE2 9235 9234 -1.04236 -0.000339818 -0.0151531 1 0 1 1 0 0 +EDGE2 9235 9195 0.0251669 -0.00258008 -3.12074 1 0 1 1 0 0 +EDGE2 9235 9175 -0.0439856 0.0610111 -3.13134 1 0 1 1 0 0 +EDGE2 9235 9174 0.958389 -0.0252809 -3.14448 1 0 1 1 0 0 +EDGE2 9235 9194 1.06318 0.0564791 -3.12781 1 0 1 1 0 0 +EDGE2 9235 9196 0.00842468 1.03418 1.54826 1 0 1 1 0 0 +EDGE2 9236 9176 -0.076083 -0.079443 0.0131889 1 0 1 1 0 0 +EDGE2 9236 9177 1.02652 0.10412 0.00948909 1 0 1 1 0 0 +EDGE2 9236 9195 -1.02393 0.00984438 -1.57502 1 0 1 1 0 0 +EDGE2 9236 9235 -0.97064 0.0508304 1.5477 1 0 1 1 0 0 +EDGE2 9236 9175 -1.03384 0.0858923 -1.56296 1 0 1 1 0 0 +EDGE2 9237 9176 -1.00028 0.0365798 0.0209075 1 0 1 1 0 0 +EDGE2 9237 9178 0.965708 0.00995212 -0.000222411 1 0 1 1 0 0 +EDGE2 9237 9177 -0.0600261 -0.0256733 -0.0258355 1 0 1 1 0 0 +EDGE2 9237 9236 -0.934695 -0.0808881 -0.0162318 1 0 1 1 0 0 +EDGE2 9238 9179 0.947525 -0.00439504 -0.00284078 1 0 1 1 0 0 +EDGE2 9238 9237 -1.08927 0.0483081 -0.0041838 1 0 1 1 0 0 +EDGE2 9238 9178 -0.00971942 0.0294287 0.0145601 1 0 1 1 0 0 +EDGE2 9238 9177 -1.05753 -0.0730188 -0.00925716 1 0 1 1 0 0 +EDGE2 9239 9180 0.94056 0.0982284 0.00261044 1 0 1 1 0 0 +EDGE2 9239 9179 0.00938309 -0.0676233 0.0218642 1 0 1 1 0 0 +EDGE2 9239 9178 -0.927773 -0.00970303 0.00934699 1 0 1 1 0 0 +EDGE2 9239 9238 -0.998293 0.0688052 0.0180493 1 0 1 1 0 0 +EDGE2 9240 9180 0.0227679 0.126422 -0.0134393 1 0 1 1 0 0 +EDGE2 9240 9239 -0.937594 0.0402229 -0.0038192 1 0 1 1 0 0 +EDGE2 9240 9179 -0.993515 0.00164822 -0.0108418 1 0 1 1 0 0 +EDGE2 9240 9181 -0.0212254 0.940451 1.56614 1 0 1 1 0 0 +EDGE2 9241 9240 -0.94109 0.0289758 -1.53529 1 0 1 1 0 0 +EDGE2 9241 9180 -0.929238 0.0619324 -1.54061 1 0 1 1 0 0 +EDGE2 9241 9181 -0.0361691 -0.0138581 0.00949383 1 0 1 1 0 0 +EDGE2 9241 9182 0.993196 -0.0722535 0.0354008 1 0 1 1 0 0 +EDGE2 9242 9241 -0.979681 0.00274646 -0.00155823 1 0 1 1 0 0 +EDGE2 9242 9181 -1.04618 0.00630529 -0.0541779 1 0 1 1 0 0 +EDGE2 9242 9183 1.0452 0.0205965 0.00607147 1 0 1 1 0 0 +EDGE2 9242 9182 -0.0939907 0.0214495 -0.00615044 1 0 1 1 0 0 +EDGE2 9243 9242 -0.970814 0.0640003 -0.0169786 1 0 1 1 0 0 +EDGE2 9243 9184 1.04288 0.0594601 0.00807409 1 0 1 1 0 0 +EDGE2 9243 9183 -0.104466 0.0881494 -0.00478638 1 0 1 1 0 0 +EDGE2 9243 9182 -1.0521 0.00147588 0.0213792 1 0 1 1 0 0 +EDGE2 9244 9184 0.0373362 0.0212454 -0.0383588 1 0 1 1 0 0 +EDGE2 9244 9183 -1.05341 -0.0393779 0.00120432 1 0 1 1 0 0 +EDGE2 9244 9243 -1.02566 0.0947282 -0.00437883 1 0 1 1 0 0 +EDGE2 9244 9185 0.998588 -0.00941045 0.00861424 1 0 1 1 0 0 +EDGE2 9245 9184 -1.01585 0.00710029 0.00108316 1 0 1 1 0 0 +EDGE2 9245 9244 -0.977249 -0.00874943 -0.000862332 1 0 1 1 0 0 +EDGE2 9245 9185 -0.000112825 0.0544785 -0.00574895 1 0 1 1 0 0 +EDGE2 9245 9186 0.0132289 1.07124 1.5732 1 0 1 1 0 0 +EDGE2 9246 9185 -0.977326 -0.0685669 -1.56703 1 0 1 1 0 0 +EDGE2 9246 9245 -1.01204 0.0906741 -1.54969 1 0 1 1 0 0 +EDGE2 9246 9186 -0.00601147 0.0295693 -0.00686685 1 0 1 1 0 0 +EDGE2 9246 9187 1.0593 0.00600132 0.00912122 1 0 1 1 0 0 +EDGE2 9247 9246 -1.05873 -0.010594 -0.00554997 1 0 1 1 0 0 +EDGE2 9247 9186 -0.96231 0.0274284 -0.0185023 1 0 1 1 0 0 +EDGE2 9247 9187 -0.0324558 -0.00545599 -0.00832374 1 0 1 1 0 0 +EDGE2 9247 9188 1.04698 -0.0335259 -0.0404831 1 0 1 1 0 0 +EDGE2 9248 9247 -0.988488 0.0237595 -0.0060087 1 0 1 1 0 0 +EDGE2 9248 9187 -0.943848 -0.00262999 0.0230811 1 0 1 1 0 0 +EDGE2 9248 9189 1.08238 0.00607578 -0.0114527 1 0 1 1 0 0 +EDGE2 9248 9188 -0.0698259 0.0334592 -0.0170577 1 0 1 1 0 0 +EDGE2 9249 9189 0.00170368 0.032833 -0.000843221 1 0 1 1 0 0 +EDGE2 9249 9188 -1.00137 0.0300607 -0.0127104 1 0 1 1 0 0 +EDGE2 9249 9248 -1.02284 0.0361294 -0.0109423 1 0 1 1 0 0 +EDGE2 9249 9170 1.05135 0.0125794 -3.13596 1 0 1 1 0 0 +EDGE2 9249 9190 0.965414 0.0333097 0.0133761 1 0 1 1 0 0 +EDGE2 9250 9189 -0.922819 -0.0684286 -0.0188093 1 0 1 1 0 0 +EDGE2 9250 9249 -0.997438 0.0923893 -0.0113883 1 0 1 1 0 0 +EDGE2 9250 9170 -0.0677413 0.0511955 -3.17435 1 0 1 1 0 0 +EDGE2 9250 9171 0.0338325 1.02374 1.59664 1 0 1 1 0 0 +EDGE2 9250 9191 0.0302748 1.09121 1.59856 1 0 1 1 0 0 +EDGE2 9250 9190 0.0233319 0.0477173 0.0214378 1 0 1 1 0 0 +EDGE2 9250 9169 1.06402 -0.0207029 -3.13687 1 0 1 1 0 0 +EDGE2 9251 9192 0.987476 -0.0423435 -0.0259893 1 0 1 1 0 0 +EDGE2 9251 9172 0.961992 -0.000699546 0.0204405 1 0 1 1 0 0 +EDGE2 9251 9170 -1.07707 0.0542544 1.56101 1 0 1 1 0 0 +EDGE2 9251 9250 -1.07317 0.098863 -1.577 1 0 1 1 0 0 +EDGE2 9251 9171 0.06931 0.0712878 -0.038266 1 0 1 1 0 0 +EDGE2 9251 9191 -0.00598992 -0.00054653 0.0206707 1 0 1 1 0 0 +EDGE2 9251 9190 -1.1047 -0.0249025 -1.586 1 0 1 1 0 0 +EDGE2 9252 9251 -1.09786 -0.0504522 0.00477751 1 0 1 1 0 0 +EDGE2 9252 9173 0.974118 -0.0291529 -0.00265281 1 0 1 1 0 0 +EDGE2 9252 9193 0.982331 0.0654228 -0.0107417 1 0 1 1 0 0 +EDGE2 9252 9192 -0.0612058 0.128372 -0.0174215 1 0 1 1 0 0 +EDGE2 9252 9172 0.0183442 -0.0787177 0.00666963 1 0 1 1 0 0 +EDGE2 9252 9171 -1.05828 0.0477214 0.0105968 1 0 1 1 0 0 +EDGE2 9252 9191 -1.0113 0.0258619 0.0141375 1 0 1 1 0 0 +EDGE2 9253 9173 -0.132364 0.0253882 0.00932701 1 0 1 1 0 0 +EDGE2 9253 9174 1.04379 0.0492932 0.00332534 1 0 1 1 0 0 +EDGE2 9253 9194 1.04808 0.0535347 0.00875638 1 0 1 1 0 0 +EDGE2 9253 9193 0.108912 0.0483458 0.0233756 1 0 1 1 0 0 +EDGE2 9253 9192 -1.00448 -0.0688416 -0.029079 1 0 1 1 0 0 +EDGE2 9253 9252 -1.0225 0.0395717 0.0139781 1 0 1 1 0 0 +EDGE2 9253 9172 -0.994153 0.0513203 -0.0127796 1 0 1 1 0 0 +EDGE2 9254 9173 -0.946021 0.0444302 -0.0154569 1 0 1 1 0 0 +EDGE2 9254 9195 0.956356 0.00673755 -0.0212104 1 0 1 1 0 0 +EDGE2 9254 9235 1.06074 -0.0753917 -3.11527 1 0 1 1 0 0 +EDGE2 9254 9175 1.01902 0.0195034 -0.00367196 1 0 1 1 0 0 +EDGE2 9254 9253 -0.952518 -0.00892749 0.000231958 1 0 1 1 0 0 +EDGE2 9254 9174 0.0350361 0.0440835 -0.0109646 1 0 1 1 0 0 +EDGE2 9254 9194 -0.0107883 -0.0646211 0.0113692 1 0 1 1 0 0 +EDGE2 9254 9193 -0.99626 -0.0479706 0.0324295 1 0 1 1 0 0 +EDGE2 9255 9176 0.00283499 1.06219 1.53905 1 0 1 1 0 0 +EDGE2 9255 9236 0.00381686 1.05988 1.56165 1 0 1 1 0 0 +EDGE2 9255 9234 0.900945 0.0982834 -3.11704 1 0 1 1 0 0 +EDGE2 9255 9254 -0.957504 -0.0600158 -0.0163025 1 0 1 1 0 0 +EDGE2 9255 9195 -0.0562708 -0.0495905 0.00726073 1 0 1 1 0 0 +EDGE2 9255 9235 0.0247323 0.00651823 -3.14079 1 0 1 1 0 0 +EDGE2 9255 9175 -0.0318395 -0.0681205 -0.0145156 1 0 1 1 0 0 +EDGE2 9255 9174 -0.962676 -0.0748282 -0.0142043 1 0 1 1 0 0 +EDGE2 9255 9194 -0.963916 0.0283269 -0.00144642 1 0 1 1 0 0 +EDGE2 9255 9196 0.0300155 -1.01512 -1.55144 1 0 1 1 0 0 +EDGE2 9256 9176 -0.0462079 -0.0914925 -0.00984826 1 0 1 1 0 0 +EDGE2 9256 9237 0.904011 0.0156052 -0.000660672 1 0 1 1 0 0 +EDGE2 9256 9177 1.0669 -0.0564228 -0.013808 1 0 1 1 0 0 +EDGE2 9256 9236 -0.0344276 -0.00831733 -0.00397474 1 0 1 1 0 0 +EDGE2 9256 9195 -0.961766 -0.041024 -1.58801 1 0 1 1 0 0 +EDGE2 9256 9235 -0.937968 0.0219655 1.60953 1 0 1 1 0 0 +EDGE2 9256 9255 -0.946088 0.0299474 -1.54147 1 0 1 1 0 0 +EDGE2 9256 9175 -0.949228 -0.0162068 -1.54708 1 0 1 1 0 0 +EDGE2 9257 9176 -0.987477 0.00165318 -0.00852898 1 0 1 1 0 0 +EDGE2 9257 9237 -0.0133781 0.0345184 0.0660654 1 0 1 1 0 0 +EDGE2 9257 9178 0.923221 0.00321484 0.0159068 1 0 1 1 0 0 +EDGE2 9257 9238 1.12484 0.0836319 0.0131538 1 0 1 1 0 0 +EDGE2 9257 9177 -0.0027183 0.0358788 -0.0225805 1 0 1 1 0 0 +EDGE2 9257 9236 -1.03668 -0.0132282 0.0271181 1 0 1 1 0 0 +EDGE2 9257 9256 -0.962244 -0.111446 0.010544 1 0 1 1 0 0 +EDGE2 9258 9239 1.03143 -0.127065 -0.000300334 1 0 1 1 0 0 +EDGE2 9258 9179 0.974523 0.0868628 -0.0228585 1 0 1 1 0 0 +EDGE2 9258 9237 -0.995955 -0.0244926 0.000254257 1 0 1 1 0 0 +EDGE2 9258 9178 -0.0188211 0.0436798 -0.00342311 1 0 1 1 0 0 +EDGE2 9258 9238 0.0432934 0.0655561 -0.0188172 1 0 1 1 0 0 +EDGE2 9258 9257 -0.940028 0.0770542 0.00914973 1 0 1 1 0 0 +EDGE2 9258 9177 -0.979758 -0.0467187 0.0114073 1 0 1 1 0 0 +EDGE2 9259 9240 0.972469 -0.0435541 -0.0118893 1 0 1 1 0 0 +EDGE2 9259 9180 0.956535 0.0705048 0.04909 1 0 1 1 0 0 +EDGE2 9259 9239 -8.93842e-06 -0.00719074 -0.0135669 1 0 1 1 0 0 +EDGE2 9259 9179 -0.0300322 -0.0718784 0.0198407 1 0 1 1 0 0 +EDGE2 9259 9178 -0.978322 0.0167071 -0.0222488 1 0 1 1 0 0 +EDGE2 9259 9238 -1.03832 0.0755684 0.0139739 1 0 1 1 0 0 +EDGE2 9259 9258 -0.95132 -0.0701328 -0.00813176 1 0 1 1 0 0 +EDGE2 9260 9240 -0.0295763 -0.0986912 0.00159846 1 0 1 1 0 0 +EDGE2 9260 9180 -0.039376 0.0367296 0.00448707 1 0 1 1 0 0 +EDGE2 9260 9239 -1.03327 -0.0726485 0.0158827 1 0 1 1 0 0 +EDGE2 9260 9259 -0.982696 0.000471968 0.0128542 1 0 1 1 0 0 +EDGE2 9260 9179 -0.970317 0.0264861 0.0335562 1 0 1 1 0 0 +EDGE2 9260 9241 0.0495787 0.960311 1.56952 1 0 1 1 0 0 +EDGE2 9260 9181 -0.0354639 0.95532 1.55804 1 0 1 1 0 0 +EDGE2 9261 9240 -1.02843 0.112989 1.57952 1 0 1 1 0 0 +EDGE2 9261 9260 -1.05283 0.0761046 1.586 1 0 1 1 0 0 +EDGE2 9261 9180 -1.02878 0.0437818 1.5929 1 0 1 1 0 0 +EDGE2 9262 9261 -1.03488 -0.111145 -0.0211461 1 0 1 1 0 0 +EDGE2 9263 9262 -1.08344 -0.0458245 -0.0189257 1 0 1 1 0 0 +EDGE2 9264 9263 -1.02553 0.0526769 0.0132543 1 0 1 1 0 0 +EDGE2 9264 9085 1.05793 -0.0257185 -3.1559 1 0 1 1 0 0 +EDGE2 9264 9105 1.0051 -0.0177257 -3.1243 1 0 1 1 0 0 +EDGE2 9265 9264 -1.08392 -0.0125489 -0.0106576 1 0 1 1 0 0 +EDGE2 9265 9106 -0.0105591 1.00022 1.60698 1 0 1 1 0 0 +EDGE2 9265 9085 -0.0117362 0.0434292 -3.14788 1 0 1 1 0 0 +EDGE2 9265 9084 0.969066 -0.0294415 -3.12965 1 0 1 1 0 0 +EDGE2 9265 9104 1.02143 -0.058833 -3.1139 1 0 1 1 0 0 +EDGE2 9265 9105 -0.0447943 -0.0425885 -3.17962 1 0 1 1 0 0 +EDGE2 9265 9086 0.0634023 -1.0249 -1.59171 1 0 1 1 0 0 +EDGE2 9266 9265 -0.975435 -0.00348544 1.57624 1 0 1 1 0 0 +EDGE2 9266 9085 -0.96094 -0.0316686 -1.57342 1 0 1 1 0 0 +EDGE2 9266 9105 -1.07339 -0.00963056 -1.54323 1 0 1 1 0 0 +EDGE2 9266 9086 0.0588632 0.00973327 -0.00405142 1 0 1 1 0 0 +EDGE2 9266 9087 0.983636 -0.013099 0.0250045 1 0 1 1 0 0 +EDGE2 9267 9266 -0.965826 -0.028821 0.0110619 1 0 1 1 0 0 +EDGE2 9267 9088 1.04888 0.0429993 -0.0239281 1 0 1 1 0 0 +EDGE2 9267 9086 -0.996389 0.0502632 -0.0118182 1 0 1 1 0 0 +EDGE2 9267 9087 0.0608801 -0.0768626 0.0187609 1 0 1 1 0 0 +EDGE2 9268 9089 1.05229 0.0965132 0.000794615 1 0 1 1 0 0 +EDGE2 9268 9088 0.0204295 -0.0304012 0.0247696 1 0 1 1 0 0 +EDGE2 9268 9267 -1.02998 0.059435 -0.0113743 1 0 1 1 0 0 +EDGE2 9268 9087 -1.13539 0.0169549 -0.0208371 1 0 1 1 0 0 +EDGE2 9269 9089 0.0296562 0.0163606 0.026509 1 0 1 1 0 0 +EDGE2 9269 9088 -1.02259 0.0535666 0.0167125 1 0 1 1 0 0 +EDGE2 9269 9268 -0.985682 0.0372234 0.00245287 1 0 1 1 0 0 +EDGE2 9269 9230 0.951678 -0.0148464 -3.13467 1 0 1 1 0 0 +EDGE2 9269 9090 0.965824 0.0469896 0.0212748 1 0 1 1 0 0 +EDGE2 9270 9089 -1.05597 -0.00518819 0.00585297 1 0 1 1 0 0 +EDGE2 9270 9269 -0.980012 0.101431 -0.00730708 1 0 1 1 0 0 +EDGE2 9270 9229 1.10645 -0.0559766 -3.17026 1 0 1 1 0 0 +EDGE2 9270 9091 0.0306704 1.0228 1.57511 1 0 1 1 0 0 +EDGE2 9270 9230 0.0327416 -0.0211398 -3.11567 1 0 1 1 0 0 +EDGE2 9270 9090 -0.0596458 0.0206281 -0.0216479 1 0 1 1 0 0 +EDGE2 9270 9231 0.0287711 -0.975289 -1.57016 1 0 1 1 0 0 +EDGE2 9271 9092 0.998734 -0.041747 0.0116995 1 0 1 1 0 0 +EDGE2 9271 9091 -0.000344109 -0.0588355 -0.0104211 1 0 1 1 0 0 +EDGE2 9271 9230 -0.998328 -0.00664666 1.55674 1 0 1 1 0 0 +EDGE2 9271 9270 -1.05981 0.0456879 -1.5609 1 0 1 1 0 0 +EDGE2 9271 9090 -0.903887 0.0193921 -1.6042 1 0 1 1 0 0 +EDGE2 9272 9093 1.04845 -0.00512632 0.000522261 1 0 1 1 0 0 +EDGE2 9272 9092 0.0187984 0.00121356 0.00569605 1 0 1 1 0 0 +EDGE2 9272 9271 -0.994165 -0.11232 -0.00511631 1 0 1 1 0 0 +EDGE2 9272 9091 -0.988954 -0.0391424 -0.000559028 1 0 1 1 0 0 +EDGE2 9273 9094 1.09808 -0.113568 -0.0214503 1 0 1 1 0 0 +EDGE2 9273 9093 0.0609922 0.00437089 -0.0171467 1 0 1 1 0 0 +EDGE2 9273 9092 -0.972999 0.0353027 0.014713 1 0 1 1 0 0 +EDGE2 9273 9272 -1.03295 -0.0087833 0.00127016 1 0 1 1 0 0 +EDGE2 9274 9075 1.02254 0.0959409 -3.10652 1 0 1 1 0 0 +EDGE2 9274 9095 0.982899 -0.0369115 0.00991814 1 0 1 1 0 0 +EDGE2 9274 9094 0.0551965 -0.0249977 0.00749778 1 0 1 1 0 0 +EDGE2 9274 9093 -1.00207 -0.177428 0.00464378 1 0 1 1 0 0 +EDGE2 9274 9273 -1.0681 -0.0458947 -0.0149584 1 0 1 1 0 0 +EDGE2 9274 8175 1.04695 -0.0502821 -3.14231 1 0 1 1 0 0 +EDGE2 9275 9096 -0.0935954 0.984129 1.59287 1 0 1 1 0 0 +EDGE2 9275 9076 0.052391 1.05829 1.51984 1 0 1 1 0 0 +EDGE2 9275 9074 0.95882 -0.000590894 -3.11948 1 0 1 1 0 0 +EDGE2 9275 9075 0.00624239 0.00418506 -3.11421 1 0 1 1 0 0 +EDGE2 9275 9095 -0.0444405 -0.03347 -0.0260905 1 0 1 1 0 0 +EDGE2 9275 9274 -1.04642 0.0848915 -0.0141501 1 0 1 1 0 0 +EDGE2 9275 9094 -0.990471 0.0130147 -0.0251082 1 0 1 1 0 0 +EDGE2 9275 8175 -0.137095 0.00402007 -3.12161 1 0 1 1 0 0 +EDGE2 9275 8174 1.06256 0.0188443 -3.13378 1 0 1 1 0 0 +EDGE2 9275 8176 0.0254843 -1.00644 -1.56064 1 0 1 1 0 0 +EDGE2 9276 9077 0.959602 0.0312391 -0.0026743 1 0 1 1 0 0 +EDGE2 9276 9097 1.00343 -0.0310483 0.0074828 1 0 1 1 0 0 +EDGE2 9276 9096 -0.0768961 -0.0310621 0.00858654 1 0 1 1 0 0 +EDGE2 9276 9076 0.0072727 -0.019211 -0.0122794 1 0 1 1 0 0 +EDGE2 9276 9075 -0.966695 0.0232082 1.56344 1 0 1 1 0 0 +EDGE2 9276 9275 -0.980634 -0.137607 -1.56683 1 0 1 1 0 0 +EDGE2 9276 9095 -1.05086 -0.0778387 -1.60156 1 0 1 1 0 0 +EDGE2 9276 8175 -1.08081 0.0851293 1.54913 1 0 1 1 0 0 +EDGE2 9277 9098 0.988712 -0.00281838 -0.0530206 1 0 1 1 0 0 +EDGE2 9277 9078 1.04798 0.065949 0.0182783 1 0 1 1 0 0 +EDGE2 9277 9077 0.0493384 0.0596114 0.00466498 1 0 1 1 0 0 +EDGE2 9277 9097 0.0547025 -0.0265917 -0.00982417 1 0 1 1 0 0 +EDGE2 9277 9096 -1.01167 0.0312685 0.00810946 1 0 1 1 0 0 +EDGE2 9277 9276 -0.976875 -0.0710178 0.0232794 1 0 1 1 0 0 +EDGE2 9277 9076 -0.973601 -0.00954474 -0.0335627 1 0 1 1 0 0 +EDGE2 9278 9099 0.981527 -0.0289061 0.0147129 1 0 1 1 0 0 +EDGE2 9278 9079 0.995382 0.00394156 0.0186272 1 0 1 1 0 0 +EDGE2 9278 9098 0.0260544 -0.0468121 -0.0306724 1 0 1 1 0 0 +EDGE2 9278 9078 0.0328969 -0.0028369 -0.0122366 1 0 1 1 0 0 +EDGE2 9278 9077 -1.05642 0.0300991 0.025076 1 0 1 1 0 0 +EDGE2 9278 9097 -0.997354 -0.000137578 0.0265195 1 0 1 1 0 0 +EDGE2 9278 9277 -1.03541 -0.0227802 0.0239695 1 0 1 1 0 0 +EDGE2 9279 8120 0.991433 -0.0241861 -3.13663 1 0 1 1 0 0 +EDGE2 9279 9080 1.01891 0.0204442 0.0119564 1 0 1 1 0 0 +EDGE2 9279 9100 0.941009 -0.0115109 0.000355677 1 0 1 1 0 0 +EDGE2 9279 9099 0.0419134 0.00427287 -0.00685972 1 0 1 1 0 0 +EDGE2 9279 9079 0.0218493 0.0173797 -0.0115432 1 0 1 1 0 0 +EDGE2 9279 9098 -0.994176 0.0258135 -0.000473887 1 0 1 1 0 0 +EDGE2 9279 9278 -0.983715 -0.0703889 0.0105754 1 0 1 1 0 0 +EDGE2 9279 9078 -1.00576 -0.134893 0.0269782 1 0 1 1 0 0 +EDGE2 9280 8120 0.000101491 0.0388482 -3.13322 1 0 1 1 0 0 +EDGE2 9280 8119 1.08835 0.00407606 -3.15395 1 0 1 1 0 0 +EDGE2 9280 9081 -0.0137219 1.06314 1.56864 1 0 1 1 0 0 +EDGE2 9280 9101 0.0705971 0.910954 1.58088 1 0 1 1 0 0 +EDGE2 9280 9080 -0.0905979 -0.0115431 0.0179525 1 0 1 1 0 0 +EDGE2 9280 9100 0.0403383 0.0596712 0.0217563 1 0 1 1 0 0 +EDGE2 9280 8121 -0.0398103 -0.972941 -1.57803 1 0 1 1 0 0 +EDGE2 9280 9099 -0.982252 0.0617628 0.0253683 1 0 1 1 0 0 +EDGE2 9280 9279 -1.04168 0.00048471 -0.0189764 1 0 1 1 0 0 +EDGE2 9280 9079 -1.14543 -0.0709912 0.0124436 1 0 1 1 0 0 +EDGE2 9281 8120 -1.02255 0.036439 1.58142 1 0 1 1 0 0 +EDGE2 9281 9280 -1.00354 -0.00104413 -1.60353 1 0 1 1 0 0 +EDGE2 9281 9081 -0.00358826 -0.0494032 -0.0300777 1 0 1 1 0 0 +EDGE2 9281 9101 -0.0430504 -0.0659234 -0.0132576 1 0 1 1 0 0 +EDGE2 9281 9080 -1.07876 0.070777 -1.61128 1 0 1 1 0 0 +EDGE2 9281 9100 -0.969933 -0.0582998 -1.52981 1 0 1 1 0 0 +EDGE2 9281 9082 0.951597 0.121888 0.0241914 1 0 1 1 0 0 +EDGE2 9281 9102 0.877094 0.00723556 -0.0539399 1 0 1 1 0 0 +EDGE2 9282 9081 -0.949077 0.0544893 0.0172563 1 0 1 1 0 0 +EDGE2 9282 9101 -0.985276 -0.0101145 0.0228129 1 0 1 1 0 0 +EDGE2 9282 9281 -0.996678 -0.00196301 -0.00245508 1 0 1 1 0 0 +EDGE2 9282 9082 -0.0244819 -0.00477083 0.0120574 1 0 1 1 0 0 +EDGE2 9282 9102 0.0149625 -0.0357326 0.029514 1 0 1 1 0 0 +EDGE2 9282 9103 1.00432 -0.0145825 0.00174164 1 0 1 1 0 0 +EDGE2 9282 9083 1.01282 -0.0350532 0.00654626 1 0 1 1 0 0 +EDGE2 9283 9082 -0.999674 -0.00340949 0.0100965 1 0 1 1 0 0 +EDGE2 9283 9102 -1.01425 -0.0909657 -0.000666887 1 0 1 1 0 0 +EDGE2 9283 9282 -0.947639 0.0361908 0.033525 1 0 1 1 0 0 +EDGE2 9283 9103 0.0366753 0.0680543 -0.00256356 1 0 1 1 0 0 +EDGE2 9283 9083 0.0577951 0.0246007 -0.00773725 1 0 1 1 0 0 +EDGE2 9283 9084 0.948252 -0.0818193 -0.0107818 1 0 1 1 0 0 +EDGE2 9283 9104 1.05431 -0.00648197 0.0103701 1 0 1 1 0 0 +EDGE2 9284 9103 -0.892945 0.00154561 -0.018011 1 0 1 1 0 0 +EDGE2 9284 9283 -0.96759 0.130138 -0.0103241 1 0 1 1 0 0 +EDGE2 9284 9083 -0.944825 0.0108484 -0.004126 1 0 1 1 0 0 +EDGE2 9284 9265 0.981944 0.110903 -3.11695 1 0 1 1 0 0 +EDGE2 9284 9085 1.04097 -0.0105356 -0.0144653 1 0 1 1 0 0 +EDGE2 9284 9084 -0.0189715 0.0706303 0.0162199 1 0 1 1 0 0 +EDGE2 9284 9104 0.0214582 0.00403895 -0.0143626 1 0 1 1 0 0 +EDGE2 9284 9105 0.967801 0.00241502 -0.0175829 1 0 1 1 0 0 +EDGE2 9285 9264 0.878253 -0.00171613 -3.12461 1 0 1 1 0 0 +EDGE2 9285 9265 0.0597267 -0.0130243 -3.16229 1 0 1 1 0 0 +EDGE2 9285 9106 -0.00924664 -1.10966 -1.58172 1 0 1 1 0 0 +EDGE2 9285 9085 -0.024545 -0.0182676 -0.0225656 1 0 1 1 0 0 +EDGE2 9285 9084 -0.927692 0.0121673 -0.0224133 1 0 1 1 0 0 +EDGE2 9285 9284 -0.924118 -0.0648357 -0.0141255 1 0 1 1 0 0 +EDGE2 9285 9104 -1.02807 0.0115169 0.00881226 1 0 1 1 0 0 +EDGE2 9285 9105 0.00222622 0.0375268 0.016954 1 0 1 1 0 0 +EDGE2 9285 9266 0.0326589 1.01816 1.5733 1 0 1 1 0 0 +EDGE2 9285 9086 -0.0714568 1.01305 1.55769 1 0 1 1 0 0 +EDGE2 9286 9265 -1.04607 -0.0215706 1.55201 1 0 1 1 0 0 +EDGE2 9286 9085 -0.930947 0.0403845 -1.58635 1 0 1 1 0 0 +EDGE2 9286 9285 -1.02848 -0.046648 -1.53063 1 0 1 1 0 0 +EDGE2 9286 9105 -1.04605 0.0176041 -1.55605 1 0 1 1 0 0 +EDGE2 9286 9266 0.00119059 -0.0210978 -0.00591994 1 0 1 1 0 0 +EDGE2 9286 9267 1.05887 0.0144007 0.0123986 1 0 1 1 0 0 +EDGE2 9286 9086 0.0118444 0.0190459 -0.00994428 1 0 1 1 0 0 +EDGE2 9286 9087 0.996722 0.0150108 0.0429339 1 0 1 1 0 0 +EDGE2 9287 9266 -1.01342 0.0312974 -0.00813341 1 0 1 1 0 0 +EDGE2 9287 9088 0.954667 0.0401155 -0.0163042 1 0 1 1 0 0 +EDGE2 9287 9267 -0.0192169 -0.0366285 0.00325377 1 0 1 1 0 0 +EDGE2 9287 9086 -1.02545 -0.0333685 0.0175858 1 0 1 1 0 0 +EDGE2 9287 9286 -1.00615 -0.048059 0.00853494 1 0 1 1 0 0 +EDGE2 9287 9268 1.04057 -0.0349404 -0.0247878 1 0 1 1 0 0 +EDGE2 9287 9087 0.0404285 0.0473491 -0.0247928 1 0 1 1 0 0 +EDGE2 9288 9089 1.00451 -0.0312832 0.0198429 1 0 1 1 0 0 +EDGE2 9288 9088 -0.0454329 0.0257557 -0.0116411 1 0 1 1 0 0 +EDGE2 9288 9287 -0.985522 0.00240975 -0.0128389 1 0 1 1 0 0 +EDGE2 9288 9267 -0.999439 -0.00390754 -0.0355981 1 0 1 1 0 0 +EDGE2 9288 9268 0.0723439 -0.0572819 -0.0228259 1 0 1 1 0 0 +EDGE2 9288 9087 -1.1564 -0.0296523 -0.00450411 1 0 1 1 0 0 +EDGE2 9288 9269 1.02348 -0.0478442 0.005682 1 0 1 1 0 0 +EDGE2 9289 9089 0.0222692 0.00374675 0.0283778 1 0 1 1 0 0 +EDGE2 9289 9088 -1.06157 -0.02366 0.0216175 1 0 1 1 0 0 +EDGE2 9289 9268 -1.05075 0.0220812 0.0343165 1 0 1 1 0 0 +EDGE2 9289 9288 -1.00345 -0.0523675 -0.0171696 1 0 1 1 0 0 +EDGE2 9289 9269 -0.057662 0.0463326 -0.0134142 1 0 1 1 0 0 +EDGE2 9289 9230 1.03144 0.0211664 -3.18592 1 0 1 1 0 0 +EDGE2 9289 9270 1.07082 0.0359175 -0.0491258 1 0 1 1 0 0 +EDGE2 9289 9090 1.03485 0.0388926 0.020552 1 0 1 1 0 0 +EDGE2 9290 9089 -0.993943 -0.0990309 -0.00801612 1 0 1 1 0 0 +EDGE2 9290 9289 -1.00801 -0.0782773 -0.00890539 1 0 1 1 0 0 +EDGE2 9290 9269 -1.01739 -0.0420881 -0.00465253 1 0 1 1 0 0 +EDGE2 9290 9229 1.03832 -0.00302028 -3.14376 1 0 1 1 0 0 +EDGE2 9290 9271 -0.0254143 0.986594 1.57382 1 0 1 1 0 0 +EDGE2 9290 9091 0.0380129 0.973012 1.59284 1 0 1 1 0 0 +EDGE2 9290 9230 -0.00217335 -0.0169709 -3.11473 1 0 1 1 0 0 +EDGE2 9290 9270 -0.0207958 -0.0171487 -0.0112977 1 0 1 1 0 0 +EDGE2 9290 9090 0.0345008 0.029807 0.00771576 1 0 1 1 0 0 +EDGE2 9290 9231 0.0380382 -1.02844 -1.58154 1 0 1 1 0 0 +EDGE2 9291 9092 0.997172 -0.0115002 0.00218416 1 0 1 1 0 0 +EDGE2 9291 9272 0.944662 -0.0398358 0.0496915 1 0 1 1 0 0 +EDGE2 9291 9271 0.00272571 0.0647876 -0.00977781 1 0 1 1 0 0 +EDGE2 9291 9091 0.0153537 0.0249811 0.0148646 1 0 1 1 0 0 +EDGE2 9291 9230 -0.957177 0.00178514 1.57759 1 0 1 1 0 0 +EDGE2 9291 9270 -1.03193 -0.0404117 -1.58806 1 0 1 1 0 0 +EDGE2 9291 9290 -1.0739 -0.0294902 -1.54148 1 0 1 1 0 0 +EDGE2 9291 9090 -1.03241 -0.0443639 -1.56537 1 0 1 1 0 0 +EDGE2 9292 9093 0.9969 0.000911131 0.0641941 1 0 1 1 0 0 +EDGE2 9292 9273 1.035 -0.0366049 -0.010478 1 0 1 1 0 0 +EDGE2 9292 9092 0.0272353 -0.00813005 0.00951498 1 0 1 1 0 0 +EDGE2 9292 9272 -0.0137801 -0.078866 0.00812683 1 0 1 1 0 0 +EDGE2 9292 9271 -1.03908 -0.0131054 -0.00910627 1 0 1 1 0 0 +EDGE2 9292 9291 -1.02218 -0.00749232 -0.021098 1 0 1 1 0 0 +EDGE2 9292 9091 -1.00271 0.00372996 -0.0106609 1 0 1 1 0 0 +EDGE2 9293 9274 0.933426 -0.0670777 0.0132499 1 0 1 1 0 0 +EDGE2 9293 9094 0.909877 0.0733554 -0.0185783 1 0 1 1 0 0 +EDGE2 9293 9292 -0.984268 0.0216692 0.0153513 1 0 1 1 0 0 +EDGE2 9293 9093 1.88528e-05 0.0431808 0.0254652 1 0 1 1 0 0 +EDGE2 9293 9273 -0.0248056 -0.0983466 -0.007038 1 0 1 1 0 0 +EDGE2 9293 9092 -1.01561 0.0613755 -0.00372953 1 0 1 1 0 0 +EDGE2 9293 9272 -1.02272 0.0244398 -0.00183264 1 0 1 1 0 0 +EDGE2 9294 9075 0.991037 0.0086475 -3.18402 1 0 1 1 0 0 +EDGE2 9294 9275 1.01444 -0.0392566 -0.0412843 1 0 1 1 0 0 +EDGE2 9294 9095 0.950041 0.0139465 -0.00650968 1 0 1 1 0 0 +EDGE2 9294 9274 0.0134643 0.00677405 0.035643 1 0 1 1 0 0 +EDGE2 9294 9094 0.047554 0.0138146 0.0100288 1 0 1 1 0 0 +EDGE2 9294 9093 -0.933966 -0.0748856 -0.0111456 1 0 1 1 0 0 +EDGE2 9294 9273 -0.970911 0.0334358 -0.0154529 1 0 1 1 0 0 +EDGE2 9294 9293 -1.07382 -0.0142689 -0.0241772 1 0 1 1 0 0 +EDGE2 9294 8175 1.063 0.0327736 -3.1667 1 0 1 1 0 0 +EDGE2 9295 9096 0.0654913 0.996962 1.57147 1 0 1 1 0 0 +EDGE2 9295 9276 -0.0397739 1.05389 1.5711 1 0 1 1 0 0 +EDGE2 9295 9076 -0.0318872 1.06637 1.53383 1 0 1 1 0 0 +EDGE2 9295 9074 1.05723 0.0457522 -3.13824 1 0 1 1 0 0 +EDGE2 9295 9075 -0.00462925 0.024866 -3.1554 1 0 1 1 0 0 +EDGE2 9295 9275 -0.0210136 -0.0232569 0.00269298 1 0 1 1 0 0 +EDGE2 9295 9095 -0.0359253 -0.00603653 -0.0125767 1 0 1 1 0 0 +EDGE2 9295 9274 -0.987116 0.00843123 0.0120583 1 0 1 1 0 0 +EDGE2 9295 9294 -0.944266 0.00592502 0.0248446 1 0 1 1 0 0 +EDGE2 9295 9094 -0.930989 -0.0643508 -0.00615184 1 0 1 1 0 0 +EDGE2 9295 8175 -0.0461106 -0.0119891 -3.13631 1 0 1 1 0 0 +EDGE2 9295 8174 1.00241 0.00809454 -3.14965 1 0 1 1 0 0 +EDGE2 9295 8176 -0.037482 -0.948886 -1.58109 1 0 1 1 0 0 +EDGE2 9296 9077 0.973656 -0.00719163 -0.000647735 1 0 1 1 0 0 +EDGE2 9296 9097 0.984363 -0.130978 -0.0225742 1 0 1 1 0 0 +EDGE2 9296 9277 1.10692 -0.0323538 -0.000928592 1 0 1 1 0 0 +EDGE2 9296 9096 -0.000601505 0.00360028 -0.00195167 1 0 1 1 0 0 +EDGE2 9296 9276 -0.0235629 -0.0340563 -0.00517183 1 0 1 1 0 0 +EDGE2 9296 9076 -0.0264992 -0.0410386 0.028722 1 0 1 1 0 0 +EDGE2 9296 9075 -1.04399 -0.0283362 1.54616 1 0 1 1 0 0 +EDGE2 9296 9275 -0.971848 0.0445742 -1.56079 1 0 1 1 0 0 +EDGE2 9296 9295 -1.03544 0.0894067 -1.53033 1 0 1 1 0 0 +EDGE2 9296 9095 -0.969465 0.0378608 -1.55015 1 0 1 1 0 0 +EDGE2 9296 8175 -0.96363 0.0171861 1.5573 1 0 1 1 0 0 +EDGE2 9297 9098 1.02178 -0.00109785 -0.00330869 1 0 1 1 0 0 +EDGE2 9297 9278 0.934204 0.0367908 -0.0184625 1 0 1 1 0 0 +EDGE2 9297 9078 0.938079 0.0054948 -0.0147203 1 0 1 1 0 0 +EDGE2 9297 9296 -1.02653 0.0628217 0.00998454 1 0 1 1 0 0 +EDGE2 9297 9077 0.0239226 0.0126145 -0.00274918 1 0 1 1 0 0 +EDGE2 9297 9097 -0.0363642 -0.00371844 -0.00658055 1 0 1 1 0 0 +EDGE2 9297 9277 -0.0355267 -0.0262823 0.035415 1 0 1 1 0 0 +EDGE2 9297 9096 -0.99928 0.0970786 -0.00499913 1 0 1 1 0 0 +EDGE2 9297 9276 -1.03179 -0.107885 -0.0186704 1 0 1 1 0 0 +EDGE2 9297 9076 -0.983309 0.00455938 0.023656 1 0 1 1 0 0 +EDGE2 9298 9099 1.05413 0.082521 0.0195546 1 0 1 1 0 0 +EDGE2 9298 9279 1.02522 -0.00357544 -0.0127414 1 0 1 1 0 0 +EDGE2 9298 9079 1.00776 -0.0892201 -0.0346105 1 0 1 1 0 0 +EDGE2 9298 9098 -0.0743139 0.0318623 -0.0151277 1 0 1 1 0 0 +EDGE2 9298 9278 0.0109291 -0.0189514 -0.00230375 1 0 1 1 0 0 +EDGE2 9298 9078 0.0385702 -0.102629 -0.0022699 1 0 1 1 0 0 +EDGE2 9298 9297 -0.956959 -0.0182371 0.00526142 1 0 1 1 0 0 +EDGE2 9298 9077 -0.9573 0.0118557 0.00914248 1 0 1 1 0 0 +EDGE2 9298 9097 -0.98587 -0.0134128 -0.016318 1 0 1 1 0 0 +EDGE2 9298 9277 -1.00924 -0.0621166 -0.00982693 1 0 1 1 0 0 +EDGE2 9299 8120 1.00505 0.0215485 -3.14419 1 0 1 1 0 0 +EDGE2 9299 9280 0.989078 -0.039293 -0.0205354 1 0 1 1 0 0 +EDGE2 9299 9080 0.930354 0.0201431 0.0179095 1 0 1 1 0 0 +EDGE2 9299 9100 0.938682 0.029574 -0.0111088 1 0 1 1 0 0 +EDGE2 9299 9099 -0.0373618 -0.0452644 0.0117052 1 0 1 1 0 0 +EDGE2 9299 9279 0.0241545 0.112787 0.0160065 1 0 1 1 0 0 +EDGE2 9299 9079 0.0847415 -0.0153249 -0.0134302 1 0 1 1 0 0 +EDGE2 9299 9098 -0.979542 -0.0350271 -0.0164032 1 0 1 1 0 0 +EDGE2 9299 9278 -0.982946 0.0270832 0.0269027 1 0 1 1 0 0 +EDGE2 9299 9298 -1.08894 -0.0326149 -0.0148096 1 0 1 1 0 0 +EDGE2 9299 9078 -0.954829 0.0367713 -0.0144132 1 0 1 1 0 0 +EDGE2 9300 8120 0.00886 0.0557447 -3.14038 1 0 1 1 0 0 +EDGE2 9300 9280 0.0654098 -0.00355688 0.0138234 1 0 1 1 0 0 +EDGE2 9300 8119 1.01083 -0.0425863 -3.13666 1 0 1 1 0 0 +EDGE2 9300 9081 -0.0382502 1.01011 1.54718 1 0 1 1 0 0 +EDGE2 9300 9101 0.0220496 0.982817 1.54896 1 0 1 1 0 0 +EDGE2 9300 9281 -0.0454438 1.00025 1.58063 1 0 1 1 0 0 +EDGE2 9300 9080 -0.113352 -0.0130353 -0.00815111 1 0 1 1 0 0 +EDGE2 9300 9100 -0.0982725 -0.010861 0.00362683 1 0 1 1 0 0 +EDGE2 9300 8121 -0.0513364 -1.00489 -1.55303 1 0 1 1 0 0 +EDGE2 9300 9099 -0.938189 -0.030732 -0.0148066 1 0 1 1 0 0 +EDGE2 9300 9279 -0.909005 -0.0516401 0.00577801 1 0 1 1 0 0 +EDGE2 9300 9299 -1.01408 0.0266692 0.0168109 1 0 1 1 0 0 +EDGE2 9300 9079 -0.988658 0.0337706 -0.0265117 1 0 1 1 0 0 +EDGE2 9301 8120 -0.96773 -0.00496351 1.58328 1 0 1 1 0 0 +EDGE2 9301 9280 -0.98392 -0.129752 -1.55685 1 0 1 1 0 0 +EDGE2 9301 9081 -0.010751 0.00433668 -0.01846 1 0 1 1 0 0 +EDGE2 9301 9101 -0.0374062 -0.0457532 -0.0106794 1 0 1 1 0 0 +EDGE2 9301 9281 0.0989329 0.0573158 -0.0268773 1 0 1 1 0 0 +EDGE2 9301 9300 -0.997021 -0.0319452 -1.57963 1 0 1 1 0 0 +EDGE2 9301 9080 -1.06243 -0.00221998 -1.59427 1 0 1 1 0 0 +EDGE2 9301 9100 -1.03368 -0.0712827 -1.59369 1 0 1 1 0 0 +EDGE2 9301 9082 1.00046 0.0677773 -0.0463416 1 0 1 1 0 0 +EDGE2 9301 9102 0.906824 0.0199201 -0.0186626 1 0 1 1 0 0 +EDGE2 9301 9282 1.03071 -0.0877544 0.0199935 1 0 1 1 0 0 +EDGE2 9302 9301 -0.998801 -0.0813257 -0.00521236 1 0 1 1 0 0 +EDGE2 9302 9081 -1.04364 0.110447 -0.00335873 1 0 1 1 0 0 +EDGE2 9302 9101 -0.982414 0.0236434 -0.034647 1 0 1 1 0 0 +EDGE2 9302 9281 -0.91037 -0.0799293 -0.00484646 1 0 1 1 0 0 +EDGE2 9302 9082 0.0303213 -0.0127605 0.00121467 1 0 1 1 0 0 +EDGE2 9302 9102 -0.0123911 0.0157494 -0.0109667 1 0 1 1 0 0 +EDGE2 9302 9282 0.0255885 0.0471401 -0.050432 1 0 1 1 0 0 +EDGE2 9302 9103 1.02121 -0.0642113 -0.0281291 1 0 1 1 0 0 +EDGE2 9302 9283 1.03533 -0.0313176 -0.011148 1 0 1 1 0 0 +EDGE2 9302 9083 0.99082 -0.0128867 -0.011845 1 0 1 1 0 0 +EDGE2 9303 9302 -1.01676 0.0308745 -0.00475929 1 0 1 1 0 0 +EDGE2 9303 9082 -0.970102 -0.0695033 0.0104647 1 0 1 1 0 0 +EDGE2 9303 9102 -1.00036 0.0305484 -0.0122005 1 0 1 1 0 0 +EDGE2 9303 9282 -1.07117 0.00393015 0.000552629 1 0 1 1 0 0 +EDGE2 9303 9103 0.0741065 -0.112188 -0.0213027 1 0 1 1 0 0 +EDGE2 9303 9283 -0.0159499 0.0364927 0.0179099 1 0 1 1 0 0 +EDGE2 9303 9083 0.0133976 -0.0268924 0.0161161 1 0 1 1 0 0 +EDGE2 9303 9084 0.983873 0.0183884 0.0277329 1 0 1 1 0 0 +EDGE2 9303 9284 1.02477 -0.0899427 -0.00477802 1 0 1 1 0 0 +EDGE2 9303 9104 1.01072 0.126445 0.0210705 1 0 1 1 0 0 +EDGE2 9304 9303 -1.0663 0.00830505 -0.0287772 1 0 1 1 0 0 +EDGE2 9304 9103 -0.956033 -0.0454624 0.0245807 1 0 1 1 0 0 +EDGE2 9304 9283 -1.06331 0.0547037 0.000240401 1 0 1 1 0 0 +EDGE2 9304 9083 -0.980967 0.0414475 -0.0116401 1 0 1 1 0 0 +EDGE2 9304 9265 0.976133 -0.0319276 -3.16016 1 0 1 1 0 0 +EDGE2 9304 9085 0.998716 -0.0217005 -0.0195063 1 0 1 1 0 0 +EDGE2 9304 9084 -0.0596155 -0.0344674 -0.0154574 1 0 1 1 0 0 +EDGE2 9304 9284 -0.0207881 -0.0121993 0.0310438 1 0 1 1 0 0 +EDGE2 9304 9104 -0.0136949 -0.0250048 0.0255002 1 0 1 1 0 0 +EDGE2 9304 9285 1.07552 -0.0518348 -0.0380714 1 0 1 1 0 0 +EDGE2 9304 9105 1.03573 0.0755615 0.0333829 1 0 1 1 0 0 +EDGE2 9305 9264 1.06695 -0.0582206 -3.12966 1 0 1 1 0 0 +EDGE2 9305 9265 0.0493328 0.0254797 -3.15072 1 0 1 1 0 0 +EDGE2 9305 9106 -0.0109247 -1.01298 -1.57974 1 0 1 1 0 0 +EDGE2 9305 9085 -0.0164509 -0.0113467 0.0283805 1 0 1 1 0 0 +EDGE2 9305 9084 -0.95009 -0.0436766 0.0426039 1 0 1 1 0 0 +EDGE2 9305 9284 -0.967922 -0.00985573 0.029168 1 0 1 1 0 0 +EDGE2 9305 9304 -0.964454 -0.0388364 -0.0288742 1 0 1 1 0 0 +EDGE2 9305 9104 -1.03078 -0.0152584 0.0362023 1 0 1 1 0 0 +EDGE2 9305 9285 -0.00613502 -0.0442808 -0.0102689 1 0 1 1 0 0 +EDGE2 9305 9105 -0.100913 -0.0431909 -0.000472318 1 0 1 1 0 0 +EDGE2 9305 9266 0.0367756 1.04567 1.51734 1 0 1 1 0 0 +EDGE2 9305 9086 -0.00531108 1.09461 1.57854 1 0 1 1 0 0 +EDGE2 9305 9286 -0.0231519 1.03306 1.54445 1 0 1 1 0 0 +EDGE2 9306 9265 -1.01653 0.0696467 1.56019 1 0 1 1 0 0 +EDGE2 9306 9085 -0.941968 0.0119762 -1.57228 1 0 1 1 0 0 +EDGE2 9306 9285 -1.02497 0.0172511 -1.57765 1 0 1 1 0 0 +EDGE2 9306 9305 -1.05012 -0.0322323 -1.57332 1 0 1 1 0 0 +EDGE2 9306 9105 -0.91877 -0.0417883 -1.56652 1 0 1 1 0 0 +EDGE2 9306 9266 0.0590475 -0.0036658 -0.0123641 1 0 1 1 0 0 +EDGE2 9306 9287 1.08675 -0.0323308 0.0318491 1 0 1 1 0 0 +EDGE2 9306 9267 1.04004 -0.0367175 -0.00872524 1 0 1 1 0 0 +EDGE2 9306 9086 -0.034952 -0.0364906 0.0181223 1 0 1 1 0 0 +EDGE2 9306 9286 0.0605587 -0.085025 0.00222081 1 0 1 1 0 0 +EDGE2 9306 9087 1.01042 -0.00936885 -0.0140927 1 0 1 1 0 0 +EDGE2 9307 9306 -0.997597 -0.0623777 -0.0113853 1 0 1 1 0 0 +EDGE2 9307 9266 -1.00744 -0.00667753 0.0181441 1 0 1 1 0 0 +EDGE2 9307 9088 1.00252 -0.00388429 0.0411813 1 0 1 1 0 0 +EDGE2 9307 9287 0.0920372 0.0436035 0.010789 1 0 1 1 0 0 +EDGE2 9307 9267 0.0219941 -0.0123714 0.00256446 1 0 1 1 0 0 +EDGE2 9307 9086 -0.989134 0.0235715 -0.00815874 1 0 1 1 0 0 +EDGE2 9307 9286 -0.921051 -0.0166633 -0.00522451 1 0 1 1 0 0 +EDGE2 9307 9268 1.02225 0.006175 -0.00148634 1 0 1 1 0 0 +EDGE2 9307 9087 -0.0668397 0.0282576 0.00358433 1 0 1 1 0 0 +EDGE2 9307 9288 1.02737 -0.0121717 -0.00695385 1 0 1 1 0 0 +EDGE2 9308 9089 1.02959 -0.0489386 -0.00344473 1 0 1 1 0 0 +EDGE2 9308 9088 -0.0263164 0.0214848 0.00640668 1 0 1 1 0 0 +EDGE2 9308 9287 -0.897378 -0.00835991 -0.0396539 1 0 1 1 0 0 +EDGE2 9308 9267 -1.00166 -0.063469 -0.00567565 1 0 1 1 0 0 +EDGE2 9308 9307 -0.986866 0.0276458 -0.0148818 1 0 1 1 0 0 +EDGE2 9308 9268 -0.0184958 -0.0202774 -0.00829225 1 0 1 1 0 0 +EDGE2 9308 9087 -1.10119 0.00930539 0.01387 1 0 1 1 0 0 +EDGE2 9308 9288 -0.00785936 0.00119303 0.00994634 1 0 1 1 0 0 +EDGE2 9308 9289 0.989141 0.0469131 0.00414214 1 0 1 1 0 0 +EDGE2 9308 9269 0.979817 0.0256568 0.0142176 1 0 1 1 0 0 +EDGE2 9309 9089 0.00153338 -0.03326 0.0488975 1 0 1 1 0 0 +EDGE2 9309 9088 -1.10377 -0.0201574 -0.0224999 1 0 1 1 0 0 +EDGE2 9309 9308 -1.01259 -0.0529014 0.0278642 1 0 1 1 0 0 +EDGE2 9309 9268 -1.06351 -0.0815707 0.028982 1 0 1 1 0 0 +EDGE2 9309 9288 -1.03441 -0.0164574 -0.0210326 1 0 1 1 0 0 +EDGE2 9309 9289 -0.0201223 -0.0369051 0.0288887 1 0 1 1 0 0 +EDGE2 9309 9269 0.0168043 0.0606813 0.0011961 1 0 1 1 0 0 +EDGE2 9309 9230 0.949376 0.0836478 -3.14083 1 0 1 1 0 0 +EDGE2 9309 9270 1.06234 -0.0311334 -6.10422e-05 1 0 1 1 0 0 +EDGE2 9309 9290 0.910102 0.0391119 -0.00964185 1 0 1 1 0 0 +EDGE2 9309 9090 1.01617 0.00560696 0.0141329 1 0 1 1 0 0 +EDGE2 9310 9089 -0.96531 -0.0330198 -0.016447 1 0 1 1 0 0 +EDGE2 9310 9289 -0.97482 -0.00985169 -0.0136568 1 0 1 1 0 0 +EDGE2 9310 9309 -0.929452 0.00384605 0.00941355 1 0 1 1 0 0 +EDGE2 9310 9269 -0.931628 0.0131384 -0.00159083 1 0 1 1 0 0 +EDGE2 9310 9229 0.997544 0.0337937 -3.12243 1 0 1 1 0 0 +EDGE2 9310 9271 0.0517612 1.02239 1.5211 1 0 1 1 0 0 +EDGE2 9310 9291 -0.0652468 0.979224 1.6036 1 0 1 1 0 0 +EDGE2 9310 9091 0.0113615 0.964148 1.57196 1 0 1 1 0 0 +EDGE2 9310 9230 -0.0265595 -0.000429838 -3.17725 1 0 1 1 0 0 +EDGE2 9310 9270 -0.020863 0.0424773 0.0136695 1 0 1 1 0 0 +EDGE2 9310 9290 -0.000989165 -0.0232295 -0.0214013 1 0 1 1 0 0 +EDGE2 9310 9090 0.0162148 0.0663945 0.0103106 1 0 1 1 0 0 +EDGE2 9310 9231 -0.0123697 -0.923915 -1.5695 1 0 1 1 0 0 +EDGE2 9311 9292 1.03865 0.00426723 0.0248856 1 0 1 1 0 0 +EDGE2 9311 9092 1.01127 0.038675 0.0296562 1 0 1 1 0 0 +EDGE2 9311 9272 1.04899 -0.0348193 -0.00695907 1 0 1 1 0 0 +EDGE2 9311 9310 -1.0414 -0.0180427 -1.55257 1 0 1 1 0 0 +EDGE2 9311 9271 0.00493785 0.00315771 0.00708809 1 0 1 1 0 0 +EDGE2 9311 9291 -0.135378 -0.0929553 -0.0109795 1 0 1 1 0 0 +EDGE2 9311 9091 0.114746 0.0181621 -0.0273957 1 0 1 1 0 0 +EDGE2 9311 9230 -0.977008 0.0114805 1.54102 1 0 1 1 0 0 +EDGE2 9311 9270 -1.00468 0.0826463 -1.57829 1 0 1 1 0 0 +EDGE2 9311 9290 -1.02964 -0.00971511 -1.54412 1 0 1 1 0 0 +EDGE2 9311 9090 -1.03307 -0.0588049 -1.54797 1 0 1 1 0 0 +EDGE2 9312 9292 -0.0170529 0.0307648 0.0230669 1 0 1 1 0 0 +EDGE2 9312 9093 1.0005 -0.0636147 -0.0324069 1 0 1 1 0 0 +EDGE2 9312 9273 1.01318 0.00465192 -0.0159014 1 0 1 1 0 0 +EDGE2 9312 9293 1.02332 0.0284139 -0.0191479 1 0 1 1 0 0 +EDGE2 9312 9092 -0.0144224 -0.0280452 0.0221001 1 0 1 1 0 0 +EDGE2 9312 9272 0.0058107 0.0192829 -0.0285598 1 0 1 1 0 0 +EDGE2 9312 9271 -0.978411 0.0631835 0.0151685 1 0 1 1 0 0 +EDGE2 9312 9291 -1.01512 0.0147179 0.0255243 1 0 1 1 0 0 +EDGE2 9312 9311 -1.03128 -0.0625761 -0.0199722 1 0 1 1 0 0 +EDGE2 9312 9091 -1.0507 0.0306009 0.00434763 1 0 1 1 0 0 +EDGE2 9313 9274 1.06836 -0.0620848 0.0235762 1 0 1 1 0 0 +EDGE2 9313 9294 1.00187 -0.0365812 -0.0125919 1 0 1 1 0 0 +EDGE2 9313 9094 1.02702 0.0478253 -0.00502696 1 0 1 1 0 0 +EDGE2 9313 9292 -0.937571 -0.0681864 0.0331757 1 0 1 1 0 0 +EDGE2 9313 9093 0.00391164 0.00275943 -0.0335677 1 0 1 1 0 0 +EDGE2 9313 9273 0.0493206 -0.0139583 -0.00208141 1 0 1 1 0 0 +EDGE2 9313 9293 0.0259521 -0.0035352 0.00197827 1 0 1 1 0 0 +EDGE2 9313 9312 -0.977808 0.0257729 -0.0111283 1 0 1 1 0 0 +EDGE2 9313 9092 -1.04047 0.0478016 -0.00337455 1 0 1 1 0 0 +EDGE2 9313 9272 -1.04697 0.0415719 0.0012852 1 0 1 1 0 0 +EDGE2 9314 9313 -1.02774 0.020442 -0.00684275 1 0 1 1 0 0 +EDGE2 9314 9075 0.937622 -0.00690247 -3.1305 1 0 1 1 0 0 +EDGE2 9314 9275 1.10091 0.0323622 -0.000735085 1 0 1 1 0 0 +EDGE2 9314 9295 1.03044 0.0132047 -0.0146274 1 0 1 1 0 0 +EDGE2 9314 9095 1.02154 -0.0303481 -0.0301446 1 0 1 1 0 0 +EDGE2 9314 9274 -0.0299566 0.0331125 -0.0141857 1 0 1 1 0 0 +EDGE2 9314 9294 -0.0867626 -0.0763781 0.00404786 1 0 1 1 0 0 +EDGE2 9314 9094 -0.0497324 -0.0250433 -0.00219105 1 0 1 1 0 0 +EDGE2 9314 9093 -0.980904 0.0566949 0.0123311 1 0 1 1 0 0 +EDGE2 9314 9273 -0.969597 -0.0894324 0.0287863 1 0 1 1 0 0 +EDGE2 9314 9293 -1.02168 -0.00189554 0.00990713 1 0 1 1 0 0 +EDGE2 9314 8175 1.06695 -0.00148771 -3.18018 1 0 1 1 0 0 +EDGE2 9315 9296 0.0497343 0.981994 1.59014 1 0 1 1 0 0 +EDGE2 9315 9096 -0.0406712 0.954466 1.54938 1 0 1 1 0 0 +EDGE2 9315 9276 0.0615868 0.967325 1.5423 1 0 1 1 0 0 +EDGE2 9315 9076 0.0650027 1.03249 1.57275 1 0 1 1 0 0 +EDGE2 9315 9074 0.93915 -0.0559209 -3.12244 1 0 1 1 0 0 +EDGE2 9315 9075 -0.0345283 0.0689865 -3.13073 1 0 1 1 0 0 +EDGE2 9315 9275 -0.0274948 0.0361803 -0.00780694 1 0 1 1 0 0 +EDGE2 9315 9295 -0.035918 0.0445987 0.0378081 1 0 1 1 0 0 +EDGE2 9315 9095 0.0682261 0.0253717 -0.024049 1 0 1 1 0 0 +EDGE2 9315 9274 -0.98026 0.00416563 0.00257061 1 0 1 1 0 0 +EDGE2 9315 9294 -0.947811 -0.0346322 0.0225386 1 0 1 1 0 0 +EDGE2 9315 9314 -0.984368 -0.0559009 -0.0272171 1 0 1 1 0 0 +EDGE2 9315 9094 -0.979319 -0.0260498 0.0146765 1 0 1 1 0 0 +EDGE2 9315 8175 0.00653163 0.0464313 -3.13087 1 0 1 1 0 0 +EDGE2 9315 8174 0.942062 -0.0721542 -3.20432 1 0 1 1 0 0 +EDGE2 9315 8176 0.00567661 -1.05681 -1.59337 1 0 1 1 0 0 +EDGE2 9316 9297 1.0221 -0.0013309 -0.00685744 1 0 1 1 0 0 +EDGE2 9316 9296 -0.0120974 -0.0375357 0.0441706 1 0 1 1 0 0 +EDGE2 9316 9077 1.03888 0.00985363 0.00138407 1 0 1 1 0 0 +EDGE2 9316 9097 1.05915 0.00512701 0.0221762 1 0 1 1 0 0 +EDGE2 9316 9277 1.01273 0.0136276 -0.0157596 1 0 1 1 0 0 +EDGE2 9316 9096 -0.072629 0.0369588 -0.00231121 1 0 1 1 0 0 +EDGE2 9316 9276 -0.040976 -0.137591 -0.00255626 1 0 1 1 0 0 +EDGE2 9316 9076 0.00991104 0.0309451 0.00852034 1 0 1 1 0 0 +EDGE2 9316 9075 -1.00521 0.0209473 1.58428 1 0 1 1 0 0 +EDGE2 9316 9275 -1.06555 -0.0504986 -1.57846 1 0 1 1 0 0 +EDGE2 9316 9295 -0.961127 -0.0743903 -1.57321 1 0 1 1 0 0 +EDGE2 9316 9315 -0.97147 -0.0314103 -1.57985 1 0 1 1 0 0 +EDGE2 9316 9095 -0.96185 -0.0017037 -1.55228 1 0 1 1 0 0 +EDGE2 9316 8175 -0.923389 -0.0390597 1.55818 1 0 1 1 0 0 +EDGE2 9317 9098 0.959726 -0.00581085 -0.0258018 1 0 1 1 0 0 +EDGE2 9317 9278 1.04775 -0.00790569 -0.0638005 1 0 1 1 0 0 +EDGE2 9317 9298 1.04366 -0.0367433 -0.0292003 1 0 1 1 0 0 +EDGE2 9317 9078 0.899647 -0.0376268 0.0164417 1 0 1 1 0 0 +EDGE2 9317 9297 0.0182782 -0.00438365 0.0251531 1 0 1 1 0 0 +EDGE2 9317 9296 -1.02933 -0.0220525 0.0144204 1 0 1 1 0 0 +EDGE2 9317 9077 0.0376215 0.0784129 0.019258 1 0 1 1 0 0 +EDGE2 9317 9097 -0.0773723 -0.0895068 0.0300214 1 0 1 1 0 0 +EDGE2 9317 9277 -0.017436 0.0973888 0.0195347 1 0 1 1 0 0 +EDGE2 9317 9316 -1.0407 -0.0153203 -0.0102988 1 0 1 1 0 0 +EDGE2 9317 9096 -1.02757 -0.0536414 0.00128492 1 0 1 1 0 0 +EDGE2 9317 9276 -0.952389 0.00162766 0.0118987 1 0 1 1 0 0 +EDGE2 9317 9076 -1.0568 0.0104686 0.0160878 1 0 1 1 0 0 +EDGE2 9318 9099 0.981666 -0.0161588 -0.0320293 1 0 1 1 0 0 +EDGE2 9318 9279 1.08462 0.0449975 7.81847e-05 1 0 1 1 0 0 +EDGE2 9318 9299 1.06223 -0.00352206 -6.1799e-06 1 0 1 1 0 0 +EDGE2 9318 9079 0.925759 -0.0947004 0.00425572 1 0 1 1 0 0 +EDGE2 9318 9098 -0.0501744 0.0202026 -0.000187223 1 0 1 1 0 0 +EDGE2 9318 9278 -0.0537517 -0.00622985 -0.0156075 1 0 1 1 0 0 +EDGE2 9318 9298 0.0253972 0.0474857 0.0280744 1 0 1 1 0 0 +EDGE2 9318 9078 0.028975 0.131124 0.0219508 1 0 1 1 0 0 +EDGE2 9318 9297 -0.994669 -0.0363514 0.0283906 1 0 1 1 0 0 +EDGE2 9318 9317 -1.00978 0.0538258 0.0161466 1 0 1 1 0 0 +EDGE2 9318 9077 -1.09713 0.032714 -0.00697357 1 0 1 1 0 0 +EDGE2 9318 9097 -0.901574 -0.0182088 -0.0238379 1 0 1 1 0 0 +EDGE2 9318 9277 -1.06598 -0.023395 -0.0151105 1 0 1 1 0 0 +EDGE2 9319 8120 0.943918 -0.00707949 -3.12947 1 0 1 1 0 0 +EDGE2 9319 9280 0.992953 0.0198816 -0.0294838 1 0 1 1 0 0 +EDGE2 9319 9300 0.933998 -0.144136 -0.0271841 1 0 1 1 0 0 +EDGE2 9319 9080 0.938852 -0.0776331 0.00889488 1 0 1 1 0 0 +EDGE2 9319 9100 1.00759 0.0267216 0.00589919 1 0 1 1 0 0 +EDGE2 9319 9318 -0.949892 0.0580561 -0.018412 1 0 1 1 0 0 +EDGE2 9319 9099 -0.0244023 -0.0235064 0.00136967 1 0 1 1 0 0 +EDGE2 9319 9279 -0.00891226 0.033708 0.0301168 1 0 1 1 0 0 +EDGE2 9319 9299 -0.00489439 -0.0413967 0.0164883 1 0 1 1 0 0 +EDGE2 9319 9079 0.154435 0.0172576 -0.0262553 1 0 1 1 0 0 +EDGE2 9319 9098 -0.988032 0.0066617 0.0314191 1 0 1 1 0 0 +EDGE2 9319 9278 -0.937894 0.0889635 0.0446929 1 0 1 1 0 0 +EDGE2 9319 9298 -1.03834 -0.136415 -0.00492464 1 0 1 1 0 0 +EDGE2 9319 9078 -1.05784 0.0262436 -0.0158889 1 0 1 1 0 0 +EDGE2 9320 8120 0.0104434 0.0335008 -3.11989 1 0 1 1 0 0 +EDGE2 9320 9280 -0.0966693 -0.0766438 0.00781673 1 0 1 1 0 0 +EDGE2 9320 8119 0.973402 0.00871272 -3.15986 1 0 1 1 0 0 +EDGE2 9320 9301 -0.00484327 1.01643 1.57459 1 0 1 1 0 0 +EDGE2 9320 9081 0.0486415 0.984569 1.56587 1 0 1 1 0 0 +EDGE2 9320 9101 -0.0674728 0.930239 1.5729 1 0 1 1 0 0 +EDGE2 9320 9281 -0.116919 1.02245 1.57719 1 0 1 1 0 0 +EDGE2 9320 9300 -5.06651e-05 -0.036157 0.000658956 1 0 1 1 0 0 +EDGE2 9320 9080 -0.0472115 0.041487 -0.0195366 1 0 1 1 0 0 +EDGE2 9320 9100 0.0294419 0.024471 -0.0184899 1 0 1 1 0 0 +EDGE2 9320 8121 -0.0267542 -1.01418 -1.59344 1 0 1 1 0 0 +EDGE2 9320 9319 -0.961807 0.000505663 -0.00702296 1 0 1 1 0 0 +EDGE2 9320 9099 -0.99583 0.0182121 0.00186508 1 0 1 1 0 0 +EDGE2 9320 9279 -1.02153 0.0145632 0.0259178 1 0 1 1 0 0 +EDGE2 9320 9299 -1.02101 0.0233344 0.0106815 1 0 1 1 0 0 +EDGE2 9320 9079 -1.08568 0.00389975 0.00501285 1 0 1 1 0 0 +EDGE2 9321 8120 -0.960921 -0.00570748 1.55349 1 0 1 1 0 0 +EDGE2 9321 9280 -1.05303 -0.0222969 -1.56923 1 0 1 1 0 0 +EDGE2 9321 9320 -0.868986 -0.0317711 -1.56952 1 0 1 1 0 0 +EDGE2 9321 9301 -0.018374 -0.0546369 0.0134814 1 0 1 1 0 0 +EDGE2 9321 9081 0.0834624 -0.00904192 -0.0069141 1 0 1 1 0 0 +EDGE2 9321 9101 0.0116309 -0.0262764 0.014992 1 0 1 1 0 0 +EDGE2 9321 9281 -0.0380143 -0.0506104 0.0139095 1 0 1 1 0 0 +EDGE2 9321 9300 -0.908433 -0.020466 -1.54104 1 0 1 1 0 0 +EDGE2 9321 9302 0.978018 0.0227636 -0.0109733 1 0 1 1 0 0 +EDGE2 9321 9080 -0.978349 -0.101996 -1.5408 1 0 1 1 0 0 +EDGE2 9321 9100 -1.00039 0.00656621 -1.54948 1 0 1 1 0 0 +EDGE2 9321 9082 1.02115 -0.0250468 0.0185192 1 0 1 1 0 0 +EDGE2 9321 9102 1.02347 -0.036928 0.0163853 1 0 1 1 0 0 +EDGE2 9321 9282 1.02785 0.0610417 -0.00599625 1 0 1 1 0 0 +EDGE2 9322 9301 -1.04956 0.0346676 -0.00736238 1 0 1 1 0 0 +EDGE2 9322 9321 -0.974227 0.00922974 -0.00886618 1 0 1 1 0 0 +EDGE2 9322 9081 -0.991288 0.0504302 0.0189294 1 0 1 1 0 0 +EDGE2 9322 9101 -1.0552 -0.102877 -0.00288709 1 0 1 1 0 0 +EDGE2 9322 9281 -0.943692 -0.0350521 -0.00492983 1 0 1 1 0 0 +EDGE2 9322 9302 0.0254594 -0.0746334 0.0289242 1 0 1 1 0 0 +EDGE2 9322 9303 0.9911 0.0221757 0.0298934 1 0 1 1 0 0 +EDGE2 9322 9082 -0.0290496 -0.0674797 0.0119338 1 0 1 1 0 0 +EDGE2 9322 9102 0.0566369 0.0262843 -0.00123636 1 0 1 1 0 0 +EDGE2 9322 9282 -0.012298 0.0200331 0.0192658 1 0 1 1 0 0 +EDGE2 9322 9103 0.990314 0.070501 0.0188255 1 0 1 1 0 0 +EDGE2 9322 9283 0.994818 -0.00115009 0.0247969 1 0 1 1 0 0 +EDGE2 9322 9083 1.01282 -0.0559723 0.00582113 1 0 1 1 0 0 +EDGE2 9323 9302 -1.04378 0.0774912 0.00932392 1 0 1 1 0 0 +EDGE2 9323 9322 -0.998584 -0.0246958 -0.00435515 1 0 1 1 0 0 +EDGE2 9323 9303 0.0386077 -0.0755813 -0.00690671 1 0 1 1 0 0 +EDGE2 9323 9082 -0.993257 0.0112367 0.0126959 1 0 1 1 0 0 +EDGE2 9323 9102 -1.00713 0.0451189 -0.0153619 1 0 1 1 0 0 +EDGE2 9323 9282 -0.974089 0.0302682 0.0222875 1 0 1 1 0 0 +EDGE2 9323 9103 0.0599318 -0.0168922 -0.0324081 1 0 1 1 0 0 +EDGE2 9323 9283 -0.00582322 0.0197454 -0.0146276 1 0 1 1 0 0 +EDGE2 9323 9083 -0.0414145 -0.0680324 -0.0242265 1 0 1 1 0 0 +EDGE2 9323 9084 1.01946 0.000208732 2.8229e-05 1 0 1 1 0 0 +EDGE2 9323 9284 1.05469 -0.101985 0.0180384 1 0 1 1 0 0 +EDGE2 9323 9304 0.95384 0.0748674 0.000465413 1 0 1 1 0 0 +EDGE2 9323 9104 1.06848 -0.0304004 0.00186801 1 0 1 1 0 0 +EDGE2 9324 9303 -0.923163 0.00797456 0.00580026 1 0 1 1 0 0 +EDGE2 9324 9323 -0.954033 0.026744 0.0294446 1 0 1 1 0 0 +EDGE2 9324 9103 -0.954787 0.0630541 0.0175151 1 0 1 1 0 0 +EDGE2 9324 9283 -1.02953 0.110845 0.0229377 1 0 1 1 0 0 +EDGE2 9324 9083 -1.02471 0.0281942 0.0198878 1 0 1 1 0 0 +EDGE2 9324 9265 0.964043 -0.00142817 -3.13453 1 0 1 1 0 0 +EDGE2 9324 9085 1.03106 0.0692737 -0.00562589 1 0 1 1 0 0 +EDGE2 9324 9084 -0.0558515 0.0663378 0.0226956 1 0 1 1 0 0 +EDGE2 9324 9284 -0.0179402 -0.0967646 -0.00101265 1 0 1 1 0 0 +EDGE2 9324 9304 -0.04583 0.0083769 0.00305633 1 0 1 1 0 0 +EDGE2 9324 9104 -0.078588 -0.0251697 0.024861 1 0 1 1 0 0 +EDGE2 9324 9285 1.01442 -0.00258508 0.00985385 1 0 1 1 0 0 +EDGE2 9324 9305 0.989998 -0.0139846 0.0174526 1 0 1 1 0 0 +EDGE2 9324 9105 0.908559 0.0587265 0.00965525 1 0 1 1 0 0 +EDGE2 9325 9306 -0.0275895 0.948813 1.54668 1 0 1 1 0 0 +EDGE2 9325 9264 0.922566 0.0132667 -3.14472 1 0 1 1 0 0 +EDGE2 9325 9265 -0.0962261 0.0197369 -3.12589 1 0 1 1 0 0 +EDGE2 9325 9106 -0.0664911 -1.03872 -1.55226 1 0 1 1 0 0 +EDGE2 9325 9085 -0.0829885 0.0819413 -0.00322519 1 0 1 1 0 0 +EDGE2 9325 9084 -1.01002 -0.0409365 -0.0159903 1 0 1 1 0 0 +EDGE2 9325 9284 -0.932225 0.0336945 0.0115507 1 0 1 1 0 0 +EDGE2 9325 9304 -0.978287 0.05343 0.00329441 1 0 1 1 0 0 +EDGE2 9325 9324 -1.00254 0.0082477 0.027592 1 0 1 1 0 0 +EDGE2 9325 9104 -1.03559 0.0569077 -0.014777 1 0 1 1 0 0 +EDGE2 9325 9285 -0.0337221 0.0108455 -0.00177722 1 0 1 1 0 0 +EDGE2 9325 9305 -0.00862914 0.0333569 -0.00911391 1 0 1 1 0 0 +EDGE2 9325 9105 0.00933742 0.0241595 0.019559 1 0 1 1 0 0 +EDGE2 9325 9266 0.0472557 1.03743 1.55185 1 0 1 1 0 0 +EDGE2 9325 9086 0.0303564 0.931893 1.56864 1 0 1 1 0 0 +EDGE2 9325 9286 0.0601624 0.984934 1.5772 1 0 1 1 0 0 +EDGE2 9326 9107 0.967165 -0.00512783 0.0113238 1 0 1 1 0 0 +EDGE2 9326 9265 -1.01192 0.0128308 -1.57032 1 0 1 1 0 0 +EDGE2 9326 9106 -0.126306 -0.0501644 0.0335093 1 0 1 1 0 0 +EDGE2 9326 9085 -0.967181 -0.0168362 1.56353 1 0 1 1 0 0 +EDGE2 9326 9285 -0.927692 0.0119259 1.55582 1 0 1 1 0 0 +EDGE2 9326 9305 -0.979534 0.00213185 1.5812 1 0 1 1 0 0 +EDGE2 9326 9325 -0.898852 0.0640072 1.5736 1 0 1 1 0 0 +EDGE2 9326 9105 -1.00145 -0.037428 1.60697 1 0 1 1 0 0 +EDGE2 9327 9326 -1.02915 0.102266 -0.0050967 1 0 1 1 0 0 +EDGE2 9327 9108 0.993859 -0.0655826 -0.00799251 1 0 1 1 0 0 +EDGE2 9327 9107 -0.0421239 0.0387908 0.0173225 1 0 1 1 0 0 +EDGE2 9327 9106 -1.06581 -0.069534 -0.00739512 1 0 1 1 0 0 +EDGE2 9328 9109 0.958036 0.0136667 -0.00915187 1 0 1 1 0 0 +EDGE2 9328 9327 -0.93754 0.0351553 -0.0241524 1 0 1 1 0 0 +EDGE2 9328 9108 -0.0766513 0.071929 -0.0238442 1 0 1 1 0 0 +EDGE2 9328 9107 -1.01312 0.11273 -0.0422935 1 0 1 1 0 0 +EDGE2 9329 9109 -0.0305556 0.0472371 0.0114464 1 0 1 1 0 0 +EDGE2 9329 9110 0.973996 -0.0256105 0.028174 1 0 1 1 0 0 +EDGE2 9329 9108 -0.982939 -0.105128 0.0247964 1 0 1 1 0 0 +EDGE2 9329 9328 -1.10827 -0.0289816 0.0132838 1 0 1 1 0 0 +EDGE2 9330 9109 -1.02714 -0.020561 -0.0235836 1 0 1 1 0 0 +EDGE2 9330 9110 0.0580468 -0.0631509 0.0156416 1 0 1 1 0 0 +EDGE2 9330 9329 -1.1028 0.022254 0.00389239 1 0 1 1 0 0 +EDGE2 9330 9111 0.0255644 1.033 1.56339 1 0 1 1 0 0 +EDGE2 9331 9110 -1.04533 -0.0351095 1.59671 1 0 1 1 0 0 +EDGE2 9331 9330 -0.991933 -0.00317044 1.581 1 0 1 1 0 0 +EDGE2 9332 9331 -1.05413 0.0302987 -0.00978912 1 0 1 1 0 0 +EDGE2 9333 9332 -0.918636 0.065759 0.00191192 1 0 1 1 0 0 +EDGE2 9334 8115 0.964154 -0.00435154 -3.12352 1 0 1 1 0 0 +EDGE2 9334 9333 -0.9728 -0.101629 -0.01067 1 0 1 1 0 0 +EDGE2 9335 8115 -0.0982694 -0.0588678 -3.14413 1 0 1 1 0 0 +EDGE2 9335 8114 1.02347 -0.0707604 -3.10264 1 0 1 1 0 0 +EDGE2 9335 8116 0.0943655 -1.04423 -1.54376 1 0 1 1 0 0 +EDGE2 9335 9334 -0.9817 -0.0686194 -0.021268 1 0 1 1 0 0 +EDGE2 9336 9335 -1.03061 0.0559943 -1.53486 1 0 1 1 0 0 +EDGE2 9336 8115 -0.98323 0.11313 1.59927 1 0 1 1 0 0 +EDGE2 9337 9336 -1.03431 0.0342275 -0.0364139 1 0 1 1 0 0 +EDGE2 9338 9337 -0.890242 0.0219135 -0.0494561 1 0 1 1 0 0 +EDGE2 9339 6660 1.03326 -0.0589356 -3.14042 1 0 1 1 0 0 +EDGE2 9339 6540 0.993606 0.0159888 -3.12005 1 0 1 1 0 0 +EDGE2 9339 9338 -0.940667 -0.0796716 0.00509721 1 0 1 1 0 0 +EDGE2 9340 6539 0.9289 0.016766 -3.13723 1 0 1 1 0 0 +EDGE2 9340 6659 1.00216 0.0446441 -3.13509 1 0 1 1 0 0 +EDGE2 9340 6660 -0.00961763 -0.0817504 -3.17788 1 0 1 1 0 0 +EDGE2 9340 6661 -0.0119816 -0.954158 -1.5886 1 0 1 1 0 0 +EDGE2 9340 9339 -0.99186 -0.0232937 0.0122 1 0 1 1 0 0 +EDGE2 9340 6541 -0.11176 1.02131 1.59304 1 0 1 1 0 0 +EDGE2 9340 6540 -0.00918832 0.0369232 -3.1689 1 0 1 1 0 0 +EDGE2 9341 6660 -0.927506 -0.0504369 -1.56129 1 0 1 1 0 0 +EDGE2 9341 6662 1.04448 0.0466543 -0.00354624 1 0 1 1 0 0 +EDGE2 9341 9340 -1.00778 -0.0075644 1.58935 1 0 1 1 0 0 +EDGE2 9341 6661 -0.0301791 -0.0125074 0.00142219 1 0 1 1 0 0 +EDGE2 9341 6540 -1.0245 -0.036754 -1.58051 1 0 1 1 0 0 +EDGE2 9342 9341 -0.946194 0.0357578 0.00126754 1 0 1 1 0 0 +EDGE2 9342 6663 1.01571 0.00704787 -0.0142457 1 0 1 1 0 0 +EDGE2 9342 6662 0.0115316 0.0652889 0.00560105 1 0 1 1 0 0 +EDGE2 9342 6661 -1.08085 0.143072 -0.0319963 1 0 1 1 0 0 +EDGE2 9343 6664 0.992708 -0.0779346 -0.0103351 1 0 1 1 0 0 +EDGE2 9343 9342 -1.03035 0.00186153 0.0316055 1 0 1 1 0 0 +EDGE2 9343 6663 -0.0562077 -0.0216892 0.0346233 1 0 1 1 0 0 +EDGE2 9343 6662 -0.97062 0.0613227 -0.0130062 1 0 1 1 0 0 +EDGE2 9344 8085 0.971835 -0.062542 -3.15026 1 0 1 1 0 0 +EDGE2 9344 6525 0.931947 0.007008 -3.15928 1 0 1 1 0 0 +EDGE2 9344 6665 0.971539 -0.105158 -0.00125787 1 0 1 1 0 0 +EDGE2 9344 6664 -0.0249817 -0.0546889 -0.00633879 1 0 1 1 0 0 +EDGE2 9344 6663 -0.978825 0.0449474 0.00785851 1 0 1 1 0 0 +EDGE2 9344 9343 -0.995516 0.0268373 0.0269816 1 0 1 1 0 0 +EDGE2 9345 6666 0.0564547 0.978894 1.57575 1 0 1 1 0 0 +EDGE2 9345 6526 -0.0160379 1.00708 1.59289 1 0 1 1 0 0 +EDGE2 9345 8085 -0.00421293 -0.0233692 -3.13504 1 0 1 1 0 0 +EDGE2 9345 6524 1.01057 0.0511799 -3.13651 1 0 1 1 0 0 +EDGE2 9345 8084 1.04119 0.0102866 -3.14417 1 0 1 1 0 0 +EDGE2 9345 8086 0.0214397 -0.907601 -1.57893 1 0 1 1 0 0 +EDGE2 9345 6525 -0.0186736 0.0977961 -3.11055 1 0 1 1 0 0 +EDGE2 9345 6665 0.0381898 -0.00574068 -0.0167984 1 0 1 1 0 0 +EDGE2 9345 6664 -1.104 -0.00421281 0.0101269 1 0 1 1 0 0 +EDGE2 9345 9344 -1.02731 -0.0659191 -0.022582 1 0 1 1 0 0 +EDGE2 9346 6667 1.03396 -0.00660543 -0.0217535 1 0 1 1 0 0 +EDGE2 9346 6666 -0.0515137 -0.0469673 0.000583028 1 0 1 1 0 0 +EDGE2 9346 6527 1.01907 0.0349897 -0.0264212 1 0 1 1 0 0 +EDGE2 9346 6526 0.0603352 -0.110353 -0.0277236 1 0 1 1 0 0 +EDGE2 9346 8085 -0.988387 0.0284209 1.58106 1 0 1 1 0 0 +EDGE2 9346 9345 -1.06058 0.0136677 -1.5581 1 0 1 1 0 0 +EDGE2 9346 6525 -0.976955 0.0179941 1.57143 1 0 1 1 0 0 +EDGE2 9346 6665 -0.94738 0.0991424 -1.56042 1 0 1 1 0 0 +EDGE2 9347 6667 -0.0770568 -0.00185917 -0.0097191 1 0 1 1 0 0 +EDGE2 9347 6528 0.993914 -0.0244168 0.00521078 1 0 1 1 0 0 +EDGE2 9347 6668 0.936167 0.0741834 -0.0219124 1 0 1 1 0 0 +EDGE2 9347 6666 -0.996352 0.00879548 -0.0395009 1 0 1 1 0 0 +EDGE2 9347 9346 -1.00823 -0.0281796 0.00439174 1 0 1 1 0 0 +EDGE2 9347 6527 -0.0487479 0.0221439 -0.00722975 1 0 1 1 0 0 +EDGE2 9347 6526 -0.942102 -0.0860698 0.000372723 1 0 1 1 0 0 +EDGE2 9348 6529 1.01281 -0.000483997 0.0104593 1 0 1 1 0 0 +EDGE2 9348 6669 1.07534 -0.034153 0.0113767 1 0 1 1 0 0 +EDGE2 9348 6667 -1.07297 0.0303204 -0.00695165 1 0 1 1 0 0 +EDGE2 9348 6528 0.0659039 -0.0206958 0.0130575 1 0 1 1 0 0 +EDGE2 9348 6668 -0.0166974 -0.0144617 -0.00446411 1 0 1 1 0 0 +EDGE2 9348 9347 -1.08424 0.0124613 -0.0382042 1 0 1 1 0 0 +EDGE2 9348 6527 -1.01856 0.018891 -0.0247736 1 0 1 1 0 0 +EDGE2 9349 8070 0.984715 0.0446433 -3.12163 1 0 1 1 0 0 +EDGE2 9349 6529 0.00217363 -0.0514255 -0.044328 1 0 1 1 0 0 +EDGE2 9349 6669 0.0381251 0.00527263 0.0139643 1 0 1 1 0 0 +EDGE2 9349 6530 1.00235 -0.0228389 -0.00844453 1 0 1 1 0 0 +EDGE2 9349 6670 1.00525 0.0906221 -0.00499255 1 0 1 1 0 0 +EDGE2 9349 6528 -0.997241 -0.049493 -0.00795861 1 0 1 1 0 0 +EDGE2 9349 6668 -1.00625 0.00103529 -0.00953485 1 0 1 1 0 0 +EDGE2 9349 9348 -0.970935 0.0223663 -0.0268284 1 0 1 1 0 0 +EDGE2 9350 8070 0.0376078 -0.0162868 -3.14465 1 0 1 1 0 0 +EDGE2 9350 8069 1.03427 -0.0189964 -3.17943 1 0 1 1 0 0 +EDGE2 9350 8071 0.015476 -0.896816 -1.57478 1 0 1 1 0 0 +EDGE2 9350 6529 -1.06634 0.00125376 0.0150007 1 0 1 1 0 0 +EDGE2 9350 6669 -0.944209 -0.0159175 0.00277536 1 0 1 1 0 0 +EDGE2 9350 6530 -0.0447893 0.00871281 -0.0141742 1 0 1 1 0 0 +EDGE2 9350 6670 0.0420204 -0.0862078 0.0235767 1 0 1 1 0 0 +EDGE2 9350 9349 -0.987226 0.0263709 0.0124005 1 0 1 1 0 0 +EDGE2 9350 6531 -0.0743253 1.0031 1.60713 1 0 1 1 0 0 +EDGE2 9350 6671 0.0959895 1.03277 1.55843 1 0 1 1 0 0 +EDGE2 9351 8070 -1.04403 -0.000681979 1.58828 1 0 1 1 0 0 +EDGE2 9351 9350 -1.00612 -0.0427822 -1.58999 1 0 1 1 0 0 +EDGE2 9351 6530 -1.00742 -0.0272992 -1.56942 1 0 1 1 0 0 +EDGE2 9351 6670 -0.965684 -0.0952019 -1.57329 1 0 1 1 0 0 +EDGE2 9351 6672 0.964498 0.0193152 0.014735 1 0 1 1 0 0 +EDGE2 9351 6531 -0.0669549 -0.00749414 0.0203014 1 0 1 1 0 0 +EDGE2 9351 6671 0.0121074 -0.0220489 -0.00734973 1 0 1 1 0 0 +EDGE2 9351 6532 1.00783 0.0322503 -5.60813e-06 1 0 1 1 0 0 +EDGE2 9352 6672 -0.0211503 -0.0716865 0.029795 1 0 1 1 0 0 +EDGE2 9352 6531 -1.05499 -0.028287 -0.0139939 1 0 1 1 0 0 +EDGE2 9352 6671 -1.07714 -0.0455575 -0.0279535 1 0 1 1 0 0 +EDGE2 9352 9351 -1.08208 -0.035604 -0.0380286 1 0 1 1 0 0 +EDGE2 9352 6673 0.993037 0.0548606 0.0013373 1 0 1 1 0 0 +EDGE2 9352 6532 0.0883951 0.0105187 0.0153323 1 0 1 1 0 0 +EDGE2 9352 6533 0.967644 0.0954208 -0.000916721 1 0 1 1 0 0 +EDGE2 9353 6672 -0.883817 0.00460468 -0.00772523 1 0 1 1 0 0 +EDGE2 9353 9352 -0.958026 -0.00410962 0.0260358 1 0 1 1 0 0 +EDGE2 9353 6673 -0.024543 0.0496052 -0.0116678 1 0 1 1 0 0 +EDGE2 9353 6532 -0.94009 0.00453912 -0.00257212 1 0 1 1 0 0 +EDGE2 9353 6533 0.035118 0.0219169 -0.0214403 1 0 1 1 0 0 +EDGE2 9353 6534 0.950687 0.049224 -0.00994024 1 0 1 1 0 0 +EDGE2 9353 6674 0.929024 -0.00922282 0.00400558 1 0 1 1 0 0 +EDGE2 9354 6535 1.03372 0.0517453 7.87389e-05 1 0 1 1 0 0 +EDGE2 9354 6673 -0.972718 0.0266966 -0.0117547 1 0 1 1 0 0 +EDGE2 9354 9353 -1.04339 0.0310938 -0.0105886 1 0 1 1 0 0 +EDGE2 9354 6533 -0.9626 0.0251537 -0.0244628 1 0 1 1 0 0 +EDGE2 9354 6675 1.07193 -0.0470222 0.0147914 1 0 1 1 0 0 +EDGE2 9354 6534 0.129889 0.0312034 0.0132743 1 0 1 1 0 0 +EDGE2 9354 6674 -0.0176981 -0.0693616 0.00485487 1 0 1 1 0 0 +EDGE2 9354 6635 1.0585 -0.0217846 -3.14962 1 0 1 1 0 0 +EDGE2 9354 6655 0.954413 0.004022 -3.12972 1 0 1 1 0 0 +EDGE2 9354 6595 0.959764 -0.0326597 -3.12008 1 0 1 1 0 0 +EDGE2 9355 6535 0.0812698 0.0309952 -0.0245555 1 0 1 1 0 0 +EDGE2 9355 6636 -0.00666339 -0.927017 -1.57536 1 0 1 1 0 0 +EDGE2 9355 6676 -0.0262541 -0.962885 -1.57353 1 0 1 1 0 0 +EDGE2 9355 9354 -1.11875 -0.0494441 0.0117522 1 0 1 1 0 0 +EDGE2 9355 6675 -0.0128221 -0.049822 0.0193844 1 0 1 1 0 0 +EDGE2 9355 6534 -1.01809 0.0114194 -0.0222157 1 0 1 1 0 0 +EDGE2 9355 6596 0.00999777 -1.00026 -1.54544 1 0 1 1 0 0 +EDGE2 9355 6674 -0.98813 0.00311089 0.00135889 1 0 1 1 0 0 +EDGE2 9355 6635 -0.0357978 -0.0112661 -3.13988 1 0 1 1 0 0 +EDGE2 9355 6655 0.0522593 -0.0436061 -3.16611 1 0 1 1 0 0 +EDGE2 9355 6595 -0.0376634 -0.0132973 -3.12227 1 0 1 1 0 0 +EDGE2 9355 6654 0.96613 0.0999981 -3.19654 1 0 1 1 0 0 +EDGE2 9355 6536 -0.0846401 0.993242 1.61129 1 0 1 1 0 0 +EDGE2 9355 6656 0.000127167 0.999964 1.58195 1 0 1 1 0 0 +EDGE2 9355 6594 1.07835 0.029857 -3.14395 1 0 1 1 0 0 +EDGE2 9355 6634 0.979651 0.0335135 -3.15831 1 0 1 1 0 0 +EDGE2 9356 6535 -1.00796 -0.0957718 1.57467 1 0 1 1 0 0 +EDGE2 9356 6636 -0.0916004 -0.00700712 0.00358865 1 0 1 1 0 0 +EDGE2 9356 6677 0.970102 -0.0741111 0.0204759 1 0 1 1 0 0 +EDGE2 9356 6597 1.09468 -0.0535236 -0.00614258 1 0 1 1 0 0 +EDGE2 9356 6637 0.939374 0.00745616 -0.029884 1 0 1 1 0 0 +EDGE2 9356 6676 0.0372377 -0.0137071 0.0115356 1 0 1 1 0 0 +EDGE2 9356 6675 -0.982469 0.0720112 1.56321 1 0 1 1 0 0 +EDGE2 9356 6596 0.0433027 -0.0431498 0.0120957 1 0 1 1 0 0 +EDGE2 9356 9355 -1.13252 0.0283787 1.58309 1 0 1 1 0 0 +EDGE2 9356 6635 -0.960488 0.091061 -1.56465 1 0 1 1 0 0 +EDGE2 9356 6655 -0.954307 -0.0191978 -1.57313 1 0 1 1 0 0 +EDGE2 9356 6595 -0.93441 0.0231139 -1.58433 1 0 1 1 0 0 +EDGE2 9357 6636 -1.01069 0.0249154 -0.00207718 1 0 1 1 0 0 +EDGE2 9357 6677 -0.0292365 0.0673492 -0.00986938 1 0 1 1 0 0 +EDGE2 9357 6598 1.00302 -0.0272491 -0.0106383 1 0 1 1 0 0 +EDGE2 9357 6638 1.03177 0.0986877 -0.0108331 1 0 1 1 0 0 +EDGE2 9357 6678 1.07045 0.0460798 -0.0071102 1 0 1 1 0 0 +EDGE2 9357 9356 -0.990849 0.0290374 0.0333631 1 0 1 1 0 0 +EDGE2 9357 6597 0.0169771 -0.037908 0.022316 1 0 1 1 0 0 +EDGE2 9357 6637 -0.0458945 0.0103429 -0.0275066 1 0 1 1 0 0 +EDGE2 9357 6676 -1.0088 0.0394915 0.00644817 1 0 1 1 0 0 +EDGE2 9357 6596 -1.04308 -0.00944243 -0.00298031 1 0 1 1 0 0 +EDGE2 9358 6677 -0.980368 0.0107135 0.0125536 1 0 1 1 0 0 +EDGE2 9358 6639 1.0029 -0.0827903 -0.0156651 1 0 1 1 0 0 +EDGE2 9358 6679 1.02406 0.0572964 -0.00740991 1 0 1 1 0 0 +EDGE2 9358 6599 0.971248 0.0255933 0.0208818 1 0 1 1 0 0 +EDGE2 9358 6598 0.0782649 0.0995795 -0.037195 1 0 1 1 0 0 +EDGE2 9358 6638 -0.0153404 0.00896837 0.0200773 1 0 1 1 0 0 +EDGE2 9358 6678 0.0219092 0.0594937 0.0154244 1 0 1 1 0 0 +EDGE2 9358 9357 -0.906651 0.0149208 0.00677343 1 0 1 1 0 0 +EDGE2 9358 6597 -0.990655 -0.0221701 0.00741391 1 0 1 1 0 0 +EDGE2 9358 6637 -1.01178 -0.0549853 0.00673001 1 0 1 1 0 0 +EDGE2 9359 6680 1.05873 0.0729318 0.0165698 1 0 1 1 0 0 +EDGE2 9359 6600 0.979991 -0.0408991 -0.00932235 1 0 1 1 0 0 +EDGE2 9359 6620 1.04248 0.0698257 -3.11525 1 0 1 1 0 0 +EDGE2 9359 6640 1.07109 0.000883155 0.0261937 1 0 1 1 0 0 +EDGE2 9359 9358 -0.97109 0.06577 -0.00171072 1 0 1 1 0 0 +EDGE2 9359 6639 -0.0502827 0.00807769 0.0177375 1 0 1 1 0 0 +EDGE2 9359 6679 -0.00275484 -0.0055703 -0.0313096 1 0 1 1 0 0 +EDGE2 9359 6599 -0.0391092 -0.059767 -0.00867697 1 0 1 1 0 0 +EDGE2 9359 6598 -0.988515 0.0613354 0.0357232 1 0 1 1 0 0 +EDGE2 9359 6638 -0.975443 0.0560036 0.00477398 1 0 1 1 0 0 +EDGE2 9359 6678 -1.09001 -0.0290564 -0.0188849 1 0 1 1 0 0 +EDGE2 9360 6619 0.979321 0.0724308 -3.11458 1 0 1 1 0 0 +EDGE2 9360 6681 -0.0051781 0.994831 1.55308 1 0 1 1 0 0 +EDGE2 9360 6680 -0.0203586 -0.0902765 0.00340434 1 0 1 1 0 0 +EDGE2 9360 6601 0.00908664 -0.994496 -1.58524 1 0 1 1 0 0 +EDGE2 9360 6600 -0.120767 -0.0277619 -0.00613401 1 0 1 1 0 0 +EDGE2 9360 6620 0.00664978 -0.0872624 -3.11879 1 0 1 1 0 0 +EDGE2 9360 6640 0.040016 0.102045 0.0262693 1 0 1 1 0 0 +EDGE2 9360 6621 0.134923 1.00713 1.59705 1 0 1 1 0 0 +EDGE2 9360 6641 0.0474741 0.952437 1.57396 1 0 1 1 0 0 +EDGE2 9360 6639 -0.941912 -0.0226484 0.0150738 1 0 1 1 0 0 +EDGE2 9360 6679 -1.01392 0.0330871 0.0199046 1 0 1 1 0 0 +EDGE2 9360 9359 -0.910207 -0.0376433 -0.012575 1 0 1 1 0 0 +EDGE2 9360 6599 -0.996491 0.0344647 0.0111291 1 0 1 1 0 0 +EDGE2 9361 6681 0.0782526 0.0191947 0.0205087 1 0 1 1 0 0 +EDGE2 9361 6680 -1.07136 -0.081091 -1.57025 1 0 1 1 0 0 +EDGE2 9361 9360 -0.951058 0.0394393 -1.56343 1 0 1 1 0 0 +EDGE2 9361 6600 -0.877586 -0.055565 -1.54795 1 0 1 1 0 0 +EDGE2 9361 6620 -0.98491 0.00025672 1.55237 1 0 1 1 0 0 +EDGE2 9361 6640 -1.01121 0.0960427 -1.59923 1 0 1 1 0 0 +EDGE2 9361 6642 0.998092 -0.0848896 -0.0161553 1 0 1 1 0 0 +EDGE2 9361 6621 -0.0696152 0.0446488 -0.00519582 1 0 1 1 0 0 +EDGE2 9361 6641 0.0950647 -0.0158408 0.0152109 1 0 1 1 0 0 +EDGE2 9361 6682 0.972323 0.016651 0.0237252 1 0 1 1 0 0 +EDGE2 9361 6622 0.983395 0.041684 0.00403375 1 0 1 1 0 0 +EDGE2 9362 6643 1.0828 0.103292 0.0114827 1 0 1 1 0 0 +EDGE2 9362 6681 -1.07257 -0.0612791 0.0186141 1 0 1 1 0 0 +EDGE2 9362 9361 -0.985262 -0.0224313 -0.000527077 1 0 1 1 0 0 +EDGE2 9362 6642 0.00434675 -0.0140296 -0.012931 1 0 1 1 0 0 +EDGE2 9362 6621 -1.01712 0.0610773 -0.0554688 1 0 1 1 0 0 +EDGE2 9362 6641 -1.12393 0.0338835 0.0374511 1 0 1 1 0 0 +EDGE2 9362 6682 0.00621811 0.0161213 -0.0057296 1 0 1 1 0 0 +EDGE2 9362 6622 0.0250596 0.0241192 -0.0296854 1 0 1 1 0 0 +EDGE2 9362 6683 1.00155 0.048255 0.00176677 1 0 1 1 0 0 +EDGE2 9362 6623 0.959187 0.00457895 0.0151413 1 0 1 1 0 0 +EDGE2 9363 6643 -0.0688387 -0.00314885 -0.0123277 1 0 1 1 0 0 +EDGE2 9363 6642 -1.02915 -0.0322683 0.0120257 1 0 1 1 0 0 +EDGE2 9363 9362 -1.02245 0.00752512 -0.00300197 1 0 1 1 0 0 +EDGE2 9363 6682 -0.884834 0.0928983 -0.042574 1 0 1 1 0 0 +EDGE2 9363 6622 -0.942654 -0.0158943 0.0294686 1 0 1 1 0 0 +EDGE2 9363 6683 -0.0692949 -0.0194729 -0.0314747 1 0 1 1 0 0 +EDGE2 9363 6624 0.954964 -0.0256748 0.00359401 1 0 1 1 0 0 +EDGE2 9363 6684 0.937476 -0.0898666 0.0400762 1 0 1 1 0 0 +EDGE2 9363 6623 -0.0282595 -0.0499704 0.021993 1 0 1 1 0 0 +EDGE2 9363 6644 0.989912 -0.0154709 0.00504546 1 0 1 1 0 0 +EDGE2 9364 6643 -1.05495 -0.0668763 0.0140541 1 0 1 1 0 0 +EDGE2 9364 9363 -0.90808 -0.0699643 -0.02546 1 0 1 1 0 0 +EDGE2 9364 6683 -0.929797 -0.111497 -0.0113791 1 0 1 1 0 0 +EDGE2 9364 6624 0.00398107 -0.0411055 -0.0251691 1 0 1 1 0 0 +EDGE2 9364 6684 -0.0353307 0.0321422 0.035608 1 0 1 1 0 0 +EDGE2 9364 6623 -1.03416 -0.094619 7.09354e-05 1 0 1 1 0 0 +EDGE2 9364 6644 -0.0831981 0.0177787 0.021627 1 0 1 1 0 0 +EDGE2 9364 6645 1.02457 -0.0446707 0.000213681 1 0 1 1 0 0 +EDGE2 9364 6685 1.00958 -0.0258935 0.00816985 1 0 1 1 0 0 +EDGE2 9364 6625 0.989069 -0.00218225 -0.0138087 1 0 1 1 0 0 +EDGE2 9365 6624 -0.991463 -0.0211935 -0.00408926 1 0 1 1 0 0 +EDGE2 9365 6684 -1.03454 -0.0158498 0.00734064 1 0 1 1 0 0 +EDGE2 9365 9364 -1.03076 -0.032498 0.00690503 1 0 1 1 0 0 +EDGE2 9365 6644 -0.990491 -0.0869234 0.0364879 1 0 1 1 0 0 +EDGE2 9365 6645 0.0149551 -0.0706462 0.0378072 1 0 1 1 0 0 +EDGE2 9365 6685 0.0546331 -0.119043 -0.00594699 1 0 1 1 0 0 +EDGE2 9365 6625 0.0292052 0.00213363 -0.019711 1 0 1 1 0 0 +EDGE2 9365 6686 -0.150256 0.9888 1.59035 1 0 1 1 0 0 +EDGE2 9365 6626 0.0088299 0.931294 1.59421 1 0 1 1 0 0 +EDGE2 9365 6646 0.0717172 0.950476 1.59639 1 0 1 1 0 0 +EDGE2 9366 6645 -0.962443 0.0331063 1.60295 1 0 1 1 0 0 +EDGE2 9366 6685 -1.00704 -0.00136212 1.5725 1 0 1 1 0 0 +EDGE2 9366 9365 -1.00933 0.0503106 1.54425 1 0 1 1 0 0 +EDGE2 9366 6625 -1.01759 -0.0635822 1.58131 1 0 1 1 0 0 +EDGE2 9367 9366 -1.12827 0.0335852 0.0438799 1 0 1 1 0 0 +EDGE2 9368 9367 -1.0231 0.064968 0.027589 1 0 1 1 0 0 +EDGE2 9369 9368 -0.993781 -0.0332261 0.0324721 1 0 1 1 0 0 +EDGE2 9370 9369 -1.03533 -0.0176623 -0.0130991 1 0 1 1 0 0 +EDGE2 9371 9370 -0.986508 -0.0495943 -1.58206 1 0 1 1 0 0 +EDGE2 9372 9371 -1.00689 -0.0123561 0.0059059 1 0 1 1 0 0 +EDGE2 9373 9372 -0.980055 -0.0381904 -0.0118622 1 0 1 1 0 0 +EDGE2 9374 9373 -0.949281 -0.011181 -0.0309818 1 0 1 1 0 0 +EDGE2 9374 6755 1.04735 -0.0370591 -3.11233 1 0 1 1 0 0 +EDGE2 9375 6756 0.0800645 -1.09933 -1.57994 1 0 1 1 0 0 +EDGE2 9375 9374 -0.954053 -0.0600618 0.0186225 1 0 1 1 0 0 +EDGE2 9375 6754 1.02236 -0.0254932 -3.16047 1 0 1 1 0 0 +EDGE2 9375 6755 -0.0893331 0.072462 -3.14922 1 0 1 1 0 0 +EDGE2 9376 6757 1.11151 -0.0873186 -0.0136732 1 0 1 1 0 0 +EDGE2 9376 6756 -0.0180523 0.007149 0.0328815 1 0 1 1 0 0 +EDGE2 9376 9375 -1.14678 0.170031 1.57161 1 0 1 1 0 0 +EDGE2 9376 6755 -1.10666 0.087866 -1.59231 1 0 1 1 0 0 +EDGE2 9377 6758 1.00607 0.0014141 0.0120604 1 0 1 1 0 0 +EDGE2 9377 6757 -0.00491838 0.0621965 -4.38529e-05 1 0 1 1 0 0 +EDGE2 9377 6756 -1.04034 -0.0134706 -0.00268249 1 0 1 1 0 0 +EDGE2 9377 9376 -1.05904 -0.0278048 -0.0183582 1 0 1 1 0 0 +EDGE2 9378 6759 1.01197 0.0100967 -0.0398901 1 0 1 1 0 0 +EDGE2 9378 6758 0.0885461 0.0294479 0.00714886 1 0 1 1 0 0 +EDGE2 9378 6757 -0.917477 -0.00319998 0.0340736 1 0 1 1 0 0 +EDGE2 9378 9377 -1.08579 -0.0319046 -0.0109765 1 0 1 1 0 0 +EDGE2 9379 6760 0.993881 -0.0137442 -0.0030145 1 0 1 1 0 0 +EDGE2 9379 6759 0.0477318 -0.0231011 -0.00998349 1 0 1 1 0 0 +EDGE2 9379 6758 -1.00377 0.0900323 0.0239358 1 0 1 1 0 0 +EDGE2 9379 9378 -0.976931 -0.0466225 0.0239498 1 0 1 1 0 0 +EDGE2 9380 6761 -0.00491951 1.07118 1.55143 1 0 1 1 0 0 +EDGE2 9380 6760 -0.0241227 0.00699453 0.00715238 1 0 1 1 0 0 +EDGE2 9380 6759 -0.95795 -0.0475016 0.00713455 1 0 1 1 0 0 +EDGE2 9380 9379 -0.968489 0.00589497 0.0300286 1 0 1 1 0 0 +EDGE2 9381 9380 -1.01691 0.0450335 1.55779 1 0 1 1 0 0 +EDGE2 9381 6760 -1.04313 -0.027723 1.54117 1 0 1 1 0 0 +EDGE2 9382 9381 -1.0174 -0.0443873 0.0107948 1 0 1 1 0 0 +EDGE2 9383 9382 -1.05146 -0.00368915 -0.027228 1 0 1 1 0 0 +EDGE2 9384 9383 -1.08005 -0.0161048 -0.000915945 1 0 1 1 0 0 +EDGE2 9385 9384 -1.01435 0.0365289 0.0507406 1 0 1 1 0 0 +EDGE2 9386 9385 -1.01484 -0.00536762 1.59824 1 0 1 1 0 0 +EDGE2 9387 9386 -1.04899 -0.0379723 -0.0473792 1 0 1 1 0 0 +EDGE2 9388 9387 -1.09004 -0.0429717 -0.000294677 1 0 1 1 0 0 +EDGE2 9389 9388 -0.920127 -0.0573267 0.0119077 1 0 1 1 0 0 +EDGE2 9389 9370 1.11685 0.0460709 -3.11611 1 0 1 1 0 0 +EDGE2 9390 9389 -1.04653 -0.0446427 -0.00729011 1 0 1 1 0 0 +EDGE2 9390 9369 1.00483 -0.00345665 -3.15243 1 0 1 1 0 0 +EDGE2 9390 9370 -0.0431689 -0.0116222 -3.15424 1 0 1 1 0 0 +EDGE2 9390 9371 -0.000205804 -0.987846 -1.5621 1 0 1 1 0 0 +EDGE2 9391 9390 -1.09135 0.0219376 -1.56505 1 0 1 1 0 0 +EDGE2 9391 9370 -0.961632 -0.0183547 1.58933 1 0 1 1 0 0 +EDGE2 9392 9391 -0.960241 -0.0552817 0.00895909 1 0 1 1 0 0 +EDGE2 9393 9392 -1.0413 0.00580276 0.00369965 1 0 1 1 0 0 +EDGE2 9394 6615 1.05788 -0.0173326 -3.12463 1 0 1 1 0 0 +EDGE2 9394 9393 -0.88658 0.0174736 -0.00898982 1 0 1 1 0 0 +EDGE2 9395 6616 0.0149618 -0.999042 -1.55529 1 0 1 1 0 0 +EDGE2 9395 6614 0.99017 0.030746 -3.12192 1 0 1 1 0 0 +EDGE2 9395 6615 -0.0383274 0.0217183 -3.14573 1 0 1 1 0 0 +EDGE2 9395 9394 -0.953314 -0.0405494 0.0384693 1 0 1 1 0 0 +EDGE2 9396 6617 1.06162 0.00662881 -0.0251963 1 0 1 1 0 0 +EDGE2 9396 6616 0.0258241 -0.00972705 -0.0259646 1 0 1 1 0 0 +EDGE2 9396 9395 -0.967795 -0.0162807 1.53778 1 0 1 1 0 0 +EDGE2 9396 6615 -0.953453 -0.0315049 -1.59762 1 0 1 1 0 0 +EDGE2 9397 6617 -0.061204 -0.000636901 -0.00568304 1 0 1 1 0 0 +EDGE2 9397 6616 -1.08346 -0.0128955 -0.0220843 1 0 1 1 0 0 +EDGE2 9397 9396 -0.941527 0.0621818 0.00588333 1 0 1 1 0 0 +EDGE2 9397 6618 1.09422 -0.0501741 -0.0219659 1 0 1 1 0 0 +EDGE2 9398 6617 -1.09837 0.00205046 0.00358059 1 0 1 1 0 0 +EDGE2 9398 9397 -1.0763 0.0445729 -0.003966 1 0 1 1 0 0 +EDGE2 9398 6618 -0.0475977 -0.0470167 -0.017063 1 0 1 1 0 0 +EDGE2 9398 6619 0.970463 -0.137793 0.00243308 1 0 1 1 0 0 +EDGE2 9399 6618 -1.04507 -0.0200765 0.00383054 1 0 1 1 0 0 +EDGE2 9399 9398 -1.05818 0.00722547 -0.00610093 1 0 1 1 0 0 +EDGE2 9399 6619 0.013043 0.0594466 0.0124639 1 0 1 1 0 0 +EDGE2 9399 6680 0.986999 0.0276382 -3.15402 1 0 1 1 0 0 +EDGE2 9399 9360 1.09062 0.0363229 -3.13204 1 0 1 1 0 0 +EDGE2 9399 6600 0.90143 -0.0351223 -3.15193 1 0 1 1 0 0 +EDGE2 9399 6620 1.06795 0.00386441 0.00824821 1 0 1 1 0 0 +EDGE2 9399 6640 0.995572 0.0181425 -3.15726 1 0 1 1 0 0 +EDGE2 9400 9399 -1.00955 -0.0528886 0.0212548 1 0 1 1 0 0 +EDGE2 9400 6619 -1.01701 -0.0375743 -0.014213 1 0 1 1 0 0 +EDGE2 9400 6681 0.0309887 -0.996043 -1.61105 1 0 1 1 0 0 +EDGE2 9400 6680 0.0350693 0.0694896 -3.13714 1 0 1 1 0 0 +EDGE2 9400 6601 -0.0149287 1.06392 1.57297 1 0 1 1 0 0 +EDGE2 9400 9360 -0.00396564 -0.0312133 -3.16801 1 0 1 1 0 0 +EDGE2 9400 6600 -0.0153388 -0.0590192 -3.122 1 0 1 1 0 0 +EDGE2 9400 6620 -0.0562654 -0.0285198 0.0120626 1 0 1 1 0 0 +EDGE2 9400 6640 0.0221011 0.0338387 -3.1634 1 0 1 1 0 0 +EDGE2 9400 9361 -0.0884781 -0.979674 -1.57049 1 0 1 1 0 0 +EDGE2 9400 6621 -0.108967 -1.01628 -1.5953 1 0 1 1 0 0 +EDGE2 9400 6641 0.025432 -0.963417 -1.56173 1 0 1 1 0 0 +EDGE2 9400 6639 1.07708 -0.0365036 -3.14508 1 0 1 1 0 0 +EDGE2 9400 6679 0.904394 -0.0148512 -3.12458 1 0 1 1 0 0 +EDGE2 9400 9359 1.05715 -0.0373851 -3.15947 1 0 1 1 0 0 +EDGE2 9400 6599 0.964627 -0.0137335 -3.15856 1 0 1 1 0 0 +EDGE2 9401 6602 0.915688 -0.0333308 0.00316378 1 0 1 1 0 0 +EDGE2 9401 6680 -0.927522 -0.0505403 1.56746 1 0 1 1 0 0 +EDGE2 9401 9400 -0.995991 -0.0585656 -1.56757 1 0 1 1 0 0 +EDGE2 9401 6601 0.0859319 0.0097124 0.0241321 1 0 1 1 0 0 +EDGE2 9401 9360 -0.929027 -0.140439 1.54776 1 0 1 1 0 0 +EDGE2 9401 6600 -0.956642 -0.0284419 1.54716 1 0 1 1 0 0 +EDGE2 9401 6620 -1.00009 0.0395035 -1.60482 1 0 1 1 0 0 +EDGE2 9401 6640 -1.03998 0.00147599 1.58269 1 0 1 1 0 0 +EDGE2 9402 6602 -0.0422966 0.00592313 0.00565778 1 0 1 1 0 0 +EDGE2 9402 6603 1.00999 -0.0628975 0.0107807 1 0 1 1 0 0 +EDGE2 9402 6601 -1.07942 0.102536 -0.0202277 1 0 1 1 0 0 +EDGE2 9402 9401 -0.975863 -0.00188036 0.000469135 1 0 1 1 0 0 +EDGE2 9403 6602 -0.976186 0.153758 -0.0127985 1 0 1 1 0 0 +EDGE2 9403 6604 1.03478 -0.00782891 0.0299272 1 0 1 1 0 0 +EDGE2 9403 6603 -0.0378878 0.0902239 0.0221862 1 0 1 1 0 0 +EDGE2 9403 9402 -0.992409 -0.0134212 -0.0239732 1 0 1 1 0 0 +EDGE2 9404 9403 -1.07699 0.0156617 0.00157628 1 0 1 1 0 0 +EDGE2 9404 6605 1.0341 -0.0242984 0.0287752 1 0 1 1 0 0 +EDGE2 9404 8065 1.0097 -0.00949714 -3.12317 1 0 1 1 0 0 +EDGE2 9404 6604 0.0146292 -0.0516593 -0.00337333 1 0 1 1 0 0 +EDGE2 9404 6603 -0.972391 -0.0215472 0.00386554 1 0 1 1 0 0 +EDGE2 9405 8064 1.0378 0.0830862 -3.13436 1 0 1 1 0 0 +EDGE2 9405 6606 -0.0402096 1.02335 1.54674 1 0 1 1 0 0 +EDGE2 9405 9404 -0.944703 0.0912081 0.00403874 1 0 1 1 0 0 +EDGE2 9405 6605 -0.0244964 0.0633205 -0.0122094 1 0 1 1 0 0 +EDGE2 9405 8065 -0.0112776 -0.0855038 -3.14096 1 0 1 1 0 0 +EDGE2 9405 6604 -0.952783 0.0610002 0.00625464 1 0 1 1 0 0 +EDGE2 9405 8066 0.0142339 -1.02991 -1.58863 1 0 1 1 0 0 +EDGE2 9406 9405 -1.02956 -0.0646842 -1.59864 1 0 1 1 0 0 +EDGE2 9406 6607 0.993177 0.025116 0.00774212 1 0 1 1 0 0 +EDGE2 9406 6606 -0.0162735 0.051931 -0.0332726 1 0 1 1 0 0 +EDGE2 9406 6605 -0.97499 -0.00961772 -1.55952 1 0 1 1 0 0 +EDGE2 9406 8065 -1.00303 -0.00425892 1.56394 1 0 1 1 0 0 +EDGE2 9407 6608 1.02027 0.0516548 0.0301141 1 0 1 1 0 0 +EDGE2 9407 9406 -0.932404 -0.0499039 -0.00323425 1 0 1 1 0 0 +EDGE2 9407 6607 0.0632615 -0.0898236 -0.0209242 1 0 1 1 0 0 +EDGE2 9407 6606 -1.03623 0.0143796 -0.0260972 1 0 1 1 0 0 +EDGE2 9408 6609 1.01685 -0.0323447 0.00974279 1 0 1 1 0 0 +EDGE2 9408 6608 0.00141699 -0.0163126 -0.00566312 1 0 1 1 0 0 +EDGE2 9408 6607 -0.919767 0.0448286 -0.0155694 1 0 1 1 0 0 +EDGE2 9408 9407 -0.980466 -0.0485776 -0.0118307 1 0 1 1 0 0 +EDGE2 9409 6610 1.04626 0.0906422 -0.00612803 1 0 1 1 0 0 +EDGE2 9409 7210 0.981222 -0.0215126 -3.12115 1 0 1 1 0 0 +EDGE2 9409 9408 -1.06985 0.0407607 -0.0155262 1 0 1 1 0 0 +EDGE2 9409 6609 0.0658536 0.0109663 -0.00643635 1 0 1 1 0 0 +EDGE2 9409 6608 -0.949501 -0.0148548 -0.0372358 1 0 1 1 0 0 +EDGE2 9410 7209 1.02758 0.0427344 -3.14896 1 0 1 1 0 0 +EDGE2 9410 7211 -0.0407849 -0.96142 -1.5624 1 0 1 1 0 0 +EDGE2 9410 6610 0.00400101 -0.00664181 -0.00813996 1 0 1 1 0 0 +EDGE2 9410 7210 0.0263288 -0.0113097 -3.17879 1 0 1 1 0 0 +EDGE2 9410 6611 0.0304242 0.920204 1.52887 1 0 1 1 0 0 +EDGE2 9410 9409 -1.06492 -0.0361268 -0.0327029 1 0 1 1 0 0 +EDGE2 9410 6609 -1.06244 0.0176098 0.0139496 1 0 1 1 0 0 +EDGE2 9411 7211 0.046647 -0.0212514 0.00158732 1 0 1 1 0 0 +EDGE2 9411 7212 1.02048 -0.0577136 -0.00706627 1 0 1 1 0 0 +EDGE2 9411 6610 -0.962695 0.0141725 1.5815 1 0 1 1 0 0 +EDGE2 9411 7210 -1.05207 0.00543565 -1.58264 1 0 1 1 0 0 +EDGE2 9411 9410 -0.958057 -0.00346764 1.53762 1 0 1 1 0 0 +EDGE2 9412 7211 -0.991998 0.0084125 0.000504798 1 0 1 1 0 0 +EDGE2 9412 7212 0.084127 -0.00749077 -0.0225721 1 0 1 1 0 0 +EDGE2 9412 7213 0.968928 0.0210075 -0.055335 1 0 1 1 0 0 +EDGE2 9412 9411 -0.955879 -0.0716064 0.0100305 1 0 1 1 0 0 +EDGE2 9413 7214 0.982584 -0.0187927 -0.0235357 1 0 1 1 0 0 +EDGE2 9413 7212 -0.969826 -0.0218194 0.0188806 1 0 1 1 0 0 +EDGE2 9413 9412 -0.95417 -0.0606613 0.0101119 1 0 1 1 0 0 +EDGE2 9413 7213 0.000967809 0.0437739 -0.0289167 1 0 1 1 0 0 +EDGE2 9414 9413 -0.989425 0.108464 0.0125406 1 0 1 1 0 0 +EDGE2 9414 7215 0.98666 0.0643802 0.00623146 1 0 1 1 0 0 +EDGE2 9414 7735 0.96707 -0.063476 -3.13841 1 0 1 1 0 0 +EDGE2 9414 7214 0.0686197 -0.0258918 0.00735259 1 0 1 1 0 0 +EDGE2 9414 7213 -0.96805 -0.00454629 -8.62874e-05 1 0 1 1 0 0 +EDGE2 9415 7736 0.00625551 0.955785 1.59416 1 0 1 1 0 0 +EDGE2 9415 7216 -0.0135028 1.01593 1.58593 1 0 1 1 0 0 +EDGE2 9415 7215 0.0470637 0.0806364 -0.00514063 1 0 1 1 0 0 +EDGE2 9415 7734 0.958028 0.0320472 -3.16168 1 0 1 1 0 0 +EDGE2 9415 7735 -0.0639762 0.000412988 -3.14748 1 0 1 1 0 0 +EDGE2 9415 7214 -0.992581 -0.0188993 -0.00433723 1 0 1 1 0 0 +EDGE2 9415 9414 -1.01641 -0.0676586 -0.0150505 1 0 1 1 0 0 +EDGE2 9416 7217 0.974287 0.0787891 0.0146763 1 0 1 1 0 0 +EDGE2 9416 7737 1.09272 -0.0821415 -0.0109347 1 0 1 1 0 0 +EDGE2 9416 7736 0.0573587 -0.00719036 -0.0125953 1 0 1 1 0 0 +EDGE2 9416 7216 0.00952935 -0.0274966 0.00396739 1 0 1 1 0 0 +EDGE2 9416 7215 -0.954838 -0.0457691 -1.55666 1 0 1 1 0 0 +EDGE2 9416 9415 -0.962886 -0.0112668 -1.53463 1 0 1 1 0 0 +EDGE2 9416 7735 -0.974831 0.0710391 1.57027 1 0 1 1 0 0 +EDGE2 9417 7217 0.0558203 0.0385346 0.0370692 1 0 1 1 0 0 +EDGE2 9417 7738 1.07316 -0.0205953 0.000994716 1 0 1 1 0 0 +EDGE2 9417 7737 -0.035077 -0.0447188 -0.00297371 1 0 1 1 0 0 +EDGE2 9417 7218 0.978503 -0.0380572 0.0291116 1 0 1 1 0 0 +EDGE2 9417 7736 -1.02914 -0.098551 -0.011196 1 0 1 1 0 0 +EDGE2 9417 9416 -0.874973 0.000111162 -0.0194902 1 0 1 1 0 0 +EDGE2 9417 7216 -1.05888 -0.00202226 0.0128052 1 0 1 1 0 0 +EDGE2 9418 7217 -0.982533 0.0168688 -0.0120597 1 0 1 1 0 0 +EDGE2 9418 7738 -0.034799 0.00955038 -0.0120506 1 0 1 1 0 0 +EDGE2 9418 7219 1.00916 0.0151961 -0.00207681 1 0 1 1 0 0 +EDGE2 9418 7739 1.00224 0.0433133 -0.0353258 1 0 1 1 0 0 +EDGE2 9418 7737 -1.06256 0.0406367 0.0186421 1 0 1 1 0 0 +EDGE2 9418 9417 -1.08106 0.036666 0.00880793 1 0 1 1 0 0 +EDGE2 9418 7218 0.0667443 0.00899888 0.0323494 1 0 1 1 0 0 +EDGE2 9419 7740 1.04088 0.00232174 0.0195757 1 0 1 1 0 0 +EDGE2 9419 7200 1.01992 -0.0352155 -3.13265 1 0 1 1 0 0 +EDGE2 9419 7220 0.985999 0.00866622 0.0341201 1 0 1 1 0 0 +EDGE2 9419 7738 -1.06946 -0.0554679 0.00863589 1 0 1 1 0 0 +EDGE2 9419 7219 0.0215957 0.0222448 -0.0186139 1 0 1 1 0 0 +EDGE2 9419 7739 -0.0346879 -0.0666245 0.0252204 1 0 1 1 0 0 +EDGE2 9419 9418 -1.0141 -0.00635427 -0.00241117 1 0 1 1 0 0 +EDGE2 9419 7218 -1.00798 -0.0294231 -0.00460374 1 0 1 1 0 0 +EDGE2 9420 7199 1.0946 0.0234261 -3.13356 1 0 1 1 0 0 +EDGE2 9420 7201 0.0318436 1.03104 1.5742 1 0 1 1 0 0 +EDGE2 9420 7740 -0.04041 0.0582214 0.0373295 1 0 1 1 0 0 +EDGE2 9420 7741 0.0859328 1.09202 1.57251 1 0 1 1 0 0 +EDGE2 9420 7200 0.0259557 -0.00614824 -3.13967 1 0 1 1 0 0 +EDGE2 9420 7220 -0.0460532 0.0557496 -0.00515765 1 0 1 1 0 0 +EDGE2 9420 7221 0.0637204 0.959738 1.59734 1 0 1 1 0 0 +EDGE2 9420 7219 -0.976412 -0.0831558 -0.00156553 1 0 1 1 0 0 +EDGE2 9420 7739 -1.00147 -0.00550254 -0.00226301 1 0 1 1 0 0 +EDGE2 9420 9419 -0.962905 0.0682424 -0.0156947 1 0 1 1 0 0 +EDGE2 9421 7740 -0.979056 0.0188812 1.58125 1 0 1 1 0 0 +EDGE2 9421 9420 -1.0283 -0.0490964 1.55599 1 0 1 1 0 0 +EDGE2 9421 7200 -0.976472 0.0127196 -1.56549 1 0 1 1 0 0 +EDGE2 9421 7220 -1.04584 0.0666365 1.54847 1 0 1 1 0 0 +EDGE2 9422 9421 -1.0149 0.0263977 0.0258779 1 0 1 1 0 0 +EDGE2 9423 9422 -1.02304 -0.0400057 0.0123242 1 0 1 1 0 0 +EDGE2 9424 7625 0.891234 0.0427307 -3.16648 1 0 1 1 0 0 +EDGE2 9424 7605 1.01579 0.0077055 -3.13343 1 0 1 1 0 0 +EDGE2 9424 9423 -0.961904 -0.0701639 -0.00359152 1 0 1 1 0 0 +EDGE2 9425 7625 0.0468578 0.0364681 -3.14088 1 0 1 1 0 0 +EDGE2 9425 7624 0.958601 0.000759589 -3.09938 1 0 1 1 0 0 +EDGE2 9425 7604 0.933612 0.0117721 -3.14294 1 0 1 1 0 0 +EDGE2 9425 7626 -0.0813177 1.02137 1.55686 1 0 1 1 0 0 +EDGE2 9425 7606 0.0213783 -0.937742 -1.55985 1 0 1 1 0 0 +EDGE2 9425 7605 0.0102605 -0.0672616 -3.16577 1 0 1 1 0 0 +EDGE2 9425 9424 -0.947094 -0.0150148 -0.0186574 1 0 1 1 0 0 +EDGE2 9426 7625 -1.01765 0.00943959 1.56923 1 0 1 1 0 0 +EDGE2 9426 7627 1.01556 0.0156229 0.013128 1 0 1 1 0 0 +EDGE2 9426 7626 0.112861 0.0123337 -0.00269944 1 0 1 1 0 0 +EDGE2 9426 9425 -1.0548 -0.00987523 -1.60959 1 0 1 1 0 0 +EDGE2 9426 7605 -0.918579 -0.0359843 1.58507 1 0 1 1 0 0 +EDGE2 9427 7627 4.46914e-05 0.0169358 0.037306 1 0 1 1 0 0 +EDGE2 9427 7628 0.992571 0.028104 0.0315931 1 0 1 1 0 0 +EDGE2 9427 7626 -0.974825 0.0370842 0.00811854 1 0 1 1 0 0 +EDGE2 9427 9426 -0.935707 0.0110354 0.0161298 1 0 1 1 0 0 +EDGE2 9428 7627 -1.06202 0.0402319 0.00272101 1 0 1 1 0 0 +EDGE2 9428 7628 0.0328377 0.0972507 -0.00900547 1 0 1 1 0 0 +EDGE2 9428 7629 1.01551 0.0554491 0.0177015 1 0 1 1 0 0 +EDGE2 9428 9427 -1.07106 0.0595284 -0.0065375 1 0 1 1 0 0 +EDGE2 9429 7370 0.97269 -0.026802 -3.18767 1 0 1 1 0 0 +EDGE2 9429 7630 1.00901 0.0482741 0.0324757 1 0 1 1 0 0 +EDGE2 9429 7190 1.02446 0.0219595 -3.11669 1 0 1 1 0 0 +EDGE2 9429 7628 -0.961958 -0.0661662 0.0285742 1 0 1 1 0 0 +EDGE2 9429 9428 -0.983944 0.0283728 -0.0219183 1 0 1 1 0 0 +EDGE2 9429 7629 -0.0266325 0.0898237 -0.0246525 1 0 1 1 0 0 +EDGE2 9430 7369 1.0012 -0.0243354 -3.16875 1 0 1 1 0 0 +EDGE2 9430 7189 1.06168 -0.0584826 -3.13729 1 0 1 1 0 0 +EDGE2 9430 7370 0.0533214 -0.0343834 -3.16709 1 0 1 1 0 0 +EDGE2 9430 7631 -0.0759119 -1.01945 -1.57079 1 0 1 1 0 0 +EDGE2 9430 7371 0.0231831 -1.07385 -1.56958 1 0 1 1 0 0 +EDGE2 9430 7630 0.0333894 0.0793822 0.0176822 1 0 1 1 0 0 +EDGE2 9430 9429 -0.998581 0.0406682 -0.00961042 1 0 1 1 0 0 +EDGE2 9430 7190 0.02983 -0.0538208 -3.16243 1 0 1 1 0 0 +EDGE2 9430 7629 -0.957512 -0.0908784 0.0186205 1 0 1 1 0 0 +EDGE2 9430 7191 0.00290229 1.00461 1.56953 1 0 1 1 0 0 +EDGE2 9431 7370 -1.14818 -0.062171 -1.57687 1 0 1 1 0 0 +EDGE2 9431 7631 -0.034075 -0.0323799 -0.0346107 1 0 1 1 0 0 +EDGE2 9431 7372 1.00673 0.0447643 0.0165995 1 0 1 1 0 0 +EDGE2 9431 7632 0.936838 0.0588529 -0.0154014 1 0 1 1 0 0 +EDGE2 9431 9430 -1.01632 0.0557557 1.56335 1 0 1 1 0 0 +EDGE2 9431 7371 -0.0673218 0.0629351 -0.0127106 1 0 1 1 0 0 +EDGE2 9431 7630 -1.03868 -0.0399703 1.60154 1 0 1 1 0 0 +EDGE2 9431 7190 -1.04888 -0.0525612 -1.56061 1 0 1 1 0 0 +EDGE2 9432 7373 0.96349 0.058351 -0.0128519 1 0 1 1 0 0 +EDGE2 9432 7633 1.01964 0.125307 0.0076933 1 0 1 1 0 0 +EDGE2 9432 7631 -0.960984 -0.0217277 0.0174584 1 0 1 1 0 0 +EDGE2 9432 7372 0.00287167 -0.0396852 -0.0123903 1 0 1 1 0 0 +EDGE2 9432 7632 -0.0100933 -0.0558338 0.0173022 1 0 1 1 0 0 +EDGE2 9432 9431 -0.993024 0.0413621 -0.0396896 1 0 1 1 0 0 +EDGE2 9432 7371 -1.08269 0.00928119 0.00976428 1 0 1 1 0 0 +EDGE2 9433 9432 -0.892063 0.059663 -0.00467888 1 0 1 1 0 0 +EDGE2 9433 7634 1.02135 0.0406607 -0.0553142 1 0 1 1 0 0 +EDGE2 9433 7374 0.986333 -0.099834 -0.0173025 1 0 1 1 0 0 +EDGE2 9433 7373 0.0367546 0.0483221 -0.009669 1 0 1 1 0 0 +EDGE2 9433 7633 -0.0277883 -0.0564285 -0.0217299 1 0 1 1 0 0 +EDGE2 9433 7372 -0.986997 -0.0138125 -0.0031705 1 0 1 1 0 0 +EDGE2 9433 7632 -0.959136 0.0814248 0.0244323 1 0 1 1 0 0 +EDGE2 9434 7975 0.998753 0.0301578 -3.15154 1 0 1 1 0 0 +EDGE2 9434 7375 1.07286 -0.00630468 0.00114725 1 0 1 1 0 0 +EDGE2 9434 7595 1.03582 0.0927781 -3.18892 1 0 1 1 0 0 +EDGE2 9434 7635 0.957515 0.020084 -0.0220044 1 0 1 1 0 0 +EDGE2 9434 7634 0.0366583 -0.0108848 0.00208638 1 0 1 1 0 0 +EDGE2 9434 7374 -0.00670032 -0.139759 -0.0074849 1 0 1 1 0 0 +EDGE2 9434 7373 -0.952407 0.00694796 0.0300527 1 0 1 1 0 0 +EDGE2 9434 7633 -1.00802 -0.0519555 -0.00269742 1 0 1 1 0 0 +EDGE2 9434 9433 -0.979739 0.0112776 0.0129655 1 0 1 1 0 0 +EDGE2 9435 7975 0.0703996 0.0498387 -3.15322 1 0 1 1 0 0 +EDGE2 9435 7974 1.00471 -0.0172313 -3.10302 1 0 1 1 0 0 +EDGE2 9435 7594 0.951227 0.0426899 -3.15942 1 0 1 1 0 0 +EDGE2 9435 7376 0.00956715 0.903214 1.55399 1 0 1 1 0 0 +EDGE2 9435 7596 -0.0379318 -0.954092 -1.5955 1 0 1 1 0 0 +EDGE2 9435 7636 0.0354261 -0.98802 -1.57871 1 0 1 1 0 0 +EDGE2 9435 7375 0.0269236 -0.0102424 0.0134686 1 0 1 1 0 0 +EDGE2 9435 7595 0.0923314 0.0645503 -3.14393 1 0 1 1 0 0 +EDGE2 9435 7635 -0.0747272 0.0480243 0.0395612 1 0 1 1 0 0 +EDGE2 9435 7976 -0.0618955 -0.968196 -1.55646 1 0 1 1 0 0 +EDGE2 9435 7634 -0.979155 -0.0192056 -0.0216004 1 0 1 1 0 0 +EDGE2 9435 9434 -1.00361 0.110964 0.0264141 1 0 1 1 0 0 +EDGE2 9435 7374 -1.03302 -0.0635621 0.00881693 1 0 1 1 0 0 +EDGE2 9436 7975 -0.997717 0.0267118 1.58575 1 0 1 1 0 0 +EDGE2 9436 7377 1.08225 -0.0245802 0.00593653 1 0 1 1 0 0 +EDGE2 9436 7376 -0.0132373 -0.0294773 0.0237905 1 0 1 1 0 0 +EDGE2 9436 9435 -0.993422 -0.0143243 -1.5822 1 0 1 1 0 0 +EDGE2 9436 7375 -1.01962 -0.0285612 -1.58956 1 0 1 1 0 0 +EDGE2 9436 7595 -1.00525 -0.0354936 1.60119 1 0 1 1 0 0 +EDGE2 9436 7635 -0.984241 0.0174401 -1.5675 1 0 1 1 0 0 +EDGE2 9437 7378 1.01606 0.0358973 0.0201168 1 0 1 1 0 0 +EDGE2 9437 7377 -0.106045 0.0906282 -0.0195153 1 0 1 1 0 0 +EDGE2 9437 7376 -0.984179 -0.0694127 -0.0252063 1 0 1 1 0 0 +EDGE2 9437 9436 -1.09183 -0.0411297 -0.0273434 1 0 1 1 0 0 +EDGE2 9438 7379 0.997702 0.0158538 0.0155118 1 0 1 1 0 0 +EDGE2 9438 9437 -1.04022 0.0313842 -0.00685951 1 0 1 1 0 0 +EDGE2 9438 7378 -0.111919 0.0653236 0.0150388 1 0 1 1 0 0 +EDGE2 9438 7377 -0.921182 0.00135157 -0.000228955 1 0 1 1 0 0 +EDGE2 9439 7520 0.961366 0.00724132 -3.1031 1 0 1 1 0 0 +EDGE2 9439 7540 1.02121 -0.0566763 -3.1215 1 0 1 1 0 0 +EDGE2 9439 7580 1.04516 -0.0357538 -3.14021 1 0 1 1 0 0 +EDGE2 9439 7940 1.08287 0.0472975 -3.15081 1 0 1 1 0 0 +EDGE2 9439 7960 0.941837 0.000556924 -3.16687 1 0 1 1 0 0 +EDGE2 9439 7560 1.01951 0.0442103 -3.16413 1 0 1 1 0 0 +EDGE2 9439 7380 0.956593 -0.0387644 -0.00623876 1 0 1 1 0 0 +EDGE2 9439 7460 0.918596 -0.0495882 -3.14311 1 0 1 1 0 0 +EDGE2 9439 9438 -0.974483 0.0971363 -0.00298022 1 0 1 1 0 0 +EDGE2 9439 7379 -0.0199233 0.0421854 -0.0294834 1 0 1 1 0 0 +EDGE2 9439 7378 -1.0006 0.00148137 0.0049871 1 0 1 1 0 0 +EDGE2 9440 7520 -0.0181588 0.00112692 -3.11234 1 0 1 1 0 0 +EDGE2 9440 7539 1.06273 -0.0557677 -3.10586 1 0 1 1 0 0 +EDGE2 9440 7579 0.981287 -0.0345662 -3.1338 1 0 1 1 0 0 +EDGE2 9440 7939 1.02418 0.00981373 -3.12286 1 0 1 1 0 0 +EDGE2 9440 7959 1.0089 0.0500915 -3.15407 1 0 1 1 0 0 +EDGE2 9440 7559 0.98856 0.0370748 -3.13023 1 0 1 1 0 0 +EDGE2 9440 7459 1.02213 0.0594794 -3.11957 1 0 1 1 0 0 +EDGE2 9440 7519 0.916645 -0.0599742 -3.11522 1 0 1 1 0 0 +EDGE2 9440 7540 -0.161499 0.083817 -3.16752 1 0 1 1 0 0 +EDGE2 9440 7561 0.045827 -0.973525 -1.5684 1 0 1 1 0 0 +EDGE2 9440 7961 0.00614892 -0.981588 -1.55566 1 0 1 1 0 0 +EDGE2 9440 7581 -0.0456881 -0.960722 -1.56846 1 0 1 1 0 0 +EDGE2 9440 7381 -0.0301123 -0.952923 -1.588 1 0 1 1 0 0 +EDGE2 9440 7461 0.0420553 -0.972812 -1.56847 1 0 1 1 0 0 +EDGE2 9440 7541 0.0916549 -0.940076 -1.57299 1 0 1 1 0 0 +EDGE2 9440 7580 -0.0288619 0.0158553 -3.15982 1 0 1 1 0 0 +EDGE2 9440 7940 0.0724589 0.0561181 -3.15376 1 0 1 1 0 0 +EDGE2 9440 7960 0.152723 -0.0872398 -3.15321 1 0 1 1 0 0 +EDGE2 9440 7560 0.0531482 0.0339922 -3.14814 1 0 1 1 0 0 +EDGE2 9440 7941 -0.020319 1.00379 1.54573 1 0 1 1 0 0 +EDGE2 9440 7380 0.0111953 0.0105361 0.0018039 1 0 1 1 0 0 +EDGE2 9440 7460 -0.0528679 -0.0325608 -3.16526 1 0 1 1 0 0 +EDGE2 9440 7521 0.023884 1.00872 1.62293 1 0 1 1 0 0 +EDGE2 9440 7379 -1.01141 -0.0335481 -0.0319101 1 0 1 1 0 0 +EDGE2 9440 9439 -1.04324 0.0986371 0.00597594 1 0 1 1 0 0 +EDGE2 9441 7520 -0.99437 0.0563552 1.58509 1 0 1 1 0 0 +EDGE2 9441 7540 -1.0391 -0.00748751 1.58841 1 0 1 1 0 0 +EDGE2 9441 9440 -1.03371 -0.0394618 -1.58196 1 0 1 1 0 0 +EDGE2 9441 7580 -1.04706 -0.00831249 1.58288 1 0 1 1 0 0 +EDGE2 9441 7940 -0.963266 -0.158847 1.57116 1 0 1 1 0 0 +EDGE2 9441 7960 -1.02165 0.0874154 1.57603 1 0 1 1 0 0 +EDGE2 9441 7560 -1.03442 0.0386728 1.53266 1 0 1 1 0 0 +EDGE2 9441 7522 1.06376 -0.0409151 0.00313728 1 0 1 1 0 0 +EDGE2 9441 7941 -0.000162779 -0.0632362 -0.0179983 1 0 1 1 0 0 +EDGE2 9441 7380 -1.03109 0.0508338 -1.54751 1 0 1 1 0 0 +EDGE2 9441 7460 -1.04862 0.0492988 1.56873 1 0 1 1 0 0 +EDGE2 9441 7521 0.0270803 -0.0507945 -0.023187 1 0 1 1 0 0 +EDGE2 9441 7942 1.04784 0.0334015 0.0114468 1 0 1 1 0 0 +EDGE2 9442 7522 0.047421 -0.0609768 -0.00876233 1 0 1 1 0 0 +EDGE2 9442 7941 -1.03141 -0.00728987 -0.0224691 1 0 1 1 0 0 +EDGE2 9442 9441 -0.978511 0.0657783 0.0460028 1 0 1 1 0 0 +EDGE2 9442 7521 -0.906569 0.0553248 0.0305035 1 0 1 1 0 0 +EDGE2 9442 7942 0.00848517 -0.0600189 0.0335803 1 0 1 1 0 0 +EDGE2 9442 7943 1.04427 0.063225 -0.0313409 1 0 1 1 0 0 +EDGE2 9442 7523 0.900602 0.0415183 -0.0169685 1 0 1 1 0 0 +EDGE2 9443 7944 0.989239 -0.017032 -0.0189371 1 0 1 1 0 0 +EDGE2 9443 7522 -1.03562 0.0575463 0.000982297 1 0 1 1 0 0 +EDGE2 9443 9442 -0.955118 0.0117369 -0.00447554 1 0 1 1 0 0 +EDGE2 9443 7942 -1.01293 0.0038462 -0.00591774 1 0 1 1 0 0 +EDGE2 9443 7943 -0.0299593 -0.0543203 -0.0190774 1 0 1 1 0 0 +EDGE2 9443 7523 0.0318035 -0.0258985 -0.015142 1 0 1 1 0 0 +EDGE2 9443 7524 0.959187 0.0348054 -0.00314564 1 0 1 1 0 0 +EDGE2 9444 7944 0.0835928 0.0400959 -0.0214657 1 0 1 1 0 0 +EDGE2 9444 7943 -1.04511 -0.0343023 -0.00560748 1 0 1 1 0 0 +EDGE2 9444 9443 -1.09467 -1.66384e-05 -0.0320984 1 0 1 1 0 0 +EDGE2 9444 7523 -1.06677 0.0426535 0.021387 1 0 1 1 0 0 +EDGE2 9444 7525 0.995835 -0.0572928 -0.00180846 1 0 1 1 0 0 +EDGE2 9444 7925 1.0911 0.0373839 -3.12277 1 0 1 1 0 0 +EDGE2 9444 7524 0.0604495 -0.0379258 0.0227115 1 0 1 1 0 0 +EDGE2 9444 7945 1.04142 0.0141605 -0.0100489 1 0 1 1 0 0 +EDGE2 9444 7285 1.07833 -0.0220025 -3.14697 1 0 1 1 0 0 +EDGE2 9444 7325 0.99359 -0.0475618 -3.11968 1 0 1 1 0 0 +EDGE2 9444 7345 1.03165 0.0466589 -3.14323 1 0 1 1 0 0 +EDGE2 9444 7365 1.02948 -0.0240291 -3.13838 1 0 1 1 0 0 +EDGE2 9444 7305 0.982115 -0.0506877 -3.12511 1 0 1 1 0 0 +EDGE2 9444 7185 1.06204 0.0255881 -3.15837 1 0 1 1 0 0 +EDGE2 9445 7944 -1.00941 0.0275292 0.00829839 1 0 1 1 0 0 +EDGE2 9445 7326 0.0427498 -1.02264 -1.5885 1 0 1 1 0 0 +EDGE2 9445 7526 -0.00880691 -0.951332 -1.55552 1 0 1 1 0 0 +EDGE2 9445 7926 0.0390596 -1.02909 -1.5785 1 0 1 1 0 0 +EDGE2 9445 7946 -0.0256168 -0.974634 -1.56692 1 0 1 1 0 0 +EDGE2 9445 7346 -0.0313439 -1.00116 -1.62176 1 0 1 1 0 0 +EDGE2 9445 7286 0.00337759 -1.09294 -1.56895 1 0 1 1 0 0 +EDGE2 9445 7306 -0.0117655 -0.978274 -1.54863 1 0 1 1 0 0 +EDGE2 9445 9444 -1.05044 -0.0259193 -0.000442111 1 0 1 1 0 0 +EDGE2 9445 7525 0.103262 0.0134552 -0.00466741 1 0 1 1 0 0 +EDGE2 9445 7925 -0.0413762 -0.00249668 -3.1363 1 0 1 1 0 0 +EDGE2 9445 7524 -0.931578 0.0328487 -0.00155265 1 0 1 1 0 0 +EDGE2 9445 7945 0.0551429 -0.078938 -0.00931495 1 0 1 1 0 0 +EDGE2 9445 7285 0.0180155 -0.033651 -3.15827 1 0 1 1 0 0 +EDGE2 9445 7325 -0.00571114 -0.00589618 -3.14531 1 0 1 1 0 0 +EDGE2 9445 7345 0.00416888 0.0262462 -3.18653 1 0 1 1 0 0 +EDGE2 9445 7365 -0.0785298 -0.0359414 -3.11644 1 0 1 1 0 0 +EDGE2 9445 7305 -0.0206458 0.0231253 -3.14468 1 0 1 1 0 0 +EDGE2 9445 7366 0.0491356 0.97776 1.55462 1 0 1 1 0 0 +EDGE2 9445 7185 0.0169328 0.0159916 -3.15468 1 0 1 1 0 0 +EDGE2 9445 7186 -0.00482195 1.02432 1.57865 1 0 1 1 0 0 +EDGE2 9445 7304 0.969884 -0.0384156 -3.14544 1 0 1 1 0 0 +EDGE2 9445 7344 0.898841 -0.0961986 -3.15258 1 0 1 1 0 0 +EDGE2 9445 7364 1.08184 -0.0157191 -3.12733 1 0 1 1 0 0 +EDGE2 9445 7924 0.902687 -0.0151953 -3.15137 1 0 1 1 0 0 +EDGE2 9445 7324 0.971699 -0.0252363 -3.16328 1 0 1 1 0 0 +EDGE2 9445 7184 1.02864 0.00221795 -3.14665 1 0 1 1 0 0 +EDGE2 9445 7284 0.917704 0.0156729 -3.12073 1 0 1 1 0 0 +EDGE2 9446 7525 -1.00387 -0.0268176 -1.55118 1 0 1 1 0 0 +EDGE2 9446 7925 -0.945647 0.0571963 1.597 1 0 1 1 0 0 +EDGE2 9446 9445 -0.935905 0.0318856 -1.58245 1 0 1 1 0 0 +EDGE2 9446 7945 -0.983281 0.0346482 -1.54871 1 0 1 1 0 0 +EDGE2 9446 7285 -1.02635 0.0136295 1.55948 1 0 1 1 0 0 +EDGE2 9446 7325 -0.900578 0.0232103 1.53544 1 0 1 1 0 0 +EDGE2 9446 7345 -0.945272 -0.0178264 1.58689 1 0 1 1 0 0 +EDGE2 9446 7365 -1.07727 0.0631703 1.5383 1 0 1 1 0 0 +EDGE2 9446 7305 -1.00556 0.0914546 1.59885 1 0 1 1 0 0 +EDGE2 9446 7366 0.081162 -0.108012 -0.0344609 1 0 1 1 0 0 +EDGE2 9446 7185 -0.977144 -0.0710482 1.55957 1 0 1 1 0 0 +EDGE2 9446 7186 0.0144907 -0.0643137 0.0062252 1 0 1 1 0 0 +EDGE2 9446 7187 1.02387 -0.00464097 0.0106497 1 0 1 1 0 0 +EDGE2 9446 7367 1.0524 -0.158118 0.00840802 1 0 1 1 0 0 +EDGE2 9447 7366 -1.05456 0.0572476 -0.000294989 1 0 1 1 0 0 +EDGE2 9447 9446 -1.09163 -0.0402927 -0.0197751 1 0 1 1 0 0 +EDGE2 9447 7186 -0.969298 0.0275583 -0.00787433 1 0 1 1 0 0 +EDGE2 9447 7188 0.905159 0.0436818 0.00258279 1 0 1 1 0 0 +EDGE2 9447 7187 0.0558704 -0.0230918 0.052197 1 0 1 1 0 0 +EDGE2 9447 7367 -0.050854 0.00173192 -0.025529 1 0 1 1 0 0 +EDGE2 9447 7368 1.0459 0.00698342 0.00705589 1 0 1 1 0 0 +EDGE2 9448 9447 -0.94905 0.0280186 0.0344342 1 0 1 1 0 0 +EDGE2 9448 7188 0.00967613 -0.0547258 -0.0100739 1 0 1 1 0 0 +EDGE2 9448 7187 -0.9901 -0.0404262 0.00963651 1 0 1 1 0 0 +EDGE2 9448 7367 -1.10461 0.024645 -0.0304325 1 0 1 1 0 0 +EDGE2 9448 7368 0.0742233 -0.0530679 -0.0151813 1 0 1 1 0 0 +EDGE2 9448 7369 1.07771 -0.0927401 -0.00976443 1 0 1 1 0 0 +EDGE2 9448 7189 0.985992 -0.00802753 -0.0126432 1 0 1 1 0 0 +EDGE2 9449 7188 -1.04742 0.0572253 -0.0483201 1 0 1 1 0 0 +EDGE2 9449 9448 -1.02414 0.0583676 0.0216588 1 0 1 1 0 0 +EDGE2 9449 7368 -0.984977 -0.0412149 0.00194713 1 0 1 1 0 0 +EDGE2 9449 7369 -0.0803256 -0.0267913 0.0424611 1 0 1 1 0 0 +EDGE2 9449 7189 0.0753529 0.0403281 0.00498798 1 0 1 1 0 0 +EDGE2 9449 7370 1.07697 0.0185414 -0.00262397 1 0 1 1 0 0 +EDGE2 9449 9430 0.979898 -0.0810796 -3.13012 1 0 1 1 0 0 +EDGE2 9449 7630 0.966019 0.0162116 -3.15506 1 0 1 1 0 0 +EDGE2 9449 7190 0.921778 -0.0117624 0.022743 1 0 1 1 0 0 +EDGE2 9450 7369 -0.954368 0.0059375 0.0181837 1 0 1 1 0 0 +EDGE2 9450 9449 -0.987571 -0.0468006 -0.0152645 1 0 1 1 0 0 +EDGE2 9450 7189 -0.931675 0.0237722 -0.00665198 1 0 1 1 0 0 +EDGE2 9450 7370 0.0606935 0.041888 -0.0198955 1 0 1 1 0 0 +EDGE2 9450 7631 0.0387616 0.88289 1.54228 1 0 1 1 0 0 +EDGE2 9450 9431 0.0537186 0.902188 1.58333 1 0 1 1 0 0 +EDGE2 9450 9430 0.0607234 -0.0719921 -3.12892 1 0 1 1 0 0 +EDGE2 9450 7371 0.091019 0.991898 1.53488 1 0 1 1 0 0 +EDGE2 9450 7630 -0.0782961 -0.0413736 -3.12702 1 0 1 1 0 0 +EDGE2 9450 9429 1.06739 -0.0845755 -3.14482 1 0 1 1 0 0 +EDGE2 9450 7190 -0.00179606 0.0710805 0.00973549 1 0 1 1 0 0 +EDGE2 9450 7629 1.02166 0.000150682 -3.11988 1 0 1 1 0 0 +EDGE2 9450 7191 -0.0477359 -1.03678 -1.54847 1 0 1 1 0 0 +EDGE2 9451 7370 -0.988306 -0.00390194 -1.59909 1 0 1 1 0 0 +EDGE2 9451 9432 0.926044 -0.0388493 0.0214568 1 0 1 1 0 0 +EDGE2 9451 7631 -0.0531626 -0.0516021 0.00109098 1 0 1 1 0 0 +EDGE2 9451 7372 1.00648 0.0317203 0.0211143 1 0 1 1 0 0 +EDGE2 9451 7632 1.10327 0.000801253 -0.00118737 1 0 1 1 0 0 +EDGE2 9451 9431 -0.05761 0.0533917 -0.0406758 1 0 1 1 0 0 +EDGE2 9451 9430 -0.983343 0.00611089 1.55377 1 0 1 1 0 0 +EDGE2 9451 9450 -0.987951 -0.0287546 -1.53894 1 0 1 1 0 0 +EDGE2 9451 7371 -0.00476551 -0.023651 0.00448555 1 0 1 1 0 0 +EDGE2 9451 7630 -0.977028 0.0999247 1.6033 1 0 1 1 0 0 +EDGE2 9451 7190 -0.958044 0.00837571 -1.58345 1 0 1 1 0 0 +EDGE2 9452 9432 0.0351107 -0.011518 -0.00566785 1 0 1 1 0 0 +EDGE2 9452 7373 0.950178 -0.0193951 0.000497379 1 0 1 1 0 0 +EDGE2 9452 7633 1.02612 -0.0531166 0.0338121 1 0 1 1 0 0 +EDGE2 9452 9433 1.06059 0.00324879 -0.00568124 1 0 1 1 0 0 +EDGE2 9452 7631 -1.05325 -0.0104068 0.000188484 1 0 1 1 0 0 +EDGE2 9452 9451 -0.968371 0.0261719 0.0297737 1 0 1 1 0 0 +EDGE2 9452 7372 0.0535872 0.0122546 0.00442032 1 0 1 1 0 0 +EDGE2 9452 7632 0.0169264 -0.0378931 0.00888301 1 0 1 1 0 0 +EDGE2 9452 9431 -0.933911 0.0032216 0.0162932 1 0 1 1 0 0 +EDGE2 9452 7371 -1.0799 0.0330852 0.000542901 1 0 1 1 0 0 +EDGE2 9453 9432 -1.0067 -0.106974 0.00164308 1 0 1 1 0 0 +EDGE2 9453 7634 0.936389 0.00602352 -0.0103076 1 0 1 1 0 0 +EDGE2 9453 9434 1.07348 0.02115 -0.00976886 1 0 1 1 0 0 +EDGE2 9453 7374 0.964582 -0.0544603 0.00587854 1 0 1 1 0 0 +EDGE2 9453 7373 0.0542654 0.00957574 0.0121792 1 0 1 1 0 0 +EDGE2 9453 7633 -0.0570691 -0.055519 -0.0141262 1 0 1 1 0 0 +EDGE2 9453 9433 -0.00290935 0.0149966 0.00120151 1 0 1 1 0 0 +EDGE2 9453 9452 -1.05217 -0.0263142 0.0348823 1 0 1 1 0 0 +EDGE2 9453 7372 -1.00585 0.0722735 -0.0123307 1 0 1 1 0 0 +EDGE2 9453 7632 -0.979021 0.000404815 0.0308159 1 0 1 1 0 0 +EDGE2 9454 7975 0.931034 -0.0402735 -3.13324 1 0 1 1 0 0 +EDGE2 9454 9435 0.98846 0.0535061 -0.00404108 1 0 1 1 0 0 +EDGE2 9454 7375 0.922389 0.0128528 -0.0183741 1 0 1 1 0 0 +EDGE2 9454 7595 1.00685 0.0631778 -3.16642 1 0 1 1 0 0 +EDGE2 9454 7635 0.960117 0.00446145 0.0185146 1 0 1 1 0 0 +EDGE2 9454 9453 -1.02504 -0.0226762 -0.0326391 1 0 1 1 0 0 +EDGE2 9454 7634 -0.0451755 0.0526701 -0.00581616 1 0 1 1 0 0 +EDGE2 9454 9434 0.144995 -0.0421678 -0.00883408 1 0 1 1 0 0 +EDGE2 9454 7374 -0.0410164 0.0833083 0.0134107 1 0 1 1 0 0 +EDGE2 9454 7373 -0.94234 -0.0150276 -0.0141993 1 0 1 1 0 0 +EDGE2 9454 7633 -1.00255 0.0562928 0.0242962 1 0 1 1 0 0 +EDGE2 9454 9433 -1.0111 0.0766786 -0.0335824 1 0 1 1 0 0 +EDGE2 9455 7975 -0.0193772 -0.0568053 -3.1716 1 0 1 1 0 0 +EDGE2 9455 7974 0.985153 0.071635 -3.15889 1 0 1 1 0 0 +EDGE2 9455 7594 1.04148 0.0352417 -3.11029 1 0 1 1 0 0 +EDGE2 9455 7376 0.0285202 0.940996 1.59342 1 0 1 1 0 0 +EDGE2 9455 9436 0.0876984 0.887059 1.58533 1 0 1 1 0 0 +EDGE2 9455 9435 0.0229141 -0.0453609 0.0321976 1 0 1 1 0 0 +EDGE2 9455 7596 -0.0412443 -1.03609 -1.56599 1 0 1 1 0 0 +EDGE2 9455 7636 -0.0253644 -0.936756 -1.58757 1 0 1 1 0 0 +EDGE2 9455 7375 0.0217175 -0.0184656 -0.0192426 1 0 1 1 0 0 +EDGE2 9455 7595 -0.11758 -0.0362396 -3.16803 1 0 1 1 0 0 +EDGE2 9455 7635 -0.0170866 -0.0920773 -0.000795321 1 0 1 1 0 0 +EDGE2 9455 7976 -0.0442719 -0.967585 -1.56301 1 0 1 1 0 0 +EDGE2 9455 7634 -0.943157 -0.0260776 -0.0101381 1 0 1 1 0 0 +EDGE2 9455 9434 -0.947458 0.0453704 -0.00909878 1 0 1 1 0 0 +EDGE2 9455 9454 -0.991199 0.0667283 -0.0517323 1 0 1 1 0 0 +EDGE2 9455 7374 -0.978814 -0.0774964 -0.0173187 1 0 1 1 0 0 +EDGE2 9456 7975 -1.01557 0.0336351 1.58867 1 0 1 1 0 0 +EDGE2 9456 9437 1.01837 -0.0780343 -0.0172352 1 0 1 1 0 0 +EDGE2 9456 7377 0.980108 -0.0776934 0.00600017 1 0 1 1 0 0 +EDGE2 9456 9455 -1.0027 -0.0877966 -1.53934 1 0 1 1 0 0 +EDGE2 9456 7376 -0.0138473 -0.0439606 0.0183285 1 0 1 1 0 0 +EDGE2 9456 9436 0.0138717 -0.0209701 -0.0108038 1 0 1 1 0 0 +EDGE2 9456 9435 -1.03354 -0.021133 -1.57703 1 0 1 1 0 0 +EDGE2 9456 7375 -0.983396 0.0233696 -1.59618 1 0 1 1 0 0 +EDGE2 9456 7595 -0.970915 0.0914316 1.54623 1 0 1 1 0 0 +EDGE2 9456 7635 -0.994263 -0.00105756 -1.55881 1 0 1 1 0 0 +EDGE2 9457 9438 1.07329 -0.00192267 -0.000937017 1 0 1 1 0 0 +EDGE2 9457 9456 -1.02492 -0.0766715 -0.0149144 1 0 1 1 0 0 +EDGE2 9457 9437 -0.0235212 0.00740568 -0.0440157 1 0 1 1 0 0 +EDGE2 9457 7378 0.949117 0.0445998 0.00775941 1 0 1 1 0 0 +EDGE2 9457 7377 -0.0331951 -0.0482926 0.00544568 1 0 1 1 0 0 +EDGE2 9457 7376 -1.04032 0.0213731 0.0137313 1 0 1 1 0 0 +EDGE2 9457 9436 -0.965228 0.0630891 -0.0126779 1 0 1 1 0 0 +EDGE2 9458 9438 0.0614509 0.134934 -0.000197692 1 0 1 1 0 0 +EDGE2 9458 7379 0.99015 -0.0521136 -0.00301835 1 0 1 1 0 0 +EDGE2 9458 9439 0.935715 0.00719963 0.00373348 1 0 1 1 0 0 +EDGE2 9458 9437 -0.981621 0.00434388 0.036359 1 0 1 1 0 0 +EDGE2 9458 9457 -1.03324 0.0366824 -0.00113538 1 0 1 1 0 0 +EDGE2 9458 7378 0.0713446 -0.00587957 -0.000299022 1 0 1 1 0 0 +EDGE2 9458 7377 -0.979457 -0.115629 0.00530465 1 0 1 1 0 0 +EDGE2 9459 7520 1.01291 -0.0425003 -3.15233 1 0 1 1 0 0 +EDGE2 9459 7540 0.963913 0.0175874 -3.14289 1 0 1 1 0 0 +EDGE2 9459 9440 1.04718 -0.0251685 -0.0197139 1 0 1 1 0 0 +EDGE2 9459 7580 0.952647 -0.0319873 -3.14901 1 0 1 1 0 0 +EDGE2 9459 7940 0.976758 0.0162597 -3.16391 1 0 1 1 0 0 +EDGE2 9459 7960 0.966986 0.0103214 -3.13766 1 0 1 1 0 0 +EDGE2 9459 7560 0.959479 0.00364864 -3.09204 1 0 1 1 0 0 +EDGE2 9459 7380 0.929189 -0.00901529 -0.0116421 1 0 1 1 0 0 +EDGE2 9459 7460 0.902488 -0.0540809 -3.19125 1 0 1 1 0 0 +EDGE2 9459 9438 -0.9337 -0.142761 0.00438331 1 0 1 1 0 0 +EDGE2 9459 7379 0.0337623 -0.0245953 -0.00120908 1 0 1 1 0 0 +EDGE2 9459 9439 -0.0868589 -0.0305247 0.00442374 1 0 1 1 0 0 +EDGE2 9459 9458 -0.960085 0.053177 0.00670785 1 0 1 1 0 0 +EDGE2 9459 7378 -1.07171 0.0111746 0.00106821 1 0 1 1 0 0 +EDGE2 9460 7520 0.0369005 0.0274808 -3.14839 1 0 1 1 0 0 +EDGE2 9460 7539 1.01102 -0.0859897 -3.13647 1 0 1 1 0 0 +EDGE2 9460 7579 1.02609 0.0400812 -3.14106 1 0 1 1 0 0 +EDGE2 9460 7939 0.930507 -0.00272529 -3.12611 1 0 1 1 0 0 +EDGE2 9460 7959 0.970946 -0.0546201 -3.12259 1 0 1 1 0 0 +EDGE2 9460 7559 1.01538 0.0663025 -3.12063 1 0 1 1 0 0 +EDGE2 9460 7459 1.00054 0.0250309 -3.12479 1 0 1 1 0 0 +EDGE2 9460 7519 1.04724 -0.00721823 -3.13299 1 0 1 1 0 0 +EDGE2 9460 7540 -0.0651862 0.0516074 -3.15983 1 0 1 1 0 0 +EDGE2 9460 7561 0.106493 -0.966681 -1.55118 1 0 1 1 0 0 +EDGE2 9460 7961 -0.0167104 -0.886255 -1.56791 1 0 1 1 0 0 +EDGE2 9460 7581 -0.0574251 -0.981211 -1.53967 1 0 1 1 0 0 +EDGE2 9460 9440 -0.0282532 -0.142332 -0.0280373 1 0 1 1 0 0 +EDGE2 9460 7381 -0.00341361 -1.04801 -1.59979 1 0 1 1 0 0 +EDGE2 9460 7461 -0.00214512 -1.04121 -1.56601 1 0 1 1 0 0 +EDGE2 9460 7541 0.0356792 -1.00264 -1.57236 1 0 1 1 0 0 +EDGE2 9460 7580 0.108859 -0.0328216 -3.12795 1 0 1 1 0 0 +EDGE2 9460 7940 0.038188 -0.013629 -3.16779 1 0 1 1 0 0 +EDGE2 9460 7960 0.0824081 -0.0294158 -3.13341 1 0 1 1 0 0 +EDGE2 9460 7560 0.0646713 -0.0351132 -3.1517 1 0 1 1 0 0 +EDGE2 9460 7941 -0.102273 0.919206 1.55078 1 0 1 1 0 0 +EDGE2 9460 7380 0.0294889 -0.0784313 0.00882275 1 0 1 1 0 0 +EDGE2 9460 7460 0.0141526 0.0633409 -3.14565 1 0 1 1 0 0 +EDGE2 9460 9441 -0.0454223 0.918642 1.5596 1 0 1 1 0 0 +EDGE2 9460 7521 0.0773974 1.01259 1.59077 1 0 1 1 0 0 +EDGE2 9460 7379 -0.939108 0.0211994 0.00340881 1 0 1 1 0 0 +EDGE2 9460 9439 -1.06194 -0.0527188 -0.00433823 1 0 1 1 0 0 +EDGE2 9460 9459 -1.00448 -0.0784013 0.00633418 1 0 1 1 0 0 +EDGE2 9461 7520 -1.03969 -0.0561209 1.55985 1 0 1 1 0 0 +EDGE2 9461 7540 -1.04838 -0.00428852 1.59336 1 0 1 1 0 0 +EDGE2 9461 9440 -1.09794 0.114737 -1.55235 1 0 1 1 0 0 +EDGE2 9461 9460 -0.973649 -0.0587207 -1.56756 1 0 1 1 0 0 +EDGE2 9461 7580 -1.14845 0.0246993 1.55844 1 0 1 1 0 0 +EDGE2 9461 7940 -1.02332 0.0970846 1.60283 1 0 1 1 0 0 +EDGE2 9461 7960 -1.02574 -0.0561333 1.5484 1 0 1 1 0 0 +EDGE2 9461 7560 -0.990794 -0.0802602 1.59658 1 0 1 1 0 0 +EDGE2 9461 7522 1.02382 -0.0250739 0.00040448 1 0 1 1 0 0 +EDGE2 9461 7941 -0.0307584 -0.0613246 0.0013462 1 0 1 1 0 0 +EDGE2 9461 7380 -1.0125 -0.0709971 -1.58332 1 0 1 1 0 0 +EDGE2 9461 7460 -0.836389 0.04027 1.5578 1 0 1 1 0 0 +EDGE2 9461 9441 0.0419463 -0.0491002 0.0125816 1 0 1 1 0 0 +EDGE2 9461 9442 1.00364 -0.00956806 0.0279195 1 0 1 1 0 0 +EDGE2 9461 7521 -0.00041898 -0.0260665 0.0265204 1 0 1 1 0 0 +EDGE2 9461 7942 1.01107 0.05414 -0.0168821 1 0 1 1 0 0 +EDGE2 9462 7522 -0.0347947 -0.0333531 0.0375685 1 0 1 1 0 0 +EDGE2 9462 7941 -0.96952 -0.010199 -0.0344594 1 0 1 1 0 0 +EDGE2 9462 9461 -1.12688 -0.0506981 0.0105846 1 0 1 1 0 0 +EDGE2 9462 9441 -1.00946 0.0609137 -0.0276306 1 0 1 1 0 0 +EDGE2 9462 9442 0.0856555 -0.00133238 -0.00809553 1 0 1 1 0 0 +EDGE2 9462 7521 -1.00958 -0.0415621 -0.0099195 1 0 1 1 0 0 +EDGE2 9462 7942 0.0119932 -0.0232897 0.0231645 1 0 1 1 0 0 +EDGE2 9462 7943 0.994306 -0.0147427 -0.00438238 1 0 1 1 0 0 +EDGE2 9462 9443 1.0298 0.00412761 -0.00504845 1 0 1 1 0 0 +EDGE2 9462 7523 1.02422 -0.0288293 -0.00346522 1 0 1 1 0 0 +EDGE2 9463 7944 1.05106 -0.0341747 0.00705942 1 0 1 1 0 0 +EDGE2 9463 7522 -1.04868 -0.0401739 0.00596234 1 0 1 1 0 0 +EDGE2 9463 9442 -1.01028 -0.0258063 0.0230105 1 0 1 1 0 0 +EDGE2 9463 9462 -1.0319 -0.043141 -0.0283687 1 0 1 1 0 0 +EDGE2 9463 7942 -0.973017 -0.0630766 0.027669 1 0 1 1 0 0 +EDGE2 9463 7943 -0.101062 -0.077766 0.0559884 1 0 1 1 0 0 +EDGE2 9463 9443 0.0343392 -0.0207351 -0.00397074 1 0 1 1 0 0 +EDGE2 9463 7523 0.0268151 0.0257589 0.000650714 1 0 1 1 0 0 +EDGE2 9463 9444 0.93796 -0.0241885 -0.00741763 1 0 1 1 0 0 +EDGE2 9463 7524 0.943161 0.120245 -0.0155934 1 0 1 1 0 0 +EDGE2 9464 7944 -0.0564455 0.0342354 0.039434 1 0 1 1 0 0 +EDGE2 9464 7943 -1.02542 -0.102346 0.0134486 1 0 1 1 0 0 +EDGE2 9464 9463 -1.00067 -0.0162062 -0.0191382 1 0 1 1 0 0 +EDGE2 9464 9443 -0.974083 0.0188094 -0.000142939 1 0 1 1 0 0 +EDGE2 9464 7523 -1.00861 -0.0276897 0.0133418 1 0 1 1 0 0 +EDGE2 9464 9444 0.0100401 -0.00352494 0.00752224 1 0 1 1 0 0 +EDGE2 9464 7525 1.02471 0.0565237 0.00221213 1 0 1 1 0 0 +EDGE2 9464 7925 1.01856 -0.0404719 -3.13291 1 0 1 1 0 0 +EDGE2 9464 9445 0.988897 -0.00782743 0.0129023 1 0 1 1 0 0 +EDGE2 9464 7524 0.0553651 -0.0275877 0.0241278 1 0 1 1 0 0 +EDGE2 9464 7945 0.959768 -0.0145462 -0.0299307 1 0 1 1 0 0 +EDGE2 9464 7285 0.963981 -0.006053 -3.14737 1 0 1 1 0 0 +EDGE2 9464 7325 1.03722 0.0106313 -3.13818 1 0 1 1 0 0 +EDGE2 9464 7345 1.08301 0.0675742 -3.15804 1 0 1 1 0 0 +EDGE2 9464 7365 1.07023 -0.0568541 -3.13734 1 0 1 1 0 0 +EDGE2 9464 7305 0.995562 0.0504853 -3.1517 1 0 1 1 0 0 +EDGE2 9464 7185 0.968661 -9.87123e-05 -3.1187 1 0 1 1 0 0 +EDGE2 9465 7944 -0.94286 -0.0249986 -0.00456591 1 0 1 1 0 0 +EDGE2 9465 7326 0.0194824 -0.983539 -1.56215 1 0 1 1 0 0 +EDGE2 9465 7526 0.0410057 -0.9835 -1.58399 1 0 1 1 0 0 +EDGE2 9465 7926 0.0352438 -1.03951 -1.55695 1 0 1 1 0 0 +EDGE2 9465 7946 0.0223188 -1.01517 -1.56937 1 0 1 1 0 0 +EDGE2 9465 7346 -0.0539439 -0.918815 -1.56556 1 0 1 1 0 0 +EDGE2 9465 7286 0.102194 -1.09348 -1.57189 1 0 1 1 0 0 +EDGE2 9465 7306 0.0212977 -0.973629 -1.58099 1 0 1 1 0 0 +EDGE2 9465 9464 -1.07361 -0.0976963 -0.0135396 1 0 1 1 0 0 +EDGE2 9465 9444 -1.06931 0.00129011 -0.00895299 1 0 1 1 0 0 +EDGE2 9465 7525 0.0434806 0.0450572 -0.00362935 1 0 1 1 0 0 +EDGE2 9465 7925 -0.00766918 0.0132854 -3.15239 1 0 1 1 0 0 +EDGE2 9465 9445 0.0578201 0.0431541 -0.00563022 1 0 1 1 0 0 +EDGE2 9465 7524 -0.998959 0.150057 -0.031833 1 0 1 1 0 0 +EDGE2 9465 7945 -0.0564071 -0.0338813 0.0039169 1 0 1 1 0 0 +EDGE2 9465 7285 0.0383438 0.0377747 -3.14548 1 0 1 1 0 0 +EDGE2 9465 7325 0.0382421 0.00472742 -3.15593 1 0 1 1 0 0 +EDGE2 9465 7345 -0.0400379 -0.0579862 -3.12998 1 0 1 1 0 0 +EDGE2 9465 7365 0.00720233 0.00515136 -3.14615 1 0 1 1 0 0 +EDGE2 9465 7305 -0.0800101 0.0444562 -3.12447 1 0 1 1 0 0 +EDGE2 9465 7366 0.0286582 1.04618 1.54713 1 0 1 1 0 0 +EDGE2 9465 9446 -0.0275689 1.03482 1.56053 1 0 1 1 0 0 +EDGE2 9465 7185 0.006512 -0.0541408 -3.1334 1 0 1 1 0 0 +EDGE2 9465 7186 -0.0523758 1.03729 1.55864 1 0 1 1 0 0 +EDGE2 9465 7304 0.977422 -0.0220435 -3.14091 1 0 1 1 0 0 +EDGE2 9465 7344 0.982044 0.030281 -3.0976 1 0 1 1 0 0 +EDGE2 9465 7364 1.02121 -0.0326409 -3.08866 1 0 1 1 0 0 +EDGE2 9465 7924 0.991919 -0.0106032 -3.14684 1 0 1 1 0 0 +EDGE2 9465 7324 1.01981 0.00884637 -3.14318 1 0 1 1 0 0 +EDGE2 9465 7184 0.956482 0.00428502 -3.16275 1 0 1 1 0 0 +EDGE2 9465 7284 1.00979 0.00843413 -3.15555 1 0 1 1 0 0 +EDGE2 9466 7326 -0.0716294 -0.041619 -0.0117017 1 0 1 1 0 0 +EDGE2 9466 7527 1.01921 0.0555352 -0.00671235 1 0 1 1 0 0 +EDGE2 9466 7947 0.955287 -0.0463162 -0.0156273 1 0 1 1 0 0 +EDGE2 9466 7927 1.04606 -0.0225199 0.00982733 1 0 1 1 0 0 +EDGE2 9466 7307 0.986239 -0.0559851 -0.0088622 1 0 1 1 0 0 +EDGE2 9466 7327 1.05377 0.0408732 0.00159958 1 0 1 1 0 0 +EDGE2 9466 7347 0.95467 -0.0211785 -0.0355253 1 0 1 1 0 0 +EDGE2 9466 7287 0.981236 -0.0388919 -0.000980418 1 0 1 1 0 0 +EDGE2 9466 7526 -0.042684 0.0909596 -0.0106086 1 0 1 1 0 0 +EDGE2 9466 7926 -0.057904 0.0680381 0.0128454 1 0 1 1 0 0 +EDGE2 9466 7946 0.074764 0.0669793 0.000395591 1 0 1 1 0 0 +EDGE2 9466 7346 0.0525652 -0.113725 0.0308397 1 0 1 1 0 0 +EDGE2 9466 7286 0.0480081 -0.0552276 0.0118852 1 0 1 1 0 0 +EDGE2 9466 7306 -0.126954 -0.0153392 0.0198498 1 0 1 1 0 0 +EDGE2 9466 7525 -0.975003 0.0765461 1.53839 1 0 1 1 0 0 +EDGE2 9466 7925 -1.01274 -0.0890023 -1.56016 1 0 1 1 0 0 +EDGE2 9466 9445 -0.958312 -0.0989675 1.58918 1 0 1 1 0 0 +EDGE2 9466 9465 -0.921218 -0.0247527 1.53849 1 0 1 1 0 0 +EDGE2 9466 7945 -1.02551 0.0215723 1.59516 1 0 1 1 0 0 +EDGE2 9466 7285 -0.933216 0.0228697 -1.59528 1 0 1 1 0 0 +EDGE2 9466 7325 -0.951108 0.10765 -1.53201 1 0 1 1 0 0 +EDGE2 9466 7345 -0.935594 -0.0567119 -1.57428 1 0 1 1 0 0 +EDGE2 9466 7365 -1.03153 0.1092 -1.5466 1 0 1 1 0 0 +EDGE2 9466 7305 -1.01498 0.0533907 -1.58423 1 0 1 1 0 0 +EDGE2 9466 7185 -0.964914 0.0232337 -1.58506 1 0 1 1 0 0 +EDGE2 9467 7948 0.939232 -0.0658306 0.00398809 1 0 1 1 0 0 +EDGE2 9467 7326 -0.966039 -0.0181472 0.0153825 1 0 1 1 0 0 +EDGE2 9467 7527 -0.0106666 0.0481381 -0.0269769 1 0 1 1 0 0 +EDGE2 9467 7308 0.981366 -0.0375187 -0.00120534 1 0 1 1 0 0 +EDGE2 9467 7348 1.0017 0.0793962 0.00839008 1 0 1 1 0 0 +EDGE2 9467 7528 1.07865 0.0546234 0.0188923 1 0 1 1 0 0 +EDGE2 9467 7928 1.01225 0.0527561 -0.021557 1 0 1 1 0 0 +EDGE2 9467 7328 1.05321 -0.0487013 0.0311349 1 0 1 1 0 0 +EDGE2 9467 7947 -0.0291144 -0.0157531 -0.0418316 1 0 1 1 0 0 +EDGE2 9467 7288 0.938055 0.065485 -0.0241357 1 0 1 1 0 0 +EDGE2 9467 7927 0.0441886 0.0540812 0.00820633 1 0 1 1 0 0 +EDGE2 9467 9466 -1.02831 0.00991989 0.00134197 1 0 1 1 0 0 +EDGE2 9467 7307 0.0723652 0.0421971 0.0016623 1 0 1 1 0 0 +EDGE2 9467 7327 0.0250496 0.0411426 0.00437938 1 0 1 1 0 0 +EDGE2 9467 7347 0.00318743 -0.0493616 -0.0178908 1 0 1 1 0 0 +EDGE2 9467 7287 -0.0471288 0.0191656 -0.00202378 1 0 1 1 0 0 +EDGE2 9467 7526 -0.941908 0.0478813 -0.0237841 1 0 1 1 0 0 +EDGE2 9467 7926 -0.991863 -0.0512117 0.00175324 1 0 1 1 0 0 +EDGE2 9467 7946 -1.04994 0.0495171 -0.0299771 1 0 1 1 0 0 +EDGE2 9467 7346 -1.02103 0.119228 0.00196337 1 0 1 1 0 0 +EDGE2 9467 7286 -0.880537 0.0547867 -0.0169264 1 0 1 1 0 0 +EDGE2 9467 7306 -0.959791 0.0635174 -0.0340518 1 0 1 1 0 0 +EDGE2 9468 7948 -0.00189224 0.00368713 -0.0134968 1 0 1 1 0 0 +EDGE2 9468 7329 1.00743 -0.064412 -0.0220876 1 0 1 1 0 0 +EDGE2 9468 7529 0.999847 0.0472816 -0.056231 1 0 1 1 0 0 +EDGE2 9468 7929 0.921205 -0.105427 0.00812117 1 0 1 1 0 0 +EDGE2 9468 7949 0.928728 -0.0056092 0.0201636 1 0 1 1 0 0 +EDGE2 9468 7349 1.03831 -0.0166273 0.00940204 1 0 1 1 0 0 +EDGE2 9468 7289 0.964777 0.0461781 -0.00326218 1 0 1 1 0 0 +EDGE2 9468 7309 0.981387 -2.57322e-05 -0.027959 1 0 1 1 0 0 +EDGE2 9468 7527 -1.01557 -0.002209 0.000985643 1 0 1 1 0 0 +EDGE2 9468 7308 0.0378705 0.0556762 0.00489116 1 0 1 1 0 0 +EDGE2 9468 7348 0.0763815 -0.000199569 -0.00851011 1 0 1 1 0 0 +EDGE2 9468 7528 -0.0889897 -0.0646477 -0.00660508 1 0 1 1 0 0 +EDGE2 9468 7928 0.00337366 0.0310207 -0.000751844 1 0 1 1 0 0 +EDGE2 9468 7328 -0.0409527 0.0289969 -0.0115537 1 0 1 1 0 0 +EDGE2 9468 7947 -0.975247 -0.020942 0.000619453 1 0 1 1 0 0 +EDGE2 9468 9467 -1.02114 0.0258323 0.0244693 1 0 1 1 0 0 +EDGE2 9468 7288 0.0193793 -0.0595775 -0.0106171 1 0 1 1 0 0 +EDGE2 9468 7927 -0.979068 0.0305411 -0.0147384 1 0 1 1 0 0 +EDGE2 9468 7307 -1.02113 0.0338339 0.029526 1 0 1 1 0 0 +EDGE2 9468 7327 -0.934708 -0.0808897 0.00265332 1 0 1 1 0 0 +EDGE2 9468 7347 -1.08337 -0.012087 0.022202 1 0 1 1 0 0 +EDGE2 9468 7287 -1.00098 -0.00388048 0.0131717 1 0 1 1 0 0 +EDGE2 9469 7948 -0.996429 -0.0221132 0.0242097 1 0 1 1 0 0 +EDGE2 9469 7530 1.03673 -0.0654159 0.0327161 1 0 1 1 0 0 +EDGE2 9469 7950 1.03231 0.00218892 -0.0306235 1 0 1 1 0 0 +EDGE2 9469 7930 1.03306 0.00141434 0.00192145 1 0 1 1 0 0 +EDGE2 9469 7310 0.996786 -0.0350452 0.0310838 1 0 1 1 0 0 +EDGE2 9469 7350 1.01721 0.0671617 -0.00221184 1 0 1 1 0 0 +EDGE2 9469 7450 0.942884 0.038129 -3.15099 1 0 1 1 0 0 +EDGE2 9469 7510 0.886149 -0.13947 -3.15921 1 0 1 1 0 0 +EDGE2 9469 7330 0.950337 0.0267166 -0.0269724 1 0 1 1 0 0 +EDGE2 9469 7170 1.02053 0.0263172 -3.11296 1 0 1 1 0 0 +EDGE2 9469 7290 0.950304 0.0528986 -0.0127566 1 0 1 1 0 0 +EDGE2 9469 7329 -0.00734361 0.00635455 -0.00268896 1 0 1 1 0 0 +EDGE2 9469 7529 0.0842003 0.0305183 0.00228665 1 0 1 1 0 0 +EDGE2 9469 7929 0.112386 0.00629647 0.0230991 1 0 1 1 0 0 +EDGE2 9469 7949 0.0817788 0.0728845 -0.0211809 1 0 1 1 0 0 +EDGE2 9469 7349 0.0530359 -0.0257671 0.0256961 1 0 1 1 0 0 +EDGE2 9469 7289 -0.108779 0.0797718 -0.0333947 1 0 1 1 0 0 +EDGE2 9469 7309 0.0122049 -0.0429659 0.0141889 1 0 1 1 0 0 +EDGE2 9469 9468 -1.0144 -0.0189376 -0.00316957 1 0 1 1 0 0 +EDGE2 9469 7308 -1.01106 0.0479744 -0.0122094 1 0 1 1 0 0 +EDGE2 9469 7348 -1.03517 -0.0721663 -0.00463754 1 0 1 1 0 0 +EDGE2 9469 7528 -0.941149 -0.00957239 -0.0340415 1 0 1 1 0 0 +EDGE2 9469 7928 -1.00525 0.0220681 0.0195685 1 0 1 1 0 0 +EDGE2 9469 7328 -1.0006 -0.0797479 0.0163881 1 0 1 1 0 0 +EDGE2 9469 7288 -1.00516 -0.020905 0.00954003 1 0 1 1 0 0 +EDGE2 9470 7449 1.02328 -0.0128763 -3.14224 1 0 1 1 0 0 +EDGE2 9470 7509 1.01713 0.00439693 -3.16406 1 0 1 1 0 0 +EDGE2 9470 7169 1.04462 0.0692274 -3.15045 1 0 1 1 0 0 +EDGE2 9470 7530 0.0587238 -0.00730601 -0.00593535 1 0 1 1 0 0 +EDGE2 9470 7511 0.00122962 -1.00415 -1.6011 1 0 1 1 0 0 +EDGE2 9470 7931 0.0493282 -0.98413 -1.55801 1 0 1 1 0 0 +EDGE2 9470 7951 -0.018409 -0.946773 -1.55832 1 0 1 1 0 0 +EDGE2 9470 7531 -0.0484296 -1.05107 -1.57403 1 0 1 1 0 0 +EDGE2 9470 7950 -0.0445755 0.0509742 -0.0293615 1 0 1 1 0 0 +EDGE2 9470 7451 -0.0107037 -1.01223 -1.56809 1 0 1 1 0 0 +EDGE2 9470 7930 0.0149081 -0.0186666 -0.00136846 1 0 1 1 0 0 +EDGE2 9470 9469 -1.03104 -0.0651629 0.0225975 1 0 1 1 0 0 +EDGE2 9470 7310 0.00207722 0.0973542 -0.0233323 1 0 1 1 0 0 +EDGE2 9470 7350 0.0254978 0.0321883 -0.00747959 1 0 1 1 0 0 +EDGE2 9470 7450 0.00412857 -0.013397 -3.12587 1 0 1 1 0 0 +EDGE2 9470 7510 -0.0556168 -0.0748739 -3.08432 1 0 1 1 0 0 +EDGE2 9470 7330 0.0575573 0.0472924 -0.0301979 1 0 1 1 0 0 +EDGE2 9470 7170 -0.00701111 -0.107007 -3.16427 1 0 1 1 0 0 +EDGE2 9470 7290 0.0185695 0.0467134 -0.0411268 1 0 1 1 0 0 +EDGE2 9470 7329 -0.999291 -0.0425678 -0.0206542 1 0 1 1 0 0 +EDGE2 9470 7529 -0.945362 0.000110006 -0.0151061 1 0 1 1 0 0 +EDGE2 9470 7929 -1.02594 0.0339626 -0.00971106 1 0 1 1 0 0 +EDGE2 9470 7949 -0.999164 -0.0627056 -0.014427 1 0 1 1 0 0 +EDGE2 9470 7349 -1.0577 0.00478649 0.0184156 1 0 1 1 0 0 +EDGE2 9470 7289 -1.05919 -0.00770853 -0.00544856 1 0 1 1 0 0 +EDGE2 9470 7309 -0.941351 0.0780493 0.0556314 1 0 1 1 0 0 +EDGE2 9470 7291 -0.0153775 1.02567 1.58211 1 0 1 1 0 0 +EDGE2 9470 7331 0.0627589 0.996779 1.58786 1 0 1 1 0 0 +EDGE2 9470 7351 -0.114428 1.02587 1.61312 1 0 1 1 0 0 +EDGE2 9470 7311 0.112632 1.07612 1.58412 1 0 1 1 0 0 +EDGE2 9470 7171 -0.0963839 0.930683 1.58873 1 0 1 1 0 0 +EDGE2 9471 7530 -1.00047 0.0113641 -1.58162 1 0 1 1 0 0 +EDGE2 9471 7950 -1.05196 -0.0309573 -1.58363 1 0 1 1 0 0 +EDGE2 9471 9470 -1.01892 -0.015634 -1.55097 1 0 1 1 0 0 +EDGE2 9471 7930 -1.0686 -0.0356028 -1.57412 1 0 1 1 0 0 +EDGE2 9471 7310 -0.992638 0.0430968 -1.5873 1 0 1 1 0 0 +EDGE2 9471 7350 -1.02251 -0.0426834 -1.57055 1 0 1 1 0 0 +EDGE2 9471 7450 -1.02787 0.016978 1.57804 1 0 1 1 0 0 +EDGE2 9471 7510 -1.08536 -0.00637859 1.57564 1 0 1 1 0 0 +EDGE2 9471 7330 -1.01454 -0.00869858 -1.52581 1 0 1 1 0 0 +EDGE2 9471 7170 -0.974949 -0.031181 1.55141 1 0 1 1 0 0 +EDGE2 9471 7290 -0.974865 -0.0434163 -1.5698 1 0 1 1 0 0 +EDGE2 9471 7312 0.982273 0.0183404 0.0110167 1 0 1 1 0 0 +EDGE2 9471 7291 0.00285925 0.0329412 0.025047 1 0 1 1 0 0 +EDGE2 9471 7331 -0.0434987 -0.143873 0.00515626 1 0 1 1 0 0 +EDGE2 9471 7351 0.0202784 -0.0386199 0.00668072 1 0 1 1 0 0 +EDGE2 9471 7311 -0.00160216 0.0213205 0.0272364 1 0 1 1 0 0 +EDGE2 9471 7352 0.967163 -0.0232326 -0.0154488 1 0 1 1 0 0 +EDGE2 9471 7171 0.0323019 -0.0242177 -0.000786861 1 0 1 1 0 0 +EDGE2 9471 7332 1.06387 0.0246985 0.0180897 1 0 1 1 0 0 +EDGE2 9471 7172 0.89478 -0.0287129 0.00665754 1 0 1 1 0 0 +EDGE2 9471 7292 0.864027 -0.0309054 -0.0105769 1 0 1 1 0 0 +EDGE2 9472 7312 0.00835073 -0.0467597 -0.0364026 1 0 1 1 0 0 +EDGE2 9472 7291 -1.0358 -0.031543 -0.0468459 1 0 1 1 0 0 +EDGE2 9472 7331 -0.947273 -0.030221 0.0277583 1 0 1 1 0 0 +EDGE2 9472 7351 -1.00564 0.0082405 -0.0330195 1 0 1 1 0 0 +EDGE2 9472 9471 -1.04208 0.00870125 -0.0103679 1 0 1 1 0 0 +EDGE2 9472 7311 -1.09502 0.0196906 0.015801 1 0 1 1 0 0 +EDGE2 9472 7352 -0.0387994 -0.0319188 0.00292909 1 0 1 1 0 0 +EDGE2 9472 7171 -0.98602 0.0912813 -0.00180355 1 0 1 1 0 0 +EDGE2 9472 7332 -0.0858259 -0.0298643 0.00326549 1 0 1 1 0 0 +EDGE2 9472 7333 0.995901 0.0479531 -0.00911899 1 0 1 1 0 0 +EDGE2 9472 7172 0.0411644 -0.0308298 0.0272921 1 0 1 1 0 0 +EDGE2 9472 7292 0.0168707 0.0354747 0.0112602 1 0 1 1 0 0 +EDGE2 9472 7353 1.07903 -0.0323122 -0.0369112 1 0 1 1 0 0 +EDGE2 9472 7173 0.963652 0.00267874 0.00569952 1 0 1 1 0 0 +EDGE2 9472 7293 0.993141 0.0287177 -0.0326385 1 0 1 1 0 0 +EDGE2 9472 7313 1.06268 -0.0439977 -0.0079152 1 0 1 1 0 0 +EDGE2 9473 7312 -1.02347 -0.0730059 -0.0153047 1 0 1 1 0 0 +EDGE2 9473 7352 -1.07365 -0.00404965 0.0339548 1 0 1 1 0 0 +EDGE2 9473 9472 -0.946093 -0.022835 0.00505922 1 0 1 1 0 0 +EDGE2 9473 7332 -1.0628 0.0598805 -0.0244776 1 0 1 1 0 0 +EDGE2 9473 7354 1.00289 0.0645847 0.006181 1 0 1 1 0 0 +EDGE2 9473 7333 0.0728925 -0.0373212 0.0275042 1 0 1 1 0 0 +EDGE2 9473 7172 -1.00458 -0.0287711 0.0126212 1 0 1 1 0 0 +EDGE2 9473 7292 -0.917735 -0.0557309 0.029674 1 0 1 1 0 0 +EDGE2 9473 7353 0.084254 -0.011857 0.0425911 1 0 1 1 0 0 +EDGE2 9473 7173 0.0232511 -0.0036893 0.00624492 1 0 1 1 0 0 +EDGE2 9473 7293 0.136896 0.0131026 0.0239513 1 0 1 1 0 0 +EDGE2 9473 7313 0.00834875 -0.0694139 -0.00974191 1 0 1 1 0 0 +EDGE2 9473 7294 0.977923 0.000173927 0.00783708 1 0 1 1 0 0 +EDGE2 9473 7314 1.01549 0.0260618 -0.00319203 1 0 1 1 0 0 +EDGE2 9473 7334 0.981229 -0.039609 -0.00778896 1 0 1 1 0 0 +EDGE2 9473 7174 1.03972 -0.00490825 -0.00423957 1 0 1 1 0 0 +EDGE2 9474 7315 0.932809 -0.0700052 0.0171749 1 0 1 1 0 0 +EDGE2 9474 7354 -0.00600552 0.0674569 -0.0393246 1 0 1 1 0 0 +EDGE2 9474 7333 -0.978765 0.0442835 -0.021497 1 0 1 1 0 0 +EDGE2 9474 9473 -1.05404 0.07317 -0.0230209 1 0 1 1 0 0 +EDGE2 9474 7353 -1.0061 0.0285193 -0.0212595 1 0 1 1 0 0 +EDGE2 9474 7173 -1.03396 -0.00760447 -0.0232873 1 0 1 1 0 0 +EDGE2 9474 7293 -0.999878 -0.0209703 -0.0326309 1 0 1 1 0 0 +EDGE2 9474 7313 -1.00831 0.0638375 0.0341265 1 0 1 1 0 0 +EDGE2 9474 7294 0.0937214 0.00139072 -0.00351854 1 0 1 1 0 0 +EDGE2 9474 7314 0.0297787 0.0153584 0.0250876 1 0 1 1 0 0 +EDGE2 9474 7334 0.0159188 0.003366 0.0042038 1 0 1 1 0 0 +EDGE2 9474 7174 0.0915143 0.0416569 -0.0207805 1 0 1 1 0 0 +EDGE2 9474 7355 0.929459 -0.0759871 0.00434667 1 0 1 1 0 0 +EDGE2 9474 7435 1.001 0.0499783 -3.18345 1 0 1 1 0 0 +EDGE2 9474 7335 0.952646 -0.0421804 0.000797913 1 0 1 1 0 0 +EDGE2 9474 7135 1.0307 -0.122518 -3.12651 1 0 1 1 0 0 +EDGE2 9474 7255 0.938398 0.0815909 -3.14163 1 0 1 1 0 0 +EDGE2 9474 7275 0.944232 0.0569472 -3.16352 1 0 1 1 0 0 +EDGE2 9474 7295 1.01654 -0.0191815 0.00619585 1 0 1 1 0 0 +EDGE2 9474 7175 1.08237 0.0295541 -0.00355327 1 0 1 1 0 0 +EDGE2 9474 7115 0.933845 0.0359702 -3.15384 1 0 1 1 0 0 +EDGE2 9475 7315 0.0725684 0.0603053 0.0048454 1 0 1 1 0 0 +EDGE2 9475 7136 -0.0289122 -1.03821 -1.58037 1 0 1 1 0 0 +EDGE2 9475 7256 0.0469264 -1.05966 -1.57284 1 0 1 1 0 0 +EDGE2 9475 7436 0.057727 -0.966034 -1.57602 1 0 1 1 0 0 +EDGE2 9475 7116 0.0463464 -1.02472 -1.57191 1 0 1 1 0 0 +EDGE2 9475 7354 -0.984909 -0.0172983 -0.0324664 1 0 1 1 0 0 +EDGE2 9475 9474 -0.981113 -0.0535099 -0.00159762 1 0 1 1 0 0 +EDGE2 9475 7294 -1.01077 -0.0374198 0.0380325 1 0 1 1 0 0 +EDGE2 9475 7314 -0.949041 -0.0874043 0.00434053 1 0 1 1 0 0 +EDGE2 9475 7334 -1.0246 0.0191399 0.00673837 1 0 1 1 0 0 +EDGE2 9475 7174 -1.00421 -0.0404576 -0.00375918 1 0 1 1 0 0 +EDGE2 9475 7355 0.0182487 -0.100233 0.00798419 1 0 1 1 0 0 +EDGE2 9475 7435 -0.0407537 0.0241851 -3.12745 1 0 1 1 0 0 +EDGE2 9475 7335 0.0185165 0.0224871 0.000436936 1 0 1 1 0 0 +EDGE2 9475 7134 0.931512 -0.0160689 -3.13342 1 0 1 1 0 0 +EDGE2 9475 7135 -0.0300989 0.0138198 -3.14054 1 0 1 1 0 0 +EDGE2 9475 7255 0.0633703 -0.0261103 -3.17543 1 0 1 1 0 0 +EDGE2 9475 7275 0.0099201 0.0467763 -3.14926 1 0 1 1 0 0 +EDGE2 9475 7295 -0.0439989 -0.0287481 0.0105144 1 0 1 1 0 0 +EDGE2 9475 7175 -0.0426366 -0.0422691 0.0295142 1 0 1 1 0 0 +EDGE2 9475 7274 0.980372 0.0544355 -3.11335 1 0 1 1 0 0 +EDGE2 9475 7434 0.950504 0.0259924 -3.16079 1 0 1 1 0 0 +EDGE2 9475 7115 -0.0539499 0.0218221 -3.0832 1 0 1 1 0 0 +EDGE2 9475 7254 1.02303 -0.0054414 -3.15728 1 0 1 1 0 0 +EDGE2 9475 7114 0.927947 -0.0116317 -3.11743 1 0 1 1 0 0 +EDGE2 9475 7296 0.0194008 1.02259 1.55013 1 0 1 1 0 0 +EDGE2 9475 7336 -0.0996868 1.04717 1.60037 1 0 1 1 0 0 +EDGE2 9475 7356 0.0353458 1.0048 1.59914 1 0 1 1 0 0 +EDGE2 9475 7316 0.006867 1.02366 1.52602 1 0 1 1 0 0 +EDGE2 9475 7176 0.0042935 0.999224 1.57853 1 0 1 1 0 0 +EDGE2 9475 7276 -0.0529586 0.974737 1.5787 1 0 1 1 0 0 +EDGE2 9476 7277 1.02569 -0.00903753 -0.0160442 1 0 1 1 0 0 +EDGE2 9476 7315 -1.02215 -0.0467302 -1.56919 1 0 1 1 0 0 +EDGE2 9476 9475 -0.975144 -0.00986321 -1.55588 1 0 1 1 0 0 +EDGE2 9476 7355 -1.02382 0.016936 -1.56046 1 0 1 1 0 0 +EDGE2 9476 7435 -0.979201 0.114443 1.55498 1 0 1 1 0 0 +EDGE2 9476 7335 -1.07177 0.0128595 -1.56451 1 0 1 1 0 0 +EDGE2 9476 7135 -1.00107 -0.0297109 1.55689 1 0 1 1 0 0 +EDGE2 9476 7255 -0.990452 0.070372 1.57152 1 0 1 1 0 0 +EDGE2 9476 7275 -0.95249 0.117079 1.61351 1 0 1 1 0 0 +EDGE2 9476 7295 -1.08156 -0.092518 -1.57402 1 0 1 1 0 0 +EDGE2 9476 7175 -0.928447 -0.0353435 -1.52343 1 0 1 1 0 0 +EDGE2 9476 7115 -0.906825 0.0117595 1.57328 1 0 1 1 0 0 +EDGE2 9476 7337 1.10246 -0.00630754 -0.0288017 1 0 1 1 0 0 +EDGE2 9476 7296 0.0343121 -0.106659 -0.0163752 1 0 1 1 0 0 +EDGE2 9476 7336 0.0194485 0.00682878 -0.00461994 1 0 1 1 0 0 +EDGE2 9476 7356 -0.0291571 0.0297312 -0.0445066 1 0 1 1 0 0 +EDGE2 9476 7316 0.0955614 0.0082209 0.00325428 1 0 1 1 0 0 +EDGE2 9476 7176 -0.0729363 0.0823962 0.0156604 1 0 1 1 0 0 +EDGE2 9476 7276 0.0552407 -0.0105326 -0.00631736 1 0 1 1 0 0 +EDGE2 9476 7357 1.01676 -0.019306 -0.00991727 1 0 1 1 0 0 +EDGE2 9476 7317 0.899959 -0.0227697 -0.0510171 1 0 1 1 0 0 +EDGE2 9476 7297 1.07145 -0.0944303 0.0215498 1 0 1 1 0 0 +EDGE2 9476 7177 0.967836 -0.0111251 0.0238911 1 0 1 1 0 0 +EDGE2 9477 7277 -0.0384504 0.0117733 -0.00744876 1 0 1 1 0 0 +EDGE2 9477 7337 0.0138563 -0.0293414 0.0417108 1 0 1 1 0 0 +EDGE2 9477 7296 -1.03999 0.062852 -0.000440211 1 0 1 1 0 0 +EDGE2 9477 7336 -1.03963 0.011972 -0.0014631 1 0 1 1 0 0 +EDGE2 9477 7356 -0.997429 0.110053 0.00474383 1 0 1 1 0 0 +EDGE2 9477 9476 -0.851771 0.0262764 0.00448223 1 0 1 1 0 0 +EDGE2 9477 7316 -0.997375 -0.0271344 0.0049965 1 0 1 1 0 0 +EDGE2 9477 7176 -1.16785 0.0365859 -0.0259108 1 0 1 1 0 0 +EDGE2 9477 7276 -1.08818 0.0629742 -0.00672276 1 0 1 1 0 0 +EDGE2 9477 7357 0.0189934 -0.0338585 0.0281604 1 0 1 1 0 0 +EDGE2 9477 7317 0.0878345 0.0268737 -0.0212902 1 0 1 1 0 0 +EDGE2 9477 7297 -0.0126245 -0.0486716 0.0225435 1 0 1 1 0 0 +EDGE2 9477 7298 0.914164 0.0372979 0.023713 1 0 1 1 0 0 +EDGE2 9477 7318 0.982667 -0.0929515 -0.0115554 1 0 1 1 0 0 +EDGE2 9477 7358 0.975871 0.00187891 -0.00303666 1 0 1 1 0 0 +EDGE2 9477 7177 0.0334625 0.0200027 0.000218167 1 0 1 1 0 0 +EDGE2 9477 7338 0.938104 -0.120802 0.0122128 1 0 1 1 0 0 +EDGE2 9477 7178 0.985228 -0.000131255 0.0187986 1 0 1 1 0 0 +EDGE2 9477 7278 0.911412 -0.00906535 -0.0246873 1 0 1 1 0 0 +EDGE2 9478 7277 -0.926758 0.101968 -0.00837193 1 0 1 1 0 0 +EDGE2 9478 7337 -1.00213 -0.0671315 -0.00732749 1 0 1 1 0 0 +EDGE2 9478 9477 -1.04691 -0.00865716 0.00338792 1 0 1 1 0 0 +EDGE2 9478 7357 -0.965661 0.121206 -0.033656 1 0 1 1 0 0 +EDGE2 9478 7317 -1.01836 0.0626574 -0.0144914 1 0 1 1 0 0 +EDGE2 9478 7297 -0.981193 -0.00802348 0.0305303 1 0 1 1 0 0 +EDGE2 9478 7298 0.0818483 0.0589336 -0.0291629 1 0 1 1 0 0 +EDGE2 9478 7318 0.108025 -0.0090739 0.010105 1 0 1 1 0 0 +EDGE2 9478 7358 0.0132354 -0.0207676 0.0273395 1 0 1 1 0 0 +EDGE2 9478 7177 -1.02867 -0.0189112 -0.0435973 1 0 1 1 0 0 +EDGE2 9478 7338 0.0109006 0.139331 -0.036151 1 0 1 1 0 0 +EDGE2 9478 7339 0.929415 0.020752 0.00963741 1 0 1 1 0 0 +EDGE2 9478 7178 -0.00686013 0.0237681 0.0240723 1 0 1 1 0 0 +EDGE2 9478 7278 -0.0179904 -0.0855871 -0.00319147 1 0 1 1 0 0 +EDGE2 9478 7359 0.987067 -0.0489984 -0.00226752 1 0 1 1 0 0 +EDGE2 9478 7279 0.945715 -0.0325264 0.00460451 1 0 1 1 0 0 +EDGE2 9478 7299 1.0032 -0.0951051 -0.00404009 1 0 1 1 0 0 +EDGE2 9478 7319 0.89953 0.0370746 -0.0186208 1 0 1 1 0 0 +EDGE2 9478 7179 0.980756 0.0441473 -0.00393545 1 0 1 1 0 0 +EDGE2 9479 7298 -0.968527 -0.00898291 0.00849004 1 0 1 1 0 0 +EDGE2 9479 7318 -1.00057 -0.0284043 0.0194858 1 0 1 1 0 0 +EDGE2 9479 7358 -0.917318 0.098506 -0.0131439 1 0 1 1 0 0 +EDGE2 9479 9478 -1.03849 -0.105263 -0.0198692 1 0 1 1 0 0 +EDGE2 9479 7338 -1.03479 -0.042381 -0.0208992 1 0 1 1 0 0 +EDGE2 9479 7339 -0.0162553 -0.0218023 -0.0102335 1 0 1 1 0 0 +EDGE2 9479 7178 -0.919406 0.00981585 -0.00483908 1 0 1 1 0 0 +EDGE2 9479 7278 -0.975017 -0.0105604 0.0208535 1 0 1 1 0 0 +EDGE2 9479 7359 0.00506238 -0.0501299 0.00538812 1 0 1 1 0 0 +EDGE2 9479 7279 0.0309852 -0.0859259 -0.0321751 1 0 1 1 0 0 +EDGE2 9479 7299 0.0420223 0.00312106 -0.010945 1 0 1 1 0 0 +EDGE2 9479 7319 -0.00764693 0.0137404 -0.00670702 1 0 1 1 0 0 +EDGE2 9479 7179 -0.069623 0.134318 -0.00127939 1 0 1 1 0 0 +EDGE2 9479 7320 1.03596 -0.0774962 0.00417845 1 0 1 1 0 0 +EDGE2 9479 7360 1.03004 0.0491844 0.0140538 1 0 1 1 0 0 +EDGE2 9479 7900 1.02419 -0.0806474 -3.15481 1 0 1 1 0 0 +EDGE2 9479 7920 0.918882 0.00914794 -3.14372 1 0 1 1 0 0 +EDGE2 9479 7340 0.97864 -0.000152338 -0.00285 1 0 1 1 0 0 +EDGE2 9479 7180 0.981262 0.0126419 -0.0101736 1 0 1 1 0 0 +EDGE2 9479 7280 1.00352 -0.0567829 -0.0127036 1 0 1 1 0 0 +EDGE2 9479 7300 0.964665 -0.0392714 -0.0144685 1 0 1 1 0 0 +EDGE2 9480 7341 -0.0441427 0.965207 1.57092 1 0 1 1 0 0 +EDGE2 9480 7339 -0.996497 -0.043009 0.0149153 1 0 1 1 0 0 +EDGE2 9480 9479 -0.975898 -0.0989075 0.0127558 1 0 1 1 0 0 +EDGE2 9480 7359 -1.05762 0.0214956 0.00622004 1 0 1 1 0 0 +EDGE2 9480 7279 -0.962999 0.00671105 -0.013481 1 0 1 1 0 0 +EDGE2 9480 7299 -0.985442 0.0013405 0.0177738 1 0 1 1 0 0 +EDGE2 9480 7319 -0.950767 0.00868533 0.0037235 1 0 1 1 0 0 +EDGE2 9480 7179 -0.996837 0.0441561 0.0191009 1 0 1 1 0 0 +EDGE2 9480 7921 0.0740456 1.01812 1.57348 1 0 1 1 0 0 +EDGE2 9480 7361 -0.0396429 0.992347 1.59088 1 0 1 1 0 0 +EDGE2 9480 7919 1.11234 -0.0719029 -3.14964 1 0 1 1 0 0 +EDGE2 9480 7320 0.00574594 -0.0629468 -0.0046487 1 0 1 1 0 0 +EDGE2 9480 7281 0.060499 1.01556 1.53609 1 0 1 1 0 0 +EDGE2 9480 7301 -0.0179198 0.914898 1.57538 1 0 1 1 0 0 +EDGE2 9480 7321 -0.0067169 1.07946 1.55552 1 0 1 1 0 0 +EDGE2 9480 7181 0.0429921 1.04411 1.59321 1 0 1 1 0 0 +EDGE2 9480 7360 0.0649422 0.0693792 0.0202554 1 0 1 1 0 0 +EDGE2 9480 7900 -0.0270707 0.0287959 -3.14071 1 0 1 1 0 0 +EDGE2 9480 7920 -0.0237192 0.0943738 -3.10578 1 0 1 1 0 0 +EDGE2 9480 7340 0.0240943 -0.0691728 -0.0237974 1 0 1 1 0 0 +EDGE2 9480 7901 0.0309389 -0.985423 -1.56937 1 0 1 1 0 0 +EDGE2 9480 7180 -0.0866681 0.00727133 0.00556501 1 0 1 1 0 0 +EDGE2 9480 7280 0.00989001 0.0279517 0.0065809 1 0 1 1 0 0 +EDGE2 9480 7300 -0.0317166 0.0700574 0.0122327 1 0 1 1 0 0 +EDGE2 9480 7899 1.00617 -0.0344031 -3.15722 1 0 1 1 0 0 +EDGE2 9481 7320 -1.04419 -0.0572001 1.55889 1 0 1 1 0 0 +EDGE2 9481 9480 -0.943662 -0.0448881 1.5494 1 0 1 1 0 0 +EDGE2 9481 7360 -0.965362 0.0255411 1.57582 1 0 1 1 0 0 +EDGE2 9481 7900 -1.08902 0.113055 -1.5711 1 0 1 1 0 0 +EDGE2 9481 7920 -1.00055 0.0868511 -1.54631 1 0 1 1 0 0 +EDGE2 9481 7340 -1.00171 -0.0111661 1.5928 1 0 1 1 0 0 +EDGE2 9481 7901 0.0433036 -0.00731059 0.0242706 1 0 1 1 0 0 +EDGE2 9481 7180 -0.948348 0.0131351 1.54346 1 0 1 1 0 0 +EDGE2 9481 7280 -1.00128 0.0410121 1.55839 1 0 1 1 0 0 +EDGE2 9481 7300 -1.09793 0.010327 1.5786 1 0 1 1 0 0 +EDGE2 9481 7902 0.966006 -0.0114527 -0.0278644 1 0 1 1 0 0 +EDGE2 9482 7901 -0.946257 0.0203994 0.00425455 1 0 1 1 0 0 +EDGE2 9482 9481 -1.04593 0.00551216 0.0307967 1 0 1 1 0 0 +EDGE2 9482 7902 0.0361883 -0.0328732 0.0113536 1 0 1 1 0 0 +EDGE2 9482 7903 1.03548 0.0638497 -0.00814484 1 0 1 1 0 0 +EDGE2 9483 7902 -0.941334 -0.0337424 -0.0180043 1 0 1 1 0 0 +EDGE2 9483 9482 -0.939903 0.0488256 -0.00766293 1 0 1 1 0 0 +EDGE2 9483 7903 0.0272496 0.0114022 0.0170572 1 0 1 1 0 0 +EDGE2 9483 7904 1.04189 -0.0379858 -0.00450378 1 0 1 1 0 0 +EDGE2 9484 9483 -1.04611 -0.0319723 -0.0172937 1 0 1 1 0 0 +EDGE2 9484 7903 -1.04574 0.0426726 -0.000325565 1 0 1 1 0 0 +EDGE2 9484 7904 -0.0596845 -0.0333682 -0.0220042 1 0 1 1 0 0 +EDGE2 9484 7865 1.02022 -0.00681414 -3.16163 1 0 1 1 0 0 +EDGE2 9484 7885 0.922911 0.0376729 -3.15213 1 0 1 1 0 0 +EDGE2 9484 7905 1.01621 0.0895715 0.0136744 1 0 1 1 0 0 +EDGE2 9484 7245 0.970176 -0.072206 -3.13834 1 0 1 1 0 0 +EDGE2 9485 9484 -1.00933 -0.0627255 -0.0109464 1 0 1 1 0 0 +EDGE2 9485 7244 0.979792 -0.050801 -3.09661 1 0 1 1 0 0 +EDGE2 9485 7884 0.978371 -0.0138939 -3.15223 1 0 1 1 0 0 +EDGE2 9485 7246 0.0143285 -1.13231 -1.55729 1 0 1 1 0 0 +EDGE2 9485 7866 -0.00728674 -1.02694 -1.57903 1 0 1 1 0 0 +EDGE2 9485 7904 -0.993127 0.0759678 -0.0131907 1 0 1 1 0 0 +EDGE2 9485 7865 0.00980305 0.0234086 -3.13509 1 0 1 1 0 0 +EDGE2 9485 7885 0.0446875 -0.0718981 -3.12119 1 0 1 1 0 0 +EDGE2 9485 7905 0.0271743 -0.0259572 0.00694753 1 0 1 1 0 0 +EDGE2 9485 7245 -0.0447881 0.0509759 -3.10527 1 0 1 1 0 0 +EDGE2 9485 7864 1.00234 -0.0536131 -3.11659 1 0 1 1 0 0 +EDGE2 9485 7886 -0.057 0.940829 1.56848 1 0 1 1 0 0 +EDGE2 9485 7906 0.097799 0.96283 1.55259 1 0 1 1 0 0 +EDGE2 9486 7247 1.07736 0.0261652 -0.0239997 1 0 1 1 0 0 +EDGE2 9486 7867 1.02546 0.106867 0.0249611 1 0 1 1 0 0 +EDGE2 9486 9485 -0.972656 0.0346519 1.60248 1 0 1 1 0 0 +EDGE2 9486 7246 0.0706952 0.00687165 -0.0119532 1 0 1 1 0 0 +EDGE2 9486 7866 0.0190398 0.0488828 0.0136662 1 0 1 1 0 0 +EDGE2 9486 7865 -0.986619 -0.0729123 -1.58235 1 0 1 1 0 0 +EDGE2 9486 7885 -0.977071 0.0688614 -1.57294 1 0 1 1 0 0 +EDGE2 9486 7905 -1.00933 -0.0469202 1.5924 1 0 1 1 0 0 +EDGE2 9486 7245 -0.934964 0.00881727 -1.55462 1 0 1 1 0 0 +EDGE2 9487 7248 1.04794 -0.0502368 -0.00502264 1 0 1 1 0 0 +EDGE2 9487 7868 0.966861 0.0105335 -0.00357537 1 0 1 1 0 0 +EDGE2 9487 7247 -0.123679 0.0557698 0.028036 1 0 1 1 0 0 +EDGE2 9487 7867 -0.013211 0.00164876 -0.00755568 1 0 1 1 0 0 +EDGE2 9487 7246 -0.929549 -0.0900064 0.00333821 1 0 1 1 0 0 +EDGE2 9487 7866 -1.02966 -0.0397955 0.0180572 1 0 1 1 0 0 +EDGE2 9487 9486 -0.892059 0.0587262 0.00425549 1 0 1 1 0 0 +EDGE2 9488 7249 1.01437 -0.0340763 0.000965929 1 0 1 1 0 0 +EDGE2 9488 7869 1.02606 -0.0231981 0.0086676 1 0 1 1 0 0 +EDGE2 9488 7248 -0.0656427 0.0893677 0.00595372 1 0 1 1 0 0 +EDGE2 9488 7868 0.109964 0.0868517 0.0212106 1 0 1 1 0 0 +EDGE2 9488 7247 -1.05195 0.045739 -0.0249496 1 0 1 1 0 0 +EDGE2 9488 7867 -1.13976 0.0461003 0.0257606 1 0 1 1 0 0 +EDGE2 9488 9487 -0.965413 0.0956492 -0.00893012 1 0 1 1 0 0 +EDGE2 9489 7250 1.02837 0.035424 -0.0221621 1 0 1 1 0 0 +EDGE2 9489 7430 1.0337 -0.0506727 -3.15893 1 0 1 1 0 0 +EDGE2 9489 7870 0.934658 0.0679641 -0.0102784 1 0 1 1 0 0 +EDGE2 9489 7270 1.00981 -0.114544 -3.17682 1 0 1 1 0 0 +EDGE2 9489 7110 1.02542 0.0970075 -3.14419 1 0 1 1 0 0 +EDGE2 9489 7130 0.971616 -0.028669 -3.10383 1 0 1 1 0 0 +EDGE2 9489 7249 -0.000697262 0.0433622 0.025748 1 0 1 1 0 0 +EDGE2 9489 7869 -0.0276971 -0.0854045 -0.0148534 1 0 1 1 0 0 +EDGE2 9489 7248 -1.08313 0.00644869 -0.00749449 1 0 1 1 0 0 +EDGE2 9489 7868 -0.973538 -0.0265227 -0.0421956 1 0 1 1 0 0 +EDGE2 9489 9488 -0.917137 0.0265293 0.0212507 1 0 1 1 0 0 +EDGE2 9490 7131 -0.00804581 -0.95308 -1.56636 1 0 1 1 0 0 +EDGE2 9490 7271 -0.037838 -0.985483 -1.55031 1 0 1 1 0 0 +EDGE2 9490 7431 -0.0243143 -1.01002 -1.57985 1 0 1 1 0 0 +EDGE2 9490 7251 -0.0636202 -0.976628 -1.61552 1 0 1 1 0 0 +EDGE2 9490 7111 0.0206953 -0.948287 -1.56914 1 0 1 1 0 0 +EDGE2 9490 7129 1.05842 -0.0109227 -3.12806 1 0 1 1 0 0 +EDGE2 9490 7269 1.04813 -0.0955416 -3.12448 1 0 1 1 0 0 +EDGE2 9490 7429 0.8744 0.0476811 -3.1226 1 0 1 1 0 0 +EDGE2 9490 7109 0.921695 -0.0308944 -3.1444 1 0 1 1 0 0 +EDGE2 9490 7250 -0.000326367 -0.00143994 0.0205749 1 0 1 1 0 0 +EDGE2 9490 7430 0.0109489 0.109292 -3.12449 1 0 1 1 0 0 +EDGE2 9490 7870 -0.0131916 0.0545479 0.0140977 1 0 1 1 0 0 +EDGE2 9490 7270 0.0356693 -0.00651856 -3.12949 1 0 1 1 0 0 +EDGE2 9490 7110 0.0134038 0.0063899 -3.11702 1 0 1 1 0 0 +EDGE2 9490 7130 0.0378336 0.0329698 -3.1527 1 0 1 1 0 0 +EDGE2 9490 7871 0.0421953 0.999509 1.56997 1 0 1 1 0 0 +EDGE2 9490 9489 -0.915294 0.0350807 -0.0132569 1 0 1 1 0 0 +EDGE2 9490 7249 -0.890697 0.0206024 0.00855847 1 0 1 1 0 0 +EDGE2 9490 7869 -1.01146 -0.0338706 -0.00585731 1 0 1 1 0 0 +EDGE2 9491 7250 -0.999424 0.0711893 -1.56704 1 0 1 1 0 0 +EDGE2 9491 7430 -0.956637 0.0239022 1.57047 1 0 1 1 0 0 +EDGE2 9491 7870 -0.971257 -0.00369621 -1.55608 1 0 1 1 0 0 +EDGE2 9491 9490 -1.02376 0.0724763 -1.5534 1 0 1 1 0 0 +EDGE2 9491 7270 -0.994558 0.0389477 1.57508 1 0 1 1 0 0 +EDGE2 9491 7110 -0.943459 -0.00740579 1.54559 1 0 1 1 0 0 +EDGE2 9491 7130 -1.03285 0.0432111 1.58087 1 0 1 1 0 0 +EDGE2 9491 7871 -0.0222091 0.0164687 -0.0241679 1 0 1 1 0 0 +EDGE2 9491 7872 1.0341 0.0363943 -0.0129306 1 0 1 1 0 0 +EDGE2 9492 9491 -0.946144 0.00165818 -0.010685 1 0 1 1 0 0 +EDGE2 9492 7871 -1.00036 0.010907 0.0128347 1 0 1 1 0 0 +EDGE2 9492 7872 -0.0496387 -0.092806 -0.000487931 1 0 1 1 0 0 +EDGE2 9492 7873 1.00026 -0.0171693 -0.00371639 1 0 1 1 0 0 +EDGE2 9493 9492 -1.07417 0.0136527 0.0460846 1 0 1 1 0 0 +EDGE2 9493 7872 -1.02683 -0.0343465 -0.0225513 1 0 1 1 0 0 +EDGE2 9493 7873 0.020449 -0.016163 0.0191847 1 0 1 1 0 0 +EDGE2 9493 7874 0.953105 0.0649196 0.0199347 1 0 1 1 0 0 +EDGE2 9494 7855 0.984263 0.0308262 -3.14555 1 0 1 1 0 0 +EDGE2 9494 9493 -0.94218 -0.0959759 0.00940408 1 0 1 1 0 0 +EDGE2 9494 7873 -0.981755 0.0295845 0.0310449 1 0 1 1 0 0 +EDGE2 9494 7874 0.0554083 -0.0225044 -0.0202571 1 0 1 1 0 0 +EDGE2 9494 7875 1.03827 0.0569507 -0.00261074 1 0 1 1 0 0 +EDGE2 9494 7055 1.06676 0.0288615 -3.11386 1 0 1 1 0 0 +EDGE2 9494 7815 1.00474 -0.0315276 -3.13872 1 0 1 1 0 0 +EDGE2 9494 7835 0.988888 -0.0426373 -3.15581 1 0 1 1 0 0 +EDGE2 9495 7855 0.0562242 0.0575005 -3.17583 1 0 1 1 0 0 +EDGE2 9495 7836 -0.0504668 -0.981983 -1.58002 1 0 1 1 0 0 +EDGE2 9495 7056 -0.0966165 -1.03934 -1.57512 1 0 1 1 0 0 +EDGE2 9495 7816 0.0207944 -1.00343 -1.56289 1 0 1 1 0 0 +EDGE2 9495 9494 -1.09514 -0.0661638 0.019577 1 0 1 1 0 0 +EDGE2 9495 7874 -0.994834 0.0442886 -0.0159938 1 0 1 1 0 0 +EDGE2 9495 7875 0.104287 0.0474709 0.00298423 1 0 1 1 0 0 +EDGE2 9495 7834 0.951922 0.0623407 -3.15221 1 0 1 1 0 0 +EDGE2 9495 7055 0.0398168 0.0628359 -3.14545 1 0 1 1 0 0 +EDGE2 9495 7815 0.0102787 0.094667 -3.15865 1 0 1 1 0 0 +EDGE2 9495 7835 -0.120055 0.0254294 -3.14732 1 0 1 1 0 0 +EDGE2 9495 7854 1.01554 0.021053 -3.13729 1 0 1 1 0 0 +EDGE2 9495 7054 0.909507 -0.0110241 -3.0987 1 0 1 1 0 0 +EDGE2 9495 7814 0.947518 0.0634268 -3.14414 1 0 1 1 0 0 +EDGE2 9495 7876 -0.10549 1.01231 1.57515 1 0 1 1 0 0 +EDGE2 9495 7856 0.016048 1.00007 1.58217 1 0 1 1 0 0 +EDGE2 9496 7855 -1.06676 0.00235378 -1.574 1 0 1 1 0 0 +EDGE2 9496 7057 0.992205 0.014462 -0.0300855 1 0 1 1 0 0 +EDGE2 9496 7837 1.05326 -0.0127535 0.00114976 1 0 1 1 0 0 +EDGE2 9496 7817 0.947937 -0.0229203 0.00282185 1 0 1 1 0 0 +EDGE2 9496 7836 0.00960794 -0.0156115 0.0173681 1 0 1 1 0 0 +EDGE2 9496 7056 -0.0367993 0.0736834 -0.0388013 1 0 1 1 0 0 +EDGE2 9496 7816 -0.0933358 0.0178199 -0.00407269 1 0 1 1 0 0 +EDGE2 9496 9495 -1.03652 -0.00372124 1.55179 1 0 1 1 0 0 +EDGE2 9496 7875 -0.964177 0.0437095 1.54506 1 0 1 1 0 0 +EDGE2 9496 7055 -1.09857 0.0246257 -1.56175 1 0 1 1 0 0 +EDGE2 9496 7815 -0.957953 -0.0617921 -1.57794 1 0 1 1 0 0 +EDGE2 9496 7835 -0.968717 -0.0357136 -1.55676 1 0 1 1 0 0 +EDGE2 9497 7818 0.975604 -0.0499362 0.000725597 1 0 1 1 0 0 +EDGE2 9497 7838 0.91629 -0.082881 0.00912648 1 0 1 1 0 0 +EDGE2 9497 7058 0.964786 0.0599563 0.00755218 1 0 1 1 0 0 +EDGE2 9497 9496 -0.967538 0.025191 -0.0358999 1 0 1 1 0 0 +EDGE2 9497 7057 -0.0621709 0.0818967 0.0124715 1 0 1 1 0 0 +EDGE2 9497 7837 -0.0995131 0.00290072 -0.0282722 1 0 1 1 0 0 +EDGE2 9497 7817 -0.0117606 -0.0135415 0.0075843 1 0 1 1 0 0 +EDGE2 9497 7836 -1.01484 -0.0770161 0.00275109 1 0 1 1 0 0 +EDGE2 9497 7056 -0.865975 0.0792268 -0.0120148 1 0 1 1 0 0 +EDGE2 9497 7816 -0.951879 -0.00731108 0.000103331 1 0 1 1 0 0 +EDGE2 9498 7818 0.00932121 -0.0148739 0.00223941 1 0 1 1 0 0 +EDGE2 9498 7059 1.02002 0.0285266 -0.0138064 1 0 1 1 0 0 +EDGE2 9498 7819 0.985774 -0.0216736 0.00138428 1 0 1 1 0 0 +EDGE2 9498 7839 0.982033 -0.0688228 -0.0172582 1 0 1 1 0 0 +EDGE2 9498 7838 0.0515074 0.0227075 0.0268503 1 0 1 1 0 0 +EDGE2 9498 7058 -0.0153509 -0.0595359 -0.0132111 1 0 1 1 0 0 +EDGE2 9498 7057 -1.02643 0.0177467 0.0247249 1 0 1 1 0 0 +EDGE2 9498 7837 -0.984426 0.0544081 0.0338655 1 0 1 1 0 0 +EDGE2 9498 9497 -1.08758 0.0980064 0.00859993 1 0 1 1 0 0 +EDGE2 9498 7817 -1.01044 0.158729 -0.0194511 1 0 1 1 0 0 +EDGE2 9499 7060 0.972146 0.0903499 0.027477 1 0 1 1 0 0 +EDGE2 9499 7820 0.956287 -0.0275627 -0.00593308 1 0 1 1 0 0 +EDGE2 9499 7840 0.981239 -0.038223 0.0204728 1 0 1 1 0 0 +EDGE2 9499 7100 1.01978 0.0340521 -3.15969 1 0 1 1 0 0 +EDGE2 9499 7818 -1.00703 0.0146768 0.030804 1 0 1 1 0 0 +EDGE2 9499 7059 -0.000244835 0.0159981 0.00541682 1 0 1 1 0 0 +EDGE2 9499 7819 -0.0302229 -0.000741611 0.00346942 1 0 1 1 0 0 +EDGE2 9499 7839 0.104752 -0.0349128 0.0241176 1 0 1 1 0 0 +EDGE2 9499 9498 -0.959948 0.0395488 0.00889341 1 0 1 1 0 0 +EDGE2 9499 7838 -0.981222 0.0258177 -0.056118 1 0 1 1 0 0 +EDGE2 9499 7058 -0.994571 -0.0185578 -0.0228309 1 0 1 1 0 0 +EDGE2 9500 7099 1.03 -0.0325065 -3.1738 1 0 1 1 0 0 +EDGE2 9500 7061 -0.0480411 -0.988141 -1.57722 1 0 1 1 0 0 +EDGE2 9500 7101 -0.0610203 -0.937414 -1.60189 1 0 1 1 0 0 +EDGE2 9500 7060 -0.0300892 0.0496551 -0.031982 1 0 1 1 0 0 +EDGE2 9500 7820 0.0253904 0.101307 -0.00852629 1 0 1 1 0 0 +EDGE2 9500 7840 0.000330834 0.118618 -0.00428987 1 0 1 1 0 0 +EDGE2 9500 7100 0.00128908 0.110498 -3.15386 1 0 1 1 0 0 +EDGE2 9500 7841 -0.0440291 0.960557 1.61137 1 0 1 1 0 0 +EDGE2 9500 7821 -0.013356 1.06823 1.5554 1 0 1 1 0 0 +EDGE2 9500 9499 -0.96336 0.0807933 0.0117669 1 0 1 1 0 0 +EDGE2 9500 7059 -1.0173 0.0626221 -0.0315999 1 0 1 1 0 0 +EDGE2 9500 7819 -1.0665 0.050895 -0.0103214 1 0 1 1 0 0 +EDGE2 9500 7839 -0.936327 -0.0496119 0.0086677 1 0 1 1 0 0 +EDGE2 9501 7060 -1.00411 -0.0291407 -1.57285 1 0 1 1 0 0 +EDGE2 9501 7820 -1.01772 0.0102791 -1.58693 1 0 1 1 0 0 +EDGE2 9501 7840 -1.01565 -0.0569662 -1.54888 1 0 1 1 0 0 +EDGE2 9501 9500 -1.01334 -0.0121324 -1.55113 1 0 1 1 0 0 +EDGE2 9501 7100 -0.968524 0.0218698 1.59587 1 0 1 1 0 0 +EDGE2 9501 7841 -0.00650213 -0.029157 0.00987987 1 0 1 1 0 0 +EDGE2 9501 7821 0.0959974 -0.114953 0.0348925 1 0 1 1 0 0 +EDGE2 9501 7822 1.04726 -0.036089 -0.00960863 1 0 1 1 0 0 +EDGE2 9501 7842 0.924837 0.00157623 -0.000803742 1 0 1 1 0 0 +EDGE2 9502 7841 -1.06319 -0.0236773 0.0268026 1 0 1 1 0 0 +EDGE2 9502 9501 -1.00773 0.0330907 -0.0290488 1 0 1 1 0 0 +EDGE2 9502 7821 -0.974769 -0.0371389 0.000182483 1 0 1 1 0 0 +EDGE2 9502 7823 1.03342 0.00403998 0.00210564 1 0 1 1 0 0 +EDGE2 9502 7822 -0.0679551 0.00853112 0.00852413 1 0 1 1 0 0 +EDGE2 9502 7842 -0.00132253 0.0799059 0.00103933 1 0 1 1 0 0 +EDGE2 9502 7843 0.982665 0.0362862 -0.0134403 1 0 1 1 0 0 +EDGE2 9503 9502 -0.968152 -0.0168866 0.00214353 1 0 1 1 0 0 +EDGE2 9503 7823 0.0282447 0.0346922 -0.0004293 1 0 1 1 0 0 +EDGE2 9503 7822 -0.994038 0.0510472 0.00849396 1 0 1 1 0 0 +EDGE2 9503 7842 -1.10494 0.0671725 -0.0067489 1 0 1 1 0 0 +EDGE2 9503 7843 -0.0344339 -0.0144939 0.0287122 1 0 1 1 0 0 +EDGE2 9503 7824 1.03036 -0.0536657 0.0112336 1 0 1 1 0 0 +EDGE2 9503 7844 0.926032 0.0106025 0.0145644 1 0 1 1 0 0 +EDGE2 9504 7823 -0.987877 0.00233034 -0.0298213 1 0 1 1 0 0 +EDGE2 9504 9503 -1.00459 0.141131 -0.0367658 1 0 1 1 0 0 +EDGE2 9504 7843 -0.886972 -0.0358773 0.0108734 1 0 1 1 0 0 +EDGE2 9504 7845 1.02916 0.00527336 0.0500702 1 0 1 1 0 0 +EDGE2 9504 7824 -0.0570755 -0.0482634 -0.0149141 1 0 1 1 0 0 +EDGE2 9504 7844 -0.000493535 0.0431446 -0.0206954 1 0 1 1 0 0 +EDGE2 9504 7805 0.99045 -0.0174541 -3.14429 1 0 1 1 0 0 +EDGE2 9504 7825 1.02727 -0.0448345 -0.000954718 1 0 1 1 0 0 +EDGE2 9505 9504 -0.935743 -0.0344781 0.0156044 1 0 1 1 0 0 +EDGE2 9505 7845 0.0159615 -0.0728716 -0.00880668 1 0 1 1 0 0 +EDGE2 9505 7824 -0.983856 0.0200948 -0.0396458 1 0 1 1 0 0 +EDGE2 9505 7844 -1.05911 -0.000341897 0.0192728 1 0 1 1 0 0 +EDGE2 9505 7805 -0.00615734 -0.0543649 -3.14369 1 0 1 1 0 0 +EDGE2 9505 7825 0.0112687 -0.068894 -0.0108928 1 0 1 1 0 0 +EDGE2 9505 7804 0.925695 0.0250724 -3.13134 1 0 1 1 0 0 +EDGE2 9505 7826 0.0303223 1.08336 1.5727 1 0 1 1 0 0 +EDGE2 9505 7846 0.0102538 0.92657 1.5663 1 0 1 1 0 0 +EDGE2 9505 7806 -0.00885344 1.01166 1.55835 1 0 1 1 0 0 +EDGE2 9506 7845 -1.0718 -0.119265 1.58975 1 0 1 1 0 0 +EDGE2 9506 9505 -1.05531 -0.050435 1.55752 1 0 1 1 0 0 +EDGE2 9506 7805 -0.96192 0.00541337 -1.5472 1 0 1 1 0 0 +EDGE2 9506 7825 -1.02935 0.000646385 1.53846 1 0 1 1 0 0 +EDGE2 9507 9506 -0.921947 0.0405792 0.0163786 1 0 1 1 0 0 +EDGE2 9508 9507 -1.06739 -0.0143994 0.0434192 1 0 1 1 0 0 +EDGE2 9509 9508 -1.1025 -0.0213034 -0.00691783 1 0 1 1 0 0 +EDGE2 9510 9509 -0.991289 0.00312938 0.00687947 1 0 1 1 0 0 +EDGE2 9511 9510 -1.01396 -0.0329174 -1.58546 1 0 1 1 0 0 +EDGE2 9512 9511 -0.96784 0.0142564 0.0120507 1 0 1 1 0 0 +EDGE2 9513 9512 -1.01864 0.0800406 0.00398782 1 0 1 1 0 0 +EDGE2 9514 9513 -0.976977 0.0483546 -0.0536538 1 0 1 1 0 0 +EDGE2 9515 9514 -1.03058 -0.0425404 -0.0302019 1 0 1 1 0 0 +EDGE2 9516 9515 -1.06051 0.00610688 -1.54371 1 0 1 1 0 0 +EDGE2 9517 9516 -0.946931 0.0146123 0.0246509 1 0 1 1 0 0 +EDGE2 9518 9517 -0.947381 0.00690883 -0.0186174 1 0 1 1 0 0 +EDGE2 9519 9518 -1.05731 0.0905995 -0.0030465 1 0 1 1 0 0 +EDGE2 9519 7800 0.993227 -0.0414609 -3.13538 1 0 1 1 0 0 +EDGE2 9520 9519 -0.952685 -0.00343565 -0.00572153 1 0 1 1 0 0 +EDGE2 9520 7801 0.0164717 1.02591 1.55898 1 0 1 1 0 0 +EDGE2 9520 7800 -0.00959868 0.0988995 -3.14052 1 0 1 1 0 0 +EDGE2 9520 7799 1.04302 -0.00781712 -3.12728 1 0 1 1 0 0 +EDGE2 9521 7802 0.967873 -0.00482119 0.0340888 1 0 1 1 0 0 +EDGE2 9521 7801 -0.0760322 -0.0601542 0.0168878 1 0 1 1 0 0 +EDGE2 9521 7800 -1.07666 0.119775 1.59683 1 0 1 1 0 0 +EDGE2 9521 9520 -1.00086 -0.0838209 -1.58679 1 0 1 1 0 0 +EDGE2 9522 7803 1.06037 -0.0586061 0.017417 1 0 1 1 0 0 +EDGE2 9522 9521 -0.961226 -0.00778085 -0.0175242 1 0 1 1 0 0 +EDGE2 9522 7802 0.00415522 0.0229757 -0.0247125 1 0 1 1 0 0 +EDGE2 9522 7801 -1.00976 -0.0768768 0.00249168 1 0 1 1 0 0 +EDGE2 9523 7804 1.01531 0.0368229 -0.00355196 1 0 1 1 0 0 +EDGE2 9523 7803 0.0999784 0.01049 -0.0137119 1 0 1 1 0 0 +EDGE2 9523 7802 -1.07682 0.0290144 0.000888863 1 0 1 1 0 0 +EDGE2 9523 9522 -1.01092 -0.0198097 0.00324729 1 0 1 1 0 0 +EDGE2 9524 7845 1.00054 -0.0204426 -3.12736 1 0 1 1 0 0 +EDGE2 9524 9505 0.977935 0.098735 -3.13982 1 0 1 1 0 0 +EDGE2 9524 7805 0.998343 -0.017862 0.00593994 1 0 1 1 0 0 +EDGE2 9524 7825 1.07547 -0.129134 -3.1364 1 0 1 1 0 0 +EDGE2 9524 7804 -0.0976593 0.0115913 0.0222949 1 0 1 1 0 0 +EDGE2 9524 7803 -1.09685 -0.0327698 -0.0194783 1 0 1 1 0 0 +EDGE2 9524 9523 -0.976082 -0.0387262 -0.0215151 1 0 1 1 0 0 +EDGE2 9525 9506 -0.00779844 0.927859 1.58787 1 0 1 1 0 0 +EDGE2 9525 9504 1.05082 -0.0109451 -3.15557 1 0 1 1 0 0 +EDGE2 9525 7845 -0.0515366 -0.0399006 -3.12982 1 0 1 1 0 0 +EDGE2 9525 7824 0.985905 -0.057746 -3.15436 1 0 1 1 0 0 +EDGE2 9525 7844 1.00897 -0.0742616 -3.13356 1 0 1 1 0 0 +EDGE2 9525 9505 -0.103358 0.0738552 -3.14587 1 0 1 1 0 0 +EDGE2 9525 9524 -1.00586 -0.0333045 -0.00508354 1 0 1 1 0 0 +EDGE2 9525 7805 -0.110124 -0.0155459 0.0217094 1 0 1 1 0 0 +EDGE2 9525 7825 0.0456535 0.014388 -3.14962 1 0 1 1 0 0 +EDGE2 9525 7804 -0.992198 0.0488576 0.00489708 1 0 1 1 0 0 +EDGE2 9525 7826 0.00774767 -1.04407 -1.56021 1 0 1 1 0 0 +EDGE2 9525 7846 0.00922762 -1.06358 -1.55234 1 0 1 1 0 0 +EDGE2 9525 7806 0.0172753 -1.0332 -1.56963 1 0 1 1 0 0 +EDGE2 9526 7807 1.12939 0.0294425 -0.0398067 1 0 1 1 0 0 +EDGE2 9526 7845 -1.04059 0.0915469 -1.57305 1 0 1 1 0 0 +EDGE2 9526 9525 -0.998899 0.0522898 1.54721 1 0 1 1 0 0 +EDGE2 9526 9505 -1.03514 -0.0521467 -1.57852 1 0 1 1 0 0 +EDGE2 9526 7805 -0.953235 0.0901898 1.54077 1 0 1 1 0 0 +EDGE2 9526 7825 -1.07475 0.0298211 -1.56515 1 0 1 1 0 0 +EDGE2 9526 7826 0.0277404 0.0389665 -0.00387329 1 0 1 1 0 0 +EDGE2 9526 7846 0.0204996 -0.061253 -0.0115384 1 0 1 1 0 0 +EDGE2 9526 7806 0.000941742 0.0307756 0.0200944 1 0 1 1 0 0 +EDGE2 9526 7847 0.954898 0.00584611 0.0367322 1 0 1 1 0 0 +EDGE2 9526 7827 1.0148 -0.0262707 0.0208159 1 0 1 1 0 0 +EDGE2 9527 7807 0.0481266 -0.0163607 -0.00845334 1 0 1 1 0 0 +EDGE2 9527 7826 -0.954076 0.0306335 0.00261659 1 0 1 1 0 0 +EDGE2 9527 7846 -0.935995 -0.0337094 -0.011651 1 0 1 1 0 0 +EDGE2 9527 9526 -0.996103 0.0378447 -0.0200153 1 0 1 1 0 0 +EDGE2 9527 7806 -1.02721 0.040069 -0.0200364 1 0 1 1 0 0 +EDGE2 9527 7847 -0.0476918 0.0291116 -0.000724784 1 0 1 1 0 0 +EDGE2 9527 7827 0.0357153 -0.0193741 0.0246721 1 0 1 1 0 0 +EDGE2 9527 7828 0.994611 0.118641 0.0171519 1 0 1 1 0 0 +EDGE2 9527 7848 1.0031 0.0260835 0.0252993 1 0 1 1 0 0 +EDGE2 9527 7808 1.0809 0.0284202 -0.0166725 1 0 1 1 0 0 +EDGE2 9528 7807 -1.04132 0.00972665 0.0128681 1 0 1 1 0 0 +EDGE2 9528 7847 -1.00404 0.00235219 0.00398947 1 0 1 1 0 0 +EDGE2 9528 9527 -0.978711 -0.068407 -0.0305969 1 0 1 1 0 0 +EDGE2 9528 7827 -1.07949 0.0720139 -0.0120484 1 0 1 1 0 0 +EDGE2 9528 7829 0.976684 -0.0198399 0.011633 1 0 1 1 0 0 +EDGE2 9528 7828 0.124341 0.0495466 0.00226116 1 0 1 1 0 0 +EDGE2 9528 7848 0.0312718 0.051842 0.0121671 1 0 1 1 0 0 +EDGE2 9528 7808 -0.00178708 0.00172149 -0.0011891 1 0 1 1 0 0 +EDGE2 9528 7849 0.911661 0.108883 0.0123395 1 0 1 1 0 0 +EDGE2 9528 7809 0.971484 0.0185923 0.0202734 1 0 1 1 0 0 +EDGE2 9529 7829 -0.0490061 -0.0360458 0.0102313 1 0 1 1 0 0 +EDGE2 9529 7828 -1.02203 0.0238102 -0.0026342 1 0 1 1 0 0 +EDGE2 9529 7848 -0.923424 -0.0129073 -0.0319069 1 0 1 1 0 0 +EDGE2 9529 9528 -0.981208 0.0102598 0.0452001 1 0 1 1 0 0 +EDGE2 9529 7808 -0.937349 0.0915154 -0.00195266 1 0 1 1 0 0 +EDGE2 9529 7849 0.104711 -0.0353263 -0.00687419 1 0 1 1 0 0 +EDGE2 9529 7809 -0.0322062 0.0392003 -0.0172285 1 0 1 1 0 0 +EDGE2 9529 7770 0.973624 0.0651606 -3.11873 1 0 1 1 0 0 +EDGE2 9529 7810 1.05013 0.0542146 -0.00933411 1 0 1 1 0 0 +EDGE2 9529 7830 0.971958 0.00247078 -0.00369088 1 0 1 1 0 0 +EDGE2 9529 7850 1.00352 -0.0402625 -0.0132711 1 0 1 1 0 0 +EDGE2 9529 7790 0.957435 0.00690737 -3.13773 1 0 1 1 0 0 +EDGE2 9529 7010 1.01195 0.0443995 -3.1458 1 0 1 1 0 0 +EDGE2 9529 7030 1.02726 -0.0316304 -3.15302 1 0 1 1 0 0 +EDGE2 9529 7050 0.997058 -0.134719 -3.14722 1 0 1 1 0 0 +EDGE2 9530 7829 -0.998322 0.0886735 -0.0283158 1 0 1 1 0 0 +EDGE2 9530 9529 -0.954523 -0.0215171 -0.0420467 1 0 1 1 0 0 +EDGE2 9530 7849 -0.956795 0.00195691 -0.00219326 1 0 1 1 0 0 +EDGE2 9530 7809 -0.977213 -0.0258724 -0.00491432 1 0 1 1 0 0 +EDGE2 9530 7811 0.00738441 0.97668 1.57706 1 0 1 1 0 0 +EDGE2 9530 7831 0.0176114 0.947053 1.54885 1 0 1 1 0 0 +EDGE2 9530 7851 -0.0189536 1.00399 1.5855 1 0 1 1 0 0 +EDGE2 9530 7051 0.00341169 1.02996 1.54966 1 0 1 1 0 0 +EDGE2 9530 7770 -0.100383 0.0253617 -3.14605 1 0 1 1 0 0 +EDGE2 9530 7810 0.0131103 0.020855 -0.00827772 1 0 1 1 0 0 +EDGE2 9530 7830 0.025336 -0.0389138 0.0230378 1 0 1 1 0 0 +EDGE2 9530 7850 -0.0487431 -0.0128487 0.0175287 1 0 1 1 0 0 +EDGE2 9530 7790 -0.00299045 -0.0339583 -3.14533 1 0 1 1 0 0 +EDGE2 9530 7769 0.938727 0.045819 -3.15523 1 0 1 1 0 0 +EDGE2 9530 7010 0.0836648 -0.0196622 -3.15831 1 0 1 1 0 0 +EDGE2 9530 7030 0.0992337 0.0832876 -3.13587 1 0 1 1 0 0 +EDGE2 9530 7050 -0.083328 -0.0708537 -3.15481 1 0 1 1 0 0 +EDGE2 9530 7789 0.96234 -0.0150958 -3.15185 1 0 1 1 0 0 +EDGE2 9530 7029 0.949828 0.000954498 -3.12256 1 0 1 1 0 0 +EDGE2 9530 7049 1.03113 -0.0314566 -3.14602 1 0 1 1 0 0 +EDGE2 9530 7009 0.955201 -0.0285693 -3.17041 1 0 1 1 0 0 +EDGE2 9530 7031 -0.0467708 -1.10629 -1.56766 1 0 1 1 0 0 +EDGE2 9530 7771 0.0262466 -0.92286 -1.56838 1 0 1 1 0 0 +EDGE2 9530 7791 -0.0617294 -1.03672 -1.55924 1 0 1 1 0 0 +EDGE2 9530 7011 -0.0319664 -1.05427 -1.53666 1 0 1 1 0 0 +EDGE2 9531 9530 -0.964003 0.0581458 1.54194 1 0 1 1 0 0 +EDGE2 9531 7770 -0.967477 -0.045791 -1.60646 1 0 1 1 0 0 +EDGE2 9531 7810 -0.967409 0.0223063 1.53588 1 0 1 1 0 0 +EDGE2 9531 7830 -1.00958 -0.0541655 1.57381 1 0 1 1 0 0 +EDGE2 9531 7850 -0.924625 -0.0652795 1.5409 1 0 1 1 0 0 +EDGE2 9531 7790 -1.03131 -0.0458331 -1.56997 1 0 1 1 0 0 +EDGE2 9531 7010 -1.01644 -0.0463376 -1.61094 1 0 1 1 0 0 +EDGE2 9531 7030 -1.03516 0.0277529 -1.55265 1 0 1 1 0 0 +EDGE2 9531 7050 -1.00952 0.000318675 -1.58525 1 0 1 1 0 0 +EDGE2 9531 7031 0.121271 0.0209507 0.0104157 1 0 1 1 0 0 +EDGE2 9531 7771 0.0322385 -0.0361852 0.0435325 1 0 1 1 0 0 +EDGE2 9531 7791 0.0493358 -0.0988836 -0.0294946 1 0 1 1 0 0 +EDGE2 9531 7011 -0.0713054 0.0222141 0.0138447 1 0 1 1 0 0 +EDGE2 9531 7032 0.876573 0.0892725 -0.022644 1 0 1 1 0 0 +EDGE2 9531 7772 0.94517 0.0243223 0.00614725 1 0 1 1 0 0 +EDGE2 9531 7792 1.01918 -0.016707 0.0125285 1 0 1 1 0 0 +EDGE2 9531 7012 1.05243 -0.00919812 0.0451424 1 0 1 1 0 0 +EDGE2 9532 9531 -1.00193 -0.0329915 0.00293734 1 0 1 1 0 0 +EDGE2 9532 7031 -1.01261 -0.0384433 0.0148596 1 0 1 1 0 0 +EDGE2 9532 7771 -0.981174 -0.0713691 0.0268546 1 0 1 1 0 0 +EDGE2 9532 7791 -1.03739 0.0515824 -0.00378272 1 0 1 1 0 0 +EDGE2 9532 7011 -0.874144 -0.0655901 -0.00411313 1 0 1 1 0 0 +EDGE2 9532 7032 0.0765759 0.0755496 0.0436347 1 0 1 1 0 0 +EDGE2 9532 7772 0.0406633 0.0818257 0.0199429 1 0 1 1 0 0 +EDGE2 9532 7792 0.0360719 0.0737086 -0.0223755 1 0 1 1 0 0 +EDGE2 9532 7012 -0.0381455 -0.0255527 0.0351874 1 0 1 1 0 0 +EDGE2 9532 7033 1.00938 -0.0198711 0.0283615 1 0 1 1 0 0 +EDGE2 9532 7773 1.01276 -0.0281738 -0.0114907 1 0 1 1 0 0 +EDGE2 9532 7793 0.974623 -0.0126986 0.0125517 1 0 1 1 0 0 +EDGE2 9532 7013 1.00787 -0.0165269 0.0291967 1 0 1 1 0 0 +EDGE2 9533 9532 -0.904984 -0.0205027 0.00130195 1 0 1 1 0 0 +EDGE2 9533 7032 -1.00294 0.0967735 0.00954181 1 0 1 1 0 0 +EDGE2 9533 7772 -0.986101 0.0659458 0.0194048 1 0 1 1 0 0 +EDGE2 9533 7792 -1.05626 -0.0341314 -0.00172198 1 0 1 1 0 0 +EDGE2 9533 7012 -1.03808 -0.13308 -0.0233477 1 0 1 1 0 0 +EDGE2 9533 7033 -0.0866992 -0.019815 0.0162582 1 0 1 1 0 0 +EDGE2 9533 7773 -0.0515229 0.00889225 0.00312342 1 0 1 1 0 0 +EDGE2 9533 7793 -0.0624133 -0.00669295 -0.013623 1 0 1 1 0 0 +EDGE2 9533 7013 0.0340056 -0.0140719 0.0122423 1 0 1 1 0 0 +EDGE2 9533 7034 1.00923 0.0420018 -0.00541654 1 0 1 1 0 0 +EDGE2 9533 7774 1.01084 -0.0140581 -0.0169411 1 0 1 1 0 0 +EDGE2 9533 7794 1.03081 -0.0579377 -0.0218383 1 0 1 1 0 0 +EDGE2 9533 7014 0.969122 0.00278517 -0.00137827 1 0 1 1 0 0 +EDGE2 9534 9533 -1.01584 -0.0239567 -0.0248879 1 0 1 1 0 0 +EDGE2 9534 7033 -0.94608 0.0506375 -0.00652125 1 0 1 1 0 0 +EDGE2 9534 7773 -0.990856 -0.0547542 0.023012 1 0 1 1 0 0 +EDGE2 9534 7793 -1.0214 0.024121 0.00650811 1 0 1 1 0 0 +EDGE2 9534 7013 -0.991129 -0.0157522 -0.012891 1 0 1 1 0 0 +EDGE2 9534 7034 -0.0936406 -0.0831076 -0.00531273 1 0 1 1 0 0 +EDGE2 9534 7774 0.0253318 0.0356265 0.00514238 1 0 1 1 0 0 +EDGE2 9534 7794 0.0206356 0.103579 -0.00392738 1 0 1 1 0 0 +EDGE2 9534 7014 -0.0266221 0.0542165 0.040122 1 0 1 1 0 0 +EDGE2 9534 6995 0.955446 -0.0104431 -3.16586 1 0 1 1 0 0 +EDGE2 9534 7035 0.941443 -0.0674533 -0.0299432 1 0 1 1 0 0 +EDGE2 9534 7775 0.955891 0.039489 -0.0107681 1 0 1 1 0 0 +EDGE2 9534 7795 1.07377 -0.0751718 -0.0097312 1 0 1 1 0 0 +EDGE2 9534 7015 1.07839 -0.0488413 0.0151211 1 0 1 1 0 0 +EDGE2 9535 7796 -0.0698431 -0.920585 -1.57953 1 0 1 1 0 0 +EDGE2 9535 9534 -1.04842 0.056619 0.000203743 1 0 1 1 0 0 +EDGE2 9535 7034 -1.03098 0.0441894 -0.0213285 1 0 1 1 0 0 +EDGE2 9535 7774 -1.00637 -0.0177746 0.00868742 1 0 1 1 0 0 +EDGE2 9535 7794 -1.07542 -0.0271449 0.0106743 1 0 1 1 0 0 +EDGE2 9535 7014 -1.00682 0.11872 0.00486419 1 0 1 1 0 0 +EDGE2 9535 6995 -0.0485344 0.137254 -3.08508 1 0 1 1 0 0 +EDGE2 9535 7035 0.0223567 -0.0147553 0.00809746 1 0 1 1 0 0 +EDGE2 9535 7775 0.012162 0.0522831 -0.0128361 1 0 1 1 0 0 +EDGE2 9535 7795 -0.00935262 -0.0327091 0.0205136 1 0 1 1 0 0 +EDGE2 9535 7015 -0.0358532 0.0318368 -0.0145842 1 0 1 1 0 0 +EDGE2 9535 6994 0.978509 0.109577 -3.13797 1 0 1 1 0 0 +EDGE2 9535 7016 0.0172586 0.930581 1.58651 1 0 1 1 0 0 +EDGE2 9535 7036 0.0102922 0.888878 1.52569 1 0 1 1 0 0 +EDGE2 9535 7776 0.0780422 1.03682 1.5614 1 0 1 1 0 0 +EDGE2 9535 6996 0.071447 0.989919 1.57476 1 0 1 1 0 0 +EDGE2 9536 7797 1.01 0.123935 0.00963581 1 0 1 1 0 0 +EDGE2 9536 7796 -0.0211048 -0.0644907 0.0176495 1 0 1 1 0 0 +EDGE2 9536 9535 -1.01367 0.055701 1.5803 1 0 1 1 0 0 +EDGE2 9536 6995 -0.961698 -0.0231034 -1.56702 1 0 1 1 0 0 +EDGE2 9536 7035 -1.0875 0.0160728 1.57132 1 0 1 1 0 0 +EDGE2 9536 7775 -1.02307 -0.0589877 1.55227 1 0 1 1 0 0 +EDGE2 9536 7795 -0.938324 -0.104811 1.56977 1 0 1 1 0 0 +EDGE2 9536 7015 -0.95781 -0.0779056 1.5788 1 0 1 1 0 0 +EDGE2 9537 7798 0.982534 -0.0951055 0.0210027 1 0 1 1 0 0 +EDGE2 9537 9536 -1.04334 0.143947 -0.0236364 1 0 1 1 0 0 +EDGE2 9537 7797 0.0806773 0.0619163 0.0183288 1 0 1 1 0 0 +EDGE2 9537 7796 -0.982438 -0.0288202 -0.00314893 1 0 1 1 0 0 +EDGE2 9538 7798 0.0213007 -0.046137 0.0232337 1 0 1 1 0 0 +EDGE2 9538 7799 1.01581 -0.0428056 0.0032467 1 0 1 1 0 0 +EDGE2 9538 7797 -0.94008 0.0776767 0.0123546 1 0 1 1 0 0 +EDGE2 9538 9537 -1.01009 -0.0205853 0.00166398 1 0 1 1 0 0 +EDGE2 9539 7800 0.998127 -0.0449388 0.000992216 1 0 1 1 0 0 +EDGE2 9539 9520 1.10465 0.0280876 -3.13116 1 0 1 1 0 0 +EDGE2 9539 7798 -0.915584 -0.0561799 -0.0449507 1 0 1 1 0 0 +EDGE2 9539 7799 -0.0232164 -0.00699171 -0.0224164 1 0 1 1 0 0 +EDGE2 9539 9538 -1.0271 0.00658691 -0.00469949 1 0 1 1 0 0 +EDGE2 9540 9519 0.948031 0.04297 -3.16639 1 0 1 1 0 0 +EDGE2 9540 9521 -0.0319756 -1.03765 -1.57067 1 0 1 1 0 0 +EDGE2 9540 7801 0.0266436 -1.06001 -1.55802 1 0 1 1 0 0 +EDGE2 9540 7800 0.0552404 -0.0286989 -0.0104339 1 0 1 1 0 0 +EDGE2 9540 9520 0.067729 -0.0458058 -3.13587 1 0 1 1 0 0 +EDGE2 9540 9539 -1.00192 0.0258487 -0.016104 1 0 1 1 0 0 +EDGE2 9540 7799 -0.978408 0.0142519 -0.0433109 1 0 1 1 0 0 +EDGE2 9541 9540 -1.03618 -0.00739698 -1.56682 1 0 1 1 0 0 +EDGE2 9541 7800 -0.972907 0.0144368 -1.53581 1 0 1 1 0 0 +EDGE2 9541 9520 -0.951915 0.0516393 1.55781 1 0 1 1 0 0 +EDGE2 9542 9541 -1.03261 -0.0269053 -0.0151146 1 0 1 1 0 0 +EDGE2 9543 9542 -1.08805 -0.0458287 -0.0335931 1 0 1 1 0 0 +EDGE2 9544 9543 -1.10444 -0.0378282 0.00722276 1 0 1 1 0 0 +EDGE2 9545 9544 -0.991518 -0.0359988 0.00522013 1 0 1 1 0 0 +EDGE2 9546 9545 -0.986086 0.00771446 1.61323 1 0 1 1 0 0 +EDGE2 9547 9546 -0.981855 -0.0551794 -0.0632612 1 0 1 1 0 0 +EDGE2 9548 9547 -1.01769 0.01522 -0.00480695 1 0 1 1 0 0 +EDGE2 9549 9548 -1.11264 -0.037213 0.0397853 1 0 1 1 0 0 +EDGE2 9550 9549 -1.03847 -0.022135 -0.0104634 1 0 1 1 0 0 +EDGE2 9551 9550 -0.977812 -0.0165683 -1.59594 1 0 1 1 0 0 +EDGE2 9552 9551 -1.07704 -0.0240213 -0.0279817 1 0 1 1 0 0 +EDGE2 9553 9552 -0.989901 0.0458974 -0.00405239 1 0 1 1 0 0 +EDGE2 9554 9553 -1.01264 0.0234022 0.00340511 1 0 1 1 0 0 +EDGE2 9555 9554 -1.0025 0.0276519 0.0158401 1 0 1 1 0 0 +EDGE2 9556 9555 -1.04955 -0.0313307 1.60761 1 0 1 1 0 0 +EDGE2 9557 9556 -1.02815 -0.0341954 -0.0171451 1 0 1 1 0 0 +EDGE2 9558 9557 -0.955096 0.0580442 -0.011725 1 0 1 1 0 0 +EDGE2 9559 9558 -0.998407 -0.152047 0.00931445 1 0 1 1 0 0 +EDGE2 9560 9559 -0.949642 0.000631364 -0.0145339 1 0 1 1 0 0 +EDGE2 9561 9560 -1.09946 0.0184375 -1.55859 1 0 1 1 0 0 +EDGE2 9562 9561 -1.00752 0.0223803 0.0546812 1 0 1 1 0 0 +EDGE2 9563 9562 -0.915409 -0.00447893 0.0183048 1 0 1 1 0 0 +EDGE2 9564 9563 -0.972723 0.0235685 -0.0153679 1 0 1 1 0 0 +EDGE2 9565 9564 -1.01774 -0.0559215 -0.0230583 1 0 1 1 0 0 +EDGE2 9566 9565 -1.01851 -0.00423615 1.56027 1 0 1 1 0 0 +EDGE2 9567 9566 -0.899229 -0.05197 -0.0181099 1 0 1 1 0 0 +EDGE2 9568 9567 -1.01531 0.00787183 -0.0428132 1 0 1 1 0 0 +EDGE2 9569 9568 -0.986051 0.0347474 -0.0187116 1 0 1 1 0 0 +EDGE2 9570 9569 -1.00561 -0.0312349 0.0122683 1 0 1 1 0 0 +EDGE2 9571 9570 -1.05835 0.0063257 -1.59573 1 0 1 1 0 0 +EDGE2 9572 9571 -1.01984 0.047584 -0.00422276 1 0 1 1 0 0 +EDGE2 9573 9572 -1.08186 -0.0268861 0.0387105 1 0 1 1 0 0 +EDGE2 9574 9573 -0.943424 -0.00708002 -0.0234862 1 0 1 1 0 0 +EDGE2 9575 9574 -0.983749 0.00288715 0.00789891 1 0 1 1 0 0 +EDGE2 9576 9575 -0.939147 0.0958348 -1.58626 1 0 1 1 0 0 +EDGE2 9577 9576 -0.997387 -0.0510642 0.00242064 1 0 1 1 0 0 +EDGE2 9578 9577 -1.02937 0.0337983 -0.0311186 1 0 1 1 0 0 +EDGE2 9579 9578 -1.02771 0.0765821 0.00959633 1 0 1 1 0 0 +EDGE2 9580 9579 -1.06376 0.00272993 0.0258857 1 0 1 1 0 0 +EDGE2 9581 9580 -1.03318 0.0372915 -1.58168 1 0 1 1 0 0 +EDGE2 9582 9581 -1.04452 -0.0104231 -0.00565429 1 0 1 1 0 0 +EDGE2 9583 9582 -1.06386 0.0480668 0.025113 1 0 1 1 0 0 +EDGE2 9584 9565 0.973734 0.00028269 -3.15861 1 0 1 1 0 0 +EDGE2 9584 9583 -1.002 0.00601922 -0.00366952 1 0 1 1 0 0 +EDGE2 9585 9564 0.996362 -0.00833774 -3.14924 1 0 1 1 0 0 +EDGE2 9585 9565 0.100744 0.0141504 -3.14545 1 0 1 1 0 0 +EDGE2 9585 9566 -0.00148646 1.00148 1.54104 1 0 1 1 0 0 +EDGE2 9585 9584 -0.994262 -0.039071 -0.00183957 1 0 1 1 0 0 +EDGE2 9586 9567 0.963199 -0.00470074 0.00344813 1 0 1 1 0 0 +EDGE2 9586 9565 -0.949953 -0.0311567 1.55247 1 0 1 1 0 0 +EDGE2 9586 9566 -0.0599154 -0.00592691 0.0040893 1 0 1 1 0 0 +EDGE2 9586 9585 -0.886352 -0.0391642 -1.55924 1 0 1 1 0 0 +EDGE2 9587 9567 0.0729074 -0.039398 -0.00722124 1 0 1 1 0 0 +EDGE2 9587 9568 1.00019 -0.0334164 -0.00513796 1 0 1 1 0 0 +EDGE2 9587 9566 -1.07619 0.051009 -0.0122018 1 0 1 1 0 0 +EDGE2 9587 9586 -0.977223 -0.0362331 -0.0198344 1 0 1 1 0 0 +EDGE2 9588 9567 -0.990817 0.000839723 0.0300602 1 0 1 1 0 0 +EDGE2 9588 9568 -0.047442 0.0581146 -0.0012268 1 0 1 1 0 0 +EDGE2 9588 9569 1.00043 -0.0873521 -0.0248265 1 0 1 1 0 0 +EDGE2 9588 9587 -1.01979 0.00697847 -0.0214993 1 0 1 1 0 0 +EDGE2 9589 9570 0.995848 0.00091783 -0.0017641 1 0 1 1 0 0 +EDGE2 9589 9568 -0.943225 0.0270096 -0.00552027 1 0 1 1 0 0 +EDGE2 9589 9588 -0.981084 0.0185307 -0.0181337 1 0 1 1 0 0 +EDGE2 9589 9569 0.0446596 -0.0182563 -0.00677586 1 0 1 1 0 0 +EDGE2 9590 9570 0.0221656 -0.00694277 -0.00130167 1 0 1 1 0 0 +EDGE2 9590 9589 -0.998672 0.0685571 -0.0256433 1 0 1 1 0 0 +EDGE2 9590 9571 0.018353 1.03003 1.5631 1 0 1 1 0 0 +EDGE2 9590 9569 -0.986699 -0.0161597 0.049765 1 0 1 1 0 0 +EDGE2 9591 9570 -1.01795 0.0470938 -1.55751 1 0 1 1 0 0 +EDGE2 9591 9590 -1.12644 -0.0034722 -1.54291 1 0 1 1 0 0 +EDGE2 9591 9571 0.00531201 0.0595138 0.000270103 1 0 1 1 0 0 +EDGE2 9591 9572 1.02113 0.0738675 -0.0132216 1 0 1 1 0 0 +EDGE2 9592 9571 -1.06547 0.0500962 -0.0222599 1 0 1 1 0 0 +EDGE2 9592 9591 -0.964916 0.0247437 0.0398918 1 0 1 1 0 0 +EDGE2 9592 9572 -0.0292835 -0.0494755 -0.0164951 1 0 1 1 0 0 +EDGE2 9592 9573 1.02738 0.0429233 -0.0165247 1 0 1 1 0 0 +EDGE2 9593 9592 -0.92634 0.0526258 -0.0235761 1 0 1 1 0 0 +EDGE2 9593 9572 -0.981383 0.0294536 -0.0229871 1 0 1 1 0 0 +EDGE2 9593 9574 1.03815 -0.00459875 0.0402312 1 0 1 1 0 0 +EDGE2 9593 9573 -0.0219139 -0.0638269 0.00642959 1 0 1 1 0 0 +EDGE2 9594 9593 -1.05314 -0.0661734 0.0447896 1 0 1 1 0 0 +EDGE2 9594 9575 0.972617 0.0188244 0.00790715 1 0 1 1 0 0 +EDGE2 9594 9574 -0.0488482 0.0288378 -0.0447636 1 0 1 1 0 0 +EDGE2 9594 9573 -0.886978 0.0476917 -0.0288417 1 0 1 1 0 0 +EDGE2 9595 9575 -0.0546158 -0.0283837 -0.0261542 1 0 1 1 0 0 +EDGE2 9595 9574 -0.939243 0.0458133 0.0146457 1 0 1 1 0 0 +EDGE2 9595 9594 -1.05332 0.0186184 -0.00279226 1 0 1 1 0 0 +EDGE2 9595 9576 0.0117458 1.01151 1.56629 1 0 1 1 0 0 +EDGE2 9596 9575 -1.02524 -0.0122604 -1.55514 1 0 1 1 0 0 +EDGE2 9596 9595 -1.0129 0.0104384 -1.5345 1 0 1 1 0 0 +EDGE2 9596 9576 0.0942037 0.0134041 -0.00541822 1 0 1 1 0 0 +EDGE2 9596 9577 0.953072 -0.0318793 -0.00154735 1 0 1 1 0 0 +EDGE2 9597 9576 -1.06486 0.0605312 -0.000565411 1 0 1 1 0 0 +EDGE2 9597 9596 -1.02315 -0.082736 0.0134014 1 0 1 1 0 0 +EDGE2 9597 9577 0.0317524 0.032234 -0.00773811 1 0 1 1 0 0 +EDGE2 9597 9578 0.970901 -0.0175752 -0.0346493 1 0 1 1 0 0 +EDGE2 9598 9597 -1.00871 0.00929006 -0.00248702 1 0 1 1 0 0 +EDGE2 9598 9577 -1.01083 -0.0438985 -0.0166767 1 0 1 1 0 0 +EDGE2 9598 9578 0.0975764 -0.0103606 0.0319084 1 0 1 1 0 0 +EDGE2 9598 9579 1.00295 0.0321203 -0.0539341 1 0 1 1 0 0 +EDGE2 9599 9580 0.974318 -0.0168663 -0.00613091 1 0 1 1 0 0 +EDGE2 9599 9578 -0.917905 -0.0888396 0.0109708 1 0 1 1 0 0 +EDGE2 9599 9598 -1.04894 0.00426372 0.0155383 1 0 1 1 0 0 +EDGE2 9599 9579 0.0295076 0.0398683 0.00976242 1 0 1 1 0 0 +EDGE2 9600 9580 -0.0497179 -0.0187393 -0.000214448 1 0 1 1 0 0 +EDGE2 9600 9599 -0.903069 -0.00863434 0.0198873 1 0 1 1 0 0 +EDGE2 9600 9579 -1.03868 -0.0549014 0.0382887 1 0 1 1 0 0 +EDGE2 9600 9581 0.041548 0.889519 1.59257 1 0 1 1 0 0 +EDGE2 9601 9580 -0.976499 0.0177545 -1.55055 1 0 1 1 0 0 +EDGE2 9601 9582 0.98558 -0.0394136 -0.0721626 1 0 1 1 0 0 +EDGE2 9601 9581 0.0109946 -0.0497588 -0.0101192 1 0 1 1 0 0 +EDGE2 9601 9600 -1.05726 0.0153382 -1.55819 1 0 1 1 0 0 +EDGE2 9602 9583 0.993733 0.0290527 -0.0184445 1 0 1 1 0 0 +EDGE2 9602 9582 -0.0907625 -0.0589091 -0.0166559 1 0 1 1 0 0 +EDGE2 9602 9581 -0.955904 -0.0236729 0.0146136 1 0 1 1 0 0 +EDGE2 9602 9601 -0.958942 -0.0150977 0.0296382 1 0 1 1 0 0 +EDGE2 9603 9602 -0.974349 -0.0084706 -0.00759094 1 0 1 1 0 0 +EDGE2 9603 9584 0.960695 0.0260656 -0.00804419 1 0 1 1 0 0 +EDGE2 9603 9583 -0.00487735 -0.00527895 -0.00667647 1 0 1 1 0 0 +EDGE2 9603 9582 -0.903779 0.00457763 0.00233239 1 0 1 1 0 0 +EDGE2 9604 9565 1.00651 0.0687763 -3.14242 1 0 1 1 0 0 +EDGE2 9604 9585 1.08426 -0.0203212 -0.0272238 1 0 1 1 0 0 +EDGE2 9604 9603 -0.966048 0.0282318 0.0149634 1 0 1 1 0 0 +EDGE2 9604 9584 0.054982 -0.0225578 0.0271481 1 0 1 1 0 0 +EDGE2 9604 9583 -0.946911 -0.0172746 -0.00315706 1 0 1 1 0 0 +EDGE2 9605 9564 1.06263 -0.0245568 -3.11874 1 0 1 1 0 0 +EDGE2 9605 9565 -0.00153072 0.0603577 -3.13118 1 0 1 1 0 0 +EDGE2 9605 9566 -0.0044132 1.05822 1.56253 1 0 1 1 0 0 +EDGE2 9605 9586 -0.0959566 0.950025 1.58687 1 0 1 1 0 0 +EDGE2 9605 9585 -0.0163948 0.0311115 0.00328548 1 0 1 1 0 0 +EDGE2 9605 9584 -1.05845 0.0333079 -0.00244489 1 0 1 1 0 0 +EDGE2 9605 9604 -0.997102 0.0546818 0.0017572 1 0 1 1 0 0 +EDGE2 9606 9565 -0.99258 -0.064081 -1.56836 1 0 1 1 0 0 +EDGE2 9606 9605 -1.01363 0.0236545 1.61497 1 0 1 1 0 0 +EDGE2 9606 9585 -0.956504 0.00549198 1.58977 1 0 1 1 0 0 +EDGE2 9607 9606 -0.92986 0.0460718 -0.0299727 1 0 1 1 0 0 +EDGE2 9608 9607 -0.941236 0.0347078 -0.00829514 1 0 1 1 0 0 +EDGE2 9609 9608 -1.05782 0.0519006 -0.0317287 1 0 1 1 0 0 +EDGE2 9610 9609 -1.0322 0.0122606 0.00618574 1 0 1 1 0 0 +EDGE2 9611 9610 -0.947287 0.00429871 1.56798 1 0 1 1 0 0 +EDGE2 9612 9611 -1.02353 0.00455081 0.01142 1 0 1 1 0 0 +EDGE2 9613 9612 -1.04178 0.15036 -0.00121196 1 0 1 1 0 0 +EDGE2 9614 9613 -1.00974 5.20407e-05 -0.00580084 1 0 1 1 0 0 +EDGE2 9615 9614 -0.945506 0.0754484 0.00587913 1 0 1 1 0 0 +EDGE2 9616 9615 -0.986205 -0.0199771 -1.53047 1 0 1 1 0 0 +EDGE2 9617 9616 -0.965131 0.0466941 0.0240773 1 0 1 1 0 0 +EDGE2 9618 9617 -1.03849 -0.0127324 0.00803076 1 0 1 1 0 0 +EDGE2 9619 9618 -0.9949 -0.0451262 -0.0102603 1 0 1 1 0 0 +EDGE2 9620 9619 -1.00987 -0.020382 0.0239271 1 0 1 1 0 0 +EDGE2 9621 9620 -0.947122 0.0657703 1.56298 1 0 1 1 0 0 +EDGE2 9622 9621 -0.942744 0.0448907 0.000544997 1 0 1 1 0 0 +EDGE2 9623 9622 -0.927215 0.0334108 0.0164026 1 0 1 1 0 0 +EDGE2 9624 9623 -1.05205 0.0551067 -0.0281444 1 0 1 1 0 0 +EDGE2 9625 9624 -0.984607 0.094151 -0.0169452 1 0 1 1 0 0 +EDGE2 9626 9625 -1.07323 -0.033335 -1.57256 1 0 1 1 0 0 +EDGE2 9627 9626 -0.978129 -0.0725307 -0.0104315 1 0 1 1 0 0 +EDGE2 9628 9627 -0.934967 -0.0406465 0.014183 1 0 1 1 0 0 +EDGE2 9629 9628 -0.981936 -0.00464195 -0.00821607 1 0 1 1 0 0 +EDGE2 9630 9629 -0.897684 -0.0202823 0.015486 1 0 1 1 0 0 +EDGE2 9631 9630 -0.926505 -0.0721552 -1.58854 1 0 1 1 0 0 +EDGE2 9632 9631 -0.969751 0.00841623 -0.0327526 1 0 1 1 0 0 +EDGE2 9633 9632 -1.0678 0.0119326 0.0222502 1 0 1 1 0 0 +EDGE2 9634 9633 -1.06295 -0.049137 -0.0203791 1 0 1 1 0 0 +EDGE2 9635 9634 -0.923234 0.144713 0.00693481 1 0 1 1 0 0 +EDGE2 9636 9635 -0.946528 -0.0782795 -1.56468 1 0 1 1 0 0 +EDGE2 9637 9636 -0.897444 0.0577728 0.0218275 1 0 1 1 0 0 +EDGE2 9638 9637 -0.967516 0.00124203 -0.0239003 1 0 1 1 0 0 +EDGE2 9639 9620 1.08338 0.00224448 -3.14416 1 0 1 1 0 0 +EDGE2 9639 9638 -1.02009 0.0519889 0.0164605 1 0 1 1 0 0 +EDGE2 9640 9619 0.96802 0.0628534 -3.16503 1 0 1 1 0 0 +EDGE2 9640 9621 -0.0299433 0.967853 1.58378 1 0 1 1 0 0 +EDGE2 9640 9620 -0.0518416 -0.0417692 -3.10712 1 0 1 1 0 0 +EDGE2 9640 9639 -0.948142 -0.0747447 0.00525345 1 0 1 1 0 0 +EDGE2 9641 9622 0.957254 0.0230496 -0.0251776 1 0 1 1 0 0 +EDGE2 9641 9640 -1.00408 -0.0336204 -1.59827 1 0 1 1 0 0 +EDGE2 9641 9621 -0.0131595 -0.0265335 -0.00812568 1 0 1 1 0 0 +EDGE2 9641 9620 -0.865809 -0.0226848 1.58315 1 0 1 1 0 0 +EDGE2 9642 9622 -0.0319387 0.0499206 -0.0216888 1 0 1 1 0 0 +EDGE2 9642 9621 -1.03463 0.0243724 0.0260971 1 0 1 1 0 0 +EDGE2 9642 9641 -1.01822 0.00856914 -0.0295238 1 0 1 1 0 0 +EDGE2 9642 9623 0.963872 0.0582766 -0.00689077 1 0 1 1 0 0 +EDGE2 9643 9622 -1.11255 -0.082177 0.0297846 1 0 1 1 0 0 +EDGE2 9643 9642 -1.11425 0.021978 0.0415115 1 0 1 1 0 0 +EDGE2 9643 9623 -0.0150676 -0.0898175 -0.0037475 1 0 1 1 0 0 +EDGE2 9643 9624 0.910823 0.0460901 0.00743689 1 0 1 1 0 0 +EDGE2 9644 9625 1.0271 -0.0856758 -0.0140711 1 0 1 1 0 0 +EDGE2 9644 9623 -0.927989 0.040238 0.0123629 1 0 1 1 0 0 +EDGE2 9644 9643 -1.00367 -0.0290828 -0.0115917 1 0 1 1 0 0 +EDGE2 9644 9624 0.0919679 -0.0764552 -0.0259711 1 0 1 1 0 0 +EDGE2 9645 9625 0.0188567 0.0234092 0.0183287 1 0 1 1 0 0 +EDGE2 9645 9644 -0.992319 0.0520032 -0.0158212 1 0 1 1 0 0 +EDGE2 9645 9624 -0.960773 -0.034906 -0.0210487 1 0 1 1 0 0 +EDGE2 9645 9626 -0.0412472 1.05531 1.55065 1 0 1 1 0 0 +EDGE2 9646 9625 -0.993327 0.0703804 -1.55632 1 0 1 1 0 0 +EDGE2 9646 9645 -0.922244 0.0696707 -1.51678 1 0 1 1 0 0 +EDGE2 9646 9626 0.0366468 0.0789393 -0.0196648 1 0 1 1 0 0 +EDGE2 9646 9627 0.973011 -0.00183509 0.00947844 1 0 1 1 0 0 +EDGE2 9647 9626 -0.989507 -0.0328127 -0.0137708 1 0 1 1 0 0 +EDGE2 9647 9646 -1.06032 0.00193711 -0.0340763 1 0 1 1 0 0 +EDGE2 9647 9627 -0.0596223 -0.0312239 0.00386709 1 0 1 1 0 0 +EDGE2 9647 9628 1.06972 -0.0139309 -0.0134814 1 0 1 1 0 0 +EDGE2 9648 9647 -0.981459 -0.0115394 -0.014206 1 0 1 1 0 0 +EDGE2 9648 9627 -0.958843 0.0172804 0.0231227 1 0 1 1 0 0 +EDGE2 9648 9628 0.0496456 -0.0295992 0.000516959 1 0 1 1 0 0 +EDGE2 9648 9629 1.01422 0.0153585 -0.0047789 1 0 1 1 0 0 +EDGE2 9649 9648 -0.918706 0.0871894 0.00732911 1 0 1 1 0 0 +EDGE2 9649 9628 -0.993458 0.0711101 0.00875319 1 0 1 1 0 0 +EDGE2 9649 9629 -0.000143025 -0.0181528 0.0220027 1 0 1 1 0 0 +EDGE2 9649 9630 1.00661 -0.0648196 -0.00797238 1 0 1 1 0 0 +EDGE2 9650 9649 -1.01822 -0.0106491 -0.0121126 1 0 1 1 0 0 +EDGE2 9650 9629 -1.00456 0.0661898 0.031906 1 0 1 1 0 0 +EDGE2 9650 9631 -0.0477326 1.03193 1.61138 1 0 1 1 0 0 +EDGE2 9650 9630 -0.0154158 -0.0339609 0.0058599 1 0 1 1 0 0 +EDGE2 9651 9632 0.933688 -0.0335002 0.0124661 1 0 1 1 0 0 +EDGE2 9651 9650 -0.957121 -0.00519453 -1.57392 1 0 1 1 0 0 +EDGE2 9651 9631 0.00419752 -0.0386742 -0.0187613 1 0 1 1 0 0 +EDGE2 9651 9630 -0.910537 -0.0245093 -1.60282 1 0 1 1 0 0 +EDGE2 9652 9632 -0.0454399 -0.0308446 -0.0190232 1 0 1 1 0 0 +EDGE2 9652 9633 1.0491 -0.0777011 0.00229411 1 0 1 1 0 0 +EDGE2 9652 9631 -0.96016 -0.0607047 -0.0247553 1 0 1 1 0 0 +EDGE2 9652 9651 -0.985513 0.0516343 -0.00414705 1 0 1 1 0 0 +EDGE2 9653 9632 -1.00633 -0.0246808 -0.0015171 1 0 1 1 0 0 +EDGE2 9653 9633 -0.0140007 -0.0877119 -0.0251904 1 0 1 1 0 0 +EDGE2 9653 9634 1.07028 -0.0707643 0.00781384 1 0 1 1 0 0 +EDGE2 9653 9652 -1.00059 -0.0261854 0.000454647 1 0 1 1 0 0 +EDGE2 9654 9635 1.05365 -0.0108915 0.0261451 1 0 1 1 0 0 +EDGE2 9654 9633 -0.972164 0.0168127 0.0322178 1 0 1 1 0 0 +EDGE2 9654 9653 -1.0324 -0.0480749 0.00555786 1 0 1 1 0 0 +EDGE2 9654 9634 0.0615426 -0.0759823 -0.0162456 1 0 1 1 0 0 +EDGE2 9655 9636 -0.0771701 0.983388 1.53697 1 0 1 1 0 0 +EDGE2 9655 9654 -0.935857 0.0259704 -0.0183677 1 0 1 1 0 0 +EDGE2 9655 9635 0.00142356 -0.0117015 -0.012822 1 0 1 1 0 0 +EDGE2 9655 9634 -1.01593 -0.0201071 0.0141379 1 0 1 1 0 0 +EDGE2 9656 9635 -1.02753 0.0779733 1.56982 1 0 1 1 0 0 +EDGE2 9656 9655 -0.943122 -0.0945438 1.58733 1 0 1 1 0 0 +EDGE2 9657 9656 -0.997292 -0.0203732 0.0133963 1 0 1 1 0 0 +EDGE2 9658 9657 -0.887586 -0.00460068 0.0356647 1 0 1 1 0 0 +EDGE2 9659 9658 -0.909274 -0.0253867 0.0276413 1 0 1 1 0 0 +EDGE2 9659 6920 1.01692 0.0805393 -3.11409 1 0 1 1 0 0 +EDGE2 9659 6960 1.08411 -0.0443981 -3.1391 1 0 1 1 0 0 +EDGE2 9660 9659 -1.00376 0.0264553 0.00431404 1 0 1 1 0 0 +EDGE2 9660 6961 -0.00781037 0.944422 1.56979 1 0 1 1 0 0 +EDGE2 9660 6920 -0.0339994 0.0809555 -3.13306 1 0 1 1 0 0 +EDGE2 9660 6960 -0.0252246 0.054361 -3.16491 1 0 1 1 0 0 +EDGE2 9660 6921 -0.0202028 -1.05614 -1.54365 1 0 1 1 0 0 +EDGE2 9660 6959 0.961577 -0.0272987 -3.14276 1 0 1 1 0 0 +EDGE2 9660 6919 0.958347 -0.0393047 -3.16342 1 0 1 1 0 0 +EDGE2 9661 6961 -0.00543329 0.0530431 -0.0180257 1 0 1 1 0 0 +EDGE2 9661 6962 0.923139 0.057994 0.0014812 1 0 1 1 0 0 +EDGE2 9661 6920 -1.0345 0.0663669 1.60395 1 0 1 1 0 0 +EDGE2 9661 6960 -1.02521 -0.00543852 1.57215 1 0 1 1 0 0 +EDGE2 9661 9660 -1.03319 0.122336 -1.5776 1 0 1 1 0 0 +EDGE2 9662 6961 -0.942641 -0.0360867 0.018656 1 0 1 1 0 0 +EDGE2 9662 6963 1.03691 0.0100966 0.0140253 1 0 1 1 0 0 +EDGE2 9662 9661 -0.968096 0.0943724 -0.0141705 1 0 1 1 0 0 +EDGE2 9662 6962 0.00386983 0.0466857 0.0164721 1 0 1 1 0 0 +EDGE2 9663 9662 -1.11344 0.0144694 0.0098383 1 0 1 1 0 0 +EDGE2 9663 6964 0.928414 -0.010898 0.00504056 1 0 1 1 0 0 +EDGE2 9663 6963 0.0973082 -0.0846976 0.0115086 1 0 1 1 0 0 +EDGE2 9663 6962 -0.966876 -0.0209391 -0.0113441 1 0 1 1 0 0 +EDGE2 9664 6885 1.0702 -0.0521852 -3.14421 1 0 1 1 0 0 +EDGE2 9664 6965 1.00823 -0.000686933 0.0335285 1 0 1 1 0 0 +EDGE2 9664 9663 -1.00309 -0.083597 -0.0270664 1 0 1 1 0 0 +EDGE2 9664 6964 0.0614279 0.0918174 -0.0208378 1 0 1 1 0 0 +EDGE2 9664 6963 -1.09088 -0.0250381 -0.00776126 1 0 1 1 0 0 +EDGE2 9665 6886 -0.0486231 -0.971377 -1.55788 1 0 1 1 0 0 +EDGE2 9665 6885 0.0103219 0.0433807 -3.15013 1 0 1 1 0 0 +EDGE2 9665 6884 1.03915 0.0566629 -3.13074 1 0 1 1 0 0 +EDGE2 9665 6965 -0.0284279 0.00408722 -0.0361266 1 0 1 1 0 0 +EDGE2 9665 6964 -0.98781 0.0153952 0.000482925 1 0 1 1 0 0 +EDGE2 9665 9664 -1.00514 -0.0415645 -0.00300975 1 0 1 1 0 0 +EDGE2 9665 6966 -0.0130019 -1.0134 -1.58206 1 0 1 1 0 0 +EDGE2 9666 6886 0.0442387 0.013751 0.00528455 1 0 1 1 0 0 +EDGE2 9666 6885 -0.986658 0.0440929 -1.60451 1 0 1 1 0 0 +EDGE2 9666 9665 -1.02025 0.0172865 1.52928 1 0 1 1 0 0 +EDGE2 9666 6965 -0.950749 -0.0457151 1.53359 1 0 1 1 0 0 +EDGE2 9666 6966 0.0370703 -0.012995 -0.00257961 1 0 1 1 0 0 +EDGE2 9666 6887 0.911782 -0.0690101 0.00552117 1 0 1 1 0 0 +EDGE2 9666 6967 0.941668 -0.0324641 0.0210939 1 0 1 1 0 0 +EDGE2 9667 6886 -1.04527 0.00975703 0.0175298 1 0 1 1 0 0 +EDGE2 9667 9666 -0.986291 -0.0961155 0.00204036 1 0 1 1 0 0 +EDGE2 9667 6966 -0.971151 0.0626421 0.000570604 1 0 1 1 0 0 +EDGE2 9667 6968 1.03299 -0.0317158 -0.0264831 1 0 1 1 0 0 +EDGE2 9667 6887 -0.0269065 -0.00333562 0.00365116 1 0 1 1 0 0 +EDGE2 9667 6967 0.0773187 0.0110641 -0.0035433 1 0 1 1 0 0 +EDGE2 9667 6888 1.03978 0.00555876 -0.0190789 1 0 1 1 0 0 +EDGE2 9668 6968 0.0124214 -0.0753491 0.0161124 1 0 1 1 0 0 +EDGE2 9668 6887 -1.01465 0.0983727 -0.00117597 1 0 1 1 0 0 +EDGE2 9668 6967 -1.00917 0.0187797 -0.00327218 1 0 1 1 0 0 +EDGE2 9668 9667 -1.03319 -0.00158799 0.00407742 1 0 1 1 0 0 +EDGE2 9668 6969 1.14469 -0.00555493 -0.00983492 1 0 1 1 0 0 +EDGE2 9668 6888 -0.117985 -0.0359627 0.00460605 1 0 1 1 0 0 +EDGE2 9668 6889 0.980427 -0.0481416 0.0366084 1 0 1 1 0 0 +EDGE2 9669 6968 -1.00868 0.0164786 0.0103562 1 0 1 1 0 0 +EDGE2 9669 9668 -0.933749 -0.0267314 0.0300385 1 0 1 1 0 0 +EDGE2 9669 6969 -0.0180287 0.000633091 0.0087085 1 0 1 1 0 0 +EDGE2 9669 6888 -0.960366 0.0583028 0.0440989 1 0 1 1 0 0 +EDGE2 9669 6889 0.0450359 -0.0923425 0.0508414 1 0 1 1 0 0 +EDGE2 9669 6970 1.02745 -0.0014464 -0.0443781 1 0 1 1 0 0 +EDGE2 9669 6870 1.03276 -0.0198821 -3.14024 1 0 1 1 0 0 +EDGE2 9669 6890 1.11369 -0.0367116 0.00476693 1 0 1 1 0 0 +EDGE2 9669 6910 1.04754 0.000934688 -3.13433 1 0 1 1 0 0 +EDGE2 9670 6969 -1.05992 -0.0666555 0.0130666 1 0 1 1 0 0 +EDGE2 9670 9669 -1.0024 0.0750548 -0.00835581 1 0 1 1 0 0 +EDGE2 9670 6889 -1.03221 -0.104222 0.000705471 1 0 1 1 0 0 +EDGE2 9670 6911 -0.0207991 -1.02296 -1.5962 1 0 1 1 0 0 +EDGE2 9670 6970 0.0247789 0.030605 -0.00563452 1 0 1 1 0 0 +EDGE2 9670 6871 -0.00732226 0.968602 1.57927 1 0 1 1 0 0 +EDGE2 9670 6971 -0.0556864 0.98665 1.58378 1 0 1 1 0 0 +EDGE2 9670 6870 0.0611365 -0.0544346 -3.13563 1 0 1 1 0 0 +EDGE2 9670 6890 0.135832 0.0215969 0.0199389 1 0 1 1 0 0 +EDGE2 9670 6910 -0.0118654 -0.00417085 -3.13709 1 0 1 1 0 0 +EDGE2 9670 6891 0.0654724 -0.896133 -1.55624 1 0 1 1 0 0 +EDGE2 9670 6909 0.950125 -0.0149796 -3.15058 1 0 1 1 0 0 +EDGE2 9670 6869 0.994176 0.00989956 -3.17619 1 0 1 1 0 0 +EDGE2 9671 6911 0.00949111 0.0282596 0.00183434 1 0 1 1 0 0 +EDGE2 9671 6970 -1.07061 0.0217027 1.5591 1 0 1 1 0 0 +EDGE2 9671 9670 -1.02694 0.0041184 1.49651 1 0 1 1 0 0 +EDGE2 9671 6870 -1.09107 -0.0445316 -1.55978 1 0 1 1 0 0 +EDGE2 9671 6890 -0.98414 0.0581308 1.57641 1 0 1 1 0 0 +EDGE2 9671 6910 -1.008 0.107086 -1.60456 1 0 1 1 0 0 +EDGE2 9671 6892 0.969422 -0.0229329 0.030882 1 0 1 1 0 0 +EDGE2 9671 6891 0.021344 0.0712452 -0.0352873 1 0 1 1 0 0 +EDGE2 9671 6912 0.884107 -0.0279412 -0.0152289 1 0 1 1 0 0 +EDGE2 9672 6911 -0.948998 0.128417 -0.0111643 1 0 1 1 0 0 +EDGE2 9672 9671 -1.05284 0.00584852 -0.0151954 1 0 1 1 0 0 +EDGE2 9672 6892 0.0376335 0.0460093 -0.000578952 1 0 1 1 0 0 +EDGE2 9672 6891 -0.9941 0.00852788 -0.0234643 1 0 1 1 0 0 +EDGE2 9672 6912 -0.178435 0.0701509 -0.0266687 1 0 1 1 0 0 +EDGE2 9672 6913 0.988279 0.0436691 0.00113465 1 0 1 1 0 0 +EDGE2 9672 6893 1.02503 0.0800666 0.0126329 1 0 1 1 0 0 +EDGE2 9673 6892 -1.04206 0.000461945 0.0127471 1 0 1 1 0 0 +EDGE2 9673 9672 -0.995104 -0.0463265 -0.0201036 1 0 1 1 0 0 +EDGE2 9673 6912 -1.01526 -0.0791669 0.0121304 1 0 1 1 0 0 +EDGE2 9673 6913 0.0428721 0.0319249 0.0292958 1 0 1 1 0 0 +EDGE2 9673 6893 -0.0108404 0.00863395 -0.0175922 1 0 1 1 0 0 +EDGE2 9673 6894 0.996275 -0.00982713 0.000574072 1 0 1 1 0 0 +EDGE2 9673 6914 1.01533 -0.0224198 -0.0128394 1 0 1 1 0 0 +EDGE2 9674 6913 -1.01503 0.0197722 0.0198587 1 0 1 1 0 0 +EDGE2 9674 9673 -1.00472 0.00562849 0.00684747 1 0 1 1 0 0 +EDGE2 9674 6893 -0.977782 -0.120579 0.0122462 1 0 1 1 0 0 +EDGE2 9674 6894 -0.0319715 0.025942 0.00493993 1 0 1 1 0 0 +EDGE2 9674 6914 0.0415643 0.0408083 0.0196547 1 0 1 1 0 0 +EDGE2 9674 6915 1.01366 -0.00664997 0.000672015 1 0 1 1 0 0 +EDGE2 9674 6955 1.02716 -0.0321791 -3.12747 1 0 1 1 0 0 +EDGE2 9674 6895 0.985168 -0.0050664 -0.0186271 1 0 1 1 0 0 +EDGE2 9675 9674 -0.968492 -0.0322674 0.00738311 1 0 1 1 0 0 +EDGE2 9675 6916 -0.00238323 -0.950277 -1.57388 1 0 1 1 0 0 +EDGE2 9675 6956 -0.00241 -0.972663 -1.60082 1 0 1 1 0 0 +EDGE2 9675 6894 -0.886215 0.0167084 0.00325622 1 0 1 1 0 0 +EDGE2 9675 6914 -0.952413 -0.0272493 0.00669676 1 0 1 1 0 0 +EDGE2 9675 6954 0.988535 -0.0145198 -3.14432 1 0 1 1 0 0 +EDGE2 9675 6915 0.0514903 0.00554236 -0.0146578 1 0 1 1 0 0 +EDGE2 9675 6955 -0.0329979 0.0641896 -3.12012 1 0 1 1 0 0 +EDGE2 9675 6895 0.0126852 -0.0196003 0.011111 1 0 1 1 0 0 +EDGE2 9675 6896 -0.0370328 0.95553 1.58411 1 0 1 1 0 0 +EDGE2 9676 6915 -0.970494 -0.0339827 -1.57773 1 0 1 1 0 0 +EDGE2 9676 6955 -0.957052 0.121131 1.53522 1 0 1 1 0 0 +EDGE2 9676 9675 -0.95906 0.0282067 -1.6007 1 0 1 1 0 0 +EDGE2 9676 6895 -0.926235 0.009251 -1.60111 1 0 1 1 0 0 +EDGE2 9676 6896 -0.0218251 -5.00943e-05 -0.0144028 1 0 1 1 0 0 +EDGE2 9676 6897 1.05756 0.0226593 0.00538563 1 0 1 1 0 0 +EDGE2 9677 9676 -1.04566 -0.00330774 -0.030498 1 0 1 1 0 0 +EDGE2 9677 6896 -0.927055 0.0279709 -0.0273504 1 0 1 1 0 0 +EDGE2 9677 6898 1.03942 0.122279 0.00703239 1 0 1 1 0 0 +EDGE2 9677 6897 -0.045547 0.0861971 -0.0248157 1 0 1 1 0 0 +EDGE2 9678 9677 -0.977034 -0.0703419 0.0347308 1 0 1 1 0 0 +EDGE2 9678 6899 1.08859 0.0381305 0.0232168 1 0 1 1 0 0 +EDGE2 9678 6898 -0.12072 0.0313818 0.00357757 1 0 1 1 0 0 +EDGE2 9678 6897 -1.04922 -0.0337506 -0.0139764 1 0 1 1 0 0 +EDGE2 9679 6899 0.0141488 0.0389677 -0.0328073 1 0 1 1 0 0 +EDGE2 9679 6898 -0.956476 -0.00459891 0.00617237 1 0 1 1 0 0 +EDGE2 9679 9678 -1.02516 0.0474479 -0.0327533 1 0 1 1 0 0 +EDGE2 9679 6900 1.05124 -0.01826 -0.0195483 1 0 1 1 0 0 +EDGE2 9680 6901 -0.0516988 1.02599 1.57444 1 0 1 1 0 0 +EDGE2 9680 6899 -1.01861 -0.0547803 -0.0384251 1 0 1 1 0 0 +EDGE2 9680 9679 -0.917152 0.0371307 0.017033 1 0 1 1 0 0 +EDGE2 9680 6900 -0.0239054 0.0270626 -0.0181186 1 0 1 1 0 0 +EDGE2 9681 6900 -1.00515 0.0631677 1.58112 1 0 1 1 0 0 +EDGE2 9681 9680 -1.04596 0.0254818 1.5691 1 0 1 1 0 0 +EDGE2 9682 9681 -1.01461 -0.0382967 0.0504409 1 0 1 1 0 0 +EDGE2 9683 9682 -1.00522 0.0149775 -0.00701256 1 0 1 1 0 0 +EDGE2 9684 9683 -1.06788 0.0894077 0.00540647 1 0 1 1 0 0 +EDGE2 9684 6945 1.03806 0.00911893 -3.14255 1 0 1 1 0 0 +EDGE2 9685 6946 0.024484 -0.974571 -1.57545 1 0 1 1 0 0 +EDGE2 9685 9684 -1.04529 0.00365043 -0.027952 1 0 1 1 0 0 +EDGE2 9685 6944 1.01675 -0.00775411 -3.16855 1 0 1 1 0 0 +EDGE2 9685 6945 0.0887321 -0.039195 -3.14542 1 0 1 1 0 0 +EDGE2 9686 9685 -1.01227 -0.0530474 -1.54613 1 0 1 1 0 0 +EDGE2 9686 6945 -0.93348 0.0494527 1.54561 1 0 1 1 0 0 +EDGE2 9687 9686 -0.963455 0.0583714 -0.0278065 1 0 1 1 0 0 +EDGE2 9688 9687 -1.06113 0.0551821 0.0123886 1 0 1 1 0 0 +EDGE2 9689 9688 -1.04336 -0.0709397 -0.0135231 1 0 1 1 0 0 +EDGE2 9690 9689 -1.04372 0.0782506 0.0191278 1 0 1 1 0 0 +EDGE2 9691 9690 -1.00516 -0.102226 -1.54782 1 0 1 1 0 0 +EDGE2 9692 9691 -1.00067 0.00156445 0.0155644 1 0 1 1 0 0 +EDGE2 9693 9692 -1.10265 -0.0469672 0.00393391 1 0 1 1 0 0 +EDGE2 9694 9693 -1.10619 -0.0415418 -0.00481755 1 0 1 1 0 0 +EDGE2 9695 9694 -0.93866 0.047409 -0.00905106 1 0 1 1 0 0 +EDGE2 9696 9695 -0.994797 0.0171127 -1.56176 1 0 1 1 0 0 +EDGE2 9697 9696 -1.06921 -0.0258736 0.00592936 1 0 1 1 0 0 +EDGE2 9698 9697 -0.990936 -0.0413424 -0.017086 1 0 1 1 0 0 +EDGE2 9699 9698 -1.00248 0.14444 0.00296661 1 0 1 1 0 0 +EDGE2 9699 6900 0.887093 0.0314966 -3.16009 1 0 1 1 0 0 +EDGE2 9699 9680 1.03998 0.0364737 -3.11166 1 0 1 1 0 0 +EDGE2 9700 6901 0.0665124 -0.993632 -1.55655 1 0 1 1 0 0 +EDGE2 9700 9681 0.0690649 0.897467 1.54572 1 0 1 1 0 0 +EDGE2 9700 6899 1.10721 -0.0745221 -3.1458 1 0 1 1 0 0 +EDGE2 9700 9679 0.909089 0.0996457 -3.13661 1 0 1 1 0 0 +EDGE2 9700 6900 -0.0235354 -0.000229771 -3.1668 1 0 1 1 0 0 +EDGE2 9700 9680 -0.101699 0.0159218 -3.07875 1 0 1 1 0 0 +EDGE2 9700 9699 -0.948554 -0.00743952 0.00973212 1 0 1 1 0 0 +EDGE2 9701 9681 -0.0241671 -0.0473601 -0.0257632 1 0 1 1 0 0 +EDGE2 9701 6900 -1.01529 0.0799085 1.56325 1 0 1 1 0 0 +EDGE2 9701 9680 -0.915379 0.0205641 1.54855 1 0 1 1 0 0 +EDGE2 9701 9700 -1.12024 -0.00789404 -1.5689 1 0 1 1 0 0 +EDGE2 9701 9682 0.945341 -0.0101374 -0.00421112 1 0 1 1 0 0 +EDGE2 9702 9681 -0.986777 -0.0673839 -0.0230785 1 0 1 1 0 0 +EDGE2 9702 9701 -0.935031 -0.0575666 -0.0196817 1 0 1 1 0 0 +EDGE2 9702 9682 0.0150387 -0.0634256 0.027616 1 0 1 1 0 0 +EDGE2 9702 9683 0.979993 0.0622434 0.0350804 1 0 1 1 0 0 +EDGE2 9703 9702 -1.06056 0.0266817 0.00316067 1 0 1 1 0 0 +EDGE2 9703 9682 -0.935385 -0.0887594 -0.00976046 1 0 1 1 0 0 +EDGE2 9703 9684 0.973899 -0.0139117 -0.00633298 1 0 1 1 0 0 +EDGE2 9703 9683 -0.0100993 -0.0479795 0.010708 1 0 1 1 0 0 +EDGE2 9704 9703 -1.0386 -0.0604474 -0.0416065 1 0 1 1 0 0 +EDGE2 9704 9685 1.01401 -0.00603466 0.0168109 1 0 1 1 0 0 +EDGE2 9704 9684 -0.0012462 0.0620257 0.00684218 1 0 1 1 0 0 +EDGE2 9704 9683 -0.969534 -0.000171229 0.00946813 1 0 1 1 0 0 +EDGE2 9704 6945 0.974306 -0.0107281 -3.16312 1 0 1 1 0 0 +EDGE2 9705 6946 0.0732975 -1.00458 -1.57291 1 0 1 1 0 0 +EDGE2 9705 9685 0.00997063 -0.0232639 0.00893776 1 0 1 1 0 0 +EDGE2 9705 9684 -0.954162 0.0404906 -0.0260902 1 0 1 1 0 0 +EDGE2 9705 9704 -0.996001 0.0585609 0.0359207 1 0 1 1 0 0 +EDGE2 9705 6944 0.939658 -0.104821 -3.14868 1 0 1 1 0 0 +EDGE2 9705 6945 0.0417503 -0.00836891 -3.1315 1 0 1 1 0 0 +EDGE2 9705 9686 0.0269281 1.00385 1.5798 1 0 1 1 0 0 +EDGE2 9706 9685 -0.956692 0.0160684 -1.57667 1 0 1 1 0 0 +EDGE2 9706 9705 -1.0634 -0.00882842 -1.60473 1 0 1 1 0 0 +EDGE2 9706 6945 -0.970221 0.0315328 1.61127 1 0 1 1 0 0 +EDGE2 9706 9686 0.00813946 0.0399953 -0.0177965 1 0 1 1 0 0 +EDGE2 9706 9687 0.963373 -0.0414102 0.0376658 1 0 1 1 0 0 +EDGE2 9707 9706 -0.963596 -0.0125015 0.0205699 1 0 1 1 0 0 +EDGE2 9707 9686 -0.95092 0.0393229 -0.0280644 1 0 1 1 0 0 +EDGE2 9707 9688 1.04374 -0.0255007 -0.00295815 1 0 1 1 0 0 +EDGE2 9707 9687 0.00197323 -0.00368325 0.00356604 1 0 1 1 0 0 +EDGE2 9708 9689 0.938457 0.00120131 0.0217676 1 0 1 1 0 0 +EDGE2 9708 9688 -0.0583407 0.078284 0.00540772 1 0 1 1 0 0 +EDGE2 9708 9687 -0.920898 -0.0330768 -0.00436114 1 0 1 1 0 0 +EDGE2 9708 9707 -1.00182 -0.0798691 -0.00173137 1 0 1 1 0 0 +EDGE2 9709 9689 0.0658055 0.028843 0.0170392 1 0 1 1 0 0 +EDGE2 9709 9688 -0.920845 0.0231952 -0.040017 1 0 1 1 0 0 +EDGE2 9709 9708 -0.981579 -0.0344716 -0.0155679 1 0 1 1 0 0 +EDGE2 9709 9690 1.02615 -0.00944187 -0.00523561 1 0 1 1 0 0 +EDGE2 9710 9689 -1.00494 0.0190124 -0.0275989 1 0 1 1 0 0 +EDGE2 9710 9709 -0.991986 -0.0115013 -0.0108254 1 0 1 1 0 0 +EDGE2 9710 9691 -0.0121808 0.990459 1.56512 1 0 1 1 0 0 +EDGE2 9710 9690 -0.0529379 0.0292739 0.0269688 1 0 1 1 0 0 +EDGE2 9711 9691 0.0080781 -0.0109901 -0.0156961 1 0 1 1 0 0 +EDGE2 9711 9692 0.956653 -0.00605939 -0.00250142 1 0 1 1 0 0 +EDGE2 9711 9690 -1.02162 -0.155504 -1.56949 1 0 1 1 0 0 +EDGE2 9711 9710 -0.985856 0.0291062 -1.54893 1 0 1 1 0 0 +EDGE2 9712 9691 -0.962185 -0.0116274 -0.0129936 1 0 1 1 0 0 +EDGE2 9712 9692 0.0171473 0.0113677 0.0157868 1 0 1 1 0 0 +EDGE2 9712 9693 0.94472 -0.0429259 -0.0127599 1 0 1 1 0 0 +EDGE2 9712 9711 -0.948243 0.108304 -0.0253803 1 0 1 1 0 0 +EDGE2 9713 9694 0.96843 0.0251532 0.0330737 1 0 1 1 0 0 +EDGE2 9713 9692 -0.968793 0.0532946 0.0166913 1 0 1 1 0 0 +EDGE2 9713 9712 -0.953279 -0.0158335 0.0109088 1 0 1 1 0 0 +EDGE2 9713 9693 0.0438845 -0.00762347 0.0150854 1 0 1 1 0 0 +EDGE2 9714 9713 -0.952205 -0.0142417 -0.021208 1 0 1 1 0 0 +EDGE2 9714 9695 1.05512 -0.0235363 -0.00862123 1 0 1 1 0 0 +EDGE2 9714 9694 0.0572905 0.0301335 0.0153276 1 0 1 1 0 0 +EDGE2 9714 9693 -0.954204 -0.012263 0.00167414 1 0 1 1 0 0 +EDGE2 9715 9696 -0.0394712 0.98006 1.59877 1 0 1 1 0 0 +EDGE2 9715 9714 -1.03268 0.0624502 0.00291793 1 0 1 1 0 0 +EDGE2 9715 9695 0.00511879 0.0223719 -0.0148207 1 0 1 1 0 0 +EDGE2 9715 9694 -1.02052 0.104067 0.0163971 1 0 1 1 0 0 +EDGE2 9716 9695 -0.987104 0.046527 1.53637 1 0 1 1 0 0 +EDGE2 9716 9715 -0.962144 -0.0166938 1.56066 1 0 1 1 0 0 +EDGE2 9717 9716 -0.976384 -0.00342716 0.0388271 1 0 1 1 0 0 +EDGE2 9718 9717 -0.949329 0.00547067 -0.00117349 1 0 1 1 0 0 +EDGE2 9719 9718 -0.933263 0.0252784 -0.0015771 1 0 1 1 0 0 +EDGE2 9720 9719 -1.02738 0.000626441 0.0242031 1 0 1 1 0 0 +EDGE2 9721 9720 -1.11246 -0.0160086 1.59491 1 0 1 1 0 0 +EDGE2 9722 9721 -0.902921 0.0207144 -0.0369672 1 0 1 1 0 0 +EDGE2 9723 9722 -1.04914 0.0261604 0.0128276 1 0 1 1 0 0 +EDGE2 9724 9723 -0.971008 -0.152551 -0.0447193 1 0 1 1 0 0 +EDGE2 9725 9724 -0.96068 -0.00121733 0.0152773 1 0 1 1 0 0 +EDGE2 9726 9725 -1.01961 0.039073 -1.59703 1 0 1 1 0 0 +EDGE2 9727 9726 -1.00153 0.0861191 -0.0311484 1 0 1 1 0 0 +EDGE2 9728 9727 -1.00688 0.0499436 -0.00671943 1 0 1 1 0 0 +EDGE2 9729 9728 -0.976855 -0.0604087 -0.0121911 1 0 1 1 0 0 +EDGE2 9730 9729 -0.999778 -0.00341929 0.012421 1 0 1 1 0 0 +EDGE2 9731 9730 -1.02076 -0.00963213 1.59086 1 0 1 1 0 0 +EDGE2 9732 9731 -0.963392 -0.0053152 0.0120467 1 0 1 1 0 0 +EDGE2 9733 9732 -1.00713 -0.0996321 0.0306686 1 0 1 1 0 0 +EDGE2 9734 9733 -0.998987 0.0169628 -0.0207731 1 0 1 1 0 0 +EDGE2 9735 9734 -0.949074 -0.0170188 0.00817566 1 0 1 1 0 0 +EDGE2 9736 9735 -0.98946 -0.0326615 1.58363 1 0 1 1 0 0 +EDGE2 9737 9736 -1.03383 0.0707751 0.0282309 1 0 1 1 0 0 +EDGE2 9738 9737 -0.964653 -0.000589311 -0.000780995 1 0 1 1 0 0 +EDGE2 9739 9738 -0.97862 -0.0373247 0.00523048 1 0 1 1 0 0 +EDGE2 9740 9739 -1.05344 -0.0685218 0.0122719 1 0 1 1 0 0 +EDGE2 9741 9740 -1.02389 -0.0749749 -1.55189 1 0 1 1 0 0 +EDGE2 9742 9741 -0.981613 0.017715 0.0107854 1 0 1 1 0 0 +EDGE2 9743 9742 -0.991814 0.0822432 -0.02949 1 0 1 1 0 0 +EDGE2 9744 9743 -0.94404 0.0218038 -0.0115266 1 0 1 1 0 0 +EDGE2 9745 9744 -1.06739 0.0466253 -0.00530824 1 0 1 1 0 0 +EDGE2 9746 9745 -1.01673 -0.0385262 1.58354 1 0 1 1 0 0 +EDGE2 9747 9746 -0.984451 0.0741403 0.0360215 1 0 1 1 0 0 +EDGE2 9748 9747 -1.01708 0.0374045 0.0164092 1 0 1 1 0 0 +EDGE2 9749 9748 -0.977405 -0.0433328 0.0207109 1 0 1 1 0 0 +EDGE2 9750 9749 -1.08007 0.0165033 -0.0172257 1 0 1 1 0 0 +EDGE2 9751 9750 -0.997787 0.125474 -1.58866 1 0 1 1 0 0 +EDGE2 9752 9751 -0.946014 -0.0708097 0.0262674 1 0 1 1 0 0 +EDGE2 9753 9752 -1.01231 0.00988153 0.0203969 1 0 1 1 0 0 +EDGE2 9754 9753 -1.05742 -0.0428385 0.00618384 1 0 1 1 0 0 +EDGE2 9755 9754 -0.997979 0.0207428 -0.0159749 1 0 1 1 0 0 +EDGE2 9756 9755 -0.95113 0.0189141 -1.56561 1 0 1 1 0 0 +EDGE2 9757 9756 -1.11082 -0.0327406 -0.00423097 1 0 1 1 0 0 +EDGE2 9758 9757 -1.05047 -0.0997403 4.43677e-05 1 0 1 1 0 0 +EDGE2 9759 9758 -0.989205 0.0148644 -0.0126148 1 0 1 1 0 0 +EDGE2 9760 9759 -0.985623 0.0611126 0.0130596 1 0 1 1 0 0 +EDGE2 9761 9760 -0.947579 -0.0798487 1.57752 1 0 1 1 0 0 +EDGE2 9762 9761 -1.04947 0.0271738 -0.00240764 1 0 1 1 0 0 +EDGE2 9763 9762 -1.01974 0.014757 0.00160575 1 0 1 1 0 0 +EDGE2 9764 9763 -1.07168 -0.0978087 -0.0312413 1 0 1 1 0 0 +EDGE2 9765 9764 -1.03007 0.0294362 0.00729851 1 0 1 1 0 0 +EDGE2 9766 9765 -0.981836 -0.02015 -1.54357 1 0 1 1 0 0 +EDGE2 9767 9766 -0.990428 -0.0619338 -0.00662998 1 0 1 1 0 0 +EDGE2 9768 9767 -0.921928 -0.0786884 -0.0396524 1 0 1 1 0 0 +EDGE2 9769 9768 -0.961322 0.0101242 -0.00486293 1 0 1 1 0 0 +EDGE2 9770 9769 -0.981565 0.0372355 0.0199254 1 0 1 1 0 0 +EDGE2 9771 9770 -1.00251 -0.0179132 -1.564 1 0 1 1 0 0 +EDGE2 9772 9771 -0.977792 0.0314278 0.015842 1 0 1 1 0 0 +EDGE2 9773 9772 -1.00642 -0.0497607 0.00659428 1 0 1 1 0 0 +EDGE2 9774 9773 -1.00329 -0.0140996 -0.0240546 1 0 1 1 0 0 +EDGE2 9775 9774 -1.01903 -0.0147717 -0.00444596 1 0 1 1 0 0 +EDGE2 9776 9775 -0.998733 0.0628555 -1.58821 1 0 1 1 0 0 +EDGE2 9777 9776 -0.915497 -0.010986 -0.0213377 1 0 1 1 0 0 +EDGE2 9778 9777 -1.07036 0.0170635 0.0018831 1 0 1 1 0 0 +EDGE2 9779 9760 0.972898 -0.0284652 -3.13272 1 0 1 1 0 0 +EDGE2 9779 9778 -1.01518 -0.0383992 -0.0206792 1 0 1 1 0 0 +EDGE2 9780 9759 0.975326 0.025063 -3.17044 1 0 1 1 0 0 +EDGE2 9780 9760 0.0166096 0.0337804 -3.17043 1 0 1 1 0 0 +EDGE2 9780 9761 0.00411825 1.02261 1.58311 1 0 1 1 0 0 +EDGE2 9780 9779 -0.944596 0.015967 -0.0170423 1 0 1 1 0 0 +EDGE2 9781 9780 -1.0099 0.0629952 -1.55185 1 0 1 1 0 0 +EDGE2 9781 9760 -1.06096 -0.0913009 1.58217 1 0 1 1 0 0 +EDGE2 9781 9761 -0.0526655 -0.0833957 0.0248437 1 0 1 1 0 0 +EDGE2 9781 9762 1.03637 0.00815856 -0.0104301 1 0 1 1 0 0 +EDGE2 9782 9761 -1.01026 0.00719858 -0.0332081 1 0 1 1 0 0 +EDGE2 9782 9781 -0.942884 -0.0104422 -0.034388 1 0 1 1 0 0 +EDGE2 9782 9762 -0.0471806 -0.000532857 0.00668809 1 0 1 1 0 0 +EDGE2 9782 9763 1.02346 0.0101044 0.00622775 1 0 1 1 0 0 +EDGE2 9783 9762 -1.00073 0.0449269 -0.0313836 1 0 1 1 0 0 +EDGE2 9783 9782 -1.01628 0.0334474 0.00825568 1 0 1 1 0 0 +EDGE2 9783 9764 1.017 0.0061581 0.0165791 1 0 1 1 0 0 +EDGE2 9783 9763 -0.00205851 0.00442921 -0.0220589 1 0 1 1 0 0 +EDGE2 9784 9783 -0.932793 0.0124173 -0.0185254 1 0 1 1 0 0 +EDGE2 9784 9764 -0.0311073 0.0574839 -0.0011461 1 0 1 1 0 0 +EDGE2 9784 9763 -1.03055 -0.0107672 0.0607044 1 0 1 1 0 0 +EDGE2 9784 9765 1.01511 0.00841994 -0.0417304 1 0 1 1 0 0 +EDGE2 9785 9764 -0.95883 -0.0609154 -0.0130739 1 0 1 1 0 0 +EDGE2 9785 9784 -0.933982 0.0249508 -0.0267391 1 0 1 1 0 0 +EDGE2 9785 9765 -0.0611314 0.0394072 0.0135897 1 0 1 1 0 0 +EDGE2 9785 9766 -0.0738463 0.942866 1.59016 1 0 1 1 0 0 +EDGE2 9786 9785 -0.945784 0.0140417 -1.5479 1 0 1 1 0 0 +EDGE2 9786 9765 -1.01319 -0.0266225 -1.54607 1 0 1 1 0 0 +EDGE2 9786 9766 0.0332547 -0.0156254 0.0136563 1 0 1 1 0 0 +EDGE2 9786 9767 1.02934 -0.00823952 -0.0267791 1 0 1 1 0 0 +EDGE2 9787 9786 -0.986345 0.0554362 0.00380214 1 0 1 1 0 0 +EDGE2 9787 9766 -1.03037 0.00318607 0.0132064 1 0 1 1 0 0 +EDGE2 9787 9767 0.0154197 0.00909423 0.00616149 1 0 1 1 0 0 +EDGE2 9787 9768 0.957026 -0.00493789 -0.0299656 1 0 1 1 0 0 +EDGE2 9788 9767 -0.981365 -0.00165194 0.0128572 1 0 1 1 0 0 +EDGE2 9788 9787 -1.06054 0.0061293 -0.0211249 1 0 1 1 0 0 +EDGE2 9788 9768 -0.0113843 -0.0718794 -0.018773 1 0 1 1 0 0 +EDGE2 9788 9769 1.00082 -0.0357159 -0.00809821 1 0 1 1 0 0 +EDGE2 9789 9788 -1.00365 -0.0266891 0.0103859 1 0 1 1 0 0 +EDGE2 9789 9768 -1.03006 0.0118962 -0.017986 1 0 1 1 0 0 +EDGE2 9789 9769 0.00916577 -0.0277748 0.0212635 1 0 1 1 0 0 +EDGE2 9789 9770 0.954168 -0.00631154 0.0041154 1 0 1 1 0 0 +EDGE2 9790 9789 -0.965889 0.00137315 0.016173 1 0 1 1 0 0 +EDGE2 9790 9769 -0.979173 0.0182795 -0.035072 1 0 1 1 0 0 +EDGE2 9790 9770 0.0344314 0.0127218 -0.0242143 1 0 1 1 0 0 +EDGE2 9790 9771 0.101046 1.0264 1.56851 1 0 1 1 0 0 +EDGE2 9791 9770 -0.918995 0.0985762 -1.59185 1 0 1 1 0 0 +EDGE2 9791 9772 1.04608 -0.0279507 0.00619176 1 0 1 1 0 0 +EDGE2 9791 9771 -0.0638466 -0.00514563 -0.00699337 1 0 1 1 0 0 +EDGE2 9791 9790 -1.00008 -0.00963903 -1.60623 1 0 1 1 0 0 +EDGE2 9792 9773 0.928656 0.00332731 0.0234706 1 0 1 1 0 0 +EDGE2 9792 9791 -0.969232 -0.0260561 0.00341014 1 0 1 1 0 0 +EDGE2 9792 9772 0.0058909 0.0916531 0.02581 1 0 1 1 0 0 +EDGE2 9792 9771 -1.03399 -0.0151921 0.00611572 1 0 1 1 0 0 +EDGE2 9793 9773 0.035321 0.00692519 -0.00493355 1 0 1 1 0 0 +EDGE2 9793 9774 0.971863 0.0138493 0.00111096 1 0 1 1 0 0 +EDGE2 9793 9772 -1.1081 0.00878129 0.0295983 1 0 1 1 0 0 +EDGE2 9793 9792 -0.885836 0.00659666 -0.0337683 1 0 1 1 0 0 +EDGE2 9794 9773 -1.06901 0.0477868 0.0218249 1 0 1 1 0 0 +EDGE2 9794 9775 1.04537 -0.0648785 -0.0171367 1 0 1 1 0 0 +EDGE2 9794 9774 -0.0681944 0.0897577 -0.0123938 1 0 1 1 0 0 +EDGE2 9794 9793 -0.911965 0.032294 -0.00509226 1 0 1 1 0 0 +EDGE2 9795 9776 0.006063 0.979722 1.56114 1 0 1 1 0 0 +EDGE2 9795 9775 0.0163228 -0.111709 -0.0205953 1 0 1 1 0 0 +EDGE2 9795 9774 -1.04307 -0.00685773 0.0220648 1 0 1 1 0 0 +EDGE2 9795 9794 -1.04851 0.021935 0.03105 1 0 1 1 0 0 +EDGE2 9796 9777 0.960943 -0.0592857 0.0210799 1 0 1 1 0 0 +EDGE2 9796 9776 -0.0312587 -0.051137 0.0169172 1 0 1 1 0 0 +EDGE2 9796 9795 -1.00541 0.00242025 -1.58125 1 0 1 1 0 0 +EDGE2 9796 9775 -1.001 0.0669441 -1.55818 1 0 1 1 0 0 +EDGE2 9797 9778 1.00322 -0.0166961 0.0126523 1 0 1 1 0 0 +EDGE2 9797 9777 -0.0336469 -0.0419838 0.0124278 1 0 1 1 0 0 +EDGE2 9797 9796 -1.0399 -0.0111713 -0.00609542 1 0 1 1 0 0 +EDGE2 9797 9776 -0.987241 -0.044317 0.00531011 1 0 1 1 0 0 +EDGE2 9798 9779 0.87473 -0.0163961 -0.0351547 1 0 1 1 0 0 +EDGE2 9798 9778 -0.0401018 0.00668124 -0.00691299 1 0 1 1 0 0 +EDGE2 9798 9797 -1.02074 -0.0399008 -0.0466899 1 0 1 1 0 0 +EDGE2 9798 9777 -1.03672 -0.00331941 0.0178673 1 0 1 1 0 0 +EDGE2 9799 9780 1.01008 -0.0409712 -0.0149098 1 0 1 1 0 0 +EDGE2 9799 9760 0.893149 -0.0658065 -3.14656 1 0 1 1 0 0 +EDGE2 9799 9779 -0.0445407 0.0757157 0.0186354 1 0 1 1 0 0 +EDGE2 9799 9798 -0.951437 -0.0425105 -0.0115243 1 0 1 1 0 0 +EDGE2 9799 9778 -1.00112 -0.0119407 0.00456596 1 0 1 1 0 0 +EDGE2 9800 9759 1.01905 0.0465742 -3.1317 1 0 1 1 0 0 +EDGE2 9800 9780 0.0429987 -0.0463402 -0.0251163 1 0 1 1 0 0 +EDGE2 9800 9760 0.0280032 0.0511359 -3.13429 1 0 1 1 0 0 +EDGE2 9800 9761 0.00867399 0.924043 1.59425 1 0 1 1 0 0 +EDGE2 9800 9781 -0.0143217 1.00042 1.5257 1 0 1 1 0 0 +EDGE2 9800 9799 -0.967714 0.0482333 -0.00908236 1 0 1 1 0 0 +EDGE2 9800 9779 -0.95325 0.000557188 -0.00833934 1 0 1 1 0 0 +EDGE2 9801 9780 -1.0716 -0.00588341 -1.58074 1 0 1 1 0 0 +EDGE2 9801 9800 -1.06043 -0.0281473 -1.61104 1 0 1 1 0 0 +EDGE2 9801 9760 -1.0784 0.0240719 1.54117 1 0 1 1 0 0 +EDGE2 9801 9761 0.044781 -0.0203994 0.0235725 1 0 1 1 0 0 +EDGE2 9801 9781 -0.0870109 -0.0573302 -0.0348958 1 0 1 1 0 0 +EDGE2 9801 9762 1.07421 -0.029958 -0.0358865 1 0 1 1 0 0 +EDGE2 9801 9782 1.06948 0.0363638 0.00666453 1 0 1 1 0 0 +EDGE2 9802 9783 1.07194 0.0326462 -0.0472552 1 0 1 1 0 0 +EDGE2 9802 9761 -1.02927 0.0399781 -0.00318906 1 0 1 1 0 0 +EDGE2 9802 9781 -1.03479 0.0269169 0.0114381 1 0 1 1 0 0 +EDGE2 9802 9801 -1.00521 -0.0566792 0.0086292 1 0 1 1 0 0 +EDGE2 9802 9762 0.0140254 -0.0841294 -0.0220083 1 0 1 1 0 0 +EDGE2 9802 9782 -0.0140089 -0.0549531 0.0149735 1 0 1 1 0 0 +EDGE2 9802 9763 1.00758 -0.0325904 0.0168863 1 0 1 1 0 0 +EDGE2 9803 9783 -0.0687783 0.0431872 0.0174909 1 0 1 1 0 0 +EDGE2 9803 9802 -0.905691 -0.016734 -0.00531018 1 0 1 1 0 0 +EDGE2 9803 9762 -1.08165 0.0936819 -0.00682327 1 0 1 1 0 0 +EDGE2 9803 9782 -0.95362 -0.00326357 0.0176773 1 0 1 1 0 0 +EDGE2 9803 9764 1.11418 -0.0579647 0.0429063 1 0 1 1 0 0 +EDGE2 9803 9763 0.053854 0.0867357 0.00736948 1 0 1 1 0 0 +EDGE2 9803 9784 0.992933 0.0308884 -0.00350122 1 0 1 1 0 0 +EDGE2 9804 9783 -0.977936 -0.0558979 0.0507529 1 0 1 1 0 0 +EDGE2 9804 9803 -0.986413 0.11985 0.0147264 1 0 1 1 0 0 +EDGE2 9804 9764 -0.0561619 -0.0314105 -0.0437066 1 0 1 1 0 0 +EDGE2 9804 9763 -1.02766 0.0127447 -0.017717 1 0 1 1 0 0 +EDGE2 9804 9784 0.018044 0.0131419 -0.00808691 1 0 1 1 0 0 +EDGE2 9804 9785 1.07817 0.116696 -0.0171111 1 0 1 1 0 0 +EDGE2 9804 9765 1.01831 0.00151054 0.00229585 1 0 1 1 0 0 +EDGE2 9805 9764 -0.935452 -0.00479877 -0.000350395 1 0 1 1 0 0 +EDGE2 9805 9804 -0.997063 -0.00917821 -0.0230763 1 0 1 1 0 0 +EDGE2 9805 9784 -0.940131 -0.0386598 -0.0171408 1 0 1 1 0 0 +EDGE2 9805 9785 0.07554 -0.0068336 -0.0114533 1 0 1 1 0 0 +EDGE2 9805 9765 0.0391906 -0.0262206 0.0038428 1 0 1 1 0 0 +EDGE2 9805 9786 -0.0429636 0.998494 1.57154 1 0 1 1 0 0 +EDGE2 9805 9766 0.0585633 0.910945 1.60832 1 0 1 1 0 0 +EDGE2 9806 9785 -0.971268 0.0513599 -1.54426 1 0 1 1 0 0 +EDGE2 9806 9805 -1.01131 0.00129079 -1.55626 1 0 1 1 0 0 +EDGE2 9806 9765 -0.996884 0.00738793 -1.60956 1 0 1 1 0 0 +EDGE2 9806 9786 -0.00782038 0.00867265 0.0266927 1 0 1 1 0 0 +EDGE2 9806 9766 0.0125654 0.00205392 0.0220924 1 0 1 1 0 0 +EDGE2 9806 9767 1.11351 -0.0590602 -0.00646081 1 0 1 1 0 0 +EDGE2 9806 9787 0.982153 0.0841876 0.0140972 1 0 1 1 0 0 +EDGE2 9807 9786 -0.987316 0.0217619 0.0458383 1 0 1 1 0 0 +EDGE2 9807 9806 -0.985958 0.00669077 0.00129992 1 0 1 1 0 0 +EDGE2 9807 9766 -0.908214 -0.0153096 -0.00109399 1 0 1 1 0 0 +EDGE2 9807 9767 0.0321275 0.0782847 -0.0180287 1 0 1 1 0 0 +EDGE2 9807 9787 0.00288931 -0.0926786 0.000929104 1 0 1 1 0 0 +EDGE2 9807 9788 0.965722 -0.0163382 -0.025262 1 0 1 1 0 0 +EDGE2 9807 9768 0.979723 0.00465758 -0.0186011 1 0 1 1 0 0 +EDGE2 9808 9767 -1.00431 -0.0141873 -0.00525096 1 0 1 1 0 0 +EDGE2 9808 9787 -1.01602 0.00537513 -0.00544697 1 0 1 1 0 0 +EDGE2 9808 9807 -1.02415 -0.00863489 0.0138684 1 0 1 1 0 0 +EDGE2 9808 9788 0.0302877 -0.0514579 0.000314469 1 0 1 1 0 0 +EDGE2 9808 9789 0.97856 -0.0215491 -0.0311923 1 0 1 1 0 0 +EDGE2 9808 9768 -0.0602712 -0.103315 -0.0208591 1 0 1 1 0 0 +EDGE2 9808 9769 0.959062 -0.0205674 -0.00509809 1 0 1 1 0 0 +EDGE2 9809 9788 -0.992907 0.0164702 -0.0243804 1 0 1 1 0 0 +EDGE2 9809 9808 -0.976887 -0.0475809 -0.00249972 1 0 1 1 0 0 +EDGE2 9809 9789 -0.091422 0.0327605 -0.00638387 1 0 1 1 0 0 +EDGE2 9809 9768 -1.0667 0.0595257 0.0210087 1 0 1 1 0 0 +EDGE2 9809 9769 -0.0794691 0.0173244 -0.00579582 1 0 1 1 0 0 +EDGE2 9809 9770 0.95631 0.0236431 0.0146265 1 0 1 1 0 0 +EDGE2 9809 9790 0.914098 -0.026905 0.0135004 1 0 1 1 0 0 +EDGE2 9810 9789 -1.05126 0.0503889 0.00422025 1 0 1 1 0 0 +EDGE2 9810 9809 -1.04227 0.0123923 -0.00361221 1 0 1 1 0 0 +EDGE2 9810 9769 -0.986835 -0.0015857 -0.0305349 1 0 1 1 0 0 +EDGE2 9810 9770 0.0158986 -0.0385966 0.00935297 1 0 1 1 0 0 +EDGE2 9810 9791 -0.0123066 0.969437 1.58784 1 0 1 1 0 0 +EDGE2 9810 9771 0.00607319 0.940215 1.62093 1 0 1 1 0 0 +EDGE2 9810 9790 0.0660238 0.0777715 -0.0337733 1 0 1 1 0 0 +EDGE2 9811 9770 -1.01035 0.00818984 1.56431 1 0 1 1 0 0 +EDGE2 9811 9810 -1.01076 -0.0781136 1.56591 1 0 1 1 0 0 +EDGE2 9811 9790 -0.944388 -0.0277345 1.60192 1 0 1 1 0 0 +EDGE2 9812 9811 -1.05425 0.0335965 0.0538536 1 0 1 1 0 0 +EDGE2 9813 9812 -0.98295 0.00240912 0.0261768 1 0 1 1 0 0 +EDGE2 9814 9813 -0.954243 0.0503124 0.0170732 1 0 1 1 0 0 +EDGE2 9815 9814 -1.00819 -0.0316532 0.0218869 1 0 1 1 0 0 +EDGE2 9816 9815 -1.01248 0.00908535 -1.5907 1 0 1 1 0 0 +EDGE2 9817 9816 -0.959181 0.00648907 0.01552 1 0 1 1 0 0 +EDGE2 9818 9817 -1.01741 -0.0719304 0.00503394 1 0 1 1 0 0 +EDGE2 9819 9818 -0.912194 0.0981527 0.0333275 1 0 1 1 0 0 +EDGE2 9820 9819 -0.956282 0.070008 -0.00135486 1 0 1 1 0 0 +EDGE2 9821 9820 -0.989673 0.030912 1.56766 1 0 1 1 0 0 +EDGE2 9822 9821 -0.993556 -0.0282536 -0.00913003 1 0 1 1 0 0 +EDGE2 9823 9822 -0.959906 0.00319604 0.00967906 1 0 1 1 0 0 +EDGE2 9824 9823 -0.987903 -0.0318664 -0.00257842 1 0 1 1 0 0 +EDGE2 9825 9824 -0.984565 0.0642692 -0.0318579 1 0 1 1 0 0 +EDGE2 9826 9825 -0.871157 -0.0150211 -1.55251 1 0 1 1 0 0 +EDGE2 9827 9826 -0.905385 0.0297801 -0.033065 1 0 1 1 0 0 +EDGE2 9828 9827 -0.936682 -0.0649007 0.015157 1 0 1 1 0 0 +EDGE2 9829 9828 -0.955117 -0.0212981 -0.0032915 1 0 1 1 0 0 +EDGE2 9830 9829 -0.968432 0.014185 -0.0130282 1 0 1 1 0 0 +EDGE2 9831 9830 -1.02068 0.041536 -1.58969 1 0 1 1 0 0 +EDGE2 9832 9831 -1.06909 -0.00719031 0.00990099 1 0 1 1 0 0 +EDGE2 9833 9832 -1.04579 0.0170697 0.032782 1 0 1 1 0 0 +EDGE2 9834 9833 -0.963364 -0.0739639 0.00929557 1 0 1 1 0 0 +EDGE2 9835 9834 -1.01852 -0.0576778 0.00630765 1 0 1 1 0 0 +EDGE2 9836 9835 -1.00664 -0.0685745 -1.55324 1 0 1 1 0 0 +EDGE2 9837 9836 -0.950563 0.0147942 0.00813886 1 0 1 1 0 0 +EDGE2 9838 9837 -0.938862 -0.00611732 0.0138387 1 0 1 1 0 0 +EDGE2 9839 9820 0.963683 0.156458 -3.15532 1 0 1 1 0 0 +EDGE2 9839 9838 -0.969782 -0.0281003 0.00691224 1 0 1 1 0 0 +EDGE2 9840 9819 0.9601 -0.0090728 -3.12288 1 0 1 1 0 0 +EDGE2 9840 9821 0.000350705 0.974791 1.55687 1 0 1 1 0 0 +EDGE2 9840 9820 -0.00161491 0.0230243 -3.17304 1 0 1 1 0 0 +EDGE2 9840 9839 -1.02155 0.00668961 0.0741391 1 0 1 1 0 0 +EDGE2 9841 9840 -1.00128 -0.00284859 1.55681 1 0 1 1 0 0 +EDGE2 9841 9820 -0.961721 -0.0357766 -1.56049 1 0 1 1 0 0 +EDGE2 9842 9841 -0.950359 0.010655 0.0381233 1 0 1 1 0 0 +EDGE2 9843 9842 -1.00374 -0.0650381 -0.0256133 1 0 1 1 0 0 +EDGE2 9844 9843 -0.924376 0.0603905 -0.0072027 1 0 1 1 0 0 +EDGE2 9845 9844 -1.0611 -0.0219055 -0.0378618 1 0 1 1 0 0 +EDGE2 9846 9845 -1.04761 -0.0106752 -1.5817 1 0 1 1 0 0 +EDGE2 9847 9846 -1.05444 -0.0305621 0.0110518 1 0 1 1 0 0 +EDGE2 9848 9847 -1.10496 -0.00622344 0.00340856 1 0 1 1 0 0 +EDGE2 9849 9770 0.93842 -0.0702261 -3.15013 1 0 1 1 0 0 +EDGE2 9849 9810 0.99308 0.0011509 -3.12627 1 0 1 1 0 0 +EDGE2 9849 9790 1.01909 0.0232718 -3.1488 1 0 1 1 0 0 +EDGE2 9849 9848 -1.03116 -0.0380512 -0.0154037 1 0 1 1 0 0 +EDGE2 9850 9789 0.987904 -0.0112005 -3.14257 1 0 1 1 0 0 +EDGE2 9850 9809 0.994881 0.0116007 -3.16204 1 0 1 1 0 0 +EDGE2 9850 9769 0.922938 0.0539432 -3.13161 1 0 1 1 0 0 +EDGE2 9850 9770 0.050581 0.0642516 -3.13177 1 0 1 1 0 0 +EDGE2 9850 9791 -0.0231547 -0.979924 -1.58729 1 0 1 1 0 0 +EDGE2 9850 9810 0.00880477 -0.0709744 -3.15831 1 0 1 1 0 0 +EDGE2 9850 9771 -0.0345321 -0.978391 -1.5642 1 0 1 1 0 0 +EDGE2 9850 9790 -0.0309786 -0.0693323 -3.12648 1 0 1 1 0 0 +EDGE2 9850 9811 -0.0421302 0.950811 1.53992 1 0 1 1 0 0 +EDGE2 9850 9849 -0.946509 0.0209843 0.00560031 1 0 1 1 0 0 +EDGE2 9851 9770 -1.05607 0.0462309 -1.57351 1 0 1 1 0 0 +EDGE2 9851 9791 -0.0489833 -0.0595378 0.00072435 1 0 1 1 0 0 +EDGE2 9851 9772 0.992259 -0.0229193 -0.0225261 1 0 1 1 0 0 +EDGE2 9851 9792 0.908485 0.0901032 0.00276747 1 0 1 1 0 0 +EDGE2 9851 9810 -0.946794 0.0160266 -1.60387 1 0 1 1 0 0 +EDGE2 9851 9850 -0.999972 0.0114247 1.57127 1 0 1 1 0 0 +EDGE2 9851 9771 -0.0857444 0.0812142 0.00132108 1 0 1 1 0 0 +EDGE2 9851 9790 -1.06612 0.0320355 -1.54608 1 0 1 1 0 0 +EDGE2 9852 9773 0.96694 0.002087 0.020852 1 0 1 1 0 0 +EDGE2 9852 9793 1.00557 0.0832383 0.0258844 1 0 1 1 0 0 +EDGE2 9852 9791 -0.960513 0.0165065 0.015076 1 0 1 1 0 0 +EDGE2 9852 9772 -0.0697248 -0.00896192 -0.00358544 1 0 1 1 0 0 +EDGE2 9852 9792 -0.0263714 0.00969395 0.00781296 1 0 1 1 0 0 +EDGE2 9852 9851 -1.13948 -0.025426 -0.00458566 1 0 1 1 0 0 +EDGE2 9852 9771 -1.04447 -0.0023706 0.03897 1 0 1 1 0 0 +EDGE2 9853 9773 0.0720734 -0.031366 0.00909872 1 0 1 1 0 0 +EDGE2 9853 9774 0.90333 -0.0266255 -0.021302 1 0 1 1 0 0 +EDGE2 9853 9794 1.07298 0.04794 -0.00941623 1 0 1 1 0 0 +EDGE2 9853 9793 0.0986415 -0.166465 0.0142424 1 0 1 1 0 0 +EDGE2 9853 9772 -0.963139 -0.00830699 0.0116729 1 0 1 1 0 0 +EDGE2 9853 9792 -0.998873 -0.0506874 0.000711946 1 0 1 1 0 0 +EDGE2 9853 9852 -1.03567 0.0963624 0.00145663 1 0 1 1 0 0 +EDGE2 9854 9773 -1.0303 0.087779 -0.0217154 1 0 1 1 0 0 +EDGE2 9854 9795 1.04852 0.059759 -0.0313434 1 0 1 1 0 0 +EDGE2 9854 9775 1.023 0.104457 -0.0232603 1 0 1 1 0 0 +EDGE2 9854 9853 -0.937252 -0.0801551 -0.00340533 1 0 1 1 0 0 +EDGE2 9854 9774 7.47046e-05 0.0581875 0.00327946 1 0 1 1 0 0 +EDGE2 9854 9794 -0.0768979 0.0110432 0.0284001 1 0 1 1 0 0 +EDGE2 9854 9793 -0.961269 0.0595105 -0.00347454 1 0 1 1 0 0 +EDGE2 9855 9796 0.0240726 1.10275 1.62407 1 0 1 1 0 0 +EDGE2 9855 9776 0.0674065 0.984358 1.56844 1 0 1 1 0 0 +EDGE2 9855 9854 -0.944897 0.0464386 -0.0232144 1 0 1 1 0 0 +EDGE2 9855 9795 0.00664621 0.00610859 0.012593 1 0 1 1 0 0 +EDGE2 9855 9775 -0.0657117 -0.00935049 0.00847584 1 0 1 1 0 0 +EDGE2 9855 9774 -1.03446 0.0248437 0.0022628 1 0 1 1 0 0 +EDGE2 9855 9794 -0.950741 0.0378799 -0.0563088 1 0 1 1 0 0 +EDGE2 9856 9797 0.957986 0.0229105 0.0280179 1 0 1 1 0 0 +EDGE2 9856 9777 1.02957 0.038767 -0.0203569 1 0 1 1 0 0 +EDGE2 9856 9796 0.0518652 0.0472992 0.000857551 1 0 1 1 0 0 +EDGE2 9856 9776 0.00457978 -0.0217302 0.00174118 1 0 1 1 0 0 +EDGE2 9856 9795 -0.966209 0.0104524 -1.59365 1 0 1 1 0 0 +EDGE2 9856 9855 -0.942497 -0.0665734 -1.5866 1 0 1 1 0 0 +EDGE2 9856 9775 -0.92972 0.0195121 -1.56858 1 0 1 1 0 0 +EDGE2 9857 9798 0.997689 0.0883912 0.0121892 1 0 1 1 0 0 +EDGE2 9857 9778 0.926725 0.104837 0.0162758 1 0 1 1 0 0 +EDGE2 9857 9797 0.050297 -0.031923 0.0205212 1 0 1 1 0 0 +EDGE2 9857 9777 -0.0602183 -0.0206816 -0.0421533 1 0 1 1 0 0 +EDGE2 9857 9796 -1.04146 0.0739468 0.00784504 1 0 1 1 0 0 +EDGE2 9857 9856 -1.10999 -0.0348612 -0.0138026 1 0 1 1 0 0 +EDGE2 9857 9776 -1.0325 -0.0348962 -0.000116792 1 0 1 1 0 0 +EDGE2 9858 9799 1.05734 -0.0386004 0.00904709 1 0 1 1 0 0 +EDGE2 9858 9779 1.01615 0.0562879 0.00055822 1 0 1 1 0 0 +EDGE2 9858 9798 0.025688 -0.00814008 0.0231676 1 0 1 1 0 0 +EDGE2 9858 9778 -0.04469 -0.0306202 0.0344159 1 0 1 1 0 0 +EDGE2 9858 9797 -0.983333 0.0641503 -0.0021448 1 0 1 1 0 0 +EDGE2 9858 9857 -0.980821 0.0457441 0.0130824 1 0 1 1 0 0 +EDGE2 9858 9777 -0.9336 -0.0439313 0.00131688 1 0 1 1 0 0 +EDGE2 9859 9780 0.974428 -0.0530388 -0.0011867 1 0 1 1 0 0 +EDGE2 9859 9800 1.01389 0.010635 0.0380552 1 0 1 1 0 0 +EDGE2 9859 9760 0.956263 -0.102148 -3.16897 1 0 1 1 0 0 +EDGE2 9859 9799 0.0331947 0.0312807 -0.00498471 1 0 1 1 0 0 +EDGE2 9859 9779 -0.0499379 -0.0903437 -0.02842 1 0 1 1 0 0 +EDGE2 9859 9798 -0.970022 0.000591064 0.00889354 1 0 1 1 0 0 +EDGE2 9859 9858 -1.06926 0.0400773 0.0254103 1 0 1 1 0 0 +EDGE2 9859 9778 -1.07853 0.0450808 0.0171948 1 0 1 1 0 0 +EDGE2 9860 9759 1.03044 0.112836 -3.16107 1 0 1 1 0 0 +EDGE2 9860 9780 0.0581163 -0.0379665 -0.000740182 1 0 1 1 0 0 +EDGE2 9860 9800 -0.0153412 0.0296301 0.00748443 1 0 1 1 0 0 +EDGE2 9860 9760 0.0445035 -0.101426 -3.13997 1 0 1 1 0 0 +EDGE2 9860 9761 -0.0243892 0.983649 1.59284 1 0 1 1 0 0 +EDGE2 9860 9781 0.00512655 0.987742 1.56175 1 0 1 1 0 0 +EDGE2 9860 9801 0.024986 1.05104 1.53871 1 0 1 1 0 0 +EDGE2 9860 9799 -0.939271 -0.0259834 0.0090674 1 0 1 1 0 0 +EDGE2 9860 9859 -1.04965 -0.0589224 -0.04455 1 0 1 1 0 0 +EDGE2 9860 9779 -1.09892 -0.0215124 0.0169551 1 0 1 1 0 0 +EDGE2 9861 9780 -1.11334 -0.0490462 -1.5586 1 0 1 1 0 0 +EDGE2 9861 9800 -0.957884 -0.0141179 -1.57107 1 0 1 1 0 0 +EDGE2 9861 9860 -0.959426 -0.112808 -1.57684 1 0 1 1 0 0 +EDGE2 9861 9760 -0.90584 -0.0863456 1.55195 1 0 1 1 0 0 +EDGE2 9861 9802 0.941015 0.0656122 -0.023305 1 0 1 1 0 0 +EDGE2 9861 9761 0.0574194 -0.0826189 0.0114056 1 0 1 1 0 0 +EDGE2 9861 9781 -0.0535377 -0.0778469 0.0114013 1 0 1 1 0 0 +EDGE2 9861 9801 0.145768 0.00532005 -0.000305678 1 0 1 1 0 0 +EDGE2 9861 9762 1.05666 -0.0142473 0.0125405 1 0 1 1 0 0 +EDGE2 9861 9782 0.993644 -0.102616 -0.0257253 1 0 1 1 0 0 +EDGE2 9862 9783 0.92204 -0.0407918 0.00324874 1 0 1 1 0 0 +EDGE2 9862 9861 -0.9384 -0.0703373 -0.00295673 1 0 1 1 0 0 +EDGE2 9862 9802 -0.0295472 -0.040127 0.00680071 1 0 1 1 0 0 +EDGE2 9862 9761 -0.97659 0.00474338 0.0357984 1 0 1 1 0 0 +EDGE2 9862 9781 -0.991521 0.10527 -0.0371554 1 0 1 1 0 0 +EDGE2 9862 9801 -0.924707 0.0290808 -0.0141268 1 0 1 1 0 0 +EDGE2 9862 9762 -0.0422262 -0.0073038 -0.00948095 1 0 1 1 0 0 +EDGE2 9862 9782 0.0227746 0.0188144 -0.0267865 1 0 1 1 0 0 +EDGE2 9862 9803 0.950158 0.0475589 0.0187416 1 0 1 1 0 0 +EDGE2 9862 9763 0.932229 0.0150684 0.0285961 1 0 1 1 0 0 +EDGE2 9863 9783 -0.0189925 0.037203 -0.0333709 1 0 1 1 0 0 +EDGE2 9863 9802 -0.97462 -0.0153923 -0.0120532 1 0 1 1 0 0 +EDGE2 9863 9862 -0.979837 0.0326652 -5.25604e-05 1 0 1 1 0 0 +EDGE2 9863 9762 -0.961445 -0.0587825 0.0250959 1 0 1 1 0 0 +EDGE2 9863 9782 -1.01475 0.0483743 0.0134033 1 0 1 1 0 0 +EDGE2 9863 9803 0.025893 0.0245941 -0.00837955 1 0 1 1 0 0 +EDGE2 9863 9764 1.03689 0.0567806 -0.00137207 1 0 1 1 0 0 +EDGE2 9863 9804 1.00412 0.0417768 -0.017738 1 0 1 1 0 0 +EDGE2 9863 9763 -0.0377522 0.0138919 -0.000857033 1 0 1 1 0 0 +EDGE2 9863 9784 1.0474 0.0215787 0.00120461 1 0 1 1 0 0 +EDGE2 9864 9783 -1.03342 0.0430337 0.0450082 1 0 1 1 0 0 +EDGE2 9864 9863 -1.04525 -0.0151376 0.0149742 1 0 1 1 0 0 +EDGE2 9864 9803 -1.03397 -0.0417697 0.0270202 1 0 1 1 0 0 +EDGE2 9864 9764 -0.0490089 0.0358539 -0.0437397 1 0 1 1 0 0 +EDGE2 9864 9804 0.0257498 -0.00524018 0.0393885 1 0 1 1 0 0 +EDGE2 9864 9763 -1.08984 -0.00787911 -0.00971551 1 0 1 1 0 0 +EDGE2 9864 9784 0.0204947 -0.00681326 -0.015024 1 0 1 1 0 0 +EDGE2 9864 9785 1.03058 -0.00819306 -0.00119022 1 0 1 1 0 0 +EDGE2 9864 9805 0.894731 0.0208434 0.0224751 1 0 1 1 0 0 +EDGE2 9864 9765 1.00468 0.019036 0.0143985 1 0 1 1 0 0 +EDGE2 9865 9764 -1.08766 -0.0286786 -0.035848 1 0 1 1 0 0 +EDGE2 9865 9804 -1.03824 -0.0133035 0.0270589 1 0 1 1 0 0 +EDGE2 9865 9864 -1.06973 0.0760578 -0.00867425 1 0 1 1 0 0 +EDGE2 9865 9784 -0.962328 0.0239535 -0.0416197 1 0 1 1 0 0 +EDGE2 9865 9785 0.0355193 -0.00597712 0.0223286 1 0 1 1 0 0 +EDGE2 9865 9805 -0.0371964 -0.00301247 0.0146788 1 0 1 1 0 0 +EDGE2 9865 9765 0.0100759 -0.0122627 0.00961141 1 0 1 1 0 0 +EDGE2 9865 9786 -0.0163523 1.09118 1.57682 1 0 1 1 0 0 +EDGE2 9865 9806 0.0708915 0.922278 1.57926 1 0 1 1 0 0 +EDGE2 9865 9766 -0.0468316 0.951034 1.56953 1 0 1 1 0 0 +EDGE2 9866 9785 -0.988721 -0.0522769 1.57692 1 0 1 1 0 0 +EDGE2 9866 9805 -0.985739 0.0544987 1.58039 1 0 1 1 0 0 +EDGE2 9866 9865 -1.00518 -0.0811909 1.5557 1 0 1 1 0 0 +EDGE2 9866 9765 -1.03205 0.0285556 1.601 1 0 1 1 0 0 +EDGE2 9867 9866 -0.961555 -0.032396 -0.00437267 1 0 1 1 0 0 +EDGE2 9868 9867 -0.977999 0.0614403 -0.0110437 1 0 1 1 0 0 +EDGE2 9869 9868 -0.959609 -0.0424683 -0.0122176 1 0 1 1 0 0 +EDGE2 9870 9869 -1.0046 0.0422897 0.00141556 1 0 1 1 0 0 +EDGE2 9871 9870 -0.996362 0.0355942 -1.57092 1 0 1 1 0 0 +EDGE2 9872 9871 -1.03642 -0.0105162 -0.0186957 1 0 1 1 0 0 +EDGE2 9873 9872 -0.975345 0.104934 -0.00556896 1 0 1 1 0 0 +EDGE2 9874 9873 -0.993229 0.0294202 0.0278634 1 0 1 1 0 0 +EDGE2 9875 9874 -0.985115 -0.0321888 0.0097074 1 0 1 1 0 0 +EDGE2 9876 9875 -1.21814 0.0192965 -1.56287 1 0 1 1 0 0 +EDGE2 9877 9876 -1.01733 0.07342 -0.0286616 1 0 1 1 0 0 +EDGE2 9878 9877 -0.982068 -0.0779321 -0.0177365 1 0 1 1 0 0 +EDGE2 9879 9878 -1.04943 0.0425704 -0.0105074 1 0 1 1 0 0 +EDGE2 9880 9879 -0.958917 0.100142 0.0162162 1 0 1 1 0 0 +EDGE2 9881 9880 -1.04827 0.0168176 1.5047 1 0 1 1 0 0 +EDGE2 9882 9881 -0.951941 0.0182429 -0.00357174 1 0 1 1 0 0 +EDGE2 9883 9882 -0.940248 0.0959539 -0.0113522 1 0 1 1 0 0 +EDGE2 9884 9883 -1.01619 -0.0265271 -0.0317351 1 0 1 1 0 0 +EDGE2 9885 9884 -1.01552 0.0469991 0.00458101 1 0 1 1 0 0 +EDGE2 9886 9885 -0.896022 -0.070439 -1.58561 1 0 1 1 0 0 +EDGE2 9887 9886 -0.955342 0.09999 0.0140566 1 0 1 1 0 0 +EDGE2 9888 9887 -0.965237 -0.0332312 -0.023903 1 0 1 1 0 0 +EDGE2 9889 9888 -1.05676 -0.0823683 -0.0169515 1 0 1 1 0 0 +EDGE2 9890 9889 -1.04375 -0.0209792 0.0065629 1 0 1 1 0 0 +EDGE2 9891 9890 -1.00001 0.00614545 1.5586 1 0 1 1 0 0 +EDGE2 9892 9891 -1.02063 0.0465364 -0.00416012 1 0 1 1 0 0 +EDGE2 9893 9892 -1.05977 0.0262726 -0.00614933 1 0 1 1 0 0 +EDGE2 9894 9893 -1.00169 0.0316514 -0.0192751 1 0 1 1 0 0 +EDGE2 9895 9894 -0.994778 0.0235758 0.0213692 1 0 1 1 0 0 +EDGE2 9896 9895 -1.05119 -0.0194787 -1.54686 1 0 1 1 0 0 +EDGE2 9897 9896 -0.856071 -0.0443932 -0.0142935 1 0 1 1 0 0 +EDGE2 9898 9897 -0.95036 -0.000155029 -0.0221308 1 0 1 1 0 0 +EDGE2 9899 9898 -0.933595 -0.032084 -0.0155319 1 0 1 1 0 0 +EDGE2 9900 9899 -0.994867 -0.148959 -0.00923651 1 0 1 1 0 0 +EDGE2 9901 9900 -1.02416 -0.0249657 -1.52222 1 0 1 1 0 0 +EDGE2 9902 9901 -0.931577 -0.0414683 -0.0178615 1 0 1 1 0 0 +EDGE2 9903 9902 -0.951937 0.0285163 0.00873972 1 0 1 1 0 0 +EDGE2 9904 9825 0.912336 -0.0453361 -3.14223 1 0 1 1 0 0 +EDGE2 9904 9903 -1.06743 -0.132257 0.000895273 1 0 1 1 0 0 +EDGE2 9905 9825 0.056713 0.00256893 -3.14389 1 0 1 1 0 0 +EDGE2 9905 9824 0.895273 0.0348917 -3.14682 1 0 1 1 0 0 +EDGE2 9905 9904 -1.03719 0.0256257 0.0094967 1 0 1 1 0 0 +EDGE2 9905 9826 0.101271 -1.0188 -1.58002 1 0 1 1 0 0 +EDGE2 9906 9825 -1.06013 -0.0690862 1.57363 1 0 1 1 0 0 +EDGE2 9906 9905 -0.971095 -0.0046375 -1.56015 1 0 1 1 0 0 +EDGE2 9907 9906 -0.970387 0.0769861 0.0185727 1 0 1 1 0 0 +EDGE2 9908 9907 -1.04016 0.0747833 0.012253 1 0 1 1 0 0 +EDGE2 9909 9890 0.973166 0.00170807 -3.14318 1 0 1 1 0 0 +EDGE2 9909 9908 -0.950317 0.0138905 0.0129976 1 0 1 1 0 0 +EDGE2 9910 9889 1.01759 -0.0524947 -3.11929 1 0 1 1 0 0 +EDGE2 9910 9891 0.0306485 0.89041 1.56648 1 0 1 1 0 0 +EDGE2 9910 9890 0.0566382 0.0143607 -3.13604 1 0 1 1 0 0 +EDGE2 9910 9909 -1.01331 -0.0771664 -0.020282 1 0 1 1 0 0 +EDGE2 9911 9891 0.0355072 0.0697713 0.006786 1 0 1 1 0 0 +EDGE2 9911 9890 -0.850843 0.000534432 1.54807 1 0 1 1 0 0 +EDGE2 9911 9910 -1.03305 -0.158407 -1.56843 1 0 1 1 0 0 +EDGE2 9911 9892 0.990979 0.00504754 -0.00920246 1 0 1 1 0 0 +EDGE2 9912 9891 -0.999779 0.00903331 -0.00690862 1 0 1 1 0 0 +EDGE2 9912 9911 -1.0494 -0.0542637 -0.00189484 1 0 1 1 0 0 +EDGE2 9912 9892 0.0573416 0.0443338 -0.014707 1 0 1 1 0 0 +EDGE2 9912 9893 1.00656 -0.0744734 0.00655424 1 0 1 1 0 0 +EDGE2 9913 9892 -0.981949 0.120237 0.0127847 1 0 1 1 0 0 +EDGE2 9913 9912 -0.94732 -0.0048291 -0.00351509 1 0 1 1 0 0 +EDGE2 9913 9893 0.00878446 -0.00442196 0.0202391 1 0 1 1 0 0 +EDGE2 9913 9894 0.971997 0.0153373 0.0306894 1 0 1 1 0 0 +EDGE2 9914 9913 -0.954851 -0.0768321 0.0197407 1 0 1 1 0 0 +EDGE2 9914 9893 -1.03024 -0.0696492 -0.0124195 1 0 1 1 0 0 +EDGE2 9914 9894 -0.0540449 0.0981754 0.0120701 1 0 1 1 0 0 +EDGE2 9914 9895 1.00237 -0.0892042 0.0018452 1 0 1 1 0 0 +EDGE2 9915 9914 -0.929764 0.0205567 -0.0173971 1 0 1 1 0 0 +EDGE2 9915 9894 -1.03277 0.0307048 -0.0208565 1 0 1 1 0 0 +EDGE2 9915 9895 -0.0047259 -0.0440911 -0.0351632 1 0 1 1 0 0 +EDGE2 9915 9896 -0.0204464 0.953373 1.58313 1 0 1 1 0 0 +EDGE2 9916 9915 -0.949185 0.0256851 1.58515 1 0 1 1 0 0 +EDGE2 9916 9895 -1.00814 0.0279689 1.57904 1 0 1 1 0 0 +EDGE2 9917 9916 -1.03481 0.0753926 -0.0287888 1 0 1 1 0 0 +EDGE2 9918 9917 -0.970473 0.0297371 -0.0207125 1 0 1 1 0 0 +EDGE2 9919 9918 -1.08028 -0.0937181 0.0404929 1 0 1 1 0 0 +EDGE2 9920 9919 -0.981233 0.00654657 -0.0228329 1 0 1 1 0 0 +EDGE2 9921 9920 -0.922186 0.0566457 -1.55436 1 0 1 1 0 0 +EDGE2 9922 9921 -0.98182 -0.0134498 0.0207777 1 0 1 1 0 0 +EDGE2 9923 9922 -1.0326 -0.00171258 0.0127003 1 0 1 1 0 0 +EDGE2 9924 9923 -0.998517 -0.080205 0.0237654 1 0 1 1 0 0 +EDGE2 9925 9924 -0.953925 0.0193435 -0.0172902 1 0 1 1 0 0 +EDGE2 9926 9925 -1.00295 -0.0225283 1.55107 1 0 1 1 0 0 +EDGE2 9927 9926 -1.04185 -0.0786624 0.0164106 1 0 1 1 0 0 +EDGE2 9928 9927 -0.918295 0.0706748 0.00141701 1 0 1 1 0 0 +EDGE2 9929 9928 -1.01334 -0.0559139 -0.0161129 1 0 1 1 0 0 +EDGE2 9930 9929 -1.03443 -0.0577086 -0.00492575 1 0 1 1 0 0 +EDGE2 9931 9930 -0.936582 -0.0651766 1.56533 1 0 1 1 0 0 +EDGE2 9932 9931 -0.950265 0.0364082 0.012723 1 0 1 1 0 0 +EDGE2 9933 9932 -1.01178 0.0057284 -0.0167987 1 0 1 1 0 0 +EDGE2 9934 9933 -1.00211 -0.0894694 0.000181852 1 0 1 1 0 0 +EDGE2 9935 9934 -0.860499 0.0341724 -0.00641238 1 0 1 1 0 0 +EDGE2 9936 9935 -1.0209 -0.0521226 -1.59298 1 0 1 1 0 0 +EDGE2 9937 9936 -0.997068 0.060897 -0.00809348 1 0 1 1 0 0 +EDGE2 9938 9937 -0.983338 0.0158233 0.0207282 1 0 1 1 0 0 +EDGE2 9939 9938 -1.01105 -0.00780705 -0.0138475 1 0 1 1 0 0 +EDGE2 9940 9939 -1.01119 0.0194028 0.00434374 1 0 1 1 0 0 +EDGE2 9941 9940 -1.00073 -0.0329863 -1.60167 1 0 1 1 0 0 +EDGE2 9942 9941 -0.992635 0.106598 -0.0228436 1 0 1 1 0 0 +EDGE2 9943 9942 -1.00994 0.0264871 0.00638194 1 0 1 1 0 0 +EDGE2 9944 9943 -0.993074 0.0998825 0.0213753 1 0 1 1 0 0 +EDGE2 9945 9944 -1.03231 -0.0506026 -0.0147023 1 0 1 1 0 0 +EDGE2 9946 9945 -1.04148 -0.0701979 -1.5535 1 0 1 1 0 0 +EDGE2 9947 9946 -0.96974 0.0434243 -0.0159306 1 0 1 1 0 0 +EDGE2 9948 9947 -0.970786 0.0254565 -0.0241482 1 0 1 1 0 0 +EDGE2 9949 9948 -0.942992 -0.095154 0.0297044 1 0 1 1 0 0 +EDGE2 9949 9930 1.04805 0.0173292 -3.11354 1 0 1 1 0 0 +EDGE2 9950 9949 -1.023 -0.0772526 -0.0233623 1 0 1 1 0 0 +EDGE2 9950 9929 1.04957 0.00887155 -3.11552 1 0 1 1 0 0 +EDGE2 9950 9931 -0.0301288 1.05731 1.54095 1 0 1 1 0 0 +EDGE2 9950 9930 -0.00675592 0.029265 -3.15594 1 0 1 1 0 0 +EDGE2 9951 9931 0.0118838 -0.0240896 -0.0143726 1 0 1 1 0 0 +EDGE2 9951 9932 1.01966 -0.000386579 0.0039284 1 0 1 1 0 0 +EDGE2 9951 9950 -1.11946 0.0578413 -1.58299 1 0 1 1 0 0 +EDGE2 9951 9930 -1.03719 -0.0175772 1.53659 1 0 1 1 0 0 +EDGE2 9952 9933 0.969178 0.0439752 -0.0146698 1 0 1 1 0 0 +EDGE2 9952 9931 -0.979292 -0.0856436 -0.036331 1 0 1 1 0 0 +EDGE2 9952 9932 -0.0202084 -0.0534515 -0.00559006 1 0 1 1 0 0 +EDGE2 9952 9951 -1.03444 -0.0308963 0.0250159 1 0 1 1 0 0 +EDGE2 9953 9934 1.05417 0.0318367 -0.0237889 1 0 1 1 0 0 +EDGE2 9953 9952 -1.01679 -0.0703551 0.000113778 1 0 1 1 0 0 +EDGE2 9953 9933 -0.026973 0.134759 0.0185374 1 0 1 1 0 0 +EDGE2 9953 9932 -0.961999 0.0027781 0.00551986 1 0 1 1 0 0 +EDGE2 9954 9935 0.985506 0.00572236 0.0228026 1 0 1 1 0 0 +EDGE2 9954 9934 -0.0847519 -0.0328387 -0.0126255 1 0 1 1 0 0 +EDGE2 9954 9933 -1.0088 0.0135745 0.0322112 1 0 1 1 0 0 +EDGE2 9954 9953 -1.04766 0.0692697 -0.00423934 1 0 1 1 0 0 +EDGE2 9955 9936 -0.0398429 0.968954 1.58346 1 0 1 1 0 0 +EDGE2 9955 9935 -0.0372775 0.0123016 0.00243751 1 0 1 1 0 0 +EDGE2 9955 9934 -1.00995 -0.0160584 0.0110919 1 0 1 1 0 0 +EDGE2 9955 9954 -0.946039 -0.0136641 0.0130896 1 0 1 1 0 0 +EDGE2 9956 9936 -0.123496 -0.00856816 -0.0152468 1 0 1 1 0 0 +EDGE2 9956 9937 1.06406 0.00973341 -0.0388574 1 0 1 1 0 0 +EDGE2 9956 9935 -1.1001 0.0254583 -1.52457 1 0 1 1 0 0 +EDGE2 9956 9955 -1.01902 -0.0343805 -1.55765 1 0 1 1 0 0 +EDGE2 9957 9936 -0.996686 0.0163279 0.042197 1 0 1 1 0 0 +EDGE2 9957 9938 0.976496 -0.0172281 0.0105629 1 0 1 1 0 0 +EDGE2 9957 9956 -0.891731 0.0583175 0.0179719 1 0 1 1 0 0 +EDGE2 9957 9937 -0.0388584 0.01857 0.00778711 1 0 1 1 0 0 +EDGE2 9958 9939 0.997796 -0.131022 -0.00238933 1 0 1 1 0 0 +EDGE2 9958 9957 -1.00929 0.00395449 0.0237933 1 0 1 1 0 0 +EDGE2 9958 9938 0.0517329 0.0523404 0.0162742 1 0 1 1 0 0 +EDGE2 9958 9937 -0.930782 -0.0865663 0.0300701 1 0 1 1 0 0 +EDGE2 9959 9940 0.982366 0.0569166 -0.00826597 1 0 1 1 0 0 +EDGE2 9959 9939 -0.0264099 0.0320712 -0.0109983 1 0 1 1 0 0 +EDGE2 9959 9938 -1.07802 -0.0620523 0.0178833 1 0 1 1 0 0 +EDGE2 9959 9958 -0.99282 -0.095367 -0.0349856 1 0 1 1 0 0 +EDGE2 9960 9940 -0.00282936 -0.112583 -0.0175141 1 0 1 1 0 0 +EDGE2 9960 9941 0.00118271 1.03771 1.59879 1 0 1 1 0 0 +EDGE2 9960 9959 -1.00739 -0.0106687 0.0612647 1 0 1 1 0 0 +EDGE2 9960 9939 -0.966058 -0.0333515 -0.00910869 1 0 1 1 0 0 +EDGE2 9961 9942 1.12175 -0.0708717 -0.00206806 1 0 1 1 0 0 +EDGE2 9961 9960 -1.00033 -0.0414828 -1.58023 1 0 1 1 0 0 +EDGE2 9961 9940 -0.94679 -0.00953044 -1.56557 1 0 1 1 0 0 +EDGE2 9961 9941 0.0242637 0.0407118 0.00147663 1 0 1 1 0 0 +EDGE2 9962 9942 -0.0319651 -0.0675981 -0.00624931 1 0 1 1 0 0 +EDGE2 9962 9941 -1.00129 -0.100657 -0.0381265 1 0 1 1 0 0 +EDGE2 9962 9961 -0.979672 -0.0944588 0.00745762 1 0 1 1 0 0 +EDGE2 9962 9943 0.921733 0.00795027 0.0107748 1 0 1 1 0 0 +EDGE2 9963 9942 -1.00917 -0.0213496 0.0188944 1 0 1 1 0 0 +EDGE2 9963 9962 -1.07807 -0.0256171 -8.91853e-06 1 0 1 1 0 0 +EDGE2 9963 9943 -0.0811244 0.0421838 -0.035786 1 0 1 1 0 0 +EDGE2 9963 9944 0.980172 -0.0030288 -0.0199599 1 0 1 1 0 0 +EDGE2 9964 9943 -0.958196 0.0366785 0.00439063 1 0 1 1 0 0 +EDGE2 9964 9963 -1.06479 0.0480273 0.00136697 1 0 1 1 0 0 +EDGE2 9964 9945 1.03118 -0.00108893 0.0175554 1 0 1 1 0 0 +EDGE2 9964 9944 0.00392369 0.01573 -0.0320585 1 0 1 1 0 0 +EDGE2 9965 9945 0.0552721 -0.0130294 0.0115773 1 0 1 1 0 0 +EDGE2 9965 9944 -1.01944 -0.0660445 0.016822 1 0 1 1 0 0 +EDGE2 9965 9964 -1.01265 -0.00709757 -0.00417927 1 0 1 1 0 0 +EDGE2 9965 9946 -0.0305526 0.988603 1.58324 1 0 1 1 0 0 +EDGE2 9966 9945 -0.928517 -0.00583902 -1.55437 1 0 1 1 0 0 +EDGE2 9966 9965 -1.01604 0.0146662 -1.60529 1 0 1 1 0 0 +EDGE2 9966 9946 -0.022598 0.0613102 0.0183249 1 0 1 1 0 0 +EDGE2 9966 9947 1.04648 -0.00816218 -0.0108611 1 0 1 1 0 0 +EDGE2 9967 9966 -0.986419 -0.0376466 -0.00492889 1 0 1 1 0 0 +EDGE2 9967 9946 -0.990917 0.0409999 0.0426296 1 0 1 1 0 0 +EDGE2 9967 9947 -0.0119613 0.0861352 -0.00118229 1 0 1 1 0 0 +EDGE2 9967 9948 1.02432 0.0917823 -0.00676143 1 0 1 1 0 0 +EDGE2 9968 9947 -0.94854 0.0404681 0.0236102 1 0 1 1 0 0 +EDGE2 9968 9967 -1.06957 -0.115524 0.045981 1 0 1 1 0 0 +EDGE2 9968 9948 -0.0220832 0.135172 0.0260949 1 0 1 1 0 0 +EDGE2 9968 9949 0.973612 0.0132195 -0.0475724 1 0 1 1 0 0 +EDGE2 9969 9968 -1.05746 0.00541496 0.0147432 1 0 1 1 0 0 +EDGE2 9969 9948 -1.0634 -0.00902586 -0.0134678 1 0 1 1 0 0 +EDGE2 9969 9949 -0.00225685 -0.0818478 -0.00683576 1 0 1 1 0 0 +EDGE2 9969 9950 0.975088 -0.0770147 -0.0133614 1 0 1 1 0 0 +EDGE2 9969 9930 0.951527 0.0348758 -3.12689 1 0 1 1 0 0 +EDGE2 9970 9969 -0.906159 0.0652177 -0.018721 1 0 1 1 0 0 +EDGE2 9970 9949 -0.927571 0.0531942 0.00389617 1 0 1 1 0 0 +EDGE2 9970 9929 1.03954 0.0162449 -3.17614 1 0 1 1 0 0 +EDGE2 9970 9931 0.00256275 0.944018 1.57737 1 0 1 1 0 0 +EDGE2 9970 9951 -0.0173207 0.89332 1.54759 1 0 1 1 0 0 +EDGE2 9970 9950 0.050366 -0.027113 -0.03683 1 0 1 1 0 0 +EDGE2 9970 9930 0.0609124 0.0175953 -3.12937 1 0 1 1 0 0 +EDGE2 9971 9952 0.934499 -0.0779074 0.0183284 1 0 1 1 0 0 +EDGE2 9971 9931 0.00969489 0.0339378 -0.00117436 1 0 1 1 0 0 +EDGE2 9971 9932 1.01308 -0.068781 0.0166704 1 0 1 1 0 0 +EDGE2 9971 9951 -0.0774468 -0.0600187 -0.00568556 1 0 1 1 0 0 +EDGE2 9971 9950 -0.965435 -0.024801 -1.58479 1 0 1 1 0 0 +EDGE2 9971 9970 -0.903675 0.0572683 -1.54751 1 0 1 1 0 0 +EDGE2 9971 9930 -1.04409 0.0317378 1.55794 1 0 1 1 0 0 +EDGE2 9972 9952 -0.0563855 0.0147472 -0.0306927 1 0 1 1 0 0 +EDGE2 9972 9933 1.00691 0.0549422 -0.00430152 1 0 1 1 0 0 +EDGE2 9972 9953 1.01301 -0.0184554 -0.00615112 1 0 1 1 0 0 +EDGE2 9972 9931 -1.01692 0.00348 -0.0267497 1 0 1 1 0 0 +EDGE2 9972 9971 -0.989291 0.094918 -0.022811 1 0 1 1 0 0 +EDGE2 9972 9932 0.0380991 0.0327695 -0.0114612 1 0 1 1 0 0 +EDGE2 9972 9951 -0.94375 0.00223521 -0.0398696 1 0 1 1 0 0 +EDGE2 9973 9934 0.959782 -0.000461271 -0.00352375 1 0 1 1 0 0 +EDGE2 9973 9954 0.930059 -0.0240197 0.0180597 1 0 1 1 0 0 +EDGE2 9973 9952 -0.956262 -0.0502742 -0.0353758 1 0 1 1 0 0 +EDGE2 9973 9933 0.0443915 -0.0978175 0.00704686 1 0 1 1 0 0 +EDGE2 9973 9953 -0.0250872 -0.0448865 -0.0177307 1 0 1 1 0 0 +EDGE2 9973 9972 -1.00732 -0.0543466 -0.0111928 1 0 1 1 0 0 +EDGE2 9973 9932 -1.00274 -0.0639248 0.00628636 1 0 1 1 0 0 +EDGE2 9974 9973 -1.04198 0.0120512 -0.0381173 1 0 1 1 0 0 +EDGE2 9974 9935 1.00257 0.135403 0.0184756 1 0 1 1 0 0 +EDGE2 9974 9955 1.00818 0.0658347 -0.0363991 1 0 1 1 0 0 +EDGE2 9974 9934 -0.0127108 -0.0149095 0.0214731 1 0 1 1 0 0 +EDGE2 9974 9954 -0.0322887 0.0228546 -0.0064299 1 0 1 1 0 0 +EDGE2 9974 9933 -0.951811 -0.0280925 0.0108555 1 0 1 1 0 0 +EDGE2 9974 9953 -1.04713 -0.0949844 -0.0179729 1 0 1 1 0 0 +EDGE2 9975 9936 0.0740877 0.919706 1.56925 1 0 1 1 0 0 +EDGE2 9975 9956 -0.0979098 0.983754 1.60515 1 0 1 1 0 0 +EDGE2 9975 9974 -1.00642 -0.0105236 0.00784229 1 0 1 1 0 0 +EDGE2 9975 9935 -0.0876511 -0.00364974 0.017645 1 0 1 1 0 0 +EDGE2 9975 9955 -0.0248077 0.0752488 0.0362789 1 0 1 1 0 0 +EDGE2 9975 9934 -0.925359 0.0143234 -0.00265043 1 0 1 1 0 0 +EDGE2 9975 9954 -0.967741 0.0343691 -0.0223691 1 0 1 1 0 0 +EDGE2 9976 9936 0.0431892 -0.0469753 0.0460943 1 0 1 1 0 0 +EDGE2 9976 9957 1.10487 -0.0859737 0.0168066 1 0 1 1 0 0 +EDGE2 9976 9956 0.00104552 0.100599 -0.0149953 1 0 1 1 0 0 +EDGE2 9976 9937 0.995912 -0.0193394 -0.00990808 1 0 1 1 0 0 +EDGE2 9976 9935 -1.05892 0.0217649 -1.55306 1 0 1 1 0 0 +EDGE2 9976 9955 -1.0449 0.0152274 -1.56848 1 0 1 1 0 0 +EDGE2 9976 9975 -1.03627 -0.0118762 -1.57316 1 0 1 1 0 0 +EDGE2 9977 9936 -1.02904 -0.0358806 -0.00744059 1 0 1 1 0 0 +EDGE2 9977 9957 -0.00859617 -0.0207388 -0.00630054 1 0 1 1 0 0 +EDGE2 9977 9938 1.00106 -0.0674526 -0.0451613 1 0 1 1 0 0 +EDGE2 9977 9958 0.986538 0.00854121 -0.00382597 1 0 1 1 0 0 +EDGE2 9977 9956 -1.13078 0.0191191 -0.033702 1 0 1 1 0 0 +EDGE2 9977 9976 -0.879759 0.0420062 0.0211336 1 0 1 1 0 0 +EDGE2 9977 9937 0.00963615 -0.0774209 0.0135519 1 0 1 1 0 0 +EDGE2 9978 9959 0.991791 0.0200231 0.0144945 1 0 1 1 0 0 +EDGE2 9978 9939 1.04319 0.0740685 -0.00295755 1 0 1 1 0 0 +EDGE2 9978 9957 -1.02763 0.0290212 -0.0073472 1 0 1 1 0 0 +EDGE2 9978 9938 -0.13341 -0.0790795 -0.00241586 1 0 1 1 0 0 +EDGE2 9978 9958 -0.00905546 0.0633751 -0.00542871 1 0 1 1 0 0 +EDGE2 9978 9977 -0.928546 0.00644954 0.0131666 1 0 1 1 0 0 +EDGE2 9978 9937 -1.00807 0.00622724 -0.000577882 1 0 1 1 0 0 +EDGE2 9979 9960 0.980568 -0.0596623 -0.00197962 1 0 1 1 0 0 +EDGE2 9979 9940 1.04632 0.0521956 0.023566 1 0 1 1 0 0 +EDGE2 9979 9959 -0.0228963 0.0358676 -0.0118565 1 0 1 1 0 0 +EDGE2 9979 9939 -0.0397621 0.0565073 -0.0210818 1 0 1 1 0 0 +EDGE2 9979 9938 -1.02851 -0.0324138 -0.00567223 1 0 1 1 0 0 +EDGE2 9979 9958 -1.05499 0.00266745 -0.0388642 1 0 1 1 0 0 +EDGE2 9979 9978 -0.990839 0.0558441 0.00248826 1 0 1 1 0 0 +EDGE2 9980 9960 -0.0501377 0.0545739 0.0133875 1 0 1 1 0 0 +EDGE2 9980 9940 0.0273842 0.019326 0.0318825 1 0 1 1 0 0 +EDGE2 9980 9941 0.0625565 0.965478 1.57575 1 0 1 1 0 0 +EDGE2 9980 9961 0.0372114 1.03622 1.56251 1 0 1 1 0 0 +EDGE2 9980 9959 -1.00713 -0.0227014 -0.0126593 1 0 1 1 0 0 +EDGE2 9980 9979 -1.05364 0.0496047 -0.0431565 1 0 1 1 0 0 +EDGE2 9980 9939 -1.0356 0.0542483 0.00334253 1 0 1 1 0 0 +EDGE2 9981 9942 1.05983 -0.0972456 -0.00781671 1 0 1 1 0 0 +EDGE2 9981 9960 -0.856078 0.0729006 -1.52657 1 0 1 1 0 0 +EDGE2 9981 9980 -1.00338 -0.0531704 -1.57472 1 0 1 1 0 0 +EDGE2 9981 9940 -0.993908 -0.0638067 -1.57455 1 0 1 1 0 0 +EDGE2 9981 9941 0.0108502 -0.0845484 0.0308976 1 0 1 1 0 0 +EDGE2 9981 9961 0.00700344 0.0234379 -0.0249185 1 0 1 1 0 0 +EDGE2 9981 9962 0.877902 0.0530254 0.0278876 1 0 1 1 0 0 +EDGE2 9982 9942 0.0195571 0.0418623 0.0350863 1 0 1 1 0 0 +EDGE2 9982 9981 -1.02457 -0.048491 -0.00446608 1 0 1 1 0 0 +EDGE2 9982 9941 -1.04185 0.0176234 -0.00267544 1 0 1 1 0 0 +EDGE2 9982 9961 -1.03369 0.0112249 -0.031554 1 0 1 1 0 0 +EDGE2 9982 9962 0.0830909 -0.0657209 -0.0337241 1 0 1 1 0 0 +EDGE2 9982 9943 0.895548 -0.0623618 0.0319696 1 0 1 1 0 0 +EDGE2 9982 9963 1.08828 0.0228015 -0.00721152 1 0 1 1 0 0 +EDGE2 9983 9942 -0.913941 0.0610054 -0.0199871 1 0 1 1 0 0 +EDGE2 9983 9982 -0.921139 0.0210626 -0.00726694 1 0 1 1 0 0 +EDGE2 9983 9962 -1.0236 -0.119144 -0.00072292 1 0 1 1 0 0 +EDGE2 9983 9943 -0.00727462 -0.0128229 0.0425496 1 0 1 1 0 0 +EDGE2 9983 9963 -0.11494 -0.029764 -0.0104214 1 0 1 1 0 0 +EDGE2 9983 9944 0.970315 0.0781154 -0.0239156 1 0 1 1 0 0 +EDGE2 9983 9964 1.01991 -0.0640556 0.0235174 1 0 1 1 0 0 +EDGE2 9984 9943 -1.02839 -0.11603 0.0180376 1 0 1 1 0 0 +EDGE2 9984 9963 -0.984357 -0.00327964 -0.0228916 1 0 1 1 0 0 +EDGE2 9984 9983 -0.985981 -0.00122294 0.0178236 1 0 1 1 0 0 +EDGE2 9984 9945 0.884838 0.0105852 0.0310412 1 0 1 1 0 0 +EDGE2 9984 9944 0.0119864 -0.0223471 0.0160207 1 0 1 1 0 0 +EDGE2 9984 9964 0.107115 -0.00614457 0.0219325 1 0 1 1 0 0 +EDGE2 9984 9965 1.02945 0.0453907 -0.0193984 1 0 1 1 0 0 +EDGE2 9985 9984 -0.956967 -0.10065 0.0229707 1 0 1 1 0 0 +EDGE2 9985 9945 -0.0140688 0.0241779 -0.0128716 1 0 1 1 0 0 +EDGE2 9985 9944 -0.979109 0.021709 -0.00963079 1 0 1 1 0 0 +EDGE2 9985 9964 -1.04845 -0.0260821 -0.00840329 1 0 1 1 0 0 +EDGE2 9985 9965 0.0410056 0.034656 0.0418932 1 0 1 1 0 0 +EDGE2 9985 9966 -0.0566531 1.01909 1.60517 1 0 1 1 0 0 +EDGE2 9985 9946 0.000975926 0.938945 1.59152 1 0 1 1 0 0 +EDGE2 9986 9945 -0.942009 0.0372851 -1.56715 1 0 1 1 0 0 +EDGE2 9986 9985 -0.982474 -0.0502691 -1.5785 1 0 1 1 0 0 +EDGE2 9986 9965 -1.01188 0.0881034 -1.57594 1 0 1 1 0 0 +EDGE2 9986 9966 -0.0741433 -0.0371694 -0.0129409 1 0 1 1 0 0 +EDGE2 9986 9946 0.0518583 0.0498808 0.00124801 1 0 1 1 0 0 +EDGE2 9986 9947 1.05708 -0.0264766 0.0321957 1 0 1 1 0 0 +EDGE2 9986 9967 0.907793 0.00189378 -0.00495462 1 0 1 1 0 0 +EDGE2 9987 9966 -0.980042 0.014805 0.0095476 1 0 1 1 0 0 +EDGE2 9987 9986 -0.916629 0.00340798 -0.0010811 1 0 1 1 0 0 +EDGE2 9987 9946 -1.07254 -0.0125203 -0.0147272 1 0 1 1 0 0 +EDGE2 9987 9968 1.05277 -0.04326 0.00578507 1 0 1 1 0 0 +EDGE2 9987 9947 0.0040207 0.0609705 -0.00391564 1 0 1 1 0 0 +EDGE2 9987 9967 -0.0107163 -0.0345071 0.0134729 1 0 1 1 0 0 +EDGE2 9987 9948 1.09722 -0.0252031 -0.0362145 1 0 1 1 0 0 +EDGE2 9988 9968 -0.0255752 -0.0780364 0.00781202 1 0 1 1 0 0 +EDGE2 9988 9947 -0.997005 0.0589118 -0.0325045 1 0 1 1 0 0 +EDGE2 9988 9967 -1.08616 -0.0218412 0.0226354 1 0 1 1 0 0 +EDGE2 9988 9987 -0.953716 0.023411 -0.00253451 1 0 1 1 0 0 +EDGE2 9988 9969 0.928642 -0.00687772 0.0141544 1 0 1 1 0 0 +EDGE2 9988 9948 0.0553384 -0.00762286 0.000893548 1 0 1 1 0 0 +EDGE2 9988 9949 1.06109 -0.0297956 0.0281662 1 0 1 1 0 0 +EDGE2 9989 9968 -1.05156 0.094916 0.00412262 1 0 1 1 0 0 +EDGE2 9989 9988 -0.998252 0.0332681 -0.0109274 1 0 1 1 0 0 +EDGE2 9989 9969 0.0822594 -0.00454216 -0.0099297 1 0 1 1 0 0 +EDGE2 9989 9948 -0.99488 0.032823 -0.046435 1 0 1 1 0 0 +EDGE2 9989 9949 -0.0555519 0.00321065 -0.00815633 1 0 1 1 0 0 +EDGE2 9989 9950 1.07721 0.0262551 0.00715572 1 0 1 1 0 0 +EDGE2 9989 9970 0.90429 0.0457745 -0.0013907 1 0 1 1 0 0 +EDGE2 9989 9930 1.00469 0.0314184 -3.13217 1 0 1 1 0 0 +EDGE2 9990 9969 -0.990199 0.0307868 0.0402095 1 0 1 1 0 0 +EDGE2 9990 9989 -0.977053 0.0324903 0.0319904 1 0 1 1 0 0 +EDGE2 9990 9949 -0.998344 0.00673501 -0.0260794 1 0 1 1 0 0 +EDGE2 9990 9929 0.986876 0.0136709 -3.16603 1 0 1 1 0 0 +EDGE2 9990 9931 0.0132652 1.02613 1.57781 1 0 1 1 0 0 +EDGE2 9990 9971 -0.0662855 1.12175 1.5379 1 0 1 1 0 0 +EDGE2 9990 9951 0.0169318 1.08114 1.57184 1 0 1 1 0 0 +EDGE2 9990 9950 0.0128489 0.0209101 -0.00823881 1 0 1 1 0 0 +EDGE2 9990 9970 -0.0108107 -0.0398516 -0.0210968 1 0 1 1 0 0 +EDGE2 9990 9930 0.0448687 -0.0771179 -3.1554 1 0 1 1 0 0 +EDGE2 9991 9952 0.904354 0.0201252 -0.0147291 1 0 1 1 0 0 +EDGE2 9991 9972 0.995093 -0.00873829 -0.0075985 1 0 1 1 0 0 +EDGE2 9991 9931 0.0403917 -0.0807131 0.00836719 1 0 1 1 0 0 +EDGE2 9991 9971 0.0352368 0.0561818 0.0097316 1 0 1 1 0 0 +EDGE2 9991 9932 1.02437 -0.0215246 0.0119699 1 0 1 1 0 0 +EDGE2 9991 9951 0.0438919 -0.07143 -0.00690779 1 0 1 1 0 0 +EDGE2 9991 9950 -1.10678 -0.0124661 -1.56534 1 0 1 1 0 0 +EDGE2 9991 9970 -1.05958 -0.0268668 -1.54435 1 0 1 1 0 0 +EDGE2 9991 9990 -1.08273 0.0135279 -1.56372 1 0 1 1 0 0 +EDGE2 9991 9930 -1.06252 0.0222145 1.58823 1 0 1 1 0 0 +EDGE2 9992 9973 0.994931 -0.0781949 0.011626 1 0 1 1 0 0 +EDGE2 9992 9952 0.0451682 -0.0583854 -0.00514461 1 0 1 1 0 0 +EDGE2 9992 9933 0.902192 -0.0239871 0.0430919 1 0 1 1 0 0 +EDGE2 9992 9953 0.941141 -0.0481567 -0.0267531 1 0 1 1 0 0 +EDGE2 9992 9972 0.0344513 -0.111945 -0.049463 1 0 1 1 0 0 +EDGE2 9992 9931 -0.932447 -0.0379275 -0.00381691 1 0 1 1 0 0 +EDGE2 9992 9971 -0.922655 0.00223925 0.0202077 1 0 1 1 0 0 +EDGE2 9992 9991 -1.07828 0.0907608 0.0060057 1 0 1 1 0 0 +EDGE2 9992 9932 0.0381935 -0.0886821 -0.00655326 1 0 1 1 0 0 +EDGE2 9992 9951 -1.05711 0.0261438 -0.00149744 1 0 1 1 0 0 +EDGE2 9993 9973 0.0334104 -0.0146338 0.0184862 1 0 1 1 0 0 +EDGE2 9993 9974 0.994442 -0.092975 -0.0148388 1 0 1 1 0 0 +EDGE2 9993 9934 0.899773 0.0732678 -0.0282004 1 0 1 1 0 0 +EDGE2 9993 9954 0.954349 0.091508 -0.0169427 1 0 1 1 0 0 +EDGE2 9993 9952 -1.00225 0.00501641 0.00799495 1 0 1 1 0 0 +EDGE2 9993 9992 -1.07632 -0.034078 -0.00231772 1 0 1 1 0 0 +EDGE2 9993 9933 -0.0126879 0.0452899 0.028629 1 0 1 1 0 0 +EDGE2 9993 9953 -0.113523 -0.0482367 0.0141149 1 0 1 1 0 0 +EDGE2 9993 9972 -0.971601 -0.00404104 0.0126385 1 0 1 1 0 0 +EDGE2 9993 9932 -1.10659 0.10857 -0.0130569 1 0 1 1 0 0 +EDGE2 9994 9973 -1.00635 -0.0948706 -0.0266755 1 0 1 1 0 0 +EDGE2 9994 9974 0.00122984 -0.0599273 0.0254552 1 0 1 1 0 0 +EDGE2 9994 9935 1.08292 -0.0103118 -0.0116941 1 0 1 1 0 0 +EDGE2 9994 9955 1.0683 -0.0386638 0.0262951 1 0 1 1 0 0 +EDGE2 9994 9975 1.03902 -0.00881279 0.0152912 1 0 1 1 0 0 +EDGE2 9994 9934 0.0141688 0.00995855 0.0126057 1 0 1 1 0 0 +EDGE2 9994 9954 -0.0134907 0.00386401 -0.0240054 1 0 1 1 0 0 +EDGE2 9994 9993 -1.03418 0.0105625 0.014756 1 0 1 1 0 0 +EDGE2 9994 9933 -1.03279 -0.109813 0.00863115 1 0 1 1 0 0 +EDGE2 9994 9953 -1.02696 -0.0737765 0.00948242 1 0 1 1 0 0 +EDGE2 9995 9936 0.0123598 1.05037 1.56288 1 0 1 1 0 0 +EDGE2 9995 9956 -0.00524368 1.06889 1.54469 1 0 1 1 0 0 +EDGE2 9995 9976 0.0831912 0.968256 1.54323 1 0 1 1 0 0 +EDGE2 9995 9974 -1.00181 -0.0398423 -0.0363353 1 0 1 1 0 0 +EDGE2 9995 9935 0.0410013 0.0112739 0.00749004 1 0 1 1 0 0 +EDGE2 9995 9955 -0.0791036 -0.0309086 -0.0269903 1 0 1 1 0 0 +EDGE2 9995 9975 -0.0423802 0.0105921 -0.0197969 1 0 1 1 0 0 +EDGE2 9995 9994 -0.991372 0.0208305 -0.0166207 1 0 1 1 0 0 +EDGE2 9995 9934 -1.00805 0.0461122 0.0261096 1 0 1 1 0 0 +EDGE2 9995 9954 -0.971357 -0.0226929 0.00122834 1 0 1 1 0 0 +EDGE2 9996 9995 -1.0305 -0.0516601 1.5536 1 0 1 1 0 0 +EDGE2 9996 9935 -1.07333 0.0228608 1.58089 1 0 1 1 0 0 +EDGE2 9996 9955 -1.06228 -0.0441774 1.57012 1 0 1 1 0 0 +EDGE2 9996 9975 -1.01959 -0.00145766 1.58863 1 0 1 1 0 0 +EDGE2 9997 9996 -0.997533 -0.0758269 0.0317773 1 0 1 1 0 0 +EDGE2 9998 9997 -0.997111 -0.0589442 -0.0270152 1 0 1 1 0 0 +EDGE2 9999 9998 -1.0415 -0.0163109 -0.0371536 1 0 1 1 0 0 +EDGE2 9999 9920 0.985251 0.00231099 -3.14569 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 +EQUIV 101 61 +EQUIV 102 62 +EQUIV 103 63 +EQUIV 104 64 +EQUIV 105 65 +EQUIV 106 66 +EQUIV 107 67 +EQUIV 108 68 +EQUIV 109 69 +EQUIV 110 70 +EQUIV 111 71 +EQUIV 112 72 +EQUIV 113 73 +EQUIV 114 74 +EQUIV 115 75 +EQUIV 191 171 +EQUIV 192 172 +EQUIV 193 173 +EQUIV 194 174 +EQUIV 195 175 +EQUIV 196 176 +EQUIV 197 177 +EQUIV 198 178 +EQUIV 199 179 +EQUIV 200 180 +EQUIV 201 181 +EQUIV 202 182 +EQUIV 203 183 +EQUIV 204 184 +EQUIV 205 185 +EQUIV 226 206 +EQUIV 227 207 +EQUIV 228 208 +EQUIV 229 209 +EQUIV 230 210 +EQUIV 251 231 +EQUIV 252 232 +EQUIV 253 233 +EQUIV 254 234 +EQUIV 255 235 +EQUIV 286 266 +EQUIV 287 267 +EQUIV 288 268 +EQUIV 289 269 +EQUIV 290 270 +EQUIV 291 271 +EQUIV 292 272 +EQUIV 293 273 +EQUIV 294 274 +EQUIV 295 275 +EQUIV 296 276 +EQUIV 297 277 +EQUIV 298 278 +EQUIV 299 279 +EQUIV 300 280 +EQUIV 321 141 +EQUIV 322 142 +EQUIV 323 143 +EQUIV 324 144 +EQUIV 325 145 +EQUIV 326 146 +EQUIV 327 147 +EQUIV 328 148 +EQUIV 329 149 +EQUIV 330 150 +EQUIV 336 136 +EQUIV 337 137 +EQUIV 338 138 +EQUIV 339 139 +EQUIV 340 140 +EQUIV 341 141 +EQUIV 342 142 +EQUIV 343 143 +EQUIV 344 144 +EQUIV 345 145 +EQUIV 346 146 +EQUIV 347 147 +EQUIV 348 148 +EQUIV 349 149 +EQUIV 350 150 +EQUIV 351 151 +EQUIV 352 152 +EQUIV 353 153 +EQUIV 354 154 +EQUIV 355 155 +EQUIV 371 151 +EQUIV 372 152 +EQUIV 373 153 +EQUIV 374 154 +EQUIV 375 155 +EQUIV 376 156 +EQUIV 377 157 +EQUIV 378 158 +EQUIV 379 159 +EQUIV 380 160 +EQUIV 391 271 +EQUIV 392 272 +EQUIV 393 273 +EQUIV 394 274 +EQUIV 395 275 +EQUIV 396 276 +EQUIV 397 277 +EQUIV 398 278 +EQUIV 399 279 +EQUIV 400 280 +EQUIV 401 281 +EQUIV 402 282 +EQUIV 403 283 +EQUIV 404 284 +EQUIV 405 285 +EQUIV 406 266 +EQUIV 407 267 +EQUIV 408 268 +EQUIV 409 269 +EQUIV 410 270 +EQUIV 411 271 +EQUIV 412 272 +EQUIV 413 273 +EQUIV 414 274 +EQUIV 415 275 +EQUIV 416 316 +EQUIV 417 317 +EQUIV 418 318 +EQUIV 419 319 +EQUIV 420 320 +EQUIV 421 141 +EQUIV 422 142 +EQUIV 423 143 +EQUIV 424 144 +EQUIV 425 145 +EQUIV 426 386 +EQUIV 427 387 +EQUIV 428 388 +EQUIV 429 389 +EQUIV 430 390 +EQUIV 431 271 +EQUIV 432 272 +EQUIV 433 273 +EQUIV 434 274 +EQUIV 435 275 +EQUIV 436 276 +EQUIV 437 277 +EQUIV 438 278 +EQUIV 439 279 +EQUIV 440 280 +EQUIV 441 281 +EQUIV 442 282 +EQUIV 443 283 +EQUIV 444 284 +EQUIV 445 285 +EQUIV 446 266 +EQUIV 447 267 +EQUIV 448 268 +EQUIV 449 269 +EQUIV 450 270 +EQUIV 451 271 +EQUIV 452 272 +EQUIV 453 273 +EQUIV 454 274 +EQUIV 455 275 +EQUIV 456 276 +EQUIV 457 277 +EQUIV 458 278 +EQUIV 459 279 +EQUIV 460 280 +EQUIV 461 281 +EQUIV 462 282 +EQUIV 463 283 +EQUIV 464 284 +EQUIV 465 285 +EQUIV 466 266 +EQUIV 467 267 +EQUIV 468 268 +EQUIV 469 269 +EQUIV 470 270 +EQUIV 471 271 +EQUIV 472 272 +EQUIV 473 273 +EQUIV 474 274 +EQUIV 475 275 +EQUIV 476 276 +EQUIV 477 277 +EQUIV 478 278 +EQUIV 479 279 +EQUIV 480 280 +EQUIV 481 281 +EQUIV 482 282 +EQUIV 483 283 +EQUIV 484 284 +EQUIV 485 285 +EQUIV 496 256 +EQUIV 497 257 +EQUIV 498 258 +EQUIV 499 259 +EQUIV 500 260 +EQUIV 501 181 +EQUIV 502 182 +EQUIV 503 183 +EQUIV 504 184 +EQUIV 505 185 +EQUIV 506 186 +EQUIV 507 187 +EQUIV 508 188 +EQUIV 509 189 +EQUIV 510 190 +EQUIV 646 626 +EQUIV 647 627 +EQUIV 648 628 +EQUIV 649 629 +EQUIV 650 630 +EQUIV 651 631 +EQUIV 652 632 +EQUIV 653 633 +EQUIV 654 634 +EQUIV 655 635 +EQUIV 656 636 +EQUIV 657 637 +EQUIV 658 638 +EQUIV 659 639 +EQUIV 660 640 +EQUIV 731 711 +EQUIV 732 712 +EQUIV 733 713 +EQUIV 734 714 +EQUIV 735 715 +EQUIV 756 696 +EQUIV 757 697 +EQUIV 758 698 +EQUIV 759 699 +EQUIV 760 700 +EQUIV 761 741 +EQUIV 762 742 +EQUIV 763 743 +EQUIV 764 744 +EQUIV 765 745 +EQUIV 766 746 +EQUIV 767 747 +EQUIV 768 748 +EQUIV 769 749 +EQUIV 770 750 +EQUIV 771 751 +EQUIV 772 752 +EQUIV 773 753 +EQUIV 774 754 +EQUIV 775 755 +EQUIV 776 696 +EQUIV 777 697 +EQUIV 778 698 +EQUIV 779 699 +EQUIV 780 700 +EQUIV 781 741 +EQUIV 782 742 +EQUIV 783 743 +EQUIV 784 744 +EQUIV 785 745 +EQUIV 786 746 +EQUIV 787 747 +EQUIV 788 748 +EQUIV 789 749 +EQUIV 790 750 +EQUIV 791 751 +EQUIV 792 752 +EQUIV 793 753 +EQUIV 794 754 +EQUIV 795 755 +EQUIV 796 696 +EQUIV 797 697 +EQUIV 798 698 +EQUIV 799 699 +EQUIV 800 700 +EQUIV 801 741 +EQUIV 802 742 +EQUIV 803 743 +EQUIV 804 744 +EQUIV 805 745 +EQUIV 806 746 +EQUIV 807 747 +EQUIV 808 748 +EQUIV 809 749 +EQUIV 810 750 +EQUIV 811 751 +EQUIV 812 752 +EQUIV 813 753 +EQUIV 814 754 +EQUIV 815 755 +EQUIV 816 696 +EQUIV 817 697 +EQUIV 818 698 +EQUIV 819 699 +EQUIV 820 700 +EQUIV 821 701 +EQUIV 822 702 +EQUIV 823 703 +EQUIV 824 704 +EQUIV 825 705 +EQUIV 846 826 +EQUIV 847 827 +EQUIV 848 828 +EQUIV 849 829 +EQUIV 850 830 +EQUIV 851 831 +EQUIV 852 832 +EQUIV 853 833 +EQUIV 854 834 +EQUIV 855 835 +EQUIV 856 836 +EQUIV 857 837 +EQUIV 858 838 +EQUIV 859 839 +EQUIV 860 840 +EQUIV 861 841 +EQUIV 862 842 +EQUIV 863 843 +EQUIV 864 844 +EQUIV 865 845 +EQUIV 866 826 +EQUIV 867 827 +EQUIV 868 828 +EQUIV 869 829 +EQUIV 870 830 +EQUIV 871 691 +EQUIV 872 692 +EQUIV 873 693 +EQUIV 874 694 +EQUIV 875 695 +EQUIV 886 686 +EQUIV 887 687 +EQUIV 888 688 +EQUIV 889 689 +EQUIV 890 690 +EQUIV 891 831 +EQUIV 892 832 +EQUIV 893 833 +EQUIV 894 834 +EQUIV 895 835 +EQUIV 896 836 +EQUIV 897 837 +EQUIV 898 838 +EQUIV 899 839 +EQUIV 900 840 +EQUIV 901 841 +EQUIV 902 842 +EQUIV 903 843 +EQUIV 904 844 +EQUIV 905 845 +EQUIV 906 826 +EQUIV 907 827 +EQUIV 908 828 +EQUIV 909 829 +EQUIV 910 830 +EQUIV 911 831 +EQUIV 912 832 +EQUIV 913 833 +EQUIV 914 834 +EQUIV 915 835 +EQUIV 971 951 +EQUIV 972 952 +EQUIV 973 953 +EQUIV 974 954 +EQUIV 975 955 +EQUIV 976 936 +EQUIV 977 937 +EQUIV 978 938 +EQUIV 979 939 +EQUIV 980 940 +EQUIV 981 941 +EQUIV 982 942 +EQUIV 983 943 +EQUIV 984 944 +EQUIV 985 945 +EQUIV 1001 941 +EQUIV 1002 942 +EQUIV 1003 943 +EQUIV 1004 944 +EQUIV 1005 945 +EQUIV 1006 986 +EQUIV 1007 987 +EQUIV 1008 988 +EQUIV 1009 989 +EQUIV 1010 990 +EQUIV 1011 991 +EQUIV 1012 992 +EQUIV 1013 993 +EQUIV 1014 994 +EQUIV 1015 995 +EQUIV 1016 996 +EQUIV 1017 997 +EQUIV 1018 998 +EQUIV 1019 999 +EQUIV 1020 1000 +EQUIV 1021 941 +EQUIV 1022 942 +EQUIV 1023 943 +EQUIV 1024 944 +EQUIV 1025 945 +EQUIV 1026 986 +EQUIV 1027 987 +EQUIV 1028 988 +EQUIV 1029 989 +EQUIV 1030 990 +EQUIV 1051 991 +EQUIV 1052 992 +EQUIV 1053 993 +EQUIV 1054 994 +EQUIV 1055 995 +EQUIV 1056 996 +EQUIV 1057 997 +EQUIV 1058 998 +EQUIV 1059 999 +EQUIV 1060 1000 +EQUIV 1061 941 +EQUIV 1062 942 +EQUIV 1063 943 +EQUIV 1064 944 +EQUIV 1065 945 +EQUIV 1066 986 +EQUIV 1067 987 +EQUIV 1068 988 +EQUIV 1069 989 +EQUIV 1070 990 +EQUIV 1071 991 +EQUIV 1072 992 +EQUIV 1073 993 +EQUIV 1074 994 +EQUIV 1075 995 +EQUIV 1116 1096 +EQUIV 1117 1097 +EQUIV 1118 1098 +EQUIV 1119 1099 +EQUIV 1120 1100 +EQUIV 1121 1101 +EQUIV 1122 1102 +EQUIV 1123 1103 +EQUIV 1124 1104 +EQUIV 1125 1105 +EQUIV 1126 1106 +EQUIV 1127 1107 +EQUIV 1128 1108 +EQUIV 1129 1109 +EQUIV 1130 1110 +EQUIV 1131 1111 +EQUIV 1132 1112 +EQUIV 1133 1113 +EQUIV 1134 1114 +EQUIV 1135 1115 +EQUIV 1136 1096 +EQUIV 1137 1097 +EQUIV 1138 1098 +EQUIV 1139 1099 +EQUIV 1140 1100 +EQUIV 1141 1101 +EQUIV 1142 1102 +EQUIV 1143 1103 +EQUIV 1144 1104 +EQUIV 1145 1105 +EQUIV 1146 1106 +EQUIV 1147 1107 +EQUIV 1148 1108 +EQUIV 1149 1109 +EQUIV 1150 1110 +EQUIV 1171 1151 +EQUIV 1172 1152 +EQUIV 1173 1153 +EQUIV 1174 1154 +EQUIV 1175 1155 +EQUIV 1176 1156 +EQUIV 1177 1157 +EQUIV 1178 1158 +EQUIV 1179 1159 +EQUIV 1180 1160 +EQUIV 1181 1161 +EQUIV 1182 1162 +EQUIV 1183 1163 +EQUIV 1184 1164 +EQUIV 1185 1165 +EQUIV 1186 1166 +EQUIV 1187 1167 +EQUIV 1188 1168 +EQUIV 1189 1169 +EQUIV 1190 1170 +EQUIV 1191 1151 +EQUIV 1192 1152 +EQUIV 1193 1153 +EQUIV 1194 1154 +EQUIV 1195 1155 +EQUIV 1196 1156 +EQUIV 1197 1157 +EQUIV 1198 1158 +EQUIV 1199 1159 +EQUIV 1200 1160 +EQUIV 1201 841 +EQUIV 1202 842 +EQUIV 1203 843 +EQUIV 1204 844 +EQUIV 1205 845 +EQUIV 1206 706 +EQUIV 1207 707 +EQUIV 1208 708 +EQUIV 1209 709 +EQUIV 1210 710 +EQUIV 1211 711 +EQUIV 1212 712 +EQUIV 1213 713 +EQUIV 1214 714 +EQUIV 1215 715 +EQUIV 1216 716 +EQUIV 1217 717 +EQUIV 1218 718 +EQUIV 1219 719 +EQUIV 1220 720 +EQUIV 1251 1231 +EQUIV 1252 1232 +EQUIV 1253 1233 +EQUIV 1254 1234 +EQUIV 1255 1235 +EQUIV 1291 1271 +EQUIV 1292 1272 +EQUIV 1293 1273 +EQUIV 1294 1274 +EQUIV 1295 1275 +EQUIV 1296 1276 +EQUIV 1297 1277 +EQUIV 1298 1278 +EQUIV 1299 1279 +EQUIV 1300 1280 +EQUIV 1301 1281 +EQUIV 1302 1282 +EQUIV 1303 1283 +EQUIV 1304 1284 +EQUIV 1305 1285 +EQUIV 1346 1326 +EQUIV 1347 1327 +EQUIV 1348 1328 +EQUIV 1349 1329 +EQUIV 1350 1330 +EQUIV 1351 1331 +EQUIV 1352 1332 +EQUIV 1353 1333 +EQUIV 1354 1334 +EQUIV 1355 1335 +EQUIV 1356 1336 +EQUIV 1357 1337 +EQUIV 1358 1338 +EQUIV 1359 1339 +EQUIV 1360 1340 +EQUIV 1361 1341 +EQUIV 1362 1342 +EQUIV 1363 1343 +EQUIV 1364 1344 +EQUIV 1365 1345 +EQUIV 1411 1391 +EQUIV 1412 1392 +EQUIV 1413 1393 +EQUIV 1414 1394 +EQUIV 1415 1395 +EQUIV 1416 1396 +EQUIV 1417 1397 +EQUIV 1418 1398 +EQUIV 1419 1399 +EQUIV 1420 1400 +EQUIV 1421 1401 +EQUIV 1422 1402 +EQUIV 1423 1403 +EQUIV 1424 1404 +EQUIV 1425 1405 +EQUIV 1426 1406 +EQUIV 1427 1407 +EQUIV 1428 1408 +EQUIV 1429 1409 +EQUIV 1430 1410 +EQUIV 1431 1391 +EQUIV 1432 1392 +EQUIV 1433 1393 +EQUIV 1434 1394 +EQUIV 1435 1395 +EQUIV 1436 1396 +EQUIV 1437 1397 +EQUIV 1438 1398 +EQUIV 1439 1399 +EQUIV 1440 1400 +EQUIV 1441 1401 +EQUIV 1442 1402 +EQUIV 1443 1403 +EQUIV 1444 1404 +EQUIV 1445 1405 +EQUIV 1446 1406 +EQUIV 1447 1407 +EQUIV 1448 1408 +EQUIV 1449 1409 +EQUIV 1450 1410 +EQUIV 1451 1391 +EQUIV 1452 1392 +EQUIV 1453 1393 +EQUIV 1454 1394 +EQUIV 1455 1395 +EQUIV 1481 1341 +EQUIV 1482 1342 +EQUIV 1483 1343 +EQUIV 1484 1344 +EQUIV 1485 1345 +EQUIV 1486 1326 +EQUIV 1487 1327 +EQUIV 1488 1328 +EQUIV 1489 1329 +EQUIV 1490 1330 +EQUIV 1491 1331 +EQUIV 1492 1332 +EQUIV 1493 1333 +EQUIV 1494 1334 +EQUIV 1495 1335 +EQUIV 1496 1336 +EQUIV 1497 1337 +EQUIV 1498 1338 +EQUIV 1499 1339 +EQUIV 1500 1340 +EQUIV 1501 1341 +EQUIV 1502 1342 +EQUIV 1503 1343 +EQUIV 1504 1344 +EQUIV 1505 1345 +EQUIV 1506 1366 +EQUIV 1507 1367 +EQUIV 1508 1368 +EQUIV 1509 1369 +EQUIV 1510 1370 +EQUIV 1511 1371 +EQUIV 1512 1372 +EQUIV 1513 1373 +EQUIV 1514 1374 +EQUIV 1515 1375 +EQUIV 1521 1321 +EQUIV 1522 1322 +EQUIV 1523 1323 +EQUIV 1524 1324 +EQUIV 1525 1325 +EQUIV 1526 1366 +EQUIV 1527 1367 +EQUIV 1528 1368 +EQUIV 1529 1369 +EQUIV 1530 1370 +EQUIV 1531 1371 +EQUIV 1532 1372 +EQUIV 1533 1373 +EQUIV 1534 1374 +EQUIV 1535 1375 +EQUIV 1536 1376 +EQUIV 1537 1377 +EQUIV 1538 1378 +EQUIV 1539 1379 +EQUIV 1540 1380 +EQUIV 1561 1541 +EQUIV 1562 1542 +EQUIV 1563 1543 +EQUIV 1564 1544 +EQUIV 1565 1545 +EQUIV 1566 1266 +EQUIV 1567 1267 +EQUIV 1568 1268 +EQUIV 1569 1269 +EQUIV 1570 1270 +EQUIV 1576 1376 +EQUIV 1577 1377 +EQUIV 1578 1378 +EQUIV 1579 1379 +EQUIV 1580 1380 +EQUIV 1581 1541 +EQUIV 1582 1542 +EQUIV 1583 1543 +EQUIV 1584 1544 +EQUIV 1585 1545 +EQUIV 1586 1266 +EQUIV 1587 1267 +EQUIV 1588 1268 +EQUIV 1589 1269 +EQUIV 1590 1270 +EQUIV 1591 1571 +EQUIV 1592 1572 +EQUIV 1593 1573 +EQUIV 1594 1574 +EQUIV 1595 1575 +EQUIV 1596 1516 +EQUIV 1597 1517 +EQUIV 1598 1518 +EQUIV 1599 1519 +EQUIV 1600 1520 +EQUIV 1606 1306 +EQUIV 1607 1307 +EQUIV 1608 1308 +EQUIV 1609 1309 +EQUIV 1610 1310 +EQUIV 1611 1311 +EQUIV 1612 1312 +EQUIV 1613 1313 +EQUIV 1614 1314 +EQUIV 1615 1315 +EQUIV 1616 1316 +EQUIV 1617 1317 +EQUIV 1618 1318 +EQUIV 1619 1319 +EQUIV 1620 1320 +EQUIV 1621 1601 +EQUIV 1622 1602 +EQUIV 1623 1603 +EQUIV 1624 1604 +EQUIV 1625 1605 +EQUIV 1626 1306 +EQUIV 1627 1307 +EQUIV 1628 1308 +EQUIV 1629 1309 +EQUIV 1630 1310 +EQUIV 1631 1311 +EQUIV 1632 1312 +EQUIV 1633 1313 +EQUIV 1634 1314 +EQUIV 1635 1315 +EQUIV 1636 1316 +EQUIV 1637 1317 +EQUIV 1638 1318 +EQUIV 1639 1319 +EQUIV 1640 1320 +EQUIV 1641 1321 +EQUIV 1642 1322 +EQUIV 1643 1323 +EQUIV 1644 1324 +EQUIV 1645 1325 +EQUIV 1646 1366 +EQUIV 1647 1367 +EQUIV 1648 1368 +EQUIV 1649 1369 +EQUIV 1650 1370 +EQUIV 1651 1371 +EQUIV 1652 1372 +EQUIV 1653 1373 +EQUIV 1654 1374 +EQUIV 1655 1375 +EQUIV 1656 1376 +EQUIV 1657 1377 +EQUIV 1658 1378 +EQUIV 1659 1379 +EQUIV 1660 1380 +EQUIV 1661 1381 +EQUIV 1662 1382 +EQUIV 1663 1383 +EQUIV 1664 1384 +EQUIV 1665 1385 +EQUIV 1666 1466 +EQUIV 1667 1467 +EQUIV 1668 1468 +EQUIV 1669 1469 +EQUIV 1670 1470 +EQUIV 1671 1471 +EQUIV 1672 1472 +EQUIV 1673 1473 +EQUIV 1674 1474 +EQUIV 1675 1475 +EQUIV 1676 1476 +EQUIV 1677 1477 +EQUIV 1678 1478 +EQUIV 1679 1479 +EQUIV 1680 1480 +EQUIV 1701 1461 +EQUIV 1702 1462 +EQUIV 1703 1463 +EQUIV 1704 1464 +EQUIV 1705 1465 +EQUIV 1706 1466 +EQUIV 1707 1467 +EQUIV 1708 1468 +EQUIV 1709 1469 +EQUIV 1710 1470 +EQUIV 1711 1471 +EQUIV 1712 1472 +EQUIV 1713 1473 +EQUIV 1714 1474 +EQUIV 1715 1475 +EQUIV 1716 1696 +EQUIV 1717 1697 +EQUIV 1718 1698 +EQUIV 1719 1699 +EQUIV 1720 1700 +EQUIV 1736 1456 +EQUIV 1737 1457 +EQUIV 1738 1458 +EQUIV 1739 1459 +EQUIV 1740 1460 +EQUIV 1741 1721 +EQUIV 1742 1722 +EQUIV 1743 1723 +EQUIV 1744 1724 +EQUIV 1745 1725 +EQUIV 1746 1726 +EQUIV 1747 1727 +EQUIV 1748 1728 +EQUIV 1749 1729 +EQUIV 1750 1730 +EQUIV 1751 1731 +EQUIV 1752 1732 +EQUIV 1753 1733 +EQUIV 1754 1734 +EQUIV 1755 1735 +EQUIV 1756 1396 +EQUIV 1757 1397 +EQUIV 1758 1398 +EQUIV 1759 1399 +EQUIV 1760 1400 +EQUIV 1831 1551 +EQUIV 1832 1552 +EQUIV 1833 1553 +EQUIV 1834 1554 +EQUIV 1835 1555 +EQUIV 1836 1556 +EQUIV 1837 1557 +EQUIV 1838 1558 +EQUIV 1839 1559 +EQUIV 1840 1560 +EQUIV 1841 1541 +EQUIV 1842 1542 +EQUIV 1843 1543 +EQUIV 1844 1544 +EQUIV 1845 1545 +EQUIV 1846 1266 +EQUIV 1847 1267 +EQUIV 1848 1268 +EQUIV 1849 1269 +EQUIV 1850 1270 +EQUIV 1851 1571 +EQUIV 1852 1572 +EQUIV 1853 1573 +EQUIV 1854 1574 +EQUIV 1855 1575 +EQUIV 1856 1376 +EQUIV 1857 1377 +EQUIV 1858 1378 +EQUIV 1859 1379 +EQUIV 1860 1380 +EQUIV 1861 1381 +EQUIV 1862 1382 +EQUIV 1863 1383 +EQUIV 1864 1384 +EQUIV 1865 1385 +EQUIV 1866 1466 +EQUIV 1867 1467 +EQUIV 1868 1468 +EQUIV 1869 1469 +EQUIV 1870 1470 +EQUIV 1871 1471 +EQUIV 1872 1472 +EQUIV 1873 1473 +EQUIV 1874 1474 +EQUIV 1875 1475 +EQUIV 1876 1476 +EQUIV 1877 1477 +EQUIV 1878 1478 +EQUIV 1879 1479 +EQUIV 1880 1480 +EQUIV 1881 1681 +EQUIV 1882 1682 +EQUIV 1883 1683 +EQUIV 1884 1684 +EQUIV 1885 1685 +EQUIV 1886 1686 +EQUIV 1887 1687 +EQUIV 1888 1688 +EQUIV 1889 1689 +EQUIV 1890 1690 +EQUIV 1891 1691 +EQUIV 1892 1692 +EQUIV 1893 1693 +EQUIV 1894 1694 +EQUIV 1895 1695 +EQUIV 1896 1476 +EQUIV 1897 1477 +EQUIV 1898 1478 +EQUIV 1899 1479 +EQUIV 1900 1480 +EQUIV 1901 1341 +EQUIV 1902 1342 +EQUIV 1903 1343 +EQUIV 1904 1344 +EQUIV 1905 1345 +EQUIV 1906 1326 +EQUIV 1907 1327 +EQUIV 1908 1328 +EQUIV 1909 1329 +EQUIV 1910 1330 +EQUIV 1911 1331 +EQUIV 1912 1332 +EQUIV 1913 1333 +EQUIV 1914 1334 +EQUIV 1915 1335 +EQUIV 1916 1336 +EQUIV 1917 1337 +EQUIV 1918 1338 +EQUIV 1919 1339 +EQUIV 1920 1340 +EQUIV 1921 1341 +EQUIV 1922 1342 +EQUIV 1923 1343 +EQUIV 1924 1344 +EQUIV 1925 1345 +EQUIV 1926 1366 +EQUIV 1927 1367 +EQUIV 1928 1368 +EQUIV 1929 1369 +EQUIV 1930 1370 +EQUIV 1931 1471 +EQUIV 1932 1472 +EQUIV 1933 1473 +EQUIV 1934 1474 +EQUIV 1935 1475 +EQUIV 1936 1696 +EQUIV 1937 1697 +EQUIV 1938 1698 +EQUIV 1939 1699 +EQUIV 1940 1700 +EQUIV 1941 1721 +EQUIV 1942 1722 +EQUIV 1943 1723 +EQUIV 1944 1724 +EQUIV 1945 1725 +EQUIV 1946 1726 +EQUIV 1947 1727 +EQUIV 1948 1728 +EQUIV 1949 1729 +EQUIV 1950 1730 +EQUIV 1976 1956 +EQUIV 1977 1957 +EQUIV 1978 1958 +EQUIV 1979 1959 +EQUIV 1980 1960 +EQUIV 1981 1961 +EQUIV 1982 1962 +EQUIV 1983 1963 +EQUIV 1984 1964 +EQUIV 1985 1965 +EQUIV 1986 1966 +EQUIV 1987 1967 +EQUIV 1988 1968 +EQUIV 1989 1969 +EQUIV 1990 1970 +EQUIV 2031 1771 +EQUIV 2032 1772 +EQUIV 2033 1773 +EQUIV 2034 1774 +EQUIV 2035 1775 +EQUIV 2036 1776 +EQUIV 2037 1777 +EQUIV 2038 1778 +EQUIV 2039 1779 +EQUIV 2040 1780 +EQUIV 2041 1781 +EQUIV 2042 1782 +EQUIV 2043 1783 +EQUIV 2044 1784 +EQUIV 2045 1785 +EQUIV 2046 1786 +EQUIV 2047 1787 +EQUIV 2048 1788 +EQUIV 2049 1789 +EQUIV 2050 1790 +EQUIV 2061 1761 +EQUIV 2062 1762 +EQUIV 2063 1763 +EQUIV 2064 1764 +EQUIV 2065 1765 +EQUIV 2066 1766 +EQUIV 2067 1767 +EQUIV 2068 1768 +EQUIV 2069 1769 +EQUIV 2070 1770 +EQUIV 2076 2016 +EQUIV 2077 2017 +EQUIV 2078 2018 +EQUIV 2079 2019 +EQUIV 2080 2020 +EQUIV 2101 2021 +EQUIV 2102 2022 +EQUIV 2103 2023 +EQUIV 2104 2024 +EQUIV 2105 2025 +EQUIV 2106 2026 +EQUIV 2107 2027 +EQUIV 2108 2028 +EQUIV 2109 2029 +EQUIV 2110 2030 +EQUIV 2111 1771 +EQUIV 2112 1772 +EQUIV 2113 1773 +EQUIV 2114 1774 +EQUIV 2115 1775 +EQUIV 2116 2056 +EQUIV 2117 2057 +EQUIV 2118 2058 +EQUIV 2119 2059 +EQUIV 2120 2060 +EQUIV 2121 1761 +EQUIV 2122 1762 +EQUIV 2123 1763 +EQUIV 2124 1764 +EQUIV 2125 1765 +EQUIV 2126 1766 +EQUIV 2127 1767 +EQUIV 2128 1768 +EQUIV 2129 1769 +EQUIV 2130 1770 +EQUIV 2131 1771 +EQUIV 2132 1772 +EQUIV 2133 1773 +EQUIV 2134 1774 +EQUIV 2135 1775 +EQUIV 2136 2056 +EQUIV 2137 2057 +EQUIV 2138 2058 +EQUIV 2139 2059 +EQUIV 2140 2060 +EQUIV 2141 1761 +EQUIV 2142 1762 +EQUIV 2143 1763 +EQUIV 2144 1764 +EQUIV 2145 1765 +EQUIV 2146 1766 +EQUIV 2147 1767 +EQUIV 2148 1768 +EQUIV 2149 1769 +EQUIV 2150 1770 +EQUIV 2151 1771 +EQUIV 2152 1772 +EQUIV 2153 1773 +EQUIV 2154 1774 +EQUIV 2155 1775 +EQUIV 2156 2056 +EQUIV 2157 2057 +EQUIV 2158 2058 +EQUIV 2159 2059 +EQUIV 2160 2060 +EQUIV 2161 1401 +EQUIV 2162 1402 +EQUIV 2163 1403 +EQUIV 2164 1404 +EQUIV 2165 1405 +EQUIV 2166 1406 +EQUIV 2167 1407 +EQUIV 2168 1408 +EQUIV 2169 1409 +EQUIV 2170 1410 +EQUIV 2171 1391 +EQUIV 2172 1392 +EQUIV 2173 1393 +EQUIV 2174 1394 +EQUIV 2175 1395 +EQUIV 2176 1396 +EQUIV 2177 1397 +EQUIV 2178 1398 +EQUIV 2179 1399 +EQUIV 2180 1400 +EQUIV 2181 1401 +EQUIV 2182 1402 +EQUIV 2183 1403 +EQUIV 2184 1404 +EQUIV 2185 1405 +EQUIV 2191 1791 +EQUIV 2192 1792 +EQUIV 2193 1793 +EQUIV 2194 1794 +EQUIV 2195 1795 +EQUIV 2231 1811 +EQUIV 2232 1812 +EQUIV 2233 1813 +EQUIV 2234 1814 +EQUIV 2235 1815 +EQUIV 2236 1816 +EQUIV 2237 1817 +EQUIV 2238 1818 +EQUIV 2239 1819 +EQUIV 2240 1820 +EQUIV 2241 1821 +EQUIV 2242 1822 +EQUIV 2243 1823 +EQUIV 2244 1824 +EQUIV 2245 1825 +EQUIV 2246 1806 +EQUIV 2247 1807 +EQUIV 2248 1808 +EQUIV 2249 1809 +EQUIV 2250 1810 +EQUIV 2251 1811 +EQUIV 2252 1812 +EQUIV 2253 1813 +EQUIV 2254 1814 +EQUIV 2255 1815 +EQUIV 2266 2226 +EQUIV 2267 2227 +EQUIV 2268 2228 +EQUIV 2269 2229 +EQUIV 2270 2230 +EQUIV 2271 1811 +EQUIV 2272 1812 +EQUIV 2273 1813 +EQUIV 2274 1814 +EQUIV 2275 1815 +EQUIV 2276 1816 +EQUIV 2277 1817 +EQUIV 2278 1818 +EQUIV 2279 1819 +EQUIV 2280 1820 +EQUIV 2281 1241 +EQUIV 2282 1242 +EQUIV 2283 1243 +EQUIV 2284 1244 +EQUIV 2285 1245 +EQUIV 2286 1246 +EQUIV 2287 1247 +EQUIV 2288 1248 +EQUIV 2289 1249 +EQUIV 2290 1250 +EQUIV 2291 1231 +EQUIV 2292 1232 +EQUIV 2293 1233 +EQUIV 2294 1234 +EQUIV 2295 1235 +EQUIV 2296 1256 +EQUIV 2297 1257 +EQUIV 2298 1258 +EQUIV 2299 1259 +EQUIV 2300 1260 +EQUIV 2301 1261 +EQUIV 2302 1262 +EQUIV 2303 1263 +EQUIV 2304 1264 +EQUIV 2305 1265 +EQUIV 2306 1266 +EQUIV 2307 1267 +EQUIV 2308 1268 +EQUIV 2309 1269 +EQUIV 2310 1270 +EQUIV 2311 1571 +EQUIV 2312 1572 +EQUIV 2313 1573 +EQUIV 2314 1574 +EQUIV 2315 1575 +EQUIV 2316 1516 +EQUIV 2317 1517 +EQUIV 2318 1518 +EQUIV 2319 1519 +EQUIV 2320 1520 +EQUIV 2321 1321 +EQUIV 2322 1322 +EQUIV 2323 1323 +EQUIV 2324 1324 +EQUIV 2325 1325 +EQUIV 2326 1366 +EQUIV 2327 1367 +EQUIV 2328 1368 +EQUIV 2329 1369 +EQUIV 2330 1370 +EQUIV 2331 1371 +EQUIV 2332 1372 +EQUIV 2333 1373 +EQUIV 2334 1374 +EQUIV 2335 1375 +EQUIV 2336 1516 +EQUIV 2337 1517 +EQUIV 2338 1518 +EQUIV 2339 1519 +EQUIV 2340 1520 +EQUIV 2341 1321 +EQUIV 2342 1322 +EQUIV 2343 1323 +EQUIV 2344 1324 +EQUIV 2345 1325 +EQUIV 2346 1366 +EQUIV 2347 1367 +EQUIV 2348 1368 +EQUIV 2349 1369 +EQUIV 2350 1370 +EQUIV 2351 1371 +EQUIV 2352 1372 +EQUIV 2353 1373 +EQUIV 2354 1374 +EQUIV 2355 1375 +EQUIV 2356 1516 +EQUIV 2357 1517 +EQUIV 2358 1518 +EQUIV 2359 1519 +EQUIV 2360 1520 +EQUIV 2361 1321 +EQUIV 2362 1322 +EQUIV 2363 1323 +EQUIV 2364 1324 +EQUIV 2365 1325 +EQUIV 2366 1366 +EQUIV 2367 1367 +EQUIV 2368 1368 +EQUIV 2369 1369 +EQUIV 2370 1370 +EQUIV 2371 1371 +EQUIV 2372 1372 +EQUIV 2373 1373 +EQUIV 2374 1374 +EQUIV 2375 1375 +EQUIV 2376 1376 +EQUIV 2377 1377 +EQUIV 2378 1378 +EQUIV 2379 1379 +EQUIV 2380 1380 +EQUIV 2381 1541 +EQUIV 2382 1542 +EQUIV 2383 1543 +EQUIV 2384 1544 +EQUIV 2385 1545 +EQUIV 2386 1266 +EQUIV 2387 1267 +EQUIV 2388 1268 +EQUIV 2389 1269 +EQUIV 2390 1270 +EQUIV 2391 1571 +EQUIV 2392 1572 +EQUIV 2393 1573 +EQUIV 2394 1574 +EQUIV 2395 1575 +EQUIV 2396 1376 +EQUIV 2397 1377 +EQUIV 2398 1378 +EQUIV 2399 1379 +EQUIV 2400 1380 +EQUIV 2401 1541 +EQUIV 2402 1542 +EQUIV 2403 1543 +EQUIV 2404 1544 +EQUIV 2405 1545 +EQUIV 2406 1546 +EQUIV 2407 1547 +EQUIV 2408 1548 +EQUIV 2409 1549 +EQUIV 2410 1550 +EQUIV 2416 1256 +EQUIV 2417 1257 +EQUIV 2418 1258 +EQUIV 2419 1259 +EQUIV 2420 1260 +EQUIV 2421 1261 +EQUIV 2422 1262 +EQUIV 2423 1263 +EQUIV 2424 1264 +EQUIV 2425 1265 +EQUIV 2426 1546 +EQUIV 2427 1547 +EQUIV 2428 1548 +EQUIV 2429 1549 +EQUIV 2430 1550 +EQUIV 2431 2411 +EQUIV 2432 2412 +EQUIV 2433 2413 +EQUIV 2434 2414 +EQUIV 2435 2415 +EQUIV 2436 1256 +EQUIV 2437 1257 +EQUIV 2438 1258 +EQUIV 2439 1259 +EQUIV 2440 1260 +EQUIV 2446 1226 +EQUIV 2447 1227 +EQUIV 2448 1228 +EQUIV 2449 1229 +EQUIV 2450 1230 +EQUIV 2451 1231 +EQUIV 2452 1232 +EQUIV 2453 1233 +EQUIV 2454 1234 +EQUIV 2455 1235 +EQUIV 2456 1236 +EQUIV 2457 1237 +EQUIV 2458 1238 +EQUIV 2459 1239 +EQUIV 2460 1240 +EQUIV 2461 1241 +EQUIV 2462 1242 +EQUIV 2463 1243 +EQUIV 2464 1244 +EQUIV 2465 1245 +EQUIV 2466 1246 +EQUIV 2467 1247 +EQUIV 2468 1248 +EQUIV 2469 1249 +EQUIV 2470 1250 +EQUIV 2476 716 +EQUIV 2477 717 +EQUIV 2478 718 +EQUIV 2479 719 +EQUIV 2480 720 +EQUIV 2481 1221 +EQUIV 2482 1222 +EQUIV 2483 1223 +EQUIV 2484 1224 +EQUIV 2485 1225 +EQUIV 2486 1226 +EQUIV 2487 1227 +EQUIV 2488 1228 +EQUIV 2489 1229 +EQUIV 2490 1230 +EQUIV 2491 1231 +EQUIV 2492 1232 +EQUIV 2493 1233 +EQUIV 2494 1234 +EQUIV 2495 1235 +EQUIV 2496 1256 +EQUIV 2497 1257 +EQUIV 2498 1258 +EQUIV 2499 1259 +EQUIV 2500 1260 +EQUIV 2501 2441 +EQUIV 2502 2442 +EQUIV 2503 2443 +EQUIV 2504 2444 +EQUIV 2505 2445 +EQUIV 2521 1261 +EQUIV 2522 1262 +EQUIV 2523 1263 +EQUIV 2524 1264 +EQUIV 2525 1265 +EQUIV 2526 1546 +EQUIV 2527 1547 +EQUIV 2528 1548 +EQUIV 2529 1549 +EQUIV 2530 1550 +EQUIV 2531 2411 +EQUIV 2532 2412 +EQUIV 2533 2413 +EQUIV 2534 2414 +EQUIV 2535 2415 +EQUIV 2536 1256 +EQUIV 2537 1257 +EQUIV 2538 1258 +EQUIV 2539 1259 +EQUIV 2540 1260 +EQUIV 2541 1261 +EQUIV 2542 1262 +EQUIV 2543 1263 +EQUIV 2544 1264 +EQUIV 2545 1265 +EQUIV 2546 1546 +EQUIV 2547 1547 +EQUIV 2548 1548 +EQUIV 2549 1549 +EQUIV 2550 1550 +EQUIV 2551 2411 +EQUIV 2552 2412 +EQUIV 2553 2413 +EQUIV 2554 2414 +EQUIV 2555 2415 +EQUIV 2556 1256 +EQUIV 2557 1257 +EQUIV 2558 1258 +EQUIV 2559 1259 +EQUIV 2560 1260 +EQUIV 2561 1261 +EQUIV 2562 1262 +EQUIV 2563 1263 +EQUIV 2564 1264 +EQUIV 2565 1265 +EQUIV 2566 1546 +EQUIV 2567 1547 +EQUIV 2568 1548 +EQUIV 2569 1549 +EQUIV 2570 1550 +EQUIV 2571 2411 +EQUIV 2572 2412 +EQUIV 2573 2413 +EQUIV 2574 2414 +EQUIV 2575 2415 +EQUIV 2576 1256 +EQUIV 2577 1257 +EQUIV 2578 1258 +EQUIV 2579 1259 +EQUIV 2580 1260 +EQUIV 2581 1261 +EQUIV 2582 1262 +EQUIV 2583 1263 +EQUIV 2584 1264 +EQUIV 2585 1265 +EQUIV 2586 1546 +EQUIV 2587 1547 +EQUIV 2588 1548 +EQUIV 2589 1549 +EQUIV 2590 1550 +EQUIV 2591 2411 +EQUIV 2592 2412 +EQUIV 2593 2413 +EQUIV 2594 2414 +EQUIV 2595 2415 +EQUIV 2596 1256 +EQUIV 2597 1257 +EQUIV 2598 1258 +EQUIV 2599 1259 +EQUIV 2600 1260 +EQUIV 2601 2441 +EQUIV 2602 2442 +EQUIV 2603 2443 +EQUIV 2604 2444 +EQUIV 2605 2445 +EQUIV 2606 2506 +EQUIV 2607 2507 +EQUIV 2608 2508 +EQUIV 2609 2509 +EQUIV 2610 2510 +EQUIV 2631 2511 +EQUIV 2632 2512 +EQUIV 2633 2513 +EQUIV 2634 2514 +EQUIV 2635 2515 +EQUIV 2636 2516 +EQUIV 2637 2517 +EQUIV 2638 2518 +EQUIV 2639 2519 +EQUIV 2640 2520 +EQUIV 2641 2441 +EQUIV 2642 2442 +EQUIV 2643 2443 +EQUIV 2644 2444 +EQUIV 2645 2445 +EQUIV 2646 2506 +EQUIV 2647 2507 +EQUIV 2648 2508 +EQUIV 2649 2509 +EQUIV 2650 2510 +EQUIV 2651 2511 +EQUIV 2652 2512 +EQUIV 2653 2513 +EQUIV 2654 2514 +EQUIV 2655 2515 +EQUIV 2656 2516 +EQUIV 2657 2517 +EQUIV 2658 2518 +EQUIV 2659 2519 +EQUIV 2660 2520 +EQUIV 2661 2441 +EQUIV 2662 2442 +EQUIV 2663 2443 +EQUIV 2664 2444 +EQUIV 2665 2445 +EQUIV 2666 2506 +EQUIV 2667 2507 +EQUIV 2668 2508 +EQUIV 2669 2509 +EQUIV 2670 2510 +EQUIV 2671 2611 +EQUIV 2672 2612 +EQUIV 2673 2613 +EQUIV 2674 2614 +EQUIV 2675 2615 +EQUIV 2676 2616 +EQUIV 2677 2617 +EQUIV 2678 2618 +EQUIV 2679 2619 +EQUIV 2680 2620 +EQUIV 2681 2621 +EQUIV 2682 2622 +EQUIV 2683 2623 +EQUIV 2684 2624 +EQUIV 2685 2625 +EQUIV 2686 2626 +EQUIV 2687 2627 +EQUIV 2688 2628 +EQUIV 2689 2629 +EQUIV 2690 2630 +EQUIV 2691 2611 +EQUIV 2692 2612 +EQUIV 2693 2613 +EQUIV 2694 2614 +EQUIV 2695 2615 +EQUIV 2696 2616 +EQUIV 2697 2617 +EQUIV 2698 2618 +EQUIV 2699 2619 +EQUIV 2700 2620 +EQUIV 2761 2621 +EQUIV 2762 2622 +EQUIV 2763 2623 +EQUIV 2764 2624 +EQUIV 2765 2625 +EQUIV 2766 2626 +EQUIV 2767 2627 +EQUIV 2768 2628 +EQUIV 2769 2629 +EQUIV 2770 2630 +EQUIV 2771 2611 +EQUIV 2772 2612 +EQUIV 2773 2613 +EQUIV 2774 2614 +EQUIV 2775 2615 +EQUIV 2776 2616 +EQUIV 2777 2617 +EQUIV 2778 2618 +EQUIV 2779 2619 +EQUIV 2780 2620 +EQUIV 2781 2621 +EQUIV 2782 2622 +EQUIV 2783 2623 +EQUIV 2784 2624 +EQUIV 2785 2625 +EQUIV 2806 2786 +EQUIV 2807 2787 +EQUIV 2808 2788 +EQUIV 2809 2789 +EQUIV 2810 2790 +EQUIV 2811 2791 +EQUIV 2812 2792 +EQUIV 2813 2793 +EQUIV 2814 2794 +EQUIV 2815 2795 +EQUIV 2816 2796 +EQUIV 2817 2797 +EQUIV 2818 2798 +EQUIV 2819 2799 +EQUIV 2820 2800 +EQUIV 2821 1281 +EQUIV 2822 1282 +EQUIV 2823 1283 +EQUIV 2824 1284 +EQUIV 2825 1285 +EQUIV 2826 1286 +EQUIV 2827 1287 +EQUIV 2828 1288 +EQUIV 2829 1289 +EQUIV 2830 1290 +EQUIV 2831 1271 +EQUIV 2832 1272 +EQUIV 2833 1273 +EQUIV 2834 1274 +EQUIV 2835 1275 +EQUIV 2836 1276 +EQUIV 2837 1277 +EQUIV 2838 1278 +EQUIV 2839 1279 +EQUIV 2840 1280 +EQUIV 2841 2801 +EQUIV 2842 2802 +EQUIV 2843 2803 +EQUIV 2844 2804 +EQUIV 2845 2805 +EQUIV 2846 2626 +EQUIV 2847 2627 +EQUIV 2848 2628 +EQUIV 2849 2629 +EQUIV 2850 2630 +EQUIV 2851 2611 +EQUIV 2852 2612 +EQUIV 2853 2613 +EQUIV 2854 2614 +EQUIV 2855 2615 +EQUIV 2856 2616 +EQUIV 2857 2617 +EQUIV 2858 2618 +EQUIV 2859 2619 +EQUIV 2860 2620 +EQUIV 2861 2701 +EQUIV 2862 2702 +EQUIV 2863 2703 +EQUIV 2864 2704 +EQUIV 2865 2705 +EQUIV 2866 2746 +EQUIV 2867 2747 +EQUIV 2868 2748 +EQUIV 2869 2749 +EQUIV 2870 2750 +EQUIV 2871 2751 +EQUIV 2872 2752 +EQUIV 2873 2753 +EQUIV 2874 2754 +EQUIV 2875 2755 +EQUIV 2876 2756 +EQUIV 2877 2757 +EQUIV 2878 2758 +EQUIV 2879 2759 +EQUIV 2880 2760 +EQUIV 2881 2701 +EQUIV 2882 2702 +EQUIV 2883 2703 +EQUIV 2884 2704 +EQUIV 2885 2705 +EQUIV 2886 2746 +EQUIV 2887 2747 +EQUIV 2888 2748 +EQUIV 2889 2749 +EQUIV 2890 2750 +EQUIV 2931 2891 +EQUIV 2932 2892 +EQUIV 2933 2893 +EQUIV 2934 2894 +EQUIV 2935 2895 +EQUIV 2936 2896 +EQUIV 2937 2897 +EQUIV 2938 2898 +EQUIV 2939 2899 +EQUIV 2940 2900 +EQUIV 2941 2901 +EQUIV 2942 2902 +EQUIV 2943 2903 +EQUIV 2944 2904 +EQUIV 2945 2905 +EQUIV 2946 2926 +EQUIV 2947 2927 +EQUIV 2948 2928 +EQUIV 2949 2929 +EQUIV 2950 2930 +EQUIV 2951 2751 +EQUIV 2952 2752 +EQUIV 2953 2753 +EQUIV 2954 2754 +EQUIV 2955 2755 +EQUIV 2956 2756 +EQUIV 2957 2757 +EQUIV 2958 2758 +EQUIV 2959 2759 +EQUIV 2960 2760 +EQUIV 2961 2701 +EQUIV 2962 2702 +EQUIV 2963 2703 +EQUIV 2964 2704 +EQUIV 2965 2705 +EQUIV 2966 2706 +EQUIV 2967 2707 +EQUIV 2968 2708 +EQUIV 2969 2709 +EQUIV 2970 2710 +EQUIV 2981 1221 +EQUIV 2982 1222 +EQUIV 2983 1223 +EQUIV 2984 1224 +EQUIV 2985 1225 +EQUIV 2986 1226 +EQUIV 2987 1227 +EQUIV 2988 1228 +EQUIV 2989 1229 +EQUIV 2990 1230 +EQUIV 2991 2471 +EQUIV 2992 2472 +EQUIV 2993 2473 +EQUIV 2994 2474 +EQUIV 2995 2475 +EQUIV 2996 716 +EQUIV 2997 717 +EQUIV 2998 718 +EQUIV 2999 719 +EQUIV 3000 720 +EQUIV 3001 721 +EQUIV 3002 722 +EQUIV 3003 723 +EQUIV 3004 724 +EQUIV 3005 725 +EQUIV 3011 2711 +EQUIV 3012 2712 +EQUIV 3013 2713 +EQUIV 3014 2714 +EQUIV 3015 2715 +EQUIV 3026 1106 +EQUIV 3027 1107 +EQUIV 3028 1108 +EQUIV 3029 1109 +EQUIV 3030 1110 +EQUIV 3031 1111 +EQUIV 3032 1112 +EQUIV 3033 1113 +EQUIV 3034 1114 +EQUIV 3035 1115 +EQUIV 3036 1096 +EQUIV 3037 1097 +EQUIV 3038 1098 +EQUIV 3039 1099 +EQUIV 3040 1100 +EQUIV 3041 1101 +EQUIV 3042 1102 +EQUIV 3043 1103 +EQUIV 3044 1104 +EQUIV 3045 1105 +EQUIV 3046 1106 +EQUIV 3047 1107 +EQUIV 3048 1108 +EQUIV 3049 1109 +EQUIV 3050 1110 +EQUIV 3051 1111 +EQUIV 3052 1112 +EQUIV 3053 1113 +EQUIV 3054 1114 +EQUIV 3055 1115 +EQUIV 3076 1076 +EQUIV 3077 1077 +EQUIV 3078 1078 +EQUIV 3079 1079 +EQUIV 3080 1080 +EQUIV 3081 3061 +EQUIV 3082 3062 +EQUIV 3083 3063 +EQUIV 3084 3064 +EQUIV 3085 3065 +EQUIV 3086 1166 +EQUIV 3087 1167 +EQUIV 3088 1168 +EQUIV 3089 1169 +EQUIV 3090 1170 +EQUIV 3091 1151 +EQUIV 3092 1152 +EQUIV 3093 1153 +EQUIV 3094 1154 +EQUIV 3095 1155 +EQUIV 3096 1156 +EQUIV 3097 1157 +EQUIV 3098 1158 +EQUIV 3099 1159 +EQUIV 3100 1160 +EQUIV 3101 1161 +EQUIV 3102 1162 +EQUIV 3103 1163 +EQUIV 3104 1164 +EQUIV 3105 1165 +EQUIV 3106 1166 +EQUIV 3107 1167 +EQUIV 3108 1168 +EQUIV 3109 1169 +EQUIV 3110 1170 +EQUIV 3111 1151 +EQUIV 3112 1152 +EQUIV 3113 1153 +EQUIV 3114 1154 +EQUIV 3115 1155 +EQUIV 3116 1156 +EQUIV 3117 1157 +EQUIV 3118 1158 +EQUIV 3119 1159 +EQUIV 3120 1160 +EQUIV 3121 1161 +EQUIV 3122 1162 +EQUIV 3123 1163 +EQUIV 3124 1164 +EQUIV 3125 1165 +EQUIV 3126 1166 +EQUIV 3127 1167 +EQUIV 3128 1168 +EQUIV 3129 1169 +EQUIV 3130 1170 +EQUIV 3131 1151 +EQUIV 3132 1152 +EQUIV 3133 1153 +EQUIV 3134 1154 +EQUIV 3135 1155 +EQUIV 3136 1156 +EQUIV 3137 1157 +EQUIV 3138 1158 +EQUIV 3139 1159 +EQUIV 3140 1160 +EQUIV 3141 1161 +EQUIV 3142 1162 +EQUIV 3143 1163 +EQUIV 3144 1164 +EQUIV 3145 1165 +EQUIV 3146 3066 +EQUIV 3147 3067 +EQUIV 3148 3068 +EQUIV 3149 3069 +EQUIV 3150 3070 +EQUIV 3151 3071 +EQUIV 3152 3072 +EQUIV 3153 3073 +EQUIV 3154 3074 +EQUIV 3155 3075 +EQUIV 3156 1076 +EQUIV 3157 1077 +EQUIV 3158 1078 +EQUIV 3159 1079 +EQUIV 3160 1080 +EQUIV 3161 3061 +EQUIV 3162 3062 +EQUIV 3163 3063 +EQUIV 3164 3064 +EQUIV 3165 3065 +EQUIV 3166 1166 +EQUIV 3167 1167 +EQUIV 3168 1168 +EQUIV 3169 1169 +EQUIV 3170 1170 +EQUIV 3171 1151 +EQUIV 3172 1152 +EQUIV 3173 1153 +EQUIV 3174 1154 +EQUIV 3175 1155 +EQUIV 3186 726 +EQUIV 3187 727 +EQUIV 3188 728 +EQUIV 3189 729 +EQUIV 3190 730 +EQUIV 3191 711 +EQUIV 3192 712 +EQUIV 3193 713 +EQUIV 3194 714 +EQUIV 3195 715 +EQUIV 3196 736 +EQUIV 3197 737 +EQUIV 3198 738 +EQUIV 3199 739 +EQUIV 3200 740 +EQUIV 3201 701 +EQUIV 3202 702 +EQUIV 3203 703 +EQUIV 3204 704 +EQUIV 3205 705 +EQUIV 3206 706 +EQUIV 3207 707 +EQUIV 3208 708 +EQUIV 3209 709 +EQUIV 3210 710 +EQUIV 3211 711 +EQUIV 3212 712 +EQUIV 3213 713 +EQUIV 3214 714 +EQUIV 3215 715 +EQUIV 3216 736 +EQUIV 3217 737 +EQUIV 3218 738 +EQUIV 3219 739 +EQUIV 3220 740 +EQUIV 3221 701 +EQUIV 3222 702 +EQUIV 3223 703 +EQUIV 3224 704 +EQUIV 3225 705 +EQUIV 3226 706 +EQUIV 3227 707 +EQUIV 3228 708 +EQUIV 3229 709 +EQUIV 3230 710 +EQUIV 3231 711 +EQUIV 3232 712 +EQUIV 3233 713 +EQUIV 3234 714 +EQUIV 3235 715 +EQUIV 3236 716 +EQUIV 3237 717 +EQUIV 3238 718 +EQUIV 3239 719 +EQUIV 3240 720 +EQUIV 3241 1221 +EQUIV 3242 1222 +EQUIV 3243 1223 +EQUIV 3244 1224 +EQUIV 3245 1225 +EQUIV 3246 1226 +EQUIV 3247 1227 +EQUIV 3248 1228 +EQUIV 3249 1229 +EQUIV 3250 1230 +EQUIV 3251 2471 +EQUIV 3252 2472 +EQUIV 3253 2473 +EQUIV 3254 2474 +EQUIV 3255 2475 +EQUIV 3256 716 +EQUIV 3257 717 +EQUIV 3258 718 +EQUIV 3259 719 +EQUIV 3260 720 +EQUIV 3261 721 +EQUIV 3262 722 +EQUIV 3263 723 +EQUIV 3264 724 +EQUIV 3265 725 +EQUIV 3266 3006 +EQUIV 3267 3007 +EQUIV 3268 3008 +EQUIV 3269 3009 +EQUIV 3270 3010 +EQUIV 3271 2971 +EQUIV 3272 2972 +EQUIV 3273 2973 +EQUIV 3274 2974 +EQUIV 3275 2975 +EQUIV 3276 2976 +EQUIV 3277 2977 +EQUIV 3278 2978 +EQUIV 3279 2979 +EQUIV 3280 2980 +EQUIV 3281 721 +EQUIV 3282 722 +EQUIV 3283 723 +EQUIV 3284 724 +EQUIV 3285 725 +EQUIV 3286 3006 +EQUIV 3287 3007 +EQUIV 3288 3008 +EQUIV 3289 3009 +EQUIV 3290 3010 +EQUIV 3291 2971 +EQUIV 3292 2972 +EQUIV 3293 2973 +EQUIV 3294 2974 +EQUIV 3295 2975 +EQUIV 3296 2976 +EQUIV 3297 2977 +EQUIV 3298 2978 +EQUIV 3299 2979 +EQUIV 3300 2980 +EQUIV 3301 1221 +EQUIV 3302 1222 +EQUIV 3303 1223 +EQUIV 3304 1224 +EQUIV 3305 1225 +EQUIV 3306 1226 +EQUIV 3307 1227 +EQUIV 3308 1228 +EQUIV 3309 1229 +EQUIV 3310 1230 +EQUIV 3311 1231 +EQUIV 3312 1232 +EQUIV 3313 1233 +EQUIV 3314 1234 +EQUIV 3315 1235 +EQUIV 3316 1236 +EQUIV 3317 1237 +EQUIV 3318 1238 +EQUIV 3319 1239 +EQUIV 3320 1240 +EQUIV 3321 1241 +EQUIV 3322 1242 +EQUIV 3323 1243 +EQUIV 3324 1244 +EQUIV 3325 1245 +EQUIV 3326 746 +EQUIV 3327 747 +EQUIV 3328 748 +EQUIV 3329 749 +EQUIV 3330 750 +EQUIV 3331 751 +EQUIV 3332 752 +EQUIV 3333 753 +EQUIV 3334 754 +EQUIV 3335 755 +EQUIV 3336 696 +EQUIV 3337 697 +EQUIV 3338 698 +EQUIV 3339 699 +EQUIV 3340 700 +EQUIV 3341 741 +EQUIV 3342 742 +EQUIV 3343 743 +EQUIV 3344 744 +EQUIV 3345 745 +EQUIV 3346 746 +EQUIV 3347 747 +EQUIV 3348 748 +EQUIV 3349 749 +EQUIV 3350 750 +EQUIV 3351 751 +EQUIV 3352 752 +EQUIV 3353 753 +EQUIV 3354 754 +EQUIV 3355 755 +EQUIV 3356 696 +EQUIV 3357 697 +EQUIV 3358 698 +EQUIV 3359 699 +EQUIV 3360 700 +EQUIV 3361 701 +EQUIV 3362 702 +EQUIV 3363 703 +EQUIV 3364 704 +EQUIV 3365 705 +EQUIV 3366 706 +EQUIV 3367 707 +EQUIV 3368 708 +EQUIV 3369 709 +EQUIV 3370 710 +EQUIV 3376 1156 +EQUIV 3377 1157 +EQUIV 3378 1158 +EQUIV 3379 1159 +EQUIV 3380 1160 +EQUIV 3381 1161 +EQUIV 3382 1162 +EQUIV 3383 1163 +EQUIV 3384 1164 +EQUIV 3385 1165 +EQUIV 3386 3066 +EQUIV 3387 3067 +EQUIV 3388 3068 +EQUIV 3389 3069 +EQUIV 3390 3070 +EQUIV 3396 916 +EQUIV 3397 917 +EQUIV 3398 918 +EQUIV 3399 919 +EQUIV 3400 920 +EQUIV 3401 921 +EQUIV 3402 922 +EQUIV 3403 923 +EQUIV 3404 924 +EQUIV 3405 925 +EQUIV 3411 3391 +EQUIV 3412 3392 +EQUIV 3413 3393 +EQUIV 3414 3394 +EQUIV 3415 3395 +EQUIV 3416 836 +EQUIV 3417 837 +EQUIV 3418 838 +EQUIV 3419 839 +EQUIV 3420 840 +EQUIV 3421 841 +EQUIV 3422 842 +EQUIV 3423 843 +EQUIV 3424 844 +EQUIV 3425 845 +EQUIV 3426 826 +EQUIV 3427 827 +EQUIV 3428 828 +EQUIV 3429 829 +EQUIV 3430 830 +EQUIV 3431 831 +EQUIV 3432 832 +EQUIV 3433 833 +EQUIV 3434 834 +EQUIV 3435 835 +EQUIV 3436 836 +EQUIV 3437 837 +EQUIV 3438 838 +EQUIV 3439 839 +EQUIV 3440 840 +EQUIV 3441 841 +EQUIV 3442 842 +EQUIV 3443 843 +EQUIV 3444 844 +EQUIV 3445 845 +EQUIV 3446 826 +EQUIV 3447 827 +EQUIV 3448 828 +EQUIV 3449 829 +EQUIV 3450 830 +EQUIV 3451 691 +EQUIV 3452 692 +EQUIV 3453 693 +EQUIV 3454 694 +EQUIV 3455 695 +EQUIV 3456 696 +EQUIV 3457 697 +EQUIV 3458 698 +EQUIV 3459 699 +EQUIV 3460 700 +EQUIV 3461 701 +EQUIV 3462 702 +EQUIV 3463 703 +EQUIV 3464 704 +EQUIV 3465 705 +EQUIV 3466 706 +EQUIV 3467 707 +EQUIV 3468 708 +EQUIV 3469 709 +EQUIV 3470 710 +EQUIV 3471 3371 +EQUIV 3472 3372 +EQUIV 3473 3373 +EQUIV 3474 3374 +EQUIV 3475 3375 +EQUIV 3476 1156 +EQUIV 3477 1157 +EQUIV 3478 1158 +EQUIV 3479 1159 +EQUIV 3480 1160 +EQUIV 3481 1161 +EQUIV 3482 1162 +EQUIV 3483 1163 +EQUIV 3484 1164 +EQUIV 3485 1165 +EQUIV 3486 1166 +EQUIV 3487 1167 +EQUIV 3488 1168 +EQUIV 3489 1169 +EQUIV 3490 1170 +EQUIV 3491 1151 +EQUIV 3492 1152 +EQUIV 3493 1153 +EQUIV 3494 1154 +EQUIV 3495 1155 +EQUIV 3496 3176 +EQUIV 3497 3177 +EQUIV 3498 3178 +EQUIV 3499 3179 +EQUIV 3500 3180 +EQUIV 3501 3021 +EQUIV 3502 3022 +EQUIV 3503 3023 +EQUIV 3504 3024 +EQUIV 3505 3025 +EQUIV 3516 2716 +EQUIV 3517 2717 +EQUIV 3518 2718 +EQUIV 3519 2719 +EQUIV 3520 2720 +EQUIV 3521 2721 +EQUIV 3522 2722 +EQUIV 3523 2723 +EQUIV 3524 2724 +EQUIV 3525 2725 +EQUIV 3526 2726 +EQUIV 3527 2727 +EQUIV 3528 2728 +EQUIV 3529 2729 +EQUIV 3530 2730 +EQUIV 3571 2911 +EQUIV 3572 2912 +EQUIV 3573 2913 +EQUIV 3574 2914 +EQUIV 3575 2915 +EQUIV 3576 2916 +EQUIV 3577 2917 +EQUIV 3578 2918 +EQUIV 3579 2919 +EQUIV 3580 2920 +EQUIV 3581 2921 +EQUIV 3582 2922 +EQUIV 3583 2923 +EQUIV 3584 2924 +EQUIV 3585 2925 +EQUIV 3586 2906 +EQUIV 3587 2907 +EQUIV 3588 2908 +EQUIV 3589 2909 +EQUIV 3590 2910 +EQUIV 3591 2911 +EQUIV 3592 2912 +EQUIV 3593 2913 +EQUIV 3594 2914 +EQUIV 3595 2915 +EQUIV 3656 3636 +EQUIV 3657 3637 +EQUIV 3658 3638 +EQUIV 3659 3639 +EQUIV 3660 3640 +EQUIV 3661 3641 +EQUIV 3662 3642 +EQUIV 3663 3643 +EQUIV 3664 3644 +EQUIV 3665 3645 +EQUIV 3666 3646 +EQUIV 3667 3647 +EQUIV 3668 3648 +EQUIV 3669 3649 +EQUIV 3670 3650 +EQUIV 3671 3651 +EQUIV 3672 3652 +EQUIV 3673 3653 +EQUIV 3674 3654 +EQUIV 3675 3655 +EQUIV 3676 3636 +EQUIV 3677 3637 +EQUIV 3678 3638 +EQUIV 3679 3639 +EQUIV 3680 3640 +EQUIV 3681 3641 +EQUIV 3682 3642 +EQUIV 3683 3643 +EQUIV 3684 3644 +EQUIV 3685 3645 +EQUIV 3686 3566 +EQUIV 3687 3567 +EQUIV 3688 3568 +EQUIV 3689 3569 +EQUIV 3690 3570 +EQUIV 3696 3556 +EQUIV 3697 3557 +EQUIV 3698 3558 +EQUIV 3699 3559 +EQUIV 3700 3560 +EQUIV 3721 3561 +EQUIV 3722 3562 +EQUIV 3723 3563 +EQUIV 3724 3564 +EQUIV 3725 3565 +EQUIV 3726 3566 +EQUIV 3727 3567 +EQUIV 3728 3568 +EQUIV 3729 3569 +EQUIV 3730 3570 +EQUIV 3731 2911 +EQUIV 3732 2912 +EQUIV 3733 2913 +EQUIV 3734 2914 +EQUIV 3735 2915 +EQUIV 3736 2916 +EQUIV 3737 2917 +EQUIV 3738 2918 +EQUIV 3739 2919 +EQUIV 3740 2920 +EQUIV 3741 2921 +EQUIV 3742 2922 +EQUIV 3743 2923 +EQUIV 3744 2924 +EQUIV 3745 2925 +EQUIV 3746 2906 +EQUIV 3747 2907 +EQUIV 3748 2908 +EQUIV 3749 2909 +EQUIV 3750 2910 +EQUIV 3751 2911 +EQUIV 3752 2912 +EQUIV 3753 2913 +EQUIV 3754 2914 +EQUIV 3755 2915 +EQUIV 3756 3596 +EQUIV 3757 3597 +EQUIV 3758 3598 +EQUIV 3759 3599 +EQUIV 3760 3600 +EQUIV 3761 3641 +EQUIV 3762 3642 +EQUIV 3763 3643 +EQUIV 3764 3644 +EQUIV 3765 3645 +EQUIV 3766 3566 +EQUIV 3767 3567 +EQUIV 3768 3568 +EQUIV 3769 3569 +EQUIV 3770 3570 +EQUIV 3771 3691 +EQUIV 3772 3692 +EQUIV 3773 3693 +EQUIV 3774 3694 +EQUIV 3775 3695 +EQUIV 3776 3556 +EQUIV 3777 3557 +EQUIV 3778 3558 +EQUIV 3779 3559 +EQUIV 3780 3560 +EQUIV 3781 3701 +EQUIV 3782 3702 +EQUIV 3783 3703 +EQUIV 3784 3704 +EQUIV 3785 3705 +EQUIV 3786 3706 +EQUIV 3787 3707 +EQUIV 3788 3708 +EQUIV 3789 3709 +EQUIV 3790 3710 +EQUIV 3791 3711 +EQUIV 3792 3712 +EQUIV 3793 3713 +EQUIV 3794 3714 +EQUIV 3795 3715 +EQUIV 3811 3651 +EQUIV 3812 3652 +EQUIV 3813 3653 +EQUIV 3814 3654 +EQUIV 3815 3655 +EQUIV 3816 3636 +EQUIV 3817 3637 +EQUIV 3818 3638 +EQUIV 3819 3639 +EQUIV 3820 3640 +EQUIV 3821 3641 +EQUIV 3822 3642 +EQUIV 3823 3643 +EQUIV 3824 3644 +EQUIV 3825 3645 +EQUIV 3826 3646 +EQUIV 3827 3647 +EQUIV 3828 3648 +EQUIV 3829 3649 +EQUIV 3830 3650 +EQUIV 3836 3796 +EQUIV 3837 3797 +EQUIV 3838 3798 +EQUIV 3839 3799 +EQUIV 3840 3800 +EQUIV 3876 3856 +EQUIV 3877 3857 +EQUIV 3878 3858 +EQUIV 3879 3859 +EQUIV 3880 3860 +EQUIV 3926 3906 +EQUIV 3927 3907 +EQUIV 3928 3908 +EQUIV 3929 3909 +EQUIV 3930 3910 +EQUIV 3931 3911 +EQUIV 3932 3912 +EQUIV 3933 3913 +EQUIV 3934 3914 +EQUIV 3935 3915 +EQUIV 3936 3916 +EQUIV 3937 3917 +EQUIV 3938 3918 +EQUIV 3939 3919 +EQUIV 3940 3920 +EQUIV 3941 3921 +EQUIV 3942 3922 +EQUIV 3943 3923 +EQUIV 3944 3924 +EQUIV 3945 3925 +EQUIV 3946 3906 +EQUIV 3947 3907 +EQUIV 3948 3908 +EQUIV 3949 3909 +EQUIV 3950 3910 +EQUIV 3971 3911 +EQUIV 3972 3912 +EQUIV 3973 3913 +EQUIV 3974 3914 +EQUIV 3975 3915 +EQUIV 3996 3976 +EQUIV 3997 3977 +EQUIV 3998 3978 +EQUIV 3999 3979 +EQUIV 4000 3980 +EQUIV 4001 3981 +EQUIV 4002 3982 +EQUIV 4003 3983 +EQUIV 4004 3984 +EQUIV 4005 3985 +EQUIV 4006 3986 +EQUIV 4007 3987 +EQUIV 4008 3988 +EQUIV 4009 3989 +EQUIV 4010 3990 +EQUIV 4011 3991 +EQUIV 4012 3992 +EQUIV 4013 3993 +EQUIV 4014 3994 +EQUIV 4015 3995 +EQUIV 4016 3976 +EQUIV 4017 3977 +EQUIV 4018 3978 +EQUIV 4019 3979 +EQUIV 4020 3980 +EQUIV 4066 4046 +EQUIV 4067 4047 +EQUIV 4068 4048 +EQUIV 4069 4049 +EQUIV 4070 4050 +EQUIV 4076 3956 +EQUIV 4077 3957 +EQUIV 4078 3958 +EQUIV 4079 3959 +EQUIV 4080 3960 +EQUIV 4081 3961 +EQUIV 4082 3962 +EQUIV 4083 3963 +EQUIV 4084 3964 +EQUIV 4085 3965 +EQUIV 4086 4026 +EQUIV 4087 4027 +EQUIV 4088 4028 +EQUIV 4089 4029 +EQUIV 4090 4030 +EQUIV 4101 4021 +EQUIV 4102 4022 +EQUIV 4103 4023 +EQUIV 4104 4024 +EQUIV 4105 4025 +EQUIV 4106 3966 +EQUIV 4107 3967 +EQUIV 4108 3968 +EQUIV 4109 3969 +EQUIV 4110 3970 +EQUIV 4111 3911 +EQUIV 4112 3912 +EQUIV 4113 3913 +EQUIV 4114 3914 +EQUIV 4115 3915 +EQUIV 4116 3916 +EQUIV 4117 3917 +EQUIV 4118 3918 +EQUIV 4119 3919 +EQUIV 4120 3920 +EQUIV 4121 3921 +EQUIV 4122 3922 +EQUIV 4123 3923 +EQUIV 4124 3924 +EQUIV 4125 3925 +EQUIV 4131 3891 +EQUIV 4132 3892 +EQUIV 4133 3893 +EQUIV 4134 3894 +EQUIV 4135 3895 +EQUIV 4146 3886 +EQUIV 4147 3887 +EQUIV 4148 3888 +EQUIV 4149 3889 +EQUIV 4150 3890 +EQUIV 4151 3891 +EQUIV 4152 3892 +EQUIV 4153 3893 +EQUIV 4154 3894 +EQUIV 4155 3895 +EQUIV 4156 3896 +EQUIV 4157 3897 +EQUIV 4158 3898 +EQUIV 4159 3899 +EQUIV 4160 3900 +EQUIV 4161 3901 +EQUIV 4162 3902 +EQUIV 4163 3903 +EQUIV 4164 3904 +EQUIV 4165 3905 +EQUIV 4166 4126 +EQUIV 4167 4127 +EQUIV 4168 4128 +EQUIV 4169 4129 +EQUIV 4170 4130 +EQUIV 4181 3881 +EQUIV 4182 3882 +EQUIV 4183 3883 +EQUIV 4184 3884 +EQUIV 4185 3885 +EQUIV 4201 4141 +EQUIV 4202 4142 +EQUIV 4203 4143 +EQUIV 4204 4144 +EQUIV 4205 4145 +EQUIV 4206 3886 +EQUIV 4207 3887 +EQUIV 4208 3888 +EQUIV 4209 3889 +EQUIV 4210 3890 +EQUIV 4211 4171 +EQUIV 4212 4172 +EQUIV 4213 4173 +EQUIV 4214 4174 +EQUIV 4215 4175 +EQUIV 4216 4176 +EQUIV 4217 4177 +EQUIV 4218 4178 +EQUIV 4219 4179 +EQUIV 4220 4180 +EQUIV 4221 3881 +EQUIV 4222 3882 +EQUIV 4223 3883 +EQUIV 4224 3884 +EQUIV 4225 3885 +EQUIV 4226 3886 +EQUIV 4227 3887 +EQUIV 4228 3888 +EQUIV 4229 3889 +EQUIV 4230 3890 +EQUIV 4231 4171 +EQUIV 4232 4172 +EQUIV 4233 4173 +EQUIV 4234 4174 +EQUIV 4235 4175 +EQUIV 4241 3921 +EQUIV 4242 3922 +EQUIV 4243 3923 +EQUIV 4244 3924 +EQUIV 4245 3925 +EQUIV 4246 3906 +EQUIV 4247 3907 +EQUIV 4248 3908 +EQUIV 4249 3909 +EQUIV 4250 3910 +EQUIV 4251 3911 +EQUIV 4252 3912 +EQUIV 4253 3913 +EQUIV 4254 3914 +EQUIV 4255 3915 +EQUIV 4256 3916 +EQUIV 4257 3917 +EQUIV 4258 3918 +EQUIV 4259 3919 +EQUIV 4260 3920 +EQUIV 4261 3921 +EQUIV 4262 3922 +EQUIV 4263 3923 +EQUIV 4264 3924 +EQUIV 4265 3925 +EQUIV 4266 3906 +EQUIV 4267 3907 +EQUIV 4268 3908 +EQUIV 4269 3909 +EQUIV 4270 3910 +EQUIV 4271 3911 +EQUIV 4272 3912 +EQUIV 4273 3913 +EQUIV 4274 3914 +EQUIV 4275 3915 +EQUIV 4276 3916 +EQUIV 4277 3917 +EQUIV 4278 3918 +EQUIV 4279 3919 +EQUIV 4280 3920 +EQUIV 4296 4176 +EQUIV 4297 4177 +EQUIV 4298 4178 +EQUIV 4299 4179 +EQUIV 4300 4180 +EQUIV 4301 3881 +EQUIV 4302 3882 +EQUIV 4303 3883 +EQUIV 4304 3884 +EQUIV 4305 3885 +EQUIV 4306 3886 +EQUIV 4307 3887 +EQUIV 4308 3888 +EQUIV 4309 3889 +EQUIV 4310 3890 +EQUIV 4311 4171 +EQUIV 4312 4172 +EQUIV 4313 4173 +EQUIV 4314 4174 +EQUIV 4315 4175 +EQUIV 4316 4176 +EQUIV 4317 4177 +EQUIV 4318 4178 +EQUIV 4319 4179 +EQUIV 4320 4180 +EQUIV 4321 3881 +EQUIV 4322 3882 +EQUIV 4323 3883 +EQUIV 4324 3884 +EQUIV 4325 3885 +EQUIV 4326 4186 +EQUIV 4327 4187 +EQUIV 4328 4188 +EQUIV 4329 4189 +EQUIV 4330 4190 +EQUIV 4331 4191 +EQUIV 4332 4192 +EQUIV 4333 4193 +EQUIV 4334 4194 +EQUIV 4335 4195 +EQUIV 4391 4371 +EQUIV 4392 4372 +EQUIV 4393 4373 +EQUIV 4394 4374 +EQUIV 4395 4375 +EQUIV 4396 4376 +EQUIV 4397 4377 +EQUIV 4398 4378 +EQUIV 4399 4379 +EQUIV 4400 4380 +EQUIV 4416 4376 +EQUIV 4417 4377 +EQUIV 4418 4378 +EQUIV 4419 4379 +EQUIV 4420 4380 +EQUIV 4421 4401 +EQUIV 4422 4402 +EQUIV 4423 4403 +EQUIV 4424 4404 +EQUIV 4425 4405 +EQUIV 4426 4406 +EQUIV 4427 4407 +EQUIV 4428 4408 +EQUIV 4429 4409 +EQUIV 4430 4410 +EQUIV 4431 4411 +EQUIV 4432 4412 +EQUIV 4433 4413 +EQUIV 4434 4414 +EQUIV 4435 4415 +EQUIV 4441 4361 +EQUIV 4442 4362 +EQUIV 4443 4363 +EQUIV 4444 4364 +EQUIV 4445 4365 +EQUIV 4451 4351 +EQUIV 4452 4352 +EQUIV 4453 4353 +EQUIV 4454 4354 +EQUIV 4455 4355 +EQUIV 4466 4346 +EQUIV 4467 4347 +EQUIV 4468 4348 +EQUIV 4469 4349 +EQUIV 4470 4350 +EQUIV 4486 4446 +EQUIV 4487 4447 +EQUIV 4488 4448 +EQUIV 4489 4449 +EQUIV 4490 4450 +EQUIV 4491 4471 +EQUIV 4492 4472 +EQUIV 4493 4473 +EQUIV 4494 4474 +EQUIV 4495 4475 +EQUIV 4506 3846 +EQUIV 4507 3847 +EQUIV 4508 3848 +EQUIV 4509 3849 +EQUIV 4510 3850 +EQUIV 4511 3851 +EQUIV 4512 3852 +EQUIV 4513 3853 +EQUIV 4514 3854 +EQUIV 4515 3855 +EQUIV 4516 3856 +EQUIV 4517 3857 +EQUIV 4518 3858 +EQUIV 4519 3859 +EQUIV 4520 3860 +EQUIV 4521 3861 +EQUIV 4522 3862 +EQUIV 4523 3863 +EQUIV 4524 3864 +EQUIV 4525 3865 +EQUIV 4526 3866 +EQUIV 4527 3867 +EQUIV 4528 3868 +EQUIV 4529 3869 +EQUIV 4530 3870 +EQUIV 4531 3871 +EQUIV 4532 3872 +EQUIV 4533 3873 +EQUIV 4534 3874 +EQUIV 4535 3875 +EQUIV 4541 3801 +EQUIV 4542 3802 +EQUIV 4543 3803 +EQUIV 4544 3804 +EQUIV 4545 3805 +EQUIV 4566 3626 +EQUIV 4567 3627 +EQUIV 4568 3628 +EQUIV 4569 3629 +EQUIV 4570 3630 +EQUIV 4571 3611 +EQUIV 4572 3612 +EQUIV 4573 3613 +EQUIV 4574 3614 +EQUIV 4575 3615 +EQUIV 4596 2916 +EQUIV 4597 2917 +EQUIV 4598 2918 +EQUIV 4599 2919 +EQUIV 4600 2920 +EQUIV 4621 4601 +EQUIV 4622 4602 +EQUIV 4623 4603 +EQUIV 4624 4604 +EQUIV 4625 4605 +EQUIV 4631 4591 +EQUIV 4632 4592 +EQUIV 4633 4593 +EQUIV 4634 4594 +EQUIV 4635 4595 +EQUIV 4636 3596 +EQUIV 4637 3597 +EQUIV 4638 3598 +EQUIV 4639 3599 +EQUIV 4640 3600 +EQUIV 4641 3601 +EQUIV 4642 3602 +EQUIV 4643 3603 +EQUIV 4644 3604 +EQUIV 4645 3605 +EQUIV 4646 4586 +EQUIV 4647 4587 +EQUIV 4648 4588 +EQUIV 4649 4589 +EQUIV 4650 4590 +EQUIV 4651 4591 +EQUIV 4652 4592 +EQUIV 4653 4593 +EQUIV 4654 4594 +EQUIV 4655 4595 +EQUIV 4656 3596 +EQUIV 4657 3597 +EQUIV 4658 3598 +EQUIV 4659 3599 +EQUIV 4660 3600 +EQUIV 4661 3601 +EQUIV 4662 3602 +EQUIV 4663 3603 +EQUIV 4664 3604 +EQUIV 4665 3605 +EQUIV 4666 3606 +EQUIV 4667 3607 +EQUIV 4668 3608 +EQUIV 4669 3609 +EQUIV 4670 3610 +EQUIV 4671 3611 +EQUIV 4672 3612 +EQUIV 4673 3613 +EQUIV 4674 3614 +EQUIV 4675 3615 +EQUIV 4676 4576 +EQUIV 4677 4577 +EQUIV 4678 4578 +EQUIV 4679 4579 +EQUIV 4680 4580 +EQUIV 4681 4581 +EQUIV 4682 4582 +EQUIV 4683 4583 +EQUIV 4684 4584 +EQUIV 4685 4585 +EQUIV 4686 3606 +EQUIV 4687 3607 +EQUIV 4688 3608 +EQUIV 4689 3609 +EQUIV 4690 3610 +EQUIV 4691 3611 +EQUIV 4692 3612 +EQUIV 4693 3613 +EQUIV 4694 3614 +EQUIV 4695 3615 +EQUIV 4696 4576 +EQUIV 4697 4577 +EQUIV 4698 4578 +EQUIV 4699 4579 +EQUIV 4700 4580 +EQUIV 4701 4581 +EQUIV 4702 4582 +EQUIV 4703 4583 +EQUIV 4704 4584 +EQUIV 4705 4585 +EQUIV 4706 4586 +EQUIV 4707 4587 +EQUIV 4708 4588 +EQUIV 4709 4589 +EQUIV 4710 4590 +EQUIV 4736 2796 +EQUIV 4737 2797 +EQUIV 4738 2798 +EQUIV 4739 2799 +EQUIV 4740 2800 +EQUIV 4741 2801 +EQUIV 4742 2802 +EQUIV 4743 2803 +EQUIV 4744 2804 +EQUIV 4745 2805 +EQUIV 4746 2786 +EQUIV 4747 2787 +EQUIV 4748 2788 +EQUIV 4749 2789 +EQUIV 4750 2790 +EQUIV 4751 2791 +EQUIV 4752 2792 +EQUIV 4753 2793 +EQUIV 4754 2794 +EQUIV 4755 2795 +EQUIV 4761 4721 +EQUIV 4762 4722 +EQUIV 4763 4723 +EQUIV 4764 4724 +EQUIV 4765 4725 +EQUIV 4801 4781 +EQUIV 4802 4782 +EQUIV 4803 4783 +EQUIV 4804 4784 +EQUIV 4805 4785 +EQUIV 4826 4806 +EQUIV 4827 4807 +EQUIV 4828 4808 +EQUIV 4829 4809 +EQUIV 4830 4810 +EQUIV 4831 4811 +EQUIV 4832 4812 +EQUIV 4833 4813 +EQUIV 4834 4814 +EQUIV 4835 4815 +EQUIV 4836 4816 +EQUIV 4837 4817 +EQUIV 4838 4818 +EQUIV 4839 4819 +EQUIV 4840 4820 +EQUIV 4841 4821 +EQUIV 4842 4822 +EQUIV 4843 4823 +EQUIV 4844 4824 +EQUIV 4845 4825 +EQUIV 4846 4786 +EQUIV 4847 4787 +EQUIV 4848 4788 +EQUIV 4849 4789 +EQUIV 4850 4790 +EQUIV 4851 4791 +EQUIV 4852 4792 +EQUIV 4853 4793 +EQUIV 4854 4794 +EQUIV 4855 4795 +EQUIV 4856 4796 +EQUIV 4857 4797 +EQUIV 4858 4798 +EQUIV 4859 4799 +EQUIV 4860 4800 +EQUIV 4861 4781 +EQUIV 4862 4782 +EQUIV 4863 4783 +EQUIV 4864 4784 +EQUIV 4865 4785 +EQUIV 4866 4786 +EQUIV 4867 4787 +EQUIV 4868 4788 +EQUIV 4869 4789 +EQUIV 4870 4790 +EQUIV 4876 3616 +EQUIV 4877 3617 +EQUIV 4878 3618 +EQUIV 4879 3619 +EQUIV 4880 3620 +EQUIV 4881 3621 +EQUIV 4882 3622 +EQUIV 4883 3623 +EQUIV 4884 3624 +EQUIV 4885 3625 +EQUIV 4911 4891 +EQUIV 4912 4892 +EQUIV 4913 4893 +EQUIV 4914 4894 +EQUIV 4915 4895 +EQUIV 4916 4896 +EQUIV 4917 4897 +EQUIV 4918 4898 +EQUIV 4919 4899 +EQUIV 4920 4900 +EQUIV 4921 4901 +EQUIV 4922 4902 +EQUIV 4923 4903 +EQUIV 4924 4904 +EQUIV 4925 4905 +EQUIV 4926 4906 +EQUIV 4927 4907 +EQUIV 4928 4908 +EQUIV 4929 4909 +EQUIV 4930 4910 +EQUIV 4931 4891 +EQUIV 4932 4892 +EQUIV 4933 4893 +EQUIV 4934 4894 +EQUIV 4935 4895 +EQUIV 4936 4556 +EQUIV 4937 4557 +EQUIV 4938 4558 +EQUIV 4939 4559 +EQUIV 4940 4560 +EQUIV 4941 4561 +EQUIV 4942 4562 +EQUIV 4943 4563 +EQUIV 4944 4564 +EQUIV 4945 4565 +EQUIV 4946 4886 +EQUIV 4947 4887 +EQUIV 4948 4888 +EQUIV 4949 4889 +EQUIV 4950 4890 +EQUIV 4961 3621 +EQUIV 4962 3622 +EQUIV 4963 3623 +EQUIV 4964 3624 +EQUIV 4965 3625 +EQUIV 4966 3626 +EQUIV 4967 3627 +EQUIV 4968 3628 +EQUIV 4969 3629 +EQUIV 4970 3630 +EQUIV 4971 3611 +EQUIV 4972 3612 +EQUIV 4973 3613 +EQUIV 4974 3614 +EQUIV 4975 3615 +EQUIV 4976 4576 +EQUIV 4977 4577 +EQUIV 4978 4578 +EQUIV 4979 4579 +EQUIV 4980 4580 +EQUIV 4981 4581 +EQUIV 4982 4582 +EQUIV 4983 4583 +EQUIV 4984 4584 +EQUIV 4985 4585 +EQUIV 4986 4586 +EQUIV 4987 4587 +EQUIV 4988 4588 +EQUIV 4989 4589 +EQUIV 4990 4590 +EQUIV 4991 4591 +EQUIV 4992 4592 +EQUIV 4993 4593 +EQUIV 4994 4594 +EQUIV 4995 4595 +EQUIV 4996 3596 +EQUIV 4997 3597 +EQUIV 4998 3598 +EQUIV 4999 3599 +EQUIV 5000 3600 +EQUIV 5001 3601 +EQUIV 5002 3602 +EQUIV 5003 3603 +EQUIV 5004 3604 +EQUIV 5005 3605 +EQUIV 5006 3606 +EQUIV 5007 3607 +EQUIV 5008 3608 +EQUIV 5009 3609 +EQUIV 5010 3610 +EQUIV 5011 3611 +EQUIV 5012 3612 +EQUIV 5013 3613 +EQUIV 5014 3614 +EQUIV 5015 3615 +EQUIV 5016 4576 +EQUIV 5017 4577 +EQUIV 5018 4578 +EQUIV 5019 4579 +EQUIV 5020 4580 +EQUIV 5021 4581 +EQUIV 5022 4582 +EQUIV 5023 4583 +EQUIV 5024 4584 +EQUIV 5025 4585 +EQUIV 5026 4586 +EQUIV 5027 4587 +EQUIV 5028 4588 +EQUIV 5029 4589 +EQUIV 5030 4590 +EQUIV 5031 4591 +EQUIV 5032 4592 +EQUIV 5033 4593 +EQUIV 5034 4594 +EQUIV 5035 4595 +EQUIV 5036 3596 +EQUIV 5037 3597 +EQUIV 5038 3598 +EQUIV 5039 3599 +EQUIV 5040 3600 +EQUIV 5041 3601 +EQUIV 5042 3602 +EQUIV 5043 3603 +EQUIV 5044 3604 +EQUIV 5045 3605 +EQUIV 5046 4586 +EQUIV 5047 4587 +EQUIV 5048 4588 +EQUIV 5049 4589 +EQUIV 5050 4590 +EQUIV 5051 4591 +EQUIV 5052 4592 +EQUIV 5053 4593 +EQUIV 5054 4594 +EQUIV 5055 4595 +EQUIV 5056 3596 +EQUIV 5057 3597 +EQUIV 5058 3598 +EQUIV 5059 3599 +EQUIV 5060 3600 +EQUIV 5061 3601 +EQUIV 5062 3602 +EQUIV 5063 3603 +EQUIV 5064 3604 +EQUIV 5065 3605 +EQUIV 5066 3606 +EQUIV 5067 3607 +EQUIV 5068 3608 +EQUIV 5069 3609 +EQUIV 5070 3610 +EQUIV 5071 3611 +EQUIV 5072 3612 +EQUIV 5073 3613 +EQUIV 5074 3614 +EQUIV 5075 3615 +EQUIV 5076 3616 +EQUIV 5077 3617 +EQUIV 5078 3618 +EQUIV 5079 3619 +EQUIV 5080 3620 +EQUIV 5091 4791 +EQUIV 5092 4792 +EQUIV 5093 4793 +EQUIV 5094 4794 +EQUIV 5095 4795 +EQUIV 5096 4796 +EQUIV 5097 4797 +EQUIV 5098 4798 +EQUIV 5099 4799 +EQUIV 5100 4800 +EQUIV 5101 4781 +EQUIV 5102 4782 +EQUIV 5103 4783 +EQUIV 5104 4784 +EQUIV 5105 4785 +EQUIV 5106 4786 +EQUIV 5107 4787 +EQUIV 5108 4788 +EQUIV 5109 4789 +EQUIV 5110 4790 +EQUIV 5111 4791 +EQUIV 5112 4792 +EQUIV 5113 4793 +EQUIV 5114 4794 +EQUIV 5115 4795 +EQUIV 5136 4796 +EQUIV 5137 4797 +EQUIV 5138 4798 +EQUIV 5139 4799 +EQUIV 5140 4800 +EQUIV 5141 4781 +EQUIV 5142 4782 +EQUIV 5143 4783 +EQUIV 5144 4784 +EQUIV 5145 4785 +EQUIV 5146 4786 +EQUIV 5147 4787 +EQUIV 5148 4788 +EQUIV 5149 4789 +EQUIV 5150 4790 +EQUIV 5151 4791 +EQUIV 5152 4792 +EQUIV 5153 4793 +EQUIV 5154 4794 +EQUIV 5155 4795 +EQUIV 5156 4796 +EQUIV 5157 4797 +EQUIV 5158 4798 +EQUIV 5159 4799 +EQUIV 5160 4800 +EQUIV 5196 5176 +EQUIV 5197 5177 +EQUIV 5198 5178 +EQUIV 5199 5179 +EQUIV 5200 5180 +EQUIV 5201 5181 +EQUIV 5202 5182 +EQUIV 5203 5183 +EQUIV 5204 5184 +EQUIV 5205 5185 +EQUIV 5206 5186 +EQUIV 5207 5187 +EQUIV 5208 5188 +EQUIV 5209 5189 +EQUIV 5210 5190 +EQUIV 5211 5191 +EQUIV 5212 5192 +EQUIV 5213 5193 +EQUIV 5214 5194 +EQUIV 5215 5195 +EQUIV 5251 5231 +EQUIV 5252 5232 +EQUIV 5253 5233 +EQUIV 5254 5234 +EQUIV 5255 5235 +EQUIV 5261 5221 +EQUIV 5262 5222 +EQUIV 5263 5223 +EQUIV 5264 5224 +EQUIV 5265 5225 +EQUIV 5266 5166 +EQUIV 5267 5167 +EQUIV 5268 5168 +EQUIV 5269 5169 +EQUIV 5270 5170 +EQUIV 5271 5171 +EQUIV 5272 5172 +EQUIV 5273 5173 +EQUIV 5274 5174 +EQUIV 5275 5175 +EQUIV 5276 5216 +EQUIV 5277 5217 +EQUIV 5278 5218 +EQUIV 5279 5219 +EQUIV 5280 5220 +EQUIV 5281 5221 +EQUIV 5282 5222 +EQUIV 5283 5223 +EQUIV 5284 5224 +EQUIV 5285 5225 +EQUIV 5286 5166 +EQUIV 5287 5167 +EQUIV 5288 5168 +EQUIV 5289 5169 +EQUIV 5290 5170 +EQUIV 5291 5171 +EQUIV 5292 5172 +EQUIV 5293 5173 +EQUIV 5294 5174 +EQUIV 5295 5175 +EQUIV 5296 5216 +EQUIV 5297 5217 +EQUIV 5298 5218 +EQUIV 5299 5219 +EQUIV 5300 5220 +EQUIV 5316 5236 +EQUIV 5317 5237 +EQUIV 5318 5238 +EQUIV 5319 5239 +EQUIV 5320 5240 +EQUIV 5321 5241 +EQUIV 5322 5242 +EQUIV 5323 5243 +EQUIV 5324 5244 +EQUIV 5325 5245 +EQUIV 5336 1316 +EQUIV 5337 1317 +EQUIV 5338 1318 +EQUIV 5339 1319 +EQUIV 5340 1320 +EQUIV 5341 1321 +EQUIV 5342 1322 +EQUIV 5343 1323 +EQUIV 5344 1324 +EQUIV 5345 1325 +EQUIV 5346 1366 +EQUIV 5347 1367 +EQUIV 5348 1368 +EQUIV 5349 1369 +EQUIV 5350 1370 +EQUIV 5351 1371 +EQUIV 5352 1372 +EQUIV 5353 1373 +EQUIV 5354 1374 +EQUIV 5355 1375 +EQUIV 5356 1516 +EQUIV 5357 1517 +EQUIV 5358 1518 +EQUIV 5359 1519 +EQUIV 5360 1520 +EQUIV 5361 1321 +EQUIV 5362 1322 +EQUIV 5363 1323 +EQUIV 5364 1324 +EQUIV 5365 1325 +EQUIV 5366 1366 +EQUIV 5367 1367 +EQUIV 5368 1368 +EQUIV 5369 1369 +EQUIV 5370 1370 +EQUIV 5371 1371 +EQUIV 5372 1372 +EQUIV 5373 1373 +EQUIV 5374 1374 +EQUIV 5375 1375 +EQUIV 5376 1516 +EQUIV 5377 1517 +EQUIV 5378 1518 +EQUIV 5379 1519 +EQUIV 5380 1520 +EQUIV 5381 1321 +EQUIV 5382 1322 +EQUIV 5383 1323 +EQUIV 5384 1324 +EQUIV 5385 1325 +EQUIV 5386 1366 +EQUIV 5387 1367 +EQUIV 5388 1368 +EQUIV 5389 1369 +EQUIV 5390 1370 +EQUIV 5391 1371 +EQUIV 5392 1372 +EQUIV 5393 1373 +EQUIV 5394 1374 +EQUIV 5395 1375 +EQUIV 5396 1516 +EQUIV 5397 1517 +EQUIV 5398 1518 +EQUIV 5399 1519 +EQUIV 5400 1520 +EQUIV 5401 1601 +EQUIV 5402 1602 +EQUIV 5403 1603 +EQUIV 5404 1604 +EQUIV 5405 1605 +EQUIV 5406 1306 +EQUIV 5407 1307 +EQUIV 5408 1308 +EQUIV 5409 1309 +EQUIV 5410 1310 +EQUIV 5411 4731 +EQUIV 5412 4732 +EQUIV 5413 4733 +EQUIV 5414 4734 +EQUIV 5415 4735 +EQUIV 5416 2796 +EQUIV 5417 2797 +EQUIV 5418 2798 +EQUIV 5419 2799 +EQUIV 5420 2800 +EQUIV 5421 2801 +EQUIV 5422 2802 +EQUIV 5423 2803 +EQUIV 5424 2804 +EQUIV 5425 2805 +EQUIV 5426 2626 +EQUIV 5427 2627 +EQUIV 5428 2628 +EQUIV 5429 2629 +EQUIV 5430 2630 +EQUIV 5431 2611 +EQUIV 5432 2612 +EQUIV 5433 2613 +EQUIV 5434 2614 +EQUIV 5435 2615 +EQUIV 5436 2616 +EQUIV 5437 2617 +EQUIV 5438 2618 +EQUIV 5439 2619 +EQUIV 5440 2620 +EQUIV 5441 2701 +EQUIV 5442 2702 +EQUIV 5443 2703 +EQUIV 5444 2704 +EQUIV 5445 2705 +EQUIV 5446 2706 +EQUIV 5447 2707 +EQUIV 5448 2708 +EQUIV 5449 2709 +EQUIV 5450 2710 +EQUIV 5451 2711 +EQUIV 5452 2712 +EQUIV 5453 2713 +EQUIV 5454 2714 +EQUIV 5455 2715 +EQUIV 5456 2716 +EQUIV 5457 2717 +EQUIV 5458 2718 +EQUIV 5459 2719 +EQUIV 5460 2720 +EQUIV 5461 2721 +EQUIV 5462 2722 +EQUIV 5463 2723 +EQUIV 5464 2724 +EQUIV 5465 2725 +EQUIV 5466 2726 +EQUIV 5467 2727 +EQUIV 5468 2728 +EQUIV 5469 2729 +EQUIV 5470 2730 +EQUIV 5471 3531 +EQUIV 5472 3532 +EQUIV 5473 3533 +EQUIV 5474 3534 +EQUIV 5475 3535 +EQUIV 5476 3536 +EQUIV 5477 3537 +EQUIV 5478 3538 +EQUIV 5479 3539 +EQUIV 5480 3540 +EQUIV 5481 3541 +EQUIV 5482 3542 +EQUIV 5483 3543 +EQUIV 5484 3544 +EQUIV 5485 3545 +EQUIV 5491 3531 +EQUIV 5492 3532 +EQUIV 5493 3533 +EQUIV 5494 3534 +EQUIV 5495 3535 +EQUIV 5521 4381 +EQUIV 5522 4382 +EQUIV 5523 4383 +EQUIV 5524 4384 +EQUIV 5525 4385 +EQUIV 5531 5511 +EQUIV 5532 5512 +EQUIV 5533 5513 +EQUIV 5534 5514 +EQUIV 5535 5515 +EQUIV 5536 5516 +EQUIV 5537 5517 +EQUIV 5538 5518 +EQUIV 5539 5519 +EQUIV 5540 5520 +EQUIV 5541 4401 +EQUIV 5542 4402 +EQUIV 5543 4403 +EQUIV 5544 4404 +EQUIV 5545 4405 +EQUIV 5556 5516 +EQUIV 5557 5517 +EQUIV 5558 5518 +EQUIV 5559 5519 +EQUIV 5560 5520 +EQUIV 5561 4381 +EQUIV 5562 4382 +EQUIV 5563 4383 +EQUIV 5564 4384 +EQUIV 5565 4385 +EQUIV 5566 5526 +EQUIV 5567 5527 +EQUIV 5568 5528 +EQUIV 5569 5529 +EQUIV 5570 5530 +EQUIV 5571 5511 +EQUIV 5572 5512 +EQUIV 5573 5513 +EQUIV 5574 5514 +EQUIV 5575 5515 +EQUIV 5591 5551 +EQUIV 5592 5552 +EQUIV 5593 5553 +EQUIV 5594 5554 +EQUIV 5595 5555 +EQUIV 5596 5516 +EQUIV 5597 5517 +EQUIV 5598 5518 +EQUIV 5599 5519 +EQUIV 5600 5520 +EQUIV 5601 4381 +EQUIV 5602 4382 +EQUIV 5603 4383 +EQUIV 5604 4384 +EQUIV 5605 4385 +EQUIV 5606 5526 +EQUIV 5607 5527 +EQUIV 5608 5528 +EQUIV 5609 5529 +EQUIV 5610 5530 +EQUIV 5611 5511 +EQUIV 5612 5512 +EQUIV 5613 5513 +EQUIV 5614 5514 +EQUIV 5615 5515 +EQUIV 5616 5576 +EQUIV 5617 5577 +EQUIV 5618 5578 +EQUIV 5619 5579 +EQUIV 5620 5580 +EQUIV 5621 5581 +EQUIV 5622 5582 +EQUIV 5623 5583 +EQUIV 5624 5584 +EQUIV 5625 5585 +EQUIV 5666 5646 +EQUIV 5667 5647 +EQUIV 5668 5648 +EQUIV 5669 5649 +EQUIV 5670 5650 +EQUIV 5676 5636 +EQUIV 5677 5637 +EQUIV 5678 5638 +EQUIV 5679 5639 +EQUIV 5680 5640 +EQUIV 5691 5631 +EQUIV 5692 5632 +EQUIV 5693 5633 +EQUIV 5694 5634 +EQUIV 5695 5635 +EQUIV 5696 5636 +EQUIV 5697 5637 +EQUIV 5698 5638 +EQUIV 5699 5639 +EQUIV 5700 5640 +EQUIV 5701 5681 +EQUIV 5702 5682 +EQUIV 5703 5683 +EQUIV 5704 5684 +EQUIV 5705 5685 +EQUIV 5706 5686 +EQUIV 5707 5687 +EQUIV 5708 5688 +EQUIV 5709 5689 +EQUIV 5710 5690 +EQUIV 5711 5631 +EQUIV 5712 5632 +EQUIV 5713 5633 +EQUIV 5714 5634 +EQUIV 5715 5635 +EQUIV 5716 5636 +EQUIV 5717 5637 +EQUIV 5718 5638 +EQUIV 5719 5639 +EQUIV 5720 5640 +EQUIV 5721 5681 +EQUIV 5722 5682 +EQUIV 5723 5683 +EQUIV 5724 5684 +EQUIV 5725 5685 +EQUIV 5746 5686 +EQUIV 5747 5687 +EQUIV 5748 5688 +EQUIV 5749 5689 +EQUIV 5750 5690 +EQUIV 5751 5631 +EQUIV 5752 5632 +EQUIV 5753 5633 +EQUIV 5754 5634 +EQUIV 5755 5635 +EQUIV 5771 5651 +EQUIV 5772 5652 +EQUIV 5773 5653 +EQUIV 5774 5654 +EQUIV 5775 5655 +EQUIV 5776 5656 +EQUIV 5777 5657 +EQUIV 5778 5658 +EQUIV 5779 5659 +EQUIV 5780 5660 +EQUIV 5781 1101 +EQUIV 5782 1102 +EQUIV 5783 1103 +EQUIV 5784 1104 +EQUIV 5785 1105 +EQUIV 5786 1106 +EQUIV 5787 1107 +EQUIV 5788 1108 +EQUIV 5789 1109 +EQUIV 5790 1110 +EQUIV 5791 1111 +EQUIV 5792 1112 +EQUIV 5793 1113 +EQUIV 5794 1114 +EQUIV 5795 1115 +EQUIV 5796 1096 +EQUIV 5797 1097 +EQUIV 5798 1098 +EQUIV 5799 1099 +EQUIV 5800 1100 +EQUIV 5801 1101 +EQUIV 5802 1102 +EQUIV 5803 1103 +EQUIV 5804 1104 +EQUIV 5805 1105 +EQUIV 5806 1106 +EQUIV 5807 1107 +EQUIV 5808 1108 +EQUIV 5809 1109 +EQUIV 5810 1110 +EQUIV 5811 1151 +EQUIV 5812 1152 +EQUIV 5813 1153 +EQUIV 5814 1154 +EQUIV 5815 1155 +EQUIV 5816 1156 +EQUIV 5817 1157 +EQUIV 5818 1158 +EQUIV 5819 1159 +EQUIV 5820 1160 +EQUIV 5821 1161 +EQUIV 5822 1162 +EQUIV 5823 1163 +EQUIV 5824 1164 +EQUIV 5825 1165 +EQUIV 5826 1166 +EQUIV 5827 1167 +EQUIV 5828 1168 +EQUIV 5829 1169 +EQUIV 5830 1170 +EQUIV 5831 1151 +EQUIV 5832 1152 +EQUIV 5833 1153 +EQUIV 5834 1154 +EQUIV 5835 1155 +EQUIV 5836 1156 +EQUIV 5837 1157 +EQUIV 5838 1158 +EQUIV 5839 1159 +EQUIV 5840 1160 +EQUIV 5841 1161 +EQUIV 5842 1162 +EQUIV 5843 1163 +EQUIV 5844 1164 +EQUIV 5845 1165 +EQUIV 5846 1166 +EQUIV 5847 1167 +EQUIV 5848 1168 +EQUIV 5849 1169 +EQUIV 5850 1170 +EQUIV 5851 1111 +EQUIV 5852 1112 +EQUIV 5853 1113 +EQUIV 5854 1114 +EQUIV 5855 1115 +EQUIV 5856 3056 +EQUIV 5857 3057 +EQUIV 5858 3058 +EQUIV 5859 3059 +EQUIV 5860 3060 +EQUIV 5861 1081 +EQUIV 5862 1082 +EQUIV 5863 1083 +EQUIV 5864 1084 +EQUIV 5865 1085 +EQUIV 5866 1086 +EQUIV 5867 1087 +EQUIV 5868 1088 +EQUIV 5869 1089 +EQUIV 5870 1090 +EQUIV 5871 1091 +EQUIV 5872 1092 +EQUIV 5873 1093 +EQUIV 5874 1094 +EQUIV 5875 1095 +EQUIV 5876 3056 +EQUIV 5877 3057 +EQUIV 5878 3058 +EQUIV 5879 3059 +EQUIV 5880 3060 +EQUIV 5881 3061 +EQUIV 5882 3062 +EQUIV 5883 3063 +EQUIV 5884 3064 +EQUIV 5885 3065 +EQUIV 5886 3066 +EQUIV 5887 3067 +EQUIV 5888 3068 +EQUIV 5889 3069 +EQUIV 5890 3070 +EQUIV 5891 3391 +EQUIV 5892 3392 +EQUIV 5893 3393 +EQUIV 5894 3394 +EQUIV 5895 3395 +EQUIV 5896 916 +EQUIV 5897 917 +EQUIV 5898 918 +EQUIV 5899 919 +EQUIV 5900 920 +EQUIV 5901 681 +EQUIV 5902 682 +EQUIV 5903 683 +EQUIV 5904 684 +EQUIV 5905 685 +EQUIV 5921 621 +EQUIV 5922 622 +EQUIV 5923 623 +EQUIV 5924 624 +EQUIV 5925 625 +EQUIV 5931 5911 +EQUIV 5932 5912 +EQUIV 5933 5913 +EQUIV 5934 5914 +EQUIV 5935 5915 +EQUIV 5941 881 +EQUIV 5942 882 +EQUIV 5943 883 +EQUIV 5944 884 +EQUIV 5945 885 +EQUIV 5946 686 +EQUIV 5947 687 +EQUIV 5948 688 +EQUIV 5949 689 +EQUIV 5950 690 +EQUIV 5951 691 +EQUIV 5952 692 +EQUIV 5953 693 +EQUIV 5954 694 +EQUIV 5955 695 +EQUIV 5956 876 +EQUIV 5957 877 +EQUIV 5958 878 +EQUIV 5959 879 +EQUIV 5960 880 +EQUIV 5961 881 +EQUIV 5962 882 +EQUIV 5963 883 +EQUIV 5964 884 +EQUIV 5965 885 +EQUIV 5966 686 +EQUIV 5967 687 +EQUIV 5968 688 +EQUIV 5969 689 +EQUIV 5970 690 +EQUIV 5971 691 +EQUIV 5972 692 +EQUIV 5973 693 +EQUIV 5974 694 +EQUIV 5975 695 +EQUIV 5976 876 +EQUIV 5977 877 +EQUIV 5978 878 +EQUIV 5979 879 +EQUIV 5980 880 +EQUIV 5981 881 +EQUIV 5982 882 +EQUIV 5983 883 +EQUIV 5984 884 +EQUIV 5985 885 +EQUIV 5986 686 +EQUIV 5987 687 +EQUIV 5988 688 +EQUIV 5989 689 +EQUIV 5990 690 +EQUIV 5991 691 +EQUIV 5992 692 +EQUIV 5993 693 +EQUIV 5994 694 +EQUIV 5995 695 +EQUIV 5996 876 +EQUIV 5997 877 +EQUIV 5998 878 +EQUIV 5999 879 +EQUIV 6000 880 +EQUIV 6016 5916 +EQUIV 6017 5917 +EQUIV 6018 5918 +EQUIV 6019 5919 +EQUIV 6020 5920 +EQUIV 6046 606 +EQUIV 6047 607 +EQUIV 6048 608 +EQUIV 6049 609 +EQUIV 6050 610 +EQUIV 6051 6031 +EQUIV 6052 6032 +EQUIV 6053 6033 +EQUIV 6054 6034 +EQUIV 6055 6035 +EQUIV 6056 6036 +EQUIV 6057 6037 +EQUIV 6058 6038 +EQUIV 6059 6039 +EQUIV 6060 6040 +EQUIV 6061 6041 +EQUIV 6062 6042 +EQUIV 6063 6043 +EQUIV 6064 6044 +EQUIV 6065 6045 +EQUIV 6066 606 +EQUIV 6067 607 +EQUIV 6068 608 +EQUIV 6069 609 +EQUIV 6070 610 +EQUIV 6071 6031 +EQUIV 6072 6032 +EQUIV 6073 6033 +EQUIV 6074 6034 +EQUIV 6075 6035 +EQUIV 6076 6036 +EQUIV 6077 6037 +EQUIV 6078 6038 +EQUIV 6079 6039 +EQUIV 6080 6040 +EQUIV 6081 6041 +EQUIV 6082 6042 +EQUIV 6083 6043 +EQUIV 6084 6044 +EQUIV 6085 6045 +EQUIV 6086 606 +EQUIV 6087 607 +EQUIV 6088 608 +EQUIV 6089 609 +EQUIV 6090 610 +EQUIV 6091 6031 +EQUIV 6092 6032 +EQUIV 6093 6033 +EQUIV 6094 6034 +EQUIV 6095 6035 +EQUIV 6096 6036 +EQUIV 6097 6037 +EQUIV 6098 6038 +EQUIV 6099 6039 +EQUIV 6100 6040 +EQUIV 6141 561 +EQUIV 6142 562 +EQUIV 6143 563 +EQUIV 6144 564 +EQUIV 6145 565 +EQUIV 6146 566 +EQUIV 6147 567 +EQUIV 6148 568 +EQUIV 6149 569 +EQUIV 6150 570 +EQUIV 6151 571 +EQUIV 6152 572 +EQUIV 6153 573 +EQUIV 6154 574 +EQUIV 6155 575 +EQUIV 6156 576 +EQUIV 6157 577 +EQUIV 6158 578 +EQUIV 6159 579 +EQUIV 6160 580 +EQUIV 6171 6111 +EQUIV 6172 6112 +EQUIV 6173 6113 +EQUIV 6174 6114 +EQUIV 6175 6115 +EQUIV 6176 6116 +EQUIV 6177 6117 +EQUIV 6178 6118 +EQUIV 6179 6119 +EQUIV 6180 6120 +EQUIV 6181 6121 +EQUIV 6182 6122 +EQUIV 6183 6123 +EQUIV 6184 6124 +EQUIV 6185 6125 +EQUIV 6186 6166 +EQUIV 6187 6167 +EQUIV 6188 6168 +EQUIV 6189 6169 +EQUIV 6190 6170 +EQUIV 6201 6101 +EQUIV 6202 6102 +EQUIV 6203 6103 +EQUIV 6204 6104 +EQUIV 6205 6105 +EQUIV 6206 6106 +EQUIV 6207 6107 +EQUIV 6208 6108 +EQUIV 6209 6109 +EQUIV 6210 6110 +EQUIV 6211 6191 +EQUIV 6212 6192 +EQUIV 6213 6193 +EQUIV 6214 6194 +EQUIV 6215 6195 +EQUIV 6216 6196 +EQUIV 6217 6197 +EQUIV 6218 6198 +EQUIV 6219 6199 +EQUIV 6220 6200 +EQUIV 6221 6041 +EQUIV 6222 6042 +EQUIV 6223 6043 +EQUIV 6224 6044 +EQUIV 6225 6045 +EQUIV 6231 591 +EQUIV 6232 592 +EQUIV 6233 593 +EQUIV 6234 594 +EQUIV 6235 595 +EQUIV 6236 596 +EQUIV 6237 597 +EQUIV 6238 598 +EQUIV 6239 599 +EQUIV 6240 600 +EQUIV 6241 601 +EQUIV 6242 602 +EQUIV 6243 603 +EQUIV 6244 604 +EQUIV 6245 605 +EQUIV 6246 606 +EQUIV 6247 607 +EQUIV 6248 608 +EQUIV 6249 609 +EQUIV 6250 610 +EQUIV 6251 6031 +EQUIV 6252 6032 +EQUIV 6253 6033 +EQUIV 6254 6034 +EQUIV 6255 6035 +EQUIV 6256 6036 +EQUIV 6257 6037 +EQUIV 6258 6038 +EQUIV 6259 6039 +EQUIV 6260 6040 +EQUIV 6261 6041 +EQUIV 6262 6042 +EQUIV 6263 6043 +EQUIV 6264 6044 +EQUIV 6265 6045 +EQUIV 6266 6226 +EQUIV 6267 6227 +EQUIV 6268 6228 +EQUIV 6269 6229 +EQUIV 6270 6230 +EQUIV 6271 591 +EQUIV 6272 592 +EQUIV 6273 593 +EQUIV 6274 594 +EQUIV 6275 595 +EQUIV 6316 6276 +EQUIV 6317 6277 +EQUIV 6318 6278 +EQUIV 6319 6279 +EQUIV 6320 6280 +EQUIV 6321 6281 +EQUIV 6322 6282 +EQUIV 6323 6283 +EQUIV 6324 6284 +EQUIV 6325 6285 +EQUIV 6326 6286 +EQUIV 6327 6287 +EQUIV 6328 6288 +EQUIV 6329 6289 +EQUIV 6330 6290 +EQUIV 6391 6331 +EQUIV 6392 6332 +EQUIV 6393 6333 +EQUIV 6394 6334 +EQUIV 6395 6335 +EQUIV 6396 576 +EQUIV 6397 577 +EQUIV 6398 578 +EQUIV 6399 579 +EQUIV 6400 580 +EQUIV 6401 581 +EQUIV 6402 582 +EQUIV 6403 583 +EQUIV 6404 584 +EQUIV 6405 585 +EQUIV 6406 6286 +EQUIV 6407 6287 +EQUIV 6408 6288 +EQUIV 6409 6289 +EQUIV 6410 6290 +EQUIV 6411 6291 +EQUIV 6412 6292 +EQUIV 6413 6293 +EQUIV 6414 6294 +EQUIV 6415 6295 +EQUIV 6436 6416 +EQUIV 6437 6417 +EQUIV 6438 6418 +EQUIV 6439 6419 +EQUIV 6440 6420 +EQUIV 6441 6421 +EQUIV 6442 6422 +EQUIV 6443 6423 +EQUIV 6444 6424 +EQUIV 6445 6425 +EQUIV 6446 6426 +EQUIV 6447 6427 +EQUIV 6448 6428 +EQUIV 6449 6429 +EQUIV 6450 6430 +EQUIV 6451 6431 +EQUIV 6452 6432 +EQUIV 6453 6433 +EQUIV 6454 6434 +EQUIV 6455 6435 +EQUIV 6456 6416 +EQUIV 6457 6417 +EQUIV 6458 6418 +EQUIV 6459 6419 +EQUIV 6460 6420 +EQUIV 6461 6421 +EQUIV 6462 6422 +EQUIV 6463 6423 +EQUIV 6464 6424 +EQUIV 6465 6425 +EQUIV 6466 6426 +EQUIV 6467 6427 +EQUIV 6468 6428 +EQUIV 6469 6429 +EQUIV 6470 6430 +EQUIV 6491 6471 +EQUIV 6492 6472 +EQUIV 6493 6473 +EQUIV 6494 6474 +EQUIV 6495 6475 +EQUIV 6496 6476 +EQUIV 6497 6477 +EQUIV 6498 6478 +EQUIV 6499 6479 +EQUIV 6500 6480 +EQUIV 6501 6481 +EQUIV 6502 6482 +EQUIV 6503 6483 +EQUIV 6504 6484 +EQUIV 6505 6485 +EQUIV 6506 6486 +EQUIV 6507 6487 +EQUIV 6508 6488 +EQUIV 6509 6489 +EQUIV 6510 6490 +EQUIV 6511 6471 +EQUIV 6512 6472 +EQUIV 6513 6473 +EQUIV 6514 6474 +EQUIV 6515 6475 +EQUIV 6566 6546 +EQUIV 6567 6547 +EQUIV 6568 6548 +EQUIV 6569 6549 +EQUIV 6570 6550 +EQUIV 6571 6551 +EQUIV 6572 6552 +EQUIV 6573 6553 +EQUIV 6574 6554 +EQUIV 6575 6555 +EQUIV 6576 6556 +EQUIV 6577 6557 +EQUIV 6578 6558 +EQUIV 6579 6559 +EQUIV 6580 6560 +EQUIV 6581 6561 +EQUIV 6582 6562 +EQUIV 6583 6563 +EQUIV 6584 6564 +EQUIV 6585 6565 +EQUIV 6586 6546 +EQUIV 6587 6547 +EQUIV 6588 6548 +EQUIV 6589 6549 +EQUIV 6590 6550 +EQUIV 6631 6591 +EQUIV 6632 6592 +EQUIV 6633 6593 +EQUIV 6634 6594 +EQUIV 6635 6595 +EQUIV 6636 6596 +EQUIV 6637 6597 +EQUIV 6638 6598 +EQUIV 6639 6599 +EQUIV 6640 6600 +EQUIV 6641 6621 +EQUIV 6642 6622 +EQUIV 6643 6623 +EQUIV 6644 6624 +EQUIV 6645 6625 +EQUIV 6646 6626 +EQUIV 6647 6627 +EQUIV 6648 6628 +EQUIV 6649 6629 +EQUIV 6650 6630 +EQUIV 6651 6591 +EQUIV 6652 6592 +EQUIV 6653 6593 +EQUIV 6654 6594 +EQUIV 6655 6595 +EQUIV 6656 6536 +EQUIV 6657 6537 +EQUIV 6658 6538 +EQUIV 6659 6539 +EQUIV 6660 6540 +EQUIV 6666 6526 +EQUIV 6667 6527 +EQUIV 6668 6528 +EQUIV 6669 6529 +EQUIV 6670 6530 +EQUIV 6671 6531 +EQUIV 6672 6532 +EQUIV 6673 6533 +EQUIV 6674 6534 +EQUIV 6675 6535 +EQUIV 6676 6596 +EQUIV 6677 6597 +EQUIV 6678 6598 +EQUIV 6679 6599 +EQUIV 6680 6600 +EQUIV 6681 6621 +EQUIV 6682 6622 +EQUIV 6683 6623 +EQUIV 6684 6624 +EQUIV 6685 6625 +EQUIV 6686 6626 +EQUIV 6687 6627 +EQUIV 6688 6628 +EQUIV 6689 6629 +EQUIV 6690 6630 +EQUIV 6691 6551 +EQUIV 6692 6552 +EQUIV 6693 6553 +EQUIV 6694 6554 +EQUIV 6695 6555 +EQUIV 6736 6716 +EQUIV 6737 6717 +EQUIV 6738 6718 +EQUIV 6739 6719 +EQUIV 6740 6720 +EQUIV 6786 6766 +EQUIV 6787 6767 +EQUIV 6788 6768 +EQUIV 6789 6769 +EQUIV 6790 6770 +EQUIV 6791 6771 +EQUIV 6792 6772 +EQUIV 6793 6773 +EQUIV 6794 6774 +EQUIV 6795 6775 +EQUIV 6796 6776 +EQUIV 6797 6777 +EQUIV 6798 6778 +EQUIV 6799 6779 +EQUIV 6800 6780 +EQUIV 6821 6801 +EQUIV 6822 6802 +EQUIV 6823 6803 +EQUIV 6824 6804 +EQUIV 6825 6805 +EQUIV 6826 6806 +EQUIV 6827 6807 +EQUIV 6828 6808 +EQUIV 6829 6809 +EQUIV 6830 6810 +EQUIV 6831 6811 +EQUIV 6832 6812 +EQUIV 6833 6813 +EQUIV 6834 6814 +EQUIV 6835 6815 +EQUIV 6841 6741 +EQUIV 6842 6742 +EQUIV 6843 6743 +EQUIV 6844 6744 +EQUIV 6845 6745 +EQUIV 6846 6746 +EQUIV 6847 6747 +EQUIV 6848 6748 +EQUIV 6849 6749 +EQUIV 6850 6750 +EQUIV 6856 6816 +EQUIV 6857 6817 +EQUIV 6858 6818 +EQUIV 6859 6819 +EQUIV 6860 6820 +EQUIV 6861 6801 +EQUIV 6862 6802 +EQUIV 6863 6803 +EQUIV 6864 6804 +EQUIV 6865 6805 +EQUIV 6906 6866 +EQUIV 6907 6867 +EQUIV 6908 6868 +EQUIV 6909 6869 +EQUIV 6910 6870 +EQUIV 6911 6891 +EQUIV 6912 6892 +EQUIV 6913 6893 +EQUIV 6914 6894 +EQUIV 6915 6895 +EQUIV 6956 6916 +EQUIV 6957 6917 +EQUIV 6958 6918 +EQUIV 6959 6919 +EQUIV 6960 6920 +EQUIV 6966 6886 +EQUIV 6967 6887 +EQUIV 6968 6888 +EQUIV 6969 6889 +EQUIV 6970 6890 +EQUIV 6971 6871 +EQUIV 6972 6872 +EQUIV 6973 6873 +EQUIV 6974 6874 +EQUIV 6975 6875 +EQUIV 6976 6876 +EQUIV 6977 6877 +EQUIV 6978 6878 +EQUIV 6979 6879 +EQUIV 6980 6880 +EQUIV 7016 6996 +EQUIV 7017 6997 +EQUIV 7018 6998 +EQUIV 7019 6999 +EQUIV 7020 7000 +EQUIV 7021 7001 +EQUIV 7022 7002 +EQUIV 7023 7003 +EQUIV 7024 7004 +EQUIV 7025 7005 +EQUIV 7026 7006 +EQUIV 7027 7007 +EQUIV 7028 7008 +EQUIV 7029 7009 +EQUIV 7030 7010 +EQUIV 7031 7011 +EQUIV 7032 7012 +EQUIV 7033 7013 +EQUIV 7034 7014 +EQUIV 7035 7015 +EQUIV 7036 6996 +EQUIV 7037 6997 +EQUIV 7038 6998 +EQUIV 7039 6999 +EQUIV 7040 7000 +EQUIV 7041 7001 +EQUIV 7042 7002 +EQUIV 7043 7003 +EQUIV 7044 7004 +EQUIV 7045 7005 +EQUIV 7046 7006 +EQUIV 7047 7007 +EQUIV 7048 7008 +EQUIV 7049 7009 +EQUIV 7050 7010 +EQUIV 7101 7061 +EQUIV 7102 7062 +EQUIV 7103 7063 +EQUIV 7104 7064 +EQUIV 7105 7065 +EQUIV 7126 7106 +EQUIV 7127 7107 +EQUIV 7128 7108 +EQUIV 7129 7109 +EQUIV 7130 7110 +EQUIV 7131 7111 +EQUIV 7132 7112 +EQUIV 7133 7113 +EQUIV 7134 7114 +EQUIV 7135 7115 +EQUIV 7136 7116 +EQUIV 7137 7117 +EQUIV 7138 7118 +EQUIV 7139 7119 +EQUIV 7140 7120 +EQUIV 7161 7141 +EQUIV 7162 7142 +EQUIV 7163 7143 +EQUIV 7164 7144 +EQUIV 7165 7145 +EQUIV 7221 7201 +EQUIV 7222 7202 +EQUIV 7223 7203 +EQUIV 7224 7204 +EQUIV 7225 7205 +EQUIV 7251 7111 +EQUIV 7252 7112 +EQUIV 7253 7113 +EQUIV 7254 7114 +EQUIV 7255 7115 +EQUIV 7256 7116 +EQUIV 7257 7117 +EQUIV 7258 7118 +EQUIV 7259 7119 +EQUIV 7260 7120 +EQUIV 7261 7121 +EQUIV 7262 7122 +EQUIV 7263 7123 +EQUIV 7264 7124 +EQUIV 7265 7125 +EQUIV 7266 7106 +EQUIV 7267 7107 +EQUIV 7268 7108 +EQUIV 7269 7109 +EQUIV 7270 7110 +EQUIV 7271 7111 +EQUIV 7272 7112 +EQUIV 7273 7113 +EQUIV 7274 7114 +EQUIV 7275 7115 +EQUIV 7276 7176 +EQUIV 7277 7177 +EQUIV 7278 7178 +EQUIV 7279 7179 +EQUIV 7280 7180 +EQUIV 7281 7181 +EQUIV 7282 7182 +EQUIV 7283 7183 +EQUIV 7284 7184 +EQUIV 7285 7185 +EQUIV 7291 7171 +EQUIV 7292 7172 +EQUIV 7293 7173 +EQUIV 7294 7174 +EQUIV 7295 7175 +EQUIV 7296 7176 +EQUIV 7297 7177 +EQUIV 7298 7178 +EQUIV 7299 7179 +EQUIV 7300 7180 +EQUIV 7301 7181 +EQUIV 7302 7182 +EQUIV 7303 7183 +EQUIV 7304 7184 +EQUIV 7305 7185 +EQUIV 7306 7286 +EQUIV 7307 7287 +EQUIV 7308 7288 +EQUIV 7309 7289 +EQUIV 7310 7290 +EQUIV 7311 7171 +EQUIV 7312 7172 +EQUIV 7313 7173 +EQUIV 7314 7174 +EQUIV 7315 7175 +EQUIV 7316 7176 +EQUIV 7317 7177 +EQUIV 7318 7178 +EQUIV 7319 7179 +EQUIV 7320 7180 +EQUIV 7321 7181 +EQUIV 7322 7182 +EQUIV 7323 7183 +EQUIV 7324 7184 +EQUIV 7325 7185 +EQUIV 7326 7286 +EQUIV 7327 7287 +EQUIV 7328 7288 +EQUIV 7329 7289 +EQUIV 7330 7290 +EQUIV 7331 7171 +EQUIV 7332 7172 +EQUIV 7333 7173 +EQUIV 7334 7174 +EQUIV 7335 7175 +EQUIV 7336 7176 +EQUIV 7337 7177 +EQUIV 7338 7178 +EQUIV 7339 7179 +EQUIV 7340 7180 +EQUIV 7341 7181 +EQUIV 7342 7182 +EQUIV 7343 7183 +EQUIV 7344 7184 +EQUIV 7345 7185 +EQUIV 7346 7286 +EQUIV 7347 7287 +EQUIV 7348 7288 +EQUIV 7349 7289 +EQUIV 7350 7290 +EQUIV 7351 7171 +EQUIV 7352 7172 +EQUIV 7353 7173 +EQUIV 7354 7174 +EQUIV 7355 7175 +EQUIV 7356 7176 +EQUIV 7357 7177 +EQUIV 7358 7178 +EQUIV 7359 7179 +EQUIV 7360 7180 +EQUIV 7361 7181 +EQUIV 7362 7182 +EQUIV 7363 7183 +EQUIV 7364 7184 +EQUIV 7365 7185 +EQUIV 7366 7186 +EQUIV 7367 7187 +EQUIV 7368 7188 +EQUIV 7369 7189 +EQUIV 7370 7190 +EQUIV 7406 7146 +EQUIV 7407 7147 +EQUIV 7408 7148 +EQUIV 7409 7149 +EQUIV 7410 7150 +EQUIV 7411 7151 +EQUIV 7412 7152 +EQUIV 7413 7153 +EQUIV 7414 7154 +EQUIV 7415 7155 +EQUIV 7416 7156 +EQUIV 7417 7157 +EQUIV 7418 7158 +EQUIV 7419 7159 +EQUIV 7420 7160 +EQUIV 7421 7121 +EQUIV 7422 7122 +EQUIV 7423 7123 +EQUIV 7424 7124 +EQUIV 7425 7125 +EQUIV 7426 7106 +EQUIV 7427 7107 +EQUIV 7428 7108 +EQUIV 7429 7109 +EQUIV 7430 7110 +EQUIV 7431 7111 +EQUIV 7432 7112 +EQUIV 7433 7113 +EQUIV 7434 7114 +EQUIV 7435 7115 +EQUIV 7436 7116 +EQUIV 7437 7117 +EQUIV 7438 7118 +EQUIV 7439 7119 +EQUIV 7440 7120 +EQUIV 7441 7141 +EQUIV 7442 7142 +EQUIV 7443 7143 +EQUIV 7444 7144 +EQUIV 7445 7145 +EQUIV 7446 7166 +EQUIV 7447 7167 +EQUIV 7448 7168 +EQUIV 7449 7169 +EQUIV 7450 7170 +EQUIV 7461 7381 +EQUIV 7462 7382 +EQUIV 7463 7383 +EQUIV 7464 7384 +EQUIV 7465 7385 +EQUIV 7466 7386 +EQUIV 7467 7387 +EQUIV 7468 7388 +EQUIV 7469 7389 +EQUIV 7470 7390 +EQUIV 7471 7391 +EQUIV 7472 7392 +EQUIV 7473 7393 +EQUIV 7474 7394 +EQUIV 7475 7395 +EQUIV 7476 7396 +EQUIV 7477 7397 +EQUIV 7478 7398 +EQUIV 7479 7399 +EQUIV 7480 7400 +EQUIV 7501 7401 +EQUIV 7502 7402 +EQUIV 7503 7403 +EQUIV 7504 7404 +EQUIV 7505 7405 +EQUIV 7506 7166 +EQUIV 7507 7167 +EQUIV 7508 7168 +EQUIV 7509 7169 +EQUIV 7510 7170 +EQUIV 7511 7451 +EQUIV 7512 7452 +EQUIV 7513 7453 +EQUIV 7514 7454 +EQUIV 7515 7455 +EQUIV 7516 7456 +EQUIV 7517 7457 +EQUIV 7518 7458 +EQUIV 7519 7459 +EQUIV 7520 7460 +EQUIV 7526 7286 +EQUIV 7527 7287 +EQUIV 7528 7288 +EQUIV 7529 7289 +EQUIV 7530 7290 +EQUIV 7531 7451 +EQUIV 7532 7452 +EQUIV 7533 7453 +EQUIV 7534 7454 +EQUIV 7535 7455 +EQUIV 7536 7456 +EQUIV 7537 7457 +EQUIV 7538 7458 +EQUIV 7539 7459 +EQUIV 7540 7460 +EQUIV 7541 7381 +EQUIV 7542 7382 +EQUIV 7543 7383 +EQUIV 7544 7384 +EQUIV 7545 7385 +EQUIV 7546 7386 +EQUIV 7547 7387 +EQUIV 7548 7388 +EQUIV 7549 7389 +EQUIV 7550 7390 +EQUIV 7551 7391 +EQUIV 7552 7392 +EQUIV 7553 7393 +EQUIV 7554 7394 +EQUIV 7555 7395 +EQUIV 7556 7456 +EQUIV 7557 7457 +EQUIV 7558 7458 +EQUIV 7559 7459 +EQUIV 7560 7460 +EQUIV 7561 7381 +EQUIV 7562 7382 +EQUIV 7563 7383 +EQUIV 7564 7384 +EQUIV 7565 7385 +EQUIV 7566 7386 +EQUIV 7567 7387 +EQUIV 7568 7388 +EQUIV 7569 7389 +EQUIV 7570 7390 +EQUIV 7571 7391 +EQUIV 7572 7392 +EQUIV 7573 7393 +EQUIV 7574 7394 +EQUIV 7575 7395 +EQUIV 7576 7456 +EQUIV 7577 7457 +EQUIV 7578 7458 +EQUIV 7579 7459 +EQUIV 7580 7460 +EQUIV 7581 7381 +EQUIV 7582 7382 +EQUIV 7583 7383 +EQUIV 7584 7384 +EQUIV 7585 7385 +EQUIV 7621 7601 +EQUIV 7622 7602 +EQUIV 7623 7603 +EQUIV 7624 7604 +EQUIV 7625 7605 +EQUIV 7631 7371 +EQUIV 7632 7372 +EQUIV 7633 7373 +EQUIV 7634 7374 +EQUIV 7635 7375 +EQUIV 7636 7596 +EQUIV 7637 7597 +EQUIV 7638 7598 +EQUIV 7639 7599 +EQUIV 7640 7600 +EQUIV 7661 6361 +EQUIV 7662 6362 +EQUIV 7663 6363 +EQUIV 7664 6364 +EQUIV 7665 6365 +EQUIV 7666 6366 +EQUIV 7667 6367 +EQUIV 7668 6368 +EQUIV 7669 6369 +EQUIV 7670 6370 +EQUIV 7671 6371 +EQUIV 7672 6372 +EQUIV 7673 6373 +EQUIV 7674 6374 +EQUIV 7675 6375 +EQUIV 7676 6356 +EQUIV 7677 6357 +EQUIV 7678 6358 +EQUIV 7679 6359 +EQUIV 7680 6360 +EQUIV 7681 6361 +EQUIV 7682 6362 +EQUIV 7683 6363 +EQUIV 7684 6364 +EQUIV 7685 6365 +EQUIV 7686 6366 +EQUIV 7687 6367 +EQUIV 7688 6368 +EQUIV 7689 6369 +EQUIV 7690 6370 +EQUIV 7716 7696 +EQUIV 7717 7697 +EQUIV 7718 7698 +EQUIV 7719 7699 +EQUIV 7720 7700 +EQUIV 7721 7701 +EQUIV 7722 7702 +EQUIV 7723 7703 +EQUIV 7724 7704 +EQUIV 7725 7705 +EQUIV 7736 7216 +EQUIV 7737 7217 +EQUIV 7738 7218 +EQUIV 7739 7219 +EQUIV 7740 7220 +EQUIV 7741 7201 +EQUIV 7742 7202 +EQUIV 7743 7203 +EQUIV 7744 7204 +EQUIV 7745 7205 +EQUIV 7746 7226 +EQUIV 7747 7227 +EQUIV 7748 7228 +EQUIV 7749 7229 +EQUIV 7750 7230 +EQUIV 7751 7231 +EQUIV 7752 7232 +EQUIV 7753 7233 +EQUIV 7754 7234 +EQUIV 7755 7235 +EQUIV 7756 7236 +EQUIV 7757 7237 +EQUIV 7758 7238 +EQUIV 7759 7239 +EQUIV 7760 7240 +EQUIV 7766 7006 +EQUIV 7767 7007 +EQUIV 7768 7008 +EQUIV 7769 7009 +EQUIV 7770 7010 +EQUIV 7771 7011 +EQUIV 7772 7012 +EQUIV 7773 7013 +EQUIV 7774 7014 +EQUIV 7775 7015 +EQUIV 7776 6996 +EQUIV 7777 6997 +EQUIV 7778 6998 +EQUIV 7779 6999 +EQUIV 7780 7000 +EQUIV 7781 7001 +EQUIV 7782 7002 +EQUIV 7783 7003 +EQUIV 7784 7004 +EQUIV 7785 7005 +EQUIV 7786 7006 +EQUIV 7787 7007 +EQUIV 7788 7008 +EQUIV 7789 7009 +EQUIV 7790 7010 +EQUIV 7791 7011 +EQUIV 7792 7012 +EQUIV 7793 7013 +EQUIV 7794 7014 +EQUIV 7795 7015 +EQUIV 7811 7051 +EQUIV 7812 7052 +EQUIV 7813 7053 +EQUIV 7814 7054 +EQUIV 7815 7055 +EQUIV 7816 7056 +EQUIV 7817 7057 +EQUIV 7818 7058 +EQUIV 7819 7059 +EQUIV 7820 7060 +EQUIV 7826 7806 +EQUIV 7827 7807 +EQUIV 7828 7808 +EQUIV 7829 7809 +EQUIV 7830 7810 +EQUIV 7831 7051 +EQUIV 7832 7052 +EQUIV 7833 7053 +EQUIV 7834 7054 +EQUIV 7835 7055 +EQUIV 7836 7056 +EQUIV 7837 7057 +EQUIV 7838 7058 +EQUIV 7839 7059 +EQUIV 7840 7060 +EQUIV 7841 7821 +EQUIV 7842 7822 +EQUIV 7843 7823 +EQUIV 7844 7824 +EQUIV 7845 7825 +EQUIV 7846 7806 +EQUIV 7847 7807 +EQUIV 7848 7808 +EQUIV 7849 7809 +EQUIV 7850 7810 +EQUIV 7851 7051 +EQUIV 7852 7052 +EQUIV 7853 7053 +EQUIV 7854 7054 +EQUIV 7855 7055 +EQUIV 7861 7241 +EQUIV 7862 7242 +EQUIV 7863 7243 +EQUIV 7864 7244 +EQUIV 7865 7245 +EQUIV 7866 7246 +EQUIV 7867 7247 +EQUIV 7868 7248 +EQUIV 7869 7249 +EQUIV 7870 7250 +EQUIV 7876 7856 +EQUIV 7877 7857 +EQUIV 7878 7858 +EQUIV 7879 7859 +EQUIV 7880 7860 +EQUIV 7881 7241 +EQUIV 7882 7242 +EQUIV 7883 7243 +EQUIV 7884 7244 +EQUIV 7885 7245 +EQUIV 7906 7886 +EQUIV 7907 7887 +EQUIV 7908 7888 +EQUIV 7909 7889 +EQUIV 7910 7890 +EQUIV 7911 7891 +EQUIV 7912 7892 +EQUIV 7913 7893 +EQUIV 7914 7894 +EQUIV 7915 7895 +EQUIV 7916 7896 +EQUIV 7917 7897 +EQUIV 7918 7898 +EQUIV 7919 7899 +EQUIV 7920 7900 +EQUIV 7921 7181 +EQUIV 7922 7182 +EQUIV 7923 7183 +EQUIV 7924 7184 +EQUIV 7925 7185 +EQUIV 7926 7286 +EQUIV 7927 7287 +EQUIV 7928 7288 +EQUIV 7929 7289 +EQUIV 7930 7290 +EQUIV 7931 7451 +EQUIV 7932 7452 +EQUIV 7933 7453 +EQUIV 7934 7454 +EQUIV 7935 7455 +EQUIV 7936 7456 +EQUIV 7937 7457 +EQUIV 7938 7458 +EQUIV 7939 7459 +EQUIV 7940 7460 +EQUIV 7941 7521 +EQUIV 7942 7522 +EQUIV 7943 7523 +EQUIV 7944 7524 +EQUIV 7945 7525 +EQUIV 7946 7286 +EQUIV 7947 7287 +EQUIV 7948 7288 +EQUIV 7949 7289 +EQUIV 7950 7290 +EQUIV 7951 7451 +EQUIV 7952 7452 +EQUIV 7953 7453 +EQUIV 7954 7454 +EQUIV 7955 7455 +EQUIV 7956 7456 +EQUIV 7957 7457 +EQUIV 7958 7458 +EQUIV 7959 7459 +EQUIV 7960 7460 +EQUIV 7961 7381 +EQUIV 7962 7382 +EQUIV 7963 7383 +EQUIV 7964 7384 +EQUIV 7965 7385 +EQUIV 7966 7586 +EQUIV 7967 7587 +EQUIV 7968 7588 +EQUIV 7969 7589 +EQUIV 7970 7590 +EQUIV 7971 7591 +EQUIV 7972 7592 +EQUIV 7973 7593 +EQUIV 7974 7594 +EQUIV 7975 7595 +EQUIV 7976 7596 +EQUIV 7977 7597 +EQUIV 7978 7598 +EQUIV 7979 7599 +EQUIV 7980 7600 +EQUIV 7981 7641 +EQUIV 7982 7642 +EQUIV 7983 7643 +EQUIV 7984 7644 +EQUIV 7985 7645 +EQUIV 7986 7646 +EQUIV 7987 7647 +EQUIV 7988 7648 +EQUIV 7989 7649 +EQUIV 7990 7650 +EQUIV 7991 7651 +EQUIV 7992 7652 +EQUIV 7993 7653 +EQUIV 7994 7654 +EQUIV 7995 7655 +EQUIV 7996 7656 +EQUIV 7997 7657 +EQUIV 7998 7658 +EQUIV 7999 7659 +EQUIV 8000 7660 +EQUIV 8001 6361 +EQUIV 8002 6362 +EQUIV 8003 6363 +EQUIV 8004 6364 +EQUIV 8005 6365 +EQUIV 8006 6366 +EQUIV 8007 6367 +EQUIV 8008 6368 +EQUIV 8009 6369 +EQUIV 8010 6370 +EQUIV 8011 7691 +EQUIV 8012 7692 +EQUIV 8013 7693 +EQUIV 8014 7694 +EQUIV 8015 7695 +EQUIV 8031 7691 +EQUIV 8032 7692 +EQUIV 8033 7693 +EQUIV 8034 7694 +EQUIV 8035 7695 +EQUIV 8036 7696 +EQUIV 8037 7697 +EQUIV 8038 7698 +EQUIV 8039 7699 +EQUIV 8040 7700 +EQUIV 8041 7701 +EQUIV 8042 7702 +EQUIV 8043 7703 +EQUIV 8044 7704 +EQUIV 8045 7705 +EQUIV 8046 7706 +EQUIV 8047 7707 +EQUIV 8048 7708 +EQUIV 8049 7709 +EQUIV 8050 7710 +EQUIV 8081 6521 +EQUIV 8082 6522 +EQUIV 8083 6523 +EQUIV 8084 6524 +EQUIV 8085 6525 +EQUIV 8096 6476 +EQUIV 8097 6477 +EQUIV 8098 6478 +EQUIV 8099 6479 +EQUIV 8100 6480 +EQUIV 8141 8101 +EQUIV 8142 8102 +EQUIV 8143 8103 +EQUIV 8144 8104 +EQUIV 8145 8105 +EQUIV 8146 8126 +EQUIV 8147 8127 +EQUIV 8148 8128 +EQUIV 8149 8129 +EQUIV 8150 8130 +EQUIV 8151 8131 +EQUIV 8152 8132 +EQUIV 8153 8133 +EQUIV 8154 8134 +EQUIV 8155 8135 +EQUIV 8156 8136 +EQUIV 8157 8137 +EQUIV 8158 8138 +EQUIV 8159 8139 +EQUIV 8160 8140 +EQUIV 8161 8101 +EQUIV 8162 8102 +EQUIV 8163 8103 +EQUIV 8164 8104 +EQUIV 8165 8105 +EQUIV 8166 8126 +EQUIV 8167 8127 +EQUIV 8168 8128 +EQUIV 8169 8129 +EQUIV 8170 8130 +EQUIV 8221 8201 +EQUIV 8222 8202 +EQUIV 8223 8203 +EQUIV 8224 8204 +EQUIV 8225 8205 +EQUIV 8226 8206 +EQUIV 8227 8207 +EQUIV 8228 8208 +EQUIV 8229 8209 +EQUIV 8230 8210 +EQUIV 8231 8211 +EQUIV 8232 8212 +EQUIV 8233 8213 +EQUIV 8234 8214 +EQUIV 8235 8215 +EQUIV 8236 8216 +EQUIV 8237 8217 +EQUIV 8238 8218 +EQUIV 8239 8219 +EQUIV 8240 8220 +EQUIV 8241 8201 +EQUIV 8242 8202 +EQUIV 8243 8203 +EQUIV 8244 8204 +EQUIV 8245 8205 +EQUIV 8246 8206 +EQUIV 8247 8207 +EQUIV 8248 8208 +EQUIV 8249 8209 +EQUIV 8250 8210 +EQUIV 8251 8211 +EQUIV 8252 8212 +EQUIV 8253 8213 +EQUIV 8254 8214 +EQUIV 8255 8215 +EQUIV 8256 8216 +EQUIV 8257 8217 +EQUIV 8258 8218 +EQUIV 8259 8219 +EQUIV 8260 8220 +EQUIV 8261 8201 +EQUIV 8262 8202 +EQUIV 8263 8203 +EQUIV 8264 8204 +EQUIV 8265 8205 +EQUIV 8336 1036 +EQUIV 8337 1037 +EQUIV 8338 1038 +EQUIV 8339 1039 +EQUIV 8340 1040 +EQUIV 8341 1041 +EQUIV 8342 1042 +EQUIV 8343 1043 +EQUIV 8344 1044 +EQUIV 8345 1045 +EQUIV 8346 1086 +EQUIV 8347 1087 +EQUIV 8348 1088 +EQUIV 8349 1089 +EQUIV 8350 1090 +EQUIV 8351 1091 +EQUIV 8352 1092 +EQUIV 8353 1093 +EQUIV 8354 1094 +EQUIV 8355 1095 +EQUIV 8356 3056 +EQUIV 8357 3057 +EQUIV 8358 3058 +EQUIV 8359 3059 +EQUIV 8360 3060 +EQUIV 8361 3061 +EQUIV 8362 3062 +EQUIV 8363 3063 +EQUIV 8364 3064 +EQUIV 8365 3065 +EQUIV 8366 3066 +EQUIV 8367 3067 +EQUIV 8368 3068 +EQUIV 8369 3069 +EQUIV 8370 3070 +EQUIV 8371 3071 +EQUIV 8372 3072 +EQUIV 8373 3073 +EQUIV 8374 3074 +EQUIV 8375 3075 +EQUIV 8376 1076 +EQUIV 8377 1077 +EQUIV 8378 1078 +EQUIV 8379 1079 +EQUIV 8380 1080 +EQUIV 8381 3061 +EQUIV 8382 3062 +EQUIV 8383 3063 +EQUIV 8384 3064 +EQUIV 8385 3065 +EQUIV 8386 1166 +EQUIV 8387 1167 +EQUIV 8388 1168 +EQUIV 8389 1169 +EQUIV 8390 1170 +EQUIV 8391 1111 +EQUIV 8392 1112 +EQUIV 8393 1113 +EQUIV 8394 1114 +EQUIV 8395 1115 +EQUIV 8396 3056 +EQUIV 8397 3057 +EQUIV 8398 3058 +EQUIV 8399 3059 +EQUIV 8400 3060 +EQUIV 8401 1081 +EQUIV 8402 1082 +EQUIV 8403 1083 +EQUIV 8404 1084 +EQUIV 8405 1085 +EQUIV 8406 1086 +EQUIV 8407 1087 +EQUIV 8408 1088 +EQUIV 8409 1089 +EQUIV 8410 1090 +EQUIV 8411 1091 +EQUIV 8412 1092 +EQUIV 8413 1093 +EQUIV 8414 1094 +EQUIV 8415 1095 +EQUIV 8416 3056 +EQUIV 8417 3057 +EQUIV 8418 3058 +EQUIV 8419 3059 +EQUIV 8420 3060 +EQUIV 8421 3061 +EQUIV 8422 3062 +EQUIV 8423 3063 +EQUIV 8424 3064 +EQUIV 8425 3065 +EQUIV 8426 3066 +EQUIV 8427 3067 +EQUIV 8428 3068 +EQUIV 8429 3069 +EQUIV 8430 3070 +EQUIV 8431 3391 +EQUIV 8432 3392 +EQUIV 8433 3393 +EQUIV 8434 3394 +EQUIV 8435 3395 +EQUIV 8436 916 +EQUIV 8437 917 +EQUIV 8438 918 +EQUIV 8439 919 +EQUIV 8440 920 +EQUIV 8441 921 +EQUIV 8442 922 +EQUIV 8443 923 +EQUIV 8444 924 +EQUIV 8445 925 +EQUIV 8446 926 +EQUIV 8447 927 +EQUIV 8448 928 +EQUIV 8449 929 +EQUIV 8450 930 +EQUIV 8451 931 +EQUIV 8452 932 +EQUIV 8453 933 +EQUIV 8454 934 +EQUIV 8455 935 +EQUIV 8456 936 +EQUIV 8457 937 +EQUIV 8458 938 +EQUIV 8459 939 +EQUIV 8460 940 +EQUIV 8466 3406 +EQUIV 8467 3407 +EQUIV 8468 3408 +EQUIV 8469 3409 +EQUIV 8470 3410 +EQUIV 8471 3071 +EQUIV 8472 3072 +EQUIV 8473 3073 +EQUIV 8474 3074 +EQUIV 8475 3075 +EQUIV 8476 1076 +EQUIV 8477 1077 +EQUIV 8478 1078 +EQUIV 8479 1079 +EQUIV 8480 1080 +EQUIV 8481 3061 +EQUIV 8482 3062 +EQUIV 8483 3063 +EQUIV 8484 3064 +EQUIV 8485 3065 +EQUIV 8486 1166 +EQUIV 8487 1167 +EQUIV 8488 1168 +EQUIV 8489 1169 +EQUIV 8490 1170 +EQUIV 8491 1151 +EQUIV 8492 1152 +EQUIV 8493 1153 +EQUIV 8494 1154 +EQUIV 8495 1155 +EQUIV 8496 1156 +EQUIV 8497 1157 +EQUIV 8498 1158 +EQUIV 8499 1159 +EQUIV 8500 1160 +EQUIV 8501 841 +EQUIV 8502 842 +EQUIV 8503 843 +EQUIV 8504 844 +EQUIV 8505 845 +EQUIV 8506 706 +EQUIV 8507 707 +EQUIV 8508 708 +EQUIV 8509 709 +EQUIV 8510 710 +EQUIV 8511 3371 +EQUIV 8512 3372 +EQUIV 8513 3373 +EQUIV 8514 3374 +EQUIV 8515 3375 +EQUIV 8516 3176 +EQUIV 8517 3177 +EQUIV 8518 3178 +EQUIV 8519 3179 +EQUIV 8520 3180 +EQUIV 8521 3181 +EQUIV 8522 3182 +EQUIV 8523 3183 +EQUIV 8524 3184 +EQUIV 8525 3185 +EQUIV 8526 3006 +EQUIV 8527 3007 +EQUIV 8528 3008 +EQUIV 8529 3009 +EQUIV 8530 3010 +EQUIV 8531 2711 +EQUIV 8532 2712 +EQUIV 8533 2713 +EQUIV 8534 2714 +EQUIV 8535 2715 +EQUIV 8536 3016 +EQUIV 8537 3017 +EQUIV 8538 3018 +EQUIV 8539 3019 +EQUIV 8540 3020 +EQUIV 8541 3021 +EQUIV 8542 3022 +EQUIV 8543 3023 +EQUIV 8544 3024 +EQUIV 8545 3025 +EQUIV 8546 1106 +EQUIV 8547 1107 +EQUIV 8548 1108 +EQUIV 8549 1109 +EQUIV 8550 1110 +EQUIV 8551 1111 +EQUIV 8552 1112 +EQUIV 8553 1113 +EQUIV 8554 1114 +EQUIV 8555 1115 +EQUIV 8556 1096 +EQUIV 8557 1097 +EQUIV 8558 1098 +EQUIV 8559 1099 +EQUIV 8560 1100 +EQUIV 8561 1101 +EQUIV 8562 1102 +EQUIV 8563 1103 +EQUIV 8564 1104 +EQUIV 8565 1105 +EQUIV 8566 1106 +EQUIV 8567 1107 +EQUIV 8568 1108 +EQUIV 8569 1109 +EQUIV 8570 1110 +EQUIV 8571 1151 +EQUIV 8572 1152 +EQUIV 8573 1153 +EQUIV 8574 1154 +EQUIV 8575 1155 +EQUIV 8576 1156 +EQUIV 8577 1157 +EQUIV 8578 1158 +EQUIV 8579 1159 +EQUIV 8580 1160 +EQUIV 8581 841 +EQUIV 8582 842 +EQUIV 8583 843 +EQUIV 8584 844 +EQUIV 8585 845 +EQUIV 8586 826 +EQUIV 8587 827 +EQUIV 8588 828 +EQUIV 8589 829 +EQUIV 8590 830 +EQUIV 8591 831 +EQUIV 8592 832 +EQUIV 8593 833 +EQUIV 8594 834 +EQUIV 8595 835 +EQUIV 8596 916 +EQUIV 8597 917 +EQUIV 8598 918 +EQUIV 8599 919 +EQUIV 8600 920 +EQUIV 8601 921 +EQUIV 8602 922 +EQUIV 8603 923 +EQUIV 8604 924 +EQUIV 8605 925 +EQUIV 8606 3406 +EQUIV 8607 3407 +EQUIV 8608 3408 +EQUIV 8609 3409 +EQUIV 8610 3410 +EQUIV 8611 3071 +EQUIV 8612 3072 +EQUIV 8613 3073 +EQUIV 8614 3074 +EQUIV 8615 3075 +EQUIV 8616 1076 +EQUIV 8617 1077 +EQUIV 8618 1078 +EQUIV 8619 1079 +EQUIV 8620 1080 +EQUIV 8621 3061 +EQUIV 8622 3062 +EQUIV 8623 3063 +EQUIV 8624 3064 +EQUIV 8625 3065 +EQUIV 8626 3066 +EQUIV 8627 3067 +EQUIV 8628 3068 +EQUIV 8629 3069 +EQUIV 8630 3070 +EQUIV 8631 3071 +EQUIV 8632 3072 +EQUIV 8633 3073 +EQUIV 8634 3074 +EQUIV 8635 3075 +EQUIV 8636 996 +EQUIV 8637 997 +EQUIV 8638 998 +EQUIV 8639 999 +EQUIV 8640 1000 +EQUIV 8641 941 +EQUIV 8642 942 +EQUIV 8643 943 +EQUIV 8644 944 +EQUIV 8645 945 +EQUIV 8646 986 +EQUIV 8647 987 +EQUIV 8648 988 +EQUIV 8649 989 +EQUIV 8650 990 +EQUIV 8651 991 +EQUIV 8652 992 +EQUIV 8653 993 +EQUIV 8654 994 +EQUIV 8655 995 +EQUIV 8656 1076 +EQUIV 8657 1077 +EQUIV 8658 1078 +EQUIV 8659 1079 +EQUIV 8660 1080 +EQUIV 8661 1081 +EQUIV 8662 1082 +EQUIV 8663 1083 +EQUIV 8664 1084 +EQUIV 8665 1085 +EQUIV 8666 1086 +EQUIV 8667 1087 +EQUIV 8668 1088 +EQUIV 8669 1089 +EQUIV 8670 1090 +EQUIV 8671 1091 +EQUIV 8672 1092 +EQUIV 8673 1093 +EQUIV 8674 1094 +EQUIV 8675 1095 +EQUIV 8676 3056 +EQUIV 8677 3057 +EQUIV 8678 3058 +EQUIV 8679 3059 +EQUIV 8680 3060 +EQUIV 8681 1081 +EQUIV 8682 1082 +EQUIV 8683 1083 +EQUIV 8684 1084 +EQUIV 8685 1085 +EQUIV 8686 1046 +EQUIV 8687 1047 +EQUIV 8688 1048 +EQUIV 8689 1049 +EQUIV 8690 1050 +EQUIV 8691 1031 +EQUIV 8692 1032 +EQUIV 8693 1033 +EQUIV 8694 1034 +EQUIV 8695 1035 +EQUIV 8696 1036 +EQUIV 8697 1037 +EQUIV 8698 1038 +EQUIV 8699 1039 +EQUIV 8700 1040 +EQUIV 8701 1041 +EQUIV 8702 1042 +EQUIV 8703 1043 +EQUIV 8704 1044 +EQUIV 8705 1045 +EQUIV 8706 1086 +EQUIV 8707 1087 +EQUIV 8708 1088 +EQUIV 8709 1089 +EQUIV 8710 1090 +EQUIV 8711 1091 +EQUIV 8712 1092 +EQUIV 8713 1093 +EQUIV 8714 1094 +EQUIV 8715 1095 +EQUIV 8716 3056 +EQUIV 8717 3057 +EQUIV 8718 3058 +EQUIV 8719 3059 +EQUIV 8720 3060 +EQUIV 8721 1081 +EQUIV 8722 1082 +EQUIV 8723 1083 +EQUIV 8724 1084 +EQUIV 8725 1085 +EQUIV 8726 1086 +EQUIV 8727 1087 +EQUIV 8728 1088 +EQUIV 8729 1089 +EQUIV 8730 1090 +EQUIV 8731 1091 +EQUIV 8732 1092 +EQUIV 8733 1093 +EQUIV 8734 1094 +EQUIV 8735 1095 +EQUIV 8736 3056 +EQUIV 8737 3057 +EQUIV 8738 3058 +EQUIV 8739 3059 +EQUIV 8740 3060 +EQUIV 8741 3061 +EQUIV 8742 3062 +EQUIV 8743 3063 +EQUIV 8744 3064 +EQUIV 8745 3065 +EQUIV 8746 3066 +EQUIV 8747 3067 +EQUIV 8748 3068 +EQUIV 8749 3069 +EQUIV 8750 3070 +EQUIV 8751 3391 +EQUIV 8752 3392 +EQUIV 8753 3393 +EQUIV 8754 3394 +EQUIV 8755 3395 +EQUIV 8756 916 +EQUIV 8757 917 +EQUIV 8758 918 +EQUIV 8759 919 +EQUIV 8760 920 +EQUIV 8761 681 +EQUIV 8762 682 +EQUIV 8763 683 +EQUIV 8764 684 +EQUIV 8765 685 +EQUIV 8766 5906 +EQUIV 8767 5907 +EQUIV 8768 5908 +EQUIV 8769 5909 +EQUIV 8770 5910 +EQUIV 8776 676 +EQUIV 8777 677 +EQUIV 8778 678 +EQUIV 8779 679 +EQUIV 8780 680 +EQUIV 8781 681 +EQUIV 8782 682 +EQUIV 8783 683 +EQUIV 8784 684 +EQUIV 8785 685 +EQUIV 8786 5906 +EQUIV 8787 5907 +EQUIV 8788 5908 +EQUIV 8789 5909 +EQUIV 8790 5910 +EQUIV 8791 8771 +EQUIV 8792 8772 +EQUIV 8793 8773 +EQUIV 8794 8774 +EQUIV 8795 8775 +EQUIV 8801 661 +EQUIV 8802 662 +EQUIV 8803 663 +EQUIV 8804 664 +EQUIV 8805 665 +EQUIV 8806 666 +EQUIV 8807 667 +EQUIV 8808 668 +EQUIV 8809 669 +EQUIV 8810 670 +EQUIV 8811 671 +EQUIV 8812 672 +EQUIV 8813 673 +EQUIV 8814 674 +EQUIV 8815 675 +EQUIV 8816 8796 +EQUIV 8817 8797 +EQUIV 8818 8798 +EQUIV 8819 8799 +EQUIV 8820 8800 +EQUIV 8821 641 +EQUIV 8822 642 +EQUIV 8823 643 +EQUIV 8824 644 +EQUIV 8825 645 +EQUIV 8826 626 +EQUIV 8827 627 +EQUIV 8828 628 +EQUIV 8829 629 +EQUIV 8830 630 +EQUIV 8831 631 +EQUIV 8832 632 +EQUIV 8833 633 +EQUIV 8834 634 +EQUIV 8835 635 +EQUIV 8836 636 +EQUIV 8837 637 +EQUIV 8838 638 +EQUIV 8839 639 +EQUIV 8840 640 +EQUIV 8841 641 +EQUIV 8842 642 +EQUIV 8843 643 +EQUIV 8844 644 +EQUIV 8845 645 +EQUIV 8846 5926 +EQUIV 8847 5927 +EQUIV 8848 5928 +EQUIV 8849 5929 +EQUIV 8850 5930 +EQUIV 8851 5911 +EQUIV 8852 5912 +EQUIV 8853 5913 +EQUIV 8854 5914 +EQUIV 8855 5915 +EQUIV 8856 5916 +EQUIV 8857 5917 +EQUIV 8858 5918 +EQUIV 8859 5919 +EQUIV 8860 5920 +EQUIV 8861 6021 +EQUIV 8862 6022 +EQUIV 8863 6023 +EQUIV 8864 6024 +EQUIV 8865 6025 +EQUIV 8866 6026 +EQUIV 8867 6027 +EQUIV 8868 6028 +EQUIV 8869 6029 +EQUIV 8870 6030 +EQUIV 8871 611 +EQUIV 8872 612 +EQUIV 8873 613 +EQUIV 8874 614 +EQUIV 8875 615 +EQUIV 8906 8886 +EQUIV 8907 8887 +EQUIV 8908 8888 +EQUIV 8909 8889 +EQUIV 8910 8890 +EQUIV 8911 8891 +EQUIV 8912 8892 +EQUIV 8913 8893 +EQUIV 8914 8894 +EQUIV 8915 8895 +EQUIV 8916 8896 +EQUIV 8917 8897 +EQUIV 8918 8898 +EQUIV 8919 8899 +EQUIV 8920 8900 +EQUIV 8921 8901 +EQUIV 8922 8902 +EQUIV 8923 8903 +EQUIV 8924 8904 +EQUIV 8925 8905 +EQUIV 8936 8876 +EQUIV 8937 8877 +EQUIV 8938 8878 +EQUIV 8939 8879 +EQUIV 8940 8880 +EQUIV 8941 601 +EQUIV 8942 602 +EQUIV 8943 603 +EQUIV 8944 604 +EQUIV 8945 605 +EQUIV 8946 606 +EQUIV 8947 607 +EQUIV 8948 608 +EQUIV 8949 609 +EQUIV 8950 610 +EQUIV 8951 6031 +EQUIV 8952 6032 +EQUIV 8953 6033 +EQUIV 8954 6034 +EQUIV 8955 6035 +EQUIV 8956 6036 +EQUIV 8957 6037 +EQUIV 8958 6038 +EQUIV 8959 6039 +EQUIV 8960 6040 +EQUIV 8961 6041 +EQUIV 8962 6042 +EQUIV 8963 6043 +EQUIV 8964 6044 +EQUIV 8965 6045 +EQUIV 8966 6226 +EQUIV 8967 6227 +EQUIV 8968 6228 +EQUIV 8969 6229 +EQUIV 8970 6230 +EQUIV 8971 591 +EQUIV 8972 592 +EQUIV 8973 593 +EQUIV 8974 594 +EQUIV 8975 595 +EQUIV 8976 6276 +EQUIV 8977 6277 +EQUIV 8978 6278 +EQUIV 8979 6279 +EQUIV 8980 6280 +EQUIV 8981 6301 +EQUIV 8982 6302 +EQUIV 8983 6303 +EQUIV 8984 6304 +EQUIV 8985 6305 +EQUIV 8986 6306 +EQUIV 8987 6307 +EQUIV 8988 6308 +EQUIV 8989 6309 +EQUIV 8990 6310 +EQUIV 8991 8891 +EQUIV 8992 8892 +EQUIV 8993 8893 +EQUIV 8994 8894 +EQUIV 8995 8895 +EQUIV 8996 8136 +EQUIV 8997 8137 +EQUIV 8998 8138 +EQUIV 8999 8139 +EQUIV 9000 8140 +EQUIV 9001 8101 +EQUIV 9002 8102 +EQUIV 9003 8103 +EQUIV 9004 8104 +EQUIV 9005 8105 +EQUIV 9006 8126 +EQUIV 9007 8127 +EQUIV 9008 8128 +EQUIV 9009 8129 +EQUIV 9010 8130 +EQUIV 9011 8131 +EQUIV 9012 8132 +EQUIV 9013 8133 +EQUIV 9014 8134 +EQUIV 9015 8135 +EQUIV 9016 8896 +EQUIV 9017 8897 +EQUIV 9018 8898 +EQUIV 9019 8899 +EQUIV 9020 8900 +EQUIV 9021 8901 +EQUIV 9022 8902 +EQUIV 9023 8903 +EQUIV 9024 8904 +EQUIV 9025 8905 +EQUIV 9026 8886 +EQUIV 9027 8887 +EQUIV 9028 8888 +EQUIV 9029 8889 +EQUIV 9030 8890 +EQUIV 9031 8891 +EQUIV 9032 8892 +EQUIV 9033 8893 +EQUIV 9034 8894 +EQUIV 9035 8895 +EQUIV 9036 8896 +EQUIV 9037 8897 +EQUIV 9038 8898 +EQUIV 9039 8899 +EQUIV 9040 8900 +EQUIV 9041 8901 +EQUIV 9042 8902 +EQUIV 9043 8903 +EQUIV 9044 8904 +EQUIV 9045 8905 +EQUIV 9046 8886 +EQUIV 9047 8887 +EQUIV 9048 8888 +EQUIV 9049 8889 +EQUIV 9050 8890 +EQUIV 9051 8891 +EQUIV 9052 8892 +EQUIV 9053 8893 +EQUIV 9054 8894 +EQUIV 9055 8895 +EQUIV 9056 8896 +EQUIV 9057 8897 +EQUIV 9058 8898 +EQUIV 9059 8899 +EQUIV 9060 8900 +EQUIV 9071 8171 +EQUIV 9072 8172 +EQUIV 9073 8173 +EQUIV 9074 8174 +EQUIV 9075 8175 +EQUIV 9096 9076 +EQUIV 9097 9077 +EQUIV 9098 9078 +EQUIV 9099 9079 +EQUIV 9100 9080 +EQUIV 9101 9081 +EQUIV 9102 9082 +EQUIV 9103 9083 +EQUIV 9104 9084 +EQUIV 9105 9085 +EQUIV 9191 9171 +EQUIV 9192 9172 +EQUIV 9193 9173 +EQUIV 9194 9174 +EQUIV 9195 9175 +EQUIV 9206 8186 +EQUIV 9207 8187 +EQUIV 9208 8188 +EQUIV 9209 8189 +EQUIV 9210 8190 +EQUIV 9221 8181 +EQUIV 9222 8182 +EQUIV 9223 8183 +EQUIV 9224 8184 +EQUIV 9225 8185 +EQUIV 9236 9176 +EQUIV 9237 9177 +EQUIV 9238 9178 +EQUIV 9239 9179 +EQUIV 9240 9180 +EQUIV 9241 9181 +EQUIV 9242 9182 +EQUIV 9243 9183 +EQUIV 9244 9184 +EQUIV 9245 9185 +EQUIV 9246 9186 +EQUIV 9247 9187 +EQUIV 9248 9188 +EQUIV 9249 9189 +EQUIV 9250 9190 +EQUIV 9251 9171 +EQUIV 9252 9172 +EQUIV 9253 9173 +EQUIV 9254 9174 +EQUIV 9255 9175 +EQUIV 9256 9176 +EQUIV 9257 9177 +EQUIV 9258 9178 +EQUIV 9259 9179 +EQUIV 9260 9180 +EQUIV 9266 9086 +EQUIV 9267 9087 +EQUIV 9268 9088 +EQUIV 9269 9089 +EQUIV 9270 9090 +EQUIV 9271 9091 +EQUIV 9272 9092 +EQUIV 9273 9093 +EQUIV 9274 9094 +EQUIV 9275 9095 +EQUIV 9276 9076 +EQUIV 9277 9077 +EQUIV 9278 9078 +EQUIV 9279 9079 +EQUIV 9280 9080 +EQUIV 9281 9081 +EQUIV 9282 9082 +EQUIV 9283 9083 +EQUIV 9284 9084 +EQUIV 9285 9085 +EQUIV 9286 9086 +EQUIV 9287 9087 +EQUIV 9288 9088 +EQUIV 9289 9089 +EQUIV 9290 9090 +EQUIV 9291 9091 +EQUIV 9292 9092 +EQUIV 9293 9093 +EQUIV 9294 9094 +EQUIV 9295 9095 +EQUIV 9296 9076 +EQUIV 9297 9077 +EQUIV 9298 9078 +EQUIV 9299 9079 +EQUIV 9300 9080 +EQUIV 9301 9081 +EQUIV 9302 9082 +EQUIV 9303 9083 +EQUIV 9304 9084 +EQUIV 9305 9085 +EQUIV 9306 9086 +EQUIV 9307 9087 +EQUIV 9308 9088 +EQUIV 9309 9089 +EQUIV 9310 9090 +EQUIV 9311 9091 +EQUIV 9312 9092 +EQUIV 9313 9093 +EQUIV 9314 9094 +EQUIV 9315 9095 +EQUIV 9316 9076 +EQUIV 9317 9077 +EQUIV 9318 9078 +EQUIV 9319 9079 +EQUIV 9320 9080 +EQUIV 9321 9081 +EQUIV 9322 9082 +EQUIV 9323 9083 +EQUIV 9324 9084 +EQUIV 9325 9085 +EQUIV 9326 9106 +EQUIV 9327 9107 +EQUIV 9328 9108 +EQUIV 9329 9109 +EQUIV 9330 9110 +EQUIV 9341 6661 +EQUIV 9342 6662 +EQUIV 9343 6663 +EQUIV 9344 6664 +EQUIV 9345 6665 +EQUIV 9346 6526 +EQUIV 9347 6527 +EQUIV 9348 6528 +EQUIV 9349 6529 +EQUIV 9350 6530 +EQUIV 9351 6531 +EQUIV 9352 6532 +EQUIV 9353 6533 +EQUIV 9354 6534 +EQUIV 9355 6535 +EQUIV 9356 6596 +EQUIV 9357 6597 +EQUIV 9358 6598 +EQUIV 9359 6599 +EQUIV 9360 6600 +EQUIV 9361 6621 +EQUIV 9362 6622 +EQUIV 9363 6623 +EQUIV 9364 6624 +EQUIV 9365 6625 +EQUIV 9376 6756 +EQUIV 9377 6757 +EQUIV 9378 6758 +EQUIV 9379 6759 +EQUIV 9380 6760 +EQUIV 9396 6616 +EQUIV 9397 6617 +EQUIV 9398 6618 +EQUIV 9399 6619 +EQUIV 9400 6620 +EQUIV 9401 6601 +EQUIV 9402 6602 +EQUIV 9403 6603 +EQUIV 9404 6604 +EQUIV 9405 6605 +EQUIV 9406 6606 +EQUIV 9407 6607 +EQUIV 9408 6608 +EQUIV 9409 6609 +EQUIV 9410 6610 +EQUIV 9411 7211 +EQUIV 9412 7212 +EQUIV 9413 7213 +EQUIV 9414 7214 +EQUIV 9415 7215 +EQUIV 9416 7216 +EQUIV 9417 7217 +EQUIV 9418 7218 +EQUIV 9419 7219 +EQUIV 9420 7220 +EQUIV 9426 7626 +EQUIV 9427 7627 +EQUIV 9428 7628 +EQUIV 9429 7629 +EQUIV 9430 7630 +EQUIV 9431 7371 +EQUIV 9432 7372 +EQUIV 9433 7373 +EQUIV 9434 7374 +EQUIV 9435 7375 +EQUIV 9436 7376 +EQUIV 9437 7377 +EQUIV 9438 7378 +EQUIV 9439 7379 +EQUIV 9440 7380 +EQUIV 9441 7521 +EQUIV 9442 7522 +EQUIV 9443 7523 +EQUIV 9444 7524 +EQUIV 9445 7525 +EQUIV 9446 7186 +EQUIV 9447 7187 +EQUIV 9448 7188 +EQUIV 9449 7189 +EQUIV 9450 7190 +EQUIV 9451 7371 +EQUIV 9452 7372 +EQUIV 9453 7373 +EQUIV 9454 7374 +EQUIV 9455 7375 +EQUIV 9456 7376 +EQUIV 9457 7377 +EQUIV 9458 7378 +EQUIV 9459 7379 +EQUIV 9460 7380 +EQUIV 9461 7521 +EQUIV 9462 7522 +EQUIV 9463 7523 +EQUIV 9464 7524 +EQUIV 9465 7525 +EQUIV 9466 7286 +EQUIV 9467 7287 +EQUIV 9468 7288 +EQUIV 9469 7289 +EQUIV 9470 7290 +EQUIV 9471 7171 +EQUIV 9472 7172 +EQUIV 9473 7173 +EQUIV 9474 7174 +EQUIV 9475 7175 +EQUIV 9476 7176 +EQUIV 9477 7177 +EQUIV 9478 7178 +EQUIV 9479 7179 +EQUIV 9480 7180 +EQUIV 9481 7901 +EQUIV 9482 7902 +EQUIV 9483 7903 +EQUIV 9484 7904 +EQUIV 9485 7905 +EQUIV 9486 7246 +EQUIV 9487 7247 +EQUIV 9488 7248 +EQUIV 9489 7249 +EQUIV 9490 7250 +EQUIV 9491 7871 +EQUIV 9492 7872 +EQUIV 9493 7873 +EQUIV 9494 7874 +EQUIV 9495 7875 +EQUIV 9496 7056 +EQUIV 9497 7057 +EQUIV 9498 7058 +EQUIV 9499 7059 +EQUIV 9500 7060 +EQUIV 9501 7821 +EQUIV 9502 7822 +EQUIV 9503 7823 +EQUIV 9504 7824 +EQUIV 9505 7825 +EQUIV 9521 7801 +EQUIV 9522 7802 +EQUIV 9523 7803 +EQUIV 9524 7804 +EQUIV 9525 7805 +EQUIV 9526 7806 +EQUIV 9527 7807 +EQUIV 9528 7808 +EQUIV 9529 7809 +EQUIV 9530 7810 +EQUIV 9531 7011 +EQUIV 9532 7012 +EQUIV 9533 7013 +EQUIV 9534 7014 +EQUIV 9535 7015 +EQUIV 9536 7796 +EQUIV 9537 7797 +EQUIV 9538 7798 +EQUIV 9539 7799 +EQUIV 9540 7800 +EQUIV 9586 9566 +EQUIV 9587 9567 +EQUIV 9588 9568 +EQUIV 9589 9569 +EQUIV 9590 9570 +EQUIV 9591 9571 +EQUIV 9592 9572 +EQUIV 9593 9573 +EQUIV 9594 9574 +EQUIV 9595 9575 +EQUIV 9596 9576 +EQUIV 9597 9577 +EQUIV 9598 9578 +EQUIV 9599 9579 +EQUIV 9600 9580 +EQUIV 9601 9581 +EQUIV 9602 9582 +EQUIV 9603 9583 +EQUIV 9604 9584 +EQUIV 9605 9585 +EQUIV 9641 9621 +EQUIV 9642 9622 +EQUIV 9643 9623 +EQUIV 9644 9624 +EQUIV 9645 9625 +EQUIV 9646 9626 +EQUIV 9647 9627 +EQUIV 9648 9628 +EQUIV 9649 9629 +EQUIV 9650 9630 +EQUIV 9651 9631 +EQUIV 9652 9632 +EQUIV 9653 9633 +EQUIV 9654 9634 +EQUIV 9655 9635 +EQUIV 9661 6961 +EQUIV 9662 6962 +EQUIV 9663 6963 +EQUIV 9664 6964 +EQUIV 9665 6965 +EQUIV 9666 6886 +EQUIV 9667 6887 +EQUIV 9668 6888 +EQUIV 9669 6889 +EQUIV 9670 6890 +EQUIV 9671 6891 +EQUIV 9672 6892 +EQUIV 9673 6893 +EQUIV 9674 6894 +EQUIV 9675 6895 +EQUIV 9676 6896 +EQUIV 9677 6897 +EQUIV 9678 6898 +EQUIV 9679 6899 +EQUIV 9680 6900 +EQUIV 9701 9681 +EQUIV 9702 9682 +EQUIV 9703 9683 +EQUIV 9704 9684 +EQUIV 9705 9685 +EQUIV 9706 9686 +EQUIV 9707 9687 +EQUIV 9708 9688 +EQUIV 9709 9689 +EQUIV 9710 9690 +EQUIV 9711 9691 +EQUIV 9712 9692 +EQUIV 9713 9693 +EQUIV 9714 9694 +EQUIV 9715 9695 +EQUIV 9781 9761 +EQUIV 9782 9762 +EQUIV 9783 9763 +EQUIV 9784 9764 +EQUIV 9785 9765 +EQUIV 9786 9766 +EQUIV 9787 9767 +EQUIV 9788 9768 +EQUIV 9789 9769 +EQUIV 9790 9770 +EQUIV 9791 9771 +EQUIV 9792 9772 +EQUIV 9793 9773 +EQUIV 9794 9774 +EQUIV 9795 9775 +EQUIV 9796 9776 +EQUIV 9797 9777 +EQUIV 9798 9778 +EQUIV 9799 9779 +EQUIV 9800 9780 +EQUIV 9801 9761 +EQUIV 9802 9762 +EQUIV 9803 9763 +EQUIV 9804 9764 +EQUIV 9805 9765 +EQUIV 9806 9766 +EQUIV 9807 9767 +EQUIV 9808 9768 +EQUIV 9809 9769 +EQUIV 9810 9770 +EQUIV 9851 9771 +EQUIV 9852 9772 +EQUIV 9853 9773 +EQUIV 9854 9774 +EQUIV 9855 9775 +EQUIV 9856 9776 +EQUIV 9857 9777 +EQUIV 9858 9778 +EQUIV 9859 9779 +EQUIV 9860 9780 +EQUIV 9861 9761 +EQUIV 9862 9762 +EQUIV 9863 9763 +EQUIV 9864 9764 +EQUIV 9865 9765 +EQUIV 9911 9891 +EQUIV 9912 9892 +EQUIV 9913 9893 +EQUIV 9914 9894 +EQUIV 9915 9895 +EQUIV 9951 9931 +EQUIV 9952 9932 +EQUIV 9953 9933 +EQUIV 9954 9934 +EQUIV 9955 9935 +EQUIV 9956 9936 +EQUIV 9957 9937 +EQUIV 9958 9938 +EQUIV 9959 9939 +EQUIV 9960 9940 +EQUIV 9961 9941 +EQUIV 9962 9942 +EQUIV 9963 9943 +EQUIV 9964 9944 +EQUIV 9965 9945 +EQUIV 9966 9946 +EQUIV 9967 9947 +EQUIV 9968 9948 +EQUIV 9969 9949 +EQUIV 9970 9950 +EQUIV 9971 9931 +EQUIV 9972 9932 +EQUIV 9973 9933 +EQUIV 9974 9934 +EQUIV 9975 9935 +EQUIV 9976 9936 +EQUIV 9977 9937 +EQUIV 9978 9938 +EQUIV 9979 9939 +EQUIV 9980 9940 +EQUIV 9981 9941 +EQUIV 9982 9942 +EQUIV 9983 9943 +EQUIV 9984 9944 +EQUIV 9985 9945 +EQUIV 9986 9946 +EQUIV 9987 9947 +EQUIV 9988 9948 +EQUIV 9989 9949 +EQUIV 9990 9950 +EQUIV 9991 9931 +EQUIV 9992 9932 +EQUIV 9993 9933 +EQUIV 9994 9934 +EQUIV 9995 9935 diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp new file mode 100644 index 000000000..6572236a0 --- /dev/null +++ b/examples/DiscreteBayesNet_FG.cpp @@ -0,0 +1,119 @@ +/* ---------------------------------------------------------------------------- + + * 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 DiscreteBayesNet_FG.cpp + * @brief Discrete Bayes Net example using Factor Graphs + * @author Abhijit + * @date Jun 4, 2012 + * + * We use the famous Rain/Cloudy/Sprinkler Example of [Russell & Norvig, 2009, p529] + * You may be familiar with other graphical model packages like BNT (available + * at http://bnt.googlecode.com/svn/trunk/docs/usage.html) where this is used as an + * example. The following demo is same as that in the above link, except that + * everything is using GTSAM. + */ + +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char **argv) { + + // We assume binary state variables + // we have 0 == "False" and 1 == "True" + const size_t nrStates = 2; + + // define variables + DiscreteKey Cloudy(1, nrStates), Sprinkler(2, nrStates), Rain(3, nrStates), + WetGrass(4, nrStates); + + // create Factor Graph of the bayes net + DiscreteFactorGraph graph; + + // add factors + graph.add(Cloudy, "0.5 0.5"); //P(Cloudy) + graph.add(Cloudy & Sprinkler, "0.5 0.5 0.9 0.1"); //P(Sprinkler | Cloudy) + graph.add(Cloudy & Rain, "0.8 0.2 0.2 0.8"); //P(Rain | Cloudy) + graph.add(Sprinkler & Rain & WetGrass, + "1 0 0.1 0.9 0.1 0.9 0.001 0.99"); //P(WetGrass | Sprinkler, Rain) + + // Alternatively we can also create a DiscreteBayesNet, add DiscreteConditional + // factors and create a FactorGraph from it. (See testDiscreteBayesNet.cpp) + + // Since this is a relatively small distribution, we can as well print + // the whole distribution.. + cout << "Distribution of Example: " << endl; + cout << setw(11) << "Cloudy(C)" << setw(14) << "Sprinkler(S)" << setw(10) + << "Rain(R)" << setw(14) << "WetGrass(W)" << setw(15) << "P(C,S,R,W)" + << endl; + for (size_t a = 0; a < nrStates; a++) + for (size_t m = 0; m < nrStates; m++) + for (size_t h = 0; h < nrStates; h++) + for (size_t c = 0; c < nrStates; c++) { + DiscreteFactor::Values values; + values[Cloudy.first] = c; + values[Sprinkler.first] = h; + values[Rain.first] = m; + values[WetGrass.first] = a; + double prodPot = graph(values); + cout << boolalpha << setw(8) << (bool) c << setw(14) + << (bool) h << setw(12) << (bool) m << setw(13) + << (bool) a << setw(16) << prodPot << endl; + } + + + // "Most Probable Explanation", i.e., configuration with largest value + DiscreteSequentialSolver solver(graph); + DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + cout <<"\nMost Probable Explanation (MPE):" << endl; + cout << boolalpha << "Cloudy = " << (bool)(*optimalDecoding)[Cloudy.first] + << " Sprinkler = " << (bool)(*optimalDecoding)[Sprinkler.first] + << " Rain = " << boolalpha << (bool)(*optimalDecoding)[Rain.first] + << " WetGrass = " << (bool)(*optimalDecoding)[WetGrass.first]<< endl; + + + // "Inference" We show an inference query like: probability that the Sprinkler was on; + // given that the grass is wet i.e. P( S | W=1) =? + cout << "\nInference Query: Probability of Sprinkler being on given Grass is Wet" << endl; + + // Method 1: we can compute the joint marginal P(S,W) and from that we can compute + // P(S | W=1) = P(S,W=1)/P(W=1) We do this in following three steps.. + + //Step1: Compute P(S,W) + DiscreteFactorGraph jointFG; + jointFG = *solver.jointFactorGraph(DiscreteKeys(Sprinkler & WetGrass).indices()); + DecisionTreeFactor probSW = jointFG.product(); + + //Step2: Compute P(W) + DiscreteFactor::shared_ptr probW = solver.marginalFactor(WetGrass.first); + + //Step3: Computer P(S | W=1) = P(S,W=1)/P(W=1) + DiscreteFactor::Values values; + values[WetGrass.first] = 1; + + //print P(S=0|W=1) + values[Sprinkler.first] = 0; + cout << "P(S=0|W=1) = " << probSW(values)/(*probW)(values) << endl; + + //print P(S=1|W=1) + values[Sprinkler.first] = 1; + cout << "P(S=1|W=1) = " << probSW(values)/(*probW)(values) << endl; + + // TODO: Method 2 : One way is to modify the factor graph to + // incorporate the evidence node and compute the marginal + // TODO: graph.addEvidence(Cloudy,0); + + return 0; +} diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp new file mode 100644 index 000000000..dfe3d1e99 --- /dev/null +++ b/examples/LocalizationExample.cpp @@ -0,0 +1,159 @@ +/* ---------------------------------------------------------------------------- + + * 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 LocalizationExample.cpp + * @brief Simple robot localization example, with three "GPS-like" measurements + * @author Frank Dellaert + */ + +/** + * A simple 2D pose slam example with "GPS" measurements + * - The robot moves forward 2 meter each iteration + * - The robot initially faces along the X axis (horizontal, to the right in 2D) + * - We have full odometry between pose + * - We have "GPS-like" measurements implemented with a custom factor + */ + +// We will use Pose2 variables (x, y, theta) to represent the robot positions +#include + +// We will use simple integer Keys to refer to the robot poses. +#include + +// As in OdometryExample.cpp, we use a BetweenFactor to model odometry measurements. +#include + +// We add all facors to a Nonlinear Factor Graph, as our factors are nonlinear. +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// standard Levenberg-Marquardt solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +using namespace std; +using namespace gtsam; + +// Before we begin the example, we must create a custom unary factor to implement a +// "GPS-like" functionality. Because standard GPS measurements provide information +// only on the position, and not on the orientation, we cannot use a simple prior to +// properly model this measurement. +// +// The factor will be a unary factor, affect only a single system variable. It will +// also use a standard Gaussian noise model. Hence, we will derive our new factor from +// the NoiseModelFactor1. +#include + +class UnaryFactor: public NoiseModelFactor1 { + + // The factor will hold a measurement consisting of an (X,Y) location + // We could this with a Point2 but here we just use two doubles + double mx_, my_; + +public: + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + // The constructor requires the variable key, the (X, Y) measurement value, and the noise model + UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): + NoiseModelFactor1(model, j), mx_(x), my_(y) {} + + virtual ~UnaryFactor() {} + + // Using the NoiseModelFactor1 base class there are two functions that must be overridden. + // The first is the 'evaluateError' function. This function implements the desired measurement + // function, returning a vector of errors when evaluated at the provided variable value. It + // must also calculate the Jacobians for this measurement function, if requested. + Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const + { + // The measurement function for a GPS-like measurement is simple: + // error_x = pose.x - measurement.x + // error_y = pose.y - measurement.y + // Consequently, the Jacobians are: + // [ derror_x/dx derror_x/dy derror_x/dtheta ] = [1 0 0] + // [ derror_y/dx derror_y/dy derror_y/dtheta ] = [0 1 0] + if (H) (*H) = Matrix_(2,3, 1.0,0.0,0.0, 0.0,1.0,0.0); + return Vector_(2, q.x() - mx_, q.y() - my_); + } + + // The second is a 'clone' function that allows the factor to be copied. Under most + // circumstances, the following code that employs the default copy constructor should + // work fine. + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); } + + // Additionally, we encourage you the use of unit testing your custom factors, + // (as all GTSAM factors are), in which you would need an equals and print, to satisfy the + // GTSAM_CONCEPT_TESTABLE_INST(T) defined in Testable.h, but these are not needed below. + +}; // UnaryFactor + + +int main(int argc, char** argv) { + + // 1. Create a factor graph container and add factors to it + NonlinearFactorGraph graph; + + // 2a. Add odometry factors + // For simplicity, we will use the same noise model for each odometry factor + noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + // Create odometry (Between) factors between consecutive poses + graph.add(BetweenFactor(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise)); + graph.add(BetweenFactor(2, 3, Pose2(2.0, 0.0, 0.0), odometryNoise)); + + // 2b. Add "GPS-like" measurements + // We will use our custom UnaryFactor for this. + noiseModel::Diagonal::shared_ptr unaryNoise = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.1)); // 10cm std on x,y + graph.push_back(boost::make_shared(1, 0.0, 0.0, unaryNoise)); + graph.push_back(boost::make_shared(2, 2.0, 0.0, unaryNoise)); + graph.push_back(boost::make_shared(3, 4.0, 0.0, unaryNoise)); + graph.print("\nFactor Graph:\n"); // print + + // 3. Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initialEstimate; + initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); + initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2)); + initialEstimate.insert(3, Pose2(4.1, 0.1, 0.1)); + initialEstimate.print("\nInitial Estimate:\n"); // print + + // 4. Optimize using Levenberg-Marquardt optimization. The optimizer + // accepts an optional set of configuration parameters, controlling + // things like convergence criteria, the type of linear system solver + // to use, and the amount of information displayed during optimization. + // Here we will use the default set of parameters. See the + // documentation for the full set of parameters. + LevenbergMarquardtOptimizer optimizer(graph, initialEstimate); + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + + // 5. Calculate and print marginal covariances for all variables + Marginals marginals(graph, result); + cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; + cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; + cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; + + return 0; +} diff --git a/examples/OdometryExample.cpp b/examples/OdometryExample.cpp new file mode 100644 index 000000000..d556798f0 --- /dev/null +++ b/examples/OdometryExample.cpp @@ -0,0 +1,99 @@ +/* ---------------------------------------------------------------------------- + + * 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 OdometryExample.cpp + * @brief Simple robot motion example, with prior and two odometry measurements + * @author Frank Dellaert + */ + +/** + * Example of a simple 2D localization example + * - Robot poses are facing along the X axis (horizontal, to the right in 2D) + * - The robot moves 2 meters each step + * - We have full odometry between poses + */ + +// We will use Pose2 variables (x, y, theta) to represent the robot positions +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Between factors for the relative motion described by odometry measurements. +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// Levenberg-Marquardt solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // Create an empty nonlinear factor graph + NonlinearFactorGraph graph; + + // Add a prior on the first pose, setting it to the origin + // A prior factor consists of a mean and a noise model (covariance matrix) + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + graph.add(PriorFactor(1, priorMean, priorNoise)); + + // Add odometry factors + Pose2 odometry(2.0, 0.0, 0.0); + // For simplicity, we will use the same noise model for each odometry factor + noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + // Create odometry (Between) factors between consecutive poses + graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); + graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); + graph.print("\nFactor Graph:\n"); // print + + // Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initial; + initial.insert(1, Pose2(0.5, 0.0, 0.2)); + initial.insert(2, Pose2(2.3, 0.1, -0.2)); + initial.insert(3, Pose2(4.1, 0.1, 0.1)); + initial.print("\nInitial Estimate:\n"); // print + + // optimize using Levenberg-Marquardt optimization + Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + result.print("Final Result:\n"); + + // Calculate and print marginal covariances for all variables + cout.precision(2); + Marginals marginals(graph, result); + cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; + cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; + cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; + + return 0; +} diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp new file mode 100644 index 000000000..c6f6b636f --- /dev/null +++ b/examples/PlanarSLAMExample.cpp @@ -0,0 +1,142 @@ +/* ---------------------------------------------------------------------------- + + * 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 PlanarSLAMExample.cpp + * @brief Simple robotics example using odometry measurements and bearing-range (laser) measurements + * @author Alex Cunningham + */ + +/** + * A simple 2D planar slam example with landmarks + * - The robot and landmarks are on a 2 meter grid + * - Robot poses are facing along the X axis (horizontal, to the right in 2D) + * - The robot moves 2 meters each step + * - We have full odometry between poses + * - We have bearing and range information for measurements + * - Landmarks are 2 meters away from the robot trajectory + */ + +// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent +// the robot positions and Point2 variables (x, y) to represent the landmark coordinates. +#include +#include + +// Each variable in the system (poses and landmarks) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use Symbols +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use a RangeBearing factor for the range-bearing measurements to identified +// landmarks, and Between factors for the relative motion described by odometry measurements. +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// common Levenberg-Marquardt solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // Create a factor graph + NonlinearFactorGraph graph; + + // Create the keys we need for this simple example + static Symbol x1('x',1), x2('x',2), x3('x',3); + static Symbol l1('l',1), l2('l',2); + + // Add a prior on pose x1 at the origin. A prior factor consists of a mean and a noise model (covariance matrix) + Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta + graph.add(PriorFactor(x1, prior, 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) + noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta + graph.add(BetweenFactor(x1, x2, odometry, odometryNoise)); + graph.add(BetweenFactor(x2, x3, odometry, odometryNoise)); + + // Add Range-Bearing measurements to two different landmarks + // create a noise model for the landmark measurements + noiseModel::Diagonal::shared_ptr measurementNoise = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range + // create the measurement values - indices are (pose id, landmark id) + Rot2 bearing11 = Rot2::fromDegrees(45), + bearing21 = Rot2::fromDegrees(90), + bearing32 = Rot2::fromDegrees(90); + double range11 = std::sqrt(4.0+4.0), + range21 = 2.0, + range32 = 2.0; + + // Add Bearing-Range factors + graph.add(BearingRangeFactor(x1, l1, bearing11, range11, measurementNoise)); + graph.add(BearingRangeFactor(x2, l1, bearing21, range21, measurementNoise)); + graph.add(BearingRangeFactor(x3, l2, bearing32, range32, measurementNoise)); + + // Print + graph.print("Factor Graph:\n"); + + // Create (deliberately inaccurate) initial estimate + Values initialEstimate; + initialEstimate.insert(x1, Pose2(0.5, 0.0, 0.2)); + initialEstimate.insert(x2, Pose2(2.3, 0.1,-0.2)); + initialEstimate.insert(x3, Pose2(4.1, 0.1, 0.1)); + initialEstimate.insert(l1, Point2(1.8, 2.1)); + initialEstimate.insert(l2, Point2(4.1, 1.8)); + + // Print + initialEstimate.print("Initial Estimate:\n"); + + // Optimize using Levenberg-Marquardt optimization. The optimizer + // accepts an optional set of configuration parameters, controlling + // things like convergence criteria, the type of linear system solver + // to use, and the amount of information displayed during optimization. + // Here we will use the default set of parameters. See the + // documentation for the full set of parameters. + LevenbergMarquardtOptimizer optimizer(graph, initialEstimate); + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + + // Calculate and print marginal covariances for all variables + Marginals marginals(graph, result); + 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"); + + return 0; +} + diff --git a/examples/PlanarSLAMExample_easy.cpp b/examples/PlanarSLAMExample_easy.cpp deleted file mode 100644 index 912589080..000000000 --- a/examples/PlanarSLAMExample_easy.cpp +++ /dev/null @@ -1,91 +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 PlanarSLAMExample.cpp - * @brief Simple robotics example using the pre-built planar SLAM domain - * @author Alex Cunningham - */ - -#include -#include - -// pull in the planar SLAM domain with all typedefs and helper functions defined -#include -#include - -using namespace std; -using namespace gtsam; -using namespace planarSLAM; - -/** - * In this version of the system we make the following assumptions: - * - All values are axis aligned - * - Robot poses are facing along the X axis (horizontal, to the right in images) - * - We have bearing and range information for measurements - * - We have full odometry for measurements - * - The robot and landmarks are on a grid, moving 2 meters each step - * - Landmarks are 2 meters away from the robot trajectory - */ -int main(int argc, char** argv) { - - // create graph container and add factors to it - Graph 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 - graph.addPrior(1, prior_measurement, prior_model); // add directly to 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) - graph.addOdometry(1, 2, odom_measurement, odom_model); - graph.addOdometry(2, 3, odom_measurement, odom_model); - - /* add measurements */ - // general noisemodel for measurements - SharedDiagonal meas_model = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); - - // create the measurement values - indices are (pose id, landmark id) - Rot2 bearing11 = Rot2::fromDegrees(45), - bearing21 = Rot2::fromDegrees(90), - bearing32 = Rot2::fromDegrees(90); - double range11 = sqrt(4+4), - range21 = 2.0, - range32 = 2.0; - - // create bearing/range factors and add them - graph.addBearingRange(1, 1, bearing11, range11, meas_model); - graph.addBearingRange(2, 1, bearing21, range21, meas_model); - graph.addBearingRange(3, 2, bearing32, range32, meas_model); - - graph.print("full graph"); - - // initialize to noisy points - 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.print("initial estimate"); - - // optimize using Levenberg-Marquardt optimization with an ordering from colamd - planarSLAM::Values result = LevenbergMarquardtOptimizer(graph, initialEstimate).optimize(); - result.print("final result"); - - return 0; -} - diff --git a/examples/PlanarSLAMSelfContained_advanced.cpp b/examples/PlanarSLAMSelfContained_advanced.cpp deleted file mode 100644 index bd5c5295a..000000000 --- a/examples/PlanarSLAMSelfContained_advanced.cpp +++ /dev/null @@ -1,137 +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 PlanarSLAMSelfContained_advanced.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 - -// implementations for structures - needed if self-contained, and these should be included last -#include -#include -#include - -using namespace std; -using namespace gtsam; - -/** - * In this version of the system we make the following assumptions: - * - All values are axis aligned - * - Robot poses are facing along the X axis (horizontal, to the right in images) - * - We have bearing and range information for measurements - * - We have full odometry for measurements - * - The robot and landmarks are on a grid, moving 2 meters each step - * - Landmarks are 2 meters away from the robot trajectory - */ -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); - - // 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 - 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) - // create between factors to represent odometry - BetweenFactor odom12(x1, x2, odom_measurement, odom_model); - BetweenFactor odom23(x2, x3, odom_measurement, odom_model); - graph.add(odom12); // add both to graph - graph.add(odom23); - - /* add measurements */ - // general noisemodel for measurements - SharedDiagonal meas_model = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); - - // create the measurement values - indices are (pose id, landmark id) - Rot2 bearing11 = Rot2::fromDegrees(45), - bearing21 = Rot2::fromDegrees(90), - bearing32 = Rot2::fromDegrees(90); - double range11 = sqrt(4+4), - range21 = 2.0, - 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); - - // add the factors - graph.add(meas11); - graph.add(meas21); - graph.add(meas32); - - graph.print("Full Graph"); - - // 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.print("initial estimate"); - - // optimize using Levenberg-Marquardt optimization with an ordering from colamd - - // first using sequential elimination - LevenbergMarquardtParams lmParams; - lmParams.elimination = LevenbergMarquardtParams::SEQUENTIAL; - Values resultSequential = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize(); - resultSequential.print("final result (solved with a sequential solver)"); - - // then using multifrontal, advanced interface - // Note that we keep the original optimizer object so we can use the COLAMD - // ordering it computes. - LevenbergMarquardtOptimizer optimizer(graph, initial); - Values resultMultifrontal = optimizer.optimize(); - resultMultifrontal.print("final result (solved with a multifrontal solver)"); - - // 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"); - - return 0; -} - diff --git a/examples/Pose2SLAMExample.cpp b/examples/Pose2SLAMExample.cpp new file mode 100644 index 000000000..4885e72c8 --- /dev/null +++ b/examples/Pose2SLAMExample.cpp @@ -0,0 +1,130 @@ +/* ---------------------------------------------------------------------------- + + * 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.cpp + * @brief A 2D Pose SLAM example + * @date Oct 21, 2010 + * @author Yong Dian Jian + */ + +/** + * A simple 2D pose slam example + * - The robot moves in a 2 meter square + * - The robot moves 2 meters each step, turning 90 degrees after each step + * - The robot initially faces along the X axis (horizontal, to the right in 2D) + * - We have full odometry between pose + * - We have a loop closure constraint when the robot returns to the first position + */ + +// In planar SLAM example we use Pose2 variables (x, y, theta) to represent the robot poses +#include + +// We will use simple integer Keys to refer to the robot poses. +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Between factors for the relative motion described by odometry measurements. +// We will also use a Between Factor to encode the loop closure constraint +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// a Gauss-Newton solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // 1. Create a factor graph container and add factors to it + NonlinearFactorGraph graph; + + // 2a. Add a prior on the first pose, setting it to the origin + // A prior factor consists of a mean and a noise model (covariance matrix) + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + graph.add(PriorFactor(1, Pose2(0, 0, 0), priorNoise)); + + // For simplicity, we will use the same noise model for odometry and loop closures + noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + + // 2b. Add odometry factors + // Create odometry (Between) factors between consecutive poses + graph.add(BetweenFactor(1, 2, Pose2(2, 0, 0 ), model)); + graph.add(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model)); + graph.add(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model)); + graph.add(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model)); + + // 2c. Add the loop closure constraint + // This factor encodes the fact that we have returned to the same pose. In real systems, + // these constraints may be identified in many ways, such as appearance-based techniques + // with camera images. We will use another Between Factor to enforce this constraint: + graph.add(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model)); + graph.print("\nFactor Graph:\n"); // print + + // 3. Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initialEstimate; + initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 )); + initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2 )); + initialEstimate.insert(3, Pose2(4.1, 0.1, M_PI_2)); + initialEstimate.insert(4, Pose2(4.0, 2.0, M_PI )); + initialEstimate.insert(5, Pose2(2.1, 2.1, -M_PI_2)); + initialEstimate.print("\nInitial Estimate:\n"); // print + + // 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer + // The optimizer accepts an optional set of configuration parameters, + // controlling things like convergence criteria, the type of linear + // system solver to use, and the amount of information displayed during + // optimization. We will set a few parameters as a demonstration. + GaussNewtonParams parameters; + // Stop iterating once the change in error between steps is less than this value + parameters.relativeErrorTol = 1e-5; + // Do not perform more than N iteration steps + parameters.maxIterations = 100; + // Create the optimizer ... + GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters); + // ... and optimize + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + + // 5. Calculate and print marginal covariances for all variables + cout.precision(3); + Marginals marginals(graph, result); + cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; + cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; + cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; + cout << "x4 covariance:\n" << marginals.marginalCovariance(4) << endl; + cout << "x5 covariance:\n" << marginals.marginalCovariance(5) << endl; + + return 0; +} diff --git a/examples/Pose2SLAMExample_advanced.cpp b/examples/Pose2SLAMExample_advanced.cpp deleted file mode 100644 index 29d8c58cf..000000000 --- a/examples/Pose2SLAMExample_advanced.cpp +++ /dev/null @@ -1,88 +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 Pose2SLAMExample_advanced.cpp - * @brief Simple Pose2SLAM Example using - * pre-built pose2SLAM domain - * @author Chris Beall - */ - -#include -#include -#include - -// pull in the Pose2 SLAM domain with all typedefs and helper functions defined -#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; - - /* 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 - - /* 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); - graph.print("full graph"); - - /* 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(3, Pose2(4.1, 0.1, 0.1)); - initial.print("initial estimate"); - - /* 4.2.1 Alternatively, you can go through the process step by step - * Choose an ordering */ - Ordering ordering = *graph.orderingCOLAMD(initial); - - /* 4.2.2 set up solver and optimize */ - LevenbergMarquardtParams params; - params.absoluteErrorTol = 1e-15; - params.relativeErrorTol = 1e-15; - params.ordering = ordering; - 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)); - - print(covariance1, "Covariance1"); - print(covariance2, "Covariance2"); - - return 0; -} - diff --git a/examples/Pose2SLAMExample_easy.cpp b/examples/Pose2SLAMExample_easy.cpp deleted file mode 100644 index 18a756aba..000000000 --- a/examples/Pose2SLAMExample_easy.cpp +++ /dev/null @@ -1,69 +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 Pose2SLAMExample_easy.cpp - * - * A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h - * - * @date Oct 21, 2010 - * @author ydjian - */ - -#include -#include -#include - -// pull in the Pose2 SLAM domain with all typedefs and helper functions defined -#include -#include - -using namespace std; -using namespace gtsam; -using namespace pose2SLAM; - -int main(int argc, char** argv) { - - /* 1. create graph container and add factors to it */ - 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 - - /* 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); - graph.print("full graph"); - - /* 3. Create the data structure to hold the initial estinmate 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(3, Pose2(4.1, 0.1, 0.1)); - initial.print("initial estimate"); - - /* 4 Single Step Optimization - * optimize using Levenberg-Marquardt optimization with an ordering from colamd */ - pose2SLAM::Values result = graph.optimize(initial); - result.print("final result"); - - - return 0; -} diff --git a/examples/Pose2SLAMExample_graph.cpp b/examples/Pose2SLAMExample_graph.cpp new file mode 100644 index 000000000..cc873eb08 --- /dev/null +++ b/examples/Pose2SLAMExample_graph.cpp @@ -0,0 +1,57 @@ +/* ---------------------------------------------------------------------------- + + * 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 +#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 + NonlinearFactorGraph::shared_ptr graph ; + Values::shared_ptr initial; + SharedDiagonal model = noiseModel::Diagonal::Sigmas(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 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.01, 0.01, 0.01)); + graph->add(PriorFactor(0, priorMean, priorNoise)); + + // Single Step Optimization using Levenberg-Marquardt + Values result = LevenbergMarquardtOptimizer(*graph, *initial).optimize(); + 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..36f2552a1 --- /dev/null +++ b/examples/Pose2SLAMwSPCG.cpp @@ -0,0 +1,118 @@ +/* ---------------------------------------------------------------------------- + + * 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 + */ + +/** + * A simple 2D pose slam example solved using a Conjugate-Gradient method + * - The robot moves in a 2 meter square + * - The robot moves 2 meters each step, turning 90 degrees after each step + * - The robot initially faces along the X axis (horizontal, to the right in 2D) + * - We have full odometry between pose + * - We have a loop closure constraint when the robot returns to the first position + */ + +// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent +// the robot positions +#include +#include + +// Each variable in the system (poses) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use simple integer keys +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Between factors for the relative motion described by odometry measurements. +// We will also use a Between Factor to encode the loop closure constraint +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // 1. Create a factor graph container and add factors to it + NonlinearFactorGraph graph; + + // 2a. Add a prior on the first pose, setting it to the origin + // A prior factor consists of a mean and a noise model (covariance matrix) + Pose2 prior(0.0, 0.0, 0.0); // prior at origin + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + graph.add(PriorFactor(1, prior, priorNoise)); + + // 2b. Add odometry factors + // For simplicity, we will use the same noise model for each odometry factor + noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + // Create odometry (Between) factors between consecutive poses + graph.add(BetweenFactor(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + graph.add(BetweenFactor(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + graph.add(BetweenFactor(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + graph.add(BetweenFactor(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + + // 2c. Add the loop closure constraint + // This factor encodes the fact that we have returned to the same pose. In real systems, + // these constraints may be identified in many ways, such as appearance-based techniques + // with camera images. + // We will use another Between Factor to enforce this constraint, with the distance set to zero, + noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + graph.add(BetweenFactor(5, 1, Pose2(0.0, 0.0, 0.0), model)); + graph.print("\nFactor Graph:\n"); // print + + + // 3. Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initialEstimate; + initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); + initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1)); + initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8)); + initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2)); + initialEstimate.insert(5, Pose2(0.1,-0.7, 5.8)); + initialEstimate.print("\nInitial Estimate:\n"); // print + + // 4. Single Step Optimization using Levenberg-Marquardt + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::ERROR; + parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA; + parameters.linearSolverType = SuccessiveLinearizationParams::CONJUGATE_GRADIENT; + + { + parameters.iterativeParams = boost::make_shared(); + LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + cout << "subgraph solver 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/SimpleRotation.cpp b/examples/SimpleRotation.cpp index 603d345bf..cff9d754e 100644 --- a/examples/SimpleRotation.cpp +++ b/examples/SimpleRotation.cpp @@ -17,20 +17,41 @@ * @author Alex Cunningham */ -#include -#include -#include + /** + * This example will perform a relatively trivial optimization on + * a single variable with a single factor. + */ + +// In this example, a 2D rotation will be used as the variable of interest #include -#include + +// Each variable in the system (poses) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use symbols #include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// We will apply a simple prior on the rotation +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. #include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// standard Levenberg-Marquardt solver #include -/* - * TODO: make factors independent of RotValues - * TODO: make toplevel documentation - * TODO: Clean up nonlinear optimization API - */ using namespace std; using namespace gtsam; @@ -40,12 +61,7 @@ const double degree = M_PI / 180; int main() { /** - * This example will perform a relatively trivial optimization on - * a single variable with a single factor. - */ - - /** - * Step 1: create a factor on to express a unary constraint + * Step 1: Create a factor to express a unary constraint * The "prior" in this case is the measurement from a sensor, * with a model of the noise on the measurement. * @@ -60,12 +76,12 @@ int main() { */ Rot2 prior = Rot2::fromAngle(30 * degree); prior.print("goal angle"); - SharedDiagonal model = noiseModel::Isotropic::Sigma(1, 1 * degree); + noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(1, 1 * degree); Symbol key('x',1); PriorFactor factor(key, prior, model); /** - * Step 2: create a graph container and add the factor to it + * Step 2: Create a graph container and add the factor to it * Before optimizing, all factors need to be added to a Graph container, * which provides the necessary top-level functionality for defining a * system of constraints. @@ -78,7 +94,7 @@ int main() { graph.print("full graph"); /** - * Step 3: create an initial estimate + * Step 3: Create an initial estimate * An initial estimate of the solution for the system is necessary to * start optimization. This system state is the "RotValues" structure, * which is similar in structure to a STL map, in that it maps @@ -98,7 +114,7 @@ int main() { initial.print("initial estimate"); /** - * Step 4: optimize + * Step 4: Optimize * After formulating the problem with a graph of constraints * and an initial estimate, executing optimization is as simple * as calling a general optimization function with the graph and diff --git a/examples/UGM_chain.cpp b/examples/UGM_chain.cpp new file mode 100644 index 000000000..56dbd4726 --- /dev/null +++ b/examples/UGM_chain.cpp @@ -0,0 +1,114 @@ +/* ---------------------------------------------------------------------------- + + * 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 small.cpp + * @brief UGM (undirected graphical model) examples: chain + * @author Frank Dellaert + * @author Abhijit Kundu + * + * See http://www.di.ens.fr/~mschmidt/Software/UGM/chain.html + * for more explanation. This code demos the same example using GTSAM. + */ + +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // Set Number of Nodes in the Graph + const int nrNodes = 60; + + // Each node takes 1 of 7 possible states denoted by 0-6 in following order: + // ["VideoGames" "Industry" "GradSchool" "VideoGames(with PhD)" + // "Industry(with PhD)" "Academia" "Deceased"] + const size_t nrStates = 7; + + // define variables + vector nodes; + for (int i = 0; i < nrNodes; i++){ + DiscreteKey dk(i, nrStates); + nodes.push_back(dk); + } + + // create graph + DiscreteFactorGraph graph; + + // add node potentials + graph.add(nodes[0], ".3 .6 .1 0 0 0 0"); + for (int i = 1; i < nrNodes; i++) + graph.add(nodes[i], "1 1 1 1 1 1 1"); + + const std::string edgePotential = ".08 .9 .01 0 0 0 .01 " + ".03 .95 .01 0 0 0 .01 " + ".06 .06 .75 .05 .05 .02 .01 " + "0 0 0 .3 .6 .09 .01 " + "0 0 0 .02 .95 .02 .01 " + "0 0 0 .01 .01 .97 .01 " + "0 0 0 0 0 0 1"; + + // add edge potentials + for (int i = 0; i < nrNodes - 1; i++) + graph.add(nodes[i] & nodes[i + 1], edgePotential); + + cout << "Created Factor Graph with " << nrNodes << " variable nodes and " + << graph.size() << " factors (Unary+Edge)."; + + // "Decoding", i.e., configuration with largest value + // We use sequential variable elimination + DiscreteSequentialSolver solver(graph); + DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + optimalDecoding->print("\nMost Probable Explanation (optimalDecoding)\n"); + + // "Inference" Computing marginals for each node + + + cout << "\nComputing Node Marginals ..(Sequential Elimination)" << endl; + tic_(1, "Sequential"); + for (vector::iterator itr = nodes.begin(); itr != nodes.end(); + ++itr) { + //Compute the marginal + Vector margProbs = solver.marginalProbabilities(*itr); + + //Print the marginals + cout << "Node#" << setw(4) << itr->first << " : "; + print(margProbs); + } + toc_(1, "Sequential"); + + // Here we'll make use of DiscreteMarginals class, which makes use of + // bayes-tree based shortcut evaluation of marginals + DiscreteMarginals marginals(graph); + + cout << "\nComputing Node Marginals ..(BayesTree based)" << endl; + tic_(2, "Multifrontal"); + for (vector::iterator itr = nodes.begin(); itr != nodes.end(); + ++itr) { + //Compute the marginal + Vector margProbs = marginals.marginalProbabilities(*itr); + + //Print the marginals + cout << "Node#" << setw(4) << itr->first << " : "; + print(margProbs); + } + toc_(2, "Multifrontal"); + + tictoc_print_(); + return 0; +} + diff --git a/examples/UGM_small.cpp b/examples/UGM_small.cpp index a4655d2ad..e9424d369 100644 --- a/examples/UGM_small.cpp +++ b/examples/UGM_small.cpp @@ -49,26 +49,38 @@ int main(int argc, char** argv) { // Print the UGM distribution cout << "\nUGM distribution:" << endl; - for (size_t a = 0; a < nrStates; a++) - for (size_t m = 0; m < nrStates; m++) - for (size_t h = 0; h < nrStates; h++) - for (size_t c = 0; c < nrStates; c++) { - DiscreteFactor::Values values; - values[1] = c; - values[2] = h; - values[3] = m; - values[4] = a; - double prodPot = graph(values); - cout << c << " " << h << " " << m << " " << a << " :\t" - << prodPot << "\t" << prodPot/3790 << endl; - } + vector allPosbValues = cartesianProduct( + Cathy & Heather & Mark & Allison); + for (size_t i = 0; i < allPosbValues.size(); ++i) { + DiscreteFactor::Values values = allPosbValues[i]; + double prodPot = graph(values); + cout << values[Cathy.first] << " " << values[Heather.first] << " " + << values[Mark.first] << " " << values[Allison.first] << " :\t" + << prodPot << "\t" << prodPot / 3790 << endl; + } - // "Decoding", i.e., configuration with largest value + // "Decoding", i.e., configuration with largest value (MPE) // We use sequential variable elimination DiscreteSequentialSolver solver(graph); DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); optimalDecoding->print("\noptimalDecoding"); + // "Inference" Computing marginals + cout << "\nComputing Node Marginals .." << endl; + Vector margProbs; + + margProbs = solver.marginalProbabilities(Cathy); + print(margProbs, "Cathy's Node Marginal:"); + + margProbs = solver.marginalProbabilities(Heather); + print(margProbs, "Heather's Node Marginal"); + + margProbs = solver.marginalProbabilities(Mark); + print(margProbs, "Mark's Node Marginal"); + + margProbs = solver.marginalProbabilities(Allison); + print(margProbs, "Allison's Node Marginal"); + return 0; } diff --git a/examples/VisualISAM2Example.cpp b/examples/VisualISAM2Example.cpp new file mode 100644 index 000000000..1485da1e4 --- /dev/null +++ b/examples/VisualISAM2Example.cpp @@ -0,0 +1,159 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualISAM2Example.cpp + * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset + * This version uses iSAM2 to solve the problem incrementally + * @author Duy-Nguyen Ta + */ + +/** + * A structure-from-motion example with landmarks + * - The landmarks form a 10 meter cube + * - The robot rotates around the landmarks, always facing towards the cube + */ + +// As this is a full 3D problem, we will use Pose3 variables to represent the camera +// positions and Point3 variables (x, y, z) to represent the landmark coordinates. +// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). +// We will also need a camera object to hold calibration information and perform projections. +#include +#include +#include +#include + +// Each variable in the system (poses and landmarks) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use Symbols +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Projection factors to model the camera's landmark observations. +// Also, we will initialize the robot at some location using a Prior factor. +#include +#include + +// We want to use iSAM2 to solve the structure-from-motion problem incrementally, so +// include iSAM2 here +#include + +// iSAM2 requires as input a set set of new factors to be added stored in a factor graph, +// and initial guesses for any new variables used in the added factors +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + // Define the camera calibration parameters + Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + // Define the camera observation noise model + noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + + // Create the set of ground-truth landmarks + std::vector points; + points.push_back(gtsam::Point3(10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + + // Create the set of ground-truth poses + std::vector poses; + double radius = 30.0; + int i = 0; + double theta = 0.0; + gtsam::Point3 up(0,0,1); + gtsam::Point3 target(0,0,0); + for(; i < 8; ++i, theta += 2*M_PI/8) { + gtsam::Point3 position = Point3(radius*cos(theta), radius*sin(theta), 0.0); + gtsam::SimpleCamera camera = SimpleCamera::Lookat(position, target, up); + poses.push_back(camera.pose()); + } + + // Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization + // and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter + // structure is available that allows the user to set various properties, such as the relinearization threshold + // and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result + // will approach the batch result. + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.01; + parameters.relinearizeSkip = 1; + ISAM2 isam(parameters); + + // Create a Factor Graph and Values to hold the new data + NonlinearFactorGraph graph; + Values initialEstimate; + + // Loop over the different poses, adding the observations to iSAM incrementally + for (size_t i = 0; i < poses.size(); ++i) { + + // Add factors for each landmark observation + for (size_t j = 0; j < points.size(); ++j) { + SimpleCamera camera(poses[i], *K); + Point2 measurement = camera.project(points[j]); + graph.add(GenericProjectionFactor(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K)); + } + + // Add an initial guess for the current pose + // Intentionally initialize the variables off from the ground truth + initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)))); + + // If this is the first iteration, add a prior on the first pose to set the coordinate frame + // and a prior on the first landmark to set the scale + // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + // adding it to iSAM. + if( i == 0) { + // Add a prior on pose x0 + noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(Vector_(6, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1)); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.add(PriorFactor(Symbol('x', 0), poses[0], poseNoise)); + + // Add a prior on landmark l0 + noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1); + graph.add(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // add directly to graph + + // Add initial guesses to all observed landmarks + // Intentionally initialize the variables off from the ground truth + for (size_t j = 0; j < points.size(); ++j) + initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15))); + + } else { + // Update iSAM with the new factors + isam.update(graph, initialEstimate); + // Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + // If accuracy is desired at the expense of time, update(*) can be called additional times + // to perform multiple optimizer iterations every step. + isam.update(); + Values currentEstimate = isam.calculateEstimate(); + cout << "****************************************************" << endl; + cout << "Frame " << i << ": " << endl; + currentEstimate.print("Current estimate: "); + + // Clear the factor graph and values for the next iteration + graph.resize(0); + initialEstimate.clear(); + } + } + + return 0; +} +/* ************************************************************************* */ diff --git a/examples/VisualISAMExample.cpp b/examples/VisualISAMExample.cpp new file mode 100644 index 000000000..832a2ab83 --- /dev/null +++ b/examples/VisualISAMExample.cpp @@ -0,0 +1,149 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualISAMExample.cpp + * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset + * This version uses iSAM to solve the problem incrementally + * @author Duy-Nguyen Ta + */ + +/** + * A structure-from-motion example with landmarks + * - The landmarks form a 10 meter cube + * - The robot rotates around the landmarks, always facing towards the cube + */ + +// As this is a full 3D problem, we will use Pose3 variables to represent the camera +// positions and Point3 variables (x, y, z) to represent the landmark coordinates. +// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). +// We will also need a camera object to hold calibration information and perform projections. +#include +#include +#include +#include + +// Each variable in the system (poses and landmarks) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use Symbols +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Projection factors to model the camera's landmark observations. +// Also, we will initialize the robot at some location using a Prior factor. +#include +#include + +// We want to use iSAM to solve the structure-from-motion problem incrementally, so +// include iSAM here +#include + +// iSAM requires as input a set set of new factors to be added stored in a factor graph, +// and initial guesses for any new variables used in the added factors +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + // Define the camera calibration parameters + Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + // Define the camera observation noise model + noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + + // Create the set of ground-truth landmarks + std::vector points; + points.push_back(gtsam::Point3(10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + + // Create the set of ground-truth poses + std::vector poses; + double radius = 30.0; + int i = 0; + double theta = 0.0; + gtsam::Point3 up(0,0,1); + gtsam::Point3 target(0,0,0); + for(; i < 8; ++i, theta += 2*M_PI/8) { + gtsam::Point3 position = Point3(radius*cos(theta), radius*sin(theta), 0.0); + gtsam::SimpleCamera camera = SimpleCamera::Lookat(position, target, up); + poses.push_back(camera.pose()); + } + + // Create a NonlinearISAM object which will relinearize and reorder the variables every "relinearizeInterval" updates + int relinearizeInterval = 3; + NonlinearISAM isam(relinearizeInterval); + + // Create a Factor Graph and Values to hold the new data + NonlinearFactorGraph graph; + Values initialEstimate; + + // Loop over the different poses, adding the observations to iSAM incrementally + for (size_t i = 0; i < poses.size(); ++i) { + + // Add factors for each landmark observation + for (size_t j = 0; j < points.size(); ++j) { + SimpleCamera camera(poses[i], *K); + Point2 measurement = camera.project(points[j]); + graph.add(GenericProjectionFactor(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K)); + } + + // Add an initial guess for the current pose + // Intentionally initialize the variables off from the ground truth + initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)))); + + // If this is the first iteration, add a prior on the first pose to set the coordinate frame + // and a prior on the first landmark to set the scale + // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + // adding it to iSAM. + if( i == 0) { + // Add a prior on pose x0 + noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(Vector_(6, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1)); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.add(PriorFactor(Symbol('x', 0), poses[0], poseNoise)); + + // Add a prior on landmark l0 + noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1); + graph.add(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // add directly to graph + + // Add initial guesses to all observed landmarks + // Intentionally initialize the variables off from the ground truth + for (size_t j = 0; j < points.size(); ++j) + initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15))); + + } else { + // Update iSAM with the new factors + isam.update(graph, initialEstimate); + Values currentEstimate = isam.estimate(); + cout << "****************************************************" << endl; + cout << "Frame " << i << ": " << endl; + currentEstimate.print("Current estimate: "); + + // Clear the factor graph and values for the next iteration + graph.resize(0); + initialEstimate.clear(); + } + } + + return 0; +} +/* ************************************************************************* */ diff --git a/examples/VisualSLAMExample.cpp b/examples/VisualSLAMExample.cpp new file mode 100644 index 000000000..8aed051eb --- /dev/null +++ b/examples/VisualSLAMExample.cpp @@ -0,0 +1,139 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualSLAMExample.cpp + * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset + * @author Duy-Nguyen Ta + */ + +/** + * A structure-from-motion example with landmarks + * - The landmarks form a 10 meter cube + * - The robot rotates around the landmarks, always facing towards the cube + */ + +// As this is a full 3D problem, we will use Pose3 variables to represent the camera +// positions and Point3 variables (x, y, z) to represent the landmark coordinates. +// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). +// We will also need a camera object to hold calibration information and perform projections. +#include +#include +#include +#include + +// Each variable in the system (poses and landmarks) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use Symbols +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Projection factors to model the camera's landmark observations. +// Also, we will initialize the robot at some location using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use a +// trust-region method known as Powell's Degleg +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + // Define the camera calibration parameters + Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + // Define the camera observation noise model + noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + + // Create the set of ground-truth landmarks + std::vector points; + points.push_back(gtsam::Point3(10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,10.0)); + points.push_back(gtsam::Point3(10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + points.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + points.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + + // Create the set of ground-truth poses + std::vector poses; + double radius = 30.0; + int i = 0; + double theta = 0.0; + gtsam::Point3 up(0,0,1); + gtsam::Point3 target(0,0,0); + for(; i < 8; ++i, theta += 2*M_PI/8) { + gtsam::Point3 position = Point3(radius*cos(theta), radius*sin(theta), 0.0); + gtsam::SimpleCamera camera = SimpleCamera::Lookat(position, target, up); + poses.push_back(camera.pose()); + } + + // Create a factor graph + NonlinearFactorGraph graph; + + // Add a prior on pose x1. This indirectly specifies where the origin is. + noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(Vector_(6, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1)); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.add(PriorFactor(Symbol('x', 0), poses[0], poseNoise)); // add directly to graph + + // Simulated measurements from each camera pose, adding them to the factor graph + for (size_t i = 0; i < poses.size(); ++i) { + for (size_t j = 0; j < points.size(); ++j) { + SimpleCamera camera(poses[i], *K); + Point2 measurement = camera.project(points[j]); + graph.add(GenericProjectionFactor(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K)); + } + } + + // Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained + // Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance + // between the first camera and the first landmark. All other landmark positions are interpreted using this scale. + noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1); + graph.add(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // add directly to graph + graph.print("Factor Graph:\n"); + + // Create the data structure to hold the initialEstimate estimate to the solution + // Intentionally initialize the variables off from the ground truth + Values initialEstimate; + for (size_t i = 0; i < poses.size(); ++i) + initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)))); + for (size_t j = 0; j < points.size(); ++j) + initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15))); + initialEstimate.print("Initial Estimates:\n"); + + /* Optimize the graph and print results */ + Values result = DoglegOptimizer(graph, initialEstimate).optimize(); + result.print("Final results:\n"); + + return 0; +} +/* ************************************************************************* */ + diff --git a/examples/easyPoint2KalmanFilter.cpp b/examples/easyPoint2KalmanFilter.cpp index b13058a07..6d75e9149 100644 --- a/examples/easyPoint2KalmanFilter.cpp +++ b/examples/easyPoint2KalmanFilter.cpp @@ -21,7 +21,8 @@ * @author Stephen Williams */ -#include +#include +#include #include #include #include diff --git a/examples/matlab/PlanarSLAMExample_easy.m b/examples/matlab/PlanarSLAMExample_easy.m deleted file mode 100644 index 54462732b..000000000 --- a/examples/matlab/PlanarSLAMExample_easy.m +++ /dev/null @@ -1,75 +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 -% -% @brief Simple robotics example using the pre-built planar SLAM domain -% @author Alex Cunningham -% @author Frank Dellaert -%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% - -%% Assumptions -% - All values are axis aligned -% - Robot poses are facing along the X axis (horizontal, to the right in images) -% - We have bearing and range information for measurements -% - We have full odometry for measurements -% - The robot and landmarks are on a grid, moving 2 meters each step -% - Landmarks are 2 meters away from the robot trajectory - -%% Create keys for variables -x1 = 1; x2 = 2; x3 = 3; -l1 = 1; l2 = 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 - -%% 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); - -%% Add measurements -% general noisemodel for measurements -meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]); - -% create the measurement values - indices are (pose id, landmark id) -degrees = pi/180; -bearing11 = gtsamRot2(45*degrees); -bearing21 = gtsamRot2(90*degrees); -bearing32 = gtsamRot2(90*degrees); -range11 = sqrt(4+4); -range21 = 2.0; -range32 = 2.0; - -% % create bearing/range factors and add them -graph.addBearingRange(x1, l1, bearing11, range11, meas_model); -graph.addBearingRange(x2, l1, bearing21, range21, meas_model); -graph.addBearingRange(x3, l2, bearing32, range32, meas_model); - -% print -graph.print('full graph'); - -%% Initialize to noisy points -initialEstimate = planarSLAMValues; -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.insertPoint(l1, gtsamPoint2(1.8, 2.1)); -initialEstimate.insertPoint(l2, gtsamPoint2(4.1, 1.8)); - -initialEstimate.print('initial estimate'); - -%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd -result = graph.optimize(initialEstimate); -result.print('final result'); diff --git a/examples/matlab/Pose2SLAMExample_easy.m b/examples/matlab/Pose2SLAMExample_easy.m deleted file mode 100644 index 6c359f314..000000000 --- a/examples/matlab/Pose2SLAMExample_easy.m +++ /dev/null @@ -1,57 +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 -% -% @brief Simple robotics example using the pre-built planar SLAM domain -% @author Alex Cunningham -% @author Frank Dellaert -% @author Chris Beall -%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% - -%% Assumptions -% - All values are axis aligned -% - Robot poses are facing along the X axis (horizontal, to the right in images) -% - 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 - -%% 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); - -%% Add measurements -% general noisemodel for measurements -meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]); - -% print -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.print('initial estimate'); - -%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd -result = graph.optimize(initialEstimate); -result.print('final result'); diff --git a/examples/vSLAMexample/CMakeLists.txt b/examples/vSLAMexample/CMakeLists.txt deleted file mode 100644 index 57fd6bf6d..000000000 --- a/examples/vSLAMexample/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -# Build vSLAMexample - -message(STATUS "Adding Example vISAMexample") -add_executable(vISAMexample vISAMexample.cpp vSLAMutils.cpp) -target_link_libraries(vISAMexample gtsam-static) -add_dependencies(examples vISAMexample) - -message(STATUS "Adding Example vSFMexample") -add_executable(vSFMexample vSFMexample.cpp vSLAMutils.cpp) -target_link_libraries(vSFMexample gtsam-static) -add_dependencies(examples vSFMexample) - - - 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 edd745676..000000000 --- a/examples/vSLAMexample/vISAMexample.cpp +++ /dev/null @@ -1,147 +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(shared_ptr& newFactors, boost::shared_ptr& initialValues, - const Values& currentEstimate, int pose_id, const Pose3& pose, - const std::vector& measurements, SharedNoiseModel measurementSigma, shared_ptrK calib) { - - // Create a graph of newFactors with new measurements - newFactors = 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); - } - - // Add prior on the first pose - if(pose_id == 0) - newFactors->addPosePrior(pose_id, Pose3(), poseSigma); - - // Create initial values for all new variables and add priors on new landmarks - initialValues = shared_ptr (new Values()); - initialValues->insert(PoseKey(pose_id), pose); - for (size_t i = 0; i < measurements.size(); i++) { - if(!currentEstimate.exists(PointKey(measurements[i].m_idLandmark))) { - initialValues->insert(PointKey(measurements[i].m_idLandmark), g_landmarks[measurements[i].m_idLandmark]); - newFactors->addPointPrior(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; - Values currentEstimate = isam.estimate(); - BOOST_FOREACH(const FeatureMap::value_type& features, g_measurements) { - const int poseId = features.first; - shared_ptr newFactors; - shared_ptr initialValues; - createNewFactors(newFactors, initialValues, currentEstimate, poseId, g_poses[poseId], - features.second, measurementSigma, g_calib); - - isam.update(*newFactors, *initialValues); - 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 18c8921cb..88efe7618 100644 --- a/gtsam.h +++ b/gtsam.h @@ -6,285 +6,1045 @@ * * Requirements: * Classes must start with an uppercase letter - * Only one Method/Constructor per line + * - Can wrap a typedef + * Only one Method/Constructor per line, though methods/constructors can extend across multiple lines * 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, unsigned char * - void * - Any class with which be copied with boost::make_shared() * - boost::shared_ptr of any object type - * Limitations on methods - * - Parsing does not support overloading - * - There can only be one method with a given name + * Constructors + * - Overloads are supported + * - A class with no constructors can be returned from other functions but not allocated directly in MATLAB + * Methods + * - Constness has no effect + * - Specify by-value (not reference) return types, even if C++ method returns reference + * - Must start with a lowercase letter + * - Overloads are supported + * Static methods + * - Must start with a letter (upper or lowercase) and use the "static" keyword + * - The first letter will be made uppercase in the generated MATLAB interface + * - Overloads are supported * 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, unsigned 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 * Namespace definitions * - Names of namespaces must start with a lowercase letter * - start a namespace with "namespace {" - * - end a namespace with exactly "}///\namespace [namespace_name]", optionally adding the name of the namespace - * - This ending is not C++ standard, and must contain "}///\namespace" to parse + * - end a namespace with exactly "}" * - Namespaces can be nested * Namespace usage * - Namespaces can be specified for classes in arguments and return values * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" - * Using namespace - * - To use a namespace (e.g., generate a "using namespace x" line in cpp files), add "using namespace x;" - * - This declaration applies to all classes *after* the declaration, regardless of brackets - * Methods must start with a lowercase letter - * Static methods must start with a letter (upper or lowercase) and use the "static" keyword * Includes in C++ wrappers - * - By default, the include will be <[classname].h> - * - All namespaces must have angle brackets: - * - To override, add a full include statement just before the class statement - * - An override include can be added for a namespace by placing it just before the namespace statement - * - Both classes and namespace accept exactly one namespace - * Overriding type dependency checks + * - All includes will be collected and added in a single file + * - All namespaces must have angle brackets: + * - No default includes will be added + * Global/Namespace functions + * - Functions specified outside of a class are global + * - Can be overloaded with different arguments + * - Can have multiple functions of the same name in different namespaces + * Using classes defined in other modules * - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error - * - Limitation: this only works if the class does not need a namespace specification + * Virtual inheritance + * - Specify fully-qualified base classes, i.e. "virtual class Derived : module::Base {" + * - Mark with 'virtual' keyword, e.g. "virtual class Base {", and also "virtual class Derived : module::Base {" + * - Forward declarations must also be marked virtual, e.g. "virtual class module::Base;" and + * also "virtual class module::Derived;" + * - Pure virtual (abstract) classes should list no constructors in this interface file + * - Virtual classes must have a clone() function in C++ (though it does not have to be included + * in the MATLAB interface). clone() will be called whenever an object copy is needed, instead + * of using the copy constructor (which is used for non-virtual objects). + * Templates + * - Basic templates are supported either with an explicit list of types to instantiate, + * e.g. template class Class1 { ... }; + * or with typedefs, e.g. + * template class Class2 { ... }; + * typedef Class2 MyInstantiatedClass; + * - In the class definition, appearances of the template argument(s) will be replaced with their + * instantiated types, e.g. 'void setValue(const T& value);'. + * - To refer to the instantiation of the template class itself, use 'This', i.e. 'static This Create();' + * - To create new instantiations in other modules, you must copy-and-paste the whole class definition + * into the new module, but use only your new instantiation types. + * - When forward-declaring template instantiations, use the generated/typedefed name, e.g. + * class gtsam::Class1Pose2; + * class gtsam::MyInstantiatedClass; */ /** * Status: - * - TODO: global functions * - TODO: default values for arguments - * - TODO: overloaded functions - * - TODO: signatures for constructors can be ambiguous if two types have the same first letter * - TODO: Handle gtsam::Rot3M conversions to quaternions */ -// Everything is in the gtsam namespace, so we avoid copying everything in -//using namespace gtsam; +/*namespace std { + template + //Module.cpp needs to be changed to allow lowercase classnames + class vector + { + //Capcaity + size_t size() const; + size_t max_size() const; + void resize(size_t sz, T c = T()); + size_t capacity() const; + bool empty() const; + void reserve(size_t n); + + //Element acces + T& at(size_t n); + const T& at(size_t n) const; + T& front(); + const T& front() const; + T& back(); + const T& back() const; + + //Modifiers + void assign(size_t n, const T& u); + void push_back(const T& x); + void pop_back(); + }; +}*/ namespace gtsam { +//typedef std::vector IndexVector; + //************************************************************************* // base //************************************************************************* +/** gtsam namespace functions */ +bool linear_independent(Matrix A, Matrix B, double tol); + +virtual class Value { + // No constructors because this is an abstract class + + // Testable + void print(string s) const; + + // Manifold + size_t dim() const; +}; + +#include +virtual class LieScalar : gtsam::Value { + // Standard constructors + LieScalar(); + LieScalar(double d); + + // Standard interface + double value() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieScalar& expected, double tol) const; + + // Group + static gtsam::LieScalar identity(); + gtsam::LieScalar inverse() const; + gtsam::LieScalar compose(const gtsam::LieScalar& p) const; + gtsam::LieScalar between(const gtsam::LieScalar& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieScalar retract(Vector v) const; + Vector localCoordinates(const gtsam::LieScalar& t2) const; + + // Lie group + static gtsam::LieScalar Expmap(Vector v); + static Vector Logmap(const gtsam::LieScalar& p); +}; + +#include +virtual class LieVector : gtsam::Value { + // Standard constructors + LieVector(); + LieVector(Vector v); + + // Standard interface + Vector vector() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieVector& expected, double tol) const; + + // Group + static gtsam::LieVector identity(); + gtsam::LieVector inverse() const; + gtsam::LieVector compose(const gtsam::LieVector& p) const; + gtsam::LieVector between(const gtsam::LieVector& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieVector retract(Vector v) const; + Vector localCoordinates(const gtsam::LieVector& t2) const; + + // Lie group + static gtsam::LieVector Expmap(Vector v); + static Vector Logmap(const gtsam::LieVector& p); +}; + +#include +virtual class LieMatrix : gtsam::Value { + // Standard constructors + LieMatrix(); + LieMatrix(Matrix v); + + // Standard interface + Matrix matrix() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieMatrix& expected, double tol) const; + + // Group + static gtsam::LieMatrix identity(); + gtsam::LieMatrix inverse() const; + gtsam::LieMatrix compose(const gtsam::LieMatrix& p) const; + gtsam::LieMatrix between(const gtsam::LieMatrix& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieMatrix retract(Vector v) const; + Vector localCoordinates(const gtsam::LieMatrix & t2) const; + + // Lie group + static gtsam::LieMatrix Expmap(Vector v); + static Vector Logmap(const gtsam::LieMatrix& p); +}; + //************************************************************************* // geometry //************************************************************************* -class Point2 { - Point2(); - Point2(double x, double y); +virtual class Point2 : gtsam::Value { + // Standard Constructors + Point2(); + Point2(double x, double y); + Point2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Point2& pose, double tol) const; + + // Group + static gtsam::Point2 identity(); + gtsam::Point2 inverse() const; + gtsam::Point2 compose(const gtsam::Point2& p2) const; + gtsam::Point2 between(const gtsam::Point2& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Point2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point2& p) const; + + // Lie Group 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); - gtsam::Point2 compose(const gtsam::Point2& p2); - gtsam::Point2 between(const gtsam::Point2& p2); - gtsam::Point2 retract(Vector v); + static Vector Logmap(const gtsam::Point2& p); + + // Standard Interface + double x() const; + double y() const; + Vector vector() const; + double dist(const gtsam::Point2& p2) const; }; -class Point3 { +virtual class StereoPoint2 : gtsam::Value { + // Standard Constructors + StereoPoint2(); + StereoPoint2(double uL, double uR, double v); + + // Testable + void print(string s) const; + bool equals(const gtsam::StereoPoint2& point, double tol) const; + + // Group + static gtsam::StereoPoint2 identity(); + gtsam::StereoPoint2 inverse() const; + gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2) const; + gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::StereoPoint2 retract(Vector v) const; + Vector localCoordinates(const gtsam::StereoPoint2& p) const; + + // Lie Group + static gtsam::StereoPoint2 Expmap(Vector v); + static Vector Logmap(const gtsam::StereoPoint2& p); + + // Standard Interface + Vector vector() const; +}; + +virtual class Point3 : gtsam::Value { + // Standard Constructors Point3(); Point3(double x, double y, double z); Point3(Vector v); - static gtsam::Point3 Expmap(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Point3& p, double tol) const; + + // Group + static gtsam::Point3 identity(); + gtsam::Point3 inverse() const; + gtsam::Point3 compose(const gtsam::Point3& p2) const; + gtsam::Point3 between(const gtsam::Point3& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Point3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point3& p) const; + + // Lie Group + static gtsam::Point3 Expmap(Vector v); static Vector Logmap(const gtsam::Point3& p); - void print(string s) const; - bool equals(const gtsam::Point3& p, double tol); + + // Standard Interface Vector vector() const; - double x(); - double y(); - double z(); - Vector localCoordinates(const gtsam::Point3& p); - gtsam::Point3 retract(Vector v); - gtsam::Point3 compose(const gtsam::Point3& p2); - gtsam::Point3 between(const gtsam::Point3& p2); + double x() const; + double y() const; + double z() const; }; -class Rot2 { +virtual class Rot2 : gtsam::Value { + // Standard Constructors and Named Constructors Rot2(); Rot2(double theta); - static gtsam::Rot2 Expmap(Vector v); + static gtsam::Rot2 fromAngle(double theta); + static gtsam::Rot2 fromDegrees(double theta); + static gtsam::Rot2 fromCosSin(double c, double s); + + // Testable + void print(string s) const; + bool equals(const gtsam::Rot2& rot, double tol) const; + + // Group + static gtsam::Rot2 identity(); + gtsam::Rot2 inverse(); + gtsam::Rot2 compose(const gtsam::Rot2& p2) const; + gtsam::Rot2 between(const gtsam::Rot2& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Rot2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Rot2& p) const; + + // Lie Group + static gtsam::Rot2 Expmap(Vector v); static Vector Logmap(const gtsam::Rot2& p); - static gtsam::Rot2 fromAngle(double theta); - static gtsam::Rot2 fromDegrees(double theta); - static gtsam::Rot2 fromCosSin(double c, double s); + + // Group Action on Point2 + gtsam::Point2 rotate(const gtsam::Point2& point) const; + gtsam::Point2 unrotate(const gtsam::Point2& point) const; + + // Standard Interface static gtsam::Rot2 relativeBearing(const gtsam::Point2& d); // Ignoring derivative static gtsam::Rot2 atan2(double y, double x); - void print(string s) const; - bool equals(const gtsam::Rot2& rot, double tol) const; double theta() const; double degrees() const; double c() const; double s() const; - Vector localCoordinates(const gtsam::Rot2& p); - gtsam::Rot2 retract(Vector v); - gtsam::Rot2 compose(const gtsam::Rot2& p2); - gtsam::Rot2 between(const gtsam::Rot2& p2); + Matrix matrix() const; }; -class Rot3 { +virtual class Rot3 : gtsam::Value { + // Standard Constructors and Named Constructors 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 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 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); + + // Testable 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; + + // Group + static gtsam::Rot3 identity(); gtsam::Rot3 inverse() const; + gtsam::Rot3 compose(const gtsam::Rot3& p2) const; gtsam::Rot3 between(const gtsam::Rot3& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options + gtsam::Rot3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Rot3& p) const; + + // Group Action on Point3 gtsam::Point3 rotate(const gtsam::Point3& p) const; gtsam::Point3 unrotate(const gtsam::Point3& p) const; - gtsam::Rot3 retractCayley(Vector v) const; - gtsam::Rot3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Rot3& p) const; + + // Standard Interface static gtsam::Rot3 Expmap(Vector v); 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 }; -class Pose2 { +virtual class Pose2 : gtsam::Value { + // Standard Constructor Pose2(); Pose2(double x, double y, double theta); Pose2(double theta, const gtsam::Point2& t); Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); Pose2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Pose2& pose, double tol) const; + + // Group + static gtsam::Pose2 identity(); + gtsam::Pose2 inverse() const; + gtsam::Pose2 compose(const gtsam::Pose2& p2) const; + gtsam::Pose2 between(const gtsam::Pose2& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Pose2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Pose2& p) const; + + // Lie Group static gtsam::Pose2 Expmap(Vector v); static Vector Logmap(const gtsam::Pose2& p); - void print(string s) const; - bool equals(const gtsam::Pose2& pose, double tol) const; + Matrix adjointMap() const; + Vector adjoint(const Vector& xi) const; + static Matrix wedge(double vx, double vy, double w); + + // Group Actions on Point2 + gtsam::Point2 transform_from(const gtsam::Point2& p) const; + gtsam::Point2 transform_to(const gtsam::Point2& p) const; + + // Standard Interface double x() const; double y() const; double theta() const; - int dim() const; - Vector localCoordinates(const gtsam::Pose2& p); - gtsam::Pose2 retract(Vector v); - gtsam::Pose2 compose(const gtsam::Pose2& p2); - gtsam::Pose2 between(const gtsam::Pose2& p2); - gtsam::Rot2 bearing(const gtsam::Point2& point); - double range(const gtsam::Point2& point); + gtsam::Rot2 bearing(const gtsam::Point2& point) const; + double range(const gtsam::Point2& point) const; gtsam::Point2 translation() const; gtsam::Rot2 rotation() const; + Matrix matrix() const; }; -class Pose3 { +virtual class Pose3 : gtsam::Value { + // Standard Constructors Pose3(); + Pose3(const gtsam::Pose3& pose); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); + Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose) Pose3(Matrix t); - Pose3(const gtsam::Pose2& pose2); - static gtsam::Pose3 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose3& p); + + // Testable void print(string s) const; bool equals(const gtsam::Pose3& pose, double tol) const; + + // Group + static gtsam::Pose3 identity(); + gtsam::Pose3 inverse() const; + gtsam::Pose3 compose(const gtsam::Pose3& p2) const; + gtsam::Pose3 between(const gtsam::Pose3& p2) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Pose3 retract(Vector v) const; + gtsam::Pose3 retractFirstOrder(Vector v) const; + 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; // FIXME: shadows other transform_to() + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& pose); }; -class CalibratedCamera { - - CalibratedCamera(); - CalibratedCamera(const gtsam::Pose3& pose); - CalibratedCamera(const Vector& v); +virtual class Cal3_S2 : gtsam::Value { + // Standard Constructors + Cal3_S2(); + Cal3_S2(double fx, double fy, double s, double u0, double v0); + Cal3_S2(Vector v); + Cal3_S2(double fov, int w, int h); - void print(string s) const; - bool equals(const gtsam::CalibratedCamera& camera, double tol) const; + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2& rhs, double tol) const; - gtsam::Pose3 pose() const; + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3_S2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3_S2& c) 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; + // Action on Point2 + gtsam::Point2 calibrate(const gtsam::Point2& p) const; + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; - gtsam::Point2 project(const gtsam::Point3& point) const; - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + Vector vector() const; + Matrix matrix() const; + Matrix matrix_inverse() const; }; +#include +virtual class Cal3DS2 : gtsam::Value { + // Standard Constructors + Cal3DS2(); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4); + Cal3DS2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3DS2& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3DS2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3DS2& c) const; + + // Action on Point2 + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + // TODO: D2d functions that start with an uppercase letter + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + Vector vector() const; + Vector k() const; + //Matrix K() const; //FIXME: Uppercase +}; + +class Cal3_S2Stereo { + // Standard Constructors + Cal3_S2Stereo(); + Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2Stereo& pose, double tol) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + double baseline() const; +}; + +virtual class CalibratedCamera : gtsam::Value { + // Standard Constructors and Named Constructors + CalibratedCamera(); + CalibratedCamera(const gtsam::Pose3& pose); + CalibratedCamera(const Vector& v); + static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height); + + // Testable + void print(string s) const; + bool equals(const gtsam::CalibratedCamera& camera, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::CalibratedCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + + // Group + gtsam::CalibratedCamera compose(const gtsam::CalibratedCamera& c) const; + gtsam::CalibratedCamera inverse() const; + + // Action on Point3 + gtsam::Point2 project(const gtsam::Point3& point) const; + static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + + // Standard Interface + gtsam::Pose3 pose() const; + double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods +}; + +virtual class SimpleCamera : gtsam::Value { + // Standard Constructors and Named Constructors + SimpleCamera(); + SimpleCamera(const gtsam::Pose3& pose); + SimpleCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2& K); + static gtsam::SimpleCamera Level(const gtsam::Cal3_S2& K, + const gtsam::Pose2& pose, double height); + static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height); // FIXME overload + static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, + const gtsam::Point3& target, const gtsam::Point3& upVector, + const gtsam::Cal3_S2& K); + + // Testable + void print(string s) const; + bool equals(const gtsam::SimpleCamera& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + gtsam::Cal3_S2 calibration(); + + // Manifold + gtsam::SimpleCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::SimpleCamera& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + pair projectSafe(const gtsam::Point3& pw) const; + gtsam::Point2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& point); // FIXME, overload +}; + +// TODO: Add this back in when Cal3DS2 has a calibrate function +//template +//virtual class PinholeCamera : gtsam::Value { +// // Standard Constructors and Named Constructors +// PinholeCamera(); +// PinholeCamera(const gtsam::Pose3& pose); +// PinholeCamera(const gtsam::Pose3& pose, const gtsam::Cal3DS2& K); +// static This Level(const gtsam::Cal3DS2& K, +// const gtsam::Pose2& pose, double height); +// static This Level(const gtsam::Pose2& pose, double height); // FIXME overload +// static This Lookat(const gtsam::Point3& eye, +// const gtsam::Point3& target, const gtsam::Point3& upVector, +// const gtsam::Cal3DS2& K); +// +// // Testable +// void print(string s) const; +// bool equals(const This& camera, double tol) const; +// +// // Standard Interface +// gtsam::Pose3 pose() const; +// CALIBRATION calibration() const; +// +// // Manifold +// This retract(const Vector& d) const; +// Vector localCoordinates(const This& T2) const; +// size_t dim() const; +// static size_t Dim(); +// +// // Transformations and measurement functions +// static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); +// pair projectSafe(const gtsam::Point3& pw) const; +// gtsam::Point2 project(const gtsam::Point3& point); +// gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; +// double range(const gtsam::Point3& point); +// double range(const gtsam::Pose3& point); // FIXME, overload +//}; //************************************************************************* // inference //************************************************************************* +#include +class Permutation { + // Standard Constructors and Named Constructors + Permutation(); + Permutation(size_t nVars); + static gtsam::Permutation Identity(size_t nVars); + // Testable + void print(string s) const; + bool equals(const gtsam::Permutation& rhs, double tol) const; + // Standard interface + size_t at(size_t variable) const; + size_t size() const; + bool empty() const; + void resize(size_t newSize); + gtsam::Permutation* permute(const gtsam::Permutation& permutation) const; + gtsam::Permutation* inverse() const; + // FIXME: Cannot currently wrap std::vector + //static gtsam::Permutation PullToFront(const vector& toFront, size_t size, bool filterDuplicates); + //static gtsam::Permutation PushToBack(const vector& toBack, size_t size, bool filterDuplicates = false); + gtsam::Permutation* partialPermutation(const gtsam::Permutation& selector, const gtsam::Permutation& partialPermutation) const; +}; + +class IndexFactor { + // Standard Constructors and Named Constructors + IndexFactor(const gtsam::IndexFactor& f); + IndexFactor(const gtsam::IndexConditional& c); + IndexFactor(); + IndexFactor(size_t j); + IndexFactor(size_t j1, size_t j2); + IndexFactor(size_t j1, size_t j2, size_t j3); + IndexFactor(size_t j1, size_t j2, size_t j3, size_t j4); + IndexFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5); + IndexFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5, size_t j6); + // FIXME: Must wrap std::set for this to work + //IndexFactor(const std::set& js); + void permuteWithInverse(const gtsam::Permutation& inversePermutation); + + // From Factor + size_t size() const; + void print(string s) const; + bool equals(const gtsam::IndexFactor& other, double tol) const; + // FIXME: Need to wrap std::vector + //std::vector& keys(); +}; + +class IndexConditional { + // Standard Constructors and Named Constructors + IndexConditional(); + IndexConditional(size_t key); + IndexConditional(size_t key, size_t parent); + IndexConditional(size_t key, size_t parent1, size_t parent2); + IndexConditional(size_t key, size_t parent1, size_t parent2, size_t parent3); + // FIXME: Must wrap std::vector for this to work + //IndexFactor(size_t key, const std::vector& parents); + //IndexConditional(const std::vector& keys, size_t nrFrontals); + //template static shared_ptr FromKeys(const KEYS& keys, size_t nrFrontals); + + // Testable + void print(string s) const; + bool equals(const gtsam::IndexConditional& other, double tol) const; + + // Standard interface + size_t nrFrontals() const; + size_t nrParents() const; + gtsam::IndexFactor* toFactor() const; + + //Advanced interface + bool permuteSeparatorWithInverse(const gtsam::Permutation& inversePermutation); + void permuteWithInverse(const gtsam::Permutation& inversePermutation); +}; + +#include +class SymbolicBayesNet { + // Standard Constructors and Named Constructors + SymbolicBayesNet(); + SymbolicBayesNet(const gtsam::SymbolicBayesNet& bn); + SymbolicBayesNet(const gtsam::IndexConditional* conditional); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicBayesNet& other, double tol) const; + + // Standard interface + size_t size() const; + void push_back(const gtsam::IndexConditional* conditional); + //TODO:Throws parse error + //void push_back(const gtsam::SymbolicBayesNet bn); + void push_front(const gtsam::IndexConditional* conditional); + //TODO:Throws parse error + //void push_front(const gtsam::SymbolicBayesNet bn); + + //Advanced Interface + gtsam::IndexConditional* front() const; + gtsam::IndexConditional* back() const; + void pop_front(); + void permuteWithInverse(const gtsam::Permutation& inversePermutation); + bool permuteSeparatorWithInverse(const gtsam::Permutation& inversePermutation); +}; + +#include +class SymbolicBayesTree { + // Standard Constructors and Named Constructors + SymbolicBayesTree(); + SymbolicBayesTree(const gtsam::SymbolicBayesNet& bn); + SymbolicBayesTree(const gtsam::SymbolicBayesTree& other); + // FIXME: wrap needs to understand std::list + //SymbolicBayesTree(const gtsam::SymbolicBayesNet& bayesNet, std::list subtrees); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicBayesTree& other, double tol) const; + + // Standard interface + size_t findParentClique(const gtsam::IndexConditional& parents) const; + size_t size() const; + void saveGraph(string s) const; + void clear(); + // TODO: There are many other BayesTree member functions which might be of use +}; + +class SymbolicFactorGraph { + // Standard Constructors and Named Constructors + SymbolicFactorGraph(); + SymbolicFactorGraph(const gtsam::SymbolicBayesNet& bayesNet); + SymbolicFactorGraph(const gtsam::SymbolicBayesTree& bayesTree); + + // From FactorGraph + void push_back(gtsam::IndexFactor* factor); + void print(string s) const; + bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; + size_t size() const; + + // Standard interface + // FIXME: Must wrap FastSet for this to work + //FastSet keys() const; + + //Advanced Interface + void push_factor(size_t key); + void push_factor(size_t key1, size_t key2); + void push_factor(size_t key1, size_t key2, size_t key3); + void push_factor(size_t key1, size_t key2, size_t key3, size_t key4); + + pair eliminateFrontals(size_t nFrontals) const; +}; + +#include +class SymbolicSequentialSolver { + // Standard Constructors and Named Constructors + SymbolicSequentialSolver(const gtsam::SymbolicFactorGraph& factorGraph); + SymbolicSequentialSolver(const gtsam::SymbolicFactorGraph* factorGraph, const gtsam::VariableIndex* variableIndex); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicSequentialSolver& rhs, double tol) const; + + // Standard interface + gtsam::SymbolicBayesNet* eliminate() const; + gtsam::IndexFactor* marginalFactor(size_t j) const; +}; + +#include +class SymbolicMultifrontalSolver { + // Standard Constructors and Named Constructors + SymbolicMultifrontalSolver(const gtsam::SymbolicFactorGraph& factorGraph); + SymbolicMultifrontalSolver(const gtsam::SymbolicFactorGraph* factorGraph, const gtsam::VariableIndex* variableIndex); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicMultifrontalSolver& rhs, double tol) const; + + // Standard interface + gtsam::SymbolicBayesTree* eliminate() const; + gtsam::IndexFactor* marginalFactor(size_t j) const; +}; + +#include +class VariableIndex { + // Standard Constructors and Named Constructors + VariableIndex(); + // TODO: Templetize constructor when wrap supports it + //template + //VariableIndex(const T& factorGraph, size_t nVariables); + //VariableIndex(const T& factorGraph); + VariableIndex(const gtsam::SymbolicFactorGraph& factorGraph); + VariableIndex(const gtsam::SymbolicFactorGraph& factorGraph, size_t nVariables); + VariableIndex(const gtsam::GaussianFactorGraph& factorGraph); + VariableIndex(const gtsam::GaussianFactorGraph& factorGraph, size_t nVariables); + VariableIndex(const gtsam::NonlinearFactorGraph& factorGraph); + VariableIndex(const gtsam::NonlinearFactorGraph& factorGraph, size_t nVariables); + VariableIndex(const gtsam::VariableIndex& other); + + // Testable + bool equals(const gtsam::VariableIndex& other, double tol) const; + void print(string s) const; + + // Standard interface + size_t size() const; + size_t nFactors() const; + size_t nEntries() const; + void permuteInPlace(const gtsam::Permutation& permutation); +}; + +#include +template +virtual class BayesTree { + + //Constructors + BayesTree(); + + //Standard Interface + bool equals(const This& other, double tol) const; + void print(string s); + //size_t findParentClique(const gtsam::IndexVector& parents) const; + size_t size(); + CLIQUE* root() const; + void clear(); + void insert(const CLIQUE* subtree); +}; + +typedef gtsam::BayesTree ISAM2BayesTree; //************************************************************************* // linear //************************************************************************* -class SharedGaussian { - SharedGaussian(Matrix covariance); +namespace noiseModel { +#include +virtual class Base { +}; + +virtual class Gaussian : gtsam::noiseModel::Base { + static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); + static gtsam::noiseModel::Gaussian* Covariance(Matrix R); + //Matrix R() const; // FIXME: cannot parse!!! + bool equals(gtsam::noiseModel::Base& expected, double tol); void print(string s) const; }; -class SharedDiagonal { - SharedDiagonal(Vector sigmas); +virtual class Diagonal : gtsam::noiseModel::Gaussian { + static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); + static gtsam::noiseModel::Diagonal* Variances(Vector variances); + static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); +// Matrix R() const; // FIXME: cannot parse!!! void print(string s) const; - Vector sample() const; }; -class SharedNoiseModel { - static gtsam::SharedNoiseModel Sigmas(Vector sigmas); - static gtsam::SharedNoiseModel Sigma(size_t dim, double sigma); - static gtsam::SharedNoiseModel Precisions(Vector precisions); - static gtsam::SharedNoiseModel Precision(size_t dim, double precision); - static gtsam::SharedNoiseModel Unit(size_t dim); - static gtsam::SharedNoiseModel SqrtInformation(Matrix R); - static gtsam::SharedNoiseModel Covariance(Matrix covariance); +virtual class Constrained : gtsam::noiseModel::Diagonal { + static gtsam::noiseModel::Constrained* MixedSigmas(const Vector& mu, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedSigmas(double m, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& mu, const Vector& variances); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& variances); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& mu, const Vector& precisions); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& precisions); + + static gtsam::noiseModel::Constrained* All(size_t dim); + static gtsam::noiseModel::Constrained* All(size_t dim, double m); + + gtsam::noiseModel::Constrained* unit() const; +}; + +virtual class Isotropic : gtsam::noiseModel::Diagonal { + static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); + static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); + static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); void print(string s) const; }; +virtual class Unit : gtsam::noiseModel::Isotropic { + static gtsam::noiseModel::Unit* Create(size_t dim); + void print(string s) const; +}; +}///\namespace noiseModel + +#include +class Sampler { + //Constructors + Sampler(gtsam::noiseModel::Diagonal* model, int seed); + Sampler(Vector sigmas, int seed); + Sampler(int seed); + + //Standard Interface + size_t dim() const; + Vector sigmas() const; + gtsam::noiseModel::Diagonal* model() const; + Vector sample(); + Vector sampleNewModel(gtsam::noiseModel::Diagonal* model); +}; + class VectorValues { + //Constructors VectorValues(); - VectorValues(int nVars, int varDim); + VectorValues(const gtsam::VectorValues& other); + VectorValues(size_t nVars, size_t varDim); + + //Named Constructors + static gtsam::VectorValues Zero(const gtsam::VectorValues& model); + static gtsam::VectorValues Zero(size_t nVars, size_t varDim); + static gtsam::VectorValues SameStructure(const gtsam::VectorValues& other); + + //Standard Interface + size_t size() const; + size_t dim(size_t j) const; + size_t dim() const; + bool exists(size_t j) const; void print(string s) const; bool equals(const gtsam::VectorValues& expected, double tol) const; - int size() const; - void insert(int j, Vector value); + void insert(size_t j, Vector value); + Vector vector() const; + Vector at(size_t j) const; + + //Advanced Interface + void resizeLike(const gtsam::VectorValues& other); + void resize(size_t nVars, size_t varDim); + void setZero(); + + //FIXME: Parse errors with vector() + //const Vector& vector() const; + //Vector& vector(); + bool hasSameStructure(const gtsam::VectorValues& other) const; + double dot(const gtsam::VectorValues& V) const; + double norm() const; }; class GaussianConditional { - GaussianConditional(int key, Vector d, Matrix R, Vector sigmas); - GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S, + //Constructors + 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); + + //Standard Interface void print(string s) const; bool equals(const gtsam::GaussianConditional &cg, double tol) const; + size_t dim() const; + + //Advanced Interface + Matrix computeInformation() const; + gtsam::JacobianFactor* toFactor() const; + void solveInPlace(gtsam::VectorValues& x) const; + void solveTransposeInPlace(gtsam::VectorValues& gy) const; + void scaleFrontalsBySigma(gtsam::VectorValues& gy) const; }; class GaussianDensity { - GaussianDensity(int key, Vector d, Matrix R, Vector sigmas); + //Constructors + GaussianDensity(size_t key, Vector d, Matrix R, Vector sigmas); + + //Standard Interface void print(string s) const; Vector mean() const; Matrix information() const; @@ -292,401 +1052,856 @@ class GaussianDensity { }; class GaussianBayesNet { + //Constructors GaussianBayesNet(); + + //Standard Interface void print(string s) const; bool equals(const gtsam::GaussianBayesNet& cbn, double tol) const; void push_back(gtsam::GaussianConditional* conditional); void push_front(gtsam::GaussianConditional* conditional); }; -class GaussianFactor { +//Non-Class methods found in GaussianBayesNet.h +//FIXME: No MATLAB documentation for these functions! +/*gtsam::GaussianBayesNet scalarGaussian(size_t key, double mu, double sigma); +gtsam::GaussianBayesNet simpleGaussian(size_t key, const Vector& mu, double sigma); +void push_front(gtsam::GaussianBayesNet& bn, size_t key, Vector d, Matrix R, size_t name1, Matrix S, Vector sigmas); +void push_front(gtsam::GaussianBayesNet& bn, size_t key, Vector d, Matrix R, size_t name1, Matrix S, size_t name2, Matrix T, Vector sigmas); +gtsam::VectorValues* allocateVectorValues(const gtsam::GaussianBayesNet& bn); +gtsam::VectorValues optimize(const gtsam::GaussianBayesNet& bn); +void optimizeInPlace(const gtsam::GaussianBayesNet& bn, gtsam::VectorValues& x); +gtsam::VectorValues optimizeGradientSearch(const gtsam::GaussianBayesNet& bn); +void optimizeGradientSearchInPlace(const gtsam::GaussianBayesNet& bn, gtsam::VectorValues& grad); +gtsam::VectorValues backSubstitute(const gtsam::GaussianBayesNet& bn, const gtsam::VectorValues& gx); +gtsam::VectorValues backSubstituteTranspose(const gtsam::GaussianBayesNet& bn, const gtsam::VectorValues& gx); +pair matrix(const gtsam::GaussianBayesNet& bn); +double determinant(const gtsam::GaussianBayesNet& bayesNet); +gtsam::VectorValues gradient(const gtsam::GaussianBayesNet& bayesNet, const gtsam::VectorValues& x0); +void gradientAtZero(const gtsam::GaussianBayesNet& bayesNet, const gtsam::VectorValues& g);*/ + +virtual class GaussianFactor { void print(string s) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const; double error(const gtsam::VectorValues& c) const; + gtsam::GaussianFactor* negate() const; + size_t size() const; }; -class JacobianFactor { +virtual class JacobianFactor : gtsam::GaussianFactor { + //Constructors 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, - const gtsam::SharedDiagonal& model); - JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, int i3, Matrix A3, - Vector b, const gtsam::SharedDiagonal& model); + JacobianFactor(size_t i1, Matrix A1, Vector b, + const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); + JacobianFactor(const gtsam::GaussianFactor& factor); + + //Testable void print(string s) const; + void printKeys(string s) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const; - bool empty() const; - Vector getb() const; + size_t size() const; + Vector unweighted_error(const gtsam::VectorValues& c) const; + Vector error_vector(const gtsam::VectorValues& c) const; double error(const gtsam::VectorValues& c) const; - gtsam::GaussianConditional* eliminateFirst(); + + //Standard Interface + gtsam::GaussianFactor* negate() const; + bool empty() const; + Matrix getA() const; + Vector getb() const; + size_t rows() const; + size_t cols() const; + size_t numberOfRows() const; + bool isConstrained() const; + pair matrix() const; + Matrix matrix_augmented() const; + + gtsam::GaussianConditional* eliminateFirst(); + gtsam::GaussianConditional* eliminate(size_t nrFrontals); + gtsam::GaussianFactor* negate() const; + Matrix computeInformation() const; + void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; + gtsam::JacobianFactor whiten() const; + gtsam::GaussianConditional* eliminateFirst(); + gtsam::GaussianConditional* eliminate(size_t nFrontals); + gtsam::GaussianConditional* splitConditional(size_t nFrontals); + + void setModel(bool anyConstrained, const Vector& sigmas); + void assertInvariants() const; + + //gtsam::SharedDiagonal& get_model(); }; -class HessianFactor { +virtual class HessianFactor : gtsam::GaussianFactor { + //Constructors 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; + + //Testable + size_t size() const; + void print(string s) const; + void printKeys(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; + + //Standard Interface + size_t rows() const; + gtsam::GaussianFactor* negate() const; + Matrix info() const; + double constantTerm() const; + Vector linearTerm() const; + Matrix computeInformation() const; + + //Advanced Interface + void partialCholesky(size_t nrFrontals); + gtsam::GaussianConditional* splitEliminatedFactor(size_t nrFrontals); + void assertInvariants() const; }; class GaussianFactorGraph { GaussianFactorGraph(); - GaussianFactorGraph(const gtsam::GaussianBayesNet& CBN); + GaussianFactorGraph(const gtsam::GaussianBayesNet& CBN); - // From FactorGraph - void push_back(gtsam::GaussianFactor* factor); + // From FactorGraph void print(string s) const; bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; - int size() const; + size_t size() const; + gtsam::GaussianFactor* at(size_t idx) const; + + // Inference + pair eliminateFrontals(size_t nFrontals) const; // Building the graph - void add(gtsam::JacobianFactor* factor); + void push_back(gtsam::GaussianFactor* factor); + void add(const gtsam::GaussianFactor& factor); 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, - const gtsam::SharedDiagonal& model); - void add(int key1, Matrix A1, int key2, Matrix A2, int key3, Matrix A3, - Vector b, const gtsam::SharedDiagonal& model); - void add(gtsam::HessianFactor* factor); + void add(size_t key1, Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); + + //Permutations + void permuteWithInverse(const gtsam::Permutation& inversePermutation); // error and probability double error(const gtsam::VectorValues& c) const; 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 Matrix sparseJacobian_() const; - Matrix denseJacobian() const; - Matrix denseHessian() const; + Matrix augmentedJacobian() const; + pair jacobian() const; + Matrix augmentedHessian() const; + pair hessian() const; }; +//Non-Class functions in GaussianFactorGraph.h +/*void multiplyInPlace(const gtsam::GaussianFactorGraph& fg, const gtsam::VectorValues& x, gtsam::Errors& e); +gtsam::VectorValues gradient(const gtsam::GaussianFactorGraph& fg, const gtsam::VectorValues& x0); +void gradientAtZero(const gtsam::GaussianFactorGraph& fg, gtsam::VectorValues& g); +void residual(const gtsam::GaussianFactorGraph& fg, const gtsam::VectorValues& x, gtsam::VectorValues& r); +void multiply(const gtsam::GaussianFactorGraph& fg, const gtsam::VectorValues& x, gtsam::VectorValues& r); +void transposeMultiply(const gtsam::GaussianFactorGraph& fg, const gtsam::VectorValues& x, gtsam::VectorValues& r);*/ + +class Errors { + //Constructors + Errors(); + Errors(const gtsam::VectorValues& V); + + //Testable + void print(string s); + bool equals(const gtsam::Errors& expected, double tol) const; +}; + +//Non-Class functions for Errors +//double dot(const gtsam::Errors& A, const gtsam::Errors& b); + +class GaussianISAM { + //Constructor + GaussianISAM(); + + //Standard Interface + void saveGraph(string s) const; + gtsam::GaussianFactor* marginalFactor(size_t j) const; + gtsam::GaussianBayesNet* marginalBayesNet(size_t key) const; + Matrix marginalCovariance(size_t key) const; + gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const; + void clear(); +}; + +#include 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; + //Constructors + GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph, + bool useQR); + + //Standard Interface + void replaceFactors(const gtsam::GaussianFactorGraph* factorGraph); + gtsam::GaussianBayesNet* eliminate() const; + gtsam::VectorValues* optimize() const; + gtsam::GaussianFactor* marginalFactor(size_t j) const; + Matrix marginalCovariance(size_t j) const; }; +#include +virtual class IterativeOptimizationParameters { + string getKernel() const ; + string getVerbosity() const; + void setKernel(string s) ; + void setVerbosity(string s) ; + void print() const; +}; + +//virtual class IterativeSolver { +// IterativeSolver(); +// gtsam::VectorValues optimize (); +//}; + +#include +virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParameters { + ConjugateGradientParameters(); + size_t getMinIterations() const ; + size_t getMaxIterations() const ; + size_t getReset() const; + double getEpsilon_rel() const; + double getEpsilon_abs() const; + + void setMinIterations(size_t value); + void setMaxIterations(size_t value); + void setReset(size_t value); + void setEpsilon_rel(double value); + void setEpsilon_abs(double value); + void print(string s); +}; + +#include +virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { + SubgraphSolverParameters(); + void print(string s) const; +}; + +class SubgraphSolver { + SubgraphSolver(const gtsam::GaussianFactorGraph &A, const gtsam::SubgraphSolverParameters ¶meters); + SubgraphSolver(const gtsam::GaussianFactorGraph &Ab1, const gtsam::GaussianFactorGraph &Ab2, const gtsam::SubgraphSolverParameters ¶meters); + gtsam::VectorValues optimize() const; +}; + +#include class KalmanFilter { KalmanFilter(size_t n); - gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0); + // 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::noiseModel::Diagonal* 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::noiseModel::Diagonal* model); + gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, + Vector z, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, + Vector z, Matrix Q); }; //************************************************************************* // nonlinear //************************************************************************* +#include +size_t symbol(char chr, size_t index); +char symbolChr(size_t key); +size_t symbolIndex(size_t key); + +#include class Ordering { - Ordering(); + // Standard Constructors and Named Constructors + Ordering(); + + // Testable void print(string s) const; bool equals(const gtsam::Ordering& ord, double tol) const; - void push_back(size_t key); + + // Standard interface + size_t nVars() const; + size_t size() const; + size_t at(size_t key) const; + bool exists(size_t key) const; + void insert(size_t key, size_t order); + void push_back(size_t key); + void permuteWithInverse(const gtsam::Permutation& inversePermutation); + gtsam::InvertedOrdering invert() const; }; -}///\namespace gtsam +class InvertedOrdering { + InvertedOrdering(); -//************************************************************************* -// planarSLAM -//************************************************************************* + // FIXME: add bracket operator overload -#include -namespace planarSLAM { + bool empty() const; + size_t size() const; + bool count(size_t index) const; // Use as a boolean function with implicit cast -class Values { - Values(); - 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 clear(); }; -class Graph { - Graph(); +class NonlinearFactorGraph { + NonlinearFactorGraph(); + NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph); + // FactorGraph void print(string s) const; + bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const; + size_t size() const; + bool empty() const; + void remove(size_t i); + size_t nrFactors() const; + gtsam::NonlinearFactor* at(size_t i) const; + void push_back(const gtsam::NonlinearFactorGraph& factors); - double error(const planarSLAM::Values& values) const; - gtsam::Ordering* orderingCOLAMD(const planarSLAM::Values& values) const; - gtsam::GaussianFactorGraph* linearize(const planarSLAM::Values& values, + // NonlinearFactorGraph + double error(const gtsam::Values& values) const; + double probPrime(const gtsam::Values& values) const; + void add(const gtsam::NonlinearFactor* factor); + gtsam::Ordering* orderingCOLAMD(const gtsam::Values& values) const; + // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map& constraints) const; + gtsam::GaussianFactorGraph* linearize(const gtsam::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::Values optimize(const planarSLAM::Values& initialEstimate); + gtsam::SymbolicFactorGraph* symbolic(const gtsam::Ordering& ordering) const; + gtsam::NonlinearFactorGraph clone() const; }; -class Odometry { - Odometry(int key1, int key2, const gtsam::Pose2& measured, - const gtsam::SharedNoiseModel& model); +virtual class NonlinearFactor { void print(string s) const; - gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, const gtsam::Ordering& ordering) const; + void printKeys(string s) const; + void equals(const gtsam::NonlinearFactor& other, double tol) const; + gtsam::KeyVector keys() const; + size_t size() const; + size_t dim() const; + double error(const gtsam::Values& c) const; + bool active(const gtsam::Values& c) const; + gtsam::GaussianFactor* linearize(const gtsam::Values& c, const gtsam::Ordering& ordering) const; + gtsam::NonlinearFactor* clone() const; + // gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen }; -}///\namespace planarSLAM - -//************************************************************************* -// gtsam::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); -}; - -}///\namespace pose2SLAM - -//************************************************************************* -// Simulated2D -//************************************************************************* - -#include -namespace simulated2D { - +#include 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); + Values(const gtsam::Values& other); + + size_t size() const; + bool empty() const; + void clear(); + size_t dim() const; + + void print(string s) const; + bool equals(const gtsam::Values& other, double tol) const; + + void insert(size_t j, const gtsam::Value& value); + void insert(const gtsam::Values& values); + void update(size_t j, const gtsam::Value& val); + void update(const gtsam::Values& values); + void erase(size_t j); + void swap(gtsam::Values& values); + + bool exists(size_t j) const; + gtsam::Value at(size_t j) const; + gtsam::KeyList keys() const; + + gtsam::VectorValues zeroVectors(const gtsam::Ordering& ordering) const; + gtsam::Ordering* orderingArbitrary(size_t firstVar) const; + + gtsam::Values retract(const gtsam::VectorValues& delta, const gtsam::Ordering& ordering) const; + gtsam::VectorValues localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering) const; + void localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering, gtsam::VectorValues& delta) const; }; -class Graph { - Graph(); +// Actually a FastList +#include +class KeyList { + KeyList(); + KeyList(const gtsam::KeyList& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t front() const; + size_t back() const; + void push_back(size_t key); + void push_front(size_t key); + void sort(); + void remove(size_t key); }; -// TODO: add factors, etc. +// Actually a FastSet +#include +class KeySet { + KeySet(); + KeySet(const gtsam::KeySet& other); -}///\namespace simulated2D + // Testable + void print(string s) const; + bool equals(const gtsam::KeySet& other) const; -// Simulated2DOriented Example Domain -#include -namespace simulated2DOriented { + // common STL methods + size_t size() const; + bool empty() const; + void clear(); -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); + // structure specific methods + void insert(size_t key); + bool erase(size_t key); // returns true if value was removed + bool count(size_t key) const; // returns true if value exists }; -class Graph { - Graph(); +// Actually a FastVector +#include +class KeyVector { + KeyVector(); + KeyVector(const gtsam::KeyVector& other); + KeyVector(const gtsam::KeySet& other); + KeyVector(const gtsam::KeyList& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t at(size_t i) const; + size_t front() const; + size_t back() const; + void push_back(size_t key) const; }; -// TODO: add factors, etc. +#include +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; + gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const; + gtsam::JointMarginal jointMarginalInformation(const gtsam::KeyVector& variables) const; +}; -}///\namespace simulated2DOriented +class JointMarginal { + Matrix at(size_t iVariable, size_t jVariable) const; + Matrix fullMatrix() const; + void print(string s) const; + void print() const; +}; + +//************************************************************************* +// Nonlinear optimizers +//************************************************************************* + +#include +virtual class NonlinearOptimizerParams { + NonlinearOptimizerParams(); + void print(string s) const; + + size_t getMaxIterations() const; + double getRelativeErrorTol() const; + double getAbsoluteErrorTol() const; + double getErrorTol() const; + string getVerbosity() const; + + void setMaxIterations(size_t value); + void setRelativeErrorTol(double value); + void setAbsoluteErrorTol(double value); + void setErrorTol(double value); + void setVerbosity(string s); +}; + +#include +virtual class SuccessiveLinearizationParams : gtsam::NonlinearOptimizerParams { + SuccessiveLinearizationParams(); + + string getLinearSolverType() const; + + void setLinearSolverType(string solver); + void setOrdering(const gtsam::Ordering& ordering); + void setIterativeParams(const gtsam::SubgraphSolverParameters ¶ms); + + bool isMultifrontal() const; + bool isSequential() const; + bool isCholmod() const; + bool isCG() const; +}; + +#include +virtual class GaussNewtonParams : gtsam::SuccessiveLinearizationParams { + GaussNewtonParams(); +}; + +#include +virtual class LevenbergMarquardtParams : gtsam::SuccessiveLinearizationParams { + LevenbergMarquardtParams(); + + double getlambdaInitial() const; + double getlambdaFactor() const; + double getlambdaUpperBound() const; + string getVerbosityLM() const; + + void setlambdaInitial(double value); + void setlambdaFactor(double value); + void setlambdaUpperBound(double value); + void setVerbosityLM(string s); +}; + +#include +virtual class DoglegParams : gtsam::SuccessiveLinearizationParams { + DoglegParams(); + + double getDeltaInitial() const; + string getVerbosityDL() const; + + void setDeltaInitial(double deltaInitial) const; + void setVerbosityDL(string verbosityDL) const; +}; + +virtual class NonlinearOptimizer { + gtsam::Values optimize(); + gtsam::Values optimizeSafely(); + double error() const; + int iterations() const; + gtsam::Values values() const; + void iterate() const; +}; + +virtual class GaussNewtonOptimizer : gtsam::NonlinearOptimizer { + GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::GaussNewtonParams& params); +}; + +virtual class DoglegOptimizer : gtsam::NonlinearOptimizer { + DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::DoglegParams& params); + double getDelta() const; +}; + +virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer { + LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params); + double lambda() const; + void print(string str) const; +}; + +#include +class ISAM2GaussNewtonParams { + ISAM2GaussNewtonParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); +}; + +class ISAM2DoglegParams { + ISAM2DoglegParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); + double getInitialDelta() const; + void setInitialDelta(double initialDelta); + string getAdaptationMode() const; + void setAdaptationMode(string adaptationMode); + bool isVerbose() const; + void setVerbose(bool verbose); +}; + +class ISAM2ThresholdMapValue { + ISAM2ThresholdMapValue(char c, Vector thresholds); + ISAM2ThresholdMapValue(const gtsam::ISAM2ThresholdMapValue& other); +}; + +class ISAM2ThresholdMap { + ISAM2ThresholdMap(); + ISAM2ThresholdMap(const gtsam::ISAM2ThresholdMap& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + void insert(const gtsam::ISAM2ThresholdMapValue& value) const; +}; + +class ISAM2Params { + ISAM2Params(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& params); + void setOptimizationParams(const gtsam::ISAM2DoglegParams& params); + void setRelinearizeThreshold(double relinearizeThreshold); + void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& relinearizeThreshold); + int getRelinearizeSkip() const; + void setRelinearizeSkip(int relinearizeSkip); + bool isEnableRelinearization() const; + void setEnableRelinearization(bool enableRelinearization); + bool isEvaluateNonlinearError() const; + void setEvaluateNonlinearError(bool evaluateNonlinearError); + string getFactorization() const; + void setFactorization(string factorization); + bool isCacheLinearizedFactors() const; + void setCacheLinearizedFactors(bool cacheLinearizedFactors); + bool isEnableDetailedResults() const; + void setEnableDetailedResults(bool enableDetailedResults); + bool isEnablePartialRelinearizationCheck() const; + void setEnablePartialRelinearizationCheck(bool enablePartialRelinearizationCheck); +}; + +virtual class ISAM2Clique { + + //Constructors + ISAM2Clique(const gtsam::GaussianConditional* conditional); + + //Standard Interface + Vector gradientContribution() const; + gtsam::ISAM2Clique* clone() const; + void print(string s); + + void permuteWithInverse(const gtsam::Permutation& inversePermutation); + bool permuteSeparatorWithInverse(const gtsam::Permutation& inversePermutation); +}; + +class ISAM2Result { + ISAM2Result(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + size_t getVariablesRelinearized() const; + size_t getVariablesReeliminated() const; + size_t getCliques() const; +}; + +virtual class ISAM2 : gtsam::ISAM2BayesTree { + ISAM2(); + ISAM2(const gtsam::ISAM2Params& params); + + bool equals(const gtsam::ISAM2& other, double tol) const; + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + + gtsam::ISAM2Result update(); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices); + // TODO: wrap the full version of update + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys); + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys, bool force_relinearize); + + gtsam::Values getLinearizationPoint() const; + gtsam::Values calculateEstimate() const; + gtsam::Values calculateBestEstimate() const; + gtsam::VectorValues getDelta() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; + gtsam::Ordering getOrdering() const; + gtsam::VariableIndex getVariableIndex() const; + gtsam::ISAM2Params params() const; +}; + +#include +class NonlinearISAM { + NonlinearISAM(); + NonlinearISAM(int reorderInterval); + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + gtsam::Values estimate() const; + Matrix marginalCovariance(size_t key) const; + int reorderInterval() const; + int reorderCounter() const; + void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& initialValues); + void reorder_relinearize(); + void addKey(size_t key); + void setOrdering(const gtsam::Ordering& new_ordering); + + // These might be expensive as instead of a reference the wrapper will make a copy + gtsam::GaussianISAM bayesTree() const; + gtsam::Values getLinearizationPoint() const; + gtsam::Ordering getOrdering() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; +}; + +//************************************************************************* +// Nonlinear factor types +//************************************************************************* +#include +#include +#include +#include +#include +#include + +#include +template +virtual class PriorFactor : gtsam::NonlinearFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); +}; -//// These are considered to be broken and will be added back as they start working -//// It's assumed that there have been interface changes that might break this -// -//class Ordering{ -// Ordering(string key); -// void print(string s) const; -// bool equals(const Ordering& ord, double tol) const; -// Ordering subtract(const Ordering& keys) const; -// void unique (); -// void reverse (); -// void push_back(string s); -//}; -// -//class GaussianFactorSet { -// GaussianFactorSet(); -// void push_back(GaussianFactor* factor); -//}; -// -//class Simulated2DPosePrior { -// Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i); -// void print(string s) const; -// double error(const Simulated2DValues& c) const; -//}; -// -//class Simulated2DOrientedPosePrior { -// Simulated2DOrientedPosePrior(Pose2& mu, const SharedDiagonal& model, int i); -// void print(string s) const; -// double error(const Simulated2DOrientedValues& c) const; -//}; -// -//class Simulated2DPointPrior { -// Simulated2DPointPrior(Point2& mu, const SharedDiagonal& model, int i); -// void print(string s) const; -// double error(const Simulated2DValues& c) const; -//}; -// -//class Simulated2DOdometry { -// Simulated2DOdometry(Point2& mu, const SharedDiagonal& model, int i1, int i2); -// void print(string s) const; -// double error(const Simulated2DValues& c) const; -//}; -// -//class Simulated2DOrientedOdometry { -// Simulated2DOrientedOdometry(Pose2& mu, const SharedDiagonal& model, int i1, int i2); -// void print(string s) const; -// double error(const Simulated2DOrientedValues& c) const; -//}; -// -//class Simulated2DMeasurement { -// Simulated2DMeasurement(Point2& mu, const SharedDiagonal& model, int i, int j); -// void print(string s) const; -// double error(const Simulated2DValues& c) const; -//}; -// -//class GaussianFactor { -// GaussianFactor(string key1, -// Matrix A1, -// Vector b_in, -// const SharedDiagonal& model); -// GaussianFactor(string key1, -// Matrix A1, -// string key2, -// Matrix A2, -// Vector b_in, -// const SharedDiagonal& model); -// GaussianFactor(string key1, -// Matrix A1, -// string key2, -// Matrix A2, -// string key3, -// Matrix A3, -// Vector b_in, -// const SharedDiagonal& model); -// bool involves(string key) const; -// Matrix getA(string key) const; -// pair matrix(const Ordering& ordering) const; -// pair eliminate(string key) const; -//}; -// -//class GaussianFactorGraph { -// GaussianConditional* eliminateOne(string key); -// GaussianBayesNet* eliminate_(const Ordering& ordering); -// VectorValues* optimize_(const Ordering& ordering); -// pair matrix(const Ordering& ordering) const; -// VectorValues* steepestDescent_(const VectorValues& x0) const; -// VectorValues* conjugateGradientDescent_(const VectorValues& x0) const; -//}; -// -//class gtsam::Pose2Values{ -// Pose2Values(); -// Pose2 get(string key) const; -// void insert(string name, const gtsam::Pose2& val); -// void print(string s) const; -// void clear(); -// int size(); -//}; -// -//class gtsam::Pose2Factor { -// Pose2Factor(string key1, string key2, -// const gtsam::Pose2& measured, Matrix measurement_covariance); -// void print(string name) const; -// double error(const gtsam::Pose2Values& c) const; -// size_t size() const; -// GaussianFactor* linearize(const gtsam::Pose2Values& config) const; -//}; -// -//class gtsam::pose2SLAM::Graph{ -// pose2SLAM::Graph(); -// void print(string s) const; -// GaussianFactorGraph* linearize_(const gtsam::Pose2Values& config) const; -// void push_back(Pose2Factor* factor); -//}; -// -//class SymbolicFactor{ -// SymbolicFactor(const Ordering& keys); -// void print(string s) const; -//}; -// -//class Simulated2DPosePrior { -// GaussianFactor* linearize(const Simulated2DValues& config) const; -//}; -// -//class Simulated2DOrientedPosePrior { -// GaussianFactor* linearize(const Simulated2DOrientedValues& config) const; -//}; -// -//class Simulated2DPointPrior { -// GaussianFactor* linearize(const Simulated2DValues& config) const; -//}; -// -//class Simulated2DOdometry { -// GaussianFactor* linearize(const Simulated2DValues& config) const; -//}; -// -//class Simulated2DOrientedOdometry { -// GaussianFactor* linearize(const Simulated2DOrientedValues& config) const; -//}; -// -//class Simulated2DMeasurement { -// GaussianFactor* linearize(const Simulated2DValues& config) const; -//}; -// -//class gtsam::Pose2SLAMOptimizer { -// Pose2SLAMOptimizer(string dataset_name); -// void print(string s) const; -// void update(Vector x) const; -// Vector optimize() const; -// double error() const; -// Matrix a1() const; -// Matrix a2() const; -// Vector b1() const; -// Vector b2() const; -//}; +#include +template +virtual class BetweenFactor : gtsam::NonlinearFactor { + BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); +}; + + +#include +template +virtual class NonlinearEquality : gtsam::NonlinearFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); +}; + + +#include +template +virtual class RangeFactor : gtsam::NonlinearFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactorPosePoint2; +typedef gtsam::RangeFactor RangeFactorPosePoint3; +typedef gtsam::RangeFactor RangeFactorPose2; +typedef gtsam::RangeFactor RangeFactorPose3; +typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; +typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; + + +#include +template +virtual class BearingFactor : gtsam::NonlinearFactor { + BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::BearingFactor BearingFactor2D; + + +#include +template +virtual class BearingRangeFactor : gtsam::NonlinearFactor { + BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; + + +#include +template +virtual class GenericProjectionFactor : gtsam::NonlinearFactor { + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k); + gtsam::Point2 measured() const; + CALIBRATION* calibration() const; +}; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; +// FIXME: Add Cal3DS2 when it has a 'calibrate' function +//typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; + + +#include +template +virtual class GeneralSFMFactor : gtsam::NonlinearFactor { + GeneralSFMFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t cameraKey, size_t landmarkKey); + gtsam::Point2 measured() const; +}; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; +// FIXME: Add Cal3DS2 when it has a 'calibrate' function +//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; + +// FIXME: Add Cal3DS2 when it has a 'calibrate' function +template +virtual class GeneralSFMFactor2 : gtsam::NonlinearFactor { + GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey); + gtsam::Point2 measured() const; +}; + + +#include +template +virtual class GenericStereoFactor : gtsam::NonlinearFactor { + GenericStereoFactor(const gtsam::StereoPoint2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t landmarkKey, const gtsam::Cal3_S2Stereo* K); + gtsam::StereoPoint2 measured() const; + gtsam::Cal3_S2Stereo* calibration() const; +}; +typedef gtsam::GenericStereoFactor GenericStereoFactor3D; + +#include +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model); + + +//************************************************************************* +// Utilities +//************************************************************************* + +namespace utilities { + + #include + Matrix extractPoint2(const gtsam::Values& values); + Matrix extractPoint3(const gtsam::Values& values); + Matrix extractPose2(const gtsam::Values& values); + Matrix extractPose3(const gtsam::Values& values); + void perturbPoint2(gtsam::Values& values, double sigma, int seed); + void perturbPoint3(gtsam::Values& values, double sigma, int seed); + void insertBackprojections(gtsam::Values& values, const gtsam::SimpleCamera& c, Vector J, Matrix Z, double depth); + void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K); + Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values); + +} //\namespace utilities + +} diff --git a/gtsam/3rdparty/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/CMakeLists.txt index 4a6a849e9..3ba310a27 100644 --- a/gtsam/3rdparty/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/CMakeLists.txt @@ -64,6 +64,10 @@ set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) find_package(StandardMathLibrary) + +set(EIGEN_TEST_CUSTOM_LINKER_FLAGS "" CACHE STRING "Additional linker flags when linking unit tests.") +set(EIGEN_TEST_CUSTOM_CXX_FLAGS "" CACHE STRING "Additional compiler flags when compiling unit tests.") + set(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO "") if(NOT STANDARD_MATH_LIBRARY_FOUND) @@ -103,6 +107,8 @@ endif() add_definitions("-DEIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS") +set(EIGEN_TEST_MAX_SIZE "320" CACHE STRING "Maximal matrix/vector size, default is 320") + if(CMAKE_COMPILER_IS_GNUCXX) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wnon-virtual-dtor -Wno-long-long -ansi -Wundef -Wcast-align -Wchar-subscripts -Wall -W -Wpointer-arith -Wwrite-strings -Wformat-security -fexceptions -fno-check-new -fno-common -fstrict-aliasing") set(CMAKE_CXX_FLAGS_DEBUG "-g3") @@ -158,7 +164,7 @@ if(CMAKE_COMPILER_IS_GNUCXX) option(EIGEN_TEST_NEON "Enable/Disable Neon in tests/examples" OFF) if(EIGEN_TEST_NEON) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfloat-abi=softfp -mfpu=neon -mcpu=cortex-a8") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon -mcpu=cortex-a8") message(STATUS "Enabling NEON in tests/examples") endif() @@ -301,44 +307,9 @@ add_subdirectory(Eigen) add_subdirectory(doc EXCLUDE_FROM_ALL) -add_custom_target(buildtests) -add_custom_target(check COMMAND "ctest") -add_dependencies(check buildtests) - -# CMake/Ctest does not allow us to change the build command, -# so we have to workaround by directly editing the generated DartConfiguration.tcl file -# save CMAKE_MAKE_PROGRAM -set(CMAKE_MAKE_PROGRAM_SAVE ${CMAKE_MAKE_PROGRAM}) -# and set a fake one -set(CMAKE_MAKE_PROGRAM "@EIGEN_MAKECOMMAND_PLACEHOLDER@") - -include(CTest) +include(EigenConfigureTesting) +# fixme, not sure this line is still needed: enable_testing() # must be called from the root CMakeLists, see man page -include(EigenTesting) -ei_init_testing() - -# overwrite default DartConfiguration.tcl -# The worarounds are different for each version of the MSVC IDE -if(MSVC_IDE) - if(MSVC_VERSION EQUAL 1600) # MSVC 2010 - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests.vcxproj /p:Configuration=\${CTEST_CONFIGURATION_TYPE} \n # ") - else() # MSVC 2008 (TODO check MSVC 2005) - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} /project buildtests") - endif() -else() - # for make and nmake - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests") -endif() - -configure_file(${CMAKE_BINARY_DIR}/DartConfiguration.tcl ${CMAKE_BINARY_DIR}/DartConfiguration.tcl) -# restore default CMAKE_MAKE_PROGRAM -set(CMAKE_MAKE_PROGRAM ${CMAKE_MAKE_PROGRAM_SAVE}) -# un-set temporary variables so that it is like they never existed. -# CMake 2.6.3 introduces the more logical unset() syntax for this. -set(CMAKE_MAKE_PROGRAM_SAVE) -set(EIGEN_MAKECOMMAND_PLACEHOLDER) - -configure_file(${CMAKE_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake) if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) @@ -347,15 +318,13 @@ else() add_subdirectory(test EXCLUDE_FROM_ALL) endif() -if(NOT MSVC) - if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) - add_subdirectory(blas) - add_subdirectory(lapack) - else() - add_subdirectory(blas EXCLUDE_FROM_ALL) - add_subdirectory(lapack EXCLUDE_FROM_ALL) - endif() -endif(NOT MSVC) +if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) + add_subdirectory(blas) + add_subdirectory(lapack) +else() + add_subdirectory(blas EXCLUDE_FROM_ALL) + add_subdirectory(lapack EXCLUDE_FROM_ALL) +endif() add_subdirectory(unsupported) @@ -369,6 +338,10 @@ if(EIGEN_BUILD_BTL) add_subdirectory(bench/btl EXCLUDE_FROM_ALL) endif(EIGEN_BUILD_BTL) +if(NOT WIN32) + add_subdirectory(bench/spbench EXCLUDE_FROM_ALL) +endif(NOT WIN32) + ei_testing_print_summary() message(STATUS "") diff --git a/gtsam/3rdparty/Eigen/COPYING.BSD b/gtsam/3rdparty/Eigen/COPYING.BSD new file mode 100644 index 000000000..11971ffe2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/COPYING.BSD @@ -0,0 +1,26 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/CTestConfig.cmake b/gtsam/3rdparty/Eigen/CTestConfig.cmake index 7edc9d48d..a5a4eb012 100644 --- a/gtsam/3rdparty/Eigen/CTestConfig.cmake +++ b/gtsam/3rdparty/Eigen/CTestConfig.cmake @@ -8,6 +8,6 @@ set(CTEST_PROJECT_NAME "Eigen") set(CTEST_NIGHTLY_START_TIME "00:00:00 UTC") set(CTEST_DROP_METHOD "http") -set(CTEST_DROP_SITE "eigen.tuxfamily.org") +set(CTEST_DROP_SITE "manao.inria.fr") set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen") set(CTEST_DROP_SITE_CDASH TRUE) diff --git a/gtsam/3rdparty/Eigen/Eigen/Cholesky b/gtsam/3rdparty/Eigen/Eigen/Cholesky index 53f7bf911..f727f5d89 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Cholesky +++ b/gtsam/3rdparty/Eigen/Eigen/Cholesky @@ -5,8 +5,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - /** \defgroup Cholesky_Module Cholesky module * * @@ -24,8 +22,9 @@ namespace Eigen { #include "src/misc/Solve.h" #include "src/Cholesky/LLT.h" #include "src/Cholesky/LDLT.h" - -} // namespace Eigen +#ifdef EIGEN_USE_LAPACKE +#include "src/Cholesky/LLT_MKL.h" +#endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/CholmodSupport b/gtsam/3rdparty/Eigen/Eigen/CholmodSupport new file mode 100644 index 000000000..745b884e7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/CholmodSupport @@ -0,0 +1,45 @@ +#ifndef EIGEN_CHOLMODSUPPORT_MODULE_H +#define EIGEN_CHOLMODSUPPORT_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +extern "C" { + #include +} + +/** \ingroup Support_modules + * \defgroup CholmodSupport_Module CholmodSupport module + * + * This module provides an interface to the Cholmod library which is part of the suitesparse package. + * It provides the two following main factorization classes: + * - class CholmodSupernodalLLT: a supernodal LLT Cholesky factorization. + * - class CholmodDecomposiiton: a general L(D)LT Cholesky factorization with automatic or explicit runtime selection of the underlying factorization method (supernodal or simplicial). + * + * For the sake of completeness, this module also propose the two following classes: + * - class CholmodSimplicialLLT + * - class CholmodSimplicialLDLT + * Note that these classes does not bring any particular advantage compared to the built-in + * SimplicialLLT and SimplicialLDLT factorization classes. + * + * \code + * #include + * \endcode + * + * In order to use this module, the cholmod headers must be accessible from the include paths, and your binary must be linked to the cholmod library and its dependencies. + * The dependencies depend on how cholmod has been compiled. + * For a cmake based project, you can use our FindCholmod.cmake module to help you in this task. + * + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/CholmodSupport/CholmodSupport.h" + + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_CHOLMODSUPPORT_MODULE_H + diff --git a/gtsam/3rdparty/Eigen/Eigen/Core b/gtsam/3rdparty/Eigen/Eigen/Core index a5025e37e..0cf101636 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Core +++ b/gtsam/3rdparty/Eigen/Eigen/Core @@ -34,6 +34,12 @@ // defined e.g. EIGEN_DONT_ALIGN) so it needs to be done before we do anything with vectorization. #include "src/Core/util/Macros.h" +#include + +// this include file manages BLAS and MKL related macros +// and inclusion of their respective header files +#include "src/Core/util/MKL_support.h" + // if alignment is disabled, then disable vectorization. Note: EIGEN_ALIGN is the proper check, it takes into // account both the user's will (EIGEN_DONT_ALIGN) and our own platform checks #if !EIGEN_ALIGN @@ -136,7 +142,7 @@ #endif // MSVC for windows mobile does not have the errno.h file -#if !(defined(_MSC_VER) && defined(_WIN32_WCE)) +#if !(defined(_MSC_VER) && defined(_WIN32_WCE)) && !defined(__ARMCC_VERSION) #define EIGEN_HAS_ERRNO #endif @@ -146,7 +152,6 @@ #include #include #include -#include #include #include #include @@ -175,9 +180,6 @@ #include #endif -// defined in bits/termios.h -#undef B0 - /** \brief Namespace containing all symbols from the %Eigen library. */ namespace Eigen { @@ -201,6 +203,8 @@ inline static const char *SimdInstructionSetsInUse(void) { #endif } +} // end namespace Eigen + #define STAGE10_FULL_EIGEN2_API 10 #define STAGE20_RESOLVE_API_CONFLICTS 20 #define STAGE30_FULL_EIGEN3_API 30 @@ -247,6 +251,10 @@ using std::ptrdiff_t; * \endcode */ +/** \defgroup Support_modules Support modules [category] + * Category of modules which add support for external libraries. + */ + #include "src/Core/util/Constants.h" #include "src/Core/util/ForwardDeclarations.h" #include "src/Core/util/Meta.h" @@ -318,15 +326,15 @@ using std::ptrdiff_t; #include "src/Core/CommaInitializer.h" #include "src/Core/Flagged.h" #include "src/Core/ProductBase.h" -#include "src/Core/Product.h" +#include "src/Core/GeneralProduct.h" #include "src/Core/TriangularMatrix.h" #include "src/Core/SelfAdjointView.h" -#include "src/Core/SolveTriangular.h" +#include "src/Core/products/GeneralBlockPanelKernel.h" #include "src/Core/products/Parallelizer.h" #include "src/Core/products/CoeffBasedProduct.h" -#include "src/Core/products/GeneralBlockPanelKernel.h" #include "src/Core/products/GeneralMatrixVector.h" #include "src/Core/products/GeneralMatrixMatrix.h" +#include "src/Core/SolveTriangular.h" #include "src/Core/products/GeneralMatrixMatrixTriangular.h" #include "src/Core/products/SelfadjointMatrixVector.h" #include "src/Core/products/SelfadjointMatrixMatrix.h" @@ -347,7 +355,20 @@ using std::ptrdiff_t; #include "src/Core/ArrayBase.h" #include "src/Core/ArrayWrapper.h" -} // namespace Eigen +#ifdef EIGEN_USE_BLAS +#include "src/Core/products/GeneralMatrixMatrix_MKL.h" +#include "src/Core/products/GeneralMatrixVector_MKL.h" +#include "src/Core/products/GeneralMatrixMatrixTriangular_MKL.h" +#include "src/Core/products/SelfadjointMatrixMatrix_MKL.h" +#include "src/Core/products/SelfadjointMatrixVector_MKL.h" +#include "src/Core/products/TriangularMatrixMatrix_MKL.h" +#include "src/Core/products/TriangularMatrixVector_MKL.h" +#include "src/Core/products/TriangularSolverMatrix_MKL.h" +#endif // EIGEN_USE_BLAS + +#ifdef EIGEN_USE_MKL_VML +#include "src/Core/Assign_MKL.h" +#endif #include "src/Core/GlobalFunctions.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Eigen2Support b/gtsam/3rdparty/Eigen/Eigen/Eigen2Support index d96592a8d..c2aa2f618 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Eigen2Support +++ b/gtsam/3rdparty/Eigen/Eigen/Eigen2Support @@ -31,9 +31,8 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - -/** \defgroup Eigen2Support_Module Eigen2 support module +/** \ingroup Support_modules + * \defgroup Eigen2Support_Module Eigen2 support module * This module provides a couple of deprecated functions improving the compatibility with Eigen2. * * To use it, define EIGEN2_SUPPORT before including any Eigen header @@ -56,13 +55,29 @@ namespace Eigen { #include "src/Eigen2Support/MathFunctions.h" -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" // Eigen2 used to include iostream #include +#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, SizeSuffix) \ +using Eigen::Matrix##SizeSuffix##TypeSuffix; \ +using Eigen::Vector##SizeSuffix##TypeSuffix; \ +using Eigen::RowVector##SizeSuffix##TypeSuffix; + +#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(TypeSuffix) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 2) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 3) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 4) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, X) \ + +#define EIGEN_USING_MATRIX_TYPEDEFS \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(i) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(f) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(d) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cf) \ +EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cd) + #define USING_PART_OF_NAMESPACE_EIGEN \ EIGEN_USING_MATRIX_TYPEDEFS \ using Eigen::Matrix; \ diff --git a/gtsam/3rdparty/Eigen/Eigen/Eigenvalues b/gtsam/3rdparty/Eigen/Eigen/Eigenvalues index 250c0f466..af99ccd1f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Eigenvalues +++ b/gtsam/3rdparty/Eigen/Eigen/Eigenvalues @@ -9,8 +9,7 @@ #include "Jacobi" #include "Householder" #include "LU" - -namespace Eigen { +#include "Geometry" /** \defgroup Eigenvalues_Module Eigenvalues module * @@ -35,8 +34,11 @@ namespace Eigen { #include "src/Eigenvalues/ComplexSchur.h" #include "src/Eigenvalues/ComplexEigenSolver.h" #include "src/Eigenvalues/MatrixBaseEigenvalues.h" - -} // namespace Eigen +#ifdef EIGEN_USE_LAPACKE +#include "src/Eigenvalues/RealSchur_MKL.h" +#include "src/Eigenvalues/ComplexSchur_MKL.h" +#include "src/Eigenvalues/SelfAdjointEigenSolver_MKL.h" +#endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Geometry b/gtsam/3rdparty/Eigen/Eigen/Geometry index 78277c0c5..efd9d4504 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Geometry +++ b/gtsam/3rdparty/Eigen/Eigen/Geometry @@ -13,8 +13,6 @@ #define M_PI 3.14159265358979323846 #endif -namespace Eigen { - /** \defgroup Geometry_Module Geometry module * * @@ -58,8 +56,6 @@ namespace Eigen { #include "src/Eigen2Support/Geometry/All.h" #endif -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_GEOMETRY_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Householder b/gtsam/3rdparty/Eigen/Eigen/Householder index 6b86cf65c..6e348db5c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Householder +++ b/gtsam/3rdparty/Eigen/Eigen/Householder @@ -5,8 +5,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - /** \defgroup Householder_Module Householder module * This module provides Householder transformations. * @@ -19,8 +17,6 @@ namespace Eigen { #include "src/Householder/HouseholderSequence.h" #include "src/Householder/BlockHouseholder.h" -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_HOUSEHOLDER_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers b/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers new file mode 100644 index 000000000..315c2dd1e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers @@ -0,0 +1,40 @@ +#ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H +#define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H + +#include "SparseCore" +#include "OrderingMethods" + +#include "src/Core/util/DisableStupidWarnings.h" + +/** \ingroup Sparse_modules + * \defgroup IterativeLinearSolvers_Module IterativeLinearSolvers module + * + * This module currently provides iterative methods to solve problems of the form \c A \c x = \c b, where \c A is a squared matrix, usually very large and sparse. + * Those solvers are accessible via the following classes: + * - ConjugateGradient for selfadjoint (hermitian) matrices, + * - BiCGSTAB for general square matrices. + * + * These iterative solvers are associated with some preconditioners: + * - IdentityPreconditioner - not really useful + * - DiagonalPreconditioner - also called JAcobi preconditioner, work very well on diagonal dominant matrices. + * - IncompleteILUT - incomplete LU factorization with dual thresholding + * + * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport. + * + * \code + * #include + * \endcode + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/IterativeLinearSolvers/IterativeSolverBase.h" +#include "src/IterativeLinearSolvers/BasicPreconditioners.h" +#include "src/IterativeLinearSolvers/ConjugateGradient.h" +#include "src/IterativeLinearSolvers/BiCGSTAB.h" +#include "src/IterativeLinearSolvers/IncompleteLUT.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_ITERATIVELINEARSOLVERS_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Jacobi b/gtsam/3rdparty/Eigen/Eigen/Jacobi index afa676813..ba8a4dc36 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Jacobi +++ b/gtsam/3rdparty/Eigen/Eigen/Jacobi @@ -5,8 +5,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - /** \defgroup Jacobi_Module Jacobi module * This module provides Jacobi and Givens rotations. * @@ -21,8 +19,6 @@ namespace Eigen { #include "src/Jacobi/Jacobi.h" -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_JACOBI_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/LU b/gtsam/3rdparty/Eigen/Eigen/LU index 226f88ca3..db5795504 100644 --- a/gtsam/3rdparty/Eigen/Eigen/LU +++ b/gtsam/3rdparty/Eigen/Eigen/LU @@ -5,8 +5,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - /** \defgroup LU_Module LU module * This module includes %LU decomposition and related notions such as matrix inversion and determinant. * This module defines the following MatrixBase methods: @@ -23,6 +21,9 @@ namespace Eigen { #include "src/misc/Image.h" #include "src/LU/FullPivLU.h" #include "src/LU/PartialPivLU.h" +#ifdef EIGEN_USE_LAPACKE +#include "src/LU/PartialPivLU_MKL.h" +#endif #include "src/LU/Determinant.h" #include "src/LU/Inverse.h" @@ -34,8 +35,6 @@ namespace Eigen { #include "src/Eigen2Support/LU.h" #endif -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_LU_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/LeastSquares b/gtsam/3rdparty/Eigen/Eigen/LeastSquares index 93a6302dc..35137c25d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/LeastSquares +++ b/gtsam/3rdparty/Eigen/Eigen/LeastSquares @@ -15,8 +15,6 @@ #include "Eigenvalues" #include "Geometry" -namespace Eigen { - /** \defgroup LeastSquares_Module LeastSquares module * This module provides linear regression and related features. * @@ -27,8 +25,6 @@ namespace Eigen { #include "src/Eigen2Support/LeastSquares.h" -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN2_SUPPORT diff --git a/gtsam/3rdparty/Eigen/Eigen/OrderingMethods b/gtsam/3rdparty/Eigen/Eigen/OrderingMethods new file mode 100644 index 000000000..1e2d87452 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/OrderingMethods @@ -0,0 +1,23 @@ +#ifndef EIGEN_ORDERINGMETHODS_MODULE_H +#define EIGEN_ORDERINGMETHODS_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +/** \ingroup Sparse_modules + * \defgroup OrderingMethods_Module OrderingMethods module + * + * This module is currently for internal use only. + * + * + * \code + * #include + * \endcode + */ + +#include "src/OrderingMethods/Amd.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_ORDERINGMETHODS_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport b/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport new file mode 100644 index 000000000..7c616ee5e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport @@ -0,0 +1,46 @@ +#ifndef EIGEN_PASTIXSUPPORT_MODULE_H +#define EIGEN_PASTIXSUPPORT_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +#include +extern "C" { +#include +#include +} + +#ifdef complex +#undef complex +#endif + +/** \ingroup Support_modules + * \defgroup PaStiXSupport_Module PaStiXSupport module + * + * This module provides an interface to the PaSTiX library. + * PaSTiX is a general \b supernodal, \b parallel and \b opensource sparse solver. + * It provides the two following main factorization classes: + * - class PastixLLT : a supernodal, parallel LLt Cholesky factorization. + * - class PastixLDLT: a supernodal, parallel LDLt Cholesky factorization. + * - class PastixLU : a supernodal, parallel LU factorization (optimized for a symmetric pattern). + * + * \code + * #include + * \endcode + * + * In order to use this module, the PaSTiX headers must be accessible from the include paths, and your binary must be linked to the PaSTiX library and its dependencies. + * The dependencies depend on how PaSTiX has been compiled. + * For a cmake based project, you can use our FindPaSTiX.cmake module to help you in this task. + * + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/PaStiXSupport/PaStiXSupport.h" + + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_PASTIXSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/PardisoSupport b/gtsam/3rdparty/Eigen/Eigen/PardisoSupport new file mode 100644 index 000000000..99330ce7a --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/PardisoSupport @@ -0,0 +1,30 @@ +#ifndef EIGEN_PARDISOSUPPORT_MODULE_H +#define EIGEN_PARDISOSUPPORT_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +#include + +#include + +/** \ingroup Support_modules + * \defgroup PardisoSupport_Module PardisoSupport module + * + * This module brings support for the Intel(R) MKL PARDISO direct sparse solvers. + * + * \code + * #include + * \endcode + * + * In order to use this module, the MKL headers must be accessible from the include paths, and your binary must be linked to the MKL library and its dependencies. + * See this \ref TopicUsingIntelMKL "page" for more information on MKL-Eigen integration. + * + */ + +#include "src/PardisoSupport/PardisoSupport.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_PARDISOSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/QR b/gtsam/3rdparty/Eigen/Eigen/QR index 97c1788ee..ac5b02693 100644 --- a/gtsam/3rdparty/Eigen/Eigen/QR +++ b/gtsam/3rdparty/Eigen/Eigen/QR @@ -9,8 +9,6 @@ #include "Jacobi" #include "Householder" -namespace Eigen { - /** \defgroup QR_Module QR module * * @@ -28,13 +26,15 @@ namespace Eigen { #include "src/QR/HouseholderQR.h" #include "src/QR/FullPivHouseholderQR.h" #include "src/QR/ColPivHouseholderQR.h" +#ifdef EIGEN_USE_LAPACKE +#include "src/QR/HouseholderQR_MKL.h" +#include "src/QR/ColPivHouseholderQR_MKL.h" +#endif #ifdef EIGEN2_SUPPORT #include "src/Eigen2Support/QR.h" #endif -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #ifdef EIGEN2_SUPPORT diff --git a/gtsam/3rdparty/Eigen/Eigen/SVD b/gtsam/3rdparty/Eigen/Eigen/SVD index 7c987a9dd..fd310017a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SVD +++ b/gtsam/3rdparty/Eigen/Eigen/SVD @@ -7,8 +7,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -namespace Eigen { - /** \defgroup SVD_Module SVD module * * @@ -24,14 +22,15 @@ namespace Eigen { #include "src/misc/Solve.h" #include "src/SVD/JacobiSVD.h" +#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT) +#include "src/SVD/JacobiSVD_MKL.h" +#endif #include "src/SVD/UpperBidiagonalization.h" #ifdef EIGEN2_SUPPORT #include "src/Eigen2Support/SVD.h" #endif -} // namespace Eigen - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SVD_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Sparse b/gtsam/3rdparty/Eigen/Eigen/Sparse index 7425b3a41..2d1757172 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Sparse +++ b/gtsam/3rdparty/Eigen/Eigen/Sparse @@ -1,69 +1,23 @@ #ifndef EIGEN_SPARSE_MODULE_H #define EIGEN_SPARSE_MODULE_H -#include "Core" - -#include "src/Core/util/DisableStupidWarnings.h" - -#include -#include -#include -#include -#include - -#ifdef EIGEN2_SUPPORT -#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET -#endif - -#ifndef EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET -#error The sparse module API is not stable yet. To use it anyway, please define the EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET preprocessor token. -#endif - -namespace Eigen { - -/** \defgroup Sparse_Module Sparse module +/** \defgroup Sparse_modules Sparse modules * - * - * - * See the \ref TutorialSparse "Sparse tutorial" + * Meta-module including all related modules: + * - SparseCore + * - OrderingMethods + * - SparseCholesky + * - IterativeLinearSolvers * * \code * #include * \endcode */ -/** The type used to identify a general sparse storage. */ -struct Sparse {}; - -#include "src/Sparse/SparseUtil.h" -#include "src/Sparse/SparseMatrixBase.h" -#include "src/Sparse/CompressedStorage.h" -#include "src/Sparse/AmbiVector.h" -#include "src/Sparse/SparseMatrix.h" -#include "src/Sparse/DynamicSparseMatrix.h" -#include "src/Sparse/MappedSparseMatrix.h" -#include "src/Sparse/SparseVector.h" -#include "src/Sparse/CoreIterators.h" -#include "src/Sparse/SparseBlock.h" -#include "src/Sparse/SparseTranspose.h" -#include "src/Sparse/SparseCwiseUnaryOp.h" -#include "src/Sparse/SparseCwiseBinaryOp.h" -#include "src/Sparse/SparseDot.h" -#include "src/Sparse/SparseAssign.h" -#include "src/Sparse/SparseRedux.h" -#include "src/Sparse/SparseFuzzy.h" -#include "src/Sparse/SparseProduct.h" -#include "src/Sparse/SparseSparseProduct.h" -#include "src/Sparse/SparseDenseProduct.h" -#include "src/Sparse/SparseDiagonalProduct.h" -#include "src/Sparse/SparseTriangularView.h" -#include "src/Sparse/SparseSelfAdjointView.h" -#include "src/Sparse/TriangularSolver.h" -#include "src/Sparse/SparseView.h" - -} // namespace Eigen - -#include "src/Core/util/ReenableStupidWarnings.h" +#include "SparseCore" +#include "OrderingMethods" +#include "SparseCholesky" +#include "IterativeLinearSolvers" #endif // EIGEN_SPARSE_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseCholesky b/gtsam/3rdparty/Eigen/Eigen/SparseCholesky new file mode 100644 index 000000000..5f82742f7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/SparseCholesky @@ -0,0 +1,30 @@ +#ifndef EIGEN_SPARSECHOLESKY_MODULE_H +#define EIGEN_SPARSECHOLESKY_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +/** \ingroup Sparse_modules + * \defgroup SparseCholesky_Module SparseCholesky module + * + * This module currently provides two variants of the direct sparse Cholesky decomposition for selfadjoint (hermitian) matrices. + * Those decompositions are accessible via the following classes: + * - SimplicialLLt, + * - SimplicialLDLt + * + * Such problems can also be solved using the ConjugateGradient solver from the IterativeLinearSolvers module. + * + * \code + * #include + * \endcode + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/SparseCholesky/SimplicialCholesky.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_SPARSECHOLESKY_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseCore b/gtsam/3rdparty/Eigen/Eigen/SparseCore new file mode 100644 index 000000000..41d28c928 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/SparseCore @@ -0,0 +1,66 @@ +#ifndef EIGEN_SPARSECORE_MODULE_H +#define EIGEN_SPARSECORE_MODULE_H + +#include "Core" + +#include "src/Core/util/DisableStupidWarnings.h" + +#include +#include +#include +#include +#include + +/** \ingroup Sparse_modules + * \defgroup SparseCore_Module SparseCore module + * + * This module provides a sparse matrix representation, and basic associatd matrix manipulations + * and operations. + * + * See the \ref TutorialSparse "Sparse tutorial" + * + * \code + * #include + * \endcode + * + * This module depends on: Core. + */ + +namespace Eigen { + +/** The type used to identify a general sparse storage. */ +struct Sparse {}; + +} + +#include "src/SparseCore/SparseUtil.h" +#include "src/SparseCore/SparseMatrixBase.h" +#include "src/SparseCore/CompressedStorage.h" +#include "src/SparseCore/AmbiVector.h" +#include "src/SparseCore/SparseMatrix.h" +#include "src/SparseCore/MappedSparseMatrix.h" +#include "src/SparseCore/SparseVector.h" +#include "src/SparseCore/CoreIterators.h" +#include "src/SparseCore/SparseBlock.h" +#include "src/SparseCore/SparseTranspose.h" +#include "src/SparseCore/SparseCwiseUnaryOp.h" +#include "src/SparseCore/SparseCwiseBinaryOp.h" +#include "src/SparseCore/SparseDot.h" +#include "src/SparseCore/SparsePermutation.h" +#include "src/SparseCore/SparseAssign.h" +#include "src/SparseCore/SparseRedux.h" +#include "src/SparseCore/SparseFuzzy.h" +#include "src/SparseCore/ConservativeSparseSparseProduct.h" +#include "src/SparseCore/SparseSparseProductWithPruning.h" +#include "src/SparseCore/SparseProduct.h" +#include "src/SparseCore/SparseDenseProduct.h" +#include "src/SparseCore/SparseDiagonalProduct.h" +#include "src/SparseCore/SparseTriangularView.h" +#include "src/SparseCore/SparseSelfAdjointView.h" +#include "src/SparseCore/TriangularSolver.h" +#include "src/SparseCore/SparseView.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_SPARSECORE_MODULE_H + diff --git a/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport b/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport new file mode 100644 index 000000000..575e14fbc --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport @@ -0,0 +1,59 @@ +#ifndef EIGEN_SUPERLUSUPPORT_MODULE_H +#define EIGEN_SUPERLUSUPPORT_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +#ifdef EMPTY +#define EIGEN_EMPTY_WAS_ALREADY_DEFINED +#endif + +typedef int int_t; +#include +#include +#include + +// slu_util.h defines a preprocessor token named EMPTY which is really polluting, +// so we remove it in favor of a SUPERLU_EMPTY token. +// If EMPTY was already defined then we don't undef it. + +#if defined(EIGEN_EMPTY_WAS_ALREADY_DEFINED) +# undef EIGEN_EMPTY_WAS_ALREADY_DEFINED +#elif defined(EMPTY) +# undef EMPTY +#endif + +#define SUPERLU_EMPTY (-1) + +namespace Eigen { struct SluMatrix; } + +/** \ingroup Support_modules + * \defgroup SuperLUSupport_Module SuperLUSupport module + * + * This module provides an interface to the SuperLU library. + * It provides the following factorization class: + * - class SuperLU: a supernodal sequential LU factorization. + * - class SuperILU: a supernodal sequential incomplete LU factorization (to be used as a preconditioner for iterative methods). + * + * \warning When including this module, you have to use SUPERLU_EMPTY instead of EMPTY which is no longer defined because it is too polluting. + * + * \code + * #include + * \endcode + * + * In order to use this module, the superlu headers must be accessible from the include paths, and your binary must be linked to the superlu library and its dependencies. + * The dependencies depend on how superlu has been compiled. + * For a cmake based project, you can use our FindSuperLU.cmake module to help you in this task. + * + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/SuperLUSupport/SuperLUSupport.h" + + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_SUPERLUSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport b/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport new file mode 100644 index 000000000..984f64a84 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport @@ -0,0 +1,36 @@ +#ifndef EIGEN_UMFPACKSUPPORT_MODULE_H +#define EIGEN_UMFPACKSUPPORT_MODULE_H + +#include "SparseCore" + +#include "src/Core/util/DisableStupidWarnings.h" + +extern "C" { +#include +} + +/** \ingroup Support_modules + * \defgroup UmfPackSupport_Module UmfPackSupport module + * + * This module provides an interface to the UmfPack library which is part of the suitesparse package. + * It provides the following factorization class: + * - class UmfPackLU: a multifrontal sequential LU factorization. + * + * \code + * #include + * \endcode + * + * In order to use this module, the umfpack headers must be accessible from the include paths, and your binary must be linked to the umfpack library and its dependencies. + * The dependencies depend on how umfpack has been compiled. + * For a cmake based project, you can use our FindUmfPack.cmake module to help you in this task. + * + */ + +#include "src/misc/Solve.h" +#include "src/misc/SparseSolve.h" + +#include "src/UmfPackSupport/UmfPackSupport.h" + +#include "src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_UMFPACKSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h index f47b2ea56..a5e3d5469 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h @@ -1,9 +1,10 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2011 Gael Guennebaud // Copyright (C) 2009 Keir Mierle // Copyright (C) 2009 Benoit Jacob +// Copyright (C) 2011 Timothy E. Holy // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -27,17 +28,21 @@ #ifndef EIGEN_LDLT_H #define EIGEN_LDLT_H +namespace Eigen { + namespace internal { template struct LDLT_Traits; } -/** \ingroup cholesky_Module +/** \ingroup Cholesky_Module * * \class LDLT * * \brief Robust Cholesky decomposition of a matrix with pivoting * * \param MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition + * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * The other triangular part won't be read. * * Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite * matrix \f$ A \f$ such that \f$ A = P^TLDL^*P \f$, where P is a permutation matrix, L @@ -48,14 +53,10 @@ template struct LDLT_Traits; * on D also stabilizes the computation. * * Remember that Cholesky decompositions are not rank-revealing. Also, do not use a Cholesky - * decomposition to determine whether a system of equations has a solution. + * decomposition to determine whether a system of equations has a solution. * * \sa MatrixBase::ldlt(), class LLT */ - /* THIS PART OF THE DOX IS CURRENTLY DISABLED BECAUSE INACCURATE BECAUSE OF BUG IN THE DECOMPOSITION CODE - * Note that during the decomposition, only the upper triangular part of A is considered. Therefore, - * the strict lower part does not have to store correct values. - */ template class LDLT { public: @@ -98,6 +99,11 @@ template class LDLT m_isInitialized(false) {} + /** \brief Constructor with decomposition + * + * This calculates the decomposition for the input \a matrix. + * \sa LDLT(Index size) + */ LDLT(const MatrixType& matrix) : m_matrix(matrix.rows(), matrix.cols()), m_transpositions(matrix.rows()), @@ -107,6 +113,14 @@ template class LDLT compute(matrix); } + /** Clear any existing decomposition + * \sa rankUpdate(w,sigma) + */ + void setZero() + { + m_isInitialized = false; + } + /** \returns a view of the upper triangular matrix U */ inline typename Traits::MatrixU matrixU() const { @@ -130,14 +144,14 @@ template class LDLT } /** \returns the coefficients of the diagonal matrix D */ - inline Diagonal vectorD(void) const + inline Diagonal vectorD() const { eigen_assert(m_isInitialized && "LDLT is not initialized."); return m_matrix.diagonal(); } /** \returns true if the matrix is positive (semidefinite) */ - inline bool isPositive(void) const + inline bool isPositive() const { eigen_assert(m_isInitialized && "LDLT is not initialized."); return m_sign == 1; @@ -196,6 +210,9 @@ template class LDLT LDLT& compute(const MatrixType& matrix); + template + LDLT& rankUpdate(const MatrixBase& w,RealScalar alpha=1); + /** \returns the internal LDLT decomposition matrix * * TODO: document the storage layout @@ -211,6 +228,17 @@ template class LDLT inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "LDLT is not initialized."); + return Success; + } + protected: /** \internal @@ -249,7 +277,7 @@ template<> struct ldlt_inplace return true; } - RealScalar cutoff = 0, biggest_in_corner; + RealScalar cutoff(0), biggest_in_corner; for (Index k = 0; k < size; ++k) { @@ -317,6 +345,61 @@ template<> struct ldlt_inplace return true; } + + // Reference for the algorithm: Davis and Hager, "Multiple Rank + // Modifications of a Sparse Cholesky Factorization" (Algorithm 1) + // Trivial rearrangements of their computations (Timothy E. Holy) + // allow their algorithm to work for rank-1 updates even if the + // original matrix is not of full rank. + // Here only rank-1 updates are implemented, to reduce the + // requirement for intermediate storage and improve accuracy + template + static bool updateInPlace(MatrixType& mat, MatrixBase& w, typename MatrixType::RealScalar sigma=1) + { + using internal::isfinite; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + + const Index size = mat.rows(); + eigen_assert(mat.cols() == size && w.size()==size); + + RealScalar alpha = 1; + + // Apply the update + for (Index j = 0; j < size; j++) + { + // Check for termination due to an original decomposition of low-rank + if (!isfinite(alpha)) + break; + + // Update the diagonal terms + RealScalar dj = real(mat.coeff(j,j)); + Scalar wj = w.coeff(j); + RealScalar swj2 = sigma*abs2(wj); + RealScalar gamma = dj*alpha + swj2; + + mat.coeffRef(j,j) += swj2/alpha; + alpha += swj2/dj; + + + // Update the terms of L + Index rs = size-j-1; + w.tail(rs) -= wj * mat.col(j).tail(rs); + if(gamma != 0) + mat.col(j).tail(rs) += (sigma*conj(wj)/gamma)*w.tail(rs); + } + return true; + } + + template + static bool update(MatrixType& mat, const TranspositionType& transpositions, Workspace& tmp, const WType& w, typename MatrixType::RealScalar sigma=1) + { + // Apply the permutation to the input w + tmp = transpositions * w; + + return ldlt_inplace::updateInPlace(mat,tmp,sigma); + } }; template<> struct ldlt_inplace @@ -327,22 +410,29 @@ template<> struct ldlt_inplace Transpose matt(mat); return ldlt_inplace::unblocked(matt, transpositions, temp, sign); } + + template + static EIGEN_STRONG_INLINE bool update(MatrixType& mat, TranspositionType& transpositions, Workspace& tmp, WType& w, typename MatrixType::RealScalar sigma=1) + { + Transpose matt(mat); + return ldlt_inplace::update(matt, transpositions, tmp, w.conjugate(), sigma); + } }; template struct LDLT_Traits { - typedef TriangularView MatrixL; - typedef TriangularView MatrixU; - inline static MatrixL getL(const MatrixType& m) { return m; } - inline static MatrixU getU(const MatrixType& m) { return m.adjoint(); } + typedef const TriangularView MatrixL; + typedef const TriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m; } + static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } }; template struct LDLT_Traits { - typedef TriangularView MatrixL; - typedef TriangularView MatrixU; - inline static MatrixL getL(const MatrixType& m) { return m.adjoint(); } - inline static MatrixU getU(const MatrixType& m) { return m; } + typedef const TriangularView MatrixL; + typedef const TriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } + static inline MatrixU getU(const MatrixType& m) { return m; } }; } // end namespace internal @@ -367,6 +457,37 @@ LDLT& LDLT::compute(const MatrixType& a) return *this; } +/** Update the LDLT decomposition: given A = L D L^T, efficiently compute the decomposition of A + sigma w w^T. + * \param w a vector to be incorporated into the decomposition. + * \param sigma a scalar, +1 for updates and -1 for "downdates," which correspond to removing previously-added column vectors. Optional; default value is +1. + * \sa setZero() + */ +template +template +LDLT& LDLT::rankUpdate(const MatrixBase& w,typename NumTraits::Real sigma) +{ + const Index size = w.rows(); + if (m_isInitialized) + { + eigen_assert(m_matrix.rows()==size); + } + else + { + m_matrix.resize(size,size); + m_matrix.setZero(); + m_transpositions.resize(size); + for (Index i = 0; i < size; i++) + m_transpositions.coeffRef(i) = i; + m_temporary.resize(size); + m_sign = sigma>=0 ? 1 : -1; + m_isInitialized = true; + } + + internal::ldlt_inplace::update(m_matrix, m_transpositions, m_temporary, w, sigma); + + return *this; +} + namespace internal { template struct solve_retval, Rhs> @@ -481,4 +602,6 @@ MatrixBase::ldlt() const return LDLT(derived()); } +} // end namespace Eigen + #endif // EIGEN_LDLT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h index a4ee5b11c..17c6d6b8d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h @@ -25,17 +25,21 @@ #ifndef EIGEN_LLT_H #define EIGEN_LLT_H +namespace Eigen { + namespace internal{ template struct LLT_Traits; } -/** \ingroup cholesky_Module +/** \ingroup Cholesky_Module * * \class LLT * * \brief Standard Cholesky decomposition (LL^T) of a matrix and associated features * * \param MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition + * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * The other triangular part won't be read. * * This class performs a LL^T Cholesky decomposition of a symmetric, positive definite * matrix A such that A = LL^* = U^*U, where L is lower triangular. @@ -49,6 +53,9 @@ template struct LLT_Traits; * use LDLT instead for the semidefinite case. Also, do not use a Cholesky decomposition to determine whether a system of equations * has a solution. * + * Example: \include LLT_example.cpp + * Output: \verbinclude LLT_example.out + * * \sa MatrixBase::llt(), class LDLT */ /* HEY THIS DOX IS DISABLED BECAUSE THERE's A BUG EITHER HERE OR IN LDLT ABOUT THAT (OR BOTH) @@ -178,6 +185,9 @@ template class LLT inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } + template + LLT rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); + protected: /** \internal * Used to compute and store L @@ -190,16 +200,85 @@ template class LLT namespace internal { -template struct llt_inplace; +template struct llt_inplace; -template<> struct llt_inplace +template +static typename MatrixType::Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) { + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::ColXpr ColXpr; + typedef typename internal::remove_all::type ColXprCleaned; + typedef typename ColXprCleaned::SegmentReturnType ColXprSegment; + typedef Matrix TempVectorType; + typedef typename TempVectorType::SegmentReturnType TempVecSegment; + + int n = mat.cols(); + eigen_assert(mat.rows()==n && vec.size()==n); + + TempVectorType temp; + + if(sigma>0) + { + // This version is based on Givens rotations. + // It is faster than the other one below, but only works for updates, + // i.e., for sigma > 0 + temp = sqrt(sigma) * vec; + + for(int i=0; i g; + g.makeGivens(mat(i,i), -temp(i), &mat(i,i)); + + int rs = n-i-1; + if(rs>0) + { + ColXprSegment x(mat.col(i).tail(rs)); + TempVecSegment y(temp.tail(rs)); + apply_rotation_in_the_plane(x, y, g); + } + } + } + else + { + temp = vec; + RealScalar beta = 1; + for(int j=0; j struct llt_inplace +{ + typedef typename NumTraits::Real RealScalar; template static typename MatrixType::Index unblocked(MatrixType& mat) { typedef typename MatrixType::Index Index; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; eigen_assert(mat.rows()==mat.cols()); const Index size = mat.rows(); @@ -254,55 +333,71 @@ template<> struct llt_inplace } return -1; } -}; -template<> struct llt_inplace + template + static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + { + return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); + } +}; + +template struct llt_inplace { + typedef typename NumTraits::Real RealScalar; + template static EIGEN_STRONG_INLINE typename MatrixType::Index unblocked(MatrixType& mat) { Transpose matt(mat); - return llt_inplace::unblocked(matt); + return llt_inplace::unblocked(matt); } template static EIGEN_STRONG_INLINE typename MatrixType::Index blocked(MatrixType& mat) { Transpose matt(mat); - return llt_inplace::blocked(matt); + return llt_inplace::blocked(matt); + } + template + static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + { + Transpose matt(mat); + return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); } }; template struct LLT_Traits { - typedef TriangularView MatrixL; - typedef TriangularView MatrixU; - inline static MatrixL getL(const MatrixType& m) { return m; } - inline static MatrixU getU(const MatrixType& m) { return m.adjoint(); } + typedef const TriangularView MatrixL; + typedef const TriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m; } + static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } static bool inplace_decomposition(MatrixType& m) - { return llt_inplace::blocked(m)==-1; } + { return llt_inplace::blocked(m)==-1; } }; template struct LLT_Traits { - typedef TriangularView MatrixL; - typedef TriangularView MatrixU; - inline static MatrixL getL(const MatrixType& m) { return m.adjoint(); } - inline static MatrixU getU(const MatrixType& m) { return m; } + typedef const TriangularView MatrixL; + typedef const TriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } + static inline MatrixU getU(const MatrixType& m) { return m; } static bool inplace_decomposition(MatrixType& m) - { return llt_inplace::blocked(m)==-1; } + { return llt_inplace::blocked(m)==-1; } }; } // end namespace internal /** Computes / recomputes the Cholesky decomposition A = LL^* = U^*U of \a matrix - * * * \returns a reference to *this + * + * Example: \include TutorialLinAlgComputeTwice.cpp + * Output: \verbinclude TutorialLinAlgComputeTwice.out */ template LLT& LLT::compute(const MatrixType& a) { - assert(a.rows()==a.cols()); + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); m_matrix.resize(size, size); m_matrix = a; @@ -314,6 +409,26 @@ LLT& LLT::compute(const MatrixType& a) return *this; } +/** Performs a rank one update (or dowdate) of the current decomposition. + * If A = LL^* before the rank one update, + * then after it we have LL^* = A + sigma * v v^* where \a v must be a vector + * of same dimension. + */ +template +template +LLT<_MatrixType,_UpLo> LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, const RealScalar& sigma) +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorType); + eigen_assert(v.size()==m_matrix.cols()); + eigen_assert(m_isInitialized); + if(internal::llt_inplace::rankUpdate(m_matrix,v,sigma)>=0) + m_info = NumericalIssue; + else + m_info = Success; + + return *this; +} + namespace internal { template struct solve_retval, Rhs> @@ -383,4 +498,6 @@ SelfAdjointView::llt() const return LLT(m_matrix); } +} // end namespace Eigen + #endif // EIGEN_LLT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h new file mode 100644 index 000000000..64daa445c --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h @@ -0,0 +1,102 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * LLt decomposition based on LAPACKE_?potrf function. + ******************************************************************************** +*/ + +#ifndef EIGEN_LLT_MKL_H +#define EIGEN_LLT_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" +#include + +namespace Eigen { + +namespace internal { + +template struct mkl_llt; + +#define EIGEN_MKL_LLT(EIGTYPE, MKLTYPE, MKLPREFIX) \ +template<> struct mkl_llt \ +{ \ + template \ + static inline typename MatrixType::Index potrf(MatrixType& m, char uplo) \ + { \ + lapack_int matrix_order; \ + lapack_int size, lda, info, StorageOrder; \ + EIGTYPE* a; \ + eigen_assert(m.rows()==m.cols()); \ + /* Set up parameters for ?potrf */ \ + size = m.rows(); \ + StorageOrder = MatrixType::Flags&RowMajorBit?RowMajor:ColMajor; \ + matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \ + a = &(m.coeffRef(0,0)); \ + lda = m.outerStride(); \ +\ + info = LAPACKE_##MKLPREFIX##potrf( matrix_order, uplo, size, (MKLTYPE*)a, lda ); \ + info = (info==0) ? Success : NumericalIssue; \ + return info; \ + } \ +}; \ +template<> struct llt_inplace \ +{ \ + template \ + static typename MatrixType::Index blocked(MatrixType& m) \ + { \ + return mkl_llt::potrf(m, 'L'); \ + } \ + template \ + static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } \ +}; \ +template<> struct llt_inplace \ +{ \ + template \ + static typename MatrixType::Index blocked(MatrixType& m) \ + { \ + return mkl_llt::potrf(m, 'U'); \ + } \ + template \ + static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + { \ + Transpose matt(mat); \ + return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); \ + } \ +}; + +EIGEN_MKL_LLT(double, double, d) +EIGEN_MKL_LLT(float, float, s) +EIGEN_MKL_LLT(dcomplex, MKL_Complex16, z) +EIGEN_MKL_LLT(scomplex, MKL_Complex8, c) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_LLT_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt new file mode 100644 index 000000000..814dfa613 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_CholmodSupport_SRCS "*.h") + +INSTALL(FILES + ${Eigen_CholmodSupport_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/CholmodSupport COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h similarity index 60% rename from gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupport.h rename to gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h index 3e502c0aa..a06c429f0 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupport.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h @@ -25,6 +25,8 @@ #ifndef EIGEN_CHOLMODSUPPORT_H #define EIGEN_CHOLMODSUPPORT_H +namespace Eigen { + namespace internal { template @@ -69,11 +71,20 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) res.nzmax = mat.nonZeros(); res.nrow = mat.rows();; res.ncol = mat.cols(); - res.p = mat._outerIndexPtr(); - res.i = mat._innerIndexPtr(); - res.x = mat._valuePtr(); + res.p = mat.outerIndexPtr(); + res.i = mat.innerIndexPtr(); + res.x = mat.valuePtr(); res.sorted = 1; - res.packed = 1; + if(mat.isCompressed()) + { + res.packed = 1; + } + else + { + res.packed = 0; + res.nz = mat.innerNonZeroPtr(); + } + res.dtype = 0; res.stype = -1; @@ -149,19 +160,14 @@ enum CholmodMode { CholmodAuto, CholmodSimplicialLLt, CholmodSupernodalLLt, CholmodLDLt }; -/** \brief A Cholesky factorization and solver based on Cholmod - * - * This class allows to solve for A.X = B sparse linear problems via a LL^T or LDL^T Cholesky factorization - * using the Cholmod library. The sparse matrix A must be selfajoint and positive definite. The vectors or matrices - * X and B can be either dense or sparse. - * - * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> - * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower - * or Upper. Default is Lower. - * + +/** \ingroup CholmodSupport_Module + * \class CholmodBase + * \brief The base class for the direct Cholesky factorization of Cholmod + * \sa class CholmodSupernodalLLT, class CholmodSimplicialLDLT, class CholmodSimplicialLLT */ -template -class CholmodDecomposition +template +class CholmodBase : internal::noncopyable { public: typedef _MatrixType MatrixType; @@ -173,21 +179,20 @@ class CholmodDecomposition public: - CholmodDecomposition() + CholmodBase() : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) { cholmod_start(&m_cholmod); - setMode(CholmodLDLt); } - CholmodDecomposition(const MatrixType& matrix) + CholmodBase(const MatrixType& matrix) : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) { cholmod_start(&m_cholmod); compute(matrix); } - ~CholmodDecomposition() + ~CholmodBase() { if(m_cholmodFactor) cholmod_free_factor(&m_cholmodFactor, &m_cholmod); @@ -197,31 +202,8 @@ class CholmodDecomposition inline Index cols() const { return m_cholmodFactor->n; } inline Index rows() const { return m_cholmodFactor->n; } - void setMode(CholmodMode mode) - { - switch(mode) - { - case CholmodAuto: - m_cholmod.final_asis = 1; - m_cholmod.supernodal = CHOLMOD_AUTO; - break; - case CholmodSimplicialLLt: - m_cholmod.final_asis = 0; - m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; - m_cholmod.final_ll = 1; - break; - case CholmodSupernodalLLt: - m_cholmod.final_asis = 1; - m_cholmod.supernodal = CHOLMOD_SUPERNODAL; - break; - case CholmodLDLt: - m_cholmod.final_asis = 1; - m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; - break; - default: - break; - } - } + Derived& derived() { return *static_cast(this); } + const Derived& derived() const { return *static_cast(this); } /** \brief Reports whether previous computation was successful. * @@ -235,10 +217,11 @@ class CholmodDecomposition } /** Computes the sparse Cholesky decomposition of \a matrix */ - void compute(const MatrixType& matrix) + Derived& compute(const MatrixType& matrix) { analyzePattern(matrix); factorize(matrix); + return derived(); } /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. @@ -246,13 +229,13 @@ class CholmodDecomposition * \sa compute() */ template - inline const internal::solve_retval + inline const internal::solve_retval solve(const MatrixBase& b) const { eigen_assert(m_isInitialized && "LLT is not initialized."); eigen_assert(rows()==b.rows() && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); + return internal::solve_retval(*this, b.derived()); } /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. @@ -260,13 +243,13 @@ class CholmodDecomposition * \sa compute() */ template - inline const internal::sparse_solve_retval + inline const internal::sparse_solve_retval solve(const SparseMatrixBase& b) const { eigen_assert(m_isInitialized && "LLT is not initialized."); eigen_assert(rows()==b.rows() && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::sparse_solve_retval(*this, b.derived()); + return internal::sparse_solve_retval(*this, b.derived()); } /** Performs a symbolic decomposition on the sparcity of \a matrix. @@ -356,7 +339,7 @@ class CholmodDecomposition template void dumpMemory(Stream& s) {} - + protected: mutable cholmod_common m_cholmod; cholmod_factor* m_cholmodFactor; @@ -366,13 +349,223 @@ class CholmodDecomposition int m_analysisIsOk; }; +/** \ingroup CholmodSupport_Module + * \class CholmodSimplicialLLT + * \brief A simplicial direct Cholesky (LLT) factorization and solver based on Cholmod + * + * This class allows to solve for A.X = B sparse linear problems via a simplicial LL^T Cholesky factorization + * using the Cholmod library. + * This simplicial variant is equivalent to Eigen's built-in SimplicialLLT class. Thefore, it has little practical interest. + * The sparse matrix A must be selfajoint and positive definite. The vectors or matrices + * X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. + * + * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLLT + */ +template +class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT<_MatrixType, _UpLo> > +{ + typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT> Base; + using Base::m_cholmod; + + public: + + typedef _MatrixType MatrixType; + + CholmodSimplicialLLT() : Base() { init(); } + + CholmodSimplicialLLT(const MatrixType& matrix) : Base() + { + init(); + compute(matrix); + } + + ~CholmodSimplicialLLT() {} + protected: + void init() + { + m_cholmod.final_asis = 0; + m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; + m_cholmod.final_ll = 1; + } +}; + + +/** \ingroup CholmodSupport_Module + * \class CholmodSimplicialLDLT + * \brief A simplicial direct Cholesky (LDLT) factorization and solver based on Cholmod + * + * This class allows to solve for A.X = B sparse linear problems via a simplicial LDL^T Cholesky factorization + * using the Cholmod library. + * This simplicial variant is equivalent to Eigen's built-in SimplicialLDLT class. Thefore, it has little practical interest. + * The sparse matrix A must be selfajoint and positive definite. The vectors or matrices + * X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. + * + * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLDLT + */ +template +class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT<_MatrixType, _UpLo> > +{ + typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT> Base; + using Base::m_cholmod; + + public: + + typedef _MatrixType MatrixType; + + CholmodSimplicialLDLT() : Base() { init(); } + + CholmodSimplicialLDLT(const MatrixType& matrix) : Base() + { + init(); + compute(matrix); + } + + ~CholmodSimplicialLDLT() {} + protected: + void init() + { + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; + } +}; + +/** \ingroup CholmodSupport_Module + * \class CholmodSupernodalLLT + * \brief A supernodal Cholesky (LLT) factorization and solver based on Cholmod + * + * This class allows to solve for A.X = B sparse linear problems via a supernodal LL^T Cholesky factorization + * using the Cholmod library. + * This supernodal variant performs best on dense enough problems, e.g., 3D FEM, or very high order 2D FEM. + * The sparse matrix A must be selfajoint and positive definite. The vectors or matrices + * X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT<_MatrixType, _UpLo> > +{ + typedef CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT> Base; + using Base::m_cholmod; + + public: + + typedef _MatrixType MatrixType; + + CholmodSupernodalLLT() : Base() { init(); } + + CholmodSupernodalLLT(const MatrixType& matrix) : Base() + { + init(); + compute(matrix); + } + + ~CholmodSupernodalLLT() {} + protected: + void init() + { + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_SUPERNODAL; + } +}; + +/** \ingroup CholmodSupport_Module + * \class CholmodDecomposition + * \brief A general Cholesky factorization and solver based on Cholmod + * + * This class allows to solve for A.X = B sparse linear problems via a LL^T or LDL^T Cholesky factorization + * using the Cholmod library. The sparse matrix A must be selfajoint and positive definite. The vectors or matrices + * X and B can be either dense or sparse. + * + * This variant permits to change the underlying Cholesky method at runtime. + * On the other hand, it does not provide access to the result of the factorization. + * The default is to let Cholmod automatically choose between a simplicial and supernodal factorization. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecomposition<_MatrixType, _UpLo> > +{ + typedef CholmodBase<_MatrixType, _UpLo, CholmodDecomposition> Base; + using Base::m_cholmod; + + public: + + typedef _MatrixType MatrixType; + + CholmodDecomposition() : Base() { init(); } + + CholmodDecomposition(const MatrixType& matrix) : Base() + { + init(); + compute(matrix); + } + + ~CholmodDecomposition() {} + + void setMode(CholmodMode mode) + { + switch(mode) + { + case CholmodAuto: + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_AUTO; + break; + case CholmodSimplicialLLt: + m_cholmod.final_asis = 0; + m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; + m_cholmod.final_ll = 1; + break; + case CholmodSupernodalLLt: + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_SUPERNODAL; + break; + case CholmodLDLt: + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; + break; + default: + break; + } + } + protected: + void init() + { + m_cholmod.final_asis = 1; + m_cholmod.supernodal = CHOLMOD_AUTO; + } +}; + namespace internal { -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> { - typedef CholmodDecomposition<_MatrixType,_UpLo> Dec; + typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) template void evalTo(Dest& dst) const @@ -381,11 +574,11 @@ struct solve_retval, Rhs> } }; -template -struct sparse_solve_retval, Rhs> - : sparse_solve_retval_base, Rhs> +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> { - typedef CholmodDecomposition<_MatrixType,_UpLo> Dec; + typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) template void evalTo(Dest& dst) const @@ -394,6 +587,8 @@ struct sparse_solve_retval, Rhs> } }; -} +} // end namespace internal + +} // end namespace Eigen #endif // EIGEN_CHOLMODSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h index a11fb1b53..4762933d7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ARRAY_H #define EIGEN_ARRAY_H +namespace Eigen { + /** \class Array * \ingroup Core_Module * @@ -316,5 +318,6 @@ EIGEN_USING_ARRAY_TYPEDEFS_FOR_TYPE(d) \ EIGEN_USING_ARRAY_TYPEDEFS_FOR_TYPE(cf) \ EIGEN_USING_ARRAY_TYPEDEFS_FOR_TYPE(cd) +} // end namespace Eigen #endif // EIGEN_ARRAY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h index 9399ac3d1..ec3a4be43 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ARRAYBASE_H #define EIGEN_ARRAYBASE_H +namespace Eigen { + template class MatrixWrapper; /** \class ArrayBase @@ -159,7 +161,7 @@ template class ArrayBase /** \returns an \link MatrixBase Matrix \endlink expression of this array * \sa MatrixBase::array() */ MatrixWrapper matrix() { return derived(); } - const MatrixWrapper matrix() const { return derived(); } + const MatrixWrapper matrix() const { return derived(); } // template // inline void evalTo(Dest& dst) const { dst = matrix(); } @@ -174,10 +176,10 @@ template class ArrayBase protected: // mixing arrays and matrices is not legal template Derived& operator+=(const MatrixBase& ) - {EIGEN_STATIC_ASSERT(sizeof(typename OtherDerived::Scalar)==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES);} + {EIGEN_STATIC_ASSERT(std::ptrdiff_t(sizeof(typename OtherDerived::Scalar))==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES); return *this;} // mixing arrays and matrices is not legal template Derived& operator-=(const MatrixBase& ) - {EIGEN_STATIC_ASSERT(sizeof(typename OtherDerived::Scalar)==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES);} + {EIGEN_STATIC_ASSERT(std::ptrdiff_t(sizeof(typename OtherDerived::Scalar))==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES); return *this;} }; /** replaces \c *this by \c *this - \a other. @@ -236,4 +238,6 @@ ArrayBase::operator/=(const ArrayBase& other) return derived(); } +} // end namespace Eigen + #endif // EIGEN_ARRAYBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h index 07f082e1e..f8a442cee 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ARRAYWRAPPER_H #define EIGEN_ARRAYWRAPPER_H +namespace Eigen { + /** \class ArrayWrapper * \ingroup Core_Module * @@ -61,7 +63,7 @@ class ArrayWrapper : public ArrayBase > typedef typename internal::nested::type NestedExpressionType; - inline ArrayWrapper(const ExpressionType& matrix) : m_expression(matrix) {} + inline ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} inline Index rows() const { return m_expression.rows(); } inline Index cols() const { return m_expression.cols(); } @@ -71,7 +73,7 @@ class ArrayWrapper : public ArrayBase > inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } inline const Scalar* data() const { return m_expression.data(); } - inline const CoeffReturnType coeff(Index row, Index col) const + inline CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } @@ -86,7 +88,7 @@ class ArrayWrapper : public ArrayBase > return m_expression.const_cast_derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + inline CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } @@ -128,8 +130,14 @@ class ArrayWrapper : public ArrayBase > template inline void evalTo(Dest& dst) const { dst = m_expression; } + const typename internal::remove_all::type& + nestedExpression() const + { + return m_expression; + } + protected: - const NestedExpressionType m_expression; + NestedExpressionType m_expression; }; /** \class MatrixWrapper @@ -168,7 +176,7 @@ class MatrixWrapper : public MatrixBase > typedef typename internal::nested::type NestedExpressionType; - inline MatrixWrapper(const ExpressionType& matrix) : m_expression(matrix) {} + inline MatrixWrapper(ExpressionType& matrix) : m_expression(matrix) {} inline Index rows() const { return m_expression.rows(); } inline Index cols() const { return m_expression.cols(); } @@ -178,7 +186,7 @@ class MatrixWrapper : public MatrixBase > inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } inline const Scalar* data() const { return m_expression.data(); } - inline const CoeffReturnType coeff(Index row, Index col) const + inline CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } @@ -193,7 +201,7 @@ class MatrixWrapper : public MatrixBase > return m_expression.derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + inline CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } @@ -232,8 +240,16 @@ class MatrixWrapper : public MatrixBase > m_expression.const_cast_derived().template writePacket(index, x); } + const typename internal::remove_all::type& + nestedExpression() const + { + return m_expression; + } + protected: - const NestedExpressionType m_expression; + NestedExpressionType m_expression; }; +} // end namespace Eigen + #endif // EIGEN_ARRAYWRAPPER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h index 3a17152f0..75390acf3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h @@ -27,6 +27,8 @@ #ifndef EIGEN_ASSIGN_H #define EIGEN_ASSIGN_H +namespace Eigen { + namespace internal { /*************************************************************************** @@ -152,7 +154,7 @@ struct assign_DefaultTraversal_CompleteUnrolling inner = Index % Derived1::InnerSizeAtCompileTime }; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { dst.copyCoeffByOuterInner(outer, inner, src); assign_DefaultTraversal_CompleteUnrolling::run(dst, src); @@ -162,13 +164,13 @@ struct assign_DefaultTraversal_CompleteUnrolling template struct assign_DefaultTraversal_CompleteUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &, const Derived2 &) {} + static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} }; template struct assign_DefaultTraversal_InnerUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src, int outer) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, int outer) { dst.copyCoeffByOuterInner(outer, Index, src); assign_DefaultTraversal_InnerUnrolling::run(dst, src, outer); @@ -178,7 +180,7 @@ struct assign_DefaultTraversal_InnerUnrolling template struct assign_DefaultTraversal_InnerUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &, const Derived2 &, int) {} + static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, int) {} }; /*********************** @@ -188,7 +190,7 @@ struct assign_DefaultTraversal_InnerUnrolling template struct assign_LinearTraversal_CompleteUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { dst.copyCoeff(Index, src); assign_LinearTraversal_CompleteUnrolling::run(dst, src); @@ -198,7 +200,7 @@ struct assign_LinearTraversal_CompleteUnrolling template struct assign_LinearTraversal_CompleteUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &, const Derived2 &) {} + static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} }; /************************** @@ -214,7 +216,7 @@ struct assign_innervec_CompleteUnrolling JointAlignment = assign_traits::JointAlignment }; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { dst.template copyPacketByOuterInner(outer, inner, src); assign_innervec_CompleteUnrolling struct assign_innervec_CompleteUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &, const Derived2 &) {} + static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} }; template struct assign_innervec_InnerUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src, int outer) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, int outer) { dst.template copyPacketByOuterInner(outer, Index, src); assign_innervec_InnerUnrolling struct assign_innervec_InnerUnrolling { - EIGEN_STRONG_INLINE static void run(Derived1 &, const Derived2 &, int) {} + static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, int) {} }; /*************************************************************************** @@ -251,24 +253,25 @@ struct assign_innervec_InnerUnrolling template::Traversal, - int Unrolling = assign_traits::Unrolling> + int Unrolling = assign_traits::Unrolling, + int Version = Specialized> struct assign_impl; /************************ *** Default traversal *** ************************/ -template -struct assign_impl +template +struct assign_impl { - inline static void run(Derived1 &, const Derived2 &) { } + static inline void run(Derived1 &, const Derived2 &) { } }; -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { const Index innerSize = dst.innerSize(); const Index outerSize = dst.outerSize(); @@ -278,21 +281,21 @@ struct assign_impl } }; -template -struct assign_impl +template +struct assign_impl { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { assign_DefaultTraversal_CompleteUnrolling ::run(dst, src); } }; -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { const Index outerSize = dst.outerSize(); for(Index outer = 0; outer < outerSize; ++outer) @@ -305,11 +308,11 @@ struct assign_impl *** Linear traversal *** ***********************/ -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { const Index size = dst.size(); for(Index i = 0; i < size; ++i) @@ -317,10 +320,10 @@ struct assign_impl } }; -template -struct assign_impl +template +struct assign_impl { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { assign_LinearTraversal_CompleteUnrolling ::run(dst, src); @@ -331,11 +334,11 @@ struct assign_impl *** Inner vectorization *** **************************/ -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { const Index innerSize = dst.innerSize(); const Index outerSize = dst.outerSize(); @@ -346,21 +349,21 @@ struct assign_impl } }; -template -struct assign_impl +template +struct assign_impl { - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { assign_innervec_CompleteUnrolling ::run(dst, src); } }; -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { const Index outerSize = dst.outerSize(); for(Index outer = 0; outer < outerSize; ++outer) @@ -398,11 +401,11 @@ struct unaligned_assign_impl } }; -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { const Index size = dst.size(); typedef packet_traits PacketTraits; @@ -412,7 +415,7 @@ struct assign_impl srcAlignment = assign_traits::JointAlignment }; const Index alignedStart = assign_traits::DstIsAligned ? 0 - : first_aligned(&dst.coeffRef(0), size); + : internal::first_aligned(&dst.coeffRef(0), size); const Index alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize; unaligned_assign_impl::DstIsAligned!=0>::run(src,dst,0,alignedStart); @@ -426,11 +429,11 @@ struct assign_impl } }; -template -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - EIGEN_STRONG_INLINE static void run(Derived1 &dst, const Derived2 &src) + static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) { enum { size = Derived1::SizeAtCompileTime, packetSize = packet_traits::size, @@ -445,11 +448,11 @@ struct assign_impl -struct assign_impl +template +struct assign_impl { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { typedef packet_traits PacketTraits; enum { @@ -463,7 +466,7 @@ struct assign_impl const Index outerSize = dst.outerSize(); const Index alignedStep = alignable ? (packetSize - dst.outerStride() % packetSize) & packetAlignedMask : 0; Index alignedStart = ((!alignable) || assign_traits::DstIsAligned) ? 0 - : first_aligned(&dst.coeffRef(0,0), innerSize); + : internal::first_aligned(&dst.coeffRef(0,0), innerSize); for(Index outer = 0; outer < outerSize; ++outer) { @@ -531,19 +534,19 @@ struct assign_selector; template struct assign_selector { - EIGEN_STRONG_INLINE static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); } + static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); } }; template struct assign_selector { - EIGEN_STRONG_INLINE static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.eval()); } + static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.eval()); } }; template struct assign_selector { - EIGEN_STRONG_INLINE static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose()); } + static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose()); } }; template struct assign_selector { - EIGEN_STRONG_INLINE static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose().eval()); } + static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose().eval()); } }; } // end namespace internal @@ -590,4 +593,6 @@ EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const ReturnByValue< return derived(); } +} // end namespace Eigen + #endif // EIGEN_ASSIGN_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h new file mode 100644 index 000000000..428c6367b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h @@ -0,0 +1,224 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * MKL VML support for coefficient-wise unary Eigen expressions like a=b.sin() + ******************************************************************************** +*/ + +#ifndef EIGEN_ASSIGN_VML_H +#define EIGEN_ASSIGN_VML_H + +namespace Eigen { + +namespace internal { + +template struct vml_call +{ enum { IsSupported = 0 }; }; + +template +class vml_assign_traits +{ + private: + enum { + DstHasDirectAccess = Dst::Flags & DirectAccessBit, + SrcHasDirectAccess = Src::Flags & DirectAccessBit, + + StorageOrdersAgree = (int(Dst::IsRowMajor) == int(Src::IsRowMajor)), + InnerSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::SizeAtCompileTime) + : int(Dst::Flags)&RowMajorBit ? int(Dst::ColsAtCompileTime) + : int(Dst::RowsAtCompileTime), + InnerMaxSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::MaxSizeAtCompileTime) + : int(Dst::Flags)&RowMajorBit ? int(Dst::MaxColsAtCompileTime) + : int(Dst::MaxRowsAtCompileTime), + MaxSizeAtCompileTime = Dst::SizeAtCompileTime, + + MightEnableVml = vml_call::IsSupported && StorageOrdersAgree && DstHasDirectAccess && SrcHasDirectAccess + && Src::InnerStrideAtCompileTime==1 && Dst::InnerStrideAtCompileTime==1, + MightLinearize = MightEnableVml && (int(Dst::Flags) & int(Src::Flags) & LinearAccessBit), + VmlSize = MightLinearize ? MaxSizeAtCompileTime : InnerMaxSize, + LargeEnough = VmlSize==Dynamic || VmlSize>=EIGEN_MKL_VML_THRESHOLD, + MayEnableVml = MightEnableVml && LargeEnough, + MayLinearize = MayEnableVml && MightLinearize + }; + public: + enum { + Traversal = MayLinearize ? LinearVectorizedTraversal + : MayEnableVml ? InnerVectorizedTraversal + : DefaultTraversal + }; +}; + +template::Traversal > +struct vml_assign_impl + : assign_impl,Traversal,Unrolling,BuiltIn> +{ +}; + +template +struct vml_assign_impl +{ + typedef typename Derived1::Scalar Scalar; + typedef typename Derived1::Index Index; + static inline void run(Derived1& dst, const CwiseUnaryOp& src) + { + // in case we want to (or have to) skip VML at runtime we can call: + // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); + const Index innerSize = dst.innerSize(); + const Index outerSize = dst.outerSize(); + for(Index outer = 0; outer < outerSize; ++outer) { + const Scalar *src_ptr = src.IsRowMajor ? &(src.nestedExpression().coeffRef(outer,0)) : + &(src.nestedExpression().coeffRef(0, outer)); + Scalar *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); + vml_call::run(src.functor(), innerSize, src_ptr, dst_ptr ); + } + } +}; + +template +struct vml_assign_impl +{ + static inline void run(Derived1& dst, const CwiseUnaryOp& src) + { + // in case we want to (or have to) skip VML at runtime we can call: + // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); + vml_call::run(src.functor(), dst.size(), src.nestedExpression().data(), dst.data() ); + } +}; + +// Macroses + +#define EIGEN_MKL_VML_SPECIALIZE_ASSIGN(TRAVERSAL,UNROLLING) \ + template \ + struct assign_impl, TRAVERSAL, UNROLLING, Specialized> { \ + static inline void run(Derived1 &dst, const Eigen::CwiseUnaryOp &src) { \ + vml_assign_impl::run(dst, src); \ + } \ + }; + +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,NoUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,CompleteUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,InnerUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,NoUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,CompleteUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,NoUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,CompleteUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,InnerUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,CompleteUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,NoUnrolling) +EIGEN_MKL_VML_SPECIALIZE_ASSIGN(SliceVectorizedTraversal,NoUnrolling) + + +#if !defined (EIGEN_FAST_MATH) || (EIGEN_FAST_MATH != 1) +#define EIGEN_MKL_VML_MODE VML_HA +#else +#define EIGEN_MKL_VML_MODE VML_LA +#endif + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ + template<> struct vml_call< scalar_##EIGENOP##_op > { \ + enum { IsSupported = 1 }; \ + static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ + int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ + VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst); \ + } \ + }; + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ + template<> struct vml_call< scalar_##EIGENOP##_op > { \ + enum { IsSupported = 1 }; \ + static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ + int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ + MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ + VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst, vmlMode); \ + } \ + }; + +#define EIGEN_MKL_VML_DECLARE_POW_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ + template<> struct vml_call< scalar_##EIGENOP##_op > { \ + enum { IsSupported = 1 }; \ + static inline void run( const scalar_##EIGENOP##_op& func, \ + int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ + EIGENTYPE exponent = func.m_exponent; \ + MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ + VMLOP(&size, (const VMLTYPE*)src, (const VMLTYPE*)&exponent, \ + (VMLTYPE*)dst, &vmlMode); \ + } \ + }; + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vs##VMLOP, float, float) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vd##VMLOP, double, double) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vc##VMLOP, scomplex, MKL_Complex8) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vz##VMLOP, dcomplex, MKL_Complex16) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) + + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vms##VMLOP, float, float) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmd##VMLOP, double, double) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmc##VMLOP, scomplex, MKL_Complex8) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmz##VMLOP, dcomplex, MKL_Complex16) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) + + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sin, Sin) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(asin, Asin) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(cos, Cos) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(acos, Acos) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(tan, Tan) +//EIGEN_MKL_VML_DECLARE_UNARY_CALLS(abs, Abs) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(exp, Exp) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(log, Ln) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sqrt, Sqrt) + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(square, Sqr) + +// The vm*powx functions are not avaibale in the windows version of MKL. +#ifdef _WIN32 +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmspowx_, float, float) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmdpowx_, double, double) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmcpowx_, scomplex, MKL_Complex8) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmzpowx_, dcomplex, MKL_Complex16) +#endif + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_ASSIGN_VML_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h index 2570d7b55..8ef917de1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h @@ -25,8 +25,9 @@ #ifndef EIGEN_BANDMATRIX_H #define EIGEN_BANDMATRIX_H -namespace internal { +namespace Eigen { +namespace internal { template class BandMatrixBase : public EigenBase @@ -343,4 +344,6 @@ class TridiagonalMatrix : public BandMatrix::type& nestedExpression() const + { + return m_xpr; + } + + Index startRow() const + { + return m_startRow.value(); + } + + Index startCol() const + { + return m_startCol.value(); + } + protected: const typename XprType::Nested m_xpr; @@ -304,6 +321,11 @@ class Block init(); } + const typename internal::remove_all::type& nestedExpression() const + { + return m_xpr; + } + /** \sa MapBase::innerStride() */ inline Index innerStride() const { @@ -341,9 +363,10 @@ class Block : m_xpr.innerStride(); } - const typename XprType::Nested m_xpr; - int m_outerStride; + typename XprType::Nested m_xpr; + Index m_outerStride; }; +} // end namespace Eigen #endif // EIGEN_BLOCK_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h index 5c3444a57..2c554a57d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ALLANDANY_H #define EIGEN_ALLANDANY_H +namespace Eigen { + namespace internal { template @@ -35,7 +37,7 @@ struct all_unroller row = (UnrollCount-1) % Derived::RowsAtCompileTime }; - inline static bool run(const Derived &mat) + static inline bool run(const Derived &mat) { return all_unroller::run(mat) && mat.coeff(row, col); } @@ -44,13 +46,13 @@ struct all_unroller template struct all_unroller { - inline static bool run(const Derived &mat) { return mat.coeff(0, 0); } + static inline bool run(const Derived &mat) { return mat.coeff(0, 0); } }; template struct all_unroller { - inline static bool run(const Derived &) { return false; } + static inline bool run(const Derived &) { return false; } }; template @@ -61,7 +63,7 @@ struct any_unroller row = (UnrollCount-1) % Derived::RowsAtCompileTime }; - inline static bool run(const Derived &mat) + static inline bool run(const Derived &mat) { return any_unroller::run(mat) || mat.coeff(row, col); } @@ -70,13 +72,13 @@ struct any_unroller template struct any_unroller { - inline static bool run(const Derived &mat) { return mat.coeff(0, 0); } + static inline bool run(const Derived &mat) { return mat.coeff(0, 0); } }; template struct any_unroller { - inline static bool run(const Derived &) { return false; } + static inline bool run(const Derived &) { return false; } }; } // end namespace internal @@ -146,4 +148,6 @@ inline typename DenseBase::Index DenseBase::count() const return derived().template cast().template cast().sum(); } +} // end namespace Eigen + #endif // EIGEN_ALLANDANY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h index 92422bf2f..f9ec1d587 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h @@ -26,6 +26,8 @@ #ifndef EIGEN_COMMAINITIALIZER_H #define EIGEN_COMMAINITIALIZER_H +namespace Eigen { + /** \class CommaInitializer * \ingroup Core_Module * @@ -147,4 +149,6 @@ DenseBase::operator<<(const DenseBase& other) return CommaInitializer(*static_cast(this), other); } +} // end namespace Eigen + #endif // EIGEN_COMMAINITIALIZER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h index 7386b2e18..32599a7d9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h @@ -26,6 +26,8 @@ #ifndef EIGEN_CWISE_BINARY_OP_H #define EIGEN_CWISE_BINARY_OP_H +namespace Eigen { + /** \class CwiseBinaryOp * \ingroup Core_Module * @@ -167,8 +169,8 @@ class CwiseBinaryOp : internal::no_assignment_operator, const BinaryOp& functor() const { return m_functor; } protected: - const LhsNested m_lhs; - const RhsNested m_rhs; + LhsNested m_lhs; + RhsNested m_rhs; const BinaryOp m_functor; }; @@ -237,4 +239,6 @@ MatrixBase::operator+=(const MatrixBase& other) return derived(); } +} // end namespace Eigen + #endif // EIGEN_CWISE_BINARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h index c616e7ae1..a6d5e0934 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h @@ -25,6 +25,8 @@ #ifndef EIGEN_CWISE_NULLARY_OP_H #define EIGEN_CWISE_NULLARY_OP_H +namespace Eigen { + /** \class CwiseNullaryOp * \ingroup Core_Module * @@ -101,6 +103,9 @@ class CwiseNullaryOp : internal::no_assignment_operator, return m_functor.packetOp(index); } + /** \returns the functor representing the nullary operation */ + const NullaryOp& functor() const { return m_functor; } + protected: const internal::variable_if_dynamic m_rows; const internal::variable_if_dynamic m_cols; @@ -238,6 +243,8 @@ DenseBase::Constant(const Scalar& value) * assumed to be a(0), a(1), ..., a(size). This assumption allows for better vectorization * and yields faster code than the random access version. * + * When size is set to 1, a vector of length 1 containing 'high' is returned. + * * \only_for_vectors * * Example: \include DenseBase_LinSpaced_seq.cpp @@ -270,6 +277,7 @@ DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& hig * \brief Sets a linearly space vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. + * When size is set to 1, a vector of length 1 containing 'high' is returned. * * \only_for_vectors * @@ -381,6 +389,7 @@ PlainObjectBase::setConstant(Index rows, Index cols, const Scalar& valu * \brief Sets a linearly space vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. + * When size is set to 1, a vector of length 1 containing 'high' is returned. * * \only_for_vectors * @@ -396,6 +405,23 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index size, const return derived() = Derived::NullaryExpr(size, internal::linspaced_op(low,high,size)); } +/** + * \brief Sets a linearly space vector. + * + * The function fill *this with equally spaced values in the closed interval [low,high]. + * When size is set to 1, a vector of length 1 containing 'high' is returned. + * + * \only_for_vectors + * + * \sa setLinSpaced(Index, const Scalar&, const Scalar&), CwiseNullaryOp + */ +template +EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, const Scalar& high) +{ + EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) + return setLinSpaced(size(), low, high); +} + // zero: /** \returns an expression of a zero matrix. @@ -848,4 +874,6 @@ template EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitW() { return Derived::Unit(3); } +} // end namespace Eigen + #endif // EIGEN_CWISE_NULLARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h index 958571d64..9110c9800 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h @@ -26,6 +26,8 @@ #ifndef EIGEN_CWISE_UNARY_OP_H #define EIGEN_CWISE_UNARY_OP_H +namespace Eigen { + /** \class CwiseUnaryOp * \ingroup Core_Module * @@ -95,7 +97,7 @@ class CwiseUnaryOp : internal::no_assignment_operator, nestedExpression() { return m_xpr.const_cast_derived(); } protected: - const typename XprType::Nested m_xpr; + typename XprType::Nested m_xpr; const UnaryOp m_functor; }; @@ -134,4 +136,6 @@ class CwiseUnaryOpImpl } }; +} // end namespace Eigen + #endif // EIGEN_CWISE_UNARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h index d24ef0373..bf16243d5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h @@ -25,6 +25,8 @@ #ifndef EIGEN_CWISE_UNARY_VIEW_H #define EIGEN_CWISE_UNARY_VIEW_H +namespace Eigen { + /** \class CwiseUnaryView * \ingroup Core_Module * @@ -97,7 +99,7 @@ class CwiseUnaryView : internal::no_assignment_operator, protected: // FIXME changed from MatrixType::Nested because of a weird compilation error with sun CC - const typename internal::nested::type m_matrix; + typename internal::nested::type m_matrix; ViewOp m_functor; }; @@ -143,6 +145,6 @@ class CwiseUnaryViewImpl } }; - +} // end namespace Eigen #endif // EIGEN_CWISE_UNARY_VIEW_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h index 838fa4030..1882dcca4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h @@ -26,6 +26,8 @@ #ifndef EIGEN_DENSEBASE_H #define EIGEN_DENSEBASE_H +namespace Eigen { + /** \class DenseBase * \ingroup Core_Module * @@ -169,8 +171,8 @@ template class DenseBase IsRowMajor = int(Flags) & RowMajorBit, /**< True if this expression has row-major storage order. */ - InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? SizeAtCompileTime - : int(IsRowMajor) ? ColsAtCompileTime : RowsAtCompileTime, + InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime) + : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime), CoeffReadCost = internal::traits::CoeffReadCost, /**< This is a rough measure of how expensive it is to read one coefficient from @@ -376,12 +378,13 @@ template class DenseBase inline Derived& operator*=(const Scalar& other); inline Derived& operator/=(const Scalar& other); + typedef typename internal::add_const_on_value_type::type>::type EvalReturnType; /** \returns the matrix or vector obtained by evaluating this expression. * * Notice that in the case of a plain matrix or vector (not an expression) this function just returns * a const reference, in order to avoid a useless copy. */ - EIGEN_STRONG_INLINE const typename internal::eval::type eval() const + EIGEN_STRONG_INLINE EvalReturnType eval() const { // Even though MSVC does not honor strong inlining when the return type // is a dynamic matrix, we desperately need strong inlining for fixed @@ -540,4 +543,6 @@ template class DenseBase template explicit DenseBase(const DenseBase&); }; +} // end namespace Eigen + #endif // EIGEN_DENSEBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h index e45238fb5..e1aa1a5f8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h @@ -25,6 +25,8 @@ #ifndef EIGEN_DENSECOEFFSBASE_H #define EIGEN_DENSECOEFFSBASE_H +namespace Eigen { + namespace internal { template struct add_const_on_value_type_if_arithmetic { @@ -710,16 +712,16 @@ namespace internal { template struct first_aligned_impl { - inline static typename Derived::Index run(const Derived&) + static inline typename Derived::Index run(const Derived&) { return 0; } }; template struct first_aligned_impl { - inline static typename Derived::Index run(const Derived& m) + static inline typename Derived::Index run(const Derived& m) { - return first_aligned(&m.const_cast_derived().coeffRef(0,0), m.size()); + return internal::first_aligned(&m.const_cast_derived().coeffRef(0,0), m.size()); } }; @@ -729,7 +731,7 @@ struct first_aligned_impl * documentation. */ template -inline static typename Derived::Index first_aligned(const Derived& m) +static inline typename Derived::Index first_aligned(const Derived& m) { return first_aligned_impl @@ -762,4 +764,6 @@ struct outer_stride_at_compile_time } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_DENSECOEFFSBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h index 813053b00..0ea05bc90 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h @@ -33,6 +33,8 @@ #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN #endif +namespace Eigen { + namespace internal { struct constructor_without_unaligned_array_assert {}; @@ -104,8 +106,8 @@ template class DenseSt : m_data(internal::constructor_without_unaligned_array_assert()) {} inline DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } - inline static DenseIndex rows(void) {return _Rows;} - inline static DenseIndex cols(void) {return _Cols;} + static inline DenseIndex rows(void) {return _Rows;} + static inline DenseIndex cols(void) {return _Cols;} inline void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} inline void resize(DenseIndex,DenseIndex,DenseIndex) {} inline const T *data() const { return m_data.array; } @@ -120,14 +122,24 @@ template class DenseStorage class DenseStorage +: public DenseStorage { }; + +template class DenseStorage +: public DenseStorage { }; + +template class DenseStorage +: public DenseStorage { }; + // dynamic-size matrix with fixed-size storage template class DenseStorage { @@ -241,7 +253,7 @@ template class DenseStorage(m_data, _Rows*m_cols); } inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - inline static DenseIndex rows(void) {return _Rows;} + static inline DenseIndex rows(void) {return _Rows;} inline DenseIndex cols(void) const {return m_cols;} inline void conservativeResize(DenseIndex size, DenseIndex, DenseIndex cols) { @@ -278,7 +290,7 @@ template class DenseStorage(m_data, _Cols*m_rows); } inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } inline DenseIndex rows(void) const {return m_rows;} - inline static DenseIndex cols(void) {return _Cols;} + static inline DenseIndex cols(void) {return _Cols;} inline void conservativeResize(DenseIndex size, DenseIndex rows, DenseIndex) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*_Cols); @@ -301,4 +313,6 @@ template class DenseStorage +// Copyright (C) 2009-2010 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -25,6 +26,8 @@ #ifndef EIGEN_DIAGONAL_H #define EIGEN_DIAGONAL_H +namespace Eigen { + /** \class Diagonal * \ingroup Core_Module * @@ -101,6 +104,15 @@ template class Diagonal return 0; } + typedef typename internal::conditional< + internal::is_lvalue::value, + Scalar, + const Scalar + >::type ScalarWithConstIfNotLvalue; + + inline ScalarWithConstIfNotLvalue* data() { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } + inline const Scalar* data() const { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } + inline Scalar& coeffRef(Index row, Index) { EIGEN_STATIC_ASSERT_LVALUE(MatrixType) @@ -133,8 +145,19 @@ template class Diagonal return m_matrix.coeff(index+rowOffset(), index+colOffset()); } + const typename internal::remove_all::type& + nestedExpression() const + { + return m_matrix; + } + + int index() const + { + return m_index.value(); + } + protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; const internal::variable_if_dynamic m_index; private: @@ -224,4 +247,6 @@ MatrixBase::diagonal() const return derived(); } +} // end namespace Eigen + #endif // EIGEN_DIAGONAL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h index f41a74bfa..844f9864b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h @@ -26,6 +26,8 @@ #ifndef EIGEN_DIAGONALMATRIX_H #define EIGEN_DIAGONALMATRIX_H +namespace Eigen { + #ifndef EIGEN_PARSED_BY_DOXYGEN template class DiagonalBase : public EigenBase @@ -72,7 +74,7 @@ class DiagonalBase : public EigenBase const DiagonalProduct operator*(const MatrixBase &matrix) const; - inline const DiagonalWrapper, const DiagonalVectorType> > + inline const DiagonalWrapper, const DiagonalVectorType> > inverse() const { return diagonal().cwiseInverse(); @@ -251,13 +253,13 @@ class DiagonalWrapper #endif /** Constructor from expression of diagonal coefficients to wrap. */ - inline DiagonalWrapper(const DiagonalVectorType& diagonal) : m_diagonal(diagonal) {} + inline DiagonalWrapper(DiagonalVectorType& diagonal) : m_diagonal(diagonal) {} /** \returns a const reference to the wrapped expression of diagonal coefficients. */ const DiagonalVectorType& diagonal() const { return m_diagonal; } protected: - const typename DiagonalVectorType::Nested m_diagonal; + typename DiagonalVectorType::Nested m_diagonal; }; /** \returns a pseudo-expression of a diagonal matrix with *this as vector of diagonal coefficients @@ -303,4 +305,6 @@ bool MatrixBase::isDiagonal(RealScalar prec) const return true; } +} // end namespace Eigen + #endif // EIGEN_DIAGONALMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h index de0c6ed11..9f6a99895 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h @@ -26,6 +26,8 @@ #ifndef EIGEN_DIAGONALPRODUCT_H #define EIGEN_DIAGONALPRODUCT_H +namespace Eigen { + namespace internal { template struct traits > @@ -107,8 +109,8 @@ class DiagonalProduct : internal::no_assignment_operator, m_diagonal.diagonal().template packet(id)); } - const typename MatrixType::Nested m_matrix; - const typename DiagonalType::Nested m_diagonal; + typename MatrixType::Nested m_matrix; + typename DiagonalType::Nested m_diagonal; }; /** \returns the diagonal matrix product of \c *this by the diagonal matrix \a diagonal. @@ -131,5 +133,6 @@ DiagonalBase::operator*(const MatrixBase &matrix return DiagonalProduct(matrix.derived(), derived()); } +} // end namespace Eigen #endif // EIGEN_DIAGONALPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h index 42da78498..67dbbf8ba 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h @@ -25,6 +25,8 @@ #ifndef EIGEN_DOT_H #define EIGEN_DOT_H +namespace Eigen { + namespace internal { // helper function for dot(). The problem is that if we put that in the body of dot(), then upon calling dot @@ -176,7 +178,7 @@ template struct lpNorm_selector { typedef typename NumTraits::Scalar>::Real RealScalar; - inline static RealScalar run(const MatrixBase& m) + static inline RealScalar run(const MatrixBase& m) { return pow(m.cwiseAbs().array().pow(p).sum(), RealScalar(1)/p); } @@ -185,7 +187,7 @@ struct lpNorm_selector template struct lpNorm_selector { - inline static typename NumTraits::Scalar>::Real run(const MatrixBase& m) + static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.cwiseAbs().sum(); } @@ -194,7 +196,7 @@ struct lpNorm_selector template struct lpNorm_selector { - inline static typename NumTraits::Scalar>::Real run(const MatrixBase& m) + static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.norm(); } @@ -203,7 +205,7 @@ struct lpNorm_selector template struct lpNorm_selector { - inline static typename NumTraits::Scalar>::Real run(const MatrixBase& m) + static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.cwiseAbs().maxCoeff(); } @@ -269,4 +271,6 @@ bool MatrixBase::isUnitary(RealScalar prec) const return true; } +} // end namespace Eigen + #endif // EIGEN_DOT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h index 0472539af..77d4c25d5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h @@ -26,6 +26,7 @@ #ifndef EIGEN_EIGENBASE_H #define EIGEN_EIGENBASE_H +namespace Eigen { /** Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). * @@ -169,4 +170,6 @@ inline void MatrixBase::applyOnTheLeft(const EigenBase &o other.derived().applyThisOnTheLeft(derived()); } +} // end namespace Eigen + #endif // EIGEN_EIGENBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h index 458213ab5..47f411b05 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h @@ -25,6 +25,8 @@ #ifndef EIGEN_FLAGGED_H #define EIGEN_FLAGGED_H +namespace Eigen { + /** \class Flagged * \ingroup Core_Module * @@ -148,4 +150,6 @@ DenseBase::flagged() const return derived(); } +} // end namespace Eigen + #endif // EIGEN_FLAGGED_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h index 11c1f8f70..238b7b770 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h @@ -25,6 +25,8 @@ #ifndef EIGEN_FORCEALIGNEDACCESS_H #define EIGEN_FORCEALIGNEDACCESS_H +namespace Eigen { + /** \class ForceAlignedAccess * \ingroup Core_Module * @@ -154,4 +156,6 @@ MatrixBase::forceAlignedAccessIf() return derived(); } +} // end namespace Eigen + #endif // EIGEN_FORCEALIGNEDACCESS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h index 54636e0d4..f33f636bb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h @@ -25,6 +25,8 @@ #ifndef EIGEN_FUNCTORS_H #define EIGEN_FUNCTORS_H +namespace Eigen { + namespace internal { // associative functors: @@ -178,6 +180,18 @@ struct functor_traits > { enum { Cost = 5 * NumTraits::MulCost, PacketAccess=0 }; }; +/** \internal + * \brief Template functor to compute the pow of two scalars + */ +template struct scalar_binary_pow_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_binary_pow_op) + inline Scalar operator() (const Scalar& a, const OtherScalar& b) const { return internal::pow(a, b); } +}; +template +struct functor_traits > { + enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; +}; + // other binary functors: /** \internal @@ -220,6 +234,38 @@ struct functor_traits > { }; }; +/** \internal + * \brief Template functor to compute the and of two booleans + * + * \sa class CwiseBinaryOp, ArrayBase::operator&& + */ +struct scalar_boolean_and_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_and_op) + EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a && b; } +}; +template<> struct functor_traits { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + +/** \internal + * \brief Template functor to compute the or of two booleans + * + * \sa class CwiseBinaryOp, ArrayBase::operator|| + */ +struct scalar_boolean_or_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_or_op) + EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a || b; } +}; +template<> struct functor_traits { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + // unary functors: /** \internal @@ -249,7 +295,7 @@ struct functor_traits > template struct scalar_abs_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_abs_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return abs(a); } + EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return internal::abs(a); } template EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pabs(a); } @@ -271,7 +317,7 @@ struct functor_traits > template struct scalar_abs2_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_abs2_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return abs2(a); } + EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return internal::abs2(a); } template EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pmul(a,a); } @@ -287,7 +333,7 @@ struct functor_traits > */ template struct scalar_conjugate_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_conjugate_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return conj(a); } + EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return internal::conj(a); } template EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pconj(a); } }; @@ -324,7 +370,7 @@ template struct scalar_real_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_real_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return real(a); } + EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return internal::real(a); } }; template struct functor_traits > @@ -339,7 +385,7 @@ template struct scalar_imag_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return imag(a); } + EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return internal::imag(a); } }; template struct functor_traits > @@ -354,7 +400,7 @@ template struct scalar_real_ref_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_real_ref_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return real_ref(*const_cast(&a)); } + EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return internal::real_ref(*const_cast(&a)); } }; template struct functor_traits > @@ -369,7 +415,7 @@ template struct scalar_imag_ref_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_ref_op) typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return imag_ref(*const_cast(&a)); } + EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return internal::imag_ref(*const_cast(&a)); } }; template struct functor_traits > @@ -383,7 +429,7 @@ struct functor_traits > */ template struct scalar_exp_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_exp_op) - inline const Scalar operator() (const Scalar& a) const { return exp(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::exp(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::pexp(a); } }; @@ -399,7 +445,7 @@ struct functor_traits > */ template struct scalar_log_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_log_op) - inline const Scalar operator() (const Scalar& a) const { return log(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::log(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::plog(a); } }; @@ -584,7 +630,7 @@ template struct functor_traits< linspaced_o template struct linspaced_op { typedef typename packet_traits::type Packet; - linspaced_op(Scalar low, Scalar high, int num_steps) : impl(low, (high-low)/(num_steps-1)) {} + linspaced_op(Scalar low, Scalar high, int num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/(num_steps-1))) {} template EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return impl(i); } @@ -657,7 +703,7 @@ struct functor_traits > */ template struct scalar_sqrt_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_sqrt_op) - inline const Scalar operator() (const Scalar& a) const { return sqrt(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::sqrt(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::psqrt(a); } }; @@ -675,7 +721,7 @@ struct functor_traits > */ template struct scalar_cos_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_cos_op) - inline Scalar operator() (const Scalar& a) const { return cos(a); } + inline Scalar operator() (const Scalar& a) const { return internal::cos(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::pcos(a); } }; @@ -694,7 +740,7 @@ struct functor_traits > */ template struct scalar_sin_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_sin_op) - inline const Scalar operator() (const Scalar& a) const { return sin(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::sin(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::psin(a); } }; @@ -714,7 +760,7 @@ struct functor_traits > */ template struct scalar_tan_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_tan_op) - inline const Scalar operator() (const Scalar& a) const { return tan(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::tan(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::ptan(a); } }; @@ -733,7 +779,7 @@ struct functor_traits > */ template struct scalar_acos_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_acos_op) - inline const Scalar operator() (const Scalar& a) const { return acos(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::acos(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::pacos(a); } }; @@ -752,7 +798,7 @@ struct functor_traits > */ template struct scalar_asin_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_asin_op) - inline const Scalar operator() (const Scalar& a) const { return asin(a); } + inline const Scalar operator() (const Scalar& a) const { return internal::asin(a); } typedef typename packet_traits::type Packet; inline Packet packetOp(const Packet& a) const { return internal::pasin(a); } }; @@ -781,6 +827,20 @@ template struct functor_traits > { enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; }; +/** \internal + * \brief Template functor to compute the quotient between a scalar and array entries. + * \sa class CwiseUnaryOp, Cwise::inverse() + */ +template +struct scalar_inverse_mult_op { + scalar_inverse_mult_op(const Scalar& other) : m_other(other) {} + inline Scalar operator() (const Scalar& a) const { return m_other / a; } + template + inline const Packet packetOp(const Packet& a) const + { return internal::pdiv(pset1(m_other),a); } + Scalar m_other; +}; + /** \internal * \brief Template functor to compute the inverse of a scalar * \sa class CwiseUnaryOp, Cwise::inverse() @@ -939,4 +999,6 @@ struct functor_traits > } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_FUNCTORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h index d266eed0a..887641163 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h @@ -26,6 +26,8 @@ #ifndef EIGEN_FUZZY_H #define EIGEN_FUZZY_H +namespace Eigen { + namespace internal { @@ -35,8 +37,8 @@ struct isApprox_selector static bool run(const Derived& x, const OtherDerived& y, typename Derived::RealScalar prec) { using std::min; - const typename internal::nested::type nested(x); - const typename internal::nested::type otherNested(y); + typename internal::nested::type nested(x); + typename internal::nested::type otherNested(y); return (nested - otherNested).cwiseAbs2().sum() <= prec * prec * (min)(nested.cwiseAbs2().sum(), otherNested.cwiseAbs2().sum()); } }; @@ -158,4 +160,6 @@ bool DenseBase::isMuchSmallerThan( return internal::isMuchSmallerThan_object_selector::run(derived(), other.derived(), prec); } +} // end namespace Eigen + #endif // EIGEN_FUZZY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h new file mode 100644 index 000000000..4fbe1f14b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h @@ -0,0 +1,628 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2008-2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_GENERAL_PRODUCT_H +#define EIGEN_GENERAL_PRODUCT_H + +namespace Eigen { + +/** \class GeneralProduct + * \ingroup Core_Module + * + * \brief Expression of the product of two general matrices or vectors + * + * \param LhsNested the type used to store the left-hand side + * \param RhsNested the type used to store the right-hand side + * \param ProductMode the type of the product + * + * This class represents an expression of the product of two general matrices. + * We call a general matrix, a dense matrix with full storage. For instance, + * This excludes triangular, selfadjoint, and sparse matrices. + * It is the return type of the operator* between general matrices. Its template + * arguments are determined automatically by ProductReturnType. Therefore, + * GeneralProduct should never be used direclty. To determine the result type of a + * function which involves a matrix product, use ProductReturnType::Type. + * + * \sa ProductReturnType, MatrixBase::operator*(const MatrixBase&) + */ +template::value> +class GeneralProduct; + +enum { + Large = 2, + Small = 3 +}; + +namespace internal { + +template struct product_type_selector; + +template struct product_size_category +{ + enum { is_large = MaxSize == Dynamic || + Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD, + value = is_large ? Large + : Size == 1 ? 1 + : Small + }; +}; + +template struct product_type +{ + typedef typename remove_all::type _Lhs; + typedef typename remove_all::type _Rhs; + enum { + MaxRows = _Lhs::MaxRowsAtCompileTime, + Rows = _Lhs::RowsAtCompileTime, + MaxCols = _Rhs::MaxColsAtCompileTime, + Cols = _Rhs::ColsAtCompileTime, + MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::MaxColsAtCompileTime, + _Rhs::MaxRowsAtCompileTime), + Depth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::ColsAtCompileTime, + _Rhs::RowsAtCompileTime), + LargeThreshold = EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD + }; + + // the splitting into different lines of code here, introducing the _select enums and the typedef below, + // is to work around an internal compiler error with gcc 4.1 and 4.2. +private: + enum { + rows_select = product_size_category::value, + cols_select = product_size_category::value, + depth_select = product_size_category::value + }; + typedef product_type_selector selector; + +public: + enum { + value = selector::ret + }; +#ifdef EIGEN_DEBUG_PRODUCT + static void debug() + { + EIGEN_DEBUG_VAR(Rows); + EIGEN_DEBUG_VAR(Cols); + EIGEN_DEBUG_VAR(Depth); + EIGEN_DEBUG_VAR(rows_select); + EIGEN_DEBUG_VAR(cols_select); + EIGEN_DEBUG_VAR(depth_select); + EIGEN_DEBUG_VAR(value); + } +#endif +}; + + +/* The following allows to select the kind of product at compile time + * based on the three dimensions of the product. + * This is a compile time mapping from {1,Small,Large}^3 -> {product types} */ +// FIXME I'm not sure the current mapping is the ideal one. +template struct product_type_selector { enum { ret = OuterProduct }; }; +template struct product_type_selector<1, 1, Depth> { enum { ret = InnerProduct }; }; +template<> struct product_type_selector<1, 1, 1> { enum { ret = InnerProduct }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector<1, Small,Small> { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; +template<> struct product_type_selector<1, Large,Small> { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector<1, Large,Large> { enum { ret = GemvProduct }; }; +template<> struct product_type_selector<1, Small,Large> { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = GemvProduct }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = GemmProduct }; }; + +} // end namespace internal + +/** \class ProductReturnType + * \ingroup Core_Module + * + * \brief Helper class to get the correct and optimized returned type of operator* + * + * \param Lhs the type of the left-hand side + * \param Rhs the type of the right-hand side + * \param ProductMode the type of the product (determined automatically by internal::product_mode) + * + * This class defines the typename Type representing the optimized product expression + * between two matrix expressions. In practice, using ProductReturnType::Type + * is the recommended way to define the result type of a function returning an expression + * which involve a matrix product. The class Product should never be + * used directly. + * + * \sa class Product, MatrixBase::operator*(const MatrixBase&) + */ +template +struct ProductReturnType +{ + // TODO use the nested type to reduce instanciations ???? +// typedef typename internal::nested::type LhsNested; +// typedef typename internal::nested::type RhsNested; + + typedef GeneralProduct Type; +}; + +template +struct ProductReturnType +{ + typedef typename internal::nested::type >::type LhsNested; + typedef typename internal::nested::type >::type RhsNested; + typedef CoeffBasedProduct Type; +}; + +template +struct ProductReturnType +{ + typedef typename internal::nested::type >::type LhsNested; + typedef typename internal::nested::type >::type RhsNested; + typedef CoeffBasedProduct Type; +}; + +// this is a workaround for sun CC +template +struct LazyProductReturnType : public ProductReturnType +{}; + +/*********************************************************************** +* Implementation of Inner Vector Vector Product +***********************************************************************/ + +// FIXME : maybe the "inner product" could return a Scalar +// instead of a 1x1 matrix ?? +// Pro: more natural for the user +// Cons: this could be a problem if in a meta unrolled algorithm a matrix-matrix +// product ends up to a row-vector times col-vector product... To tackle this use +// case, we could have a specialization for Block with: operator=(Scalar x); + +namespace internal { + +template +struct traits > + : traits::ReturnType,1,1> > +{}; + +} + +template +class GeneralProduct + : internal::no_assignment_operator, + public Matrix::ReturnType,1,1> +{ + typedef Matrix::ReturnType,1,1> Base; + public: + GeneralProduct(const Lhs& lhs, const Rhs& rhs) + { + EIGEN_STATIC_ASSERT((internal::is_same::value), + YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) + + Base::coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); + } + + /** Convertion to scalar */ + operator const typename Base::Scalar() const { + return Base::coeff(0,0); + } +}; + +/*********************************************************************** +* Implementation of Outer Vector Vector Product +***********************************************************************/ + +namespace internal { +template struct outer_product_selector; + +template +struct traits > + : traits, Lhs, Rhs> > +{}; + +} + +template +class GeneralProduct + : public ProductBase, Lhs, Rhs> +{ + public: + EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) + + GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) + { + EIGEN_STATIC_ASSERT((internal::is_same::value), + YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) + } + + template void scaleAndAddTo(Dest& dest, Scalar alpha) const + { + internal::outer_product_selector<(int(Dest::Flags)&RowMajorBit) ? RowMajor : ColMajor>::run(*this, dest, alpha); + } +}; + +namespace internal { + +template<> struct outer_product_selector { + template + static EIGEN_DONT_INLINE void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) { + typedef typename Dest::Index Index; + // FIXME make sure lhs is sequentially stored + // FIXME not very good if rhs is real and lhs complex while alpha is real too + const Index cols = dest.cols(); + for (Index j=0; j struct outer_product_selector { + template + static EIGEN_DONT_INLINE void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) { + typedef typename Dest::Index Index; + // FIXME make sure rhs is sequentially stored + // FIXME not very good if lhs is real and rhs complex while alpha is real too + const Index rows = dest.rows(); + for (Index i=0; i call fast BLAS-like colmajor routine + * 2 - the matrix is row-major, BLAS compatible and N is large => call fast BLAS-like rowmajor routine + * 3 - all other cases are handled using a simple loop along the outer-storage direction. + * Therefore we need a lower level meta selector. + * Furthermore, if the matrix is the rhs, then the product has to be transposed. + */ +namespace internal { + +template +struct traits > + : traits, Lhs, Rhs> > +{}; + +template +struct gemv_selector; + +} // end namespace internal + +template +class GeneralProduct + : public ProductBase, Lhs, Rhs> +{ + public: + EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) + + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + + GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) + { +// EIGEN_STATIC_ASSERT((internal::is_same::value), +// YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) + } + + enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; + typedef typename internal::conditional::type MatrixType; + + template void scaleAndAddTo(Dest& dst, Scalar alpha) const + { + eigen_assert(m_lhs.rows() == dst.rows() && m_rhs.cols() == dst.cols()); + internal::gemv_selector::HasUsableDirectAccess)>::run(*this, dst, alpha); + } +}; + +namespace internal { + +// The vector is on the left => transposition +template +struct gemv_selector +{ + template + static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) + { + Transpose destT(dest); + enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; + gemv_selector + ::run(GeneralProduct,Transpose, GemvProduct> + (prod.rhs().transpose(), prod.lhs().transpose()), destT, alpha); + } +}; + +template struct gemv_static_vector_if; + +template +struct gemv_static_vector_if +{ + EIGEN_STRONG_INLINE Scalar* data() { eigen_internal_assert(false && "should never be called"); return 0; } +}; + +template +struct gemv_static_vector_if +{ + EIGEN_STRONG_INLINE Scalar* data() { return 0; } +}; + +template +struct gemv_static_vector_if +{ + #if EIGEN_ALIGN_STATICALLY + internal::plain_array m_data; + EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } + #else + // Some architectures cannot align on the stack, + // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. + enum { + ForceAlignment = internal::packet_traits::Vectorizable, + PacketSize = internal::packet_traits::size + }; + internal::plain_array m_data; + EIGEN_STRONG_INLINE Scalar* data() { + return ForceAlignment + ? reinterpret_cast((reinterpret_cast(m_data.array) & ~(size_t(15))) + 16) + : m_data.array; + } + #endif +}; + +template<> struct gemv_selector +{ + template + static inline void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) + { + typedef typename ProductType::Index Index; + typedef typename ProductType::LhsScalar LhsScalar; + typedef typename ProductType::RhsScalar RhsScalar; + typedef typename ProductType::Scalar ResScalar; + typedef typename ProductType::RealScalar RealScalar; + typedef typename ProductType::ActualLhsType ActualLhsType; + typedef typename ProductType::ActualRhsType ActualRhsType; + typedef typename ProductType::LhsBlasTraits LhsBlasTraits; + typedef typename ProductType::RhsBlasTraits RhsBlasTraits; + typedef Map, Aligned> MappedDest; + + ActualLhsType actualLhs = LhsBlasTraits::extract(prod.lhs()); + ActualRhsType actualRhs = RhsBlasTraits::extract(prod.rhs()); + + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) + * RhsBlasTraits::extractScalarFactor(prod.rhs()); + + enum { + // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 + // on, the other hand it is good for the cache to pack the vector anyways... + EvalToDestAtCompileTime = Dest::InnerStrideAtCompileTime==1, + ComplexByReal = (NumTraits::IsComplex) && (!NumTraits::IsComplex), + MightCannotUseDest = (Dest::InnerStrideAtCompileTime!=1) || ComplexByReal + }; + + gemv_static_vector_if static_dest; + + bool alphaIsCompatible = (!ComplexByReal) || (imag(actualAlpha)==RealScalar(0)); + bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; + + RhsScalar compatibleAlpha = get_factor::run(actualAlpha); + + ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), + evalToDest ? dest.data() : static_dest.data()); + + if(!evalToDest) + { + #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN + int size = dest.size(); + EIGEN_DENSE_STORAGE_CTOR_PLUGIN + #endif + if(!alphaIsCompatible) + { + MappedDest(actualDestPtr, dest.size()).setZero(); + compatibleAlpha = RhsScalar(1); + } + else + MappedDest(actualDestPtr, dest.size()) = dest; + } + + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + actualLhs.data(), actualLhs.outerStride(), + actualRhs.data(), actualRhs.innerStride(), + actualDestPtr, 1, + compatibleAlpha); + + if (!evalToDest) + { + if(!alphaIsCompatible) + dest += actualAlpha * MappedDest(actualDestPtr, dest.size()); + else + dest = MappedDest(actualDestPtr, dest.size()); + } + } +}; + +template<> struct gemv_selector +{ + template + static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) + { + typedef typename ProductType::LhsScalar LhsScalar; + typedef typename ProductType::RhsScalar RhsScalar; + typedef typename ProductType::Scalar ResScalar; + typedef typename ProductType::Index Index; + typedef typename ProductType::ActualLhsType ActualLhsType; + typedef typename ProductType::ActualRhsType ActualRhsType; + typedef typename ProductType::_ActualRhsType _ActualRhsType; + typedef typename ProductType::LhsBlasTraits LhsBlasTraits; + typedef typename ProductType::RhsBlasTraits RhsBlasTraits; + + typename add_const::type actualLhs = LhsBlasTraits::extract(prod.lhs()); + typename add_const::type actualRhs = RhsBlasTraits::extract(prod.rhs()); + + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) + * RhsBlasTraits::extractScalarFactor(prod.rhs()); + + enum { + // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 + // on, the other hand it is good for the cache to pack the vector anyways... + DirectlyUseRhs = _ActualRhsType::InnerStrideAtCompileTime==1 + }; + + gemv_static_vector_if static_rhs; + + ei_declare_aligned_stack_constructed_variable(RhsScalar,actualRhsPtr,actualRhs.size(), + DirectlyUseRhs ? const_cast(actualRhs.data()) : static_rhs.data()); + + if(!DirectlyUseRhs) + { + #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN + int size = actualRhs.size(); + EIGEN_DENSE_STORAGE_CTOR_PLUGIN + #endif + Map(actualRhsPtr, actualRhs.size()) = actualRhs; + } + + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + actualLhs.data(), actualLhs.outerStride(), + actualRhsPtr, 1, + dest.data(), dest.innerStride(), + actualAlpha); + } +}; + +template<> struct gemv_selector +{ + template + static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) + { + typedef typename Dest::Index Index; + // TODO makes sure dest is sequentially stored in memory, otherwise use a temp + const Index size = prod.rhs().rows(); + for(Index k=0; k struct gemv_selector +{ + template + static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) + { + typedef typename Dest::Index Index; + // TODO makes sure rhs is sequentially stored in memory, otherwise use a temp + const Index rows = prod.rows(); + for(Index i=0; i +template +inline const typename ProductReturnType::Type +MatrixBase::operator*(const MatrixBase &other) const +{ + // A note regarding the function declaration: In MSVC, this function will sometimes + // not be inlined since DenseStorage is an unwindable object for dynamic + // matrices and product types are holding a member to store the result. + // Thus it does not help tagging this function with EIGEN_STRONG_INLINE. + enum { + ProductIsValid = Derived::ColsAtCompileTime==Dynamic + || OtherDerived::RowsAtCompileTime==Dynamic + || int(Derived::ColsAtCompileTime)==int(OtherDerived::RowsAtCompileTime), + AreVectors = Derived::IsVectorAtCompileTime && OtherDerived::IsVectorAtCompileTime, + SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(Derived,OtherDerived) + }; + // note to the lost user: + // * for a dot product use: v1.dot(v2) + // * for a coeff-wise product use: v1.cwiseProduct(v2) + EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes), + INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS) + EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors), + INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) + EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) +#ifdef EIGEN_DEBUG_PRODUCT + internal::product_type::debug(); +#endif + return typename ProductReturnType::Type(derived(), other.derived()); +} + +/** \returns an expression of the matrix product of \c *this and \a other without implicit evaluation. + * + * The returned product will behave like any other expressions: the coefficients of the product will be + * computed once at a time as requested. This might be useful in some extremely rare cases when only + * a small and no coherent fraction of the result's coefficients have to be computed. + * + * \warning This version of the matrix product can be much much slower. So use it only if you know + * what you are doing and that you measured a true speed improvement. + * + * \sa operator*(const MatrixBase&) + */ +template +template +const typename LazyProductReturnType::Type +MatrixBase::lazyProduct(const MatrixBase &other) const +{ + enum { + ProductIsValid = Derived::ColsAtCompileTime==Dynamic + || OtherDerived::RowsAtCompileTime==Dynamic + || int(Derived::ColsAtCompileTime)==int(OtherDerived::RowsAtCompileTime), + AreVectors = Derived::IsVectorAtCompileTime && OtherDerived::IsVectorAtCompileTime, + SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(Derived,OtherDerived) + }; + // note to the lost user: + // * for a dot product use: v1.dot(v2) + // * for a coeff-wise product use: v1.cwiseProduct(v2) + EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes), + INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS) + EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors), + INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) + EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) + + return typename LazyProductReturnType::Type(derived(), other.derived()); +} + +} // end namespace Eigen + +#endif // EIGEN_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h index 8ed835327..d92ac9529 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h @@ -26,6 +26,8 @@ #ifndef EIGEN_GENERIC_PACKET_MATH_H #define EIGEN_GENERIC_PACKET_MATH_H +namespace Eigen { + namespace internal { /** \internal @@ -312,7 +314,7 @@ template struct palign_impl { // by default data are aligned, so there is nothing to be done :) - inline static void run(PacketType&, const PacketType&) {} + static inline void run(PacketType&, const PacketType&) {} }; /** \internal update \a first using the concatenation of the \a Offset last elements @@ -335,5 +337,7 @@ template<> inline std::complex pmul(const std::complex& a, const } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_GENERIC_PACKET_MATH_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h index 144145a95..94605252d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h @@ -66,13 +66,36 @@ namespace std template inline const Eigen::CwiseUnaryOp, const Derived> - pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { \ - return x.derived().pow(exponent); \ + pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { + return x.derived().pow(exponent); + } + + template + inline const Eigen::CwiseBinaryOp, const Derived, const Derived> + pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) + { + return Eigen::CwiseBinaryOp, const Derived, const Derived>( + x.derived(), + exponents.derived() + ); } } namespace Eigen { + /** + * \brief Component-wise division of a scalar by array elements. + **/ + template + inline const Eigen::CwiseUnaryOp, const Derived> + operator/(typename Derived::Scalar s, const Eigen::ArrayBase& a) + { + return Eigen::CwiseUnaryOp, const Derived>( + a.derived(), + Eigen::internal::scalar_inverse_mult_op(s) + ); + } + namespace internal { EIGEN_ARRAY_DECLARE_GLOBAL_EIGEN_UNARY(real,scalar_real_op) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h index f3cfcdbf4..2f1906f2a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h @@ -26,6 +26,8 @@ #ifndef EIGEN_IO_H #define EIGEN_IO_H +namespace Eigen { + enum { DontAlignCols = 1 }; enum { StreamPrecision = -1, FullPrecision = -2 }; @@ -171,7 +173,7 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& return s; } - const typename Derived::Nested m = _m; + typename Derived::Nested m = _m; typedef typename Derived::Scalar Scalar; typedef typename Derived::Index Index; @@ -257,4 +259,6 @@ std::ostream & operator << return internal::print_matrix(s, m.eval(), EIGEN_DEFAULT_IO_FORMAT); } +} // end namespace Eigen + #endif // EIGEN_IO_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h index 2bf80b3af..360a2280e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h @@ -26,6 +26,8 @@ #ifndef EIGEN_MAP_H #define EIGEN_MAP_H +namespace Eigen { + /** \class Map * \ingroup Core_Module * @@ -200,4 +202,6 @@ inline Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> this->_set_noalias(Eigen::Map(data)); } +} // end namespace Eigen + #endif // EIGEN_MAP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h index 9426e2d24..2b736cb74 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h @@ -30,6 +30,7 @@ EIGEN_STATIC_ASSERT((int(internal::traits::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ YOU_ARE_TRYING_TO_USE_AN_INDEX_BASED_ACCESSOR_ON_AN_EXPRESSION_THAT_DOES_NOT_SUPPORT_THAT) +namespace Eigen { /** \class MapBase * \ingroup Core_Module @@ -251,5 +252,6 @@ template class MapBase using Base::Base::operator=; }; +} // end namespace Eigen #endif // EIGEN_MAPBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h index 2b454db21..ab153c1eb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MATHFUNCTIONS_H #define EIGEN_MATHFUNCTIONS_H +namespace Eigen { + namespace internal { /** \internal \struct global_math_functions_filtering_base @@ -309,8 +311,7 @@ struct abs2_impl > { static inline RealScalar run(const std::complex& x) { - using std::norm; - return norm(x); + return real(x)*real(x) + imag(x)*imag(x); } }; @@ -553,7 +554,7 @@ struct pow_default_impl { static inline Scalar run(Scalar x, Scalar y) { - Scalar res = 1; + Scalar res(1); eigen_assert(!NumTraits::IsSigned || y >= 0); if(y & 1) res *= x; y >>= 1; @@ -838,6 +839,19 @@ template<> struct scalar_fuzzy_impl }; +/**************************************************************************** +* Special functions * +****************************************************************************/ + +// std::isfinite is non standard, so let's define our own version, +// even though it is not very efficient. +template bool isfinite(const T& x) +{ + return x::highest() && x>NumTraits::lowest(); +} + } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_MATHFUNCTIONS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h index 982c9256a..8742a0130 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h @@ -26,6 +26,8 @@ #ifndef EIGEN_MATRIX_H #define EIGEN_MATRIX_H +namespace Eigen { + /** \class Matrix * \ingroup Core_Module * @@ -411,25 +413,8 @@ EIGEN_MAKE_TYPEDEFS_ALL_SIZES(std::complex, cd) #undef EIGEN_MAKE_TYPEDEFS_ALL_SIZES #undef EIGEN_MAKE_TYPEDEFS +#undef EIGEN_MAKE_FIXED_TYPEDEFS -#undef EIGEN_MAKE_TYPEDEFS_LARGE - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, SizeSuffix) \ -using Eigen::Matrix##SizeSuffix##TypeSuffix; \ -using Eigen::Vector##SizeSuffix##TypeSuffix; \ -using Eigen::RowVector##SizeSuffix##TypeSuffix; - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(TypeSuffix) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 2) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 3) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 4) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, X) \ - -#define EIGEN_USING_MATRIX_TYPEDEFS \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(i) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(f) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(d) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cf) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cd) +} // end namespace Eigen #endif // EIGEN_MATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h index 62877bce0..5a744c5ec 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h @@ -26,6 +26,8 @@ #ifndef EIGEN_MATRIXBASE_H #define EIGEN_MATRIXBASE_H +namespace Eigen { + /** \class MatrixBase * \ingroup Core_Module * @@ -250,8 +252,7 @@ template class MatrixBase // huuuge hack. make Eigen2's matrix.part() work in eigen3. Problem: Diagonal is now a class template instead // of an integer constant. Solution: overload the part() method template wrt template parameters list. - // Note: replacing next line by "template class U>" produces a mysterious error C2082 in MSVC. - template class U> + template class U> const DiagonalWrapper part() const { return diagonal().asDiagonal(); } #endif // EIGEN2_SUPPORT @@ -331,7 +332,7 @@ template class MatrixBase /** \returns an \link ArrayBase Array \endlink expression of this matrix * \sa ArrayBase::matrix() */ ArrayWrapper array() { return derived(); } - const ArrayWrapper array() const { return derived(); } + const ArrayWrapper array() const { return derived(); } /////////// LU module /////////// @@ -466,6 +467,8 @@ template class MatrixBase const MatrixFunctionReturnValue sinh() const; const MatrixFunctionReturnValue cos() const; const MatrixFunctionReturnValue sin() const; + const MatrixSquareRootReturnValue sqrt() const; + const MatrixLogarithmReturnValue log() const; #ifdef EIGEN2_SUPPORT template @@ -512,10 +515,12 @@ template class MatrixBase protected: // mixing arrays and matrices is not legal template Derived& operator+=(const ArrayBase& ) - {EIGEN_STATIC_ASSERT(sizeof(typename OtherDerived::Scalar)==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES);} + {EIGEN_STATIC_ASSERT(std::ptrdiff_t(sizeof(typename OtherDerived::Scalar))==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES); return *this;} // mixing arrays and matrices is not legal template Derived& operator-=(const ArrayBase& ) - {EIGEN_STATIC_ASSERT(sizeof(typename OtherDerived::Scalar)==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES);} + {EIGEN_STATIC_ASSERT(std::ptrdiff_t(sizeof(typename OtherDerived::Scalar))==-1,YOU_CANNOT_MIX_ARRAYS_AND_MATRICES); return *this;} }; +} // end namespace Eigen + #endif // EIGEN_MATRIXBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h index a6104d2a4..cfe3e7990 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h @@ -26,6 +26,8 @@ #ifndef EIGEN_NESTBYVALUE_H #define EIGEN_NESTBYVALUE_H +namespace Eigen { + /** \class NestByValue * \ingroup Core_Module * @@ -119,4 +121,6 @@ DenseBase::nestByValue() const return NestByValue(derived()); } +} // end namespace Eigen + #endif // EIGEN_NESTBYVALUE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h index da64affcf..5278cfb73 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h @@ -25,6 +25,8 @@ #ifndef EIGEN_NOALIAS_H #define EIGEN_NOALIAS_H +namespace Eigen { + /** \class NoAlias * \ingroup Core_Module * @@ -133,4 +135,6 @@ NoAlias MatrixBase::noalias() return derived(); } +} // end namespace Eigen + #endif // EIGEN_NOALIAS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h index 73ef05dfe..e8867235e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h @@ -25,6 +25,8 @@ #ifndef EIGEN_NUMTRAITS_H #define EIGEN_NUMTRAITS_H +namespace Eigen { + /** \class NumTraits * \ingroup Core_Module * @@ -81,14 +83,14 @@ template struct GenericNumTraits >::type NonInteger; typedef T Nested; - inline static Real epsilon() { return std::numeric_limits::epsilon(); } - inline static Real dummy_precision() + static inline Real epsilon() { return std::numeric_limits::epsilon(); } + static inline Real dummy_precision() { // make sure to override this for floating-point types return Real(0); } - inline static T highest() { return (std::numeric_limits::max)(); } - inline static T lowest() { return IsInteger ? (std::numeric_limits::min)() : (-(std::numeric_limits::max)()); } + static inline T highest() { return (std::numeric_limits::max)(); } + static inline T lowest() { return IsInteger ? (std::numeric_limits::min)() : (-(std::numeric_limits::max)()); } #ifdef EIGEN2_SUPPORT enum { @@ -104,12 +106,12 @@ template struct NumTraits : GenericNumTraits template<> struct NumTraits : GenericNumTraits { - inline static float dummy_precision() { return 1e-5f; } + static inline float dummy_precision() { return 1e-5f; } }; template<> struct NumTraits : GenericNumTraits { - inline static double dummy_precision() { return 1e-12; } + static inline double dummy_precision() { return 1e-12; } }; template<> struct NumTraits @@ -130,8 +132,8 @@ template struct NumTraits > MulCost = 4 * NumTraits::MulCost + 2 * NumTraits::AddCost }; - inline static Real epsilon() { return NumTraits::epsilon(); } - inline static Real dummy_precision() { return NumTraits::dummy_precision(); } + static inline Real epsilon() { return NumTraits::epsilon(); } + static inline Real dummy_precision() { return NumTraits::dummy_precision(); } }; template @@ -155,6 +157,6 @@ struct NumTraits > }; }; - +} // end namespace Eigen #endif // EIGEN_NUMTRAITS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h index a064e053e..e0d618dfb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h @@ -26,6 +26,8 @@ #ifndef EIGEN_PERMUTATIONMATRIX_H #define EIGEN_PERMUTATIONMATRIX_H +namespace Eigen { + template class PermutedImpl; /** \class PermutationBase @@ -56,6 +58,8 @@ namespace internal { template struct permut_matrix_product_retval; +template +struct permut_sparsematrix_product_retval; enum PermPermProduct_t {PermPermProduct}; } // end namespace internal @@ -511,7 +515,7 @@ class PermutationWrapper : public PermutationBase MatrixBase::asPermutation() con return derived(); } +} // end namespace Eigen + #endif // EIGEN_PERMUTATIONMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index 612254e9d..f9c432732 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -32,6 +32,8 @@ # define EIGEN_INITIALIZE_BY_ZERO_IF_THAT_OPTION_IS_ENABLED #endif +namespace Eigen { + namespace internal { template @@ -47,13 +49,13 @@ EIGEN_ALWAYS_INLINE void check_rows_cols_for_overflow(Index rows, Index cols) throw_std_bad_alloc(); } -template (Derived::IsVectorAtCompileTime)> struct conservative_resize_like_impl; +template struct conservative_resize_like_impl; template struct matrix_swap_impl; } // end namespace internal -/** +/** \class PlainObjectBase * \brief %Dense storage base class for matrices and arrays. * * This class can be extended with the help of the plugin mechanism described on the page @@ -61,8 +63,29 @@ template struct m * * \sa \ref TopicClassHierarchy */ +#ifdef EIGEN_PARSED_BY_DOXYGEN +namespace internal { + +// this is a warkaround to doxygen not being able to understand the inheritence logic +// when it is hidden by the dense_xpr_base helper struct. +template struct dense_xpr_base_dispatcher_for_doxygen;// : public MatrixBase {}; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher_for_doxygen > + : public MatrixBase > {}; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher_for_doxygen > + : public ArrayBase > {}; + +} // namespace internal + +template +class PlainObjectBase : public internal::dense_xpr_base_dispatcher_for_doxygen +#else template class PlainObjectBase : public internal::dense_xpr_base::type +#endif { public: enum { Options = internal::traits::Options }; @@ -443,68 +466,68 @@ class PlainObjectBase : public internal::dense_xpr_base::type * \see class Map */ //@{ - inline static ConstMapType Map(const Scalar* data) + static inline ConstMapType Map(const Scalar* data) { return ConstMapType(data); } - inline static MapType Map(Scalar* data) + static inline MapType Map(Scalar* data) { return MapType(data); } - inline static ConstMapType Map(const Scalar* data, Index size) + static inline ConstMapType Map(const Scalar* data, Index size) { return ConstMapType(data, size); } - inline static MapType Map(Scalar* data, Index size) + static inline MapType Map(Scalar* data, Index size) { return MapType(data, size); } - inline static ConstMapType Map(const Scalar* data, Index rows, Index cols) + static inline ConstMapType Map(const Scalar* data, Index rows, Index cols) { return ConstMapType(data, rows, cols); } - inline static MapType Map(Scalar* data, Index rows, Index cols) + static inline MapType Map(Scalar* data, Index rows, Index cols) { return MapType(data, rows, cols); } - inline static ConstAlignedMapType MapAligned(const Scalar* data) + static inline ConstAlignedMapType MapAligned(const Scalar* data) { return ConstAlignedMapType(data); } - inline static AlignedMapType MapAligned(Scalar* data) + static inline AlignedMapType MapAligned(Scalar* data) { return AlignedMapType(data); } - inline static ConstAlignedMapType MapAligned(const Scalar* data, Index size) + static inline ConstAlignedMapType MapAligned(const Scalar* data, Index size) { return ConstAlignedMapType(data, size); } - inline static AlignedMapType MapAligned(Scalar* data, Index size) + static inline AlignedMapType MapAligned(Scalar* data, Index size) { return AlignedMapType(data, size); } - inline static ConstAlignedMapType MapAligned(const Scalar* data, Index rows, Index cols) + static inline ConstAlignedMapType MapAligned(const Scalar* data, Index rows, Index cols) { return ConstAlignedMapType(data, rows, cols); } - inline static AlignedMapType MapAligned(Scalar* data, Index rows, Index cols) + static inline AlignedMapType MapAligned(Scalar* data, Index rows, Index cols) { return AlignedMapType(data, rows, cols); } template - inline static typename StridedConstMapType >::type Map(const Scalar* data, const Stride& stride) + static inline typename StridedConstMapType >::type Map(const Scalar* data, const Stride& stride) { return typename StridedConstMapType >::type(data, stride); } template - inline static typename StridedMapType >::type Map(Scalar* data, const Stride& stride) + static inline typename StridedMapType >::type Map(Scalar* data, const Stride& stride) { return typename StridedMapType >::type(data, stride); } template - inline static typename StridedConstMapType >::type Map(const Scalar* data, Index size, const Stride& stride) + static inline typename StridedConstMapType >::type Map(const Scalar* data, Index size, const Stride& stride) { return typename StridedConstMapType >::type(data, size, stride); } template - inline static typename StridedMapType >::type Map(Scalar* data, Index size, const Stride& stride) + static inline typename StridedMapType >::type Map(Scalar* data, Index size, const Stride& stride) { return typename StridedMapType >::type(data, size, stride); } template - inline static typename StridedConstMapType >::type Map(const Scalar* data, Index rows, Index cols, const Stride& stride) + static inline typename StridedConstMapType >::type Map(const Scalar* data, Index rows, Index cols, const Stride& stride) { return typename StridedConstMapType >::type(data, rows, cols, stride); } template - inline static typename StridedMapType >::type Map(Scalar* data, Index rows, Index cols, const Stride& stride) + static inline typename StridedMapType >::type Map(Scalar* data, Index rows, Index cols, const Stride& stride) { return typename StridedMapType >::type(data, rows, cols, stride); } template - inline static typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, const Stride& stride) + static inline typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, const Stride& stride) { return typename StridedConstAlignedMapType >::type(data, stride); } template - inline static typename StridedAlignedMapType >::type MapAligned(Scalar* data, const Stride& stride) + static inline typename StridedAlignedMapType >::type MapAligned(Scalar* data, const Stride& stride) { return typename StridedAlignedMapType >::type(data, stride); } template - inline static typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, Index size, const Stride& stride) + static inline typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, Index size, const Stride& stride) { return typename StridedConstAlignedMapType >::type(data, size, stride); } template - inline static typename StridedAlignedMapType >::type MapAligned(Scalar* data, Index size, const Stride& stride) + static inline typename StridedAlignedMapType >::type MapAligned(Scalar* data, Index size, const Stride& stride) { return typename StridedAlignedMapType >::type(data, size, stride); } template - inline static typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, Index rows, Index cols, const Stride& stride) + static inline typename StridedConstAlignedMapType >::type MapAligned(const Scalar* data, Index rows, Index cols, const Stride& stride) { return typename StridedConstAlignedMapType >::type(data, rows, cols, stride); } template - inline static typename StridedAlignedMapType >::type MapAligned(Scalar* data, Index rows, Index cols, const Stride& stride) + static inline typename StridedAlignedMapType >::type MapAligned(Scalar* data, Index rows, Index cols, const Stride& stride) { return typename StridedAlignedMapType >::type(data, rows, cols, stride); } //@} @@ -594,6 +617,9 @@ class PlainObjectBase : public internal::dense_xpr_base::type template EIGEN_STRONG_INLINE void _init2(Index rows, Index cols, typename internal::enable_if::type* = 0) { + EIGEN_STATIC_ASSERT(bool(NumTraits::IsInteger) && + bool(NumTraits::IsInteger), + FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) eigen_assert(rows >= 0 && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == rows) && cols >= 0 && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == cols)); internal::check_rows_cols_for_overflow(rows, cols); @@ -623,7 +649,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type public: #ifndef EIGEN_PARSED_BY_DOXYGEN - EIGEN_STRONG_INLINE static void _check_template_params() + static EIGEN_STRONG_INLINE void _check_template_params() { EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, (Options&RowMajor)==RowMajor) && EIGEN_IMPLIES(MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1, (Options&RowMajor)==0) @@ -751,4 +777,6 @@ struct matrix_swap_impl } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_DENSESTORAGEBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h index e2035b242..53eb0fbae 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h @@ -1,8 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2006-2008 Benoit Jacob -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2008-2011 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -26,600 +25,89 @@ #ifndef EIGEN_PRODUCT_H #define EIGEN_PRODUCT_H -/** \class GeneralProduct +template class Product; +template class ProductImpl; + +/** \class Product * \ingroup Core_Module * - * \brief Expression of the product of two general matrices or vectors + * \brief Expression of the product of two arbitrary matrices or vectors * - * \param LhsNested the type used to store the left-hand side - * \param RhsNested the type used to store the right-hand side - * \param ProductMode the type of the product + * \param Lhs the type of the left-hand side expression + * \param Rhs the type of the right-hand side expression * - * This class represents an expression of the product of two general matrices. - * We call a general matrix, a dense matrix with full storage. For instance, - * This excludes triangular, selfadjoint, and sparse matrices. - * It is the return type of the operator* between general matrices. Its template - * arguments are determined automatically by ProductReturnType. Therefore, - * GeneralProduct should never be used direclty. To determine the result type of a - * function which involves a matrix product, use ProductReturnType::Type. + * This class represents an expression of the product of two arbitrary matrices. * - * \sa ProductReturnType, MatrixBase::operator*(const MatrixBase&) */ -template::value> -class GeneralProduct; - -enum { - Large = 2, - Small = 3 -}; namespace internal { - -template struct product_type_selector; - -template struct product_size_category +template +struct traits > { - enum { is_large = MaxSize == Dynamic || - Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD, - value = is_large ? Large - : Size == 1 ? 1 - : Small + typedef MatrixXpr XprKind; + typedef typename remove_all::type LhsCleaned; + typedef typename remove_all::type RhsCleaned; + typedef typename scalar_product_traits::Scalar, typename traits::Scalar>::ReturnType Scalar; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + enum { + RowsAtCompileTime = LhsCleaned::RowsAtCompileTime, + ColsAtCompileTime = RhsCleaned::ColsAtCompileTime, + MaxRowsAtCompileTime = LhsCleaned::MaxRowsAtCompileTime, + MaxColsAtCompileTime = RhsCleaned::MaxColsAtCompileTime, + Flags = (MaxRowsAtCompileTime==1 ? RowMajorBit : 0), // TODO should be no storage order + CoeffReadCost = 0 // TODO CoeffReadCost should not be part of the expression traits }; }; - -template struct product_type -{ - typedef typename remove_all::type _Lhs; - typedef typename remove_all::type _Rhs; - enum { - MaxRows = _Lhs::MaxRowsAtCompileTime, - Rows = _Lhs::RowsAtCompileTime, - MaxCols = _Rhs::MaxColsAtCompileTime, - Cols = _Rhs::ColsAtCompileTime, - MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::MaxColsAtCompileTime, - _Rhs::MaxRowsAtCompileTime), - Depth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::ColsAtCompileTime, - _Rhs::RowsAtCompileTime), - LargeThreshold = EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD - }; - - // the splitting into different lines of code here, introducing the _select enums and the typedef below, - // is to work around an internal compiler error with gcc 4.1 and 4.2. -private: - enum { - rows_select = product_size_category::value, - cols_select = product_size_category::value, - depth_select = product_size_category::value - }; - typedef product_type_selector selector; - -public: - enum { - value = selector::ret - }; -#ifdef EIGEN_DEBUG_PRODUCT - static void debug() - { - EIGEN_DEBUG_VAR(Rows); - EIGEN_DEBUG_VAR(Cols); - EIGEN_DEBUG_VAR(Depth); - EIGEN_DEBUG_VAR(rows_select); - EIGEN_DEBUG_VAR(cols_select); - EIGEN_DEBUG_VAR(depth_select); - EIGEN_DEBUG_VAR(value); - } -#endif -}; - - -/* The following allows to select the kind of product at compile time - * based on the three dimensions of the product. - * This is a compile time mapping from {1,Small,Large}^3 -> {product types} */ -// FIXME I'm not sure the current mapping is the ideal one. -template struct product_type_selector { enum { ret = OuterProduct }; }; -template struct product_type_selector<1, 1, Depth> { enum { ret = InnerProduct }; }; -template<> struct product_type_selector<1, 1, 1> { enum { ret = InnerProduct }; }; -template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector<1, Small,Small> { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; -template<> struct product_type_selector<1, Large,Small> { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector<1, Large,Large> { enum { ret = GemvProduct }; }; -template<> struct product_type_selector<1, Small,Large> { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = GemvProduct }; }; -template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; - } // end namespace internal -/** \class ProductReturnType - * \ingroup Core_Module - * - * \brief Helper class to get the correct and optimized returned type of operator* - * - * \param Lhs the type of the left-hand side - * \param Rhs the type of the right-hand side - * \param ProductMode the type of the product (determined automatically by internal::product_mode) - * - * This class defines the typename Type representing the optimized product expression - * between two matrix expressions. In practice, using ProductReturnType::Type - * is the recommended way to define the result type of a function returning an expression - * which involve a matrix product. The class Product should never be - * used directly. - * - * \sa class Product, MatrixBase::operator*(const MatrixBase&) - */ -template -struct ProductReturnType -{ - // TODO use the nested type to reduce instanciations ???? -// typedef typename internal::nested::type LhsNested; -// typedef typename internal::nested::type RhsNested; - - typedef GeneralProduct Type; -}; template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -// this is a workaround for sun CC -template -struct LazyProductReturnType : public ProductReturnType -{}; - -/*********************************************************************** -* Implementation of Inner Vector Vector Product -***********************************************************************/ - -// FIXME : maybe the "inner product" could return a Scalar -// instead of a 1x1 matrix ?? -// Pro: more natural for the user -// Cons: this could be a problem if in a meta unrolled algorithm a matrix-matrix -// product ends up to a row-vector times col-vector product... To tackle this use -// case, we could have a specialization for Block with: operator=(Scalar x); - -namespace internal { - -template -struct traits > - : traits::ReturnType,1,1> > -{}; - -} - -template -class GeneralProduct - : internal::no_assignment_operator, - public Matrix::ReturnType,1,1> -{ - typedef Matrix::ReturnType,1,1> Base; - public: - GeneralProduct(const Lhs& lhs, const Rhs& rhs) - { - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - Base::coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); - } - - /** Convertion to scalar */ - operator const typename Base::Scalar() const { - return Base::coeff(0,0); - } -}; - -/*********************************************************************** -* Implementation of Outer Vector Vector Product -***********************************************************************/ - -namespace internal { -template struct outer_product_selector; - -template -struct traits > - : traits, Lhs, Rhs> > -{}; - -} - -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> +class Product : public ProductImpl::StorageKind, + typename internal::traits::StorageKind>::ret> { public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) - { - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - } - - template void scaleAndAddTo(Dest& dest, Scalar alpha) const - { - internal::outer_product_selector<(int(Dest::Flags)&RowMajorBit) ? RowMajor : ColMajor>::run(*this, dest, alpha); - } -}; - -namespace internal { - -template<> struct outer_product_selector { - template - static EIGEN_DONT_INLINE void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) { - typedef typename Dest::Index Index; - // FIXME make sure lhs is sequentially stored - // FIXME not very good if rhs is real and lhs complex while alpha is real too - const Index cols = dest.cols(); - for (Index j=0; j struct outer_product_selector { - template - static EIGEN_DONT_INLINE void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) { - typedef typename Dest::Index Index; - // FIXME make sure rhs is sequentially stored - // FIXME not very good if lhs is real and rhs complex while alpha is real too - const Index rows = dest.rows(); - for (Index i=0; i call fast BLAS-like colmajor routine - * 2 - the matrix is row-major, BLAS compatible and N is large => call fast BLAS-like rowmajor routine - * 3 - all other cases are handled using a simple loop along the outer-storage direction. - * Therefore we need a lower level meta selector. - * Furthermore, if the matrix is the rhs, then the product has to be transposed. - */ -namespace internal { - -template -struct traits > - : traits, Lhs, Rhs> > -{}; - -template -struct gemv_selector; - -} // end namespace internal - -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> -{ - public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - typedef typename Lhs::Scalar LhsScalar; - typedef typename Rhs::Scalar RhsScalar; - - GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) - { -// EIGEN_STATIC_ASSERT((internal::is_same::value), -// YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - } - - enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; - typedef typename internal::conditional::type MatrixType; - - template void scaleAndAddTo(Dest& dst, Scalar alpha) const - { - eigen_assert(m_lhs.rows() == dst.rows() && m_rhs.cols() == dst.cols()); - internal::gemv_selector::HasUsableDirectAccess)>::run(*this, dst, alpha); - } -}; - -namespace internal { - -// The vector is on the left => transposition -template -struct gemv_selector -{ - template - static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) - { - Transpose destT(dest); - enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; - gemv_selector - ::run(GeneralProduct,Transpose, GemvProduct> - (prod.rhs().transpose(), prod.lhs().transpose()), destT, alpha); - } -}; - -template struct gemv_static_vector_if; - -template -struct gemv_static_vector_if -{ - EIGEN_STRONG_INLINE Scalar* data() { eigen_internal_assert(false && "should never be called"); return 0; } -}; - -template -struct gemv_static_vector_if -{ - EIGEN_STRONG_INLINE Scalar* data() { return 0; } -}; - -template -struct gemv_static_vector_if -{ - #if EIGEN_ALIGN_STATICALLY - internal::plain_array m_data; - EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } - #else - // Some architectures cannot align on the stack, - // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. - enum { - ForceAlignment = internal::packet_traits::Vectorizable, - PacketSize = internal::packet_traits::size - }; - internal::plain_array m_data; - EIGEN_STRONG_INLINE Scalar* data() { - return ForceAlignment - ? reinterpret_cast((reinterpret_cast(m_data.array) & ~(size_t(15))) + 16) - : m_data.array; - } - #endif -}; - -template<> struct gemv_selector -{ - template - static inline void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) - { - typedef typename ProductType::Index Index; - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::RealScalar RealScalar; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; - typedef Map, Aligned> MappedDest; - - const ActualLhsType actualLhs = LhsBlasTraits::extract(prod.lhs()); - const ActualRhsType actualRhs = RhsBlasTraits::extract(prod.rhs()); - - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); - - enum { - // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 - // on, the other hand it is good for the cache to pack the vector anyways... - EvalToDestAtCompileTime = Dest::InnerStrideAtCompileTime==1, - ComplexByReal = (NumTraits::IsComplex) && (!NumTraits::IsComplex), - MightCannotUseDest = (Dest::InnerStrideAtCompileTime!=1) || ComplexByReal - }; - - gemv_static_vector_if static_dest; - - // this is written like this (i.e., with a ?:) to workaround an ICE with ICC 12 - bool alphaIsCompatible = (!ComplexByReal) ? true : (imag(actualAlpha)==RealScalar(0)); - bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; - RhsScalar compatibleAlpha = get_factor::run(actualAlpha); + typedef typename ProductImpl< + Lhs, Rhs, + typename internal::promote_storage_type::ret>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(Product) - ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), - evalToDest ? dest.data() : static_dest.data()); - - if(!evalToDest) + typedef typename Lhs::Nested LhsNested; + typedef typename Rhs::Nested RhsNested; + typedef typename internal::remove_all::type LhsNestedCleaned; + typedef typename internal::remove_all::type RhsNestedCleaned; + + Product(const Lhs& lhs, const Rhs& rhs) : m_lhs(lhs), m_rhs(rhs) { - #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = dest.size(); - EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #endif - if(!alphaIsCompatible) - { - MappedDest(actualDestPtr, dest.size()).setZero(); - compatibleAlpha = RhsScalar(1); - } - else - MappedDest(actualDestPtr, dest.size()) = dest; + eigen_assert(lhs.cols() == rhs.rows() + && "invalid matrix product" + && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); } - general_matrix_vector_product - ::run( - actualLhs.rows(), actualLhs.cols(), - &actualLhs.coeffRef(0,0), actualLhs.outerStride(), - actualRhs.data(), actualRhs.innerStride(), - actualDestPtr, 1, - compatibleAlpha); + inline Index rows() const { return m_lhs.rows(); } + inline Index cols() const { return m_rhs.cols(); } - if (!evalToDest) - { - if(!alphaIsCompatible) - dest += actualAlpha * MappedDest(actualDestPtr, dest.size()); - else - dest = MappedDest(actualDestPtr, dest.size()); - } - } + const LhsNestedCleaned& lhs() const { return m_lhs; } + const RhsNestedCleaned& rhs() const { return m_rhs; } + + protected: + + const LhsNested m_lhs; + const RhsNested m_rhs; }; -template<> struct gemv_selector +template +class ProductImpl : public internal::dense_xpr_base >::type { - template - static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) - { - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::Index Index; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::_ActualRhsType _ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; + typedef Product Derived; + public: - typename add_const::type actualLhs = LhsBlasTraits::extract(prod.lhs()); - typename add_const::type actualRhs = RhsBlasTraits::extract(prod.rhs()); - - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); - - enum { - // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 - // on, the other hand it is good for the cache to pack the vector anyways... - DirectlyUseRhs = _ActualRhsType::InnerStrideAtCompileTime==1 - }; - - gemv_static_vector_if static_rhs; - - ei_declare_aligned_stack_constructed_variable(RhsScalar,actualRhsPtr,actualRhs.size(), - DirectlyUseRhs ? const_cast(actualRhs.data()) : static_rhs.data()); - - if(!DirectlyUseRhs) - { - #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = actualRhs.size(); - EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #endif - Map(actualRhsPtr, actualRhs.size()) = actualRhs; - } - - general_matrix_vector_product - ::run( - actualLhs.rows(), actualLhs.cols(), - &actualLhs.coeffRef(0,0), actualLhs.outerStride(), - actualRhsPtr, 1, - &dest.coeffRef(0,0), dest.innerStride(), - actualAlpha); - } + typedef typename internal::dense_xpr_base >::type Base; + EIGEN_DENSE_PUBLIC_INTERFACE(Derived) }; -template<> struct gemv_selector -{ - template - static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) - { - typedef typename Dest::Index Index; - // TODO makes sure dest is sequentially stored in memory, otherwise use a temp - const Index size = prod.rhs().rows(); - for(Index k=0; k struct gemv_selector -{ - template - static void run(const ProductType& prod, Dest& dest, typename ProductType::Scalar alpha) - { - typedef typename Dest::Index Index; - // TODO makes sure rhs is sequentially stored in memory, otherwise use a temp - const Index rows = prod.rows(); - for(Index i=0; i -template -inline const typename ProductReturnType::Type -MatrixBase::operator*(const MatrixBase &other) const -{ - // A note regarding the function declaration: In MSVC, this function will sometimes - // not be inlined since DenseStorage is an unwindable object for dynamic - // matrices and product types are holding a member to store the result. - // Thus it does not help tagging this function with EIGEN_STRONG_INLINE. - enum { - ProductIsValid = Derived::ColsAtCompileTime==Dynamic - || OtherDerived::RowsAtCompileTime==Dynamic - || int(Derived::ColsAtCompileTime)==int(OtherDerived::RowsAtCompileTime), - AreVectors = Derived::IsVectorAtCompileTime && OtherDerived::IsVectorAtCompileTime, - SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(Derived,OtherDerived) - }; - // note to the lost user: - // * for a dot product use: v1.dot(v2) - // * for a coeff-wise product use: v1.cwiseProduct(v2) - EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes), - INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS) - EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors), - INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) - EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) -#ifdef EIGEN_DEBUG_PRODUCT - internal::product_type::debug(); -#endif - return typename ProductReturnType::Type(derived(), other.derived()); -} - -/** \returns an expression of the matrix product of \c *this and \a other without implicit evaluation. - * - * The returned product will behave like any other expressions: the coefficients of the product will be - * computed once at a time as requested. This might be useful in some extremely rare cases when only - * a small and no coherent fraction of the result's coefficients have to be computed. - * - * \warning This version of the matrix product can be much much slower. So use it only if you know - * what you are doing and that you measured a true speed improvement. - * - * \sa operator*(const MatrixBase&) - */ -template -template -const typename LazyProductReturnType::Type -MatrixBase::lazyProduct(const MatrixBase &other) const -{ - enum { - ProductIsValid = Derived::ColsAtCompileTime==Dynamic - || OtherDerived::RowsAtCompileTime==Dynamic - || int(Derived::ColsAtCompileTime)==int(OtherDerived::RowsAtCompileTime), - AreVectors = Derived::IsVectorAtCompileTime && OtherDerived::IsVectorAtCompileTime, - SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(Derived,OtherDerived) - }; - // note to the lost user: - // * for a dot product use: v1.dot(v2) - // * for a coeff-wise product use: v1.cwiseProduct(v2) - EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes), - INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS) - EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors), - INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) - EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) - - return typename LazyProductReturnType::Type(derived(), other.derived()); -} - #endif // EIGEN_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h index 233ed6467..6cf02a649 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h @@ -25,6 +25,8 @@ #ifndef EIGEN_PRODUCTBASE_H #define EIGEN_PRODUCTBASE_H +namespace Eigen { + /** \class ProductBase * \ingroup Core_Module * @@ -115,10 +117,10 @@ class ProductBase : public MatrixBase inline void evalTo(Dest& dst) const { dst.setZero(); scaleAndAddTo(dst,Scalar(1)); } template - inline void addTo(Dest& dst) const { scaleAndAddTo(dst,1); } + inline void addTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(1)); } template - inline void subTo(Dest& dst) const { scaleAndAddTo(dst,-1); } + inline void subTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(-1)); } template inline void scaleAndAddTo(Dest& dst,Scalar alpha) const { derived().scaleAndAddTo(dst,alpha); } @@ -152,7 +154,8 @@ class ProductBase : public MatrixBase #else EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeff(row,col); + Matrix result = *this; + return result.coeff(row,col); #endif } @@ -160,7 +163,8 @@ class ProductBase : public MatrixBase { EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeff(i); + Matrix result = *this; + return result.coeff(i); } const Scalar& coeffRef(Index row, Index col) const @@ -179,8 +183,8 @@ class ProductBase : public MatrixBase protected: - const LhsNested m_lhs; - const RhsNested m_rhs; + LhsNested m_lhs; + RhsNested m_rhs; mutable PlainObject m_result; }; @@ -284,5 +288,6 @@ Derived& MatrixBase::lazyAssign(const ProductBase struct scalar_random_op { @@ -160,4 +162,6 @@ PlainObjectBase::setRandom(Index rows, Index cols) return setRandom(); } +} // end namespace Eigen + #endif // EIGEN_RANDOM_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h index f9f5a95d5..d66ff00c1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h @@ -26,6 +26,8 @@ #ifndef EIGEN_REDUX_H #define EIGEN_REDUX_H +namespace Eigen { + namespace internal { // TODO @@ -95,7 +97,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; - EIGEN_STRONG_INLINE static Scalar run(const Derived &mat, const Func& func) + static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { return func(redux_novec_unroller::run(mat,func), redux_novec_unroller::run(mat,func)); @@ -112,7 +114,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; - EIGEN_STRONG_INLINE static Scalar run(const Derived &mat, const Func&) + static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func&) { return mat.coeffByOuterInner(outer, inner); } @@ -125,7 +127,7 @@ template struct redux_novec_unroller { typedef typename Derived::Scalar Scalar; - EIGEN_STRONG_INLINE static Scalar run(const Derived&, const Func&) { return Scalar(); } + static EIGEN_STRONG_INLINE Scalar run(const Derived&, const Func&) { return Scalar(); } }; /*** vectorization ***/ @@ -141,7 +143,7 @@ struct redux_vec_unroller typedef typename Derived::Scalar Scalar; typedef typename packet_traits::type PacketScalar; - EIGEN_STRONG_INLINE static PacketScalar run(const Derived &mat, const Func& func) + static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func& func) { return func.packetOp( redux_vec_unroller::run(mat,func), @@ -162,7 +164,7 @@ struct redux_vec_unroller typedef typename Derived::Scalar Scalar; typedef typename packet_traits::type PacketScalar; - EIGEN_STRONG_INLINE static PacketScalar run(const Derived &mat, const Func&) + static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func&) { return mat.template packetByOuterInner(outer, inner); } @@ -214,20 +216,33 @@ struct redux_impl const Index size = mat.size(); eigen_assert(size && "you are using an empty matrix"); const Index packetSize = packet_traits::size; - const Index alignedStart = first_aligned(mat); + const Index alignedStart = internal::first_aligned(mat); enum { alignment = bool(Derived::Flags & DirectAccessBit) || bool(Derived::Flags & AlignedBit) ? Aligned : Unaligned }; - const Index alignedSize = ((size-alignedStart)/packetSize)*packetSize; - const Index alignedEnd = alignedStart + alignedSize; + const Index alignedSize2 = ((size-alignedStart)/(2*packetSize))*(2*packetSize); + const Index alignedSize = ((size-alignedStart)/(packetSize))*(packetSize); + const Index alignedEnd2 = alignedStart + alignedSize2; + const Index alignedEnd = alignedStart + alignedSize; Scalar res; if(alignedSize) { - PacketScalar packet_res = mat.template packet(alignedStart); - for(Index index = alignedStart + packetSize; index < alignedEnd; index += packetSize) - packet_res = func.packetOp(packet_res, mat.template packet(index)); - res = func.predux(packet_res); + PacketScalar packet_res0 = mat.template packet(alignedStart); + if(alignedSize>packetSize) // we have at least two packets to partly unroll the loop + { + PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); + for(Index index = alignedStart + 2*packetSize; index < alignedEnd2; index += 2*packetSize) + { + packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); + packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); + } + + packet_res0 = func.packetOp(packet_res0,packet_res1); + if(alignedEnd>alignedEnd2) + packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); + } + res = func.predux(packet_res0); for(Index index = 0; index < alignedStart; ++index) res = func(res,mat.coeff(index)); @@ -296,7 +311,7 @@ struct redux_impl Size = Derived::SizeAtCompileTime, VectorizedSize = (Size / PacketSize) * PacketSize }; - EIGEN_STRONG_INLINE static Scalar run(const Derived& mat, const Func& func) + static EIGEN_STRONG_INLINE Scalar run(const Derived& mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); Scalar res = func.predux(redux_vec_unroller::run(mat,func)); @@ -401,4 +416,6 @@ MatrixBase::trace() const return derived().diagonal().sum(); } +} // end namespace Eigen + #endif // EIGEN_REDUX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h index d2f9712db..79e3578df 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h @@ -25,6 +25,8 @@ #ifndef EIGEN_REPLICATE_H #define EIGEN_REPLICATE_H +namespace Eigen { + /** * \class Replicate * \ingroup Core_Module @@ -48,7 +50,10 @@ struct traits > typedef typename MatrixType::Scalar Scalar; typedef typename traits::StorageKind StorageKind; typedef typename traits::XprKind XprKind; - typedef typename nested::type MatrixTypeNested; + enum { + Factor = (RowFactor==Dynamic || ColFactor==Dynamic) ? Dynamic : RowFactor*ColFactor + }; + typedef typename nested::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; enum { RowsAtCompileTime = RowFactor==Dynamic || int(MatrixType::RowsAtCompileTime)==Dynamic @@ -72,6 +77,8 @@ struct traits > template class Replicate : public internal::dense_xpr_base< Replicate >::type { + typedef typename internal::traits::MatrixTypeNested MatrixTypeNested; + typedef typename internal::traits::_MatrixTypeNested _MatrixTypeNested; public: typedef typename internal::dense_xpr_base::type Base; @@ -87,7 +94,7 @@ template class Replicate } template - inline Replicate(const OriginalMatrixType& matrix, int rowFactor, int colFactor) + inline Replicate(const OriginalMatrixType& matrix, Index rowFactor, Index colFactor) : m_matrix(matrix), m_rowFactor(rowFactor), m_colFactor(colFactor) { EIGEN_STATIC_ASSERT((internal::is_same::type,OriginalMatrixType>::value), @@ -122,9 +129,13 @@ template class Replicate return m_matrix.template packet(actual_row, actual_col); } + const _MatrixTypeNested& nestedExpression() const + { + return m_matrix; + } protected: - const typename MatrixType::Nested m_matrix; + MatrixTypeNested m_matrix; const internal::variable_if_dynamic m_rowFactor; const internal::variable_if_dynamic m_colFactor; }; @@ -176,4 +187,6 @@ VectorwiseOp::replicate(Index factor) const (_expression(),Direction==Vertical?factor:1,Direction==Horizontal?factor:1); } +} // end namespace Eigen + #endif // EIGEN_REPLICATE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h index 24c5a4e21..24b6a3f6a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h @@ -26,6 +26,8 @@ #ifndef EIGEN_RETURNBYVALUE_H #define EIGEN_RETURNBYVALUE_H +namespace Eigen { + /** \class ReturnByValue * \ingroup Core_Module * @@ -96,4 +98,6 @@ Derived& DenseBase::operator=(const ReturnByValue& other) return derived(); } +} // end namespace Eigen + #endif // EIGEN_RETURNBYVALUE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h index 600744ae7..9e4e8a2bc 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h @@ -27,6 +27,8 @@ #ifndef EIGEN_REVERSE_H #define EIGEN_REVERSE_H +namespace Eigen { + /** \class Reverse * \ingroup Core_Module * @@ -183,8 +185,14 @@ template class Reverse m_matrix.const_cast_derived().template writePacket(m_matrix.size() - index - PacketSize, internal::preverse(x)); } + const typename internal::remove_all::type& + nestedExpression() const + { + return m_matrix; + } + protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; }; /** \returns an expression of the reverse of *this. @@ -226,5 +234,6 @@ inline void DenseBase::reverseInPlace() derived() = derived().reverse().eval(); } +} // end namespace Eigen #endif // EIGEN_REVERSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h index d0cd66a26..92508a168 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELECT_H #define EIGEN_SELECT_H +namespace Eigen { + /** \class Select * \ingroup Core_Module * @@ -101,10 +103,25 @@ class Select : internal::no_assignment_operator, return m_else.coeff(i); } + const ConditionMatrixType& conditionMatrix() const + { + return m_condition; + } + + const ThenMatrixType& thenMatrix() const + { + return m_then; + } + + const ElseMatrixType& elseMatrix() const + { + return m_else; + } + protected: - const typename ConditionMatrixType::Nested m_condition; - const typename ThenMatrixType::Nested m_then; - const typename ElseMatrixType::Nested m_else; + typename ConditionMatrixType::Nested m_condition; + typename ThenMatrixType::Nested m_then; + typename ElseMatrixType::Nested m_else; }; @@ -155,4 +172,6 @@ DenseBase::select(typename ElseDerived::Scalar thenScalar, derived(), ElseDerived::Constant(rows(),cols(),thenScalar), elseMatrix.derived()); } +} // end namespace Eigen + #endif // EIGEN_SELECT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfAdjointView.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfAdjointView.h index 4bb68755e..086f05c49 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfAdjointView.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfAdjointView.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELFADJOINTMATRIX_H #define EIGEN_SELFADJOINTMATRIX_H +namespace Eigen { + /** \class SelfAdjointView * \ingroup Core_Module * @@ -82,7 +84,7 @@ template class SelfAdjointView }; typedef typename MatrixType::PlainObject PlainObject; - inline SelfAdjointView(const MatrixType& matrix) : m_matrix(matrix) + inline SelfAdjointView(MatrixType& matrix) : m_matrix(matrix) {} inline Index rows() const { return m_matrix.rows(); } @@ -199,7 +201,7 @@ template class SelfAdjointView #endif protected: - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; }; @@ -222,7 +224,7 @@ struct triangular_assignment_selector::run(dst, src); @@ -236,7 +238,7 @@ struct triangular_assignment_selector struct triangular_assignment_selector { - inline static void run(Derived1 &, const Derived2 &) {} + static inline void run(Derived1 &, const Derived2 &) {} }; template @@ -247,7 +249,7 @@ struct triangular_assignment_selector::run(dst, src); @@ -261,14 +263,14 @@ struct triangular_assignment_selector struct triangular_assignment_selector { - inline static void run(Derived1 &, const Derived2 &) {} + static inline void run(Derived1 &, const Derived2 &) {} }; template struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -285,7 +287,7 @@ struct triangular_assignment_selector struct triangular_assignment_selector { - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { typedef typename Derived1::Index Index; for(Index i = 0; i < dst.rows(); ++i) @@ -322,4 +324,6 @@ MatrixBase::selfadjointView() return derived(); } +} // end namespace Eigen + #endif // EIGEN_SELFADJOINTMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h index 4e9ca8874..99389d7e2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELFCWISEBINARYOP_H #define EIGEN_SELFCWISEBINARYOP_H +namespace Eigen { + /** \class SelfCwiseBinaryOp * \ingroup Core_Module * @@ -163,6 +165,16 @@ template class SelfCwiseBinaryOp return Base::operator=(rhs); } + Lhs& expression() const + { + return m_matrix; + } + + const BinaryOp& functor() const + { + return m_functor; + } + protected: Lhs& m_matrix; const BinaryOp& m_functor; @@ -192,4 +204,6 @@ inline Derived& DenseBase::operator/=(const Scalar& other) return derived(); } +} // end namespace Eigen + #endif // EIGEN_SELFCWISEBINARYOP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/SolveTriangular.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/SolveTriangular.h index a23014a34..ef09226a4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/SolveTriangular.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/SolveTriangular.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SOLVETRIANGULAR_H #define EIGEN_SOLVETRIANGULAR_H +namespace Eigen { + namespace internal { // Forward declarations: @@ -98,12 +100,22 @@ struct triangular_solver_selector typedef typename Rhs::Index Index; typedef blas_traits LhsProductTraits; typedef typename LhsProductTraits::DirectLinearAccessType ActualLhsType; + static void run(const Lhs& lhs, Rhs& rhs) { - const ActualLhsType actualLhs = LhsProductTraits::extract(lhs); + typename internal::add_const_on_value_type::type actualLhs = LhsProductTraits::extract(lhs); + + const Index size = lhs.rows(); + const Index othersize = Side==OnTheLeft? rhs.cols() : rhs.rows(); + + typedef internal::gemm_blocking_space<(Rhs::Flags&RowMajorBit) ? RowMajor : ColMajor,Scalar,Scalar, + Rhs::MaxRowsAtCompileTime, Rhs::MaxColsAtCompileTime, Lhs::MaxRowsAtCompileTime,4> BlockingType; + + BlockingType blocking(rhs.rows(), rhs.cols(), size); + triangular_solve_matrix - ::run(lhs.rows(), Side==OnTheLeft? rhs.cols() : rhs.rows(), &actualLhs.coeffRef(0,0), actualLhs.outerStride(), &rhs.coeffRef(0,0), rhs.outerStride()); + ::run(size, othersize, &actualLhs.coeffRef(0,0), actualLhs.outerStride(), &rhs.coeffRef(0,0), rhs.outerStride(), blocking); } }; @@ -177,10 +189,8 @@ template void TriangularView::solveInPlace(const MatrixBase& _other) const { OtherDerived& other = _other.const_cast_derived(); - eigen_assert(cols() == rows()); - eigen_assert( (Side==OnTheLeft && cols() == other.rows()) || (Side==OnTheRight && cols() == other.cols()) ); - eigen_assert(!(Mode & ZeroDiag)); - eigen_assert((Mode & (Upper|Lower)) != 0); + eigen_assert( cols() == rows() && ((Side==OnTheLeft && cols() == other.rows()) || (Side==OnTheRight && cols() == other.cols())) ); + eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower))); enum { copy = internal::traits::Flags & RowMajorBit && OtherDerived::IsVectorAtCompileTime }; typedef typename internal::conditional struct triangular_solv protected: const TriangularType& m_triangularMatrix; - const typename Rhs::Nested m_rhs; + typename Rhs::Nested m_rhs; }; } // namespace internal +} // end namespace Eigen + #endif // EIGEN_SOLVETRIANGULAR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/StableNorm.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/StableNorm.h index f667272e4..16514c86a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/StableNorm.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/StableNorm.h @@ -25,6 +25,8 @@ #ifndef EIGEN_STABLENORM_H #define EIGEN_STABLENORM_H +namespace Eigen { + namespace internal { template inline void stable_norm_kernel(const ExpressionType& bl, Scalar& ssq, Scalar& scale, Scalar& invScale) @@ -58,9 +60,9 @@ MatrixBase::stableNorm() const { using std::min; const Index blockSize = 4096; - RealScalar scale = 0; - RealScalar invScale = 1; - RealScalar ssq = 0; // sum of square + RealScalar scale(0); + RealScalar invScale(1); + RealScalar ssq(0); // sum of square enum { Alignment = (int(Flags)&DirectAccessBit) || (int(Flags)&AlignedBit) ? 1 : 0 }; @@ -187,4 +189,6 @@ MatrixBase::hypotNorm() const return this->cwiseAbs().redux(internal::scalar_hypot_op()); } +} // end namespace Eigen + #endif // EIGEN_STABLENORM_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Stride.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Stride.h index 0430f1116..73c54e6bf 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Stride.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Stride.h @@ -25,6 +25,8 @@ #ifndef EIGEN_STRIDE_H #define EIGEN_STRIDE_H +namespace Eigen { + /** \class Stride * \ingroup Core_Module * @@ -116,4 +118,6 @@ class OuterStride : public Stride OuterStride(Index v) : Base(v,0) {} }; +} // end namespace Eigen + #endif // EIGEN_STRIDE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Swap.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Swap.h index 5fb032866..deb1d2831 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Swap.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Swap.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SWAP_H #define EIGEN_SWAP_H +namespace Eigen { + /** \class SwapWrapper * \ingroup Core_Module * @@ -52,6 +54,15 @@ template class SwapWrapper inline Index cols() const { return m_expression.cols(); } inline Index outerStride() const { return m_expression.outerStride(); } inline Index innerStride() const { return m_expression.innerStride(); } + + typedef typename internal::conditional< + internal::is_lvalue::value, + Scalar, + const Scalar + >::type ScalarWithConstIfNotLvalue; + + inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } + inline const Scalar* data() const { return m_expression.data(); } inline Scalar& coeffRef(Index row, Index col) { @@ -119,8 +130,12 @@ template class SwapWrapper _other.template writePacket(index, tmp); } + ExpressionType& expression() const { return m_expression; } + protected: ExpressionType& m_expression; }; +} // end namespace Eigen + #endif // EIGEN_SWAP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpose.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpose.h index 3f7c7df6e..c62f74764 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpose.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpose.h @@ -26,6 +26,8 @@ #ifndef EIGEN_TRANSPOSE_H #define EIGEN_TRANSPOSE_H +namespace Eigen { + /** \class Transpose * \ingroup Core_Module * @@ -91,7 +93,7 @@ template class Transpose nestedExpression() { return m_matrix.const_cast_derived(); } protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; }; namespace internal { @@ -152,12 +154,12 @@ template class TransposeImpl return derived().nestedExpression().coeffRef(index); } - inline const CoeffReturnType coeff(Index row, Index col) const + inline CoeffReturnType coeff(Index row, Index col) const { return derived().nestedExpression().coeff(col, row); } - inline const CoeffReturnType coeff(Index index) const + inline CoeffReturnType coeff(Index index) const { return derived().nestedExpression().coeff(index); } @@ -422,4 +424,6 @@ void DenseBase::checkTransposeAliasing(const OtherDerived& other) const } #endif +} // end namespace Eigen + #endif // EIGEN_TRANSPOSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpositions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpositions.h index 88fdfb222..fa37822f8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpositions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Transpositions.h @@ -25,6 +25,8 @@ #ifndef EIGEN_TRANSPOSITIONS_H #define EIGEN_TRANSPOSITIONS_H +namespace Eigen { + /** \class Transpositions * \ingroup Core_Module * @@ -404,7 +406,7 @@ struct transposition_matrix_product_retval protected: const TranspositionType& m_transpositions; - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; }; } // end namespace internal @@ -444,4 +446,6 @@ class Transpose > const TranspositionType& m_transpositions; }; +} // end namespace Eigen + #endif // EIGEN_TRANSPOSITIONS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h index 033e81036..5e97e4052 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h @@ -26,6 +26,8 @@ #ifndef EIGEN_TRIANGULARMATRIX_H #define EIGEN_TRIANGULARMATRIX_H +namespace Eigen { + namespace internal { template struct triangular_solve_retval; @@ -273,11 +275,8 @@ template class TriangularView inline const TriangularView conjugate() const { return m_matrix.conjugate(); } - /** \sa MatrixBase::adjoint() */ - inline TriangularView adjoint() - { return m_matrix.adjoint(); } /** \sa MatrixBase::adjoint() const */ - inline const TriangularView adjoint() const + inline const TriangularView adjoint() const { return m_matrix.adjoint(); } /** \sa MatrixBase::transpose() */ @@ -288,11 +287,13 @@ template class TriangularView } /** \sa MatrixBase::transpose() const */ inline const TriangularView,TransposeMode> transpose() const - { return m_matrix.transpose(); } + { + return m_matrix.transpose(); + } /** Efficient triangular matrix times vector/matrix product */ template - TriangularProduct + TriangularProduct operator*(const MatrixBase& rhs) const { return TriangularProduct @@ -375,7 +376,8 @@ template class TriangularView template void swap(MatrixBase const & other) { - TriangularView,Mode>(const_cast(m_matrix)).lazyAssign(other.derived()); + SwapWrapper swaper(const_cast(m_matrix)); + TriangularView,Mode>(swaper).lazyAssign(other.derived()); } Scalar determinant() const @@ -433,7 +435,7 @@ template class TriangularView template EIGEN_STRONG_INLINE TriangularView& assignProduct(const ProductBase& prod, const Scalar& alpha); - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; }; /*************************************************************************** @@ -452,7 +454,7 @@ struct triangular_assignment_selector typedef typename Derived1::Scalar Scalar; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { triangular_assignment_selector::run(dst, src); @@ -480,7 +482,7 @@ struct triangular_assignment_selector template struct triangular_assignment_selector { - inline static void run(Derived1 &, const Derived2 &) {} + static inline void run(Derived1 &, const Derived2 &) {} }; template @@ -488,7 +490,7 @@ struct triangular_assignment_selector struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -524,7 +526,7 @@ template struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -542,7 +544,7 @@ template struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -560,7 +562,7 @@ template struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -580,7 +582,7 @@ template struct triangular_assignment_selector { typedef typename Derived1::Index Index; - inline static void run(Derived1 &dst, const Derived2 &src) + static inline void run(Derived1 &dst, const Derived2 &src) { for(Index j = 0; j < dst.cols(); ++j) { @@ -835,4 +837,6 @@ bool MatrixBase::isLowerTriangular(RealScalar prec) const return true; } +} // end namespace Eigen + #endif // EIGEN_TRIANGULARMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorBlock.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorBlock.h index 858e4c786..66c9fd21a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorBlock.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorBlock.h @@ -26,6 +26,8 @@ #ifndef EIGEN_VECTORBLOCK_H #define EIGEN_VECTORBLOCK_H +namespace Eigen { + /** \class VectorBlock * \ingroup Core_Module * @@ -292,5 +294,6 @@ DenseBase::tail() const return typename ConstFixedSegmentReturnType::Type(derived(), size() - Size); } +} // end namespace Eigen #endif // EIGEN_VECTORBLOCK_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorwiseOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorwiseOp.h index 20f688157..7b5be7cd5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorwiseOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/VectorwiseOp.h @@ -26,6 +26,8 @@ #ifndef EIGEN_PARTIAL_REDUX_H #define EIGEN_PARTIAL_REDUX_H +namespace Eigen { + /** \class PartialReduxExpr * \ingroup Core_Module * @@ -110,7 +112,7 @@ class PartialReduxExpr : internal::no_assignment_operator, } protected: - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; const MemberOp m_functor; }; @@ -237,7 +239,10 @@ template class VectorwiseOp typename ExtendedType::Type extendedTo(const DenseBase& other) const { - EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived); + EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(Direction==Vertical, OtherDerived::MaxColsAtCompileTime==1), + YOU_PASSED_A_ROW_VECTOR_BUT_A_COLUMN_VECTOR_WAS_EXPECTED) + EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(Direction==Horizontal, OtherDerived::MaxRowsAtCompileTime==1), + YOU_PASSED_A_COLUMN_VECTOR_BUT_A_ROW_VECTOR_WAS_EXPECTED) return typename ExtendedType::Type (other.derived(), Direction==Vertical ? 1 : m_matrix.rows(), @@ -418,10 +423,9 @@ template class VectorwiseOp ExpressionType& operator=(const DenseBase& other) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) //eigen_assert((m_matrix.isNull()) == (other.isNull())); FIXME - for(Index j=0; j(m_matrix); + return const_cast(m_matrix = extendedTo(other.derived())); } /** Adds the vector \a other to each subvector of \c *this */ @@ -429,9 +433,8 @@ template class VectorwiseOp ExpressionType& operator+=(const DenseBase& other) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) - for(Index j=0; j(m_matrix); + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) + return const_cast(m_matrix += extendedTo(other.derived())); } /** Substracts the vector \a other to each subvector of \c *this */ @@ -439,8 +442,29 @@ template class VectorwiseOp ExpressionType& operator-=(const DenseBase& other) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) - for(Index j=0; j(m_matrix -= extendedTo(other.derived())); + } + + /** Multiples each subvector of \c *this by the vector \a other */ + template + ExpressionType& operator*=(const DenseBase& other) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) + m_matrix *= extendedTo(other.derived()); + return const_cast(m_matrix); + } + + /** Divides each subvector of \c *this by the vector \a other */ + template + ExpressionType& operator/=(const DenseBase& other) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) + m_matrix /= extendedTo(other.derived()); return const_cast(m_matrix); } @@ -451,7 +475,8 @@ template class VectorwiseOp const typename ExtendedType::Type> operator+(const DenseBase& other) const { - EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived); + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) return m_matrix + extendedTo(other.derived()); } @@ -462,10 +487,39 @@ template class VectorwiseOp const typename ExtendedType::Type> operator-(const DenseBase& other) const { - EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived); + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) return m_matrix - extendedTo(other.derived()); } + /** Returns the expression where each subvector is the product of the vector \a other + * by the corresponding subvector of \c *this */ + template EIGEN_STRONG_INLINE + CwiseBinaryOp, + const ExpressionTypeNestedCleaned, + const typename ExtendedType::Type> + operator*(const DenseBase& other) const + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) + return m_matrix * extendedTo(other.derived()); + } + + /** Returns the expression where each subvector is the quotient of the corresponding + * subvector of \c *this by the vector \a other */ + template + CwiseBinaryOp, + const ExpressionTypeNestedCleaned, + const typename ExtendedType::Type> + operator/(const DenseBase& other) const + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) + EIGEN_STATIC_ASSERT_ARRAYXPR(ExpressionType) + EIGEN_STATIC_ASSERT_SAME_XPR_KIND(ExpressionType, OtherDerived) + return m_matrix / extendedTo(other.derived()); + } + /////////// Geometry module /////////// #if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS @@ -509,7 +563,7 @@ template class VectorwiseOp * Example: \include MatrixBase_colwise.cpp * Output: \verbinclude MatrixBase_colwise.out * - * \sa rowwise(), class VectorwiseOp + * \sa rowwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting */ template inline const typename DenseBase::ConstColwiseReturnType @@ -520,7 +574,7 @@ DenseBase::colwise() const /** \returns a writable VectorwiseOp wrapper of *this providing additional partial reduction operations * - * \sa rowwise(), class VectorwiseOp + * \sa rowwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting */ template inline typename DenseBase::ColwiseReturnType @@ -534,7 +588,7 @@ DenseBase::colwise() * Example: \include MatrixBase_rowwise.cpp * Output: \verbinclude MatrixBase_rowwise.out * - * \sa colwise(), class VectorwiseOp + * \sa colwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting */ template inline const typename DenseBase::ConstRowwiseReturnType @@ -545,7 +599,7 @@ DenseBase::rowwise() const /** \returns a writable VectorwiseOp wrapper of *this providing additional partial reduction operations * - * \sa colwise(), class VectorwiseOp + * \sa colwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting */ template inline typename DenseBase::RowwiseReturnType @@ -554,4 +608,6 @@ DenseBase::rowwise() return derived(); } +} // end namespace Eigen + #endif // EIGEN_PARTIAL_REDUX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Visitor.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Visitor.h index 378ebcba1..fd04fd978 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Visitor.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Visitor.h @@ -25,6 +25,8 @@ #ifndef EIGEN_VISITOR_H #define EIGEN_VISITOR_H +namespace Eigen { + namespace internal { template @@ -35,7 +37,7 @@ struct visitor_impl row = (UnrollCount-1) % Derived::RowsAtCompileTime }; - inline static void run(const Derived &mat, Visitor& visitor) + static inline void run(const Derived &mat, Visitor& visitor) { visitor_impl::run(mat, visitor); visitor(mat.coeff(row, col), row, col); @@ -45,7 +47,7 @@ struct visitor_impl template struct visitor_impl { - inline static void run(const Derived &mat, Visitor& visitor) + static inline void run(const Derived &mat, Visitor& visitor) { return visitor.init(mat.coeff(0, 0), 0, 0); } @@ -55,7 +57,7 @@ template struct visitor_impl { typedef typename Derived::Index Index; - inline static void run(const Derived& mat, Visitor& visitor) + static inline void run(const Derived& mat, Visitor& visitor) { visitor.init(mat.coeff(0,0), 0, 0); for(Index i = 1; i < mat.rows(); ++i) @@ -245,4 +247,6 @@ DenseBase::maxCoeff(IndexType* index) const return maxVisitor.res; } +} // end namespace Eigen + #endif // EIGEN_VISITOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/Complex.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/Complex.h index f8adf1b63..b2d866b71 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/Complex.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/Complex.h @@ -25,6 +25,8 @@ #ifndef EIGEN_COMPLEX_ALTIVEC_H #define EIGEN_COMPLEX_ALTIVEC_H +namespace Eigen { + namespace internal { static Packet4ui p4ui_CONJ_XOR = vec_mergeh((Packet4ui)p4i_ZERO, (Packet4ui)p4f_ZERO_);//{ 0x00000000, 0x80000000, 0x00000000, 0x80000000 }; @@ -168,7 +170,7 @@ template<> EIGEN_STRONG_INLINE std::complex predux_mul(const P template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet2cf& first, const Packet2cf& second) + static EIGEN_STRONG_INLINE void run(Packet2cf& first, const Packet2cf& second) { if (Offset==1) { @@ -225,4 +227,6 @@ template<> EIGEN_STRONG_INLINE Packet2cf pcplxflip(const Packet2cf& x } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_COMPLEX_ALTIVEC_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/PacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/PacketMath.h index dc34ebbd6..5b62b4c31 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/PacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/PacketMath.h @@ -25,6 +25,8 @@ #ifndef EIGEN_PACKET_MATH_ALTIVEC_H #define EIGEN_PACKET_MATH_ALTIVEC_H +namespace Eigen { + namespace internal { #ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD @@ -487,7 +489,7 @@ template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4f& first, const Packet4f& second) + static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) { if (Offset!=0) first = vec_sld(first, second, Offset*4); @@ -497,7 +499,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4i& first, const Packet4i& second) + static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) { if (Offset!=0) first = vec_sld(first, second, Offset*4); @@ -506,4 +508,6 @@ struct palign_impl } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_PACKET_MATH_ALTIVEC_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/Complex.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/Complex.h index 212887184..72abb6f4a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/Complex.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/Complex.h @@ -25,6 +25,8 @@ #ifndef EIGEN_COMPLEX_NEON_H #define EIGEN_COMPLEX_NEON_H +namespace Eigen { + namespace internal { static uint32x4_t p4ui_CONJ_XOR = EIGEN_INIT_NEON_PACKET4(0x00000000, 0x80000000, 0x00000000, 0x80000000); @@ -267,4 +269,6 @@ template<> EIGEN_STRONG_INLINE Packet2cf pdiv(const Packet2cf& a, con } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_COMPLEX_NEON_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h index 6c7cd1590..1eb082a5b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h @@ -27,6 +27,8 @@ #ifndef EIGEN_PACKET_MATH_NEON_H #define EIGEN_PACKET_MATH_NEON_H +namespace Eigen { + namespace internal { #ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD @@ -158,7 +160,8 @@ template<> EIGEN_STRONG_INLINE Packet4i pdiv(const Packet4i& /*a*/, co } // for some weird raisons, it has to be overloaded for packet of integers -template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return padd(pmul(a,b), c); } +template<> EIGEN_STRONG_INLINE Packet4f pmadd(const Packet4f& a, const Packet4f& b, const Packet4f& c) { return vmlaq_f32(c,a,b); } +template<> EIGEN_STRONG_INLINE Packet4i pmadd(const Packet4i& a, const Packet4i& b, const Packet4i& c) { return vmlaq_s32(c,a,b); } template<> EIGEN_STRONG_INLINE Packet4f pmin(const Packet4f& a, const Packet4f& b) { return vminq_f32(a,b); } template<> EIGEN_STRONG_INLINE Packet4i pmin(const Packet4i& a, const Packet4i& b) { return vminq_s32(a,b); } @@ -431,4 +434,6 @@ PALIGN_NEON(3,Packet4i,vextq_s32) } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_PACKET_MATH_NEON_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/Complex.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/Complex.h index c352bb3e6..1615886ac 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/Complex.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/Complex.h @@ -25,6 +25,8 @@ #ifndef EIGEN_COMPLEX_SSE_H #define EIGEN_COMPLEX_SSE_H +namespace Eigen { + namespace internal { //---------- float ---------- @@ -102,7 +104,7 @@ template<> EIGEN_STRONG_INLINE Packet2cf pset1(const std::complex(&from)); #else res.v = _mm_loadl_pi(res.v, (const __m64*)&from); #endif @@ -151,7 +153,7 @@ template<> EIGEN_STRONG_INLINE std::complex predux_mul(const P template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet2cf& first, const Packet2cf& second) + static EIGEN_STRONG_INLINE void run(Packet2cf& first, const Packet2cf& second) { if (Offset==1) { @@ -350,7 +352,7 @@ template<> EIGEN_STRONG_INLINE std::complex predux_mul(const template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) + static EIGEN_STRONG_INLINE void run(Packet1cd& /*first*/, const Packet1cd& /*second*/) { // FIXME is it sure we never have to align a Packet1cd? // Even though a std::complex has 16 bytes, it is not necessarily aligned on a 16 bytes boundary... @@ -444,4 +446,6 @@ EIGEN_STRONG_INLINE Packet1cd pcplxflip/**/(const Packet1cd& x) } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_COMPLEX_SSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h index 9d56d8218..de2f06d5f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h @@ -30,6 +30,8 @@ #ifndef EIGEN_MATH_FUNCTIONS_SSE_H #define EIGEN_MATH_FUNCTIONS_SSE_H +namespace Eigen { + namespace internal { template<> EIGEN_DEFINE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS EIGEN_UNUSED @@ -121,7 +123,7 @@ Packet4f pexp(const Packet4f& _x) _EIGEN_DECLARE_CONST_Packet4i(0x7f, 0x7f); - _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647949f); + _EIGEN_DECLARE_CONST_Packet4f(exp_hi, 88.3762626647950f); _EIGEN_DECLARE_CONST_Packet4f(exp_lo, -88.3762626647949f); _EIGEN_DECLARE_CONST_Packet4f(cephes_LOG2EF, 1.44269504088896341f); @@ -168,7 +170,7 @@ Packet4f pexp(const Packet4f& _x) y = pmadd(y, z, x); y = padd(y, p4f_1); - /* build 2^n */ + // build 2^n emm0 = _mm_cvttps_epi32(fx); emm0 = _mm_add_epi32(emm0, p4i_0x7f); emm0 = _mm_slli_epi32(emm0, 23); @@ -392,4 +394,6 @@ Packet4f psqrt(const Packet4f& _x) } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_MATH_FUNCTIONS_SSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/PacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/PacketMath.h index 908e27368..8faeeefc9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/PacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/PacketMath.h @@ -25,6 +25,8 @@ #ifndef EIGEN_PACKET_MATH_SSE_H #define EIGEN_PACKET_MATH_SSE_H +namespace Eigen { + namespace internal { #ifndef EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD @@ -110,9 +112,18 @@ template<> struct unpacket_traits { typedef float type; enum {size=4} template<> struct unpacket_traits { typedef double type; enum {size=2}; }; template<> struct unpacket_traits { typedef int type; enum {size=4}; }; +#if defined(_MSC_VER) && (_MSC_VER==1500) +// Workaround MSVC 9 internal compiler error. +// TODO: It has been detected with win64 builds (amd64), so let's check whether it also happens in 32bits+SSE mode +// TODO: let's check whether there does not exist a better fix, like adding a pset0() function. (it crashed on pset1(0)). +template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { return _mm_set_ps(from,from,from,from); } +template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return _mm_set_pd(from,from); } +template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) { return _mm_set_epi32(from,from,from,from); } +#else template<> EIGEN_STRONG_INLINE Packet4f pset1(const float& from) { return _mm_set1_ps(from); } template<> EIGEN_STRONG_INLINE Packet2d pset1(const double& from) { return _mm_set1_pd(from); } template<> EIGEN_STRONG_INLINE Packet4i pset1(const int& from) { return _mm_set1_epi32(from); } +#endif template<> EIGEN_STRONG_INLINE Packet4f plset(const float& a) { return _mm_add_ps(pset1(a), _mm_set_ps(3,2,1,0)); } template<> EIGEN_STRONG_INLINE Packet2d plset(const double& a) { return _mm_add_pd(pset1(a),_mm_set_pd(1,0)); } @@ -282,7 +293,7 @@ template<> EIGEN_STRONG_INLINE Packet4i ploadu(const int* from) template<> EIGEN_STRONG_INLINE Packet4f ploaddup(const float* from) { - return vec4f_swizzle1(_mm_castpd_ps(_mm_load_sd((const double*)from)), 0, 0, 1, 1); + return vec4f_swizzle1(_mm_castpd_ps(_mm_load_sd(reinterpret_cast(from))), 0, 0, 1, 1); } template<> EIGEN_STRONG_INLINE Packet2d ploaddup(const double* from) { return pset1(from[0]); } @@ -302,8 +313,8 @@ template<> EIGEN_STRONG_INLINE void pstoreu(double* to, const Packet2d& _mm_storel_pd((to), from); _mm_storeh_pd((to+1), from); } -template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, _mm_castps_pd(from)); } -template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu((double*)to, _mm_castsi128_pd(from)); } +template<> EIGEN_STRONG_INLINE void pstoreu(float* to, const Packet4f& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu(reinterpret_cast(to), _mm_castps_pd(from)); } +template<> EIGEN_STRONG_INLINE void pstoreu(int* to, const Packet4i& from) { EIGEN_DEBUG_UNALIGNED_STORE pstoreu(reinterpret_cast(to), _mm_castsi128_pd(from)); } // some compilers might be tempted to perform multiple moves instead of using a vector path. template<> EIGEN_STRONG_INLINE void pstore1(float* to, const float& a) @@ -541,7 +552,7 @@ template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4f& first, const Packet4f& second) + static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) { if (Offset!=0) first = _mm_castsi128_ps(_mm_alignr_epi8(_mm_castps_si128(second), _mm_castps_si128(first), Offset*4)); @@ -551,7 +562,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4i& first, const Packet4i& second) + static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) { if (Offset!=0) first = _mm_alignr_epi8(second,first, Offset*4); @@ -561,7 +572,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet2d& first, const Packet2d& second) + static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) { if (Offset==1) first = _mm_castsi128_pd(_mm_alignr_epi8(_mm_castpd_si128(second), _mm_castpd_si128(first), 8)); @@ -572,7 +583,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4f& first, const Packet4f& second) + static EIGEN_STRONG_INLINE void run(Packet4f& first, const Packet4f& second) { if (Offset==1) { @@ -595,7 +606,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet4i& first, const Packet4i& second) + static EIGEN_STRONG_INLINE void run(Packet4i& first, const Packet4i& second) { if (Offset==1) { @@ -618,7 +629,7 @@ struct palign_impl template struct palign_impl { - EIGEN_STRONG_INLINE static void run(Packet2d& first, const Packet2d& second) + static EIGEN_STRONG_INLINE void run(Packet2d& first, const Packet2d& second) { if (Offset==1) { @@ -631,4 +642,6 @@ struct palign_impl } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_PACKET_MATH_SSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h index dc20f7e1e..8f53c43ad 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h @@ -26,6 +26,8 @@ #ifndef EIGEN_COEFFBASED_PRODUCT_H #define EIGEN_COEFFBASED_PRODUCT_H +namespace Eigen { + namespace internal { /********************************************************************************* @@ -224,8 +226,8 @@ class CoeffBasedProduct { return reinterpret_cast(*this).diagonal(index); } protected: - const LhsNested m_lhs; - const RhsNested m_rhs; + typename internal::add_const_on_value_type::type m_lhs; + typename internal::add_const_on_value_type::type m_rhs; mutable PlainObject m_result; }; @@ -252,7 +254,7 @@ template struct product_coeff_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) { product_coeff_impl::run(row, col, lhs, rhs, res); res += lhs.coeff(row, UnrollingIndex) * rhs.coeff(UnrollingIndex, col); @@ -263,7 +265,7 @@ template struct product_coeff_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) { res = lhs.coeff(row, 0) * rhs.coeff(0, col); } @@ -273,7 +275,7 @@ template struct product_coeff_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar& res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar& res) { eigen_assert(lhs.cols()>0 && "you are using a non initialized matrix"); res = lhs.coeff(row, 0) * rhs.coeff(0, col); @@ -291,7 +293,7 @@ struct product_coeff_vectorized_unroller { typedef typename Lhs::Index Index; enum { PacketSize = packet_traits::size }; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::PacketScalar &pres) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::PacketScalar &pres) { product_coeff_vectorized_unroller::run(row, col, lhs, rhs, pres); pres = padd(pres, pmul( lhs.template packet(row, UnrollingIndex) , rhs.template packet(UnrollingIndex, col) )); @@ -302,7 +304,7 @@ template struct product_coeff_vectorized_unroller<0, Lhs, Rhs, Packet> { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::PacketScalar &pres) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::PacketScalar &pres) { pres = pmul(lhs.template packet(row, 0) , rhs.template packet(0, col)); } @@ -314,7 +316,7 @@ struct product_coeff_impl::size }; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) { Packet pres; product_coeff_vectorized_unroller::run(row, col, lhs, rhs, pres); @@ -327,7 +329,7 @@ template struct product_coeff_vectorized_dyn_selector { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index /*row*/, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) { res = lhs.transpose().cwiseProduct(rhs.col(col)).sum(); } @@ -349,7 +351,7 @@ template struct product_coeff_vectorized_dyn_selector { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index /*col*/, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) + static EIGEN_STRONG_INLINE void run(Index row, Index /*col*/, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) { res = lhs.row(row).transpose().cwiseProduct(rhs).sum(); } @@ -359,7 +361,7 @@ template struct product_coeff_vectorized_dyn_selector { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index /*row*/, Index /*col*/, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) { res = lhs.transpose().cwiseProduct(rhs).sum(); } @@ -369,7 +371,7 @@ template struct product_coeff_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, typename Lhs::Scalar &res) { product_coeff_vectorized_dyn_selector::run(row, col, lhs, rhs, res); } @@ -383,7 +385,7 @@ template { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { product_packet_impl::run(row, col, lhs, rhs, res); res = pmadd(pset1(lhs.coeff(row, UnrollingIndex)), rhs.template packet(UnrollingIndex, col), res); @@ -394,7 +396,7 @@ template { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { product_packet_impl::run(row, col, lhs, rhs, res); res = pmadd(lhs.template packet(row, UnrollingIndex), pset1(rhs.coeff(UnrollingIndex, col)), res); @@ -405,7 +407,7 @@ template struct product_packet_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { res = pmul(pset1(lhs.coeff(row, 0)),rhs.template packet(0, col)); } @@ -415,7 +417,7 @@ template struct product_packet_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { res = pmul(lhs.template packet(row, 0), pset1(rhs.coeff(0, col))); } @@ -425,7 +427,7 @@ template struct product_packet_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) { eigen_assert(lhs.cols()>0 && "you are using a non initialized matrix"); res = pmul(pset1(lhs.coeff(row, 0)),rhs.template packet(0, col)); @@ -438,7 +440,7 @@ template struct product_packet_impl { typedef typename Lhs::Index Index; - EIGEN_STRONG_INLINE static void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) { eigen_assert(lhs.cols()>0 && "you are using a non initialized matrix"); res = pmul(lhs.template packet(row, 0), pset1(rhs.coeff(0, col))); @@ -449,4 +451,6 @@ struct product_packet_impl } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_COEFFBASED_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h index cd1c37c78..d631fa28e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h @@ -25,12 +25,16 @@ #ifndef EIGEN_GENERAL_BLOCK_PANEL_H #define EIGEN_GENERAL_BLOCK_PANEL_H +namespace Eigen { + namespace internal { template class gebp_traits; -inline std::ptrdiff_t manage_caching_sizes_second_if_negative(std::ptrdiff_t a, std::ptrdiff_t b) + +/** \internal \returns b if a<=0, and returns a otherwise. */ +inline std::ptrdiff_t manage_caching_sizes_helper(std::ptrdiff_t a, std::ptrdiff_t b) { return a<=0 ? b : a; } @@ -38,9 +42,14 @@ inline std::ptrdiff_t manage_caching_sizes_second_if_negative(std::ptrdiff_t a, /** \internal */ inline void manage_caching_sizes(Action action, std::ptrdiff_t* l1=0, std::ptrdiff_t* l2=0) { - static std::ptrdiff_t m_l1CacheSize = manage_caching_sizes_second_if_negative(queryL1CacheSize(),8 * 1024); - static std::ptrdiff_t m_l2CacheSize = manage_caching_sizes_second_if_negative(queryTopLevelCacheSize(),1*1024*1024); - + static std::ptrdiff_t m_l1CacheSize = 0; + static std::ptrdiff_t m_l2CacheSize = 0; + if(m_l2CacheSize==0) + { + m_l1CacheSize = manage_caching_sizes_helper(queryL1CacheSize(),8 * 1024); + m_l2CacheSize = manage_caching_sizes_helper(queryTopLevelCacheSize(),1*1024*1024); + } + if(action==SetAction) { // set the cpu cache size and cache all block sizes from a global cache size in byte @@ -533,7 +542,7 @@ struct gebp_kernel ResPacketSize = Traits::ResPacketSize }; - EIGEN_FLATTEN_ATTRIB + EIGEN_DONT_INLINE EIGEN_FLATTEN_ATTRIB void operator()(ResScalar* res, Index resStride, const LhsScalar* blockA, const RhsScalar* blockB, Index rows, Index depth, Index cols, ResScalar alpha, Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0, RhsScalar* unpackedB = 0) { @@ -595,64 +604,64 @@ struct gebp_kernel if(nr==2) { LhsPacket A0, A1; - RhsPacket B0; + RhsPacket B_0; RhsPacket T0; EIGEN_ASM_COMMENT("mybegin2"); traits.loadLhs(&blA[0*LhsProgress], A0); traits.loadLhs(&blA[1*LhsProgress], A1); - traits.loadRhs(&blB[0*RhsProgress], B0); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[1*RhsProgress], B0); - traits.madd(A0,B0,C1,T0); - traits.madd(A1,B0,C5,B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[1*RhsProgress], B_0); + traits.madd(A0,B_0,C1,T0); + traits.madd(A1,B_0,C5,B_0); traits.loadLhs(&blA[2*LhsProgress], A0); traits.loadLhs(&blA[3*LhsProgress], A1); - traits.loadRhs(&blB[2*RhsProgress], B0); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[3*RhsProgress], B0); - traits.madd(A0,B0,C1,T0); - traits.madd(A1,B0,C5,B0); + traits.loadRhs(&blB[2*RhsProgress], B_0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[3*RhsProgress], B_0); + traits.madd(A0,B_0,C1,T0); + traits.madd(A1,B_0,C5,B_0); traits.loadLhs(&blA[4*LhsProgress], A0); traits.loadLhs(&blA[5*LhsProgress], A1); - traits.loadRhs(&blB[4*RhsProgress], B0); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[5*RhsProgress], B0); - traits.madd(A0,B0,C1,T0); - traits.madd(A1,B0,C5,B0); + traits.loadRhs(&blB[4*RhsProgress], B_0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[5*RhsProgress], B_0); + traits.madd(A0,B_0,C1,T0); + traits.madd(A1,B_0,C5,B_0); traits.loadLhs(&blA[6*LhsProgress], A0); traits.loadLhs(&blA[7*LhsProgress], A1); - traits.loadRhs(&blB[6*RhsProgress], B0); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[7*RhsProgress], B0); - traits.madd(A0,B0,C1,T0); - traits.madd(A1,B0,C5,B0); + traits.loadRhs(&blB[6*RhsProgress], B_0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[7*RhsProgress], B_0); + traits.madd(A0,B_0,C1,T0); + traits.madd(A1,B_0,C5,B_0); EIGEN_ASM_COMMENT("myend"); } else { EIGEN_ASM_COMMENT("mybegin4"); LhsPacket A0, A1; - RhsPacket B0, B1, B2, B3; + RhsPacket B_0, B1, B2, B3; RhsPacket T0; traits.loadLhs(&blA[0*LhsProgress], A0); traits.loadLhs(&blA[1*LhsProgress], A1); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); - traits.madd(A0,B0,C0,T0); + traits.madd(A0,B_0,C0,T0); traits.loadRhs(&blB[2*RhsProgress], B2); - traits.madd(A1,B0,C4,B0); + traits.madd(A1,B_0,C4,B_0); traits.loadRhs(&blB[3*RhsProgress], B3); - traits.loadRhs(&blB[4*RhsProgress], B0); + traits.loadRhs(&blB[4*RhsProgress], B_0); traits.madd(A0,B1,C1,T0); traits.madd(A1,B1,C5,B1); traits.loadRhs(&blB[5*RhsProgress], B1); @@ -664,9 +673,9 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.madd(A1,B3,C7,B3); traits.loadLhs(&blA[3*LhsProgress], A1); traits.loadRhs(&blB[7*RhsProgress], B3); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[8*RhsProgress], B0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[8*RhsProgress], B_0); traits.madd(A0,B1,C1,T0); traits.madd(A1,B1,C5,B1); traits.loadRhs(&blB[9*RhsProgress], B1); @@ -679,9 +688,9 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.loadLhs(&blA[5*LhsProgress], A1); traits.loadRhs(&blB[11*RhsProgress], B3); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[12*RhsProgress], B0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[12*RhsProgress], B_0); traits.madd(A0,B1,C1,T0); traits.madd(A1,B1,C5,B1); traits.loadRhs(&blB[13*RhsProgress], B1); @@ -693,8 +702,8 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.madd(A1,B3,C7,B3); traits.loadLhs(&blA[7*LhsProgress], A1); traits.loadRhs(&blB[15*RhsProgress], B3); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); traits.madd(A0,B1,C1,T0); traits.madd(A1,B1,C5,B1); traits.madd(A0,B2,C2,T0); @@ -712,32 +721,32 @@ EIGEN_ASM_COMMENT("mybegin4"); if(nr==2) { LhsPacket A0, A1; - RhsPacket B0; + RhsPacket B_0; RhsPacket T0; traits.loadLhs(&blA[0*LhsProgress], A0); traits.loadLhs(&blA[1*LhsProgress], A1); - traits.loadRhs(&blB[0*RhsProgress], B0); - traits.madd(A0,B0,C0,T0); - traits.madd(A1,B0,C4,B0); - traits.loadRhs(&blB[1*RhsProgress], B0); - traits.madd(A0,B0,C1,T0); - traits.madd(A1,B0,C5,B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); + traits.madd(A0,B_0,C0,T0); + traits.madd(A1,B_0,C4,B_0); + traits.loadRhs(&blB[1*RhsProgress], B_0); + traits.madd(A0,B_0,C1,T0); + traits.madd(A1,B_0,C5,B_0); } else { LhsPacket A0, A1; - RhsPacket B0, B1, B2, B3; + RhsPacket B_0, B1, B2, B3; RhsPacket T0; traits.loadLhs(&blA[0*LhsProgress], A0); traits.loadLhs(&blA[1*LhsProgress], A1); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); - traits.madd(A0,B0,C0,T0); + traits.madd(A0,B_0,C0,T0); traits.loadRhs(&blB[2*RhsProgress], B2); - traits.madd(A1,B0,C4,B0); + traits.madd(A1,B_0,C4,B_0); traits.loadRhs(&blB[3*RhsProgress], B3); traits.madd(A0,B1,C1,T0); traits.madd(A1,B1,C5,B1); @@ -824,42 +833,42 @@ EIGEN_ASM_COMMENT("mybegin4"); if(nr==2) { LhsPacket A0; - RhsPacket B0, B1; + RhsPacket B_0, B1; traits.loadLhs(&blA[0*LhsProgress], A0); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); - traits.loadRhs(&blB[2*RhsProgress], B0); + traits.madd(A0,B_0,C0,B_0); + traits.loadRhs(&blB[2*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadLhs(&blA[1*LhsProgress], A0); traits.loadRhs(&blB[3*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); - traits.loadRhs(&blB[4*RhsProgress], B0); + traits.madd(A0,B_0,C0,B_0); + traits.loadRhs(&blB[4*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadLhs(&blA[2*LhsProgress], A0); traits.loadRhs(&blB[5*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); - traits.loadRhs(&blB[6*RhsProgress], B0); + traits.madd(A0,B_0,C0,B_0); + traits.loadRhs(&blB[6*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadLhs(&blA[3*LhsProgress], A0); traits.loadRhs(&blB[7*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); + traits.madd(A0,B_0,C0,B_0); traits.madd(A0,B1,C1,B1); } else { LhsPacket A0; - RhsPacket B0, B1, B2, B3; + RhsPacket B_0, B1, B2, B3; traits.loadLhs(&blA[0*LhsProgress], A0); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); + traits.madd(A0,B_0,C0,B_0); traits.loadRhs(&blB[2*RhsProgress], B2); traits.loadRhs(&blB[3*RhsProgress], B3); - traits.loadRhs(&blB[4*RhsProgress], B0); + traits.loadRhs(&blB[4*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadRhs(&blB[5*RhsProgress], B1); traits.madd(A0,B2,C2,B2); @@ -867,8 +876,8 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.madd(A0,B3,C3,B3); traits.loadLhs(&blA[1*LhsProgress], A0); traits.loadRhs(&blB[7*RhsProgress], B3); - traits.madd(A0,B0,C0,B0); - traits.loadRhs(&blB[8*RhsProgress], B0); + traits.madd(A0,B_0,C0,B_0); + traits.loadRhs(&blB[8*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadRhs(&blB[9*RhsProgress], B1); traits.madd(A0,B2,C2,B2); @@ -877,8 +886,8 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.loadLhs(&blA[2*LhsProgress], A0); traits.loadRhs(&blB[11*RhsProgress], B3); - traits.madd(A0,B0,C0,B0); - traits.loadRhs(&blB[12*RhsProgress], B0); + traits.madd(A0,B_0,C0,B_0); + traits.loadRhs(&blB[12*RhsProgress], B_0); traits.madd(A0,B1,C1,B1); traits.loadRhs(&blB[13*RhsProgress], B1); traits.madd(A0,B2,C2,B2); @@ -887,7 +896,7 @@ EIGEN_ASM_COMMENT("mybegin4"); traits.loadLhs(&blA[3*LhsProgress], A0); traits.loadRhs(&blB[15*RhsProgress], B3); - traits.madd(A0,B0,C0,B0); + traits.madd(A0,B_0,C0,B_0); traits.madd(A0,B1,C1,B1); traits.madd(A0,B2,C2,B2); traits.madd(A0,B3,C3,B3); @@ -902,26 +911,26 @@ EIGEN_ASM_COMMENT("mybegin4"); if(nr==2) { LhsPacket A0; - RhsPacket B0, B1; + RhsPacket B_0, B1; traits.loadLhs(&blA[0*LhsProgress], A0); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); - traits.madd(A0,B0,C0,B0); + traits.madd(A0,B_0,C0,B_0); traits.madd(A0,B1,C1,B1); } else { LhsPacket A0; - RhsPacket B0, B1, B2, B3; + RhsPacket B_0, B1, B2, B3; traits.loadLhs(&blA[0*LhsProgress], A0); - traits.loadRhs(&blB[0*RhsProgress], B0); + traits.loadRhs(&blB[0*RhsProgress], B_0); traits.loadRhs(&blB[1*RhsProgress], B1); traits.loadRhs(&blB[2*RhsProgress], B2); traits.loadRhs(&blB[3*RhsProgress], B3); - traits.madd(A0,B0,C0,B0); + traits.madd(A0,B_0,C0,B_0); traits.madd(A0,B1,C1,B1); traits.madd(A0,B2,C2,B2); traits.madd(A0,B3,C3,B3); @@ -968,26 +977,26 @@ EIGEN_ASM_COMMENT("mybegin4"); if(nr==2) { LhsScalar A0; - RhsScalar B0, B1; + RhsScalar B_0, B1; A0 = blA[k]; - B0 = blB[0]; + B_0 = blB[0]; B1 = blB[1]; - MADD(cj,A0,B0,C0,B0); + MADD(cj,A0,B_0,C0,B_0); MADD(cj,A0,B1,C1,B1); } else { LhsScalar A0; - RhsScalar B0, B1, B2, B3; + RhsScalar B_0, B1, B2, B3; A0 = blA[k]; - B0 = blB[0]; + B_0 = blB[0]; B1 = blB[1]; B2 = blB[2]; B3 = blB[3]; - MADD(cj,A0,B0,C0,B0); + MADD(cj,A0,B_0,C0,B_0); MADD(cj,A0,B1,C1,B1); MADD(cj,A0,B2,C2,B2); MADD(cj,A0,B3,C3,B3); @@ -1024,14 +1033,14 @@ EIGEN_ASM_COMMENT("mybegin4"); for(Index k=0; k struct gemm_pack_lhs { - void operator()(Scalar* blockA, const Scalar* EIGEN_RESTRICT _lhs, Index lhsStride, Index depth, Index rows, + EIGEN_DONT_INLINE void operator()(Scalar* blockA, const Scalar* EIGEN_RESTRICT _lhs, Index lhsStride, Index depth, Index rows, Index stride=0, Index offset=0) { -// enum { PacketSize = packet_traits::size }; + typedef typename packet_traits::type Packet; + enum { PacketSize = packet_traits::size }; + + EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK LHS"); eigen_assert(((!PanelMode) && stride==0 && offset==0) || (PanelMode && stride>=depth && offset<=stride)); + eigen_assert( (StorageOrder==RowMajor) || ((Pack1%PacketSize)==0 && Pack1<=4*PacketSize) ); conj_if::IsComplex && Conjugate> cj; const_blas_data_mapper lhs(_lhs,lhsStride); Index count = 0; @@ -1128,9 +1141,44 @@ struct gemm_pack_lhs for(Index i=0; i=1*PacketSize) A = ploadu(&lhs(i+0*PacketSize, k)); + if(Pack1>=2*PacketSize) B = ploadu(&lhs(i+1*PacketSize, k)); + if(Pack1>=3*PacketSize) C = ploadu(&lhs(i+2*PacketSize, k)); + if(Pack1>=4*PacketSize) D = ploadu(&lhs(i+3*PacketSize, k)); + if(Pack1>=1*PacketSize) { pstore(blockA+count, cj.pconj(A)); count+=PacketSize; } + if(Pack1>=2*PacketSize) { pstore(blockA+count, cj.pconj(B)); count+=PacketSize; } + if(Pack1>=3*PacketSize) { pstore(blockA+count, cj.pconj(C)); count+=PacketSize; } + if(Pack1>=4*PacketSize) { pstore(blockA+count, cj.pconj(D)); count+=PacketSize; } + } + } + else + { + for(Index k=0; k=Pack2) @@ -1164,9 +1212,10 @@ struct gemm_pack_rhs { typedef typename packet_traits::type Packet; enum { PacketSize = packet_traits::size }; - void operator()(Scalar* blockB, const Scalar* rhs, Index rhsStride, Index depth, Index cols, + EIGEN_DONT_INLINE void operator()(Scalar* blockB, const Scalar* rhs, Index rhsStride, Index depth, Index cols, Index stride=0, Index offset=0) { + EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK RHS COLMAJOR"); eigen_assert(((!PanelMode) && stride==0 && offset==0) || (PanelMode && stride>=depth && offset<=stride)); conj_if::IsComplex && Conjugate> cj; Index packet_cols = (cols/nr) * nr; @@ -1211,9 +1260,10 @@ template { enum { PacketSize = packet_traits::size }; - void operator()(Scalar* blockB, const Scalar* rhs, Index rhsStride, Index depth, Index cols, + EIGEN_DONT_INLINE void operator()(Scalar* blockB, const Scalar* rhs, Index rhsStride, Index depth, Index cols, Index stride=0, Index offset=0) { + EIGEN_ASM_COMMENT("EIGEN PRODUCT PACK RHS ROWMAJOR"); eigen_assert(((!PanelMode) && stride==0 && offset==0) || (PanelMode && stride>=depth && offset<=stride)); conj_if::IsComplex && Conjugate> cj; Index packet_cols = (cols/nr) * nr; @@ -1279,4 +1329,6 @@ inline void setCpuCacheSizes(std::ptrdiff_t l1, std::ptrdiff_t l2) internal::manage_caching_sizes(SetAction, &l1, &l2); } +} // end namespace Eigen + #endif // EIGEN_GENERAL_BLOCK_PANEL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix.h index ae94a2795..76fc32032 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix.h @@ -25,6 +25,8 @@ #ifndef EIGEN_GENERAL_MATRIX_MATRIX_H #define EIGEN_GENERAL_MATRIX_MATRIX_H +namespace Eigen { + namespace internal { template class level3_blocking; @@ -77,7 +79,7 @@ static void run(Index rows, Index cols, Index depth, typedef gebp_traits Traits; - Index kc = blocking.kc(); // cache block size along the K direction + Index kc = blocking.kc(); // cache block size along the K direction Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction //Index nc = blocking.nc(); // cache block size along the N direction @@ -247,7 +249,7 @@ struct gemm_functor BlockingType& m_blocking; }; -template class gemm_blocking_space; template @@ -280,8 +282,8 @@ class level3_blocking inline RhsScalar* blockW() { return m_blockW; } }; -template -class gemm_blocking_space +template +class gemm_blocking_space : public level3_blocking< typename conditional::type, typename conditional::type> @@ -322,8 +324,8 @@ class gemm_blocking_space -class gemm_blocking_space +template +class gemm_blocking_space : public level3_blocking< typename conditional::type, typename conditional::type> @@ -347,7 +349,7 @@ class gemm_blocking_spacem_nc = Transpose ? rows : cols; this->m_kc = depth; - computeProductBlockingSizes(this->m_kc, this->m_mc, this->m_nc); + computeProductBlockingSizes(this->m_kc, this->m_mc, this->m_nc); m_sizeA = this->m_mc * this->m_kc; m_sizeB = this->m_kc * this->m_nc; m_sizeW = this->m_kc*Traits::WorkSpaceFactor; @@ -412,8 +414,8 @@ class GeneralProduct { eigen_assert(dst.rows()==m_lhs.rows() && dst.cols()==m_rhs.cols()); - const ActualLhsType lhs = LhsBlasTraits::extract(m_lhs); - const ActualRhsType rhs = RhsBlasTraits::extract(m_rhs); + typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(m_lhs); + typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(m_rhs); Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(m_lhs) * RhsBlasTraits::extractScalarFactor(m_rhs); @@ -436,4 +438,6 @@ class GeneralProduct } }; +} // end namespace Eigen + #endif // EIGEN_GENERAL_MATRIX_MATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h index 5043b64fe..74331ee4f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h @@ -25,6 +25,8 @@ #ifndef EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_H #define EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_H +namespace Eigen { + namespace internal { /********************************************************************** @@ -42,14 +44,14 @@ struct tribb_kernel; template + int ResStorageOrder, int UpLo, int Version = Specialized> struct general_matrix_matrix_triangular_product; // as usual if the result is row major => we transpose the product template -struct general_matrix_matrix_triangular_product -{ + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, int UpLo, int Version> +struct general_matrix_matrix_triangular_product +{ typedef typename scalar_product_traits::ReturnType ResScalar; static EIGEN_STRONG_INLINE void run(Index size, Index depth,const LhsScalar* lhs, Index lhsStride, const RhsScalar* rhs, Index rhsStride, ResScalar* res, Index resStride, ResScalar alpha) @@ -63,8 +65,8 @@ struct general_matrix_matrix_triangular_product -struct general_matrix_matrix_triangular_product + typename RhsScalar, int RhsStorageOrder, bool ConjugateRhs, int UpLo, int Version> +struct general_matrix_matrix_triangular_product { typedef typename scalar_product_traits::ReturnType ResScalar; static EIGEN_STRONG_INLINE void run(Index size, Index depth,const LhsScalar* _lhs, Index lhsStride, @@ -201,13 +203,13 @@ TriangularView& TriangularView::assignProduct( typedef internal::blas_traits LhsBlasTraits; typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhs; typedef typename internal::remove_all::type _ActualLhs; - const ActualLhs actualLhs = LhsBlasTraits::extract(prod.lhs()); + typename internal::add_const_on_value_type::type actualLhs = LhsBlasTraits::extract(prod.lhs()); typedef typename internal::remove_all::type Rhs; typedef internal::blas_traits RhsBlasTraits; typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhs; typedef typename internal::remove_all::type _ActualRhs; - const ActualRhs actualRhs = RhsBlasTraits::extract(prod.rhs()); + typename internal::add_const_on_value_type::type actualRhs = RhsBlasTraits::extract(prod.rhs()); typename ProductDerived::Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs().derived()) * RhsBlasTraits::extractScalarFactor(prod.rhs().derived()); @@ -222,4 +224,6 @@ TriangularView& TriangularView::assignProduct( return *this; } +} // end namespace Eigen + #endif // EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h new file mode 100644 index 000000000..3deed068e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h @@ -0,0 +1,146 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Level 3 BLAS SYRK/HERK implementation. + ******************************************************************************** +*/ + +#ifndef EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_MKL_H +#define EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_MKL_H + +namespace Eigen { + +namespace internal { + +template +struct general_matrix_matrix_rankupdate : + general_matrix_matrix_triangular_product< + Index,Scalar,AStorageOrder,ConjugateA,Scalar,AStorageOrder,ConjugateA,ResStorageOrder,UpLo,BuiltIn> {}; + + +// try to go to BLAS specialization +#define EIGEN_MKL_RANKUPDATE_SPECIALIZE(Scalar) \ +template \ +struct general_matrix_matrix_triangular_product { \ + static EIGEN_STRONG_INLINE void run(Index size, Index depth,const Scalar* lhs, Index lhsStride, \ + const Scalar* rhs, Index rhsStride, Scalar* res, Index resStride, Scalar alpha) \ + { \ + if (lhs==rhs) { \ + general_matrix_matrix_rankupdate \ + ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resStride,alpha); \ + } else { \ + general_matrix_matrix_triangular_product \ + ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resStride,alpha); \ + } \ + } \ +}; + +EIGEN_MKL_RANKUPDATE_SPECIALIZE(double) +//EIGEN_MKL_RANKUPDATE_SPECIALIZE(dcomplex) +EIGEN_MKL_RANKUPDATE_SPECIALIZE(float) +//EIGEN_MKL_RANKUPDATE_SPECIALIZE(scomplex) + +// SYRK for float/double +#define EIGEN_MKL_RANKUPDATE_R(EIGTYPE, MKLTYPE, MKLFUNC) \ +template \ +struct general_matrix_matrix_rankupdate { \ + enum { \ + IsLower = (UpLo&Lower) == Lower, \ + LowUp = IsLower ? Lower : Upper, \ + conjA = ((AStorageOrder==ColMajor) && ConjugateA) ? 1 : 0 \ + }; \ + static EIGEN_STRONG_INLINE void run(Index size, Index depth,const EIGTYPE* lhs, Index lhsStride, \ + const EIGTYPE* rhs, Index rhsStride, EIGTYPE* res, Index resStride, EIGTYPE alpha) \ + { \ + /* typedef Matrix MatrixRhs;*/ \ +\ + MKL_INT lda=lhsStride, ldc=resStride, n=size, k=depth; \ + char uplo=(IsLower) ? 'L' : 'U', trans=(AStorageOrder==RowMajor) ? 'T':'N'; \ + MKLTYPE alpha_, beta_; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, EIGTYPE(1)); \ + MKLFUNC(&uplo, &trans, &n, &k, &alpha_, lhs, &lda, &beta_, res, &ldc); \ + } \ +}; + +// HERK for complex data +#define EIGEN_MKL_RANKUPDATE_C(EIGTYPE, MKLTYPE, RTYPE, MKLFUNC) \ +template \ +struct general_matrix_matrix_rankupdate { \ + enum { \ + IsLower = (UpLo&Lower) == Lower, \ + LowUp = IsLower ? Lower : Upper, \ + conjA = (((AStorageOrder==ColMajor) && ConjugateA) || ((AStorageOrder==RowMajor) && !ConjugateA)) ? 1 : 0 \ + }; \ + static EIGEN_STRONG_INLINE void run(Index size, Index depth,const EIGTYPE* lhs, Index lhsStride, \ + const EIGTYPE* rhs, Index rhsStride, EIGTYPE* res, Index resStride, EIGTYPE alpha) \ + { \ + typedef Matrix MatrixType; \ +\ + MKL_INT lda=lhsStride, ldc=resStride, n=size, k=depth; \ + char uplo=(IsLower) ? 'L' : 'U', trans=(AStorageOrder==RowMajor) ? 'C':'N'; \ + RTYPE alpha_, beta_; \ + const EIGTYPE* a_ptr; \ +\ +/* Set alpha_ & beta_ */ \ +/* assign_scalar_eig2mkl(alpha_, alpha); */\ +/* assign_scalar_eig2mkl(beta_, EIGTYPE(1));*/ \ + alpha_ = alpha.real(); \ + beta_ = 1.0; \ +/* Copy with conjugation in some cases*/ \ + MatrixType a; \ + if (conjA) { \ + Map > mapA(lhs,n,k,OuterStride<>(lhsStride)); \ + a = mapA.conjugate(); \ + lda = a.outerStride(); \ + a_ptr = a.data(); \ + } else a_ptr=lhs; \ + MKLFUNC(&uplo, &trans, &n, &k, &alpha_, (MKLTYPE*)a_ptr, &lda, &beta_, (MKLTYPE*)res, &ldc); \ + } \ +}; + + +EIGEN_MKL_RANKUPDATE_R(double, double, dsyrk) +EIGEN_MKL_RANKUPDATE_R(float, float, ssyrk) + +//EIGEN_MKL_RANKUPDATE_C(dcomplex, MKL_Complex16, double, zherk) +//EIGEN_MKL_RANKUPDATE_C(scomplex, MKL_Complex8, double, cherk) + + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_GENERAL_MATRIX_MATRIX_TRIANGULAR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h new file mode 100644 index 000000000..060af328e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h @@ -0,0 +1,118 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * General matrix-matrix product functionality based on ?GEMM. + ******************************************************************************** +*/ + +#ifndef EIGEN_GENERAL_MATRIX_MATRIX_MKL_H +#define EIGEN_GENERAL_MATRIX_MATRIX_MKL_H + +namespace Eigen { + +namespace internal { + +/********************************************************************** +* This file implements general matrix-matrix multiplication using BLAS +* gemm function via partial specialization of +* general_matrix_matrix_product::run(..) method for float, double, +* std::complex and std::complex types +**********************************************************************/ + +// gemm specialization + +#define GEMM_SPECIALIZATION(EIGTYPE, EIGPREFIX, MKLTYPE, MKLPREFIX) \ +template< \ + typename Index, \ + int LhsStorageOrder, bool ConjugateLhs, \ + int RhsStorageOrder, bool ConjugateRhs> \ +struct general_matrix_matrix_product \ +{ \ +static void run(Index rows, Index cols, Index depth, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha, \ + level3_blocking& /*blocking*/, \ + GemmParallelInfo* /*info = 0*/) \ +{ \ + using std::conj; \ +\ + char transa, transb; \ + MKL_INT m, n, k, lda, ldb, ldc; \ + const EIGTYPE *a, *b; \ + MKLTYPE alpha_, beta_; \ + MatrixX##EIGPREFIX a_tmp, b_tmp; \ + EIGTYPE myone(1);\ +\ +/* Set transpose options */ \ + transa = (LhsStorageOrder==RowMajor) ? ((ConjugateLhs) ? 'C' : 'T') : 'N'; \ + transb = (RhsStorageOrder==RowMajor) ? ((ConjugateRhs) ? 'C' : 'T') : 'N'; \ +\ +/* Set m, n, k */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)cols; \ + k = (MKL_INT)depth; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ +\ +/* Set lda, ldb, ldc */ \ + lda = (MKL_INT)lhsStride; \ + ldb = (MKL_INT)rhsStride; \ + ldc = (MKL_INT)resStride; \ +\ +/* Set a, b, c */ \ + if ((LhsStorageOrder==ColMajor) && (ConjugateLhs)) { \ + Map > lhs(_lhs,m,k,OuterStride<>(lhsStride)); \ + a_tmp = lhs.conjugate(); \ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else a = _lhs; \ +\ + if ((RhsStorageOrder==ColMajor) && (ConjugateRhs)) { \ + Map > rhs(_rhs,k,n,OuterStride<>(rhsStride)); \ + b_tmp = rhs.conjugate(); \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ + } else b = _rhs; \ +\ + MKLPREFIX##gemm(&transa, &transb, &m, &n, &k, &alpha_, (const MKLTYPE*)a, &lda, (const MKLTYPE*)b, &ldb, &beta_, (MKLTYPE*)res, &ldc); \ +}}; + +GEMM_SPECIALIZATION(double, d, double, d) +GEMM_SPECIALIZATION(float, f, float, s) +GEMM_SPECIALIZATION(dcomplex, cd, MKL_Complex16, z) +GEMM_SPECIALIZATION(scomplex, cf, MKL_Complex8, c) + +} // end namespase internal + +} // end namespace Eigen + +#endif // EIGEN_GENERAL_MATRIX_MATRIX_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector.h index e0e2cbf8f..d868a66a1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector.h @@ -25,6 +25,8 @@ #ifndef EIGEN_GENERAL_MATRIX_VECTOR_H #define EIGEN_GENERAL_MATRIX_VECTOR_H +namespace Eigen { + namespace internal { /* Optimized col-major matrix * vector product: @@ -40,8 +42,8 @@ namespace internal { * |cplx |real |cplx | invalid, the caller has to do tmp: = A * B; C += alpha*tmp * |cplx |real |real | optimal case, vectorization possible via real-cplx mul */ -template -struct general_matrix_vector_product +template +struct general_matrix_vector_product { typedef typename scalar_product_traits::ReturnType ResScalar; @@ -99,7 +101,7 @@ EIGEN_DONT_INLINE static void run( // How many coeffs of the result do we have to skip to be aligned. // Here we assume data are at least aligned on the base scalar type. - Index alignedStart = first_aligned(res,size); + Index alignedStart = internal::first_aligned(res,size); Index alignedSize = ResPacketSize>1 ? alignedStart + ((size-alignedStart) & ~ResPacketAlignedMask) : 0; const Index peeledSize = peels>1 ? alignedStart + ((alignedSize-alignedStart) & ~PeelAlignedMask) : alignedStart; @@ -109,7 +111,7 @@ EIGEN_DONT_INLINE static void run( : FirstAligned; // we cannot assume the first element is aligned because of sub-matrices - const Index lhsAlignmentOffset = first_aligned(lhs,size); + const Index lhsAlignmentOffset = internal::first_aligned(lhs,size); // find how many columns do we have to skip to be aligned with the result (if possible) Index skipColumns = 0; @@ -296,8 +298,8 @@ EIGEN_DONT_INLINE static void run( * - alpha is always a complex (or converted to a complex) * - no vectorization */ -template -struct general_matrix_vector_product +template +struct general_matrix_vector_product { typedef typename scalar_product_traits::ReturnType ResScalar; @@ -351,7 +353,7 @@ EIGEN_DONT_INLINE static void run( // How many coeffs of the result do we have to skip to be aligned. // Here we assume data are at least aligned on the base scalar type // if that's not the case then vectorization is discarded, see below. - Index alignedStart = first_aligned(rhs, depth); + Index alignedStart = internal::first_aligned(rhs, depth); Index alignedSize = RhsPacketSize>1 ? alignedStart + ((depth-alignedStart) & ~RhsPacketAlignedMask) : 0; const Index peeledSize = peels>1 ? alignedStart + ((alignedSize-alignedStart) & ~PeelAlignedMask) : alignedStart; @@ -361,7 +363,7 @@ EIGEN_DONT_INLINE static void run( : FirstAligned; // we cannot assume the first element is aligned because of sub-matrices - const Index lhsAlignmentOffset = first_aligned(lhs,depth); + const Index lhsAlignmentOffset = internal::first_aligned(lhs,depth); // find how many rows do we have to skip to be aligned with rhs (if possible) Index skipRows = 0; @@ -556,4 +558,6 @@ EIGEN_DONT_INLINE static void run( } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_GENERAL_MATRIX_VECTOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector_MKL.h new file mode 100644 index 000000000..e9de6af3e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixVector_MKL.h @@ -0,0 +1,131 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * General matrix-vector product functionality based on ?GEMV. + ******************************************************************************** +*/ + +#ifndef EIGEN_GENERAL_MATRIX_VECTOR_MKL_H +#define EIGEN_GENERAL_MATRIX_VECTOR_MKL_H + +namespace Eigen { + +namespace internal { + +/********************************************************************** +* This file implements general matrix-vector multiplication using BLAS +* gemv function via partial specialization of +* general_matrix_vector_product::run(..) method for float, double, +* std::complex and std::complex types +**********************************************************************/ + +// gemv specialization + +template +struct general_matrix_vector_product_gemv : + general_matrix_vector_product {}; + +#define EIGEN_MKL_GEMV_SPECIALIZE(Scalar) \ +template \ +struct general_matrix_vector_product { \ +static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const Scalar* lhs, Index lhsStride, \ + const Scalar* rhs, Index rhsIncr, \ + Scalar* res, Index resIncr, Scalar alpha) \ +{ \ + if (ConjugateLhs) { \ + general_matrix_vector_product::run( \ + rows, cols, lhs, lhsStride, rhs, rhsIncr, res, resIncr, alpha); \ + } else { \ + general_matrix_vector_product_gemv::run( \ + rows, cols, lhs, lhsStride, rhs, rhsIncr, res, resIncr, alpha); \ + } \ +} \ +}; \ +template \ +struct general_matrix_vector_product { \ +static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const Scalar* lhs, Index lhsStride, \ + const Scalar* rhs, Index rhsIncr, \ + Scalar* res, Index resIncr, Scalar alpha) \ +{ \ + general_matrix_vector_product_gemv::run( \ + rows, cols, lhs, lhsStride, rhs, rhsIncr, res, resIncr, alpha); \ +} \ +}; \ + +EIGEN_MKL_GEMV_SPECIALIZE(double) +EIGEN_MKL_GEMV_SPECIALIZE(float) +EIGEN_MKL_GEMV_SPECIALIZE(dcomplex) +EIGEN_MKL_GEMV_SPECIALIZE(scomplex) + +#define EIGEN_MKL_GEMV_SPECIALIZATION(EIGTYPE,MKLTYPE,MKLPREFIX) \ +template \ +struct general_matrix_vector_product_gemv \ +{ \ +typedef Matrix GEMVVector;\ +\ +static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const EIGTYPE* lhs, Index lhsStride, \ + const EIGTYPE* rhs, Index rhsIncr, \ + EIGTYPE* res, Index resIncr, EIGTYPE alpha) \ +{ \ + MKL_INT m=rows, n=cols, lda=lhsStride, incx=rhsIncr, incy=resIncr; \ + MKLTYPE alpha_, beta_; \ + const EIGTYPE *x_ptr, myone(1); \ + char trans=(LhsStorageOrder==ColMajor) ? 'N' : (ConjugateLhs) ? 'C' : 'T'; \ + if (LhsStorageOrder==RowMajor) { \ + m=cols; \ + n=rows; \ + }\ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ + GEMVVector x_tmp; \ + if (ConjugateRhs) { \ + Map > map_x(rhs,cols,1,InnerStride<>(incx)); \ + x_tmp=map_x.conjugate(); \ + x_ptr=x_tmp.data(); \ + incx=1; \ + } else x_ptr=rhs; \ + MKLPREFIX##gemv(&trans, &m, &n, &alpha_, (const MKLTYPE*)lhs, &lda, (const MKLTYPE*)x_ptr, &incx, &beta_, (MKLTYPE*)res, &incy); \ +}\ +}; + +EIGEN_MKL_GEMV_SPECIALIZATION(double, double, d) +EIGEN_MKL_GEMV_SPECIALIZATION(float, float, s) +EIGEN_MKL_GEMV_SPECIALIZATION(dcomplex, MKL_Complex16, z) +EIGEN_MKL_GEMV_SPECIALIZATION(scomplex, MKL_Complex8, c) + +} // end namespase internal + +} // end namespace Eigen + +#endif // EIGEN_GENERAL_MATRIX_VECTOR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h index ecdedc363..725216162 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h @@ -25,6 +25,8 @@ #ifndef EIGEN_PARALLELIZER_H #define EIGEN_PARALLELIZER_H +namespace Eigen { + namespace internal { /** \internal */ @@ -55,12 +57,23 @@ inline void manage_multi_threading(Action action, int* v) } } +} + +/** Must be call first when calling Eigen from multiple threads */ +inline void initParallel() +{ + int nbt; + internal::manage_multi_threading(GetAction, &nbt); + std::ptrdiff_t l1, l2; + internal::manage_caching_sizes(GetAction, &l1, &l2); +} + /** \returns the max number of threads reserved for Eigen * \sa setNbThreads */ inline int nbThreads() { int ret; - manage_multi_threading(GetAction, &ret); + internal::manage_multi_threading(GetAction, &ret); return ret; } @@ -68,9 +81,11 @@ inline int nbThreads() * \sa nbThreads */ inline void setNbThreads(int v) { - manage_multi_threading(SetAction, &v); + internal::manage_multi_threading(SetAction, &v); } +namespace internal { + template struct GemmParallelInfo { GemmParallelInfo() : sync(-1), users(0), rhs_start(0), rhs_length(0) {} @@ -85,7 +100,9 @@ template struct GemmParallelInfo template void parallelize_gemm(const Functor& func, Index rows, Index cols, bool transpose) { -#ifndef EIGEN_HAS_OPENMP + // TODO when EIGEN_USE_BLAS is defined, + // we should still enable OMP for other scalar types +#if !(defined (EIGEN_HAS_OPENMP)) || defined (EIGEN_USE_BLAS) // FIXME the transpose variable is only needed to properly split // the matrix product when multithreading is enabled. This is a temporary // fix to support row-major destination matrices. This whole @@ -117,6 +134,7 @@ void parallelize_gemm(const Functor& func, Index rows, Index cols, bool transpos if(threads==1) return func(0,rows, 0,cols); + Eigen::initParallel(); func.initParallelSession(); if(transpose) @@ -151,4 +169,6 @@ void parallelize_gemm(const Functor& func, Index rows, Index cols, bool transpos } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_PARALLELIZER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix.h index ccd757cfa..91ba12081 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELFADJOINT_MATRIX_MATRIX_H #define EIGEN_SELFADJOINT_MATRIX_MATRIX_H +namespace Eigen { + namespace internal { // pack a selfadjoint block diagonal for use with the gebp_kernel @@ -400,8 +402,8 @@ struct SelfadjointProductMatrix { eigen_assert(dst.rows()==m_lhs.rows() && dst.cols()==m_rhs.cols()); - const ActualLhsType lhs = LhsBlasTraits::extract(m_lhs); - const ActualRhsType rhs = RhsBlasTraits::extract(m_rhs); + typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(m_lhs); + typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(m_rhs); Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(m_lhs) * RhsBlasTraits::extractScalarFactor(m_rhs); @@ -424,4 +426,6 @@ struct SelfadjointProductMatrix } }; +} // end namespace Eigen + #endif // EIGEN_SELFADJOINT_MATRIX_MATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h new file mode 100644 index 000000000..4e5c4125c --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h @@ -0,0 +1,295 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Self adjoint matrix * matrix product functionality based on ?SYMM/?HEMM. + ******************************************************************************** +*/ + +#ifndef EIGEN_SELFADJOINT_MATRIX_MATRIX_MKL_H +#define EIGEN_SELFADJOINT_MATRIX_MATRIX_MKL_H + +namespace Eigen { + +namespace internal { + + +/* Optimized selfadjoint matrix * matrix (?SYMM/?HEMM) product */ + +#define EIGEN_MKL_SYMM_L(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_selfadjoint_matrix \ +{\ +\ + static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + char side='L', uplo='L'; \ + MKL_INT m, n, lda, ldb, ldc; \ + const EIGTYPE *a, *b; \ + MKLTYPE alpha_, beta_; \ + MatrixX##EIGPREFIX b_tmp; \ + EIGTYPE myone(1);\ +\ +/* Set transpose options */ \ +/* Set m, n, k */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)cols; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ +\ +/* Set lda, ldb, ldc */ \ + lda = (MKL_INT)lhsStride; \ + ldb = (MKL_INT)rhsStride; \ + ldc = (MKL_INT)resStride; \ +\ +/* Set a, b, c */ \ + if (LhsStorageOrder==RowMajor) uplo='U'; \ + a = _lhs; \ +\ + if (RhsStorageOrder==RowMajor) { \ + Map > rhs(_rhs,n,m,OuterStride<>(rhsStride)); \ + b_tmp = rhs.adjoint(); \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ + } else b = _rhs; \ +\ + MKLPREFIX##symm(&side, &uplo, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (const MKLTYPE*)b, &ldb, &beta_, (MKLTYPE*)res, &ldc); \ +\ + } \ +}; + + +#define EIGEN_MKL_HEMM_L(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_selfadjoint_matrix \ +{\ + static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + char side='L', uplo='L'; \ + MKL_INT m, n, lda, ldb, ldc; \ + const EIGTYPE *a, *b; \ + MKLTYPE alpha_, beta_; \ + MatrixX##EIGPREFIX b_tmp; \ + Matrix a_tmp; \ + EIGTYPE myone(1); \ +\ +/* Set transpose options */ \ +/* Set m, n, k */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)cols; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ +\ +/* Set lda, ldb, ldc */ \ + lda = (MKL_INT)lhsStride; \ + ldb = (MKL_INT)rhsStride; \ + ldc = (MKL_INT)resStride; \ +\ +/* Set a, b, c */ \ + if (((LhsStorageOrder==ColMajor) && ConjugateLhs) || ((LhsStorageOrder==RowMajor) && (!ConjugateLhs))) { \ + Map, 0, OuterStride<> > lhs(_lhs,m,m,OuterStride<>(lhsStride)); \ + a_tmp = lhs.conjugate(); \ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else a = _lhs; \ + if (LhsStorageOrder==RowMajor) uplo='U'; \ +\ + if (RhsStorageOrder==ColMajor && (!ConjugateRhs)) { \ + b = _rhs; } \ + else { \ + if (RhsStorageOrder==ColMajor && ConjugateRhs) { \ + Map > rhs(_rhs,m,n,OuterStride<>(rhsStride)); \ + b_tmp = rhs.conjugate(); \ + } else \ + if (ConjugateRhs) { \ + Map > rhs(_rhs,n,m,OuterStride<>(rhsStride)); \ + b_tmp = rhs.adjoint(); \ + } else { \ + Map > rhs(_rhs,n,m,OuterStride<>(rhsStride)); \ + b_tmp = rhs.transpose(); \ + } \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ + } \ +\ + MKLPREFIX##hemm(&side, &uplo, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (const MKLTYPE*)b, &ldb, &beta_, (MKLTYPE*)res, &ldc); \ +\ + } \ +}; + +EIGEN_MKL_SYMM_L(double, double, d, d) +EIGEN_MKL_SYMM_L(float, float, f, s) +EIGEN_MKL_HEMM_L(dcomplex, MKL_Complex16, cd, z) +EIGEN_MKL_HEMM_L(scomplex, MKL_Complex8, cf, c) + + +/* Optimized matrix * selfadjoint matrix (?SYMM/?HEMM) product */ + +#define EIGEN_MKL_SYMM_R(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_selfadjoint_matrix \ +{\ +\ + static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + char side='R', uplo='L'; \ + MKL_INT m, n, lda, ldb, ldc; \ + const EIGTYPE *a, *b; \ + MKLTYPE alpha_, beta_; \ + MatrixX##EIGPREFIX b_tmp; \ + EIGTYPE myone(1);\ +\ +/* Set m, n, k */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)cols; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ +\ +/* Set lda, ldb, ldc */ \ + lda = (MKL_INT)rhsStride; \ + ldb = (MKL_INT)lhsStride; \ + ldc = (MKL_INT)resStride; \ +\ +/* Set a, b, c */ \ + if (RhsStorageOrder==RowMajor) uplo='U'; \ + a = _rhs; \ +\ + if (LhsStorageOrder==RowMajor) { \ + Map > lhs(_lhs,n,m,OuterStride<>(rhsStride)); \ + b_tmp = lhs.adjoint(); \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ + } else b = _lhs; \ +\ + MKLPREFIX##symm(&side, &uplo, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (const MKLTYPE*)b, &ldb, &beta_, (MKLTYPE*)res, &ldc); \ +\ + } \ +}; + + +#define EIGEN_MKL_HEMM_R(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_selfadjoint_matrix \ +{\ + static EIGEN_DONT_INLINE void run( \ + Index rows, Index cols, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + char side='R', uplo='L'; \ + MKL_INT m, n, lda, ldb, ldc; \ + const EIGTYPE *a, *b; \ + MKLTYPE alpha_, beta_; \ + MatrixX##EIGPREFIX b_tmp; \ + Matrix a_tmp; \ + EIGTYPE myone(1); \ +\ +/* Set m, n, k */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)cols; \ +\ +/* Set alpha_ & beta_ */ \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ +\ +/* Set lda, ldb, ldc */ \ + lda = (MKL_INT)rhsStride; \ + ldb = (MKL_INT)lhsStride; \ + ldc = (MKL_INT)resStride; \ +\ +/* Set a, b, c */ \ + if (((RhsStorageOrder==ColMajor) && ConjugateRhs) || ((RhsStorageOrder==RowMajor) && (!ConjugateRhs))) { \ + Map, 0, OuterStride<> > rhs(_rhs,n,n,OuterStride<>(rhsStride)); \ + a_tmp = rhs.conjugate(); \ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else a = _rhs; \ + if (RhsStorageOrder==RowMajor) uplo='U'; \ +\ + if (LhsStorageOrder==ColMajor && (!ConjugateLhs)) { \ + b = _lhs; } \ + else { \ + if (LhsStorageOrder==ColMajor && ConjugateLhs) { \ + Map > lhs(_lhs,m,n,OuterStride<>(lhsStride)); \ + b_tmp = lhs.conjugate(); \ + } else \ + if (ConjugateLhs) { \ + Map > lhs(_lhs,n,m,OuterStride<>(lhsStride)); \ + b_tmp = lhs.adjoint(); \ + } else { \ + Map > lhs(_lhs,n,m,OuterStride<>(lhsStride)); \ + b_tmp = lhs.transpose(); \ + } \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ + } \ +\ + MKLPREFIX##hemm(&side, &uplo, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (const MKLTYPE*)b, &ldb, &beta_, (MKLTYPE*)res, &ldc); \ + } \ +}; + +EIGEN_MKL_SYMM_R(double, double, d, d) +EIGEN_MKL_SYMM_R(float, float, f, s) +EIGEN_MKL_HEMM_R(dcomplex, MKL_Complex16, cd, z) +EIGEN_MKL_HEMM_R(scomplex, MKL_Complex8, cf, c) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_SELFADJOINT_MATRIX_MATRIX_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector.h index d6121fc07..7f39ef01a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELFADJOINT_MATRIX_VECTOR_H #define EIGEN_SELFADJOINT_MATRIX_VECTOR_H +namespace Eigen { + namespace internal { /* Optimized selfadjoint matrix * vector product: @@ -32,8 +34,15 @@ namespace internal { * the number of load/stores of the result by a factor 2 and to reduce * the instruction dependency. */ -template -static EIGEN_DONT_INLINE void product_selfadjoint_vector( + +template +struct selfadjoint_matrix_vector_product; + +template +struct selfadjoint_matrix_vector_product + +{ +static EIGEN_DONT_INLINE void run( Index size, const Scalar* lhs, Index lhsStride, const Scalar* _rhs, Index rhsIncr, @@ -85,14 +94,14 @@ static EIGEN_DONT_INLINE void product_selfadjoint_vector( Scalar t1 = cjAlpha * rhs[j+1]; Packet ptmp1 = pset1(t1); - Scalar t2 = 0; + Scalar t2(0); Packet ptmp2 = pset1(t2); - Scalar t3 = 0; + Scalar t3(0); Packet ptmp3 = pset1(t3); size_t starti = FirstTriangular ? 0 : j+2; size_t endi = FirstTriangular ? j : size; - size_t alignedStart = (starti) + first_aligned(&res[starti], endi-starti); + size_t alignedStart = (starti) + internal::first_aligned(&res[starti], endi-starti); size_t alignedEnd = alignedStart + ((endi-alignedStart)/(PacketSize))*(PacketSize); // TODO make sure this product is a real * complex and that the rhs is properly conjugated if needed @@ -148,7 +157,7 @@ static EIGEN_DONT_INLINE void product_selfadjoint_vector( register const Scalar* EIGEN_RESTRICT A0 = lhs + j*lhsStride; Scalar t1 = cjAlpha * rhs[j]; - Scalar t2 = 0; + Scalar t2(0); // TODO make sure this product is a real * complex and that the rhs is properly conjugated if needed res[j] += cjd.pmul(internal::real(A0[j]), t1); for (Index i=FirstTriangular ? 0 : j+1; i<(FirstTriangular ? j : size); i++) @@ -159,6 +168,7 @@ static EIGEN_DONT_INLINE void product_selfadjoint_vector( res[j] += alpha * t2; } } +}; } // end namespace internal @@ -193,8 +203,8 @@ struct SelfadjointProductMatrix eigen_assert(dest.rows()==m_lhs.rows() && dest.cols()==m_rhs.cols()); - const ActualLhsType lhs = LhsBlasTraits::extract(m_lhs); - const ActualRhsType rhs = RhsBlasTraits::extract(m_rhs); + typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(m_lhs); + typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(m_rhs); Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(m_lhs) * RhsBlasTraits::extractScalarFactor(m_rhs); @@ -232,7 +242,7 @@ struct SelfadjointProductMatrix } - internal::product_selfadjoint_vector::Flags&RowMajorBit) ? RowMajor : ColMajor, int(LhsUpLo), bool(LhsBlasTraits::NeedToConjugate), bool(RhsBlasTraits::NeedToConjugate)> + internal::selfadjoint_matrix_vector_product::Flags&RowMajorBit) ? RowMajor : ColMajor, int(LhsUpLo), bool(LhsBlasTraits::NeedToConjugate), bool(RhsBlasTraits::NeedToConjugate)>::run ( lhs.rows(), // size &lhs.coeffRef(0,0), lhs.outerStride(), // lhs info @@ -274,5 +284,6 @@ struct SelfadjointProductMatrix } }; +} // end namespace Eigen #endif // EIGEN_SELFADJOINT_MATRIX_VECTOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h new file mode 100644 index 000000000..f88d483b6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h @@ -0,0 +1,114 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Selfadjoint matrix-vector product functionality based on ?SYMV/HEMV. + ******************************************************************************** +*/ + +#ifndef EIGEN_SELFADJOINT_MATRIX_VECTOR_MKL_H +#define EIGEN_SELFADJOINT_MATRIX_VECTOR_MKL_H + +namespace Eigen { + +namespace internal { + +/********************************************************************** +* This file implements selfadjoint matrix-vector multiplication using BLAS +**********************************************************************/ + +// symv/hemv specialization + +template +struct selfadjoint_matrix_vector_product_symv : + selfadjoint_matrix_vector_product {}; + +#define EIGEN_MKL_SYMV_SPECIALIZE(Scalar) \ +template \ +struct selfadjoint_matrix_vector_product { \ +static EIGEN_DONT_INLINE void run( \ + Index size, const Scalar* lhs, Index lhsStride, \ + const Scalar* _rhs, Index rhsIncr, Scalar* res, Scalar alpha) { \ + enum {\ + IsColMajor = StorageOrder==ColMajor \ + }; \ + if (IsColMajor == ConjugateLhs) {\ + selfadjoint_matrix_vector_product::run( \ + size, lhs, lhsStride, _rhs, rhsIncr, res, alpha); \ + } else {\ + selfadjoint_matrix_vector_product_symv::run( \ + size, lhs, lhsStride, _rhs, rhsIncr, res, alpha); \ + }\ + } \ +}; \ + +EIGEN_MKL_SYMV_SPECIALIZE(double) +EIGEN_MKL_SYMV_SPECIALIZE(float) +EIGEN_MKL_SYMV_SPECIALIZE(dcomplex) +EIGEN_MKL_SYMV_SPECIALIZE(scomplex) + +#define EIGEN_MKL_SYMV_SPECIALIZATION(EIGTYPE,MKLTYPE,MKLFUNC) \ +template \ +struct selfadjoint_matrix_vector_product_symv \ +{ \ +typedef Matrix SYMVVector;\ +\ +static EIGEN_DONT_INLINE void run( \ +Index size, const EIGTYPE* lhs, Index lhsStride, \ +const EIGTYPE* _rhs, Index rhsIncr, EIGTYPE* res, EIGTYPE alpha) \ +{ \ + enum {\ + IsRowMajor = StorageOrder==RowMajor ? 1 : 0, \ + IsLower = UpLo == Lower ? 1 : 0 \ + }; \ + MKL_INT n=size, lda=lhsStride, incx=rhsIncr, incy=1; \ + MKLTYPE alpha_, beta_; \ + const EIGTYPE *x_ptr, myone(1); \ + char uplo=(IsRowMajor) ? (IsLower ? 'U' : 'L') : (IsLower ? 'L' : 'U'); \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, myone); \ + SYMVVector x_tmp; \ + if (ConjugateRhs) { \ + Map > map_x(_rhs,size,1,InnerStride<>(incx)); \ + x_tmp=map_x.conjugate(); \ + x_ptr=x_tmp.data(); \ + incx=1; \ + } else x_ptr=_rhs; \ + MKLFUNC(&uplo, &n, &alpha_, (const MKLTYPE*)lhs, &lda, (const MKLTYPE*)x_ptr, &incx, &beta_, (MKLTYPE*)res, &incy); \ +}\ +}; + +EIGEN_MKL_SYMV_SPECIALIZATION(double, double, dsymv) +EIGEN_MKL_SYMV_SPECIALIZATION(float, float, ssymv) +EIGEN_MKL_SYMV_SPECIALIZATION(dcomplex, MKL_Complex16, zhemv) +EIGEN_MKL_SYMV_SPECIALIZATION(scomplex, MKL_Complex8, chemv) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_SELFADJOINT_MATRIX_VECTOR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointProduct.h index 3a4523fa4..a3ff9e3e7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointProduct.h @@ -31,6 +31,8 @@ * It corresponds to the level 3 SYRK and level 2 SYR Blas routines. **********************************************************************/ +namespace Eigen { + template struct selfadjoint_rank1_update; @@ -72,7 +74,7 @@ struct selfadjoint_product_selector typedef internal::blas_traits OtherBlasTraits; typedef typename OtherBlasTraits::DirectLinearAccessType ActualOtherType; typedef typename internal::remove_all::type _ActualOtherType; - const ActualOtherType actualOther = OtherBlasTraits::extract(other.derived()); + typename internal::add_const_on_value_type::type actualOther = OtherBlasTraits::extract(other.derived()); Scalar actualAlpha = alpha * OtherBlasTraits::extractScalarFactor(other.derived()); @@ -105,12 +107,12 @@ struct selfadjoint_product_selector typedef internal::blas_traits OtherBlasTraits; typedef typename OtherBlasTraits::DirectLinearAccessType ActualOtherType; typedef typename internal::remove_all::type _ActualOtherType; - const ActualOtherType actualOther = OtherBlasTraits::extract(other.derived()); + typename internal::add_const_on_value_type::type actualOther = OtherBlasTraits::extract(other.derived()); Scalar actualAlpha = alpha * OtherBlasTraits::extractScalarFactor(other.derived()); enum { IsRowMajor = (internal::traits::Flags&RowMajorBit) ? 1 : 0 }; - + internal::general_matrix_matrix_triangular_product::IsComplex, Scalar, _ActualOtherType::Flags&RowMajorBit ? ColMajor : RowMajor, (!OtherBlasTraits::NeedToConjugate) && NumTraits::IsComplex, @@ -133,4 +135,6 @@ SelfAdjointView& SelfAdjointView return *this; } +} // end namespace Eigen + #endif // EIGEN_SELFADJOINT_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointRank2Update.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointRank2Update.h index 9f8b8438a..001cfb591 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointRank2Update.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/SelfadjointRank2Update.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SELFADJOINTRANK2UPTADE_H #define EIGEN_SELFADJOINTRANK2UPTADE_H +namespace Eigen { + namespace internal { /* Optimized selfadjoint matrix += alpha * uv' + conj(alpha)*vu' @@ -76,12 +78,12 @@ SelfAdjointView& SelfAdjointView typedef internal::blas_traits UBlasTraits; typedef typename UBlasTraits::DirectLinearAccessType ActualUType; typedef typename internal::remove_all::type _ActualUType; - const ActualUType actualU = UBlasTraits::extract(u.derived()); + typename internal::add_const_on_value_type::type actualU = UBlasTraits::extract(u.derived()); typedef internal::blas_traits VBlasTraits; typedef typename VBlasTraits::DirectLinearAccessType ActualVType; typedef typename internal::remove_all::type _ActualVType; - const ActualVType actualV = VBlasTraits::extract(v.derived()); + typename internal::add_const_on_value_type::type actualV = VBlasTraits::extract(v.derived()); // If MatrixType is row major, then we use the routine for lower triangular in the upper triangular case and // vice versa, and take the complex conjugate of all coefficients and vector entries. @@ -101,4 +103,6 @@ SelfAdjointView& SelfAdjointView return *this; } +} // end namespace Eigen + #endif // EIGEN_SELFADJOINTRANK2UPTADE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix.h index 0c48d2efb..06053bfd9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix.h @@ -25,6 +25,8 @@ #ifndef EIGEN_TRIANGULAR_MATRIX_MATRIX_H #define EIGEN_TRIANGULAR_MATRIX_MATRIX_H +namespace Eigen { + namespace internal { // template @@ -58,16 +60,16 @@ template + int ResStorageOrder, int Version = Specialized> struct product_triangular_matrix_matrix; template + int RhsStorageOrder, bool ConjugateRhs, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,RowMajor,Version> { static EIGEN_STRONG_INLINE void run( Index rows, Index cols, Index depth, @@ -91,15 +93,15 @@ struct product_triangular_matrix_matrix + int RhsStorageOrder, bool ConjugateRhs, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,ColMajor,Version> { typedef gebp_traits Traits; enum { - SmallPanelWidth = EIGEN_PLAIN_ENUM_MAX(Traits::mr,Traits::nr), + SmallPanelWidth = 2 * EIGEN_PLAIN_ENUM_MAX(Traits::mr,Traits::nr), IsLower = (Mode&Lower) == Lower, SetDiag = (Mode&(ZeroDiag|UnitDiag)) ? 0 : 1 }; @@ -220,10 +222,10 @@ struct product_triangular_matrix_matrix + int RhsStorageOrder, bool ConjugateRhs, int Version> struct product_triangular_matrix_matrix + RhsStorageOrder,ConjugateRhs,ColMajor,Version> { typedef gebp_traits Traits; enum { @@ -378,8 +380,8 @@ struct TriangularProduct template void scaleAndAddTo(Dest& dst, Scalar alpha) const { - const ActualLhsType lhs = LhsBlasTraits::extract(m_lhs); - const ActualRhsType rhs = RhsBlasTraits::extract(m_rhs); + typename internal::add_const_on_value_type::type lhs = LhsBlasTraits::extract(m_lhs); + typename internal::add_const_on_value_type::type rhs = RhsBlasTraits::extract(m_rhs); Scalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(m_lhs) * RhsBlasTraits::extractScalarFactor(m_rhs); @@ -399,5 +401,6 @@ struct TriangularProduct } }; +} // end namespace Eigen #endif // EIGEN_TRIANGULAR_MATRIX_MATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h new file mode 100644 index 000000000..8173da5bb --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h @@ -0,0 +1,309 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Triangular matrix * matrix product functionality based on ?TRMM. + ******************************************************************************** +*/ + +#ifndef EIGEN_TRIANGULAR_MATRIX_MATRIX_MKL_H +#define EIGEN_TRIANGULAR_MATRIX_MATRIX_MKL_H + +namespace Eigen { + +namespace internal { + + +template +struct product_triangular_matrix_matrix_trmm : + product_triangular_matrix_matrix {}; + + +// try to go to BLAS specialization +#define EIGEN_MKL_TRMM_SPECIALIZE(Scalar, LhsIsTriangular) \ +template \ +struct product_triangular_matrix_matrix { \ + static inline void run(Index _rows, Index _cols, Index _depth, const Scalar* _lhs, Index lhsStride,\ + const Scalar* _rhs, Index rhsStride, Scalar* res, Index resStride, Scalar alpha) { \ + product_triangular_matrix_matrix_trmm::run( \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha); \ + } \ +}; + +EIGEN_MKL_TRMM_SPECIALIZE(double, true) +EIGEN_MKL_TRMM_SPECIALIZE(double, false) +EIGEN_MKL_TRMM_SPECIALIZE(dcomplex, true) +EIGEN_MKL_TRMM_SPECIALIZE(dcomplex, false) +EIGEN_MKL_TRMM_SPECIALIZE(float, true) +EIGEN_MKL_TRMM_SPECIALIZE(float, false) +EIGEN_MKL_TRMM_SPECIALIZE(scomplex, true) +EIGEN_MKL_TRMM_SPECIALIZE(scomplex, false) + +// implements col-major += alpha * op(triangular) * op(general) +#define EIGEN_MKL_TRMM_L(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_triangular_matrix_matrix_trmm \ +{ \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + SetDiag = (Mode&(ZeroDiag|UnitDiag)) ? 0 : 1, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + LowUp = IsLower ? Lower : Upper, \ + conjA = ((LhsStorageOrder==ColMajor) && ConjugateLhs) ? 1 : 0 \ + }; \ +\ + static EIGEN_DONT_INLINE void run( \ + Index _rows, Index _cols, Index _depth, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + Index diagSize = (std::min)(_rows,_depth); \ + Index rows = IsLower ? _rows : diagSize; \ + Index depth = IsLower ? diagSize : _depth; \ + Index cols = _cols; \ +\ + typedef Matrix MatrixLhs; \ + typedef Matrix MatrixRhs; \ +\ +/* Non-square case - doesn't fit to MKL ?TRMM. Fall to default triangular product or call MKL ?GEMM*/ \ + if (rows != depth) { \ +\ + int nthr = mkl_domain_get_max_threads(MKL_BLAS); \ +\ + if (((nthr==1) && (((std::max)(rows,depth)-diagSize)/(double)diagSize < 0.5))) { \ + /* Most likely no benefit to call TRMM or GEMM from MKL*/ \ + product_triangular_matrix_matrix::run( \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha); \ + /*std::cout << "TRMM_L: A is not square! Go to Eigen TRMM implementation!\n";*/ \ + } else { \ + /* Make sense to call GEMM */ \ + Map > lhsMap(_lhs,rows,depth,OuterStride<>(lhsStride)); \ + MatrixLhs aa_tmp=lhsMap.template triangularView(); \ + MKL_INT aStride = aa_tmp.outerStride(); \ + gemm_blocking_space blocking(_rows,_cols,_depth); \ + general_matrix_matrix_product::run( \ + rows, cols, depth, aa_tmp.data(), aStride, _rhs, rhsStride, res, resStride, alpha, blocking, 0); \ +\ + /*std::cout << "TRMM_L: A is not square! Go to MKL GEMM implementation! " << nthr<<" \n";*/ \ + } \ + return; \ + } \ + char side = 'L', transa, uplo, diag = 'N'; \ + EIGTYPE *b; \ + const EIGTYPE *a; \ + MKL_INT m, n, lda, ldb; \ + MKLTYPE alpha_; \ +\ +/* Set alpha_*/ \ + assign_scalar_eig2mkl(alpha_, alpha); \ +\ +/* Set m, n */ \ + m = (MKL_INT)diagSize; \ + n = (MKL_INT)cols; \ +\ +/* Set trans */ \ + transa = (LhsStorageOrder==RowMajor) ? ((ConjugateLhs) ? 'C' : 'T') : 'N'; \ +\ +/* Set b, ldb */ \ + Map > rhs(_rhs,depth,cols,OuterStride<>(rhsStride)); \ + MatrixX##EIGPREFIX b_tmp; \ +\ + if (ConjugateRhs) b_tmp = rhs.conjugate(); else b_tmp = rhs; \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ +\ +/* Set uplo */ \ + uplo = IsLower ? 'L' : 'U'; \ + if (LhsStorageOrder==RowMajor) uplo = (uplo == 'L') ? 'U' : 'L'; \ +/* Set a, lda */ \ + Map > lhs(_lhs,rows,depth,OuterStride<>(lhsStride)); \ + MatrixLhs a_tmp; \ +\ + if ((conjA!=0) || (SetDiag==0)) { \ + if (conjA) a_tmp = lhs.conjugate(); else a_tmp = lhs; \ + if (IsZeroDiag) \ + a_tmp.diagonal().setZero(); \ + else if (IsUnitDiag) \ + a_tmp.diagonal().setOnes();\ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else { \ + a = _lhs; \ + lda = lhsStride; \ + } \ + /*std::cout << "TRMM_L: A is square! Go to MKL TRMM implementation! \n";*/ \ +/* call ?trmm*/ \ + MKLPREFIX##trmm(&side, &uplo, &transa, &diag, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (MKLTYPE*)b, &ldb); \ +\ +/* Add op(a_triangular)*b into res*/ \ + Map > res_tmp(res,rows,cols,OuterStride<>(resStride)); \ + res_tmp=res_tmp+b_tmp; \ + } \ +}; + +EIGEN_MKL_TRMM_L(double, double, d, d) +EIGEN_MKL_TRMM_L(dcomplex, MKL_Complex16, cd, z) +EIGEN_MKL_TRMM_L(float, float, f, s) +EIGEN_MKL_TRMM_L(scomplex, MKL_Complex8, cf, c) + +// implements col-major += alpha * op(general) * op(triangular) +#define EIGEN_MKL_TRMM_R(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct product_triangular_matrix_matrix_trmm \ +{ \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + SetDiag = (Mode&(ZeroDiag|UnitDiag)) ? 0 : 1, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + LowUp = IsLower ? Lower : Upper, \ + conjA = ((RhsStorageOrder==ColMajor) && ConjugateRhs) ? 1 : 0 \ + }; \ +\ + static EIGEN_DONT_INLINE void run( \ + Index _rows, Index _cols, Index _depth, \ + const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsStride, \ + EIGTYPE* res, Index resStride, \ + EIGTYPE alpha) \ + { \ + Index diagSize = (std::min)(_cols,_depth); \ + Index rows = _rows; \ + Index depth = IsLower ? _depth : diagSize; \ + Index cols = IsLower ? diagSize : _cols; \ +\ + typedef Matrix MatrixLhs; \ + typedef Matrix MatrixRhs; \ +\ +/* Non-square case - doesn't fit to MKL ?TRMM. Fall to default triangular product or call MKL ?GEMM*/ \ + if (cols != depth) { \ +\ + int nthr = mkl_domain_get_max_threads(MKL_BLAS); \ +\ + if ((nthr==1) && (((std::max)(cols,depth)-diagSize)/(double)diagSize < 0.5)) { \ + /* Most likely no benefit to call TRMM or GEMM from MKL*/ \ + product_triangular_matrix_matrix::run( \ + _rows, _cols, _depth, _lhs, lhsStride, _rhs, rhsStride, res, resStride, alpha); \ + /*std::cout << "TRMM_R: A is not square! Go to Eigen TRMM implementation!\n";*/ \ + } else { \ + /* Make sense to call GEMM */ \ + Map > rhsMap(_rhs,depth,cols, OuterStride<>(rhsStride)); \ + MatrixRhs aa_tmp=rhsMap.template triangularView(); \ + MKL_INT aStride = aa_tmp.outerStride(); \ + gemm_blocking_space blocking(_rows,_cols,_depth); \ + general_matrix_matrix_product::run( \ + rows, cols, depth, _lhs, lhsStride, aa_tmp.data(), aStride, res, resStride, alpha, blocking, 0); \ +\ + /*std::cout << "TRMM_R: A is not square! Go to MKL GEMM implementation! " << nthr<<" \n";*/ \ + } \ + return; \ + } \ + char side = 'R', transa, uplo, diag = 'N'; \ + EIGTYPE *b; \ + const EIGTYPE *a; \ + MKL_INT m, n, lda, ldb; \ + MKLTYPE alpha_; \ +\ +/* Set alpha_*/ \ + assign_scalar_eig2mkl(alpha_, alpha); \ +\ +/* Set m, n */ \ + m = (MKL_INT)rows; \ + n = (MKL_INT)diagSize; \ +\ +/* Set trans */ \ + transa = (RhsStorageOrder==RowMajor) ? ((ConjugateRhs) ? 'C' : 'T') : 'N'; \ +\ +/* Set b, ldb */ \ + Map > lhs(_lhs,rows,depth,OuterStride<>(lhsStride)); \ + MatrixX##EIGPREFIX b_tmp; \ +\ + if (ConjugateLhs) b_tmp = lhs.conjugate(); else b_tmp = lhs; \ + b = b_tmp.data(); \ + ldb = b_tmp.outerStride(); \ +\ +/* Set uplo */ \ + uplo = IsLower ? 'L' : 'U'; \ + if (RhsStorageOrder==RowMajor) uplo = (uplo == 'L') ? 'U' : 'L'; \ +/* Set a, lda */ \ + Map > rhs(_rhs,depth,cols, OuterStride<>(rhsStride)); \ + MatrixRhs a_tmp; \ +\ + if ((conjA!=0) || (SetDiag==0)) { \ + if (conjA) a_tmp = rhs.conjugate(); else a_tmp = rhs; \ + if (IsZeroDiag) \ + a_tmp.diagonal().setZero(); \ + else if (IsUnitDiag) \ + a_tmp.diagonal().setOnes();\ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else { \ + a = _rhs; \ + lda = rhsStride; \ + } \ + /*std::cout << "TRMM_R: A is square! Go to MKL TRMM implementation! \n";*/ \ +/* call ?trmm*/ \ + MKLPREFIX##trmm(&side, &uplo, &transa, &diag, &m, &n, &alpha_, (const MKLTYPE*)a, &lda, (MKLTYPE*)b, &ldb); \ +\ +/* Add op(a_triangular)*b into res*/ \ + Map > res_tmp(res,rows,cols,OuterStride<>(resStride)); \ + res_tmp=res_tmp+b_tmp; \ + } \ +}; + +EIGEN_MKL_TRMM_R(double, double, d, d) +EIGEN_MKL_TRMM_R(dcomplex, MKL_Complex16, cd, z) +EIGEN_MKL_TRMM_R(float, float, f, s) +EIGEN_MKL_TRMM_R(scomplex, MKL_Complex8, cf, c) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TRIANGULAR_MATRIX_MATRIX_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector.h index 71b4a52ab..e1dc0c23e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector.h @@ -25,23 +25,29 @@ #ifndef EIGEN_TRIANGULARMATRIXVECTOR_H #define EIGEN_TRIANGULARMATRIXVECTOR_H +namespace Eigen { + namespace internal { -template -struct product_triangular_matrix_vector; +template +struct triangular_matrix_vector_product; -template -struct product_triangular_matrix_vector +template +struct triangular_matrix_vector_product { typedef typename scalar_product_traits::ReturnType ResScalar; enum { IsLower = ((Mode&Lower)==Lower), - HasUnitDiag = (Mode & UnitDiag)==UnitDiag + HasUnitDiag = (Mode & UnitDiag)==UnitDiag, + HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag }; - static EIGEN_DONT_INLINE void run(Index rows, Index cols, const LhsScalar* _lhs, Index lhsStride, + static EIGEN_DONT_INLINE void run(Index _rows, Index _cols, const LhsScalar* _lhs, Index lhsStride, const RhsScalar* _rhs, Index rhsIncr, ResScalar* _res, Index resIncr, ResScalar alpha) { static const Index PanelWidth = EIGEN_TUNE_TRIANGULAR_PANEL_WIDTH; + Index size = (std::min)(_rows,_cols); + Index rows = IsLower ? _rows : (std::min)(_rows,_cols); + Index cols = IsLower ? (std::min)(_rows,_cols) : _cols; typedef Map, 0, OuterStride<> > LhsMap; const LhsMap lhs(_lhs,rows,cols,OuterStride<>(lhsStride)); @@ -54,45 +60,57 @@ struct product_triangular_matrix_vector > ResMap; ResMap res(_res,rows); - for (Index pi=0; pi0) + if ((!(HasUnitDiag||HasZeroDiag)) || (--r)>0) res.segment(s,r) += (alpha * cjRhs.coeff(i)) * cjLhs.col(i).segment(s,r); if (HasUnitDiag) res.coeffRef(i) += alpha * cjRhs.coeff(i); } - Index r = IsLower ? cols - pi - actualPanelWidth : pi; + Index r = IsLower ? rows - pi - actualPanelWidth : pi; if (r>0) { Index s = IsLower ? pi+actualPanelWidth : 0; - general_matrix_vector_product::run( + general_matrix_vector_product::run( r, actualPanelWidth, &lhs.coeffRef(s,pi), lhsStride, &rhs.coeffRef(pi), rhsIncr, &res.coeffRef(s), resIncr, alpha); } } + if((!IsLower) && cols>size) + { + general_matrix_vector_product::run( + rows, cols-size, + &lhs.coeffRef(0,size), lhsStride, + &rhs.coeffRef(size), rhsIncr, + _res, resIncr, alpha); + } } }; -template -struct product_triangular_matrix_vector +template +struct triangular_matrix_vector_product { typedef typename scalar_product_traits::ReturnType ResScalar; enum { IsLower = ((Mode&Lower)==Lower), - HasUnitDiag = (Mode & UnitDiag)==UnitDiag + HasUnitDiag = (Mode & UnitDiag)==UnitDiag, + HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag }; - static void run(Index rows, Index cols, const LhsScalar* _lhs, Index lhsStride, + static void run(Index _rows, Index _cols, const LhsScalar* _lhs, Index lhsStride, const RhsScalar* _rhs, Index rhsIncr, ResScalar* _res, Index resIncr, ResScalar alpha) { static const Index PanelWidth = EIGEN_TUNE_TRIANGULAR_PANEL_WIDTH; + Index diagSize = (std::min)(_rows,_cols); + Index rows = IsLower ? _rows : diagSize; + Index cols = IsLower ? diagSize : _cols; typedef Map, 0, OuterStride<> > LhsMap; const LhsMap lhs(_lhs,rows,cols,OuterStride<>(lhsStride)); @@ -105,15 +123,15 @@ struct product_triangular_matrix_vector, 0, InnerStride<> > ResMap; ResMap res(_res,rows,InnerStride<>(resIncr)); - for (Index pi=0; pi0) + if ((!(HasUnitDiag||HasZeroDiag)) || (--r)>0) res.coeffRef(i) += alpha * (cjLhs.row(i).segment(s,r).cwiseProduct(cjRhs.segment(s,r).transpose())).sum(); if (HasUnitDiag) res.coeffRef(i) += alpha * cjRhs.coeff(i); @@ -122,13 +140,21 @@ struct product_triangular_matrix_vector0) { Index s = IsLower ? 0 : pi + actualPanelWidth; - general_matrix_vector_product::run( + general_matrix_vector_product::run( actualPanelWidth, r, &lhs.coeffRef(pi,s), lhsStride, &rhs.coeffRef(s), rhsIncr, &res.coeffRef(pi), resIncr, alpha); } } + if(IsLower && rows>diagSize) + { + general_matrix_vector_product::run( + rows-diagSize, cols, + &lhs.coeffRef(diagSize,0), lhsStride, + &rhs.coeffRef(0), rhsIncr, + &res.coeffRef(diagSize), resIncr, alpha); + } } }; @@ -180,7 +206,7 @@ struct TriangularProduct { eigen_assert(dst.rows()==m_lhs.rows() && dst.cols()==m_rhs.cols()); - typedef TriangularProduct<(Mode & UnitDiag) | ((Mode & Lower) ? Upper : Lower),true,Transpose,false,Transpose,true> TriangularProductTranspose; + typedef TriangularProduct<(Mode & (UnitDiag|ZeroDiag)) | ((Mode & Lower) ? Upper : Lower),true,Transpose,false,Transpose,true> TriangularProductTranspose; Transpose dstT(dst); internal::trmv_selector<(int(internal::traits::Flags)&RowMajorBit) ? ColMajor : RowMajor>::run( TriangularProductTranspose(m_rhs.transpose(),m_lhs.transpose()), dstT, alpha); @@ -208,8 +234,8 @@ template<> struct trmv_selector typedef typename ProductType::RhsBlasTraits RhsBlasTraits; typedef Map, Aligned> MappedDest; - const ActualLhsType actualLhs = LhsBlasTraits::extract(prod.lhs()); - const ActualRhsType actualRhs = RhsBlasTraits::extract(prod.rhs()); + typename internal::add_const_on_value_type::type actualLhs = LhsBlasTraits::extract(prod.lhs()); + typename internal::add_const_on_value_type::type actualRhs = RhsBlasTraits::extract(prod.rhs()); ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) * RhsBlasTraits::extractScalarFactor(prod.rhs()); @@ -247,7 +273,7 @@ template<> struct trmv_selector MappedDest(actualDestPtr, dest.size()) = dest; } - internal::product_triangular_matrix_vector + internal::triangular_matrix_vector_product struct trmv_selector Map(actualRhsPtr, actualRhs.size()) = actualRhs; } - internal::product_triangular_matrix_vector + internal::triangular_matrix_vector_product struct trmv_selector } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_TRIANGULARMATRIXVECTOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector_MKL.h new file mode 100644 index 000000000..3c2c3049a --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularMatrixVector_MKL.h @@ -0,0 +1,247 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Triangular matrix-vector product functionality based on ?TRMV. + ******************************************************************************** +*/ + +#ifndef EIGEN_TRIANGULAR_MATRIX_VECTOR_MKL_H +#define EIGEN_TRIANGULAR_MATRIX_VECTOR_MKL_H + +namespace Eigen { + +namespace internal { + +/********************************************************************** +* This file implements triangular matrix-vector multiplication using BLAS +**********************************************************************/ + +// trmv/hemv specialization + +template +struct triangular_matrix_vector_product_trmv : + triangular_matrix_vector_product {}; + +#define EIGEN_MKL_TRMV_SPECIALIZE(Scalar) \ +template \ +struct triangular_matrix_vector_product { \ + static EIGEN_DONT_INLINE void run(Index _rows, Index _cols, const Scalar* _lhs, Index lhsStride, \ + const Scalar* _rhs, Index rhsIncr, Scalar* _res, Index resIncr, Scalar alpha) { \ + triangular_matrix_vector_product_trmv::run( \ + _rows, _cols, _lhs, lhsStride, _rhs, rhsIncr, _res, resIncr, alpha); \ + } \ +}; \ +template \ +struct triangular_matrix_vector_product { \ + static EIGEN_DONT_INLINE void run(Index _rows, Index _cols, const Scalar* _lhs, Index lhsStride, \ + const Scalar* _rhs, Index rhsIncr, Scalar* _res, Index resIncr, Scalar alpha) { \ + triangular_matrix_vector_product_trmv::run( \ + _rows, _cols, _lhs, lhsStride, _rhs, rhsIncr, _res, resIncr, alpha); \ + } \ +}; + +EIGEN_MKL_TRMV_SPECIALIZE(double) +EIGEN_MKL_TRMV_SPECIALIZE(float) +EIGEN_MKL_TRMV_SPECIALIZE(dcomplex) +EIGEN_MKL_TRMV_SPECIALIZE(scomplex) + +// implements col-major: res += alpha * op(triangular) * vector +#define EIGEN_MKL_TRMV_CM(EIGTYPE, MKLTYPE, EIGPREFIX, MKLPREFIX) \ +template \ +struct triangular_matrix_vector_product_trmv { \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + SetDiag = (Mode&(ZeroDiag|UnitDiag)) ? 0 : 1, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + LowUp = IsLower ? Lower : Upper \ + }; \ + static EIGEN_DONT_INLINE void run(Index _rows, Index _cols, const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsIncr, EIGTYPE* _res, Index resIncr, EIGTYPE alpha) \ + { \ + if (ConjLhs || IsZeroDiag) { \ + triangular_matrix_vector_product::run( \ + _rows, _cols, _lhs, lhsStride, _rhs, rhsIncr, _res, resIncr, alpha); \ + return; \ + }\ + Index size = (std::min)(_rows,_cols); \ + Index rows = IsLower ? _rows : size; \ + Index cols = IsLower ? size : _cols; \ +\ + typedef VectorX##EIGPREFIX VectorRhs; \ + EIGTYPE *x, *y;\ +\ +/* Set x*/ \ + Map > rhs(_rhs,cols,InnerStride<>(rhsIncr)); \ + VectorRhs x_tmp; \ + if (ConjRhs) x_tmp = rhs.conjugate(); else x_tmp = rhs; \ + x = x_tmp.data(); \ +\ +/* Square part handling */\ +\ + char trans, uplo, diag; \ + MKL_INT m, n, lda, incx, incy; \ + EIGTYPE const *a; \ + MKLTYPE alpha_, beta_; \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, EIGTYPE(1)); \ +\ +/* Set m, n */ \ + n = (MKL_INT)size; \ + lda = lhsStride; \ + incx = 1; \ + incy = resIncr; \ +\ +/* Set uplo, trans and diag*/ \ + trans = 'N'; \ + uplo = IsLower ? 'L' : 'U'; \ + diag = IsUnitDiag ? 'U' : 'N'; \ +\ +/* call ?TRMV*/ \ + MKLPREFIX##trmv(&uplo, &trans, &diag, &n, (const MKLTYPE*)_lhs, &lda, (MKLTYPE*)x, &incx); \ +\ +/* Add op(a_tr)rhs into res*/ \ + MKLPREFIX##axpy(&n, &alpha_,(const MKLTYPE*)x, &incx, (MKLTYPE*)_res, &incy); \ +/* Non-square case - doesn't fit to MKL ?TRMV. Fall to default triangular product*/ \ + if (size<(std::max)(rows,cols)) { \ + typedef Matrix MatrixLhs; \ + if (ConjRhs) x_tmp = rhs.conjugate(); else x_tmp = rhs; \ + x = x_tmp.data(); \ + if (size \ +struct triangular_matrix_vector_product_trmv { \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + SetDiag = (Mode&(ZeroDiag|UnitDiag)) ? 0 : 1, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + LowUp = IsLower ? Lower : Upper \ + }; \ + static EIGEN_DONT_INLINE void run(Index _rows, Index _cols, const EIGTYPE* _lhs, Index lhsStride, \ + const EIGTYPE* _rhs, Index rhsIncr, EIGTYPE* _res, Index resIncr, EIGTYPE alpha) \ + { \ + if (IsZeroDiag) { \ + triangular_matrix_vector_product::run( \ + _rows, _cols, _lhs, lhsStride, _rhs, rhsIncr, _res, resIncr, alpha); \ + return; \ + }\ + Index size = (std::min)(_rows,_cols); \ + Index rows = IsLower ? _rows : size; \ + Index cols = IsLower ? size : _cols; \ +\ + typedef VectorX##EIGPREFIX VectorRhs; \ + EIGTYPE *x, *y;\ +\ +/* Set x*/ \ + Map > rhs(_rhs,cols,InnerStride<>(rhsIncr)); \ + VectorRhs x_tmp; \ + if (ConjRhs) x_tmp = rhs.conjugate(); else x_tmp = rhs; \ + x = x_tmp.data(); \ +\ +/* Square part handling */\ +\ + char trans, uplo, diag; \ + MKL_INT m, n, lda, incx, incy; \ + EIGTYPE const *a; \ + MKLTYPE alpha_, beta_; \ + assign_scalar_eig2mkl(alpha_, alpha); \ + assign_scalar_eig2mkl(beta_, EIGTYPE(1)); \ +\ +/* Set m, n */ \ + n = (MKL_INT)size; \ + lda = lhsStride; \ + incx = 1; \ + incy = resIncr; \ +\ +/* Set uplo, trans and diag*/ \ + trans = ConjLhs ? 'C' : 'T'; \ + uplo = IsLower ? 'U' : 'L'; \ + diag = IsUnitDiag ? 'U' : 'N'; \ +\ +/* call ?TRMV*/ \ + MKLPREFIX##trmv(&uplo, &trans, &diag, &n, (const MKLTYPE*)_lhs, &lda, (MKLTYPE*)x, &incx); \ +\ +/* Add op(a_tr)rhs into res*/ \ + MKLPREFIX##axpy(&n, &alpha_,(const MKLTYPE*)x, &incx, (MKLTYPE*)_res, &incy); \ +/* Non-square case - doesn't fit to MKL ?TRMV. Fall to default triangular product*/ \ + if (size<(std::max)(rows,cols)) { \ + typedef Matrix MatrixLhs; \ + if (ConjRhs) x_tmp = rhs.conjugate(); else x_tmp = rhs; \ + x = x_tmp.data(); \ + if (size& blocking) { triangular_solve_matrix< Scalar, Index, Side==OnTheLeft?OnTheRight:OnTheLeft, (Mode&UnitDiag) | ((Mode&Upper) ? Lower : Upper), NumTraits::IsComplex && Conjugate, TriStorageOrder==RowMajor ? ColMajor : RowMajor, ColMajor> - ::run(size, cols, tri, triStride, _other, otherStride); + ::run(size, cols, tri, triStride, _other, otherStride, blocking); } }; @@ -53,7 +56,8 @@ struct triangular_solve_matrix& blocking) { Index cols = otherSize; const_blas_data_mapper tri(_tri,triStride); @@ -65,22 +69,29 @@ struct triangular_solve_matrix(kc, mc, nc); + Index kc = blocking.kc(); // cache block size along the K direction + Index mc = (std::min)(size,blocking.mc()); // cache block size along the M direction + std::size_t sizeA = kc*mc; + std::size_t sizeB = kc*cols; std::size_t sizeW = kc*Traits::WorkSpaceFactor; - std::size_t sizeB = sizeW + kc*cols; - ei_declare_aligned_stack_constructed_variable(Scalar, blockA, kc*mc, 0); - ei_declare_aligned_stack_constructed_variable(Scalar, allocatedBlockB, sizeB, 0); - Scalar* blockB = allocatedBlockB + sizeW; + + ei_declare_aligned_stack_constructed_variable(Scalar, blockA, sizeA, blocking.blockA()); + ei_declare_aligned_stack_constructed_variable(Scalar, blockB, sizeB, blocking.blockB()); + ei_declare_aligned_stack_constructed_variable(Scalar, blockW, sizeW, blocking.blockW()); conj_if conj; gebp_kernel gebp_kernel; gemm_pack_lhs pack_lhs; gemm_pack_rhs pack_rhs; + // the goal here is to subdivise the Rhs panels such that we keep some cache + // coherence when accessing the rhs elements + std::ptrdiff_t l1, l2; + manage_caching_sizes(GetAction, &l1, &l2); + Index subcols = cols>0 ? l2/(4 * sizeof(Scalar) * otherStride) : 0; + subcols = std::max((subcols/Traits::nr)*Traits::nr, Traits::nr); + for(Index k2=IsLower ? 0 : size; IsLower ? k20; IsLower ? k2+=kc : k2-=kc) @@ -92,16 +103,18 @@ struct triangular_solve_matrix general block copy (done during the next step) - // - R1 = L1^-1 B => tricky part + // - R1 = A11^-1 B => tricky part // - update B from the new R1 => actually this has to be performed continuously during the above step - // - R2 = L2 * B => GEPP + // - R2 -= A21 * B => GEPP - // The tricky part: compute R1 = L1^-1 B while updating B from R1 - // The idea is to split L1 into multiple small vertical panels. - // Each panel can be split into a small triangular part A1 which is processed without optimization, - // and the remaining small part A2 which is processed using gebp with appropriate block strides + // The tricky part: compute R1 = A11^-1 B while updating B from R1 + // The idea is to split A11 into multiple small vertical panels. + // Each panel can be split into a small triangular part T1k which is processed without optimization, + // and the remaining small part T2k which is processed using gebp with appropriate block strides + for(Index j2=0; j2(actual_kc-k1, SmallPanelWidth); @@ -114,11 +127,11 @@ struct triangular_solve_matrix0) @@ -152,13 +165,13 @@ struct triangular_solve_matrix GEPP + + // R2 -= A21 * B => GEPP { Index start = IsLower ? k2+kc : 0; Index end = IsLower ? size : k2-kc; @@ -169,7 +182,7 @@ struct triangular_solve_matrix& blocking) { Index rows = otherSize; const_blas_data_mapper rhs(_tri,triStride); @@ -198,19 +212,16 @@ struct triangular_solve_matrix(Traits::Max_kc/4,size); // cache block size along the K direction -// Index mc = std::min(Traits::Max_mc,size); // cache block size along the M direction - // check that !!!! - Index kc = size; // cache block size along the K direction - Index mc = size; // cache block size along the M direction - Index nc = rows; // cache block size along the N direction - computeProductBlockingSizes(kc, mc, nc); + Index kc = blocking.kc(); // cache block size along the K direction + Index mc = (std::min)(rows,blocking.mc()); // cache block size along the M direction + std::size_t sizeA = kc*mc; + std::size_t sizeB = kc*size; std::size_t sizeW = kc*Traits::WorkSpaceFactor; - std::size_t sizeB = sizeW + kc*size; - ei_declare_aligned_stack_constructed_variable(Scalar, blockA, kc*mc, 0); - ei_declare_aligned_stack_constructed_variable(Scalar, allocatedBlockB, sizeB, 0); - Scalar* blockB = allocatedBlockB + sizeW; + + ei_declare_aligned_stack_constructed_variable(Scalar, blockA, sizeA, blocking.blockA()); + ei_declare_aligned_stack_constructed_variable(Scalar, blockB, sizeB, blocking.blockB()); + ei_declare_aligned_stack_constructed_variable(Scalar, blockW, sizeW, blocking.blockW()); conj_if conj; gebp_kernel gebp_kernel; @@ -277,7 +288,7 @@ struct triangular_solve_matrix0) gebp_kernel(_other+i2+startPanel*otherStride, otherStride, blockA, geb, actual_mc, actual_kc, rs, Scalar(-1), - -1, -1, 0, 0, allocatedBlockB); + -1, -1, 0, 0, blockW); } } } @@ -316,4 +327,6 @@ struct triangular_solve_matrix \ +struct triangular_solve_matrix \ +{ \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + conjA = ((TriStorageOrder==ColMajor) && Conjugate) ? 1 : 0 \ + }; \ + static EIGEN_DONT_INLINE void run( \ + Index size, Index otherSize, \ + const EIGTYPE* _tri, Index triStride, \ + EIGTYPE* _other, Index otherStride, level3_blocking& /*blocking*/) \ + { \ + MKL_INT m = size, n = otherSize, lda, ldb; \ + char side = 'L', uplo, diag='N', transa; \ + /* Set alpha_ */ \ + MKLTYPE alpha; \ + EIGTYPE myone(1); \ + assign_scalar_eig2mkl(alpha, myone); \ + ldb = otherStride;\ +\ + const EIGTYPE *a; \ +/* Set trans */ \ + transa = (TriStorageOrder==RowMajor) ? ((Conjugate) ? 'C' : 'T') : 'N'; \ +/* Set uplo */ \ + uplo = IsLower ? 'L' : 'U'; \ + if (TriStorageOrder==RowMajor) uplo = (uplo == 'L') ? 'U' : 'L'; \ +/* Set a, lda */ \ + typedef Matrix MatrixTri; \ + Map > tri(_tri,size,size,OuterStride<>(triStride)); \ + MatrixTri a_tmp; \ +\ + if (conjA) { \ + a_tmp = tri.conjugate(); \ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else { \ + a = _tri; \ + lda = triStride; \ + } \ + if (IsUnitDiag) diag='U'; \ +/* call ?trsm*/ \ + MKLPREFIX##trsm(&side, &uplo, &transa, &diag, &m, &n, &alpha, (const MKLTYPE*)a, &lda, (MKLTYPE*)_other, &ldb); \ + } \ +}; + +EIGEN_MKL_TRSM_L(double, double, d) +EIGEN_MKL_TRSM_L(dcomplex, MKL_Complex16, z) +EIGEN_MKL_TRSM_L(float, float, s) +EIGEN_MKL_TRSM_L(scomplex, MKL_Complex8, c) + + +// implements RightSide general * op(triangular)^-1 +#define EIGEN_MKL_TRSM_R(EIGTYPE, MKLTYPE, MKLPREFIX) \ +template \ +struct triangular_solve_matrix \ +{ \ + enum { \ + IsLower = (Mode&Lower) == Lower, \ + IsUnitDiag = (Mode&UnitDiag) ? 1 : 0, \ + IsZeroDiag = (Mode&ZeroDiag) ? 1 : 0, \ + conjA = ((TriStorageOrder==ColMajor) && Conjugate) ? 1 : 0 \ + }; \ + static EIGEN_DONT_INLINE void run( \ + Index size, Index otherSize, \ + const EIGTYPE* _tri, Index triStride, \ + EIGTYPE* _other, Index otherStride, level3_blocking& /*blocking*/) \ + { \ + MKL_INT m = otherSize, n = size, lda, ldb; \ + char side = 'R', uplo, diag='N', transa; \ + /* Set alpha_ */ \ + MKLTYPE alpha; \ + EIGTYPE myone(1); \ + assign_scalar_eig2mkl(alpha, myone); \ + ldb = otherStride;\ +\ + const EIGTYPE *a; \ +/* Set trans */ \ + transa = (TriStorageOrder==RowMajor) ? ((Conjugate) ? 'C' : 'T') : 'N'; \ +/* Set uplo */ \ + uplo = IsLower ? 'L' : 'U'; \ + if (TriStorageOrder==RowMajor) uplo = (uplo == 'L') ? 'U' : 'L'; \ +/* Set a, lda */ \ + typedef Matrix MatrixTri; \ + Map > tri(_tri,size,size,OuterStride<>(triStride)); \ + MatrixTri a_tmp; \ +\ + if (conjA) { \ + a_tmp = tri.conjugate(); \ + a = a_tmp.data(); \ + lda = a_tmp.outerStride(); \ + } else { \ + a = _tri; \ + lda = triStride; \ + } \ + if (IsUnitDiag) diag='U'; \ +/* call ?trsm*/ \ + MKLPREFIX##trsm(&side, &uplo, &transa, &diag, &m, &n, &alpha, (const MKLTYPE*)a, &lda, (MKLTYPE*)_other, &ldb); \ + /*std::cout << "TRMS_L specialization!\n";*/ \ + } \ +}; + +EIGEN_MKL_TRSM_R(double, double, d) +EIGEN_MKL_TRSM_R(dcomplex, MKL_Complex16, z) +EIGEN_MKL_TRSM_R(float, float, s) +EIGEN_MKL_TRSM_R(scomplex, MKL_Complex8, c) + + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_TRIANGULAR_SOLVER_MATRIX_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularSolverVector.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularSolverVector.h index 639d4a5b4..f83a81061 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularSolverVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/TriangularSolverVector.h @@ -25,6 +25,8 @@ #ifndef EIGEN_TRIANGULAR_SOLVER_VECTOR_H #define EIGEN_TRIANGULAR_SOLVER_VECTOR_H +namespace Eigen { + namespace internal { template @@ -147,4 +149,6 @@ struct triangular_solve_vector struct general_matrix_matrix_product; -template +template struct general_matrix_vector_product; @@ -56,11 +58,15 @@ template struct conj_if; template<> struct conj_if { template inline T operator()(const T& x) { return conj(x); } + template + inline T pconj(const T& x) { return internal::pconj(x); } }; template<> struct conj_if { template inline const T& operator()(const T& x) { return x; } + template + inline const T& pconj(const T& x) { return x; } }; template struct conj_helper @@ -118,11 +124,11 @@ template struct conj_helper struct get_factor { - EIGEN_STRONG_INLINE static To run(const From& x) { return x; } + static EIGEN_STRONG_INLINE To run(const From& x) { return x; } }; template struct get_factor::Real> { - EIGEN_STRONG_INLINE static typename NumTraits::Real run(const Scalar& x) { return real(x); } + static EIGEN_STRONG_INLINE typename NumTraits::Real run(const Scalar& x) { return real(x); } }; // Lightweight helper class to access matrix coefficients. @@ -175,7 +181,7 @@ template struct blas_traits ExtractType, typename _ExtractType::PlainObject >::type DirectLinearAccessType; - static inline const ExtractType extract(const XprType& x) { return x; } + static inline ExtractType extract(const XprType& x) { return x; } static inline const Scalar extractScalarFactor(const XprType&) { return Scalar(1); } }; @@ -192,7 +198,7 @@ struct blas_traits, NestedXpr> > IsComplex = NumTraits::IsComplex, NeedToConjugate = Base::NeedToConjugate ? 0 : IsComplex }; - static inline const ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } + static inline ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } static inline Scalar extractScalarFactor(const XprType& x) { return conj(Base::extractScalarFactor(x.nestedExpression())); } }; @@ -204,7 +210,7 @@ struct blas_traits, NestedXpr> > typedef blas_traits Base; typedef CwiseUnaryOp, NestedXpr> XprType; typedef typename Base::ExtractType ExtractType; - static inline const ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } + static inline ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } static inline Scalar extractScalarFactor(const XprType& x) { return x.functor().m_other * Base::extractScalarFactor(x.nestedExpression()); } }; @@ -217,7 +223,7 @@ struct blas_traits, NestedXpr> > typedef blas_traits Base; typedef CwiseUnaryOp, NestedXpr> XprType; typedef typename Base::ExtractType ExtractType; - static inline const ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } + static inline ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } static inline Scalar extractScalarFactor(const XprType& x) { return - Base::extractScalarFactor(x.nestedExpression()); } }; @@ -239,7 +245,7 @@ struct blas_traits > enum { IsTransposed = Base::IsTransposed ? 0 : 1 }; - static inline const ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } + static inline ExtractType extract(const XprType& x) { return Base::extract(x.nestedExpression()); } static inline Scalar extractScalarFactor(const XprType& x) { return Base::extractScalarFactor(x.nestedExpression()); } }; @@ -252,7 +258,7 @@ template::HasUsableDirectA struct extract_data_selector { static const typename T::Scalar* run(const T& m) { - return const_cast(&blas_traits::extract(m).coeffRef(0,0)); // FIXME this should be .data() + return blas_traits::extract(m).data(); } }; @@ -268,4 +274,6 @@ template const typename T::Scalar* extract_data(const T& m) } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_BLASUTIL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Constants.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Constants.h index c3dd3a09d..f34aac85a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Constants.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Constants.h @@ -26,6 +26,8 @@ #ifndef EIGEN_CONSTANTS_H #define EIGEN_CONSTANTS_H +namespace Eigen { + /** This value means that a quantity is not known at compile-time, and that instead the value is * stored in some runtime variable. * @@ -188,7 +190,9 @@ enum { /** View matrix as an upper triangular matrix with zeros on the diagonal. */ StrictlyUpper=ZeroDiag|Upper, /** Used in BandMatrix and SelfAdjointView to indicate that the matrix is self-adjoint. */ - SelfAdjoint=0x10 + SelfAdjoint=0x10, + /** Used to support symmetric, non-selfadjoint, complex matrices. */ + Symmetric=0x20 }; /** \ingroup enums @@ -200,8 +204,6 @@ enum { Aligned=1 }; -enum { ConditionalJumpCost = 5 }; - /** \ingroup enums * Enum used by DenseBase::corner() in Eigen2 compatibility mode. */ // FIXME after the corner() API change, this was not needed anymore, except by AlignedBox @@ -223,8 +225,6 @@ enum DirectionType { BothDirections }; -enum ProductEvaluationMode { NormalProduct, CacheFriendlyProduct }; - /** \internal \ingroup enums * Enum to specify how to traverse the entries of a matrix. */ enum { @@ -257,6 +257,13 @@ enum { CompleteUnrolling }; +/** \internal \ingroup enums + * Enum to specify whether to use the default (built-in) implementation or the specialization. */ +enum { + Specialized, + BuiltIn +}; + /** \ingroup enums * Enum containing possible values for the \p _Options template parameter of * Matrix, Array and BandMatrix. */ @@ -280,26 +287,21 @@ enum { OnTheRight = 2 }; -/* the following could as well be written: - * enum NoChange_t { NoChange }; - * but it feels dangerous to disambiguate overloaded functions on enum/integer types. - * If on some platform it is really impossible to get rid of "unused variable" warnings, then - * we can always come back to that solution. +/* the following used to be written as: + * + * struct NoChange_t {}; + * namespace { + * EIGEN_UNUSED NoChange_t NoChange; + * } + * + * on the ground that it feels dangerous to disambiguate overloaded functions on enum/integer types. + * However, this leads to "variable declared but never referenced" warnings on Intel Composer XE, + * and we do not know how to get rid of them (bug 450). */ -struct NoChange_t {}; -namespace { - EIGEN_UNUSED NoChange_t NoChange; -} -struct Sequential_t {}; -namespace { - EIGEN_UNUSED Sequential_t Sequential; -} - -struct Default_t {}; -namespace { - EIGEN_UNUSED Default_t Default; -} +enum NoChange_t { NoChange }; +enum Sequential_t { Sequential }; +enum Default_t { Default }; /** \internal \ingroup enums * Used in AmbiVector. */ @@ -375,7 +377,7 @@ enum QRPreconditioners { #error The preprocessor symbol 'Success' is defined, possibly by the X11 header file X.h #endif -/** \ingroups enums +/** \ingroup enums * Enum for reporting the status of a computation. */ enum ComputationInfo { /** Computation was successful. */ @@ -383,7 +385,10 @@ enum ComputationInfo { /** The provided data did not satisfy the prerequisites. */ NumericalIssue = 1, /** Iterative procedure did not converge. */ - NoConvergence = 2 + NoConvergence = 2, + /** The inputs are invalid, or the algorithm has been improperly called. + * When assertions are enabled, such errors trigger an assert. */ + InvalidInput = 3 }; /** \ingroup enums @@ -436,4 +441,6 @@ struct MatrixXpr {}; /** The type used to identify an array expression */ struct ArrayXpr {}; +} // end namespace Eigen + #endif // EIGEN_CONSTANTS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/DisableStupidWarnings.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/DisableStupidWarnings.h index 00730524b..6a0bf0629 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/DisableStupidWarnings.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/DisableStupidWarnings.h @@ -21,15 +21,13 @@ #elif defined __INTEL_COMPILER // 2196 - routine is both "inline" and "noinline" ("noinline" assumed) // ICC 12 generates this warning even without any inline keyword, when defining class methods 'inline' i.e. inside of class body - // 2536 - type qualifiers are meaningless here - // ICC 12 generates this warning when a function return type is const qualified, even if that type is a template-parameter-dependent // typedef that may be a reference type. // 279 - controlling expression is constant // ICC 12 generates this warning on assert(constant_expression_depending_on_template_params) and frankly this is a legitimate use case. #ifndef EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS #pragma warning push #endif - #pragma warning disable 2196 2536 279 + #pragma warning disable 2196 279 #elif defined __clang__ // -Wconstant-logical-operand - warning: use of logical && with constant operand; switch to bitwise & or remove constant // this is really a stupid warning as it warns on compile-time expressions involving enums diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/ForwardDeclarations.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/ForwardDeclarations.h index 7fbccf98c..e5303f052 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/ForwardDeclarations.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/ForwardDeclarations.h @@ -26,6 +26,7 @@ #ifndef EIGEN_FORWARDDECLARATIONS_H #define EIGEN_FORWARDDECLARATIONS_H +namespace Eigen { namespace internal { template struct traits; @@ -133,6 +134,7 @@ template class WithFormat; template struct CommaInitializer; template class ReturnByValue; template class ArrayWrapper; +template class MatrixWrapper; namespace internal { template struct solve_retval_base; @@ -282,6 +284,8 @@ template class Homogeneous; // MatrixFunctions module template struct MatrixExponentialReturnValue; template class MatrixFunctionReturnValue; +template class MatrixSquareRootReturnValue; +template class MatrixLogarithmReturnValue; namespace internal { template @@ -304,4 +308,6 @@ template struct eigen2_part_return_type; } #endif +} // end namespace Eigen + #endif // EIGEN_FORWARDDECLARATIONS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h new file mode 100644 index 000000000..1e6e355d6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h @@ -0,0 +1,109 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Include file with common MKL declarations + ******************************************************************************** +*/ + +#ifndef EIGEN_MKL_SUPPORT_H +#define EIGEN_MKL_SUPPORT_H + +#ifdef EIGEN_USE_MKL_ALL + #ifndef EIGEN_USE_BLAS + #define EIGEN_USE_BLAS + #endif + #ifndef EIGEN_USE_LAPACKE + #define EIGEN_USE_LAPACKE + #endif + #ifndef EIGEN_USE_MKL_VML + #define EIGEN_USE_MKL_VML + #endif +#endif + +#ifdef EIGEN_USE_LAPACKE_STRICT + #define EIGEN_USE_LAPACKE +#endif + +#if defined(EIGEN_USE_BLAS) || defined(EIGEN_USE_LAPACKE) || defined(EIGEN_USE_MKL_VML) + #define EIGEN_USE_MKL +#endif + +#if defined EIGEN_USE_MKL + +#include +#include +#define EIGEN_MKL_VML_THRESHOLD 128 + +namespace Eigen { + +typedef std::complex dcomplex; +typedef std::complex scomplex; + +namespace internal { + +template +static inline void assign_scalar_eig2mkl(MKLType& mklScalar, const EigenType& eigenScalar) { + mklScalar=eigenScalar; +} + +template +static inline void assign_conj_scalar_eig2mkl(MKLType& mklScalar, const EigenType& eigenScalar) { + mklScalar=eigenScalar; +} + +template <> +inline void assign_scalar_eig2mkl(MKL_Complex16& mklScalar, const dcomplex& eigenScalar) { + mklScalar.real=eigenScalar.real(); + mklScalar.imag=eigenScalar.imag(); +} + +template <> +inline void assign_scalar_eig2mkl(MKL_Complex8& mklScalar, const scomplex& eigenScalar) { + mklScalar.real=eigenScalar.real(); + mklScalar.imag=eigenScalar.imag(); +} + +template <> +inline void assign_conj_scalar_eig2mkl(MKL_Complex16& mklScalar, const dcomplex& eigenScalar) { + mklScalar.real=eigenScalar.real(); + mklScalar.imag=-eigenScalar.imag(); +} + +template <> +inline void assign_conj_scalar_eig2mkl(MKL_Complex8& mklScalar, const scomplex& eigenScalar) { + mklScalar.real=eigenScalar.real(); + mklScalar.imag=-eigenScalar.imag(); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif + +#endif // EIGEN_MKL_SUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h index b7c2b79af..b361a05d4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h @@ -1,4 +1,3 @@ - // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // @@ -28,8 +27,8 @@ #define EIGEN_MACROS_H #define EIGEN_WORLD_VERSION 3 -#define EIGEN_MAJOR_VERSION 0 -#define EIGEN_MINOR_VERSION 5 +#define EIGEN_MAJOR_VERSION 1 +#define EIGEN_MINOR_VERSION 0 #define EIGEN_VERSION_AT_LEAST(x,y,z) (EIGEN_WORLD_VERSION>x || (EIGEN_WORLD_VERSION>=x && \ (EIGEN_MAJOR_VERSION>y || (EIGEN_MAJOR_VERSION>=y && \ @@ -235,12 +234,16 @@ #define EIGEN_ONLY_USED_FOR_DEBUG(x) #endif -#if (defined __GNUC__) -#define EIGEN_DEPRECATED __attribute__((deprecated)) -#elif (defined _MSC_VER) -#define EIGEN_DEPRECATED __declspec(deprecated) +#ifndef EIGEN_NO_DEPRECATED_WARNING + #if (defined __GNUC__) + #define EIGEN_DEPRECATED __attribute__((deprecated)) + #elif (defined _MSC_VER) + #define EIGEN_DEPRECATED __declspec(deprecated) + #else + #define EIGEN_DEPRECATED + #endif #else -#define EIGEN_DEPRECATED + #define EIGEN_DEPRECATED #endif #if (defined __GNUC__) @@ -252,7 +255,7 @@ // Suppresses 'unused variable' warnings. #define EIGEN_UNUSED_VARIABLE(var) (void)var; -#if (defined __GNUC__) +#if !defined(EIGEN_ASM_COMMENT) && (defined __GNUC__) #define EIGEN_ASM_COMMENT(X) asm("#" X) #else #define EIGEN_ASM_COMMENT(X) @@ -265,7 +268,7 @@ * If we made alignment depend on whether or not EIGEN_VECTORIZE is defined, it would be impossible to link * vectorized and non-vectorized code. */ -#if (defined __GNUC__) || (defined __PGI) || (defined __IBMCPP__) +#if (defined __GNUC__) || (defined __PGI) || (defined __IBMCPP__) || (defined __ARMCC_VERSION) #define EIGEN_ALIGN_TO_BOUNDARY(n) __attribute__((aligned(n))) #elif (defined _MSC_VER) #define EIGEN_ALIGN_TO_BOUNDARY(n) __declspec(align(n)) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h index 023716dc9..56a16b5cb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h @@ -80,6 +80,8 @@ #define EIGEN_HAS_MM_MALLOC 0 #endif +namespace Eigen { + namespace internal { inline void throw_std_bad_alloc() @@ -457,7 +459,7 @@ template inline void conditional_aligned_delete_auto(T * * There is also the variant first_aligned(const MatrixBase&) defined in DenseCoeffsBase.h. */ template -inline static Index first_aligned(const Scalar* array, Index size) +static inline Index first_aligned(const Scalar* array, Index size) { typedef typename packet_traits::type Packet; enum { PacketSize = packet_traits::size, @@ -483,7 +485,26 @@ inline static Index first_aligned(const Scalar* array, Index size) } } -} // end namespace internal + +// std::copy is much slower than memcpy, so let's introduce a smart_copy which +// use memcpy on trivial types, i.e., on types that does not require an initialization ctor. +template struct smart_copy_helper; + +template void smart_copy(const T* start, const T* end, T* target) +{ + smart_copy_helper::RequireInitialization>::run(start, end, target); +} + +template struct smart_copy_helper { + static inline void run(const T* start, const T* end, T* target) + { memcpy(target, start, std::ptrdiff_t(end)-std::ptrdiff_t(start)); } +}; + +template struct smart_copy_helper { + static inline void run(const T* start, const T* end, T* target) + { std::copy(start, end, target); } +}; + /***************************************************************************** *** Implementation of runtime stack allocation (falling back to malloc) *** @@ -499,8 +520,6 @@ inline static Index first_aligned(const Scalar* array, Index size) #endif #endif -namespace internal { - // This helper class construct the allocated memory, and takes care of destructing and freeing the handled data // at destruction time. In practice this helper class is mainly useful to avoid memory leak in case of exceptions. template class aligned_stack_memory_handler @@ -531,14 +550,14 @@ template class aligned_stack_memory_handler bool m_deallocate; }; -} +} // end namespace internal /** \internal * Declares, allocates and construct an aligned buffer named NAME of SIZE elements of type TYPE on the stack * if SIZE is smaller than EIGEN_STACK_ALLOCATION_LIMIT, and if stack allocation is supported by the platform * (currently, this is Linux and Visual Studio only). Otherwise the memory is allocated on the heap. * The allocated buffer is automatically deleted when exiting the scope of this declaration. - * If BUFFER is non nul, then the declared variable is simply an alias for BUFFER, and no allocation/deletion occurs. + * If BUFFER is non null, then the declared variable is simply an alias for BUFFER, and no allocation/deletion occurs. * Here is an example: * \code * { @@ -619,7 +638,7 @@ template class aligned_stack_memory_handler #define EIGEN_MAKE_ALIGNED_OPERATOR_NEW EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(true) #define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar,Size) \ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(((Size)!=Eigen::Dynamic) && ((sizeof(Scalar)*(Size))%16==0)) + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool(((Size)!=Eigen::Dynamic) && ((sizeof(Scalar)*(Size))%16==0))) /****************************************************************************/ @@ -667,24 +686,24 @@ public: return &value; } - aligned_allocator() throw() + aligned_allocator() { } - aligned_allocator( const aligned_allocator& ) throw() + aligned_allocator( const aligned_allocator& ) { } template - aligned_allocator( const aligned_allocator& ) throw() + aligned_allocator( const aligned_allocator& ) { } - ~aligned_allocator() throw() + ~aligned_allocator() { } - size_type max_size() const throw() + size_type max_size() const { return (std::numeric_limits::max)(); } @@ -701,6 +720,15 @@ public: ::new( p ) T( value ); } + // Support for c++11 +#if (__cplusplus >= 201103L) + template + void construct(pointer p, Args&&... args) + { + ::new(p) T(std::forward(args)...); + } +#endif + void destroy( pointer p ) { p->~T(); @@ -720,19 +748,21 @@ public: //---------- Cache sizes ---------- -#if defined(__GNUC__) && ( defined(__i386__) || defined(__x86_64__) ) -# if defined(__PIC__) && defined(__i386__) - // Case for x86 with PIC -# define EIGEN_CPUID(abcd,func,id) \ - __asm__ __volatile__ ("xchgl %%ebx, %%esi;cpuid; xchgl %%ebx,%%esi": "=a" (abcd[0]), "=S" (abcd[1]), "=c" (abcd[2]), "=d" (abcd[3]) : "a" (func), "c" (id)); -# else - // Case for x86_64 or x86 w/o PIC -# define EIGEN_CPUID(abcd,func,id) \ - __asm__ __volatile__ ("cpuid": "=a" (abcd[0]), "=b" (abcd[1]), "=c" (abcd[2]), "=d" (abcd[3]) : "a" (func), "c" (id) ); -# endif -#elif defined(_MSC_VER) -# if (_MSC_VER > 1500) -# define EIGEN_CPUID(abcd,func,id) __cpuidex((int*)abcd,func,id) +#if !defined(EIGEN_NO_CPUID) +# if defined(__GNUC__) && ( defined(__i386__) || defined(__x86_64__) ) +# if defined(__PIC__) && defined(__i386__) + // Case for x86 with PIC +# define EIGEN_CPUID(abcd,func,id) \ + __asm__ __volatile__ ("xchgl %%ebx, %%esi;cpuid; xchgl %%ebx,%%esi": "=a" (abcd[0]), "=S" (abcd[1]), "=c" (abcd[2]), "=d" (abcd[3]) : "a" (func), "c" (id)); +# else + // Case for x86_64 or x86 w/o PIC +# define EIGEN_CPUID(abcd,func,id) \ + __asm__ __volatile__ ("cpuid": "=a" (abcd[0]), "=b" (abcd[1]), "=c" (abcd[2]), "=d" (abcd[3]) : "a" (func), "c" (id) ); +# endif +# elif defined(_MSC_VER) +# if (_MSC_VER > 1500) +# define EIGEN_CPUID(abcd,func,id) __cpuidex((int*)abcd,func,id) +# endif # endif #endif @@ -742,7 +772,7 @@ namespace internal { inline bool cpuid_is_vendor(int abcd[4], const char* vendor) { - return abcd[1]==((int*)(vendor))[0] && abcd[3]==((int*)(vendor))[1] && abcd[2]==((int*)(vendor))[2]; + return abcd[1]==(reinterpret_cast(vendor))[0] && abcd[3]==(reinterpret_cast(vendor))[1] && abcd[2]==(reinterpret_cast(vendor))[2]; } inline void queryCacheSizes_intel_direct(int& l1, int& l2, int& l3) @@ -932,4 +962,6 @@ inline int queryTopLevelCacheSize() } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_MEMORY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Meta.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Meta.h index 4518261ef..82c93f922 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Meta.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Meta.h @@ -26,6 +26,8 @@ #ifndef EIGEN_META_H #define EIGEN_META_H +namespace Eigen { + namespace internal { /** \internal @@ -80,8 +82,6 @@ template<> struct is_arithmetic { enum { value = true }; }; template<> struct is_arithmetic { enum { value = true }; }; template<> struct is_arithmetic { enum { value = true }; }; template<> struct is_arithmetic { enum { value = true }; }; -template<> struct is_arithmetic { enum { value = true }; }; -template<> struct is_arithmetic { enum { value = true }; }; template struct add_const { typedef const T type; }; template struct add_const { typedef T& type; }; @@ -103,6 +103,21 @@ template struct enable_if; template struct enable_if { typedef T type; }; + + +/** \internal + * A base class do disable default copy ctor and copy assignement operator. + */ +class noncopyable +{ + noncopyable(const noncopyable&); + const noncopyable& operator=(const noncopyable&); +protected: + noncopyable() {} + ~noncopyable() {} +}; + + /** \internal * Convenient struct to get the result type of a unary or binary functor. * @@ -226,4 +241,6 @@ template struct is_diagonal > } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_META_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/StaticAssert.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/StaticAssert.h index 99c7c9972..9a5dbbbf3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/StaticAssert.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/StaticAssert.h @@ -48,6 +48,8 @@ #else // not CXX0X + namespace Eigen { + namespace internal { template @@ -70,6 +72,7 @@ YOU_CALLED_A_DYNAMIC_SIZE_METHOD_ON_A_FIXED_SIZE_MATRIX_OR_VECTOR, UNALIGNED_LOAD_AND_STORE_OPERATIONS_UNIMPLEMENTED_ON_ALTIVEC, THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES, + FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED, NUMERIC_TYPE_MUST_BE_REAL, COEFFICIENT_WRITE_ACCESS_TO_SELFADJOINT_NOT_SUPPORTED, WRITING_TO_TRIANGULAR_PART_WITH_UNIT_DIAGONAL_IS_NOT_SUPPORTED, @@ -95,12 +98,20 @@ YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION, THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY, YOU_ARE_TRYING_TO_USE_AN_INDEX_BASED_ACCESSOR_ON_AN_EXPRESSION_THAT_DOES_NOT_SUPPORT_THAT, - THIS_METHOD_IS_ONLY_FOR_1x1_EXPRESSIONS + THIS_METHOD_IS_ONLY_FOR_1x1_EXPRESSIONS, + THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL, + THIS_METHOD_IS_ONLY_FOR_ARRAYS_NOT_MATRICES, + YOU_PASSED_A_ROW_VECTOR_BUT_A_COLUMN_VECTOR_WAS_EXPECTED, + YOU_PASSED_A_COLUMN_VECTOR_BUT_A_ROW_VECTOR_WAS_EXPECTED, + THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE, + THE_STORAGE_ORDER_OF_BOTH_SIDES_MUST_MATCH }; }; } // end namespace internal + } // end namespace Eigen + // Specialized implementation for MSVC to avoid "conditional // expression is constant" warnings. This implementation doesn't // appear to work under GCC, hence the multiple implementations. @@ -195,4 +206,15 @@ EIGEN_STATIC_ASSERT(internal::is_lvalue::value, \ THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY) +#define EIGEN_STATIC_ASSERT_ARRAYXPR(Derived) \ + EIGEN_STATIC_ASSERT((internal::is_same::XprKind, ArrayXpr>::value), \ + THIS_METHOD_IS_ONLY_FOR_ARRAYS_NOT_MATRICES) + +#define EIGEN_STATIC_ASSERT_SAME_XPR_KIND(Derived1, Derived2) \ + EIGEN_STATIC_ASSERT((internal::is_same::XprKind, \ + typename internal::traits::XprKind \ + >::value), \ + YOU_CANNOT_MIX_ARRAYS_AND_MATRICES) + + #endif // EIGEN_STATIC_ASSERT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h index c2078f137..5bb0a624f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h @@ -37,6 +37,8 @@ #define EIGEN_EMPTY_STRUCT_CTOR(X) #endif +namespace Eigen { + typedef EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex; namespace internal { @@ -260,30 +262,27 @@ template struct plain_matrix_type_row_major // we should be able to get rid of this one too template struct must_nest_by_value { enum { ret = false }; }; -template -struct is_reference -{ - enum { ret = false }; -}; - -template -struct is_reference -{ - enum { ret = true }; -}; - -/** -* \internal The reference selector for template expressions. The idea is that we don't -* need to use references for expressions since they are light weight proxy -* objects which should generate no copying overhead. -**/ +/** \internal The reference selector for template expressions. The idea is that we don't + * need to use references for expressions since they are light weight proxy + * objects which should generate no copying overhead. */ template struct ref_selector { typedef typename conditional< bool(traits::Flags & NestByRefBit), T const&, - T + const T + >::type type; +}; + +/** \internal Adds the const qualifier on the value-type of T2 if and only if T1 is a const type */ +template +struct transfer_constness +{ + typedef typename conditional< + bool(internal::is_const::value), + typename internal::add_const_on_value_type::type, + T2 >::type type; }; @@ -297,6 +296,8 @@ struct ref_selector * \param T the type of the expression being nested * \param n the number of coefficient accesses in the nested expression for each coefficient access in the bigger expression. * + * Note that if no evaluation occur, then the constness of T is preserved. + * * Example. Suppose that a, b, and c are of type Matrix3d. The user forms the expression a*(b+c). * b+c is an expression "sum of matrices", which we will denote by S. In order to determine how to nest it, * the Product expression uses: nested::ret, which turns out to be Matrix3d because the internal logic of @@ -456,4 +457,6 @@ struct is_lvalue } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_XPRHELPER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Block.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Block.h index bc28051e0..d77ff62bb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Block.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Block.h @@ -26,6 +26,8 @@ #ifndef EIGEN_BLOCK2_H #define EIGEN_BLOCK2_H +namespace Eigen { + /** \returns a dynamic-size expression of a corner of *this. * * \param type the type of corner. Can be \a Eigen::TopLeft, \a Eigen::TopRight, @@ -134,4 +136,6 @@ DenseBase::corner(CornerType type) const } } +} // end namespace Eigen + #endif // EIGEN_BLOCK2_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Cwise.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Cwise.h index 2dc83b6a7..383645b8e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Cwise.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Cwise.h @@ -26,6 +26,8 @@ #ifndef EIGEN_CWISE_H #define EIGEN_CWISE_H +namespace Eigen { + /** \internal * convenient macro to defined the return type of a cwise binary operation */ #define EIGEN_CWISE_BINOP_RETURN_TYPE(OP) \ @@ -200,4 +202,6 @@ inline Cwise MatrixBase::cwise() return derived(); } +} // end namespace Eigen + #endif // EIGEN_CWISE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CwiseOperators.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CwiseOperators.h index 9c28559c3..207a167c1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CwiseOperators.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CwiseOperators.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ARRAY_CWISE_OPERATORS_H #define EIGEN_ARRAY_CWISE_OPERATORS_H +namespace Eigen { + /*************************************************************************** * The following functions were defined in Core ***************************************************************************/ @@ -306,4 +308,6 @@ inline ExpressionType& Cwise::operator-=(const Scalar& scalar) return m_matrix.const_cast_derived() = *this - scalar; } +} // end namespace Eigen + #endif // EIGEN_ARRAY_CWISE_OPERATORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h index 78df29d40..dd29dfc34 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h @@ -24,6 +24,8 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * \nonstableyet * @@ -63,7 +65,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim== ~AlignedBox() {} /** \returns the dimension in which the box holds */ - inline int dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size()-1 : int(AmbientDimAtCompileTime); } + inline int dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size()-1 : AmbientDimAtCompileTime; } /** \returns true if the box is null, i.e, empty. */ inline bool isNull() const { return (m_min.cwise() > m_max).any(); } @@ -157,14 +159,16 @@ protected: template inline Scalar AlignedBox::squaredExteriorDistance(const VectorType& p) const { - Scalar dist2 = 0.; + Scalar dist2(0); Scalar aux; for (int k=0; k::toRotationMatrix(void) const return res; } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h index 81c4f55b1..8b4f7a080 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h @@ -25,6 +25,8 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Hyperplane @@ -263,3 +265,5 @@ protected: Coefficients m_coeffs; }; + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h index 411c4b570..cc8eb7089 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h @@ -25,6 +25,7 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -151,3 +152,5 @@ inline _Scalar ParametrizedLine<_Scalar, _AmbientDim>::intersection(const Hyperp return -(hyperplane.offset()+origin().eigen2_dot(hyperplane.normal())) /(direction().eigen2_dot(hyperplane.normal())); } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h index a75fa42ae..616671c67 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h @@ -24,6 +24,8 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { + template @@ -143,7 +145,7 @@ public: /** \returns a quaternion representing an identity rotation * \sa MatrixBase::Identity() */ - inline static Quaternion Identity() { return Quaternion(1, 0, 0, 0); } + static inline Quaternion Identity() { return Quaternion(1, 0, 0, 0); } /** \sa Quaternion::Identity(), MatrixBase::setIdentity() */ @@ -314,9 +316,9 @@ Quaternion::toRotationMatrix(void) const // it has to be inlined, and so the return by value is not an issue Matrix3 res; - const Scalar tx = 2*this->x(); - const Scalar ty = 2*this->y(); - const Scalar tz = 2*this->z(); + const Scalar tx = Scalar(2)*this->x(); + const Scalar ty = Scalar(2)*this->y(); + const Scalar tz = Scalar(2)*this->z(); const Scalar twx = tx*this->w(); const Scalar twy = ty*this->w(); const Scalar twz = tz*this->w(); @@ -327,15 +329,15 @@ Quaternion::toRotationMatrix(void) const const Scalar tyz = tz*this->y(); const Scalar tzz = tz*this->z(); - res.coeffRef(0,0) = 1-(tyy+tzz); + res.coeffRef(0,0) = Scalar(1)-(tyy+tzz); res.coeffRef(0,1) = txy-twz; res.coeffRef(0,2) = txz+twy; res.coeffRef(1,0) = txy+twz; - res.coeffRef(1,1) = 1-(txx+tzz); + res.coeffRef(1,1) = Scalar(1)-(txx+tzz); res.coeffRef(1,2) = tyz-twx; res.coeffRef(2,0) = txz-twy; res.coeffRef(2,1) = tyz+twx; - res.coeffRef(2,2) = 1-(txx+tyy); + res.coeffRef(2,2) = Scalar(1)-(txx+tyy); return res; } @@ -460,7 +462,7 @@ template struct ei_quaternion_assign_impl { typedef typename Other::Scalar Scalar; - inline static void run(Quaternion& q, const Other& mat) + static inline void run(Quaternion& q, const Other& mat) { // This algorithm comes from "Quaternion Calculus and Fast Animation", // Ken Shoemake, 1987 SIGGRAPH course notes @@ -499,8 +501,10 @@ template struct ei_quaternion_assign_impl { typedef typename Other::Scalar Scalar; - inline static void run(Quaternion& q, const Other& vec) + static inline void run(Quaternion& q, const Other& vec) { q.coeffs() = vec; } }; + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h index ee7c80e7e..0993fa5bb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h @@ -24,6 +24,7 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -155,3 +156,5 @@ Rotation2D::toRotationMatrix(void) const Scalar cosA = ei_cos(m_angle); return (Matrix2() << cosA, -sinA, sinA, cosA).finished(); } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h index 2f494f198..b65abfe0d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h @@ -24,6 +24,8 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { + // this file aims to contains the various representations of rotation/orientation // in 2D and 3D space excepted Matrix and Quaternion. @@ -113,22 +115,24 @@ Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols> * \sa class Transform, class Rotation2D, class Quaternion, class AngleAxis */ template -inline static Matrix ei_toRotationMatrix(const Scalar& s) +static inline Matrix ei_toRotationMatrix(const Scalar& s) { EIGEN_STATIC_ASSERT(Dim==2,YOU_MADE_A_PROGRAMMING_MISTAKE) return Rotation2D(s).toRotationMatrix(); } template -inline static Matrix ei_toRotationMatrix(const RotationBase& r) +static inline Matrix ei_toRotationMatrix(const RotationBase& r) { return r.toRotationMatrix(); } template -inline static const MatrixBase& ei_toRotationMatrix(const MatrixBase& mat) +static inline const MatrixBase& ei_toRotationMatrix(const MatrixBase& mat) { EIGEN_STATIC_ASSERT(OtherDerived::RowsAtCompileTime==Dim && OtherDerived::ColsAtCompileTime==Dim, YOU_MADE_A_PROGRAMMING_MISTAKE) return mat; } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h index 108e6d7d5..8e47c78fe 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h @@ -24,6 +24,7 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -177,3 +178,5 @@ Scaling::operator* (const TransformType& t) const res.prescale(m_coeffs); return res; } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Transform.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Transform.h index 88956c86c..28dcc03b7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Transform.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Transform.h @@ -25,6 +25,7 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { // Note that we have to pass Dim and HDim because it is not allowed to use a template // parameter to define a template specialization. To be more precise, in the following @@ -796,3 +797,5 @@ struct ei_transform_product_impl { return ((tr.linear() * other) + tr.translation()) * (Scalar(1) / ( (tr.matrix().template block<1,Dim>(Dim,0) * other).coeff(0) + tr.matrix().coeff(Dim,Dim))); } }; + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Translation.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Translation.h index e651e3102..dd6256893 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Translation.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Translation.h @@ -24,6 +24,7 @@ // no include guard, we'll include this twice from All.h from Eigen2Support, and it's internal anyway +namespace Eigen { /** \geometry_module \ingroup Geometry_Module * @@ -194,3 +195,5 @@ Translation::operator* (const TransformType& t) const res.pretranslate(m_coeffs); return res; } + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LU.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LU.h index c23c11baa..0620096af 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LU.h @@ -25,6 +25,8 @@ #ifndef EIGEN2_LU_H #define EIGEN2_LU_H +namespace Eigen { + template class LU : public FullPivLU { @@ -57,7 +59,6 @@ class LU : public FullPivLU > ImageResultType; typedef FullPivLU Base; - LU() : Base() {} template explicit LU(const T& t) : Base(t), m_originalMatrix(t) {} @@ -129,5 +130,6 @@ MatrixBase::eigen2_lu() const } #endif +} // end namespace Eigen #endif // EIGEN2_LU_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Lazy.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Lazy.h index c4288ede2..a1fb9c753 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Lazy.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Lazy.h @@ -25,6 +25,8 @@ #ifndef EIGEN_LAZY_H #define EIGEN_LAZY_H +namespace Eigen { + /** \deprecated it is only used by lazy() which is deprecated * * \returns an expression of *this with added flags @@ -79,4 +81,6 @@ Derived& MatrixBase::operator-=(const Flaggedoffset() = - (result->normal().cwise()* mean).sum(); } +} // end namespace Eigen #endif // EIGEN2_LEASTSQUARES_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/MathFunctions.h index caa44e63f..2baf4bb8f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/MathFunctions.h @@ -25,6 +25,8 @@ #ifndef EIGEN2_MATH_FUNCTIONS_H #define EIGEN2_MATH_FUNCTIONS_H +namespace Eigen { + template inline typename NumTraits::Real ei_real(const T& x) { return internal::real(x); } template inline typename NumTraits::Real ei_imag(const T& x) { return internal::imag(x); } template inline T ei_conj(const T& x) { return internal::conj(x); } @@ -65,4 +67,6 @@ inline bool ei_isApproxOrLessThan(const Scalar& x, const Scalar& y, return internal::isApproxOrLessThan(x, y, precision); } +} // end namespace Eigen + #endif // EIGEN2_MATH_FUNCTIONS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Memory.h index 028347541..0588e2b34 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Memory.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Memory.h @@ -25,6 +25,8 @@ #ifndef EIGEN2_MEMORY_H #define EIGEN2_MEMORY_H +namespace Eigen { + inline void* ei_aligned_malloc(size_t size) { return internal::aligned_malloc(size); } inline void ei_aligned_free(void *ptr) { internal::aligned_free(ptr); } inline void* ei_aligned_realloc(void *ptr, size_t new_size, size_t old_size) { return internal::aligned_realloc(ptr, new_size, old_size); } @@ -53,6 +55,6 @@ template inline void ei_aligned_delete(T *ptr, size_t size) return internal::aligned_delete(ptr, size); } - +} // end namespace Eigen #endif // EIGEN2_MACROS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Meta.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Meta.h index 6e500b79a..70c210822 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Meta.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Meta.h @@ -25,6 +25,8 @@ #ifndef EIGEN2_META_H #define EIGEN2_META_H +namespace Eigen { + template struct ei_traits : internal::traits {}; @@ -83,4 +85,6 @@ class ei_meta_sqrt template class ei_meta_sqrt { public: enum { ret = (SupX*SupX <= Y) ? SupX : InfX }; }; +} // end namespace Eigen + #endif // EIGEN2_META_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Minor.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Minor.h index eda91cc32..964e9546d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Minor.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Minor.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MINOR_H #define EIGEN_MINOR_H +namespace Eigen { + /** * \class Minor * @@ -125,4 +127,6 @@ MatrixBase::minor(Index row, Index col) const return Minor(derived(), row, col); } +} // end namespace Eigen + #endif // EIGEN_MINOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/QR.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/QR.h index 64f5d5ccb..60fc21f56 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/QR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/QR.h @@ -26,6 +26,8 @@ #ifndef EIGEN2_QR_H #define EIGEN2_QR_H +namespace Eigen { + template class QR : public HouseholderQR { @@ -75,5 +77,6 @@ MatrixBase::qr() const return QR(eval()); } +} // end namespace Eigen #endif // EIGEN2_QR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/SVD.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/SVD.h index 16b4b488f..ff3b8a416 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/SVD.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/SVD.h @@ -25,6 +25,8 @@ #ifndef EIGEN2_SVD_H #define EIGEN2_SVD_H +namespace Eigen { + /** \ingroup SVD_Module * \nonstableyet * @@ -390,7 +392,7 @@ void SVD::compute(const MatrixType& matrix) Scalar ek = e[k]/scale; Scalar b = ((spm1 + sp)*(spm1 - sp) + epm1*epm1)/Scalar(2); Scalar c = (sp*epm1)*(sp*epm1); - Scalar shift = 0.0; + Scalar shift(0); if ((b != 0.0) || (c != 0.0)) { shift = ei_sqrt(b*b + c); @@ -646,4 +648,6 @@ MatrixBase::svd() const return SVD(derived()); } +} // end namespace Eigen + #endif // EIGEN2_SVD_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/TriangularSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/TriangularSolver.h index e94e47a50..e3374d8c0 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/TriangularSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/TriangularSolver.h @@ -25,6 +25,8 @@ #ifndef EIGEN_TRIANGULAR_SOLVER2_H #define EIGEN_TRIANGULAR_SOLVER2_H +namespace Eigen { + const unsigned int UnitDiagBit = UnitDiag; const unsigned int SelfAdjointBit = SelfAdjoint; const unsigned int UpperTriangularBit = Upper; @@ -49,5 +51,7 @@ void Flagged::solveTriangularInPlace(const MatrixB { m_matrix.template triangularView().solveInPlace(other.derived()); } + +} // end namespace Eigen #endif // EIGEN_TRIANGULAR_SOLVER2_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/VectorBlock.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/VectorBlock.h index 010031d19..8967c9019 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/VectorBlock.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/VectorBlock.h @@ -26,6 +26,8 @@ #ifndef EIGEN2_VECTORBLOCK_H #define EIGEN2_VECTORBLOCK_H +namespace Eigen { + /** \deprecated use DenseMase::head(Index) */ template inline VectorBlock @@ -102,4 +104,6 @@ MatrixBase::end() const return VectorBlock(derived(), size() - Size); } +} // end namespace Eigen + #endif // EIGEN2_VECTORBLOCK_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h index 57e00227d..91b4fa1e2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h @@ -27,9 +27,10 @@ #ifndef EIGEN_COMPLEX_EIGEN_SOLVER_H #define EIGEN_COMPLEX_EIGEN_SOLVER_H -#include "./EigenvaluesCommon.h" #include "./ComplexSchur.h" +namespace Eigen { + /** \eigenvalues_module \ingroup Eigenvalues_Module * * @@ -328,5 +329,6 @@ void ComplexEigenSolver::sortEigenvalues(bool computeEigenvectors) } } +} // end namespace Eigen #endif // EIGEN_COMPLEX_EIGEN_SOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur.h index ec93af2e5..1a49cca13 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur.h @@ -27,9 +27,10 @@ #ifndef EIGEN_COMPLEX_SCHUR_H #define EIGEN_COMPLEX_SCHUR_H -#include "./EigenvaluesCommon.h" #include "./HessenbergDecomposition.h" +namespace Eigen { + namespace internal { template struct complex_schur_reduce_to_hessenberg; } @@ -227,46 +228,6 @@ template class ComplexSchur friend struct internal::complex_schur_reduce_to_hessenberg::IsComplex>; }; -namespace internal { - -/** Computes the principal value of the square root of the complex \a z. */ -template -std::complex sqrt(const std::complex &z) -{ - RealScalar t, tre, tim; - - t = abs(z); - - if (abs(real(z)) <= abs(imag(z))) - { - // No cancellation in these formulas - tre = sqrt(RealScalar(0.5)*(t + real(z))); - tim = sqrt(RealScalar(0.5)*(t - real(z))); - } - else - { - // Stable computation of the above formulas - if (z.real() > RealScalar(0)) - { - tre = t + z.real(); - tim = abs(imag(z))*sqrt(RealScalar(0.5)/tre); - tre = sqrt(RealScalar(0.5)*tre); - } - else - { - tim = t - z.real(); - tre = abs(imag(z))*sqrt(RealScalar(0.5)/tim); - tim = sqrt(RealScalar(0.5)*tim); - } - } - if(z.imag() < RealScalar(0)) - tim = -tim; - - return (std::complex(tre,tim)); -} -} // end namespace internal - - /** If m_matT(i+1,i) is neglegible in floating point arithmetic * compared to m_matT(i,i) and m_matT(j,j), then set it to zero and * return true, else return false. */ @@ -302,7 +263,7 @@ typename ComplexSchur::ComplexScalar ComplexSchur::compu ComplexScalar b = t.coeff(0,1) * t.coeff(1,0); ComplexScalar c = t.coeff(0,0) - t.coeff(1,1); - ComplexScalar disc = internal::sqrt(c*c + RealScalar(4)*b); + ComplexScalar disc = sqrt(c*c + RealScalar(4)*b); ComplexScalar det = t.coeff(0,0) * t.coeff(1,1) - b; ComplexScalar trace = t.coeff(0,0) + t.coeff(1,1); ComplexScalar eival1 = (trace + disc) / RealScalar(2); @@ -445,4 +406,6 @@ void ComplexSchur::reduceToTriangularForm(bool computeU) m_matUisUptodate = computeU; } +} // end namespace Eigen + #endif // EIGEN_COMPLEX_SCHUR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur_MKL.h new file mode 100644 index 000000000..e21a8d836 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexSchur_MKL.h @@ -0,0 +1,94 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Complex Schur needed to complex unsymmetrical eigenvalues/eigenvectors. + ******************************************************************************** +*/ + +#ifndef EIGEN_COMPLEX_SCHUR_MKL_H +#define EIGEN_COMPLEX_SCHUR_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_SCHUR_COMPLEX(EIGTYPE, MKLTYPE, MKLPREFIX, MKLPREFIX_U, EIGCOLROW, MKLCOLROW) \ +template<> \ +ComplexSchur >& \ +ComplexSchur >::compute(const Matrix& matrix, bool computeU) \ +{ \ + typedef Matrix MatrixType; \ + typedef MatrixType::Scalar Scalar; \ + typedef MatrixType::RealScalar RealScalar; \ + typedef std::complex ComplexScalar; \ +\ + assert(matrix.cols() == matrix.rows()); \ +\ + m_matUisUptodate = false; \ + if(matrix.cols() == 1) \ + { \ + m_matT = matrix.cast(); \ + if(computeU) m_matU = ComplexMatrixType::Identity(1,1); \ + m_info = Success; \ + m_isInitialized = true; \ + m_matUisUptodate = computeU; \ + return *this; \ + } \ + lapack_int n = matrix.cols(), sdim, info; \ + lapack_int lda = matrix.outerStride(); \ + lapack_int matrix_order = MKLCOLROW; \ + char jobvs, sort='N'; \ + LAPACK_##MKLPREFIX_U##_SELECT1 select = 0; \ + jobvs = (computeU) ? 'V' : 'N'; \ + m_matU.resize(n, n); \ + lapack_int ldvs = m_matU.outerStride(); \ + m_matT = matrix; \ + Matrix w; \ + w.resize(n, 1);\ + info = LAPACKE_##MKLPREFIX##gees( matrix_order, jobvs, sort, select, n, (MKLTYPE*)m_matT.data(), lda, &sdim, (MKLTYPE*)w.data(), (MKLTYPE*)m_matU.data(), ldvs ); \ + if(info == 0) \ + m_info = Success; \ + else \ + m_info = NoConvergence; \ +\ + m_isInitialized = true; \ + m_matUisUptodate = computeU; \ + return *this; \ +\ +} + +EIGEN_MKL_SCHUR_COMPLEX(dcomplex, MKL_Complex16, z, Z, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_SCHUR_COMPLEX(scomplex, MKL_Complex8, c, C, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_SCHUR_COMPLEX(dcomplex, MKL_Complex16, z, Z, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_MKL_SCHUR_COMPLEX(scomplex, MKL_Complex8, c, C, RowMajor, LAPACK_ROW_MAJOR) + +} // end namespace Eigen + +#endif // EIGEN_COMPLEX_SCHUR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h index f57353c06..f9365ae59 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h @@ -26,9 +26,10 @@ #ifndef EIGEN_EIGENSOLVER_H #define EIGEN_EIGENSOLVER_H -#include "./EigenvaluesCommon.h" #include "./RealSchur.h" +namespace Eigen { + /** \eigenvalues_module \ingroup Eigenvalues_Module * * @@ -432,7 +433,7 @@ void EigenSolver::doComputeEigenvectors() const Scalar eps = NumTraits::epsilon(); // inefficient! this is already computed in RealSchur - Scalar norm = 0.0; + Scalar norm(0); for (Index j = 0; j < size; ++j) { norm += m_matT.row(j).segment((std::max)(j-1,Index(0)), size-(std::max)(j-1,Index(0))).cwiseAbs().sum(); @@ -452,7 +453,7 @@ void EigenSolver::doComputeEigenvectors() // Scalar vector if (q == Scalar(0)) { - Scalar lastr=0, lastw=0; + Scalar lastr(0), lastw(0); Index l = n; m_matT.coeffRef(n,n) = 1.0; @@ -498,7 +499,7 @@ void EigenSolver::doComputeEigenvectors() } else if (q < Scalar(0) && n > 0) // Complex vector { - Scalar lastra=0, lastsa=0, lastw=0; + Scalar lastra(0), lastsa(0), lastw(0); Index l = n-1; // Last vector component imaginary so matrix is triangular @@ -588,4 +589,6 @@ void EigenSolver::doComputeEigenvectors() } } +} // end namespace Eigen + #endif // EIGEN_EIGENSOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h index 980af14ce..4eb2b229d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h @@ -26,9 +26,10 @@ #ifndef EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H #define EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H -#include "./EigenvaluesCommon.h" #include "./Tridiagonalization.h" +namespace Eigen { + /** \eigenvalues_module \ingroup Eigenvalues_Module * * @@ -236,4 +237,6 @@ compute(const MatrixType& matA, const MatrixType& matB, int options) return *this; } +} // end namespace Eigen + #endif // EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h index c17f155a5..88e63eba4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h @@ -26,6 +26,8 @@ #ifndef EIGEN_HESSENBERGDECOMPOSITION_H #define EIGEN_HESSENBERGDECOMPOSITION_H +namespace Eigen { + namespace internal { template struct HessenbergDecompositionMatrixHReturnType; @@ -379,6 +381,8 @@ template struct HessenbergDecompositionMatrixHReturnType const HessenbergDecomposition& m_hess; }; -} +} // end namespace internal + +} // end namespace Eigen #endif // EIGEN_HESSENBERGDECOMPOSITION_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h index 5591519fb..a004e7e63 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h @@ -26,6 +26,8 @@ #ifndef EIGEN_MATRIXBASEEIGENVALUES_H #define EIGEN_MATRIXBASEEIGENVALUES_H +namespace Eigen { + namespace internal { template @@ -167,4 +169,6 @@ SelfAdjointView::operatorNorm() const return eigenvalues().cwiseAbs().maxCoeff(); } +} // end namespace Eigen + #endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h index cc9af11c1..e204344e0 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h @@ -26,9 +26,10 @@ #ifndef EIGEN_REAL_SCHUR_H #define EIGEN_REAL_SCHUR_H -#include "./EigenvaluesCommon.h" #include "./HessenbergDecomposition.h" +namespace Eigen { + /** \eigenvalues_module \ingroup Eigenvalues_Module * * @@ -235,41 +236,43 @@ RealSchur& RealSchur::compute(const MatrixType& matrix, // Rows iu+1,...,end are already brought in triangular form. Index iu = m_matT.cols() - 1; Index iter = 0; // iteration count - Scalar exshift = 0.0; // sum of exceptional shifts + Scalar exshift(0); // sum of exceptional shifts Scalar norm = computeNormOfT(); - while (iu >= 0) + if(norm!=0) { - Index il = findSmallSubdiagEntry(iu, norm); + while (iu >= 0) + { + Index il = findSmallSubdiagEntry(iu, norm); - // Check for convergence - if (il == iu) // One root found - { - m_matT.coeffRef(iu,iu) = m_matT.coeff(iu,iu) + exshift; - if (iu > 0) - m_matT.coeffRef(iu, iu-1) = Scalar(0); - iu--; - iter = 0; + // Check for convergence + if (il == iu) // One root found + { + m_matT.coeffRef(iu,iu) = m_matT.coeff(iu,iu) + exshift; + if (iu > 0) + m_matT.coeffRef(iu, iu-1) = Scalar(0); + iu--; + iter = 0; + } + else if (il == iu-1) // Two roots found + { + splitOffTwoRows(iu, computeU, exshift); + iu -= 2; + iter = 0; + } + else // No convergence yet + { + // The firstHouseholderVector vector has to be initialized to something to get rid of a silly GCC warning (-O1 -Wall -DNDEBUG ) + Vector3s firstHouseholderVector(0,0,0), shiftInfo; + computeShift(iu, iter, exshift, shiftInfo); + iter = iter + 1; + if (iter > m_maxIterations) break; + Index im; + initFrancisQRStep(il, iu, shiftInfo, im, firstHouseholderVector); + performFrancisQRStep(il, im, iu, computeU, firstHouseholderVector, workspace); + } } - else if (il == iu-1) // Two roots found - { - splitOffTwoRows(iu, computeU, exshift); - iu -= 2; - iter = 0; - } - else // No convergence yet - { - // The firstHouseholderVector vector has to be initialized to something to get rid of a silly GCC warning (-O1 -Wall -DNDEBUG ) - Vector3s firstHouseholderVector(0,0,0), shiftInfo; - computeShift(iu, iter, exshift, shiftInfo); - iter = iter + 1; - if (iter > m_maxIterations) break; - Index im; - initFrancisQRStep(il, iu, shiftInfo, im, firstHouseholderVector); - performFrancisQRStep(il, im, iu, computeU, firstHouseholderVector, workspace); - } - } - + } if(iter <= m_maxIterations) m_info = Success; else @@ -288,7 +291,7 @@ inline typename MatrixType::Scalar RealSchur::computeNormOfT() // FIXME to be efficient the following would requires a triangular reduxion code // Scalar norm = m_matT.upper().cwiseAbs().sum() // + m_matT.bottomLeftCorner(size-1,size-1).diagonal().cwiseAbs().sum(); - Scalar norm = 0.0; + Scalar norm(0); for (Index j = 0; j < size; ++j) norm += m_matT.row(j).segment((std::max)(j-1,Index(0)), size-(std::max)(j-1,Index(0))).cwiseAbs().sum(); return norm; @@ -471,4 +474,6 @@ inline void RealSchur::performFrancisQRStep(Index il, Index im, Inde } } +} // end namespace Eigen + #endif // EIGEN_REAL_SCHUR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur_MKL.h new file mode 100644 index 000000000..c9689520b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur_MKL.h @@ -0,0 +1,83 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Real Schur needed to real unsymmetrical eigenvalues/eigenvectors. + ******************************************************************************** +*/ + +#ifndef EIGEN_REAL_SCHUR_MKL_H +#define EIGEN_REAL_SCHUR_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_SCHUR_REAL(EIGTYPE, MKLTYPE, MKLPREFIX, MKLPREFIX_U, EIGCOLROW, MKLCOLROW) \ +template<> \ +RealSchur >& \ +RealSchur >::compute(const Matrix& matrix, bool computeU) \ +{ \ + typedef Matrix MatrixType; \ + typedef MatrixType::Scalar Scalar; \ + typedef MatrixType::RealScalar RealScalar; \ +\ + assert(matrix.cols() == matrix.rows()); \ +\ + lapack_int n = matrix.cols(), sdim, info; \ + lapack_int lda = matrix.outerStride(); \ + lapack_int matrix_order = MKLCOLROW; \ + char jobvs, sort='N'; \ + LAPACK_##MKLPREFIX_U##_SELECT2 select = 0; \ + jobvs = (computeU) ? 'V' : 'N'; \ + m_matU.resize(n, n); \ + lapack_int ldvs = m_matU.outerStride(); \ + m_matT = matrix; \ + Matrix wr, wi; \ + wr.resize(n, 1); wi.resize(n, 1); \ + info = LAPACKE_##MKLPREFIX##gees( matrix_order, jobvs, sort, select, n, (MKLTYPE*)m_matT.data(), lda, &sdim, (MKLTYPE*)wr.data(), (MKLTYPE*)wi.data(), (MKLTYPE*)m_matU.data(), ldvs ); \ + if(info == 0) \ + m_info = Success; \ + else \ + m_info = NoConvergence; \ +\ + m_isInitialized = true; \ + m_matUisUptodate = computeU; \ + return *this; \ +\ +} + +EIGEN_MKL_SCHUR_REAL(double, double, d, D, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_SCHUR_REAL(float, float, s, S, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_SCHUR_REAL(double, double, d, D, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_MKL_SCHUR_REAL(float, float, s, S, RowMajor, LAPACK_ROW_MAJOR) + +} // end namespace Eigen + +#endif // EIGEN_REAL_SCHUR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h index ad107c632..b4aa1ef20 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h @@ -26,12 +26,17 @@ #ifndef EIGEN_SELFADJOINTEIGENSOLVER_H #define EIGEN_SELFADJOINTEIGENSOLVER_H -#include "./EigenvaluesCommon.h" #include "./Tridiagonalization.h" +namespace Eigen { + template class GeneralizedSelfAdjointEigenSolver; +namespace internal { +template struct direct_selfadjoint_eigenvalues; +} + /** \eigenvalues_module \ingroup Eigenvalues_Module * * @@ -86,7 +91,7 @@ template class SelfAdjointEigenSolver Options = MatrixType::Options, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; - + /** \brief Scalar type for matrices of type \p _MatrixType. */ typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::Index Index; @@ -98,6 +103,8 @@ template class SelfAdjointEigenSolver * complex. */ typedef typename NumTraits::Real RealScalar; + + friend struct internal::direct_selfadjoint_eigenvalues::IsComplex>; /** \brief Type for vector of eigenvalues as returned by eigenvalues(). * @@ -198,6 +205,22 @@ template class SelfAdjointEigenSolver * \sa SelfAdjointEigenSolver(const MatrixType&, int) */ SelfAdjointEigenSolver& compute(const MatrixType& matrix, int options = ComputeEigenvectors); + + /** \brief Computes eigendecomposition of given matrix using a direct algorithm + * + * This is a variant of compute(const MatrixType&, int options) which + * directly solves the underlying polynomial equation. + * + * Currently only 3x3 matrices for which the sizes are known at compile time are supported (e.g., Matrix3d). + * + * This method is usually significantly faster than the QR algorithm + * but it might also be less accurate. It is also worth noting that + * for 3x3 matrices it involves trigonometric operations which are + * not necessarily available for all scalar types. + * + * \sa compute(const MatrixType&, int options) + */ + SelfAdjointEigenSolver& computeDirect(const MatrixType& matrix, int options = ComputeEigenvectors); /** \brief Returns the eigenvectors of given matrix. * @@ -401,7 +424,7 @@ SelfAdjointEigenSolver& SelfAdjointEigenSolver // map the matrix coefficients to [-1:1] to avoid over- and underflow. RealScalar scale = matrix.cwiseAbs().maxCoeff(); - if(scale==Scalar(0)) scale = 1; + if(scale==RealScalar(0)) scale = RealScalar(1); mat = matrix / scale; m_subdiag.resize(n-1); internal::tridiagonalization_inplace(mat, diag, m_subdiag, computeEigenvectors); @@ -466,6 +489,264 @@ SelfAdjointEigenSolver& SelfAdjointEigenSolver return *this; } + +namespace internal { + +template struct direct_selfadjoint_eigenvalues +{ + static inline void run(SolverType& eig, const typename SolverType::MatrixType& A, int options) + { eig.compute(A,options); } +}; + +template struct direct_selfadjoint_eigenvalues +{ + typedef typename SolverType::MatrixType MatrixType; + typedef typename SolverType::RealVectorType VectorType; + typedef typename SolverType::Scalar Scalar; + + static inline void computeRoots(const MatrixType& m, VectorType& roots) + { + using std::sqrt; + using std::atan2; + using std::cos; + using std::sin; + const Scalar s_inv3 = Scalar(1.0)/Scalar(3.0); + const Scalar s_sqrt3 = sqrt(Scalar(3.0)); + + // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0. The + // eigenvalues are the roots to this equation, all guaranteed to be + // real-valued, because the matrix is symmetric. + Scalar c0 = m(0,0)*m(1,1)*m(2,2) + Scalar(2)*m(1,0)*m(2,0)*m(2,1) - m(0,0)*m(2,1)*m(2,1) - m(1,1)*m(2,0)*m(2,0) - m(2,2)*m(1,0)*m(1,0); + Scalar c1 = m(0,0)*m(1,1) - m(1,0)*m(1,0) + m(0,0)*m(2,2) - m(2,0)*m(2,0) + m(1,1)*m(2,2) - m(2,1)*m(2,1); + Scalar c2 = m(0,0) + m(1,1) + m(2,2); + + // Construct the parameters used in classifying the roots of the equation + // and in solving the equation for the roots in closed form. + Scalar c2_over_3 = c2*s_inv3; + Scalar a_over_3 = (c1 - c2*c2_over_3)*s_inv3; + if (a_over_3 > Scalar(0)) + a_over_3 = Scalar(0); + + Scalar half_b = Scalar(0.5)*(c0 + c2_over_3*(Scalar(2)*c2_over_3*c2_over_3 - c1)); + + Scalar q = half_b*half_b + a_over_3*a_over_3*a_over_3; + if (q > Scalar(0)) + q = Scalar(0); + + // Compute the eigenvalues by solving for the roots of the polynomial. + Scalar rho = sqrt(-a_over_3); + Scalar theta = atan2(sqrt(-q),half_b)*s_inv3; + Scalar cos_theta = cos(theta); + Scalar sin_theta = sin(theta); + roots(0) = c2_over_3 + Scalar(2)*rho*cos_theta; + roots(1) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); + roots(2) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); + + // Sort in increasing order. + if (roots(0) >= roots(1)) + std::swap(roots(0),roots(1)); + if (roots(1) >= roots(2)) + { + std::swap(roots(1),roots(2)); + if (roots(0) >= roots(1)) + std::swap(roots(0),roots(1)); + } + } + + static inline void run(SolverType& solver, const MatrixType& mat, int options) + { + using std::sqrt; + eigen_assert(mat.cols() == 3 && mat.cols() == mat.rows()); + eigen_assert((options&~(EigVecMask|GenEigMask))==0 + && (options&EigVecMask)!=EigVecMask + && "invalid option parameter"); + bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; + + MatrixType& eivecs = solver.m_eivec; + VectorType& eivals = solver.m_eivalues; + + // map the matrix coefficients to [-1:1] to avoid over- and underflow. + Scalar scale = mat.cwiseAbs().maxCoeff(); + MatrixType scaledMat = mat / scale; + + // compute the eigenvalues + computeRoots(scaledMat,eivals); + + // compute the eigen vectors + if(computeEigenvectors) + { + Scalar safeNorm2 = Eigen::NumTraits::epsilon(); + safeNorm2 *= safeNorm2; + if((eivals(2)-eivals(0))<=Eigen::NumTraits::epsilon()) + { + eivecs.setIdentity(); + } + else + { + scaledMat = scaledMat.template selfadjointView(); + MatrixType tmp; + tmp = scaledMat; + + Scalar d0 = eivals(2) - eivals(1); + Scalar d1 = eivals(1) - eivals(0); + int k = d0 > d1 ? 2 : 0; + d0 = d0 > d1 ? d1 : d0; + + tmp.diagonal().array () -= eivals(k); + VectorType cross; + Scalar n; + n = (cross = tmp.row(0).cross(tmp.row(1))).squaredNorm(); + + if(n>safeNorm2) + eivecs.col(k) = cross / sqrt(n); + else + { + n = (cross = tmp.row(0).cross(tmp.row(2))).squaredNorm(); + + if(n>safeNorm2) + eivecs.col(k) = cross / sqrt(n); + else + { + n = (cross = tmp.row(1).cross(tmp.row(2))).squaredNorm(); + + if(n>safeNorm2) + eivecs.col(k) = cross / sqrt(n); + else + { + // the input matrix and/or the eigenvaues probably contains some inf/NaN, + // => exit + // scale back to the original size. + eivals *= scale; + + solver.m_info = NumericalIssue; + solver.m_isInitialized = true; + solver.m_eigenvectorsOk = computeEigenvectors; + return; + } + } + } + + tmp = scaledMat; + tmp.diagonal().array() -= eivals(1); + + if(d0<=Eigen::NumTraits::epsilon()) + eivecs.col(1) = eivecs.col(k).unitOrthogonal(); + else + { + n = (cross = eivecs.col(k).cross(tmp.row(0).normalized())).squaredNorm(); + if(n>safeNorm2) + eivecs.col(1) = cross / sqrt(n); + else + { + n = (cross = eivecs.col(k).cross(tmp.row(1))).squaredNorm(); + if(n>safeNorm2) + eivecs.col(1) = cross / sqrt(n); + else + { + n = (cross = eivecs.col(k).cross(tmp.row(2))).squaredNorm(); + if(n>safeNorm2) + eivecs.col(1) = cross / sqrt(n); + else + { + // we should never reach this point, + // if so the last two eigenvalues are likely to ve very closed to each other + eivecs.col(1) = eivecs.col(k).unitOrthogonal(); + } + } + } + + // make sure that eivecs[1] is orthogonal to eivecs[2] + Scalar d = eivecs.col(1).dot(eivecs.col(k)); + eivecs.col(1) = (eivecs.col(1) - d * eivecs.col(k)).normalized(); + } + + eivecs.col(k==2 ? 0 : 2) = eivecs.col(k).cross(eivecs.col(1)).normalized(); + } + } + // Rescale back to the original size. + eivals *= scale; + + solver.m_info = Success; + solver.m_isInitialized = true; + solver.m_eigenvectorsOk = computeEigenvectors; + } +}; + +// 2x2 direct eigenvalues decomposition, code from Hauke Heibel +template struct direct_selfadjoint_eigenvalues +{ + typedef typename SolverType::MatrixType MatrixType; + typedef typename SolverType::RealVectorType VectorType; + typedef typename SolverType::Scalar Scalar; + + static inline void computeRoots(const MatrixType& m, VectorType& roots) + { + using std::sqrt; + const Scalar t0 = Scalar(0.5) * sqrt( abs2(m(0,0)-m(1,1)) + Scalar(4)*m(1,0)*m(1,0)); + const Scalar t1 = Scalar(0.5) * (m(0,0) + m(1,1)); + roots(0) = t1 - t0; + roots(1) = t1 + t0; + } + + static inline void run(SolverType& solver, const MatrixType& mat, int options) + { + eigen_assert(mat.cols() == 2 && mat.cols() == mat.rows()); + eigen_assert((options&~(EigVecMask|GenEigMask))==0 + && (options&EigVecMask)!=EigVecMask + && "invalid option parameter"); + bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; + + MatrixType& eivecs = solver.m_eivec; + VectorType& eivals = solver.m_eivalues; + + // map the matrix coefficients to [-1:1] to avoid over- and underflow. + Scalar scale = mat.cwiseAbs().maxCoeff(); + scale = (std::max)(scale,Scalar(1)); + MatrixType scaledMat = mat / scale; + + // Compute the eigenvalues + computeRoots(scaledMat,eivals); + + // compute the eigen vectors + if(computeEigenvectors) + { + scaledMat.diagonal().array () -= eivals(1); + Scalar a2 = abs2(scaledMat(0,0)); + Scalar c2 = abs2(scaledMat(1,1)); + Scalar b2 = abs2(scaledMat(1,0)); + if(a2>c2) + { + eivecs.col(1) << -scaledMat(1,0), scaledMat(0,0); + eivecs.col(1) /= sqrt(a2+b2); + } + else + { + eivecs.col(1) << -scaledMat(1,1), scaledMat(1,0); + eivecs.col(1) /= sqrt(c2+b2); + } + + eivecs.col(0) << eivecs.col(1).unitOrthogonal(); + } + + // Rescale back to the original size. + eivals *= scale; + + solver.m_info = Success; + solver.m_isInitialized = true; + solver.m_eigenvectorsOk = computeEigenvectors; + } +}; + +} + +template +SelfAdjointEigenSolver& SelfAdjointEigenSolver +::computeDirect(const MatrixType& matrix, int options) +{ + internal::direct_selfadjoint_eigenvalues::IsComplex>::run(*this,matrix,options); + return *this; +} + namespace internal { template static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n) @@ -515,6 +796,9 @@ static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index sta } } } + } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_SELFADJOINTEIGENSOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h new file mode 100644 index 000000000..5ebcd08e1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h @@ -0,0 +1,92 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Self-adjoint eigenvalues/eigenvectors. + ******************************************************************************** +*/ + +#ifndef EIGEN_SAEIGENSOLVER_MKL_H +#define EIGEN_SAEIGENSOLVER_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_EIG_SELFADJ(EIGTYPE, MKLTYPE, MKLRTYPE, MKLNAME, EIGCOLROW, MKLCOLROW ) \ +template<> \ +SelfAdjointEigenSolver >& \ +SelfAdjointEigenSolver >::compute(const Matrix& matrix, int options) \ +{ \ + eigen_assert(matrix.cols() == matrix.rows()); \ + eigen_assert((options&~(EigVecMask|GenEigMask))==0 \ + && (options&EigVecMask)!=EigVecMask \ + && "invalid option parameter"); \ + bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; \ + lapack_int n = matrix.cols(), lda, matrix_order, info; \ + m_eivalues.resize(n,1); \ + m_subdiag.resize(n-1); \ + m_eivec = matrix; \ +\ + if(n==1) \ + { \ + m_eivalues.coeffRef(0,0) = internal::real(matrix.coeff(0,0)); \ + if(computeEigenvectors) m_eivec.setOnes(n,n); \ + m_info = Success; \ + m_isInitialized = true; \ + m_eigenvectorsOk = computeEigenvectors; \ + return *this; \ + } \ +\ + lda = matrix.outerStride(); \ + matrix_order=MKLCOLROW; \ + char jobz, uplo='L'/*, range='A'*/; \ + jobz = computeEigenvectors ? 'V' : 'N'; \ +\ + info = LAPACKE_##MKLNAME( matrix_order, jobz, uplo, n, (MKLTYPE*)m_eivec.data(), lda, (MKLRTYPE*)m_eivalues.data() ); \ + m_info = (info==0) ? Success : NoConvergence; \ + m_isInitialized = true; \ + m_eigenvectorsOk = computeEigenvectors; \ + return *this; \ +} + + +EIGEN_MKL_EIG_SELFADJ(double, double, double, dsyev, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_EIG_SELFADJ(float, float, float, ssyev, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_EIG_SELFADJ(dcomplex, MKL_Complex16, double, zheev, ColMajor, LAPACK_COL_MAJOR) +EIGEN_MKL_EIG_SELFADJ(scomplex, MKL_Complex8, float, cheev, ColMajor, LAPACK_COL_MAJOR) + +EIGEN_MKL_EIG_SELFADJ(double, double, double, dsyev, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_MKL_EIG_SELFADJ(float, float, float, ssyev, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_MKL_EIG_SELFADJ(dcomplex, MKL_Complex16, double, zheev, RowMajor, LAPACK_ROW_MAJOR) +EIGEN_MKL_EIG_SELFADJ(scomplex, MKL_Complex8, float, cheev, RowMajor, LAPACK_ROW_MAJOR) + +} // end namespace Eigen + +#endif // EIGEN_SAEIGENSOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/Tridiagonalization.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/Tridiagonalization.h index ae4cdce7a..e8f0ac5d1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/Tridiagonalization.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/Tridiagonalization.h @@ -26,6 +26,8 @@ #ifndef EIGEN_TRIDIAGONALIZATION_H #define EIGEN_TRIDIAGONALIZATION_H +namespace Eigen { + namespace internal { template struct TridiagonalizationMatrixTReturnType; @@ -97,13 +99,13 @@ template class Tridiagonalization typedef internal::TridiagonalizationMatrixTReturnType MatrixTReturnType; typedef typename internal::conditional::IsComplex, - const typename Diagonal::RealReturnType, + typename internal::add_const_on_value_type::RealReturnType>::type, const Diagonal >::type DiagonalReturnType; typedef typename internal::conditional::IsComplex, - const typename Diagonal< - Block >::RealReturnType, + typename internal::add_const_on_value_type >::RealReturnType>::type, const Diagonal< Block > >::type SubDiagonalReturnType; @@ -560,9 +562,11 @@ template struct TridiagonalizationMatrixTReturnType Index cols() const { return m_matrix.cols(); } protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; }; } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_TRIDIAGONALIZATION_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h index b51deb3f3..2cb894330 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ALIGNEDBOX_H #define EIGEN_ALIGNEDBOX_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * @@ -190,7 +192,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) template inline bool contains(const MatrixBase& a_p) const { - const typename internal::nested::type p(a_p.derived()); + typename internal::nested::type p(a_p.derived()); return (m_min.array()<=p.array()).all() && (p.array()<=m_max.array()).all(); } @@ -202,7 +204,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) template inline AlignedBox& extend(const MatrixBase& a_p) { - const typename internal::nested::type p(a_p.derived()); + typename internal::nested::type p(a_p.derived()); m_min = m_min.cwiseMin(p); m_max = m_max.cwiseMax(p); return *this; @@ -310,7 +312,7 @@ template inline Scalar AlignedBox::squaredExteriorDistance(const MatrixBase& a_p) const { const typename internal::nested::type p(a_p.derived()); - Scalar dist2 = 0.; + Scalar dist2(0); Scalar aux; for (Index k=0; k::squaredExteriorDistance(const Matri template inline Scalar AlignedBox::squaredExteriorDistance(const AlignedBox& b) const { - Scalar dist2 = 0.; + Scalar dist2(0); Scalar aux; for (Index k=0; k::squaredExteriorDistance(const Align return dist2; } +/** \defgroup alignedboxtypedefs Global aligned box typedefs + * + * \ingroup Geometry_Module + * + * Eigen defines several typedef shortcuts for most common aligned box types. + * + * The general patterns are the following: + * + * \c AlignedBoxSizeType where \c Size can be \c 1, \c 2,\c 3,\c 4 for fixed size boxes or \c X for dynamic size, + * and where \c Type can be \c i for integer, \c f for float, \c d for double. + * + * For example, \c AlignedBox3d is a fixed-size 3x3 aligned box type of doubles, and \c AlignedBoxXf is a dynamic-size aligned box of floats. + * + * \sa class AlignedBox + */ + +#define EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Size, SizeSuffix) \ +/** \ingroup alignedboxtypedefs */ \ +typedef AlignedBox AlignedBox##SizeSuffix##TypeSuffix; + +#define EIGEN_MAKE_TYPEDEFS_ALL_SIZES(Type, TypeSuffix) \ +EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 1, 1) \ +EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 2, 2) \ +EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 3, 3) \ +EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 4, 4) \ +EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Dynamic, X) + +EIGEN_MAKE_TYPEDEFS_ALL_SIZES(int, i) +EIGEN_MAKE_TYPEDEFS_ALL_SIZES(float, f) +EIGEN_MAKE_TYPEDEFS_ALL_SIZES(double, d) + +#undef EIGEN_MAKE_TYPEDEFS_ALL_SIZES +#undef EIGEN_MAKE_TYPEDEFS + +} // end namespace Eigen + #endif // EIGEN_ALIGNEDBOX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h index 0ec4624cf..f0e3ff2b3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ANGLEAXIS_H #define EIGEN_ANGLEAXIS_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class AngleAxis @@ -144,7 +146,7 @@ public: m_angle = Scalar(other.angle()); } - inline static const AngleAxis Identity() { return AngleAxis(0, Vector3::UnitX()); } + static inline const AngleAxis Identity() { return AngleAxis(0, Vector3::UnitX()); } /** \returns \c true if \c *this is approximately equal to \a other, within the precision * determined by \a prec. @@ -238,4 +240,6 @@ AngleAxis::toRotationMatrix(void) const return res; } +} // end namespace Eigen + #endif // EIGEN_ANGLEAXIS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/EulerAngles.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/EulerAngles.h index d246a6ebf..0ce7f957d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/EulerAngles.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/EulerAngles.h @@ -25,6 +25,8 @@ #ifndef EIGEN_EULERANGLES_H #define EIGEN_EULERANGLES_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * @@ -92,5 +94,6 @@ MatrixBase::eulerAngles(Index a0, Index a1, Index a2) const return res; } +} // end namespace Eigen #endif // EIGEN_EULERANGLES_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h index 2bc4f7e87..0c4cda01d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h @@ -25,6 +25,8 @@ #ifndef EIGEN_HOMOGENEOUS_H #define EIGEN_HOMOGENEOUS_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Homogeneous @@ -121,7 +123,7 @@ template class Homogeneous } protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; }; /** \geometry_module @@ -216,8 +218,8 @@ template struct take_matrix_for_product > { typedef Transform TransformType; - typedef typename TransformType::ConstAffinePart type; - static const type run (const TransformType& x) { return x.affine(); } + typedef typename internal::add_const::type type; + static type run (const TransformType& x) { return x.affine(); } }; template @@ -270,8 +272,8 @@ struct homogeneous_left_product_impl,Lhs> .template replicate(m_rhs.cols()); } - const typename LhsMatrixTypeCleaned::Nested m_lhs; - const typename MatrixType::Nested m_rhs; + typename LhsMatrixTypeCleaned::Nested m_lhs; + typename MatrixType::Nested m_rhs; }; template @@ -309,10 +311,12 @@ struct homogeneous_right_product_impl,Rhs> .template replicate(m_lhs.rows()); } - const typename MatrixType::Nested m_lhs; - const typename Rhs::Nested m_rhs; + typename MatrixType::Nested m_lhs; + typename Rhs::Nested m_rhs; }; } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_HOMOGENEOUS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Hyperplane.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Hyperplane.h index d85d3e553..6abf1664d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Hyperplane.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Hyperplane.h @@ -26,6 +26,8 @@ #ifndef EIGEN_HYPERPLANE_H #define EIGEN_HYPERPLANE_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Hyperplane @@ -277,4 +279,6 @@ protected: Coefficients m_coeffs; }; +} // end namespace Eigen + #endif // EIGEN_HYPERPLANE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/OrthoMethods.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/OrthoMethods.h index 52b469881..0a8a81dd1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/OrthoMethods.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/OrthoMethods.h @@ -26,6 +26,8 @@ #ifndef EIGEN_ORTHOMETHODS_H #define EIGEN_ORTHOMETHODS_H +namespace Eigen { + /** \geometry_module * * \returns the cross product of \c *this and \a other @@ -43,8 +45,8 @@ MatrixBase::cross(const MatrixBase& other) const // Note that there is no need for an expression here since the compiler // optimize such a small temporary very well (even within a complex expression) - const typename internal::nested::type lhs(derived()); - const typename internal::nested::type rhs(other.derived()); + typename internal::nested::type lhs(derived()); + typename internal::nested::type rhs(other.derived()); return typename cross_product_return_type::type( internal::conj(lhs.coeff(1) * rhs.coeff(2) - lhs.coeff(2) * rhs.coeff(1)), internal::conj(lhs.coeff(2) * rhs.coeff(0) - lhs.coeff(0) * rhs.coeff(2)), @@ -56,9 +58,9 @@ namespace internal { template< int Arch,typename VectorLhs,typename VectorRhs, typename Scalar = typename VectorLhs::Scalar, - bool Vectorizable = (VectorLhs::Flags&VectorRhs::Flags)&PacketAccessBit> + bool Vectorizable = bool((VectorLhs::Flags&VectorRhs::Flags)&PacketAccessBit)> struct cross3_impl { - inline static typename internal::plain_matrix_type::type + static inline typename internal::plain_matrix_type::type run(const VectorLhs& lhs, const VectorRhs& rhs) { return typename internal::plain_matrix_type::type( @@ -145,7 +147,7 @@ struct unitOrthogonal_selector typedef typename NumTraits::Real RealScalar; typedef typename Derived::Index Index; typedef Matrix Vector2; - inline static VectorType run(const Derived& src) + static inline VectorType run(const Derived& src) { VectorType perp = VectorType::Zero(src.size()); Index maxi = 0; @@ -167,7 +169,7 @@ struct unitOrthogonal_selector typedef typename plain_matrix_type::type VectorType; typedef typename traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - inline static VectorType run(const Derived& src) + static inline VectorType run(const Derived& src) { VectorType perp; /* Let us compute the crossed product of *this with a vector @@ -205,7 +207,7 @@ template struct unitOrthogonal_selector { typedef typename plain_matrix_type::type VectorType; - inline static VectorType run(const Derived& src) + static inline VectorType run(const Derived& src) { return VectorType(-conj(src.y()), conj(src.x())).normalized(); } }; @@ -226,4 +228,6 @@ MatrixBase::unitOrthogonal() const return internal::unitOrthogonal_selector::run(derived()); } +} // end namespace Eigen + #endif // EIGEN_ORTHOMETHODS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/ParametrizedLine.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/ParametrizedLine.h index b90f9c088..ddbda83dc 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/ParametrizedLine.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/ParametrizedLine.h @@ -26,6 +26,8 @@ #ifndef EIGEN_PARAMETRIZEDLINE_H #define EIGEN_PARAMETRIZEDLINE_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class ParametrizedLine @@ -106,8 +108,16 @@ public: VectorType projection(const VectorType& p) const { return origin() + direction().dot(p-origin()) * direction(); } + VectorType pointAt( Scalar t ) const; + + template + Scalar intersectionParameter(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const; + template Scalar intersection(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const; + + template + VectorType intersectionPoint(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const; /** \returns \c *this with scalar type casted to \a NewScalarType * @@ -155,14 +165,46 @@ inline ParametrizedLine<_Scalar, _AmbientDim,_Options>::ParametrizedLine(const H origin() = -hyperplane.normal()*hyperplane.offset(); } -/** \returns the parameter value of the intersection between \c *this and the given hyperplane +/** \returns the point at \a t along this line + */ +template +inline typename ParametrizedLine<_Scalar, _AmbientDim,_Options>::VectorType +ParametrizedLine<_Scalar, _AmbientDim,_Options>::pointAt( _Scalar t ) const +{ + return origin() + (direction()*t); +} + +/** \returns the parameter value of the intersection between \c *this and the given \a hyperplane */ template template -inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersection(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const +inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersectionParameter(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const { return -(hyperplane.offset()+hyperplane.normal().dot(origin())) / hyperplane.normal().dot(direction()); } + +/** \deprecated use intersectionParameter() + * \returns the parameter value of the intersection between \c *this and the given \a hyperplane + */ +template +template +inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersection(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const +{ + return intersectionParameter(hyperplane); +} + +/** \returns the point of the intersection between \c *this and the given hyperplane + */ +template +template +inline typename ParametrizedLine<_Scalar, _AmbientDim,_Options>::VectorType +ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersectionPoint(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const +{ + return pointAt(intersectionParameter(hyperplane)); +} + +} // end namespace Eigen + #endif // EIGEN_PARAMETRIZEDLINE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h index 9180db67d..75083363c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h @@ -25,6 +25,8 @@ #ifndef EIGEN_QUATERNION_H #define EIGEN_QUATERNION_H +namespace Eigen { + /*************************************************************************** * Definition of QuaternionBase @@ -38,6 +40,12 @@ template class QuaternionBase : public RotationBase { @@ -109,7 +117,7 @@ public: /** \returns a quaternion representing an identity rotation * \sa MatrixBase::Identity() */ - inline static Quaternion Identity() { return Quaternion(1, 0, 0, 0); } + static inline Quaternion Identity() { return Quaternion(1, 0, 0, 0); } /** \sa QuaternionBase::Identity(), MatrixBase::setIdentity() */ @@ -278,6 +286,9 @@ public: explicit inline Quaternion(const Quaternion& other) { m_coeffs = other.coeffs().template cast(); } + template + static Quaternion FromTwoVectors(const MatrixBase& a, const MatrixBase& b); + inline Coefficients& coeffs() { return m_coeffs;} inline const Coefficients& coeffs() const { return m_coeffs;} @@ -287,7 +298,7 @@ protected: Coefficients m_coeffs; #ifndef EIGEN_PARSED_BY_DOXYGEN - EIGEN_STRONG_INLINE static void _check_template_params() + static EIGEN_STRONG_INLINE void _check_template_params() { EIGEN_STATIC_ASSERT( (_Options & DontAlign) == _Options, INVALID_MATRIX_TEMPLATE_PARAMETERS) @@ -434,7 +445,7 @@ typedef Map, Aligned> QuaternionMapAlignedd; namespace internal { template struct quat_product { - EIGEN_STRONG_INLINE static Quaternion run(const QuaternionBase& a, const QuaternionBase& b){ + static EIGEN_STRONG_INLINE Quaternion run(const QuaternionBase& a, const QuaternionBase& b){ return Quaternion ( a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(), @@ -544,9 +555,9 @@ QuaternionBase::toRotationMatrix(void) const // it has to be inlined, and so the return by value is not an issue Matrix3 res; - const Scalar tx = 2*this->x(); - const Scalar ty = 2*this->y(); - const Scalar tz = 2*this->z(); + const Scalar tx = Scalar(2)*this->x(); + const Scalar ty = Scalar(2)*this->y(); + const Scalar tz = Scalar(2)*this->z(); const Scalar twx = tx*this->w(); const Scalar twy = ty*this->w(); const Scalar twz = tz*this->w(); @@ -557,15 +568,15 @@ QuaternionBase::toRotationMatrix(void) const const Scalar tyz = tz*this->y(); const Scalar tzz = tz*this->z(); - res.coeffRef(0,0) = 1-(tyy+tzz); + res.coeffRef(0,0) = Scalar(1)-(tyy+tzz); res.coeffRef(0,1) = txy-twz; res.coeffRef(0,2) = txz+twy; res.coeffRef(1,0) = txy+twz; - res.coeffRef(1,1) = 1-(txx+tzz); + res.coeffRef(1,1) = Scalar(1)-(txx+tzz); res.coeffRef(1,2) = tyz-twx; res.coeffRef(2,0) = txz-twy; res.coeffRef(2,1) = tyz+twx; - res.coeffRef(2,2) = 1-(txx+tyy); + res.coeffRef(2,2) = Scalar(1)-(txx+tyy); return res; } @@ -618,6 +629,27 @@ inline Derived& QuaternionBase::setFromTwoVectors(const MatrixBase +template +Quaternion Quaternion::FromTwoVectors(const MatrixBase& a, const MatrixBase& b) +{ + Quaternion quat; + quat.setFromTwoVectors(a, b); + return quat; +} + + /** \returns the multiplicative inverse of \c *this * Note that in most cases, i.e., if you simply want the opposite rotation, * and/or the quaternion is normalized, then it is enough to use the conjugate. @@ -709,7 +741,7 @@ struct quaternionbase_assign_impl { typedef typename Other::Scalar Scalar; typedef DenseIndex Index; - template inline static void run(QuaternionBase& q, const Other& mat) + template static inline void run(QuaternionBase& q, const Other& mat) { // This algorithm comes from "Quaternion Calculus and Fast Animation", // Ken Shoemake, 1987 SIGGRAPH course notes @@ -748,7 +780,7 @@ template struct quaternionbase_assign_impl { typedef typename Other::Scalar Scalar; - template inline static void run(QuaternionBase& q, const Other& vec) + template static inline void run(QuaternionBase& q, const Other& vec) { q.coeffs() = vec; } @@ -756,4 +788,6 @@ struct quaternionbase_assign_impl } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_QUATERNION_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Rotation2D.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Rotation2D.h index cf36da1c5..4339e0f0f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Rotation2D.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Rotation2D.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ROTATION2D_H #define EIGEN_ROTATION2D_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Rotation2D @@ -121,7 +123,7 @@ public: m_angle = Scalar(other.angle()); } - inline static Rotation2D Identity() { return Rotation2D(0); } + static inline Rotation2D Identity() { return Rotation2D(0); } /** \returns \c true if \c *this is approximately equal to \a other, within the precision * determined by \a prec. @@ -162,4 +164,6 @@ Rotation2D::toRotationMatrix(void) const return (Matrix2() << cosA, -sinA, sinA, cosA).finished(); } +} // end namespace Eigen + #endif // EIGEN_ROTATION2D_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/RotationBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/RotationBase.h index 1abf06bb6..0b8fb0a52 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/RotationBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/RotationBase.h @@ -25,6 +25,8 @@ #ifndef EIGEN_ROTATIONBASE_H #define EIGEN_ROTATIONBASE_H +namespace Eigen { + // forward declaration namespace internal { template @@ -115,7 +117,7 @@ struct rotation_base_generic_product_selector { enum { Dim = RotationDerived::Dim }; typedef Matrix ReturnType; - inline static ReturnType run(const RotationDerived& r, const MatrixType& m) + static inline ReturnType run(const RotationDerived& r, const MatrixType& m) { return r.toRotationMatrix() * m; } }; @@ -123,7 +125,7 @@ template struct rotation_base_generic_product_selector< RotationDerived, DiagonalMatrix, false > { typedef Transform ReturnType; - inline static ReturnType run(const RotationDerived& r, const DiagonalMatrix& m) + static inline ReturnType run(const RotationDerived& r, const DiagonalMatrix& m) { ReturnType res(r); res.linear() *= m; @@ -136,7 +138,7 @@ struct rotation_base_generic_product_selector ReturnType; - EIGEN_STRONG_INLINE static ReturnType run(const RotationDerived& r, const OtherVectorType& v) + static EIGEN_STRONG_INLINE ReturnType run(const RotationDerived& r, const OtherVectorType& v) { return r._transformVector(v); } @@ -192,20 +194,20 @@ namespace internal { * \sa class Transform, class Rotation2D, class Quaternion, class AngleAxis */ template -inline static Matrix toRotationMatrix(const Scalar& s) +static inline Matrix toRotationMatrix(const Scalar& s) { EIGEN_STATIC_ASSERT(Dim==2,YOU_MADE_A_PROGRAMMING_MISTAKE) return Rotation2D(s).toRotationMatrix(); } template -inline static Matrix toRotationMatrix(const RotationBase& r) +static inline Matrix toRotationMatrix(const RotationBase& r) { return r.toRotationMatrix(); } template -inline static const MatrixBase& toRotationMatrix(const MatrixBase& mat) +static inline const MatrixBase& toRotationMatrix(const MatrixBase& mat) { EIGEN_STATIC_ASSERT(OtherDerived::RowsAtCompileTime==Dim && OtherDerived::ColsAtCompileTime==Dim, YOU_MADE_A_PROGRAMMING_MISTAKE) @@ -214,4 +216,6 @@ inline static const MatrixBase& toRotationMatrix(const MatrixBase< } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_ROTATIONBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Scaling.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Scaling.h index c911d13e1..080f33794 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Scaling.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Scaling.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SCALING_H #define EIGEN_SCALING_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Scaling @@ -179,4 +181,6 @@ UniformScaling::operator* (const Transform& t return res; } +} // end namespace Eigen + #endif // EIGEN_SCALING_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h index 19d012572..e81305ccc 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h @@ -27,6 +27,8 @@ #ifndef EIGEN_TRANSFORM_H #define EIGEN_TRANSFORM_H +namespace Eigen { + namespace internal { template @@ -37,7 +39,7 @@ struct transform_traits Dim = Transform::Dim, HDim = Transform::HDim, Mode = Transform::Mode, - IsProjective = (Mode==Projective) + IsProjective = (int(Mode)==int(Projective)) }; }; @@ -61,7 +63,7 @@ template< typename Lhs, typename Rhs, bool AnyProjective = transform_traits::IsProjective || - transform_traits::IsProjective> + transform_traits::IsProjective> struct transform_transform_product_impl; template< typename Other, @@ -207,9 +209,9 @@ public: /** type of the matrix used to represent the linear part of the transformation */ typedef Matrix LinearMatrixType; /** type of read/write reference to the linear part of the transformation */ - typedef Block LinearPart; + typedef Block LinearPart; /** type of read reference to the linear part of the transformation */ - typedef const Block ConstLinearPart; + typedef const Block ConstLinearPart; /** type of read/write reference to the affine part of the transformation */ typedef typename internal::conditional VectorType; /** type of a read/write reference to the translation part of the rotation */ - typedef Block TranslationPart; + typedef Block TranslationPart; /** type of a read reference to the translation part of the rotation */ - typedef const Block ConstTranslationPart; + typedef const Block ConstTranslationPart; /** corresponding translation type */ typedef Translation TranslationType; @@ -279,6 +281,9 @@ public: template inline explicit Transform(const EigenBase& other) { + EIGEN_STATIC_ASSERT((internal::is_same::value), + YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY); + check_template_params(); internal::transform_construct_from_matrix::run(this, other.derived()); } @@ -287,6 +292,9 @@ public: template inline Transform& operator=(const EigenBase& other) { + EIGEN_STATIC_ASSERT((internal::is_same::value), + YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY); + internal::transform_construct_from_matrix::run(this, other.derived()); return *this; } @@ -376,9 +384,9 @@ public: inline MatrixType& matrix() { return m_matrix; } /** \returns a read-only expression of the linear part of the transformation */ - inline ConstLinearPart linear() const { return m_matrix.template block(0,0); } + inline ConstLinearPart linear() const { return ConstLinearPart(m_matrix,0,0); } /** \returns a writable expression of the linear part of the transformation */ - inline LinearPart linear() { return m_matrix.template block(0,0); } + inline LinearPart linear() { return LinearPart(m_matrix,0,0); } /** \returns a read-only expression of the Dim x HDim affine part of the transformation */ inline ConstAffinePart affine() const { return take_affine_part::run(m_matrix); } @@ -386,9 +394,9 @@ public: inline AffinePart affine() { return take_affine_part::run(m_matrix); } /** \returns a read-only expression of the translation vector of the transformation */ - inline ConstTranslationPart translation() const { return m_matrix.template block(0,Dim); } + inline ConstTranslationPart translation() const { return ConstTranslationPart(m_matrix,0,Dim); } /** \returns a writable expression of the translation vector of the transformation */ - inline TranslationPart translation() { return m_matrix.template block(0,Dim); } + inline TranslationPart translation() { return TranslationPart(m_matrix,0,Dim); } /** \returns an expression of the product between the transform \c *this and a matrix expression \a other * @@ -460,15 +468,40 @@ public: { return internal::transform_transform_product_impl::run(*this,other); } - + + #ifdef __INTEL_COMPILER +private: + // this intermediate structure permits to workaround a bug in ICC 11: + // error: template instantiation resulted in unexpected function type of "Eigen::Transform + // (const Eigen::Transform &) const" + // (the meaning of a name may have changed since the template declaration -- the type of the template is: + // "Eigen::internal::transform_transform_product_impl, + // Eigen::Transform, >::ResultType (const Eigen::Transform &) const") + // + template struct icc_11_workaround + { + typedef internal::transform_transform_product_impl > ProductType; + typedef typename ProductType::ResultType ResultType; + }; + +public: /** Concatenates two different transformations */ template - inline const typename internal::transform_transform_product_impl< - Transform,Transform >::ResultType + inline typename icc_11_workaround::ResultType + operator * (const Transform& other) const + { + typedef typename icc_11_workaround::ProductType ProductType; + return ProductType::run(*this,other); + } + #else + /** Concatenates two different transformations */ + template + inline typename internal::transform_transform_product_impl >::ResultType operator * (const Transform& other) const { return internal::transform_transform_product_impl >::run(*this,other); } + #endif /** \sa MatrixBase::setIdentity() */ void setIdentity() { m_matrix.setIdentity(); } @@ -608,7 +641,7 @@ public: protected: #ifndef EIGEN_PARSED_BY_DOXYGEN - EIGEN_STRONG_INLINE static void check_template_params() + static EIGEN_STRONG_INLINE void check_template_params() { EIGEN_STATIC_ASSERT((Options & (DontAlign|RowMajor)) == Options, INVALID_MATRIX_TEMPLATE_PARAMETERS) } @@ -1219,7 +1252,7 @@ struct transform_right_product_impl< TransformType, MatrixType, 0 > { typedef typename MatrixType::PlainObject ResultType; - EIGEN_STRONG_INLINE static ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { return T.matrix() * other; } @@ -1237,11 +1270,11 @@ struct transform_right_product_impl< TransformType, MatrixType, 1 > typedef typename MatrixType::PlainObject ResultType; - EIGEN_STRONG_INLINE static ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { EIGEN_STATIC_ASSERT(OtherRows==HDim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES); - typedef Block TopLeftLhs; + typedef Block TopLeftLhs; ResultType res(other.rows(),other.cols()); TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.affine() * other; @@ -1263,15 +1296,13 @@ struct transform_right_product_impl< TransformType, MatrixType, 2 > typedef typename MatrixType::PlainObject ResultType; - EIGEN_STRONG_INLINE static ResultType run(const TransformType& T, const MatrixType& other) + static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other) { EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES); - typedef Block TopLeftLhs; - - ResultType res(other.rows(),other.cols()); - TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.linear() * other; - TopLeftLhs(res, 0, 0, Dim, other.cols()).colwise() += T.translation(); + typedef Block TopLeftLhs; + ResultType res(Replicate(T.translation(),1,other.cols())); + TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() += T.linear() * other; return res; } @@ -1391,6 +1422,37 @@ struct transform_transform_product_impl } }; +template +struct transform_transform_product_impl,Transform,true > +{ + typedef Transform Lhs; + typedef Transform Rhs; + typedef Transform ResultType; + static ResultType run(const Lhs& lhs, const Rhs& rhs) + { + ResultType res; + res.matrix().template topRows() = lhs.matrix() * rhs.matrix(); + res.matrix().row(Dim) = rhs.matrix().row(Dim); + return res; + } +}; + +template +struct transform_transform_product_impl,Transform,true > +{ + typedef Transform Lhs; + typedef Transform Rhs; + typedef Transform ResultType; + static ResultType run(const Lhs& lhs, const Rhs& rhs) + { + ResultType res(lhs.matrix().template leftCols() * rhs.matrix()); + res.matrix().col(Dim) += lhs.matrix().col(Dim); + return res; + } +}; + } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_TRANSFORM_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Translation.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Translation.h index d8fe50f98..8d77a3d23 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Translation.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Translation.h @@ -25,6 +25,8 @@ #ifndef EIGEN_TRANSLATION_H #define EIGEN_TRANSLATION_H +namespace Eigen { + /** \geometry_module \ingroup Geometry_Module * * \class Translation @@ -54,6 +56,8 @@ public: typedef Matrix LinearMatrixType; /** corresponding affine transformation type */ typedef Transform AffineTransformType; + /** corresponding isometric transformation type */ + typedef Transform IsometryTransformType; protected: @@ -114,8 +118,8 @@ public: /** Concatenates a translation and a rotation */ template - inline AffineTransformType operator*(const RotationBase& r) const - { return *this * r.toRotationMatrix(); } + inline IsometryTransformType operator*(const RotationBase& r) const + { return *this * IsometryTransformType(r); } /** \returns the concatenation of a linear transformation \a l with the translation \a t */ // its a nightmare to define a templated friend function outside its declaration @@ -212,4 +216,6 @@ Translation::operator* (const EigenBase& linear) const return res; } +} // end namespace Eigen + #endif // EIGEN_TRANSLATION_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Umeyama.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Umeyama.h index b50f46173..4d4cc3632 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Umeyama.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Umeyama.h @@ -31,6 +31,8 @@ // * Eigen/SVD // * Eigen/Array +namespace Eigen { + #ifndef EIGEN_PARSED_BY_DOXYGEN // These helpers are required since it allows to use mixed types as parameters @@ -180,4 +182,6 @@ umeyama(const MatrixBase& src, const MatrixBase& dst, boo return Rt; } +} // end namespace Eigen + #endif // EIGEN_UMEYAMA_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/arch/Geometry_SSE.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/arch/Geometry_SSE.h index cbe695c72..08d0f600a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/arch/Geometry_SSE.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/arch/Geometry_SSE.h @@ -26,12 +26,14 @@ #ifndef EIGEN_GEOMETRY_SSE_H #define EIGEN_GEOMETRY_SSE_H +namespace Eigen { + namespace internal { template struct quat_product { - inline static Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) + static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) { const __m128 mask = _mm_castsi128_ps(_mm_setr_epi32(0,0,0,0x80000000)); Quaternion res; @@ -53,7 +55,7 @@ struct quat_product template struct cross3_impl { - inline static typename plain_matrix_type::type + static inline typename plain_matrix_type::type run(const VectorLhs& lhs, const VectorRhs& rhs) { __m128 a = lhs.template packet(0); @@ -72,7 +74,7 @@ struct cross3_impl template struct quat_product { - inline static Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) + static inline Quaternion run(const QuaternionBase& _a, const QuaternionBase& _b) { const Packet2d mask = _mm_castsi128_pd(_mm_set_epi32(0x0,0x0,0x80000000,0x0)); @@ -96,7 +98,7 @@ struct quat_product */ t1 = padd(pmul(a_ww, b_xy), pmul(a_yy, b_zw)); t2 = psub(pmul(a_zz, b_xy), pmul(a_xx, b_zw)); -#ifdef __SSE3__ +#ifdef EIGEN_VECTORIZE_SSE3 EIGEN_UNUSED_VARIABLE(mask) pstore(&res.x(), _mm_addsub_pd(t1, preverse(t2))); #else @@ -110,7 +112,7 @@ struct quat_product */ t1 = psub(pmul(a_ww, b_zw), pmul(a_yy, b_xy)); t2 = padd(pmul(a_zz, b_zw), pmul(a_xx, b_xy)); -#ifdef __SSE3__ +#ifdef EIGEN_VECTORIZE_SSE3 EIGEN_UNUSED_VARIABLE(mask) pstore(&res.z(), preverse(_mm_addsub_pd(preverse(t1), t2))); #else @@ -123,4 +125,6 @@ struct quat_product } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_GEOMETRY_SSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h index 23ce1bfbd..b69fd46d5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h @@ -28,6 +28,8 @@ // This file contains some helper function to deal with block householder reflectors +namespace Eigen { + namespace internal { /** \internal */ @@ -64,7 +66,7 @@ void apply_block_householder_on_the_left(MatrixType& mat, const VectorsType& vec Matrix T(nbVecs,nbVecs); make_block_householder_triangular_factor(T, vectors, hCoeffs); - const TriangularView& V(vectors); + const TriangularView& V(vectors); // A -= V T V^* A Matrix struct decrement_size { @@ -35,6 +37,22 @@ template struct decrement_size }; } +/** Computes the elementary reflector H such that: + * \f$ H *this = [ beta 0 ... 0]^T \f$ + * where the transformation H is: + * \f$ H = I - tau v v^*\f$ + * and the vector v is: + * \f$ v^T = [1 essential^T] \f$ + * + * The essential part of the vector \c v is stored in *this. + * + * On output: + * \param tau the scaling factor of the Householder transformation + * \param beta the result of H * \c *this + * + * \sa MatrixBase::makeHouseholder(), MatrixBase::applyHouseholderOnTheLeft(), + * MatrixBase::applyHouseholderOnTheRight() + */ template void MatrixBase::makeHouseholderInPlace(Scalar& tau, RealScalar& beta) { @@ -51,7 +69,7 @@ void MatrixBase::makeHouseholderInPlace(Scalar& tau, RealScalar& beta) * * On output: * \param essential the essential part of the vector \c v - * \param tau the scaling factor of the householder transformation + * \param tau the scaling factor of the Householder transformation * \param beta the result of H * \c *this * * \sa MatrixBase::makeHouseholderInPlace(), MatrixBase::applyHouseholderOnTheLeft(), @@ -86,6 +104,21 @@ void MatrixBase::makeHouseholder( } } +/** Apply the elementary reflector H given by + * \f$ H = I - tau v v^*\f$ + * with + * \f$ v^T = [1 essential^T] \f$ + * from the left to a vector or matrix. + * + * On input: + * \param essential the essential part of the vector \c v + * \param tau the scaling factor of the Householder transformation + * \param workspace a pointer to working space with at least + * this->cols() * essential.size() entries + * + * \sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), + * MatrixBase::applyHouseholderOnTheRight() + */ template template void MatrixBase::applyHouseholderOnTheLeft( @@ -108,6 +141,21 @@ void MatrixBase::applyHouseholderOnTheLeft( } } +/** Apply the elementary reflector H given by + * \f$ H = I - tau v v^*\f$ + * with + * \f$ v^T = [1 essential^T] \f$ + * from the right to a vector or matrix. + * + * On input: + * \param essential the essential part of the vector \c v + * \param tau the scaling factor of the Householder transformation + * \param workspace a pointer to working space with at least + * this->cols() * essential.size() entries + * + * \sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), + * MatrixBase::applyHouseholderOnTheLeft() + */ template template void MatrixBase::applyHouseholderOnTheRight( @@ -130,4 +178,6 @@ void MatrixBase::applyHouseholderOnTheRight( } } +} // end namespace Eigen + #endif // EIGEN_HOUSEHOLDER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Householder/HouseholderSequence.h b/gtsam/3rdparty/Eigen/Eigen/src/Householder/HouseholderSequence.h index 717f29c99..1cb461b48 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Householder/HouseholderSequence.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Householder/HouseholderSequence.h @@ -26,6 +26,8 @@ #ifndef EIGEN_HOUSEHOLDER_SEQUENCE_H #define EIGEN_HOUSEHOLDER_SEQUENCE_H +namespace Eigen { + /** \ingroup Householder_Module * \householder_module * \class HouseholderSequence @@ -237,13 +239,20 @@ template class HouseholderS ConjugateReturnType inverse() const { return adjoint(); } /** \internal */ - template void evalTo(DestType& dst) const + template inline void evalTo(DestType& dst) const { - Index vecs = m_length; - // FIXME find a way to pass this temporary if the user wants to Matrix temp(rows()); - if( internal::is_same::type,DestType>::value + AutoAlign|ColMajor, DestType::MaxRowsAtCompileTime, 1> workspace(rows()); + evalTo(dst, workspace); + } + + /** \internal */ + template + void evalTo(Dest& dst, Workspace& workspace) const + { + workspace.resize(rows()); + Index vecs = m_length; + if( internal::is_same::type,Dest>::value && internal::extract_data(dst) == internal::extract_data(m_vectors)) { // in-place @@ -254,10 +263,10 @@ template class HouseholderS Index cornerSize = rows() - k - m_shift; if(m_trans) dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), &temp.coeffRef(0)); + .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data()); else dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), &temp.coeffRef(0)); + .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data()); // clear the off diagonal vector dst.col(k).tail(rows()-k-1).setZero(); @@ -274,10 +283,10 @@ template class HouseholderS Index cornerSize = rows() - k - m_shift; if(m_trans) dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), &temp.coeffRef(0)); + .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), &workspace.coeffRef(0)); else dst.bottomRightCorner(cornerSize, cornerSize) - .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), &temp.coeffRef(0)); + .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), &workspace.coeffRef(0)); } } } @@ -285,24 +294,40 @@ template class HouseholderS /** \internal */ template inline void applyThisOnTheRight(Dest& dst) const { - Matrix temp(dst.rows()); + Matrix workspace(dst.rows()); + applyThisOnTheRight(dst, workspace); + } + + /** \internal */ + template + inline void applyThisOnTheRight(Dest& dst, Workspace& workspace) const + { + workspace.resize(dst.rows()); for(Index k = 0; k < m_length; ++k) { Index actual_k = m_trans ? m_length-k-1 : k; dst.rightCols(rows()-m_shift-actual_k) - .applyHouseholderOnTheRight(essentialVector(actual_k), m_coeffs.coeff(actual_k), &temp.coeffRef(0)); + .applyHouseholderOnTheRight(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data()); } } /** \internal */ template inline void applyThisOnTheLeft(Dest& dst) const { - Matrix temp(dst.cols()); + Matrix workspace(dst.cols()); + applyThisOnTheLeft(dst, workspace); + } + + /** \internal */ + template + inline void applyThisOnTheLeft(Dest& dst, Workspace& workspace) const + { + workspace.resize(dst.cols()); for(Index k = 0; k < m_length; ++k) { Index actual_k = m_trans ? k : m_length-k-1; dst.bottomRows(rows()-m_shift-actual_k) - .applyHouseholderOnTheLeft(essentialVector(actual_k), m_coeffs.coeff(actual_k), &temp.coeffRef(0)); + .applyHouseholderOnTheLeft(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data()); } } @@ -426,4 +451,6 @@ HouseholderSequence rightHouseholderSequence( return HouseholderSequence(v, h); } +} // end namespace Eigen + #endif // EIGEN_HOUSEHOLDER_SEQUENCE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h new file mode 100644 index 000000000..c9fe9c618 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h @@ -0,0 +1,163 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_BASIC_PRECONDITIONERS_H +#define EIGEN_BASIC_PRECONDITIONERS_H + +namespace Eigen { + +/** \ingroup IterativeLinearSolvers_Module + * \brief A preconditioner based on the digonal entries + * + * This class allows to approximately solve for A.x = b problems assuming A is a diagonal matrix. + * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for: + * \code + * A.diagonal().asDiagonal() . x = b + * \endcode + * + * \tparam _Scalar the type of the scalar. + * + * This preconditioner is suitable for both selfadjoint and general problems. + * The diagonal entries are pre-inverted and stored into a dense vector. + * + * \note A variant that has yet to be implemented would attempt to preserve the norm of each column. + * + */ +template +class DiagonalPreconditioner +{ + typedef _Scalar Scalar; + typedef Matrix Vector; + typedef typename Vector::Index Index; + + public: + typedef Matrix MatrixType; + + DiagonalPreconditioner() : m_isInitialized(false) {} + + template + DiagonalPreconditioner(const MatrixType& mat) : m_invdiag(mat.cols()) + { + compute(mat); + } + + Index rows() const { return m_invdiag.size(); } + Index cols() const { return m_invdiag.size(); } + + template + DiagonalPreconditioner& analyzePattern(const MatrixType& ) + { + return *this; + } + + template + DiagonalPreconditioner& factorize(const MatrixType& mat) + { + m_invdiag.resize(mat.cols()); + for(int j=0; j + DiagonalPreconditioner& compute(const MatrixType& mat) + { + return factorize(mat); + } + + template + void _solve(const Rhs& b, Dest& x) const + { + x = m_invdiag.array() * b.array() ; + } + + template inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "DiagonalPreconditioner is not initialized."); + eigen_assert(m_invdiag.size()==b.rows() + && "DiagonalPreconditioner::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + protected: + Vector m_invdiag; + bool m_isInitialized; +}; + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef DiagonalPreconditioner<_MatrixType> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} + +/** \ingroup IterativeLinearSolvers_Module + * \brief A naive preconditioner which approximates any matrix as the identity matrix + * + * \sa class DiagonalPreconditioner + */ +class IdentityPreconditioner +{ + public: + + IdentityPreconditioner() {} + + template + IdentityPreconditioner(const MatrixType& ) {} + + template + IdentityPreconditioner& analyzePattern(const MatrixType& ) { return *this; } + + template + IdentityPreconditioner& factorize(const MatrixType& ) { return *this; } + + template + IdentityPreconditioner& compute(const MatrixType& ) { return *this; } + + template + inline const Rhs& solve(const Rhs& b) const { return b; } +}; + +} // end namespace Eigen + +#endif // EIGEN_BASIC_PRECONDITIONERS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h new file mode 100644 index 000000000..5f23968bc --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h @@ -0,0 +1,269 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2012 Désiré Nuentsa-Wakam +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_BICGSTAB_H +#define EIGEN_BICGSTAB_H + +namespace Eigen { + +namespace internal { + +/** \internal Low-level bi conjugate gradient stabilized algorithm + * \param mat The matrix A + * \param rhs The right hand side vector b + * \param x On input and initial solution, on output the computed solution. + * \param precond A preconditioner being able to efficiently solve for an + * approximation of Ax=b (regardless of b) + * \param iters On input the max number of iteration, on output the number of performed iterations. + * \param tol_error On input the tolerance error, on output an estimation of the relative error. + * \return false in the case of numerical issue, for example a break down of BiCGSTAB. + */ +template +bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x, + const Preconditioner& precond, int& iters, + typename Dest::RealScalar& tol_error) +{ + using std::sqrt; + using std::abs; + typedef typename Dest::RealScalar RealScalar; + typedef typename Dest::Scalar Scalar; + typedef Matrix VectorType; + RealScalar tol = tol_error; + int maxIters = iters; + + int n = mat.cols(); + VectorType r = rhs - mat * x; + VectorType r0 = r; + + RealScalar r0_sqnorm = r0.squaredNorm(); + Scalar rho = 1; + Scalar alpha = 1; + Scalar w = 1; + + VectorType v = VectorType::Zero(n), p = VectorType::Zero(n); + VectorType y(n), z(n); + VectorType kt(n), ks(n); + + VectorType s(n), t(n); + + RealScalar tol2 = tol*tol; + int i = 0; + + while ( r.squaredNorm()/r0_sqnorm > tol2 && i > +class BiCGSTAB; + +namespace internal { + +template< typename _MatrixType, typename _Preconditioner> +struct traits > +{ + typedef _MatrixType MatrixType; + typedef _Preconditioner Preconditioner; +}; + +} + +/** \ingroup IterativeLinearSolvers_Module + * \brief A bi conjugate gradient stabilized solver for sparse square problems + * + * This class allows to solve for A.x = b sparse linear problems using a bi conjugate gradient + * stabilized algorithm. The vectors x and b can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix. + * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner + * + * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations() + * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations + * and NumTraits::epsilon() for the tolerance. + * + * This class can be used as the direct solver classes. Here is a typical usage example: + * \code + * int n = 10000; + * VectorXd x(n), b(n); + * SparseMatrix A(n,n); + * // fill A and b + * BiCGSTAB > solver; + * solver(A); + * x = solver.solve(b); + * std::cout << "#iterations: " << solver.iterations() << std::endl; + * std::cout << "estimated error: " << solver.error() << std::endl; + * // update b, and solve again + * x = solver.solve(b); + * \endcode + * + * By default the iterations start with x=0 as an initial guess of the solution. + * One can control the start using the solveWithGuess() method. Here is a step by + * step execution example starting with a random guess and printing the evolution + * of the estimated error: + * * \code + * x = VectorXd::Random(n); + * solver.setMaxIterations(1); + * int i = 0; + * do { + * x = solver.solveWithGuess(b,x); + * std::cout << i << " : " << solver.error() << std::endl; + * ++i; + * } while (solver.info()!=Success && i<100); + * \endcode + * Note that such a step by step excution is slightly slower. + * + * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner + */ +template< typename _MatrixType, typename _Preconditioner> +class BiCGSTAB : public IterativeSolverBase > +{ + typedef IterativeSolverBase Base; + using Base::mp_matrix; + using Base::m_error; + using Base::m_iterations; + using Base::m_info; + using Base::m_isInitialized; +public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::RealScalar RealScalar; + typedef _Preconditioner Preconditioner; + +public: + + /** Default constructor. */ + BiCGSTAB() : Base() {} + + /** Initialize the solver with matrix \a A for further \c Ax=b solving. + * + * This constructor is a shortcut for the default constructor followed + * by a call to compute(). + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + BiCGSTAB(const MatrixType& A) : Base(A) {} + + ~BiCGSTAB() {} + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A + * \a x0 as an initial solution. + * + * \sa compute() + */ + template + inline const internal::solve_retval_with_guess + solveWithGuess(const MatrixBase& b, const Guess& x0) const + { + eigen_assert(m_isInitialized && "BiCGSTAB is not initialized."); + eigen_assert(Base::rows()==b.rows() + && "BiCGSTAB::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval_with_guess + (*this, b.derived(), x0); + } + + /** \internal */ + template + void _solveWithGuess(const Rhs& b, Dest& x) const + { + bool failed = false; + for(int j=0; j + void _solve(const Rhs& b, Dest& x) const + { + x.setZero(); + _solveWithGuess(b,x); + } + +protected: + +}; + + +namespace internal { + + template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef BiCGSTAB<_MatrixType, _Preconditioner> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_BICGSTAB_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/CMakeLists.txt new file mode 100644 index 000000000..59ccc0072 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_IterativeLinearSolvers_SRCS "*.h") + +INSTALL(FILES + ${Eigen_IterativeLinearSolvers_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/IterativeLinearSolvers COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h new file mode 100644 index 000000000..edab2299e --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h @@ -0,0 +1,266 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_CONJUGATE_GRADIENT_H +#define EIGEN_CONJUGATE_GRADIENT_H + +namespace Eigen { + +namespace internal { + +/** \internal Low-level conjugate gradient algorithm + * \param mat The matrix A + * \param rhs The right hand side vector b + * \param x On input and initial solution, on output the computed solution. + * \param precond A preconditioner being able to efficiently solve for an + * approximation of Ax=b (regardless of b) + * \param iters On input the max number of iteration, on output the number of performed iterations. + * \param tol_error On input the tolerance error, on output an estimation of the relative error. + */ +template +EIGEN_DONT_INLINE +void conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x, + const Preconditioner& precond, int& iters, + typename Dest::RealScalar& tol_error) +{ + using std::sqrt; + using std::abs; + typedef typename Dest::RealScalar RealScalar; + typedef typename Dest::Scalar Scalar; + typedef Matrix VectorType; + + RealScalar tol = tol_error; + int maxIters = iters; + + int n = mat.cols(); + + VectorType residual = rhs - mat * x; //initial residual + VectorType p(n); + + p = precond.solve(residual); //initial search direction + + VectorType z(n), tmp(n); + RealScalar absNew = internal::real(residual.dot(p)); // the square of the absolute value of r scaled by invM + RealScalar rhsNorm2 = rhs.squaredNorm(); + RealScalar residualNorm2 = 0; + RealScalar threshold = tol*tol*rhsNorm2; + int i = 0; + while(i < maxIters) + { + tmp.noalias() = mat * p; // the bottleneck of the algorithm + + Scalar alpha = absNew / p.dot(tmp); // the amount we travel on dir + x += alpha * p; // update solution + residual -= alpha * tmp; // update residue + + residualNorm2 = residual.squaredNorm(); + if(residualNorm2 < threshold) + break; + + z = precond.solve(residual); // approximately solve for "A z = residual" + + RealScalar absOld = absNew; + absNew = internal::real(residual.dot(z)); // update the absolute value of r + RealScalar beta = absNew / absOld; // calculate the Gram-Schmidt value used to create the new search direction + p = z + beta * p; // update search direction + i++; + } + tol_error = sqrt(residualNorm2 / rhsNorm2); + iters = i; +} + +} + +template< typename _MatrixType, int _UpLo=Lower, + typename _Preconditioner = DiagonalPreconditioner > +class ConjugateGradient; + +namespace internal { + +template< typename _MatrixType, int _UpLo, typename _Preconditioner> +struct traits > +{ + typedef _MatrixType MatrixType; + typedef _Preconditioner Preconditioner; +}; + +} + +/** \ingroup IterativeLinearSolvers_Module + * \brief A conjugate gradient solver for sparse self-adjoint problems + * + * This class allows to solve for A.x = b sparse linear problems using a conjugate gradient algorithm. + * The sparse matrix A must be selfadjoint. The vectors x and b can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix. + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner + * + * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations() + * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations + * and NumTraits::epsilon() for the tolerance. + * + * This class can be used as the direct solver classes. Here is a typical usage example: + * \code + * int n = 10000; + * VectorXd x(n), b(n); + * SparseMatrix A(n,n); + * // fill A and b + * ConjugateGradient > cg; + * cg.compute(A); + * x = cg.solve(b); + * std::cout << "#iterations: " << cg.iterations() << std::endl; + * std::cout << "estimated error: " << cg.error() << std::endl; + * // update b, and solve again + * x = cg.solve(b); + * \endcode + * + * By default the iterations start with x=0 as an initial guess of the solution. + * One can control the start using the solveWithGuess() method. Here is a step by + * step execution example starting with a random guess and printing the evolution + * of the estimated error: + * * \code + * x = VectorXd::Random(n); + * cg.setMaxIterations(1); + * int i = 0; + * do { + * x = cg.solveWithGuess(b,x); + * std::cout << i << " : " << cg.error() << std::endl; + * ++i; + * } while (cg.info()!=Success && i<100); + * \endcode + * Note that such a step by step excution is slightly slower. + * + * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner + */ +template< typename _MatrixType, int _UpLo, typename _Preconditioner> +class ConjugateGradient : public IterativeSolverBase > +{ + typedef IterativeSolverBase Base; + using Base::mp_matrix; + using Base::m_error; + using Base::m_iterations; + using Base::m_info; + using Base::m_isInitialized; +public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::RealScalar RealScalar; + typedef _Preconditioner Preconditioner; + + enum { + UpLo = _UpLo + }; + +public: + + /** Default constructor. */ + ConjugateGradient() : Base() {} + + /** Initialize the solver with matrix \a A for further \c Ax=b solving. + * + * This constructor is a shortcut for the default constructor followed + * by a call to compute(). + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + ConjugateGradient(const MatrixType& A) : Base(A) {} + + ~ConjugateGradient() {} + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A + * \a x0 as an initial solution. + * + * \sa compute() + */ + template + inline const internal::solve_retval_with_guess + solveWithGuess(const MatrixBase& b, const Guess& x0) const + { + eigen_assert(m_isInitialized && "ConjugateGradient is not initialized."); + eigen_assert(Base::rows()==b.rows() + && "ConjugateGradient::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval_with_guess + (*this, b.derived(), x0); + } + + /** \internal */ + template + void _solveWithGuess(const Rhs& b, Dest& x) const + { + m_iterations = Base::maxIterations(); + m_error = Base::m_tolerance; + + for(int j=0; jtemplate selfadjointView(), b.col(j), xj, + Base::m_preconditioner, m_iterations, m_error); + } + + m_isInitialized = true; + m_info = m_error <= Base::m_tolerance ? Success : NoConvergence; + } + + /** \internal */ + template + void _solve(const Rhs& b, Dest& x) const + { + x.setOnes(); + _solveWithGuess(b,x); + } + +protected: + +}; + + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CONJUGATE_GRADIENT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h new file mode 100644 index 000000000..32f152634 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h @@ -0,0 +1,476 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2012 Désiré Nuentsa-Wakam +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_INCOMPLETE_LUT_H +#define EIGEN_INCOMPLETE_LUT_H + +namespace Eigen { + +/** + * \brief Incomplete LU factorization with dual-threshold strategy + * During the numerical factorization, two dropping rules are used : + * 1) any element whose magnitude is less than some tolerance is dropped. + * This tolerance is obtained by multiplying the input tolerance @p droptol + * by the average magnitude of all the original elements in the current row. + * 2) After the elimination of the row, only the @p fill largest elements in + * the L part and the @p fill largest elements in the U part are kept + * (in addition to the diagonal element ). Note that @p fill is computed from + * the input parameter @p fillfactor which is used the ratio to control the fill_in + * relatively to the initial number of nonzero elements. + * + * The two extreme cases are when @p droptol=0 (to keep all the @p fill*2 largest elements) + * and when @p fill=n/2 with @p droptol being different to zero. + * + * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization, + * Numerical Linear Algebra with Applications, 1(4), pp 387-402, 1994. + * + * NOTE : The following implementation is derived from the ILUT implementation + * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota + * released under the terms of the GNU LGPL; + * see http://www-users.cs.umn.edu/~saad/software/SPARSKIT/README for more details. + */ +template +class IncompleteLUT : internal::noncopyable +{ + typedef _Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef Matrix Vector; + typedef SparseMatrix FactorType; + typedef SparseMatrix PermutType; + typedef typename FactorType::Index Index; + + public: + typedef Matrix MatrixType; + + IncompleteLUT() + : m_droptol(NumTraits::dummy_precision()), m_fillfactor(10), + m_analysisIsOk(false), m_factorizationIsOk(false), m_isInitialized(false) + {} + + template + IncompleteLUT(const MatrixType& mat, RealScalar droptol=NumTraits::dummy_precision(), int fillfactor = 10) + : m_droptol(droptol),m_fillfactor(fillfactor), + m_analysisIsOk(false),m_factorizationIsOk(false),m_isInitialized(false) + { + eigen_assert(fillfactor != 0); + compute(mat); + } + + Index rows() const { return m_lu.rows(); } + + Index cols() const { return m_lu.cols(); } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "IncompleteLUT is not initialized."); + return m_info; + } + + template + void analyzePattern(const MatrixType& amat); + + template + void factorize(const MatrixType& amat); + + /** + * Compute an incomplete LU factorization with dual threshold on the matrix mat + * No pivoting is done in this version + * + **/ + template + IncompleteLUT& compute(const MatrixType& amat) + { + analyzePattern(amat); + factorize(amat); + eigen_assert(m_factorizationIsOk == true); + m_isInitialized = true; + return *this; + } + + void setDroptol(RealScalar droptol); + void setFillfactor(int fillfactor); + + template + void _solve(const Rhs& b, Dest& x) const + { + x = m_Pinv * b; + x = m_lu.template triangularView().solve(x); + x = m_lu.template triangularView().solve(x); + x = m_P * x; + } + + template inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "IncompleteLUT is not initialized."); + eigen_assert(cols()==b.rows() + && "IncompleteLUT::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + +protected: + + template + int QuickSplit(VectorV &row, VectorI &ind, int ncut); + + + /** keeps off-diagonal entries; drops diagonal entries */ + struct keep_diag { + inline bool operator() (const Index& row, const Index& col, const Scalar&) const + { + return row!=col; + } + }; + +protected: + + FactorType m_lu; + RealScalar m_droptol; + int m_fillfactor; + bool m_analysisIsOk; + bool m_factorizationIsOk; + bool m_isInitialized; + ComputationInfo m_info; + PermutationMatrix m_P; // Fill-reducing permutation + PermutationMatrix m_Pinv; // Inverse permutation +}; + +/** + * Set control parameter droptol + * \param droptol Drop any element whose magnitude is less than this tolerance + **/ +template +void IncompleteLUT::setDroptol(RealScalar droptol) +{ + this->m_droptol = droptol; +} + +/** + * Set control parameter fillfactor + * \param fillfactor This is used to compute the number @p fill_in of largest elements to keep on each row. + **/ +template +void IncompleteLUT::setFillfactor(int fillfactor) +{ + this->m_fillfactor = fillfactor; +} + + +/** + * Compute a quick-sort split of a vector + * On output, the vector row is permuted such that its elements satisfy + * abs(row(i)) >= abs(row(ncut)) if incut + * \param row The vector of values + * \param ind The array of index for the elements in @p row + * \param ncut The number of largest elements to keep + **/ +template +template +int IncompleteLUT::QuickSplit(VectorV &row, VectorI &ind, int ncut) +{ + using std::swap; + int mid; + int n = row.size(); /* length of the vector */ + int first, last ; + + ncut--; /* to fit the zero-based indices */ + first = 0; + last = n-1; + if (ncut < first || ncut > last ) return 0; + + do { + mid = first; + RealScalar abskey = std::abs(row(mid)); + for (int j = first + 1; j <= last; j++) { + if ( std::abs(row(j)) > abskey) { + ++mid; + swap(row(mid), row(j)); + swap(ind(mid), ind(j)); + } + } + /* Interchange for the pivot element */ + swap(row(mid), row(first)); + swap(ind(mid), ind(first)); + + if (mid > ncut) last = mid - 1; + else if (mid < ncut ) first = mid + 1; + } while (mid != ncut ); + + return 0; /* mid is equal to ncut */ +} + +template +template +void IncompleteLUT::analyzePattern(const _MatrixType& amat) +{ + // Compute the Fill-reducing permutation + SparseMatrix mat1 = amat; + SparseMatrix mat2 = amat.transpose(); + // Symmetrize the pattern + // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice. + // on the other hand for a really non-symmetric pattern, mat2*mat1 should be prefered... + SparseMatrix AtA = mat2 + mat1; + AtA.prune(keep_diag()); + internal::minimum_degree_ordering(AtA, m_P); // Then compute the AMD ordering... + + m_Pinv = m_P.inverse(); // ... and the inverse permutation + + m_analysisIsOk = true; +} + +template +template +void IncompleteLUT::factorize(const _MatrixType& amat) +{ + using std::sqrt; + using std::swap; + using std::abs; + + eigen_assert((amat.rows() == amat.cols()) && "The factorization should be done on a square matrix"); + int n = amat.cols(); // Size of the matrix + m_lu.resize(n,n); + // Declare Working vectors and variables + Vector u(n) ; // real values of the row -- maximum size is n -- + VectorXi ju(n); // column position of the values in u -- maximum size is n + VectorXi jr(n); // Indicate the position of the nonzero elements in the vector u -- A zero location is indicated by -1 + + // Apply the fill-reducing permutation + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + SparseMatrix mat; + mat = amat.twistedBy(m_Pinv); + + // Initialization + jr.fill(-1); + ju.fill(0); + u.fill(0); + + // number of largest elements to keep in each row: + int fill_in = static_cast (amat.nonZeros()*m_fillfactor)/n+1; + if (fill_in > n) fill_in = n; + + // number of largest nonzero elements to keep in the L and the U part of the current row: + int nnzL = fill_in/2; + int nnzU = nnzL; + m_lu.reserve(n * (nnzL + nnzU + 1)); + + // global loop over the rows of the sparse matrix + for (int ii = 0; ii < n; ii++) + { + // 1 - copy the lower and the upper part of the row i of mat in the working vector u + + int sizeu = 1; // number of nonzero elements in the upper part of the current row + int sizel = 0; // number of nonzero elements in the lower part of the current row + ju(ii) = ii; + u(ii) = 0; + jr(ii) = ii; + RealScalar rownorm = 0; + + typename FactorType::InnerIterator j_it(mat, ii); // Iterate through the current row ii + for (; j_it; ++j_it) + { + int k = j_it.index(); + if (k < ii) + { + // copy the lower part + ju(sizel) = k; + u(sizel) = j_it.value(); + jr(k) = sizel; + ++sizel; + } + else if (k == ii) + { + u(ii) = j_it.value(); + } + else + { + // copy the upper part + int jpos = ii + sizeu; + ju(jpos) = k; + u(jpos) = j_it.value(); + jr(k) = jpos; + ++sizeu; + } + rownorm += internal::abs2(j_it.value()); + } + + // 2 - detect possible zero row + if(rownorm==0) + { + m_info = NumericalIssue; + return; + } + // Take the 2-norm of the current row as a relative tolerance + rownorm = sqrt(rownorm); + + // 3 - eliminate the previous nonzero rows + int jj = 0; + int len = 0; + while (jj < sizel) + { + // In order to eliminate in the correct order, + // we must select first the smallest column index among ju(jj:sizel) + int k; + int minrow = ju.segment(jj,sizel-jj).minCoeff(&k); // k is relative to the segment + k += jj; + if (minrow != ju(jj)) + { + // swap the two locations + int j = ju(jj); + swap(ju(jj), ju(k)); + jr(minrow) = jj; jr(j) = k; + swap(u(jj), u(k)); + } + // Reset this location + jr(minrow) = -1; + + // Start elimination + typename FactorType::InnerIterator ki_it(m_lu, minrow); + while (ki_it && ki_it.index() < minrow) ++ki_it; + eigen_internal_assert(ki_it && ki_it.col()==minrow); + Scalar fact = u(jj) / ki_it.value(); + + // drop too small elements + if(abs(fact) <= m_droptol) + { + jj++; + continue; + } + + // linear combination of the current row ii and the row minrow + ++ki_it; + for (; ki_it; ++ki_it) + { + Scalar prod = fact * ki_it.value(); + int j = ki_it.index(); + int jpos = jr(j); + if (jpos == -1) // fill-in element + { + int newpos; + if (j >= ii) // dealing with the upper part + { + newpos = ii + sizeu; + sizeu++; + eigen_internal_assert(sizeu<=n); + } + else // dealing with the lower part + { + newpos = sizel; + sizel++; + eigen_internal_assert(sizel<=ii); + } + ju(newpos) = j; + u(newpos) = -prod; + jr(j) = newpos; + } + else + u(jpos) -= prod; + } + // store the pivot element + u(len) = fact; + ju(len) = minrow; + ++len; + + jj++; + } // end of the elimination on the row ii + + // reset the upper part of the pointer jr to zero + for(int k = 0; k m_droptol * rownorm ) + { + ++len; + u(ii + len) = u(ii + k); + ju(ii + len) = ju(ii + k); + } + } + sizeu = len + 1; // +1 to take into account the diagonal element + len = (std::min)(sizeu, nnzU); + typename Vector::SegmentReturnType uu(u.segment(ii+1, sizeu-1)); + typename VectorXi::SegmentReturnType juu(ju.segment(ii+1, sizeu-1)); + QuickSplit(uu, juu, len); + + // store the largest elements of the U part + for(int k = ii + 1; k < ii + len; k++) + m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k); + } + + m_lu.finalize(); + m_lu.makeCompressed(); + + m_factorizationIsOk = true; + m_info = Success; +} + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef IncompleteLUT<_MatrixType> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_INCOMPLETE_LUT_H + diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h new file mode 100644 index 000000000..b27ad82ec --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h @@ -0,0 +1,269 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_ITERATIVE_SOLVER_BASE_H +#define EIGEN_ITERATIVE_SOLVER_BASE_H + +namespace Eigen { + +/** \ingroup IterativeLinearSolvers_Module + * \brief Base class for linear iterative solvers + * + * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner + */ +template< typename Derived> +class IterativeSolverBase : internal::noncopyable +{ +public: + typedef typename internal::traits::MatrixType MatrixType; + typedef typename internal::traits::Preconditioner Preconditioner; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::RealScalar RealScalar; + +public: + + Derived& derived() { return *static_cast(this); } + const Derived& derived() const { return *static_cast(this); } + + /** Default constructor. */ + IterativeSolverBase() + : mp_matrix(0) + { + init(); + } + + /** Initialize the solver with matrix \a A for further \c Ax=b solving. + * + * This constructor is a shortcut for the default constructor followed + * by a call to compute(). + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + IterativeSolverBase(const MatrixType& A) + { + init(); + compute(A); + } + + ~IterativeSolverBase() {} + + /** Initializes the iterative solver for the sparcity pattern of the matrix \a A for further solving \c Ax=b problems. + * + * Currently, this function mostly call analyzePattern on the preconditioner. In the future + * we might, for instance, implement column reodering for faster matrix vector products. + */ + Derived& analyzePattern(const MatrixType& A) + { + m_preconditioner.analyzePattern(A); + m_isInitialized = true; + m_analysisIsOk = true; + m_info = Success; + return derived(); + } + + /** Initializes the iterative solver with the numerical values of the matrix \a A for further solving \c Ax=b problems. + * + * Currently, this function mostly call factorize on the preconditioner. + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + Derived& factorize(const MatrixType& A) + { + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + mp_matrix = &A; + m_preconditioner.factorize(A); + m_factorizationIsOk = true; + m_info = Success; + return derived(); + } + + /** Initializes the iterative solver with the matrix \a A for further solving \c Ax=b problems. + * + * Currently, this function mostly initialized/compute the preconditioner. In the future + * we might, for instance, implement column reodering for faster matrix vector products. + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + Derived& compute(const MatrixType& A) + { + mp_matrix = &A; + m_preconditioner.compute(A); + m_isInitialized = true; + m_analysisIsOk = true; + m_factorizationIsOk = true; + m_info = Success; + return derived(); + } + + /** \internal */ + Index rows() const { return mp_matrix ? mp_matrix->rows() : 0; } + /** \internal */ + Index cols() const { return mp_matrix ? mp_matrix->cols() : 0; } + + /** \returns the tolerance threshold used by the stopping criteria */ + RealScalar tolerance() const { return m_tolerance; } + + /** Sets the tolerance threshold used by the stopping criteria */ + Derived& setTolerance(RealScalar tolerance) + { + m_tolerance = tolerance; + return derived(); + } + + /** \returns a read-write reference to the preconditioner for custom configuration. */ + Preconditioner& preconditioner() { return m_preconditioner; } + + /** \returns a read-only reference to the preconditioner. */ + const Preconditioner& preconditioner() const { return m_preconditioner; } + + /** \returns the max number of iterations */ + int maxIterations() const + { + return (mp_matrix && m_maxIterations<0) ? mp_matrix->cols() : m_maxIterations; + } + + /** Sets the max number of iterations */ + Derived& setMaxIterations(int maxIters) + { + m_maxIterations = maxIters; + return derived(); + } + + /** \returns the number of iterations performed during the last solve */ + int iterations() const + { + eigen_assert(m_isInitialized && "ConjugateGradient is not initialized."); + return m_iterations; + } + + /** \returns the tolerance error reached during the last solve */ + RealScalar error() const + { + eigen_assert(m_isInitialized && "ConjugateGradient is not initialized."); + return m_error; + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized."); + eigen_assert(rows()==b.rows() + && "IterativeSolverBase::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(derived(), b.derived()); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::sparse_solve_retval + solve(const SparseMatrixBase& b) const + { + eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized."); + eigen_assert(rows()==b.rows() + && "IterativeSolverBase::solve(): invalid number of rows of the right hand side matrix b"); + return internal::sparse_solve_retval(*this, b.derived()); + } + + /** \returns Success if the iterations converged, and NoConvergence otherwise. */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized."); + return m_info; + } + + /** \internal */ + template + void _solve_sparse(const Rhs& b, SparseMatrix &dest) const + { + eigen_assert(rows()==b.rows()); + + int rhsCols = b.cols(); + int size = b.rows(); + Eigen::Matrix tb(size); + Eigen::Matrix tx(size); + for(int k=0; k::epsilon(); + } + const MatrixType* mp_matrix; + Preconditioner m_preconditioner; + + int m_maxIterations; + RealScalar m_tolerance; + + mutable RealScalar m_error; + mutable int m_iterations; + mutable ComputationInfo m_info; + mutable bool m_isInitialized, m_analysisIsOk, m_factorizationIsOk; +}; + +namespace internal { + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef IterativeSolverBase Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve_sparse(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_ITERATIVE_SOLVER_BASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Jacobi/Jacobi.h b/gtsam/3rdparty/Eigen/Eigen/src/Jacobi/Jacobi.h index 98dea6800..691f5f22b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Jacobi/Jacobi.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Jacobi/Jacobi.h @@ -26,6 +26,8 @@ #ifndef EIGEN_JACOBI_H #define EIGEN_JACOBI_H +namespace Eigen { + /** \ingroup Jacobi_Module * \jacobi_module * \class JacobiRotation @@ -326,7 +328,7 @@ void /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(VectorX& _x, VectorY& _y, // both vectors are sequentially stored in memory => vectorization enum { Peeling = 2 }; - Index alignedStart = first_aligned(y, size); + Index alignedStart = internal::first_aligned(y, size); Index alignedEnd = alignedStart + ((size-alignedStart)/PacketSize)*PacketSize; const Packet pc = pset1(j.c()); @@ -344,7 +346,7 @@ void /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(VectorX& _x, VectorY& _y, Scalar* EIGEN_RESTRICT px = x + alignedStart; Scalar* EIGEN_RESTRICT py = y + alignedStart; - if(first_aligned(x, size)==alignedStart) + if(internal::first_aligned(x, size)==alignedStart) { for(Index i=alignedStart; i @@ -109,4 +111,6 @@ inline typename internal::traits::Scalar MatrixBase::determina return internal::determinant_impl::type>::run(derived()); } +} // end namespace Eigen + #endif // EIGEN_DETERMINANT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h index 46ae7d651..c342bc470 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h @@ -25,6 +25,8 @@ #ifndef EIGEN_LU_H #define EIGEN_LU_H +namespace Eigen { + /** \ingroup LU_Module * * \class FullPivLU @@ -282,6 +284,7 @@ template class FullPivLU FullPivLU& setThreshold(Default_t) { m_usePrescribedThreshold = false; + return *this; } /** Returns the threshold that will be used by certain methods such as rank(). @@ -743,4 +746,6 @@ MatrixBase::fullPivLu() const return FullPivLU(eval()); } +} // end namespace Eigen + #endif // EIGEN_LU_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/Inverse.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/Inverse.h index 2d3e6d105..aa90dc8ad 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/Inverse.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/Inverse.h @@ -25,6 +25,8 @@ #ifndef EIGEN_INVERSE_H #define EIGEN_INVERSE_H +namespace Eigen { + namespace internal { /********************************** @@ -286,7 +288,7 @@ struct inverse_impl : public ReturnByValue > typedef typename MatrixType::Index Index; typedef typename internal::eval::type MatrixTypeNested; typedef typename remove_all::type MatrixTypeNestedCleaned; - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; inverse_impl(const MatrixType& matrix) : m_matrix(matrix) @@ -404,4 +406,6 @@ inline void MatrixBase::computeInverseWithCheck( computeInverseAndDetWithCheck(inverse,determinant,invertible,absDeterminantThreshold); } +} // end namespace Eigen + #endif // EIGEN_INVERSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h index 09394b01f..8ae556eb6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h @@ -26,6 +26,8 @@ #ifndef EIGEN_PARTIALLU_H #define EIGEN_PARTIALLU_H +namespace Eigen { + /** \ingroup LU_Module * * \class PartialPivLU @@ -506,4 +508,6 @@ MatrixBase::lu() const } #endif +} // end namespace Eigen + #endif // EIGEN_PARTIALLU_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU_MKL.h new file mode 100644 index 000000000..9035953c8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU_MKL.h @@ -0,0 +1,85 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * LU decomposition with partial pivoting based on LAPACKE_?getrf function. + ******************************************************************************** +*/ + +#ifndef EIGEN_PARTIALLU_LAPACK_H +#define EIGEN_PARTIALLU_LAPACK_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +namespace internal { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_LU_PARTPIV(EIGTYPE, MKLTYPE, MKLPREFIX) \ +template \ +struct partial_lu_impl \ +{ \ + /* \internal performs the LU decomposition in-place of the matrix represented */ \ + static lapack_int blocked_lu(lapack_int rows, lapack_int cols, EIGTYPE* lu_data, lapack_int luStride, lapack_int* row_transpositions, lapack_int& nb_transpositions, lapack_int maxBlockSize=256) \ + { \ + EIGEN_UNUSED_VARIABLE(maxBlockSize);\ + lapack_int matrix_order, first_zero_pivot; \ + lapack_int m, n, lda, *ipiv, info; \ + EIGTYPE* a; \ +/* Set up parameters for ?getrf */ \ + matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \ + lda = luStride; \ + a = lu_data; \ + ipiv = row_transpositions; \ + m = rows; \ + n = cols; \ + nb_transpositions = 0; \ +\ + info = LAPACKE_##MKLPREFIX##getrf( matrix_order, m, n, (MKLTYPE*)a, lda, ipiv ); \ +\ + for(int i=0;i= 0); \ +/* something should be done with nb_transpositions */ \ +\ + first_zero_pivot = info; \ + return first_zero_pivot; \ + } \ +}; + +EIGEN_MKL_LU_PARTPIV(double, double, d) +EIGEN_MKL_LU_PARTPIV(float, float, s) +EIGEN_MKL_LU_PARTPIV(dcomplex, MKL_Complex16, z) +EIGEN_MKL_LU_PARTPIV(scomplex, MKL_Complex8, c) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PARTIALLU_LAPACK_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/arch/Inverse_SSE.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/arch/Inverse_SSE.h index 4c6153f0a..afb8e4a1d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/arch/Inverse_SSE.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/arch/Inverse_SSE.h @@ -42,6 +42,8 @@ #ifndef EIGEN_INVERSE_SSE_H #define EIGEN_INVERSE_SSE_H +namespace Eigen { + namespace internal { template @@ -335,6 +337,8 @@ struct compute_inverse_size4 } }; -} +} // end namespace internal + +} // end namespace Eigen #endif // EIGEN_INVERSE_SSE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Amd.h b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h similarity index 91% rename from gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Amd.h rename to gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h index 52fd56bc4..ec13077fe 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Amd.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h @@ -48,13 +48,14 @@ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA #ifndef EIGEN_SPARSE_AMD_H #define EIGEN_SPARSE_AMD_H +namespace Eigen { + namespace internal { - -#define CS_FLIP(i) (-(i)-2) -#define CS_UNFLIP(i) (((i) < 0) ? CS_FLIP(i) : (i)) -#define CS_MARKED(w,j) (w[j] < 0) -#define CS_MARK(w,j) { w[j] = CS_FLIP (w[j]); } +template inline T amd_flip(const T& i) { return -i-2; } +template inline T amd_unflip(const T& i) { return i<0 ? amd_flip(i) : i; } +template inline bool amd_marked(const T0* w, const T1& j) { return w[j]<0; } +template inline void amd_mark(const T0* w, const T1& j) { return w[j] = amd_flip(w[j]); } /* clear w */ template @@ -103,8 +104,9 @@ Index cs_tdfs(Index j, Index k, Index *head, const Index *next, Index *post, Ind * The input matrix \a C must be a selfadjoint compressed column major SparseMatrix object. Both the upper and lower parts have to be stored, but the diagonal entries are optional. * On exit the values of C are destroyed */ template -void minimum_degree_ordering(SparseMatrix& C, PermutationMatrix& perm) +void minimum_degree_ordering(SparseMatrix& C, PermutationMatrix& perm) { + using std::sqrt; typedef SparseMatrix CCS; int d, dk, dext, lemax = 0, e, elenk, eln, i, j, k, k1, @@ -113,7 +115,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation unsigned int h; Index n = C.cols(); - dense = std::max (16, 10 * sqrt ((double) n)); /* find dense threshold */ + dense = std::max (16, Index(10 * sqrt(double(n)))); /* find dense threshold */ dense = std::min (n-2, dense); Index cnz = C.nonZeros(); @@ -133,8 +135,8 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation Index* last = perm.indices().data(); /* use P as workspace for last */ /* --- Initialize quotient graph ---------------------------------------- */ - Index* Cp = C._outerIndexPtr(); - Index* Ci = C._innerIndexPtr(); + Index* Cp = C.outerIndexPtr(); + Index* Ci = C.innerIndexPtr(); for(k = 0; k < n; k++) len[k] = Cp[k+1] - Cp[k]; len[n] = 0; @@ -151,7 +153,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation elen[i] = 0; // Ek of node i is empty degree[i] = len[i]; // degree of node i } - mark = cs_wclear (0, 0, w, n); /* clear w */ + mark = internal::cs_wclear(0, 0, w, n); /* clear w */ elen[n] = -2; /* n is a dead element */ Cp[n] = -1; /* n is a root of assembly tree */ w[n] = 0; /* n is a dead element */ @@ -172,7 +174,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation nv[i] = 0; /* absorb i into element n */ elen[i] = -1; /* node i is dead */ nel++; - Cp[i] = CS_FLIP (n); + Cp[i] = amd_flip (n); nv[n]++; } else @@ -201,12 +203,12 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation if((p = Cp[j]) >= 0) /* j is a live node or element */ { Cp[j] = Ci[p]; /* save first entry of object */ - Ci[p] = CS_FLIP (j); /* first entry is now CS_FLIP(j) */ + Ci[p] = amd_flip (j); /* first entry is now amd_flip(j) */ } } for(q = 0, p = 0; p < cnz; ) /* scan all of memory */ { - if((j = CS_FLIP (Ci[p++])) >= 0) /* found object j */ + if((j = amd_flip (Ci[p++])) >= 0) /* found object j */ { Ci[q] = Cp[j]; /* restore first entry of object */ Cp[j] = q++; /* new pointer to object j */ @@ -255,7 +257,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } if(e != k) { - Cp[e] = CS_FLIP (k); /* absorb e into k */ + Cp[e] = amd_flip (k); /* absorb e into k */ w[e] = 0; /* e is now a dead element */ } } @@ -266,7 +268,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation elen[k] = -2; /* k is now an element */ /* --- Find set differences ----------------------------------------- */ - mark = cs_wclear (mark, lemax, w, n); /* clear w if necessary */ + mark = internal::cs_wclear(mark, lemax, w, n); /* clear w if necessary */ for(pk = pk1; pk < pk2; pk++) /* scan 1: find |Le\Lk| */ { i = Ci[pk]; @@ -308,7 +310,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } else { - Cp[e] = CS_FLIP (k); /* aggressive absorb. e->k */ + Cp[e] = amd_flip (k); /* aggressive absorb. e->k */ w[e] = 0; /* e is a dead element */ } } @@ -326,7 +328,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } if(d == 0) /* check for mass elimination */ { - Cp[i] = CS_FLIP (k); /* absorb i into k */ + Cp[i] = amd_flip (k); /* absorb i into k */ nvi = -nv[i]; dk -= nvi; /* |Lk| -= |i| */ nvk += nvi; /* |k| += nv[i] */ @@ -349,7 +351,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } /* scan2 is done */ degree[k] = dk; /* finalize |Lk| */ lemax = std::max(lemax, dk); - mark = cs_wclear (mark+lemax, lemax, w, n); /* clear w */ + mark = internal::cs_wclear(mark+lemax, lemax, w, n); /* clear w */ /* --- Supernode detection ------------------------------------------ */ for(pk = pk1; pk < pk2; pk++) @@ -374,7 +376,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } if(ok) /* i and j are identical */ { - Cp[j] = CS_FLIP (i); /* absorb j into i */ + Cp[j] = amd_flip (i); /* absorb j into i */ nv[i] += nv[j]; nv[j] = 0; elen[j] = -1; /* node j is dead */ @@ -416,7 +418,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } /* --- Postordering ----------------------------------------------------- */ - for(i = 0; i < n; i++) Cp[i] = CS_FLIP (Cp[i]);/* fix assembly tree */ + for(i = 0; i < n; i++) Cp[i] = amd_flip (Cp[i]);/* fix assembly tree */ for(j = 0; j <= n; j++) head[j] = -1; for(j = n; j >= 0; j--) /* place unordered nodes in lists */ { @@ -435,7 +437,7 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } for(k = 0, i = 0; i <= n; i++) /* postorder the assembly tree */ { - if(Cp[i] == -1) k = cs_tdfs (i, k, head, next, perm.indices().data(), w); + if(Cp[i] == -1) k = internal::cs_tdfs(i, k, head, next, perm.indices().data(), w); } perm.indices().conservativeResize(n); @@ -445,4 +447,6 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } // namespace internal +} // end namespace Eigen + #endif // EIGEN_SPARSE_AMD_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/CMakeLists.txt new file mode 100644 index 000000000..9f4bb2758 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_OrderingMethods_SRCS "*.h") + +INSTALL(FILES + ${Eigen_OrderingMethods_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/OrderingMethods COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/CMakeLists.txt new file mode 100644 index 000000000..28c657e9b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_PastixSupport_SRCS "*.h") + +INSTALL(FILES + ${Eigen_PastixSupport_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/PaStiXSupport COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/PaStiXSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/PaStiXSupport.h new file mode 100644 index 000000000..f687a5e6b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/PaStiXSupport.h @@ -0,0 +1,757 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2012 Désiré Nuentsa-Wakam +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_PASTIXSUPPORT_H +#define EIGEN_PASTIXSUPPORT_H + +namespace Eigen { + +/** \ingroup PaStiXSupport_Module + * \brief Interface to the PaStix solver + * + * This class is used to solve the linear systems A.X = B via the PaStix library. + * The matrix can be either real or complex, symmetric or not. + * + * \sa TutorialSparseDirectSolvers + */ +template class PastixLU; +template class PastixLLT; +template class PastixLDLT; + +namespace internal +{ + + template struct pastix_traits; + + template + struct pastix_traits< PastixLU<_MatrixType> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + + template + struct pastix_traits< PastixLLT<_MatrixType,Options> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + + template + struct pastix_traits< PastixLDLT<_MatrixType,Options> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + + void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, float *vals, int *perm, int * invp, float *x, int nbrhs, int *iparm, double *dparm) + { + if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } + if (nbrhs == 0) {x = NULL; nbrhs=1;} + s_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); + } + + void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, double *vals, int *perm, int * invp, double *x, int nbrhs, int *iparm, double *dparm) + { + if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } + if (nbrhs == 0) {x = NULL; nbrhs=1;} + d_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); + } + + void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) + { + if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } + if (nbrhs == 0) {x = NULL; nbrhs=1;} + c_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast(vals), perm, invp, reinterpret_cast(x), nbrhs, iparm, dparm); + } + + void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex *vals, int *perm, int * invp, std::complex *x, int nbrhs, int *iparm, double *dparm) + { + if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; } + if (nbrhs == 0) {x = NULL; nbrhs=1;} + z_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast(vals), perm, invp, reinterpret_cast(x), nbrhs, iparm, dparm); + } + + // Convert the matrix to Fortran-style Numbering + template + void c_to_fortran_numbering (MatrixType& mat) + { + if ( !(mat.outerIndexPtr()[0]) ) + { + int i; + for(i = 0; i <= mat.rows(); ++i) + ++mat.outerIndexPtr()[i]; + for(i = 0; i < mat.nonZeros(); ++i) + ++mat.innerIndexPtr()[i]; + } + } + + // Convert to C-style Numbering + template + void fortran_to_c_numbering (MatrixType& mat) + { + // Check the Numbering + if ( mat.outerIndexPtr()[0] == 1 ) + { // Convert to C-style numbering + int i; + for(i = 0; i <= mat.rows(); ++i) + --mat.outerIndexPtr()[i]; + for(i = 0; i < mat.nonZeros(); ++i) + --mat.innerIndexPtr()[i]; + } + } +} + +// This is the base class to interface with PaStiX functions. +// Users should not used this class directly. +template +class PastixBase : internal::noncopyable +{ + public: + typedef typename internal::pastix_traits::MatrixType _MatrixType; + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef Matrix Vector; + typedef SparseMatrix ColSpMatrix; + + public: + + PastixBase() : m_initisOk(false), m_analysisIsOk(false), m_factorizationIsOk(false), m_isInitialized(false), m_pastixdata(0), m_size(0) + { + init(); + } + + ~PastixBase() + { + clean(); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "Pastix solver is not initialized."); + eigen_assert(rows()==b.rows() + && "PastixBase::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + template + bool _solve (const MatrixBase &b, MatrixBase &x) const; + + /** \internal */ + template + void _solve_sparse(const Rhs& b, SparseMatrix &dest) const + { + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + eigen_assert(rows()==b.rows()); + + // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix. + static const int NbColsAtOnce = 1; + int rhsCols = b.cols(); + int size = b.rows(); + Eigen::Matrix tmp(size,rhsCols); + for(int k=0; k(rhsCols-k, NbColsAtOnce); + tmp.leftCols(actualCols) = b.middleCols(k,actualCols); + tmp.leftCols(actualCols) = derived().solve(tmp.leftCols(actualCols)); + dest.middleCols(k,actualCols) = tmp.leftCols(actualCols).sparseView(); + } + } + + Derived& derived() + { + return *static_cast(this); + } + const Derived& derived() const + { + return *static_cast(this); + } + + /** Returns a reference to the integer vector IPARM of PaStiX parameters + * to modify the default parameters. + * The statistics related to the different phases of factorization and solve are saved here as well + * \sa analyzePattern() factorize() + */ + Array& iparm() + { + return m_iparm; + } + + /** Return a reference to a particular index parameter of the IPARM vector + * \sa iparm() + */ + + int& iparm(int idxparam) + { + return m_iparm(idxparam); + } + + /** Returns a reference to the double vector DPARM of PaStiX parameters + * The statistics related to the different phases of factorization and solve are saved here as well + * \sa analyzePattern() factorize() + */ + Array& dparm() + { + return m_dparm; + } + + + /** Return a reference to a particular index parameter of the DPARM vector + * \sa dparm() + */ + double& dparm(int idxparam) + { + return m_dparm(idxparam); + } + + inline Index cols() const { return m_size; } + inline Index rows() const { return m_size; } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the PaStiX reports a problem + * \c InvalidInput if the input matrix is invalid + * + * \sa iparm() + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "Decomposition is not initialized."); + return m_info; + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::sparse_solve_retval + solve(const SparseMatrixBase& b) const + { + eigen_assert(m_isInitialized && "Pastix LU, LLT or LDLT is not initialized."); + eigen_assert(rows()==b.rows() + && "PastixBase::solve(): invalid number of rows of the right hand side matrix b"); + return internal::sparse_solve_retval(*this, b.derived()); + } + + protected: + + // Initialize the Pastix data structure, check the matrix + void init(); + + // Compute the ordering and the symbolic factorization + void analyzePattern(ColSpMatrix& mat); + + // Compute the numerical factorization + void factorize(ColSpMatrix& mat); + + // Free all the data allocated by Pastix + void clean() + { + eigen_assert(m_initisOk && "The Pastix structure should be allocated first"); + m_iparm(IPARM_START_TASK) = API_TASK_CLEAN; + m_iparm(IPARM_END_TASK) = API_TASK_CLEAN; + internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0, + m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data()); + } + + void compute(ColSpMatrix& mat); + + int m_initisOk; + int m_analysisIsOk; + int m_factorizationIsOk; + bool m_isInitialized; + mutable ComputationInfo m_info; + mutable pastix_data_t *m_pastixdata; // Data structure for pastix + mutable int m_comm; // The MPI communicator identifier + mutable Matrix m_iparm; // integer vector for the input parameters + mutable Matrix m_dparm; // Scalar vector for the input parameters + mutable Matrix m_perm; // Permutation vector + mutable Matrix m_invp; // Inverse permutation vector + mutable int m_size; // Size of the matrix +}; + + /** Initialize the PaStiX data structure. + *A first call to this function fills iparm and dparm with the default PaStiX parameters + * \sa iparm() dparm() + */ +template +void PastixBase::init() +{ + m_size = 0; + m_iparm.setZero(IPARM_SIZE); + m_dparm.setZero(DPARM_SIZE); + + m_iparm(IPARM_MODIFY_PARAMETER) = API_NO; + pastix(&m_pastixdata, MPI_COMM_WORLD, + 0, 0, 0, 0, + 0, 0, 0, 1, m_iparm.data(), m_dparm.data()); + + m_iparm[IPARM_MATRIX_VERIFICATION] = API_NO; + m_iparm[IPARM_VERBOSE] = 2; + m_iparm[IPARM_ORDERING] = API_ORDER_SCOTCH; + m_iparm[IPARM_INCOMPLETE] = API_NO; + m_iparm[IPARM_OOC_LIMIT] = 2000; + m_iparm[IPARM_RHS_MAKING] = API_RHS_B; + m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO; + + m_iparm(IPARM_START_TASK) = API_TASK_INIT; + m_iparm(IPARM_END_TASK) = API_TASK_INIT; + internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0, + 0, 0, 0, 0, m_iparm.data(), m_dparm.data()); + + // Check the returned error + if(m_iparm(IPARM_ERROR_NUMBER)) { + m_info = InvalidInput; + m_initisOk = false; + } + else { + m_info = Success; + m_initisOk = true; + } +} + +template +void PastixBase::compute(ColSpMatrix& mat) +{ + eigen_assert(mat.rows() == mat.cols() && "The input matrix should be squared"); + + analyzePattern(mat); + factorize(mat); + + m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO; + m_isInitialized = m_factorizationIsOk; +} + + +template +void PastixBase::analyzePattern(ColSpMatrix& mat) +{ + eigen_assert(m_initisOk && "The initialization of PaSTiX failed"); + + // clean previous calls + if(m_size>0) + clean(); + + m_size = mat.rows(); + m_perm.resize(m_size); + m_invp.resize(m_size); + + m_iparm(IPARM_START_TASK) = API_TASK_ORDERING; + m_iparm(IPARM_END_TASK) = API_TASK_ANALYSE; + internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(), + mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data()); + + // Check the returned error + if(m_iparm(IPARM_ERROR_NUMBER)) + { + m_info = NumericalIssue; + m_analysisIsOk = false; + } + else + { + m_info = Success; + m_analysisIsOk = true; + } +} + +template +void PastixBase::factorize(ColSpMatrix& mat) +{ +// if(&m_cpyMat != &mat) m_cpyMat = mat; + eigen_assert(m_analysisIsOk && "The analysis phase should be called before the factorization phase"); + m_iparm(IPARM_START_TASK) = API_TASK_NUMFACT; + m_iparm(IPARM_END_TASK) = API_TASK_NUMFACT; + m_size = mat.rows(); + + internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(), + mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data()); + + // Check the returned error + if(m_iparm(IPARM_ERROR_NUMBER)) + { + m_info = NumericalIssue; + m_factorizationIsOk = false; + m_isInitialized = false; + } + else + { + m_info = Success; + m_factorizationIsOk = true; + m_isInitialized = true; + } +} + +/* Solve the system */ +template +template +bool PastixBase::_solve (const MatrixBase &b, MatrixBase &x) const +{ + eigen_assert(m_isInitialized && "The matrix should be factorized first"); + EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0, + THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); + int rhs = 1; + + x = b; /* on return, x is overwritten by the computed solution */ + + for (int i = 0; i < b.cols(); i++){ + m_iparm[IPARM_START_TASK] = API_TASK_SOLVE; + m_iparm[IPARM_END_TASK] = API_TASK_REFINE; + + internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, x.rows(), 0, 0, 0, + m_perm.data(), m_invp.data(), &x(0, i), rhs, m_iparm.data(), m_dparm.data()); + } + + // Check the returned error + m_info = m_iparm(IPARM_ERROR_NUMBER)==0 ? Success : NumericalIssue; + + return m_iparm(IPARM_ERROR_NUMBER)==0; +} + +/** \ingroup PaStiXSupport_Module + * \class PastixLU + * \brief Sparse direct LU solver based on PaStiX library + * + * This class is used to solve the linear systems A.X = B with a supernodal LU + * factorization in the PaStiX library. The matrix A should be squared and nonsingular + * PaStiX requires that the matrix A has a symmetric structural pattern. + * This interface can symmetrize the input matrix otherwise. + * The vectors or matrices X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam IsStrSym Indicates if the input matrix has a symmetric pattern, default is false + * NOTE : Note that if the analysis and factorization phase are called separately, + * the input matrix will be symmetrized at each call, hence it is advised to + * symmetrize the matrix in a end-user program and set \p IsStrSym to true + * + * \sa \ref TutorialSparseDirectSolvers + * + */ +template +class PastixLU : public PastixBase< PastixLU<_MatrixType> > +{ + public: + typedef _MatrixType MatrixType; + typedef PastixBase > Base; + typedef typename Base::ColSpMatrix ColSpMatrix; + typedef typename MatrixType::Index Index; + + public: + PastixLU() : Base() + { + init(); + } + + PastixLU(const MatrixType& matrix):Base() + { + init(); + compute(matrix); + } + /** Compute the LU supernodal factorization of \p matrix. + * iparm and dparm can be used to tune the PaStiX parameters. + * see the PaStiX user's manual + * \sa analyzePattern() factorize() + */ + void compute (const MatrixType& matrix) + { + m_structureIsUptodate = false; + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::compute(temp); + } + /** Compute the LU symbolic factorization of \p matrix using its sparsity pattern. + * Several ordering methods can be used at this step. See the PaStiX user's manual. + * The result of this operation can be used with successive matrices having the same pattern as \p matrix + * \sa factorize() + */ + void analyzePattern(const MatrixType& matrix) + { + m_structureIsUptodate = false; + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::analyzePattern(temp); + } + + /** Compute the LU supernodal factorization of \p matrix + * WARNING The matrix \p matrix should have the same structural pattern + * as the same used in the analysis phase. + * \sa analyzePattern() + */ + void factorize(const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::factorize(temp); + } + protected: + + void init() + { + m_structureIsUptodate = false; + m_iparm(IPARM_SYM) = API_SYM_NO; + m_iparm(IPARM_FACTORIZATION) = API_FACT_LU; + } + + void grabMatrix(const MatrixType& matrix, ColSpMatrix& out) + { + if(IsStrSym) + out = matrix; + else + { + if(!m_structureIsUptodate) + { + // update the transposed structure + m_transposedStructure = matrix.transpose(); + + // Set the elements of the matrix to zero + for (Index j=0; j + * \tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class PastixLLT : public PastixBase< PastixLLT<_MatrixType, _UpLo> > +{ + public: + typedef _MatrixType MatrixType; + typedef PastixBase > Base; + typedef typename Base::ColSpMatrix ColSpMatrix; + + public: + enum { UpLo = _UpLo }; + PastixLLT() : Base() + { + init(); + } + + PastixLLT(const MatrixType& matrix):Base() + { + init(); + compute(matrix); + } + + /** Compute the L factor of the LL^T supernodal factorization of \p matrix + * \sa analyzePattern() factorize() + */ + void compute (const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::compute(temp); + } + + /** Compute the LL^T symbolic factorization of \p matrix using its sparsity pattern + * The result of this operation can be used with successive matrices having the same pattern as \p matrix + * \sa factorize() + */ + void analyzePattern(const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::analyzePattern(temp); + } + /** Compute the LL^T supernodal numerical factorization of \p matrix + * \sa analyzePattern() + */ + void factorize(const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::factorize(temp); + } + protected: + using Base::m_iparm; + + void init() + { + m_iparm(IPARM_SYM) = API_SYM_YES; + m_iparm(IPARM_FACTORIZATION) = API_FACT_LLT; + } + + void grabMatrix(const MatrixType& matrix, ColSpMatrix& out) + { + // Pastix supports only lower, column-major matrices + out.template selfadjointView() = matrix.template selfadjointView(); + internal::c_to_fortran_numbering(out); + } +}; + +/** \ingroup PaStiXSupport_Module + * \class PastixLDLT + * \brief A sparse direct supernodal Cholesky (LLT) factorization and solver based on the PaStiX library + * + * This class is used to solve the linear systems A.X = B via a LDL^T supernodal Cholesky factorization + * available in the PaStiX library. The matrix A should be symmetric and positive definite + * WARNING Selfadjoint complex matrices are not supported in the current version of PaStiX + * The vectors or matrices X and B can be either dense or sparse + * + * \tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class PastixLDLT : public PastixBase< PastixLDLT<_MatrixType, _UpLo> > +{ + public: + typedef _MatrixType MatrixType; + typedef PastixBase > Base; + typedef typename Base::ColSpMatrix ColSpMatrix; + + public: + enum { UpLo = _UpLo }; + PastixLDLT():Base() + { + init(); + } + + PastixLDLT(const MatrixType& matrix):Base() + { + init(); + compute(matrix); + } + + /** Compute the L and D factors of the LDL^T factorization of \p matrix + * \sa analyzePattern() factorize() + */ + void compute (const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::compute(temp); + } + + /** Compute the LDL^T symbolic factorization of \p matrix using its sparsity pattern + * The result of this operation can be used with successive matrices having the same pattern as \p matrix + * \sa factorize() + */ + void analyzePattern(const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::analyzePattern(temp); + } + /** Compute the LDL^T supernodal numerical factorization of \p matrix + * + */ + void factorize(const MatrixType& matrix) + { + ColSpMatrix temp; + grabMatrix(matrix, temp); + Base::factorize(temp); + } + + protected: + using Base::m_iparm; + + void init() + { + m_iparm(IPARM_SYM) = API_SYM_YES; + m_iparm(IPARM_FACTORIZATION) = API_FACT_LDLT; + } + + void grabMatrix(const MatrixType& matrix, ColSpMatrix& out) + { + // Pastix supports only lower, column-major matrices + out.template selfadjointView() = matrix.template selfadjointView(); + internal::c_to_fortran_numbering(out); + } +}; + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef PastixBase<_MatrixType> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef PastixBase<_MatrixType> Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve_sparse(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/CMakeLists.txt new file mode 100644 index 000000000..a097ab401 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_PardisoSupport_SRCS "*.h") + +INSTALL(FILES + ${Eigen_PardisoSupport_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/PardisoSupport COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/PardisoSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/PardisoSupport.h new file mode 100644 index 000000000..e6defc8c3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/PardisoSupport.h @@ -0,0 +1,614 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL PARDISO + ******************************************************************************** +*/ + +#ifndef EIGEN_PARDISOSUPPORT_H +#define EIGEN_PARDISOSUPPORT_H + +namespace Eigen { + +template class PardisoLU; +template class PardisoLLT; +template class PardisoLDLT; + +namespace internal +{ + template + struct pardiso_run_selector + { + static Index run( _MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a, + Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x) + { + Index error = 0; + ::pardiso(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error); + return error; + } + }; + template<> + struct pardiso_run_selector + { + typedef long long int Index; + static Index run( _MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a, + Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x) + { + Index error = 0; + ::pardiso_64(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error); + return error; + } + }; + + template struct pardiso_traits; + + template + struct pardiso_traits< PardisoLU<_MatrixType> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + + template + struct pardiso_traits< PardisoLLT<_MatrixType, Options> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + + template + struct pardiso_traits< PardisoLDLT<_MatrixType, Options> > + { + typedef _MatrixType MatrixType; + typedef typename _MatrixType::Scalar Scalar; + typedef typename _MatrixType::RealScalar RealScalar; + typedef typename _MatrixType::Index Index; + }; + +} + +template +class PardisoImpl +{ + typedef internal::pardiso_traits Traits; + public: + typedef typename Traits::MatrixType MatrixType; + typedef typename Traits::Scalar Scalar; + typedef typename Traits::RealScalar RealScalar; + typedef typename Traits::Index Index; + typedef SparseMatrix SparseMatrixType; + typedef Matrix VectorType; + typedef Matrix IntRowVectorType; + typedef Matrix IntColVectorType; + enum { + ScalarIsComplex = NumTraits::IsComplex + }; + + PardisoImpl() + { + eigen_assert((sizeof(Index) >= sizeof(_INTEGER_t) && sizeof(Index) <= 8) && "Non-supported index type"); + m_iparm.setZero(); + m_msglvl = 0; // No output + m_initialized = false; + } + + ~PardisoImpl() + { + pardisoRelease(); + } + + inline Index cols() const { return m_size; } + inline Index rows() const { return m_size; } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_initialized && "Decomposition is not initialized."); + return m_info; + } + + /** \warning for advanced usage only. + * \returns a reference to the parameter array controlling PARDISO. + * See the PARDISO manual to know how to use it. */ + Array& pardisoParameterArray() + { + return m_iparm; + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + Derived& analyzePattern(const MatrixType& matrix); + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + Derived& factorize(const MatrixType& matrix); + + Derived& compute(const MatrixType& matrix); + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_initialized && "Pardiso solver is not initialized."); + eigen_assert(rows()==b.rows() + && "PardisoImpl::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::sparse_solve_retval + solve(const SparseMatrixBase& b) const + { + eigen_assert(m_initialized && "Pardiso solver is not initialized."); + eigen_assert(rows()==b.rows() + && "PardisoImpl::solve(): invalid number of rows of the right hand side matrix b"); + return internal::sparse_solve_retval(*this, b.derived()); + } + + Derived& derived() + { + return *static_cast(this); + } + const Derived& derived() const + { + return *static_cast(this); + } + + template + bool _solve(const MatrixBase &b, MatrixBase& x) const; + + /** \internal */ + template + void _solve_sparse(const Rhs& b, SparseMatrix &dest) const + { + eigen_assert(m_size==b.rows()); + + // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix. + static const int NbColsAtOnce = 4; + int rhsCols = b.cols(); + int size = b.rows(); + // Pardiso cannot solve in-place, + // so we need two temporaries + Eigen::Matrix tmp_rhs(size,rhsCols); + Eigen::Matrix tmp_res(size,rhsCols); + for(int k=0; k(rhsCols-k, NbColsAtOnce); + tmp_rhs.leftCols(actualCols) = b.middleCols(k,actualCols); + tmp_res.leftCols(actualCols) = derived().solve(tmp_rhs.leftCols(actualCols)); + dest.middleCols(k,actualCols) = tmp_res.leftCols(actualCols).sparseView(); + } + } + + protected: + void pardisoRelease() + { + if(m_initialized) // Factorization ran at least once + { + internal::pardiso_run_selector::run(m_pt, 1, 1, m_type, -1, m_size, 0, 0, 0, m_perm.data(), 0, + m_iparm.data(), m_msglvl, 0, 0); + } + } + + void pardisoInit(int type) + { + m_type = type; + bool symmetric = abs(m_type) < 10; + m_iparm[0] = 1; // No solver default + m_iparm[1] = 3; // use Metis for the ordering + m_iparm[2] = 1; // Numbers of processors, value of OMP_NUM_THREADS + m_iparm[3] = 0; // No iterative-direct algorithm + m_iparm[4] = 0; // No user fill-in reducing permutation + m_iparm[5] = 0; // Write solution into x + m_iparm[6] = 0; // Not in use + m_iparm[7] = 2; // Max numbers of iterative refinement steps + m_iparm[8] = 0; // Not in use + m_iparm[9] = 13; // Perturb the pivot elements with 1E-13 + m_iparm[10] = symmetric ? 0 : 1; // Use nonsymmetric permutation and scaling MPS + m_iparm[11] = 0; // Not in use + m_iparm[12] = symmetric ? 0 : 1; // Maximum weighted matching algorithm is switched-off (default for symmetric). + // Try m_iparm[12] = 1 in case of inappropriate accuracy + m_iparm[13] = 0; // Output: Number of perturbed pivots + m_iparm[14] = 0; // Not in use + m_iparm[15] = 0; // Not in use + m_iparm[16] = 0; // Not in use + m_iparm[17] = -1; // Output: Number of nonzeros in the factor LU + m_iparm[18] = -1; // Output: Mflops for LU factorization + m_iparm[19] = 0; // Output: Numbers of CG Iterations + + m_iparm[20] = 0; // 1x1 pivoting + m_iparm[26] = 0; // No matrix checker + m_iparm[27] = (sizeof(RealScalar) == 4) ? 1 : 0; + m_iparm[34] = 1; // C indexing + m_iparm[59] = 1; // Automatic switch between In-Core and Out-of-Core modes + } + + protected: + // cached data to reduce reallocation, etc. + + void manageErrorCode(Index error) + { + switch(error) + { + case 0: + m_info = Success; + break; + case -4: + case -7: + m_info = NumericalIssue; + break; + default: + m_info = InvalidInput; + } + } + + mutable SparseMatrixType m_matrix; + ComputationInfo m_info; + bool m_initialized, m_analysisIsOk, m_factorizationIsOk; + Index m_type, m_msglvl; + mutable void *m_pt[64]; + mutable Array m_iparm; + mutable IntColVectorType m_perm; + Index m_size; + + private: + PardisoImpl(PardisoImpl &) {} +}; + +template +Derived& PardisoImpl::compute(const MatrixType& a) +{ + m_size = a.rows(); + eigen_assert(a.rows() == a.cols()); + + pardisoRelease(); + memset(m_pt, 0, sizeof(m_pt)); + m_perm.setZero(m_size); + derived().getMatrix(a); + + Index error; + error = internal::pardiso_run_selector::run(m_pt, 1, 1, m_type, 12, m_size, + m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(), + m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL); + + manageErrorCode(error); + m_analysisIsOk = true; + m_factorizationIsOk = true; + m_initialized = true; + return derived(); +} + +template +Derived& PardisoImpl::analyzePattern(const MatrixType& a) +{ + m_size = a.rows(); + eigen_assert(m_size == a.cols()); + + pardisoRelease(); + memset(m_pt, 0, sizeof(m_pt)); + m_perm.setZero(m_size); + derived().getMatrix(a); + + Index error; + error = internal::pardiso_run_selector::run(m_pt, 1, 1, m_type, 11, m_size, + m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(), + m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL); + + manageErrorCode(error); + m_analysisIsOk = true; + m_factorizationIsOk = false; + m_initialized = true; + return derived(); +} + +template +Derived& PardisoImpl::factorize(const MatrixType& a) +{ + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + eigen_assert(m_size == a.rows() && m_size == a.cols()); + + derived().getMatrix(a); + + Index error; + error = internal::pardiso_run_selector::run(m_pt, 1, 1, m_type, 22, m_size, + m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(), + m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL); + + manageErrorCode(error); + m_factorizationIsOk = true; + return derived(); +} + +template +template +bool PardisoImpl::_solve(const MatrixBase &b, MatrixBase& x) const +{ + if(m_iparm[0] == 0) // Factorization was not computed + return false; + + //Index n = m_matrix.rows(); + Index nrhs = Index(b.cols()); + eigen_assert(m_size==b.rows()); + eigen_assert(((MatrixBase::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major right hand sides are not supported"); + eigen_assert(((MatrixBase::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major matrices of unknowns are not supported"); + eigen_assert(((nrhs == 1) || b.outerStride() == b.rows())); + + +// switch (transposed) { +// case SvNoTrans : m_iparm[11] = 0 ; break; +// case SvTranspose : m_iparm[11] = 2 ; break; +// case SvAdjoint : m_iparm[11] = 1 ; break; +// default: +// //std::cerr << "Eigen: transposition option \"" << transposed << "\" not supported by the PARDISO backend\n"; +// m_iparm[11] = 0; +// } + + Scalar* rhs_ptr = const_cast(b.derived().data()); + Matrix tmp; + + // Pardiso cannot solve in-place + if(rhs_ptr == x.derived().data()) + { + tmp = b; + rhs_ptr = tmp.data(); + } + + Index error; + error = internal::pardiso_run_selector::run(m_pt, 1, 1, m_type, 33, m_size, + m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(), + m_perm.data(), nrhs, m_iparm.data(), m_msglvl, + rhs_ptr, x.derived().data()); + + return error==0; +} + + +/** \ingroup PardisoSupport_Module + * \class PardisoLU + * \brief A sparse direct LU factorization and solver based on the PARDISO library + * + * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization + * using the Intel MKL PARDISO library. The sparse matrix A must be squared and invertible. + * The vectors or matrices X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class PardisoLU : public PardisoImpl< PardisoLU > +{ + protected: + typedef PardisoImpl< PardisoLU > Base; + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; + using Base::pardisoInit; + using Base::m_matrix; + friend class PardisoImpl< PardisoLU >; + + public: + + using Base::compute; + using Base::solve; + + PardisoLU() + : Base() + { + pardisoInit(Base::ScalarIsComplex ? 13 : 11); + } + + PardisoLU(const MatrixType& matrix) + : Base() + { + pardisoInit(Base::ScalarIsComplex ? 13 : 11); + compute(matrix); + } + protected: + void getMatrix(const MatrixType& matrix) + { + m_matrix = matrix; + } + + private: + PardisoLU(PardisoLU& ) {} +}; + +/** \ingroup PardisoSupport_Module + * \class PardisoLLT + * \brief A sparse direct Cholesky (LLT) factorization and solver based on the PARDISO library + * + * This class allows to solve for A.X = B sparse linear problems via a LL^T Cholesky factorization + * using the Intel MKL PARDISO library. The sparse matrix A must be selfajoint and positive definite. + * The vectors or matrices X and B can be either dense or sparse. + * + * \tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam UpLo can be any bitwise combination of Upper, Lower. The default is Upper, meaning only the upper triangular part has to be used. + * Upper|Lower can be used to tell both triangular parts can be used as input. + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class PardisoLLT : public PardisoImpl< PardisoLLT > +{ + protected: + typedef PardisoImpl< PardisoLLT > Base; + typedef typename Base::Scalar Scalar; + typedef typename Base::Index Index; + typedef typename Base::RealScalar RealScalar; + using Base::pardisoInit; + using Base::m_matrix; + friend class PardisoImpl< PardisoLLT >; + + public: + + enum { UpLo = _UpLo }; + using Base::compute; + using Base::solve; + + PardisoLLT() + : Base() + { + pardisoInit(Base::ScalarIsComplex ? 4 : 2); + } + + PardisoLLT(const MatrixType& matrix) + : Base() + { + pardisoInit(Base::ScalarIsComplex ? 4 : 2); + compute(matrix); + } + + protected: + + void getMatrix(const MatrixType& matrix) + { + // PARDISO supports only upper, row-major matrices + PermutationMatrix p_null; + m_matrix.resize(matrix.rows(), matrix.cols()); + m_matrix.template selfadjointView() = matrix.template selfadjointView().twistedBy(p_null); + } + + private: + PardisoLLT(PardisoLLT& ) {} +}; + +/** \ingroup PardisoSupport_Module + * \class PardisoLDLT + * \brief A sparse direct Cholesky (LDLT) factorization and solver based on the PARDISO library + * + * This class allows to solve for A.X = B sparse linear problems via a LDL^T Cholesky factorization + * using the Intel MKL PARDISO library. The sparse matrix A is assumed to be selfajoint and positive definite. + * For complex matrices, A can also be symmetric only, see the \a Options template parameter. + * The vectors or matrices X and B can be either dense or sparse. + * + * \tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam Options can be any bitwise combination of Upper, Lower, and Symmetric. The default is Upper, meaning only the upper triangular part has to be used. + * Symmetric can be used for symmetric, non-selfadjoint complex matrices, the default being to assume a selfadjoint matrix. + * Upper|Lower can be used to tell both triangular parts can be used as input. + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class PardisoLDLT : public PardisoImpl< PardisoLDLT > +{ + protected: + typedef PardisoImpl< PardisoLDLT > Base; + typedef typename Base::Scalar Scalar; + typedef typename Base::Index Index; + typedef typename Base::RealScalar RealScalar; + using Base::pardisoInit; + using Base::m_matrix; + friend class PardisoImpl< PardisoLDLT >; + + public: + + using Base::compute; + using Base::solve; + enum { UpLo = Options&(Upper|Lower) }; + + PardisoLDLT() + : Base() + { + pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2); + } + + PardisoLDLT(const MatrixType& matrix) + : Base() + { + pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2); + compute(matrix); + } + + void getMatrix(const MatrixType& matrix) + { + // PARDISO supports only upper, row-major matrices + PermutationMatrix p_null; + m_matrix.resize(matrix.rows(), matrix.cols()); + m_matrix.template selfadjointView() = matrix.template selfadjointView().twistedBy(p_null); + } + + private: + PardisoLDLT(PardisoLDLT& ) {} +}; + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef PardisoImpl<_Derived> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef PardisoImpl Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve_sparse(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PARDISOSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h index f04c6038d..9550b6bf6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h @@ -26,6 +26,8 @@ #ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_H #define EIGEN_COLPIVOTINGHOUSEHOLDERQR_H +namespace Eigen { + /** \ingroup QR_Module * * \class ColPivHouseholderQR @@ -528,5 +530,6 @@ MatrixBase::colPivHouseholderQr() const return ColPivHouseholderQR(eval()); } +} // end namespace Eigen #endif // EIGEN_COLPIVOTINGHOUSEHOLDERQR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h new file mode 100644 index 000000000..0ad66d3f8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h @@ -0,0 +1,98 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Householder QR decomposition of a matrix with column pivoting based on + * LAPACKE_?geqp3 function. + ******************************************************************************** +*/ + +#ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_MKL_H +#define EIGEN_COLPIVOTINGHOUSEHOLDERQR_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_QR_COLPIV(EIGTYPE, MKLTYPE, MKLPREFIX, EIGCOLROW, MKLCOLROW) \ +template<> \ +ColPivHouseholderQR >& \ +ColPivHouseholderQR >::compute( \ + const Matrix& matrix) \ +\ +{ \ + typedef Matrix MatrixType; \ + typedef MatrixType::Scalar Scalar; \ + typedef MatrixType::RealScalar RealScalar; \ + Index rows = matrix.rows();\ + Index cols = matrix.cols();\ + Index size = matrix.diagonalSize();\ +\ + m_qr = matrix;\ + m_hCoeffs.resize(size);\ +\ + m_colsTranspositions.resize(cols);\ + /*Index number_of_transpositions = 0;*/ \ +\ + m_nonzero_pivots = 0; \ + m_maxpivot = RealScalar(0);\ + m_colsPermutation.resize(cols); \ + m_colsPermutation.indices().setZero(); \ +\ + lapack_int lda = m_qr.outerStride(), i; \ + lapack_int matrix_order = MKLCOLROW; \ + LAPACKE_##MKLPREFIX##geqp3( matrix_order, rows, cols, (MKLTYPE*)m_qr.data(), lda, (lapack_int*)m_colsPermutation.indices().data(), (MKLTYPE*)m_hCoeffs.data()); \ + m_isInitialized = true; \ + m_maxpivot=m_qr.diagonal().cwiseAbs().maxCoeff(); \ + m_hCoeffs.adjointInPlace(); \ + RealScalar premultiplied_threshold = internal::abs(m_maxpivot) * threshold(); \ + lapack_int *perm = m_colsPermutation.indices().data(); \ + for(i=0;i premultiplied_threshold);\ + } \ + for(i=0;i struct FullPivHouseholderQRMatrixQReturnType; + +template +struct traits > +{ + typedef typename MatrixType::PlainObject ReturnType; +}; + +} + /** \ingroup QR_Module * * \class FullPivHouseholderQR @@ -62,7 +76,7 @@ template class FullPivHouseholderQR typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; typedef typename MatrixType::Index Index; - typedef Matrix MatrixQType; + typedef internal::FullPivHouseholderQRMatrixQReturnType MatrixQReturnType; typedef typename internal::plain_diag_type::type HCoeffsType; typedef Matrix IntRowVectorType; typedef PermutationMatrix PermutationType; @@ -139,7 +153,9 @@ template class FullPivHouseholderQR return internal::solve_retval(*this, b.derived()); } - MatrixQType matrixQ(void) const; + /** \returns Expression object representing the matrix Q + */ + MatrixQReturnType matrixQ(void) const; /** \returns a reference to the matrix where the Householder QR decomposition is stored */ @@ -508,28 +524,73 @@ struct solve_retval, Rhs> } }; +/** \ingroup QR_Module + * + * \brief Expression type for return value of FullPivHouseholderQR::matrixQ() + * + * \tparam MatrixType type of underlying dense matrix + */ +template struct FullPivHouseholderQRMatrixQReturnType + : public ReturnByValue > +{ +public: + typedef typename MatrixType::Index Index; + typedef typename internal::plain_col_type::type IntColVectorType; + typedef typename internal::plain_diag_type::type HCoeffsType; + typedef Matrix WorkVectorType; + + FullPivHouseholderQRMatrixQReturnType(const MatrixType& qr, + const HCoeffsType& hCoeffs, + const IntColVectorType& rowsTranspositions) + : m_qr(qr), + m_hCoeffs(hCoeffs), + m_rowsTranspositions(rowsTranspositions) + {} + + template + void evalTo(ResultType& result) const + { + const Index rows = m_qr.rows(); + WorkVectorType workspace(rows); + evalTo(result, workspace); + } + + template + void evalTo(ResultType& result, WorkVectorType& workspace) const + { + // compute the product H'_0 H'_1 ... H'_n-1, + // where H_k is the k-th Householder transformation I - h_k v_k v_k' + // and v_k is the k-th Householder vector [1,m_qr(k+1,k), m_qr(k+2,k), ...] + const Index rows = m_qr.rows(); + const Index cols = m_qr.cols(); + const Index size = (std::min)(rows, cols); + workspace.resize(rows); + result.setIdentity(rows, rows); + for (Index k = size-1; k >= 0; k--) + { + result.block(k, k, rows-k, rows-k) + .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), internal::conj(m_hCoeffs.coeff(k)), &workspace.coeffRef(k)); + result.row(k).swap(result.row(m_rowsTranspositions.coeff(k))); + } + } + + Index rows() const { return m_qr.rows(); } + Index cols() const { return m_qr.rows(); } + +protected: + typename MatrixType::Nested m_qr; + typename HCoeffsType::Nested m_hCoeffs; + typename IntColVectorType::Nested m_rowsTranspositions; +}; + } // end namespace internal -/** \returns the matrix Q */ template -typename FullPivHouseholderQR::MatrixQType FullPivHouseholderQR::matrixQ() const +inline typename FullPivHouseholderQR::MatrixQReturnType FullPivHouseholderQR::matrixQ() const { eigen_assert(m_isInitialized && "FullPivHouseholderQR is not initialized."); - // compute the product H'_0 H'_1 ... H'_n-1, - // where H_k is the k-th Householder transformation I - h_k v_k v_k' - // and v_k is the k-th Householder vector [1,m_qr(k+1,k), m_qr(k+2,k), ...] - Index rows = m_qr.rows(); - Index cols = m_qr.cols(); - Index size = (std::min)(rows,cols); - MatrixQType res = MatrixQType::Identity(rows, rows); - Matrix temp(rows); - for (Index k = size-1; k >= 0; k--) - { - res.block(k, k, rows-k, rows-k) - .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), internal::conj(m_hCoeffs.coeff(k)), &temp.coeffRef(k)); - res.row(k).swap(res.row(m_rows_transpositions.coeff(k))); - } - return res; + return MatrixQReturnType(m_qr, m_hCoeffs, m_rows_transpositions); } /** \return the full-pivoting Householder QR decomposition of \c *this. @@ -543,4 +604,6 @@ MatrixBase::fullPivHouseholderQr() const return FullPivHouseholderQR(eval()); } +} // end namespace Eigen + #endif // EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h index 9ee96de26..59f6fcaa2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h @@ -27,6 +27,8 @@ #ifndef EIGEN_QR_H #define EIGEN_QR_H +namespace Eigen { + /** \ingroup QR_Module * * @@ -351,5 +353,6 @@ MatrixBase::householderQr() const return HouseholderQR(eval()); } +} // end namespace Eigen #endif // EIGEN_QR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR_MKL.h new file mode 100644 index 000000000..5313de604 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR_MKL.h @@ -0,0 +1,69 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Householder QR decomposition of a matrix w/o pivoting based on + * LAPACKE_?geqrf function. + ******************************************************************************** +*/ + +#ifndef EIGEN_QR_MKL_H +#define EIGEN_QR_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +namespace internal { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_QR_NOPIV(EIGTYPE, MKLTYPE, MKLPREFIX) \ +template \ +void householder_qr_inplace_blocked(MatrixQR& mat, HCoeffs& hCoeffs, \ + typename MatrixQR::Index maxBlockSize=32, \ + EIGTYPE* tempData = 0) \ +{ \ + lapack_int m = mat.rows(); \ + lapack_int n = mat.cols(); \ + lapack_int lda = mat.outerStride(); \ + lapack_int matrix_order = (MatrixQR::IsRowMajor) ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \ + LAPACKE_##MKLPREFIX##geqrf( matrix_order, m, n, (MKLTYPE*)mat.data(), lda, (MKLTYPE*)hCoeffs.data()); \ + hCoeffs.adjointInPlace(); \ +\ +} + +EIGEN_MKL_QR_NOPIV(double, double, d) +EIGEN_MKL_QR_NOPIV(float, float, s) +EIGEN_MKL_QR_NOPIV(dcomplex, MKL_Complex16, z) +EIGEN_MKL_QR_NOPIV(scomplex, MKL_Complex8, c) + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_QR_MKL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h index 3c423095c..9eadaa9fc 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h @@ -25,6 +25,8 @@ #ifndef EIGEN_JACOBISVD_H #define EIGEN_JACOBISVD_H +namespace Eigen { + namespace internal { // forward declaration (needed by ICC) // the empty body is required by MSVC @@ -61,9 +63,12 @@ template struct qr_preconditioner_impl {}; template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD&, const MatrixType&) +public: + typedef typename MatrixType::Index Index; + void allocate(const JacobiSVD&) {} + bool run(JacobiSVD&, const MatrixType&) { return false; } @@ -72,134 +77,279 @@ struct qr_preconditioner_impl /*** preconditioner using FullPivHouseholderQR ***/ template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + enum + { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime + }; + typedef Matrix WorkspaceType; + + void allocate(const JacobiSVD& svd) + { + if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols()) + { + m_qr = FullPivHouseholderQR(svd.rows(), svd.cols()); + } + if (svd.m_computeFullU) m_workspace.resize(svd.rows()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.rows() > matrix.cols()) { - FullPivHouseholderQR qr(matrix); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); - if(svd.m_computeFullU) svd.m_matrixU = qr.matrixQ(); - if(svd.computeV()) svd.m_matrixV = qr.colsPermutation(); + m_qr.compute(matrix); + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); + if(svd.m_computeFullU) m_qr.matrixQ().evalTo(svd.m_matrixU, m_workspace); + if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation(); return true; } return false; } +private: + FullPivHouseholderQR m_qr; + WorkspaceType m_workspace; }; template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + enum + { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, + Options = MatrixType::Options + }; + typedef Matrix + TransposeTypeWithSameStorageOrder; + + void allocate(const JacobiSVD& svd) + { + if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols()) + { + m_qr = FullPivHouseholderQR(svd.cols(), svd.rows()); + } + m_adjoint.resize(svd.cols(), svd.rows()); + if (svd.m_computeFullV) m_workspace.resize(svd.cols()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.cols() > matrix.rows()) { - typedef Matrix - TransposeTypeWithSameStorageOrder; - FullPivHouseholderQR qr(matrix.adjoint()); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); - if(svd.m_computeFullV) svd.m_matrixV = qr.matrixQ(); - if(svd.computeU()) svd.m_matrixU = qr.colsPermutation(); + m_adjoint = matrix.adjoint(); + m_qr.compute(m_adjoint); + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); + if(svd.m_computeFullV) m_qr.matrixQ().evalTo(svd.m_matrixV, m_workspace); + if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation(); return true; } else return false; } +private: + FullPivHouseholderQR m_qr; + TransposeTypeWithSameStorageOrder m_adjoint; + typename internal::plain_row_type::type m_workspace; }; /*** preconditioner using ColPivHouseholderQR ***/ template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + + void allocate(const JacobiSVD& svd) + { + if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols()) + { + m_qr = ColPivHouseholderQR(svd.rows(), svd.cols()); + } + if (svd.m_computeFullU) m_workspace.resize(svd.rows()); + else if (svd.m_computeThinU) m_workspace.resize(svd.cols()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.rows() > matrix.cols()) { - ColPivHouseholderQR qr(matrix); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); - if(svd.m_computeFullU) svd.m_matrixU = qr.householderQ(); - else if(svd.m_computeThinU) { + m_qr.compute(matrix); + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); + if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace); + else if(svd.m_computeThinU) + { svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols()); - qr.householderQ().applyThisOnTheLeft(svd.m_matrixU); + m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace); } - if(svd.computeV()) svd.m_matrixV = qr.colsPermutation(); + if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation(); return true; } return false; } + +private: + ColPivHouseholderQR m_qr; + typename internal::plain_col_type::type m_workspace; }; template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + enum + { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, + Options = MatrixType::Options + }; + + typedef Matrix + TransposeTypeWithSameStorageOrder; + + void allocate(const JacobiSVD& svd) + { + if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols()) + { + m_qr = ColPivHouseholderQR(svd.cols(), svd.rows()); + } + if (svd.m_computeFullV) m_workspace.resize(svd.cols()); + else if (svd.m_computeThinV) m_workspace.resize(svd.rows()); + m_adjoint.resize(svd.cols(), svd.rows()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.cols() > matrix.rows()) { - typedef Matrix - TransposeTypeWithSameStorageOrder; - ColPivHouseholderQR qr(matrix.adjoint()); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); - if(svd.m_computeFullV) svd.m_matrixV = qr.householderQ(); - else if(svd.m_computeThinV) { + m_adjoint = matrix.adjoint(); + m_qr.compute(m_adjoint); + + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); + if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace); + else if(svd.m_computeThinV) + { svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows()); - qr.householderQ().applyThisOnTheLeft(svd.m_matrixV); + m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace); } - if(svd.computeU()) svd.m_matrixU = qr.colsPermutation(); + if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation(); return true; } else return false; } + +private: + ColPivHouseholderQR m_qr; + TransposeTypeWithSameStorageOrder m_adjoint; + typename internal::plain_row_type::type m_workspace; }; /*** preconditioner using HouseholderQR ***/ template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + + void allocate(const JacobiSVD& svd) + { + if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols()) + { + m_qr = HouseholderQR(svd.rows(), svd.cols()); + } + if (svd.m_computeFullU) m_workspace.resize(svd.rows()); + else if (svd.m_computeThinU) m_workspace.resize(svd.cols()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.rows() > matrix.cols()) { - HouseholderQR qr(matrix); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); - if(svd.m_computeFullU) svd.m_matrixU = qr.householderQ(); - else if(svd.m_computeThinU) { + m_qr.compute(matrix); + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView(); + if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace); + else if(svd.m_computeThinU) + { svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols()); - qr.householderQ().applyThisOnTheLeft(svd.m_matrixU); + m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace); } if(svd.computeV()) svd.m_matrixV.setIdentity(matrix.cols(), matrix.cols()); return true; } return false; } +private: + HouseholderQR m_qr; + typename internal::plain_col_type::type m_workspace; }; template -struct qr_preconditioner_impl +class qr_preconditioner_impl { - static bool run(JacobiSVD& svd, const MatrixType& matrix) +public: + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + enum + { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, + Options = MatrixType::Options + }; + + typedef Matrix + TransposeTypeWithSameStorageOrder; + + void allocate(const JacobiSVD& svd) + { + if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols()) + { + m_qr = HouseholderQR(svd.cols(), svd.rows()); + } + if (svd.m_computeFullV) m_workspace.resize(svd.cols()); + else if (svd.m_computeThinV) m_workspace.resize(svd.rows()); + m_adjoint.resize(svd.cols(), svd.rows()); + } + + bool run(JacobiSVD& svd, const MatrixType& matrix) { if(matrix.cols() > matrix.rows()) { - typedef Matrix - TransposeTypeWithSameStorageOrder; - HouseholderQR qr(matrix.adjoint()); - svd.m_workMatrix = qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); - if(svd.m_computeFullV) svd.m_matrixV = qr.householderQ(); - else if(svd.m_computeThinV) { + m_adjoint = matrix.adjoint(); + m_qr.compute(m_adjoint); + + svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView().adjoint(); + if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace); + else if(svd.m_computeThinV) + { svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows()); - qr.householderQ().applyThisOnTheLeft(svd.m_matrixV); + m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace); } if(svd.computeU()) svd.m_matrixU.setIdentity(matrix.rows(), matrix.rows()); return true; } else return false; } + +private: + HouseholderQR m_qr; + TransposeTypeWithSameStorageOrder m_adjoint; + typename internal::plain_row_type::type m_workspace; }; /*** 2x2 SVD implementation @@ -316,7 +466,7 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q, * Here's an example demonstrating basic usage: * \include JacobiSVD_basic.cpp * Output: \verbinclude JacobiSVD_basic.out - * + * * This JacobiSVD class is a two-sided Jacobi R-SVD decomposition, ensuring optimal reliability and accuracy. The downside is that it's slower than * bidiagonalizing SVD algorithms for large square matrices; however its complexity is still \f$ O(n^2p) \f$ where \a n is the smaller dimension and * \a p is the greater dimension, meaning that it is still of the same order of complexity as the faster bidiagonalizing R-SVD algorithms. @@ -324,7 +474,7 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q, * * If the input matrix has inf or nan coefficients, the result of the computation is undefined, but the computation is guaranteed to * terminate in finite (and reasonable) time. - * + * * The possible values for QRPreconditioner are: * \li ColPivHouseholderQRPreconditioner is the default. In practice it's very safe. It uses column-pivoting QR. * \li FullPivHouseholderQRPreconditioner, is the safest and slowest. It uses full-pivoting QR. @@ -494,7 +644,7 @@ template class JacobiSVD * \param b the right-hand-side of the equation to solve. * * \note Solving requires both U and V to be computed. Thin U and V are enough, there is no need for full U or V. - * + * * \note SVD solving is implicitly least-squares. Thus, this method serves both purposes of exact solving and least-squares solving. * In other words, the returned solution is guaranteed to minimize the Euclidean norm \f$ \Vert A x - b \Vert \f$. */ @@ -535,6 +685,9 @@ template class JacobiSVD friend struct internal::svd_precondition_2x2_block_to_be_real; template friend struct internal::qr_preconditioner_impl; + + internal::qr_preconditioner_impl m_qr_precond_morecols; + internal::qr_preconditioner_impl m_qr_precond_morerows; }; template @@ -578,6 +731,9 @@ void JacobiSVD::allocate(Index rows, Index cols, u : m_computeThinV ? m_diagSize : 0); m_workMatrix.resize(m_diagSize, m_diagSize); + + if(m_cols>m_rows) m_qr_precond_morecols.allocate(*this); + if(m_rows>m_cols) m_qr_precond_morerows.allocate(*this); } template @@ -595,8 +751,7 @@ JacobiSVD::compute(const MatrixType& matrix, unsig /*** step 1. The R-SVD step: we use a QR decomposition to reduce to the case of a square matrix */ - if(!internal::qr_preconditioner_impl::run(*this, matrix) - && !internal::qr_preconditioner_impl::run(*this, matrix)) + if(!m_qr_precond_morecols.run(*this, matrix) && !m_qr_precond_morerows.run(*this, matrix)) { m_workMatrix = matrix.block(0,0,m_diagSize,m_diagSize); if(m_computeFullU) m_matrixU.setIdentity(m_rows,m_rows); @@ -722,6 +877,6 @@ MatrixBase::jacobiSvd(unsigned int computationOptions) const return JacobiSVD(*this, computationOptions); } - +} // end namespace Eigen #endif // EIGEN_JACOBISVD_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD_MKL.h new file mode 100644 index 000000000..1eeafca49 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD_MKL.h @@ -0,0 +1,92 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Eigen bindings to Intel(R) MKL + * Singular Value Decomposition - SVD. + ******************************************************************************** +*/ + +#ifndef EIGEN_JACOBISVD_MKL_H +#define EIGEN_JACOBISVD_MKL_H + +#include "Eigen/src/Core/util/MKL_support.h" + +namespace Eigen { + +/** \internal Specialization for the data types supported by MKL */ + +#define EIGEN_MKL_SVD(EIGTYPE, MKLTYPE, MKLRTYPE, MKLPREFIX, EIGCOLROW, MKLCOLROW) \ +template<> \ +JacobiSVD, ColPivHouseholderQRPreconditioner>& \ +JacobiSVD, ColPivHouseholderQRPreconditioner>::compute(const Matrix& matrix, unsigned int computationOptions) \ +{ \ + typedef Matrix MatrixType; \ + typedef MatrixType::Scalar Scalar; \ + typedef MatrixType::RealScalar RealScalar; \ + allocate(matrix.rows(), matrix.cols(), computationOptions); \ +\ + /*const RealScalar precision = RealScalar(2) * NumTraits::epsilon();*/ \ + m_nonzeroSingularValues = m_diagSize; \ +\ + lapack_int lda = matrix.outerStride(), ldu, ldvt; \ + lapack_int matrix_order = MKLCOLROW; \ + char jobu, jobvt; \ + MKLTYPE *u, *vt, dummy; \ + jobu = (m_computeFullU) ? 'A' : (m_computeThinU) ? 'S' : 'N'; \ + jobvt = (m_computeFullV) ? 'A' : (m_computeThinV) ? 'S' : 'N'; \ + if (computeU()) { \ + ldu = m_matrixU.outerStride(); \ + u = (MKLTYPE*)m_matrixU.data(); \ + } else { ldu=1; u=&dummy; }\ + MatrixType localV; \ + ldvt = (m_computeFullV) ? m_cols : (m_computeThinV) ? m_diagSize : 1; \ + if (computeV()) { \ + localV.resize(ldvt, m_cols); \ + vt = (MKLTYPE*)localV.data(); \ + } else { ldvt=1; vt=&dummy; }\ + Matrix superb; superb.resize(m_diagSize, 1); \ + MatrixType m_temp; m_temp = matrix; \ + LAPACKE_##MKLPREFIX##gesvd( matrix_order, jobu, jobvt, m_rows, m_cols, (MKLTYPE*)m_temp.data(), lda, (MKLRTYPE*)m_singularValues.data(), u, ldu, vt, ldvt, superb.data()); \ + if (computeV()) m_matrixV = localV.adjoint(); \ + /* for(int i=0;i::bidiagonalization() const } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_BIDIAGONALIZATION_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CMakeLists.txt deleted file mode 100644 index aa1468812..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -FILE(GLOB Eigen_Sparse_SRCS "*.h") - -INSTALL(FILES - ${Eigen_Sparse_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/Sparse COMPONENT Devel - ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrix.h deleted file mode 100644 index 0e175ec6e..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrix.h +++ /dev/null @@ -1,651 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SPARSEMATRIX_H -#define EIGEN_SPARSEMATRIX_H - -/** \ingroup Sparse_Module - * - * \class SparseMatrix - * - * \brief The main sparse matrix class - * - * This class implements a sparse matrix using the very common compressed row/column storage - * scheme. - * - * \tparam _Scalar the scalar type, i.e. the type of the coefficients - * \tparam _Options Union of bit flags controlling the storage scheme. Currently the only possibility - * is RowMajor. The default is 0 which means column-major. - * \tparam _Index the type of the indices. Default is \c int. - * - * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme. - * - * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_SPARSEMATRIX_PLUGIN. - */ - -namespace internal { -template -struct traits > -{ - typedef _Scalar Scalar; - typedef _Index Index; - typedef Sparse StorageKind; - typedef MatrixXpr XprKind; - enum { - RowsAtCompileTime = Dynamic, - ColsAtCompileTime = Dynamic, - MaxRowsAtCompileTime = Dynamic, - MaxColsAtCompileTime = Dynamic, - Flags = _Options | NestByRefBit | LvalueBit, - CoeffReadCost = NumTraits::ReadCost, - SupportedAccessPatterns = InnerRandomAccessPattern - }; -}; - -} // end namespace internal - -template -class SparseMatrix - : public SparseMatrixBase > -{ - public: - EIGEN_SPARSE_PUBLIC_INTERFACE(SparseMatrix) -// using Base::operator=; - EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseMatrix, +=) - EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseMatrix, -=) - // FIXME: why are these operator already alvailable ??? - // EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(SparseMatrix, *=) - // EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(SparseMatrix, /=) - - typedef MappedSparseMatrix Map; - using Base::IsRowMajor; - typedef CompressedStorage Storage; - enum { - Options = _Options - }; - - protected: - - typedef SparseMatrix TransposedSparseMatrix; - - Index m_outerSize; - Index m_innerSize; - Index* m_outerIndex; - CompressedStorage m_data; - - public: - - inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; } - inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; } - - inline Index innerSize() const { return m_innerSize; } - inline Index outerSize() const { return m_outerSize; } - inline Index innerNonZeros(Index j) const { return m_outerIndex[j+1]-m_outerIndex[j]; } - - inline const Scalar* _valuePtr() const { return &m_data.value(0); } - inline Scalar* _valuePtr() { return &m_data.value(0); } - - inline const Index* _innerIndexPtr() const { return &m_data.index(0); } - inline Index* _innerIndexPtr() { return &m_data.index(0); } - - inline const Index* _outerIndexPtr() const { return m_outerIndex; } - inline Index* _outerIndexPtr() { return m_outerIndex; } - - inline Storage& data() { return m_data; } - inline const Storage& data() const { return m_data; } - - inline Scalar coeff(Index row, Index col) const - { - const Index outer = IsRowMajor ? row : col; - const Index inner = IsRowMajor ? col : row; - return m_data.atInRange(m_outerIndex[outer], m_outerIndex[outer+1], inner); - } - - inline Scalar& coeffRef(Index row, Index col) - { - const Index outer = IsRowMajor ? row : col; - const Index inner = IsRowMajor ? col : row; - - Index start = m_outerIndex[outer]; - Index end = m_outerIndex[outer+1]; - eigen_assert(end>=start && "you probably called coeffRef on a non finalized matrix"); - eigen_assert(end>start && "coeffRef cannot be called on a zero coefficient"); - const Index p = m_data.searchLowerIndex(start,end-1,inner); - eigen_assert((p(m_data.size()); } - - /** Preallocates \a reserveSize non zeros */ - inline void reserve(Index reserveSize) - { - m_data.reserve(reserveSize); - } - - //--- low level purely coherent filling --- - - /** \returns a reference to the non zero coefficient at position \a row, \a col assuming that: - * - the nonzero does not already exist - * - the new coefficient is the last one according to the storage order - * - * Before filling a given inner vector you must call the statVec(Index) function. - * - * After an insertion session, you should call the finalize() function. - * - * \sa insert, insertBackByOuterInner, startVec */ - inline Scalar& insertBack(Index row, Index col) - { - return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row); - } - - /** \sa insertBack, startVec */ - inline Scalar& insertBackByOuterInner(Index outer, Index inner) - { - eigen_assert(size_t(m_outerIndex[outer+1]) == m_data.size() && "Invalid ordered insertion (invalid outer index)"); - eigen_assert( (m_outerIndex[outer+1]-m_outerIndex[outer]==0 || m_data.index(m_data.size()-1)=0 && m_outerIndex[previousOuter]==0) - { - m_outerIndex[previousOuter] = static_cast(m_data.size()); - --previousOuter; - } - m_outerIndex[outer+1] = m_outerIndex[outer]; - } - - // here we have to handle the tricky case where the outerIndex array - // starts with: [ 0 0 0 0 0 1 ...] and we are inserting in, e.g., - // the 2nd inner vector... - bool isLastVec = (!(previousOuter==-1 && m_data.size()!=0)) - && (size_t(m_outerIndex[outer+1]) == m_data.size()); - - size_t startId = m_outerIndex[outer]; - // FIXME let's make sure sizeof(long int) == sizeof(size_t) - size_t p = m_outerIndex[outer+1]; - ++m_outerIndex[outer+1]; - - float reallocRatio = 1; - if (m_data.allocatedSize()<=m_data.size()) - { - // if there is no preallocated memory, let's reserve a minimum of 32 elements - if (m_data.size()==0) - { - m_data.reserve(32); - } - else - { - // we need to reallocate the data, to reduce multiple reallocations - // we use a smart resize algorithm based on the current filling ratio - // in addition, we use float to avoid integers overflows - float nnzEstimate = float(m_outerIndex[outer])*float(m_outerSize)/float(outer+1); - reallocRatio = (nnzEstimate-float(m_data.size()))/float(m_data.size()); - // furthermore we bound the realloc ratio to: - // 1) reduce multiple minor realloc when the matrix is almost filled - // 2) avoid to allocate too much memory when the matrix is almost empty - reallocRatio = (std::min)((std::max)(reallocRatio,1.5f),8.f); - } - } - m_data.resize(m_data.size()+1,reallocRatio); - - if (!isLastVec) - { - if (previousOuter==-1) - { - // oops wrong guess. - // let's correct the outer offsets - for (Index k=0; k<=(outer+1); ++k) - m_outerIndex[k] = 0; - Index k=outer+1; - while(m_outerIndex[k]==0) - m_outerIndex[k++] = 1; - while (k<=m_outerSize && m_outerIndex[k]!=0) - m_outerIndex[k++]++; - p = 0; - --k; - k = m_outerIndex[k]-1; - while (k>0) - { - m_data.index(k) = m_data.index(k-1); - m_data.value(k) = m_data.value(k-1); - k--; - } - } - else - { - // we are not inserting into the last inner vec - // update outer indices: - Index j = outer+2; - while (j<=m_outerSize && m_outerIndex[j]!=0) - m_outerIndex[j++]++; - --j; - // shift data of last vecs: - Index k = m_outerIndex[j]-1; - while (k>=Index(p)) - { - m_data.index(k) = m_data.index(k-1); - m_data.value(k) = m_data.value(k-1); - k--; - } - } - } - - while ( (p > startId) && (m_data.index(p-1) > inner) ) - { - m_data.index(p) = m_data.index(p-1); - m_data.value(p) = m_data.value(p-1); - --p; - } - - m_data.index(p) = inner; - return (m_data.value(p) = 0); - } - - - - - /** Must be called after inserting a set of non zero entries. - */ - inline void finalize() - { - Index size = static_cast(m_data.size()); - Index i = m_outerSize; - // find the last filled column - while (i>=0 && m_outerIndex[i]==0) - --i; - ++i; - while (i<=m_outerSize) - { - m_outerIndex[i] = size; - ++i; - } - } - - /** Suppress all nonzeros which are smaller than \a reference under the tolerence \a epsilon */ - void prune(Scalar reference, RealScalar epsilon = NumTraits::dummy_precision()) - { - prune(default_prunning_func(reference,epsilon)); - } - - /** Suppress all nonzeros which do not satisfy the predicate \a keep. - * The functor type \a KeepFunc must implement the following function: - * \code - * bool operator() (const Index& row, const Index& col, const Scalar& value) const; - * \endcode - * \sa prune(Scalar,RealScalar) - */ - template - void prune(const KeepFunc& keep = KeepFunc()) - { - Index k = 0; - for(Index j=0; j - inline SparseMatrix(const SparseMatrixBase& other) - : m_outerSize(0), m_innerSize(0), m_outerIndex(0) - { - *this = other.derived(); - } - - /** Copy constructor */ - inline SparseMatrix(const SparseMatrix& other) - : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0) - { - *this = other.derived(); - } - - /** Swap the content of two sparse matrices of same type (optimization) */ - inline void swap(SparseMatrix& other) - { - //EIGEN_DBG_SPARSE(std::cout << "SparseMatrix:: swap\n"); - std::swap(m_outerIndex, other.m_outerIndex); - std::swap(m_innerSize, other.m_innerSize); - std::swap(m_outerSize, other.m_outerSize); - m_data.swap(other.m_data); - } - - inline SparseMatrix& operator=(const SparseMatrix& other) - { -// std::cout << "SparseMatrix& operator=(const SparseMatrix& other)\n"; - if (other.isRValue()) - { - swap(other.const_cast_derived()); - } - else - { - resize(other.rows(), other.cols()); - memcpy(m_outerIndex, other.m_outerIndex, (m_outerSize+1)*sizeof(Index)); - m_data = other.m_data; - } - return *this; - } - - #ifndef EIGEN_PARSED_BY_DOXYGEN - template - inline SparseMatrix& operator=(const SparseSparseProduct& product) - { return Base::operator=(product); } - - template - inline SparseMatrix& operator=(const ReturnByValue& other) - { return Base::operator=(other); } - - template - inline SparseMatrix& operator=(const EigenBase& other) - { return Base::operator=(other); } - #endif - - template - EIGEN_DONT_INLINE SparseMatrix& operator=(const SparseMatrixBase& other) - { - const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); - if (needToTranspose) - { - // two passes algorithm: - // 1 - compute the number of coeffs per dest inner vector - // 2 - do the actual copy/eval - // Since each coeff of the rhs has to be evaluated twice, let's evaluate it if needed - typedef typename internal::nested::type OtherCopy; - typedef typename internal::remove_all::type _OtherCopy; - OtherCopy otherCopy(other.derived()); - - resize(other.rows(), other.cols()); - Eigen::Map > (m_outerIndex,outerSize()).setZero(); - // pass 1 - // FIXME the above copy could be merged with that pass - for (Index j=0; j::operator=(other.derived()); - } - } - - friend std::ostream & operator << (std::ostream & s, const SparseMatrix& m) - { - EIGEN_DBG_SPARSE( - s << "Nonzero entries:\n"; - for (Index i=0; i&>(m); - return s; - } - - /** Destructor */ - inline ~SparseMatrix() - { - delete[] m_outerIndex; - } - - /** Overloaded for performance */ - Scalar sum() const; - - public: - - /** \deprecated use setZero() and reserve() - * Initializes the filling process of \c *this. - * \param reserveSize approximate number of nonzeros - * Note that the matrix \c *this is zero-ed. - */ - EIGEN_DEPRECATED void startFill(Index reserveSize = 1000) - { - setZero(); - m_data.reserve(reserveSize); - } - - /** \deprecated use insert() - * Like fill() but with random inner coordinates. - */ - EIGEN_DEPRECATED Scalar& fillrand(Index row, Index col) - { - return insert(row,col); - } - - /** \deprecated use insert() - */ - EIGEN_DEPRECATED Scalar& fill(Index row, Index col) - { - const Index outer = IsRowMajor ? row : col; - const Index inner = IsRowMajor ? col : row; - - if (m_outerIndex[outer+1]==0) - { - // we start a new inner vector - Index i = outer; - while (i>=0 && m_outerIndex[i]==0) - { - m_outerIndex[i] = m_data.size(); - --i; - } - m_outerIndex[outer+1] = m_outerIndex[outer]; - } - else - { - eigen_assert(m_data.index(m_data.size()-1) -class SparseMatrix::InnerIterator -{ - public: - InnerIterator(const SparseMatrix& mat, Index outer) - : m_values(mat._valuePtr()), m_indices(mat._innerIndexPtr()), m_outer(outer), m_id(mat.m_outerIndex[outer]), m_end(mat.m_outerIndex[outer+1]) - {} - - inline InnerIterator& operator++() { m_id++; return *this; } - - inline const Scalar& value() const { return m_values[m_id]; } - inline Scalar& valueRef() { return const_cast(m_values[m_id]); } - - inline Index index() const { return m_indices[m_id]; } - inline Index outer() const { return m_outer; } - inline Index row() const { return IsRowMajor ? m_outer : index(); } - inline Index col() const { return IsRowMajor ? index() : m_outer; } - - inline operator bool() const { return (m_id < m_end); } - - protected: - const Scalar* m_values; - const Index* m_indices; - const Index m_outer; - Index m_id; - const Index m_end; -}; - -#endif // EIGEN_SPARSEMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSparseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSparseProduct.h deleted file mode 100644 index 19abcd1f8..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSparseProduct.h +++ /dev/null @@ -1,401 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SPARSESPARSEPRODUCT_H -#define EIGEN_SPARSESPARSEPRODUCT_H - -namespace internal { - -template -static void sparse_product_impl2(const Lhs& lhs, const Rhs& rhs, ResultType& res) -{ - typedef typename remove_all::type::Scalar Scalar; - typedef typename remove_all::type::Index Index; - - // make sure to call innerSize/outerSize since we fake the storage order. - Index rows = lhs.innerSize(); - Index cols = rhs.outerSize(); - eigen_assert(lhs.outerSize() == rhs.innerSize()); - - std::vector mask(rows,false); - Matrix values(rows); - Matrix indices(rows); - - // estimate the number of non zero entries - float ratioLhs = float(lhs.nonZeros())/(float(lhs.rows())*float(lhs.cols())); - float avgNnzPerRhsColumn = float(rhs.nonZeros())/float(cols); - float ratioRes = (std::min)(ratioLhs * avgNnzPerRhsColumn, 1.f); - -// int t200 = rows/(log2(200)*1.39); -// int t = (rows*100)/139; - - res.resize(rows, cols); - res.reserve(Index(ratioRes*rows*cols)); - // we compute each column of the result, one after the other - for (Index j=0; j use a quick sort - // otherwise => loop through the entire vector - // In order to avoid to perform an expensive log2 when the - // result is clearly very sparse we use a linear bound up to 200. -// if((nnz<200 && nnz1) std::sort(indices.data(),indices.data()+nnz); -// for(int k=0; k -static void sparse_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res) -{ -// return sparse_product_impl2(lhs,rhs,res); - - typedef typename remove_all::type::Scalar Scalar; - typedef typename remove_all::type::Index Index; - - // make sure to call innerSize/outerSize since we fake the storage order. - Index rows = lhs.innerSize(); - Index cols = rhs.outerSize(); - //int size = lhs.outerSize(); - eigen_assert(lhs.outerSize() == rhs.innerSize()); - - // allocate a temporary buffer - AmbiVector tempVector(rows); - - // estimate the number of non zero entries - float ratioLhs = float(lhs.nonZeros())/(float(lhs.rows())*float(lhs.cols())); - float avgNnzPerRhsColumn = float(rhs.nonZeros())/float(cols); - float ratioRes = (std::min)(ratioLhs * avgNnzPerRhsColumn, 1.f); - - // mimics a resizeByInnerOuter: - if(ResultType::IsRowMajor) - res.resize(cols, rows); - else - res.resize(rows, cols); - - res.reserve(Index(ratioRes*rows*cols)); - for (Index j=0; j::Iterator it(tempVector); it; ++it) - res.insertBackByOuterInner(j,it.index()) = it.value(); - } - res.finalize(); -} - -template::Flags&RowMajorBit, - int RhsStorageOrder = traits::Flags&RowMajorBit, - int ResStorageOrder = traits::Flags&RowMajorBit> -struct sparse_product_selector; - -template -struct sparse_product_selector -{ - typedef typename traits::type>::Scalar Scalar; - - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { -// std::cerr << __LINE__ << "\n"; - typename remove_all::type _res(res.rows(), res.cols()); - sparse_product_impl(lhs, rhs, _res); - res.swap(_res); - } -}; - -template -struct sparse_product_selector -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { -// std::cerr << __LINE__ << "\n"; - // we need a col-major matrix to hold the result - typedef SparseMatrix SparseTemporaryType; - SparseTemporaryType _res(res.rows(), res.cols()); - sparse_product_impl(lhs, rhs, _res); - res = _res; - } -}; - -template -struct sparse_product_selector -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { -// std::cerr << __LINE__ << "\n"; - // let's transpose the product to get a column x column product - typename remove_all::type _res(res.rows(), res.cols()); - sparse_product_impl(rhs, lhs, _res); - res.swap(_res); - } -}; - -template -struct sparse_product_selector -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { -// std::cerr << "here...\n"; - typedef SparseMatrix ColMajorMatrix; - ColMajorMatrix colLhs(lhs); - ColMajorMatrix colRhs(rhs); -// std::cerr << "more...\n"; - sparse_product_impl(colLhs, colRhs, res); -// std::cerr << "OK.\n"; - - // let's transpose the product to get a column x column product - -// typedef SparseMatrix SparseTemporaryType; -// SparseTemporaryType _res(res.cols(), res.rows()); -// sparse_product_impl(rhs, lhs, _res); -// res = _res.transpose(); - } -}; - -// NOTE the 2 others cases (col row *) must never occur since they are caught -// by ProductReturnType which transforms it to (col col *) by evaluating rhs. - -} // end namespace internal - -// sparse = sparse * sparse -template -template -inline Derived& SparseMatrixBase::operator=(const SparseSparseProduct& product) -{ -// std::cerr << "there..." << typeid(Lhs).name() << " " << typeid(Lhs).name() << " " << (Derived::Flags&&RowMajorBit) << "\n"; - internal::sparse_product_selector< - typename internal::remove_all::type, - typename internal::remove_all::type, - Derived>::run(product.lhs(),product.rhs(),derived()); - return derived(); -} - -namespace internal { - -template::Flags&RowMajorBit, - int RhsStorageOrder = traits::Flags&RowMajorBit, - int ResStorageOrder = traits::Flags&RowMajorBit> -struct sparse_product_selector2; - -template -struct sparse_product_selector2 -{ - typedef typename traits::type>::Scalar Scalar; - - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - sparse_product_impl2(lhs, rhs, res); - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - // prevent warnings until the code is fixed - EIGEN_UNUSED_VARIABLE(lhs); - EIGEN_UNUSED_VARIABLE(rhs); - EIGEN_UNUSED_VARIABLE(res); - -// typedef SparseMatrix RowMajorMatrix; -// RowMajorMatrix rhsRow = rhs; -// RowMajorMatrix resRow(res.rows(), res.cols()); -// sparse_product_impl2(rhsRow, lhs, resRow); -// res = resRow; - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix RowMajorMatrix; - RowMajorMatrix lhsRow = lhs; - RowMajorMatrix resRow(res.rows(), res.cols()); - sparse_product_impl2(rhs, lhsRow, resRow); - res = resRow; - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix RowMajorMatrix; - RowMajorMatrix resRow(res.rows(), res.cols()); - sparse_product_impl2(rhs, lhs, resRow); - res = resRow; - } -}; - - -template -struct sparse_product_selector2 -{ - typedef typename traits::type>::Scalar Scalar; - - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix ColMajorMatrix; - ColMajorMatrix resCol(res.rows(), res.cols()); - sparse_product_impl2(lhs, rhs, resCol); - res = resCol; - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix ColMajorMatrix; - ColMajorMatrix lhsCol = lhs; - ColMajorMatrix resCol(res.rows(), res.cols()); - sparse_product_impl2(lhsCol, rhs, resCol); - res = resCol; - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix ColMajorMatrix; - ColMajorMatrix rhsCol = rhs; - ColMajorMatrix resCol(res.rows(), res.cols()); - sparse_product_impl2(lhs, rhsCol, resCol); - res = resCol; - } -}; - -template -struct sparse_product_selector2 -{ - static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) - { - typedef SparseMatrix ColMajorMatrix; -// ColMajorMatrix lhsTr(lhs); -// ColMajorMatrix rhsTr(rhs); -// ColMajorMatrix aux(res.rows(), res.cols()); -// sparse_product_impl2(rhs, lhs, aux); -// // ColMajorMatrix aux2 = aux.transpose(); -// res = aux; - typedef SparseMatrix ColMajorMatrix; - ColMajorMatrix lhsCol(lhs); - ColMajorMatrix rhsCol(rhs); - ColMajorMatrix resCol(res.rows(), res.cols()); - sparse_product_impl2(lhsCol, rhsCol, resCol); - res = resCol; - } -}; - -} // end namespace internal - -template -template -inline void SparseMatrixBase::_experimentalNewProduct(const Lhs& lhs, const Rhs& rhs) -{ - //derived().resize(lhs.rows(), rhs.cols()); - internal::sparse_product_selector2< - typename internal::remove_all::type, - typename internal::remove_all::type, - Derived>::run(lhs,rhs,derived()); -} - -// sparse * sparse -template -template -inline const typename SparseSparseProductReturnType::Type -SparseMatrixBase::operator*(const SparseMatrixBase &other) const -{ - return typename SparseSparseProductReturnType::Type(derived(), other.derived()); -} - -#endif // EIGEN_SPARSESPARSEPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTriangularView.h b/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTriangularView.h deleted file mode 100644 index 319eaf066..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTriangularView.h +++ /dev/null @@ -1,100 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SPARSE_TRIANGULARVIEW_H -#define EIGEN_SPARSE_TRIANGULARVIEW_H - -namespace internal { - -template -struct traits > -: public traits -{}; - -} // namespace internal - -template class SparseTriangularView - : public SparseMatrixBase > -{ - enum { SkipFirst = (Mode==Lower && !(MatrixType::Flags&RowMajorBit)) - || (Mode==Upper && (MatrixType::Flags&RowMajorBit)) }; - public: - - EIGEN_SPARSE_PUBLIC_INTERFACE(SparseTriangularView) - - class InnerIterator; - - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } - - typedef typename internal::conditional::ret, - MatrixType, const MatrixType&>::type MatrixTypeNested; - - inline SparseTriangularView(const MatrixType& matrix) : m_matrix(matrix) {} - - /** \internal */ - inline const MatrixType& nestedExpression() const { return m_matrix; } - - template - typename internal::plain_matrix_type_column_major::type - solve(const MatrixBase& other) const; - - template void solveInPlace(MatrixBase& other) const; - template void solveInPlace(SparseMatrixBase& other) const; - - protected: - MatrixTypeNested m_matrix; -}; - -template -class SparseTriangularView::InnerIterator : public MatrixType::InnerIterator -{ - typedef typename MatrixType::InnerIterator Base; - public: - - EIGEN_STRONG_INLINE InnerIterator(const SparseTriangularView& view, Index outer) - : Base(view.nestedExpression(), outer) - { - if(SkipFirst) - while((*this) && this->index()index() <= this->outer()); - } -}; - -template -template -inline const SparseTriangularView -SparseMatrixBase::triangularView() const -{ - return derived(); -} - -#endif // EIGEN_SPARSE_TRIANGULARVIEW_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/CMakeLists.txt new file mode 100644 index 000000000..375a59d7a --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_SparseCholesky_SRCS "*.h") + +INSTALL(FILES + ${Eigen_SparseCholesky_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/SparseCholesky COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h new file mode 100644 index 000000000..e5d98933f --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h @@ -0,0 +1,886 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2010 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +/* + +NOTE: the _symbolic, and _numeric functions has been adapted from + the LDL library: + +LDL Copyright (c) 2005 by Timothy A. Davis. All Rights Reserved. + +LDL License: + + Your use or distribution of LDL or any modified version of + LDL implies that you agree to this License. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 + USA + + Permission is hereby granted to use or copy this program under the + terms of the GNU LGPL, provided that the Copyright, this License, + and the Availability of the original version is retained on all copies. + User documentation of any code that uses this code or any modified + version of this code must cite the Copyright, this License, the + Availability note, and "Used by permission." Permission to modify + the code and to distribute modified code is granted, provided the + Copyright, this License, and the Availability note are retained, + and a notice that the code was modified is included. + */ + +#ifndef EIGEN_SIMPLICIAL_CHOLESKY_H +#define EIGEN_SIMPLICIAL_CHOLESKY_H + +namespace Eigen { + +enum SimplicialCholeskyMode { + SimplicialCholeskyLLT, + SimplicialCholeskyLDLT +}; + +/** \ingroup SparseCholesky_Module + * \brief A direct sparse Cholesky factorizations + * + * These classes provide LL^T and LDL^T Cholesky factorizations of sparse matrices that are + * selfadjoint and positive definite. The factorization allows for solving A.X = B where + * X and B can be either dense or sparse. + * + * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization + * such that the factorized matrix is P A P^-1. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + */ +template +class SimplicialCholeskyBase : internal::noncopyable +{ + public: + typedef typename internal::traits::MatrixType MatrixType; + enum { UpLo = internal::traits::UpLo }; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef Matrix VectorType; + + public: + + /** Default constructor */ + SimplicialCholeskyBase() + : m_info(Success), m_isInitialized(false), m_shiftOffset(0), m_shiftScale(1) + {} + + SimplicialCholeskyBase(const MatrixType& matrix) + : m_info(Success), m_isInitialized(false), m_shiftOffset(0), m_shiftScale(1) + { + derived().compute(matrix); + } + + ~SimplicialCholeskyBase() + { + } + + Derived& derived() { return *static_cast(this); } + const Derived& derived() const { return *static_cast(this); } + + inline Index cols() const { return m_matrix.cols(); } + inline Index rows() const { return m_matrix.rows(); } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "Decomposition is not initialized."); + return m_info; + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "Simplicial LLT or LDLT is not initialized."); + eigen_assert(rows()==b.rows() + && "SimplicialCholeskyBase::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::sparse_solve_retval + solve(const SparseMatrixBase& b) const + { + eigen_assert(m_isInitialized && "Simplicial LLT or LDLT is not initialized."); + eigen_assert(rows()==b.rows() + && "SimplicialCholesky::solve(): invalid number of rows of the right hand side matrix b"); + return internal::sparse_solve_retval(*this, b.derived()); + } + + /** \returns the permutation P + * \sa permutationPinv() */ + const PermutationMatrix& permutationP() const + { return m_P; } + + /** \returns the inverse P^-1 of the permutation P + * \sa permutationP() */ + const PermutationMatrix& permutationPinv() const + { return m_Pinv; } + + /** Sets the shift parameters that will be used to adjust the diagonal coefficients during the numerical factorization. + * + * During the numerical factorization, the diagonal coefficients are transformed by the following linear model:\n + * \c d_ii = \a offset + \a scale * \c d_ii + * + * The default is the identity transformation with \a offset=0, and \a scale=1. + * + * \returns a reference to \c *this. + */ + Derived& setShift(const RealScalar& offset, const RealScalar& scale = 1) + { + m_shiftOffset = offset; + m_shiftScale = scale; + return derived(); + } + +#ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal */ + template + void dumpMemory(Stream& s) + { + int total = 0; + s << " L: " << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << "Mb" << "\n"; + s << " diag: " << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << "Mb" << "\n"; + s << " tree: " << ((total+=m_parent.size() * sizeof(int)) >> 20) << "Mb" << "\n"; + s << " nonzeros: " << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << "Mb" << "\n"; + s << " perm: " << ((total+=m_P.size() * sizeof(int)) >> 20) << "Mb" << "\n"; + s << " perm^-1: " << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << "Mb" << "\n"; + s << " TOTAL: " << (total>> 20) << "Mb" << "\n"; + } + + /** \internal */ + template + void _solve(const MatrixBase &b, MatrixBase &dest) const + { + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + eigen_assert(m_matrix.rows()==b.rows()); + + if(m_info!=Success) + return; + + if(m_P.size()>0) + dest = m_P * b; + else + dest = b; + + if(m_matrix.nonZeros()>0) // otherwise L==I + derived().matrixL().solveInPlace(dest); + + if(m_diag.size()>0) + dest = m_diag.asDiagonal().inverse() * dest; + + if (m_matrix.nonZeros()>0) // otherwise U==I + derived().matrixU().solveInPlace(dest); + + if(m_P.size()>0) + dest = m_Pinv * dest; + } + + /** \internal */ + template + void _solve_sparse(const Rhs& b, SparseMatrix &dest) const + { + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + eigen_assert(m_matrix.rows()==b.rows()); + + // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix. + static const int NbColsAtOnce = 4; + int rhsCols = b.cols(); + int size = b.rows(); + Eigen::Matrix tmp(size,rhsCols); + for(int k=0; k(rhsCols-k, NbColsAtOnce); + tmp.leftCols(actualCols) = b.middleCols(k,actualCols); + tmp.leftCols(actualCols) = derived().solve(tmp.leftCols(actualCols)); + dest.middleCols(k,actualCols) = tmp.leftCols(actualCols).sparseView(); + } + } + +#endif // EIGEN_PARSED_BY_DOXYGEN + + protected: + + /** Computes the sparse Cholesky decomposition of \a matrix */ + template + void compute(const MatrixType& matrix) + { + eigen_assert(matrix.rows()==matrix.cols()); + Index size = matrix.cols(); + CholMatrixType ap(size,size); + ordering(matrix, ap); + analyzePattern_preordered(ap, DoLDLT); + factorize_preordered(ap); + } + + template + void factorize(const MatrixType& a) + { + eigen_assert(a.rows()==a.cols()); + int size = a.cols(); + CholMatrixType ap(size,size); + ap.template selfadjointView() = a.template selfadjointView().twistedBy(m_P); + factorize_preordered(ap); + } + + template + void factorize_preordered(const CholMatrixType& a); + + void analyzePattern(const MatrixType& a, bool doLDLT) + { + eigen_assert(a.rows()==a.cols()); + int size = a.cols(); + CholMatrixType ap(size,size); + ordering(a, ap); + analyzePattern_preordered(ap,doLDLT); + } + void analyzePattern_preordered(const CholMatrixType& a, bool doLDLT); + + void ordering(const MatrixType& a, CholMatrixType& ap); + + /** keeps off-diagonal entries; drops diagonal entries */ + struct keep_diag { + inline bool operator() (const Index& row, const Index& col, const Scalar&) const + { + return row!=col; + } + }; + + mutable ComputationInfo m_info; + bool m_isInitialized; + bool m_factorizationIsOk; + bool m_analysisIsOk; + + CholMatrixType m_matrix; + VectorType m_diag; // the diagonal coefficients (LDLT mode) + VectorXi m_parent; // elimination tree + VectorXi m_nonZerosPerCol; + PermutationMatrix m_P; // the permutation + PermutationMatrix m_Pinv; // the inverse permutation + + RealScalar m_shiftOffset; + RealScalar m_shiftScale; +}; + +template class SimplicialLLT; +template class SimplicialLDLT; +template class SimplicialCholesky; + +namespace internal { + +template struct traits > +{ + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef SparseTriangularView MatrixL; + typedef SparseTriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m; } + static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } +}; + +template struct traits > +{ + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef SparseTriangularView MatrixL; + typedef SparseTriangularView MatrixU; + static inline MatrixL getL(const MatrixType& m) { return m; } + static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } +}; + +template struct traits > +{ + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; +}; + +} + +/** \ingroup SparseCholesky_Module + * \class SimplicialLLT + * \brief A direct sparse LLT Cholesky factorizations + * + * This class provides a LL^T Cholesky factorizations of sparse matrices that are + * selfadjoint and positive definite. The factorization allows for solving A.X = B where + * X and B can be either dense or sparse. + * + * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization + * such that the factorized matrix is P A P^-1. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * \sa class SimplicialLDLT + */ +template + class SimplicialLLT : public SimplicialCholeskyBase > +{ +public: + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; + typedef SimplicialCholeskyBase Base; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef Matrix VectorType; + typedef internal::traits Traits; + typedef typename Traits::MatrixL MatrixL; + typedef typename Traits::MatrixU MatrixU; +public: + /** Default constructor */ + SimplicialLLT() : Base() {} + /** Constructs and performs the LLT factorization of \a matrix */ + SimplicialLLT(const MatrixType& matrix) + : Base(matrix) {} + + /** \returns an expression of the factor L */ + inline const MatrixL matrixL() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized"); + return Traits::getL(Base::m_matrix); + } + + /** \returns an expression of the factor U (= L^*) */ + inline const MatrixU matrixU() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized"); + return Traits::getU(Base::m_matrix); + } + + /** Computes the sparse Cholesky decomposition of \a matrix */ + SimplicialLLT& compute(const MatrixType& matrix) + { + Base::template compute(matrix); + return *this; + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& a) + { + Base::analyzePattern(a, false); + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + void factorize(const MatrixType& a) + { + Base::template factorize(a); + } + + /** \returns the determinant of the underlying matrix from the current factorization */ + Scalar determinant() const + { + Scalar detL = Base::m_matrix.diagonal().prod(); + return internal::abs2(detL); + } +}; + +/** \ingroup SparseCholesky_Module + * \class SimplicialLDLT + * \brief A direct sparse LDLT Cholesky factorizations without square root. + * + * This class provides a LDL^T Cholesky factorizations without square root of sparse matrices that are + * selfadjoint and positive definite. The factorization allows for solving A.X = B where + * X and B can be either dense or sparse. + * + * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization + * such that the factorized matrix is P A P^-1. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower + * or Upper. Default is Lower. + * + * \sa class SimplicialLLT + */ +template + class SimplicialLDLT : public SimplicialCholeskyBase > +{ +public: + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; + typedef SimplicialCholeskyBase Base; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef Matrix VectorType; + typedef internal::traits Traits; + typedef typename Traits::MatrixL MatrixL; + typedef typename Traits::MatrixU MatrixU; +public: + /** Default constructor */ + SimplicialLDLT() : Base() {} + + /** Constructs and performs the LLT factorization of \a matrix */ + SimplicialLDLT(const MatrixType& matrix) + : Base(matrix) {} + + /** \returns a vector expression of the diagonal D */ + inline const VectorType vectorD() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized"); + return Base::m_diag; + } + /** \returns an expression of the factor L */ + inline const MatrixL matrixL() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized"); + return Traits::getL(Base::m_matrix); + } + + /** \returns an expression of the factor U (= L^*) */ + inline const MatrixU matrixU() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized"); + return Traits::getU(Base::m_matrix); + } + + /** Computes the sparse Cholesky decomposition of \a matrix */ + SimplicialLDLT& compute(const MatrixType& matrix) + { + Base::template compute(matrix); + return *this; + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& a) + { + Base::analyzePattern(a, true); + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + void factorize(const MatrixType& a) + { + Base::template factorize(a); + } + + /** \returns the determinant of the underlying matrix from the current factorization */ + Scalar determinant() const + { + return Base::m_diag.prod(); + } +}; + +/** \deprecated use SimplicialLDLT or class SimplicialLLT + * \ingroup SparseCholesky_Module + * \class SimplicialCholesky + * + * \sa class SimplicialLDLT, class SimplicialLLT + */ +template + class SimplicialCholesky : public SimplicialCholeskyBase > +{ +public: + typedef _MatrixType MatrixType; + enum { UpLo = _UpLo }; + typedef SimplicialCholeskyBase Base; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef SparseMatrix CholMatrixType; + typedef Matrix VectorType; + typedef internal::traits Traits; + typedef internal::traits > LDLTTraits; + typedef internal::traits > LLTTraits; + public: + SimplicialCholesky() : Base(), m_LDLT(true) {} + + SimplicialCholesky(const MatrixType& matrix) + : Base(), m_LDLT(true) + { + compute(matrix); + } + + SimplicialCholesky& setMode(SimplicialCholeskyMode mode) + { + switch(mode) + { + case SimplicialCholeskyLLT: + m_LDLT = false; + break; + case SimplicialCholeskyLDLT: + m_LDLT = true; + break; + default: + break; + } + + return *this; + } + + inline const VectorType vectorD() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized"); + return Base::m_diag; + } + inline const CholMatrixType rawMatrix() const { + eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized"); + return Base::m_matrix; + } + + /** Computes the sparse Cholesky decomposition of \a matrix */ + SimplicialCholesky& compute(const MatrixType& matrix) + { + if(m_LDLT) + Base::template compute(matrix); + else + Base::template compute(matrix); + return *this; + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& a) + { + Base::analyzePattern(a, m_LDLT); + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + void factorize(const MatrixType& a) + { + if(m_LDLT) + Base::template factorize(a); + else + Base::template factorize(a); + } + + /** \internal */ + template + void _solve(const MatrixBase &b, MatrixBase &dest) const + { + eigen_assert(Base::m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + eigen_assert(Base::m_matrix.rows()==b.rows()); + + if(Base::m_info!=Success) + return; + + if(Base::m_P.size()>0) + dest = Base::m_P * b; + else + dest = b; + + if(Base::m_matrix.nonZeros()>0) // otherwise L==I + { + if(m_LDLT) + LDLTTraits::getL(Base::m_matrix).solveInPlace(dest); + else + LLTTraits::getL(Base::m_matrix).solveInPlace(dest); + } + + if(Base::m_diag.size()>0) + dest = Base::m_diag.asDiagonal().inverse() * dest; + + if (Base::m_matrix.nonZeros()>0) // otherwise I==I + { + if(m_LDLT) + LDLTTraits::getU(Base::m_matrix).solveInPlace(dest); + else + LLTTraits::getU(Base::m_matrix).solveInPlace(dest); + } + + if(Base::m_P.size()>0) + dest = Base::m_Pinv * dest; + } + + Scalar determinant() const + { + if(m_LDLT) + { + return Base::m_diag.prod(); + } + else + { + Scalar detL = Diagonal(Base::m_matrix).prod(); + return internal::abs2(detL); + } + } + + protected: + bool m_LDLT; +}; + +template +void SimplicialCholeskyBase::ordering(const MatrixType& a, CholMatrixType& ap) +{ + eigen_assert(a.rows()==a.cols()); + const Index size = a.rows(); + // TODO allows to configure the permutation + // Note that amd compute the inverse permutation + { + CholMatrixType C; + C = a.template selfadjointView(); + // remove diagonal entries: + // seems not to be needed + // C.prune(keep_diag()); + internal::minimum_degree_ordering(C, m_Pinv); + } + + if(m_Pinv.size()>0) + m_P = m_Pinv.inverse(); + else + m_P.resize(0); + + ap.resize(size,size); + ap.template selfadjointView() = a.template selfadjointView().twistedBy(m_P); +} + +template +void SimplicialCholeskyBase::analyzePattern_preordered(const CholMatrixType& ap, bool doLDLT) +{ + const Index size = ap.rows(); + m_matrix.resize(size, size); + m_parent.resize(size); + m_nonZerosPerCol.resize(size); + + ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); + + for(Index k = 0; k < size; ++k) + { + /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */ + m_parent[k] = -1; /* parent of k is not yet known */ + tags[k] = k; /* mark node k as visited */ + m_nonZerosPerCol[k] = 0; /* count of nonzeros in column k of L */ + for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it) + { + Index i = it.index(); + if(i < k) + { + /* follow path from i to root of etree, stop at flagged node */ + for(; tags[i] != k; i = m_parent[i]) + { + /* find parent of i if not yet determined */ + if (m_parent[i] == -1) + m_parent[i] = k; + m_nonZerosPerCol[i]++; /* L (k,i) is nonzero */ + tags[i] = k; /* mark i as visited */ + } + } + } + } + + /* construct Lp index array from m_nonZerosPerCol column counts */ + Index* Lp = m_matrix.outerIndexPtr(); + Lp[0] = 0; + for(Index k = 0; k < size; ++k) + Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (doLDLT ? 0 : 1); + + m_matrix.resizeNonZeros(Lp[size]); + + m_isInitialized = true; + m_info = Success; + m_analysisIsOk = true; + m_factorizationIsOk = false; +} + + +template +template +void SimplicialCholeskyBase::factorize_preordered(const CholMatrixType& ap) +{ + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + eigen_assert(ap.rows()==ap.cols()); + const Index size = ap.rows(); + eigen_assert(m_parent.size()==size); + eigen_assert(m_nonZerosPerCol.size()==size); + + const Index* Lp = m_matrix.outerIndexPtr(); + Index* Li = m_matrix.innerIndexPtr(); + Scalar* Lx = m_matrix.valuePtr(); + + ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0); + ei_declare_aligned_stack_constructed_variable(Index, pattern, size, 0); + ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); + + bool ok = true; + m_diag.resize(DoLDLT ? size : 0); + + for(Index k = 0; k < size; ++k) + { + // compute nonzero pattern of kth row of L, in topological order + y[k] = 0.0; // Y(0:k) is now all zero + Index top = size; // stack for pattern is empty + tags[k] = k; // mark node k as visited + m_nonZerosPerCol[k] = 0; // count of nonzeros in column k of L + for(typename MatrixType::InnerIterator it(ap,k); it; ++it) + { + Index i = it.index(); + if(i <= k) + { + y[i] += internal::conj(it.value()); /* scatter A(i,k) into Y (sum duplicates) */ + Index len; + for(len = 0; tags[i] != k; i = m_parent[i]) + { + pattern[len++] = i; /* L(k,i) is nonzero */ + tags[i] = k; /* mark i as visited */ + } + while(len > 0) + pattern[--top] = pattern[--len]; + } + } + + /* compute numerical values kth row of L (a sparse triangular solve) */ + + RealScalar d = internal::real(y[k]) * m_shiftScale + m_shiftOffset; // get D(k,k), apply the shift function, and clear Y(k) + y[k] = 0.0; + for(; top < size; ++top) + { + Index i = pattern[top]; /* pattern[top:n-1] is pattern of L(:,k) */ + Scalar yi = y[i]; /* get and clear Y(i) */ + y[i] = 0.0; + + /* the nonzero entry L(k,i) */ + Scalar l_ki; + if(DoLDLT) + l_ki = yi / m_diag[i]; + else + yi = l_ki = yi / Lx[Lp[i]]; + + Index p2 = Lp[i] + m_nonZerosPerCol[i]; + Index p; + for(p = Lp[i] + (DoLDLT ? 0 : 1); p < p2; ++p) + y[Li[p]] -= internal::conj(Lx[p]) * yi; + d -= internal::real(l_ki * internal::conj(yi)); + Li[p] = k; /* store L(k,i) in column form of L */ + Lx[p] = l_ki; + ++m_nonZerosPerCol[i]; /* increment count of nonzeros in col i */ + } + if(DoLDLT) + { + m_diag[k] = d; + if(d == RealScalar(0)) + { + ok = false; /* failure, D(k,k) is zero */ + break; + } + } + else + { + Index p = Lp[k] + m_nonZerosPerCol[k]++; + Li[p] = k ; /* store L(k,k) = sqrt (d) in column k */ + if(d <= RealScalar(0)) { + ok = false; /* failure, matrix is not positive definite */ + break; + } + Lx[p] = internal::sqrt(d) ; + } + } + + m_info = ok ? Success : NumericalIssue; + m_factorizationIsOk = true; +} + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef SimplicialCholeskyBase Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve(rhs(),dst); + } +}; + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef SimplicialCholeskyBase Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve_sparse(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_SIMPLICIAL_CHOLESKY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/AmbiVector.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/AmbiVector.h similarity index 98% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/AmbiVector.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/AmbiVector.h index 2ea8ba309..8ec63107a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/AmbiVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/AmbiVector.h @@ -25,6 +25,10 @@ #ifndef EIGEN_AMBIVECTOR_H #define EIGEN_AMBIVECTOR_H +namespace Eigen { + +namespace internal { + /** \internal * Hybrid sparse/dense vector class designed for intensive read-write operations. * @@ -299,7 +303,7 @@ class AmbiVector<_Scalar,_Index>::Iterator * In practice, all coefficients having a magnitude smaller than \a epsilon * are skipped. */ - Iterator(const AmbiVector& vec, RealScalar epsilon = RealScalar(0.1)*NumTraits::dummy_precision()) + Iterator(const AmbiVector& vec, RealScalar epsilon = 0) : m_vector(vec) { m_epsilon = epsilon; @@ -315,7 +319,7 @@ class AmbiVector<_Scalar,_Index>::Iterator { ListEl* EIGEN_RESTRICT llElements = reinterpret_cast(m_vector.m_buffer); m_currentEl = m_vector.m_llStart; - while (m_currentEl>=0 && internal::abs(llElements[m_currentEl].value)=0 && internal::abs(llElements[m_currentEl].value)<=m_epsilon) m_currentEl = llElements[m_currentEl].next; if (m_currentEl<0) { @@ -375,5 +379,8 @@ class AmbiVector<_Scalar,_Index>::Iterator bool m_isDense; // mode of the vector }; +} // end namespace internal + +} // end namespace Eigen #endif // EIGEN_AMBIVECTOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CMakeLists.txt new file mode 100644 index 000000000..d860452a6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_SparseCore_SRCS "*.h") + +INSTALL(FILES + ${Eigen_SparseCore_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/SparseCore COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CompressedStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h similarity index 95% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/CompressedStorage.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h index b3bde272e..fa2bfd763 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CompressedStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h @@ -25,7 +25,12 @@ #ifndef EIGEN_COMPRESSED_STORAGE_H #define EIGEN_COMPRESSED_STORAGE_H -/** Stores a sparse set of values as a list of values and a list of indices. +namespace Eigen { + +namespace internal { + +/** \internal + * Stores a sparse set of values as a list of values and a list of indices. * */ template @@ -218,8 +223,8 @@ class CompressedStorage Index* newIndices = new Index[size]; size_t copySize = (std::min)(size, m_size); // copy - memcpy(newValues, m_values, copySize * sizeof(Scalar)); - memcpy(newIndices, m_indices, copySize * sizeof(Index)); + internal::smart_copy(m_values, m_values+copySize, newValues); + internal::smart_copy(m_indices, m_indices+copySize, newIndices); // delete old stuff delete[] m_values; delete[] m_indices; @@ -236,4 +241,8 @@ class CompressedStorage }; +} // end namespace internal + +} // end namespace Eigen + #endif // EIGEN_COMPRESSED_STORAGE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h new file mode 100644 index 000000000..0fb4c1c97 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h @@ -0,0 +1,260 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H +#define EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H + +namespace Eigen { + +namespace internal { + +template +static void conservative_sparse_sparse_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res) +{ + typedef typename remove_all::type::Scalar Scalar; + typedef typename remove_all::type::Index Index; + + // make sure to call innerSize/outerSize since we fake the storage order. + Index rows = lhs.innerSize(); + Index cols = rhs.outerSize(); + eigen_assert(lhs.outerSize() == rhs.innerSize()); + + std::vector mask(rows,false); + Matrix values(rows); + Matrix indices(rows); + + // estimate the number of non zero entries + // given a rhs column containing Y non zeros, we assume that the respective Y columns + // of the lhs differs in average of one non zeros, thus the number of non zeros for + // the product of a rhs column with the lhs is X+Y where X is the average number of non zero + // per column of the lhs. + // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs) + Index estimated_nnz_prod = lhs.nonZeros() + rhs.nonZeros(); + + res.setZero(); + res.reserve(Index(estimated_nnz_prod)); + // we compute each column of the result, one after the other + for (Index j=0; j use a quick sort + // otherwise => loop through the entire vector + // In order to avoid to perform an expensive log2 when the + // result is clearly very sparse we use a linear bound up to 200. + //if((nnz<200 && nnz1) std::sort(indices.data(),indices.data()+nnz); + for(int k=0; k::Flags&RowMajorBit, + int RhsStorageOrder = traits::Flags&RowMajorBit, + int ResStorageOrder = traits::Flags&RowMajorBit> +struct conservative_sparse_sparse_product_selector; + +template +struct conservative_sparse_sparse_product_selector +{ + typedef typename remove_all::type LhsCleaned; + typedef typename LhsCleaned::Scalar Scalar; + + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix RowMajorMatrix; + typedef SparseMatrix ColMajorMatrix; + ColMajorMatrix resCol(lhs.rows(),rhs.cols()); + internal::conservative_sparse_sparse_product_impl(lhs, rhs, resCol); + // sort the non zeros: + RowMajorMatrix resRow(resCol); + res = resRow; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix RowMajorMatrix; + RowMajorMatrix rhsRow = rhs; + RowMajorMatrix resRow(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(rhsRow, lhs, resRow); + res = resRow; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix RowMajorMatrix; + RowMajorMatrix lhsRow = lhs; + RowMajorMatrix resRow(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(rhs, lhsRow, resRow); + res = resRow; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix RowMajorMatrix; + RowMajorMatrix resRow(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(rhs, lhs, resRow); + res = resRow; + } +}; + + +template +struct conservative_sparse_sparse_product_selector +{ + typedef typename traits::type>::Scalar Scalar; + + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix ColMajorMatrix; + ColMajorMatrix resCol(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(lhs, rhs, resCol); + res = resCol; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix ColMajorMatrix; + ColMajorMatrix lhsCol = lhs; + ColMajorMatrix resCol(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(lhsCol, rhs, resCol); + res = resCol; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix ColMajorMatrix; + ColMajorMatrix rhsCol = rhs; + ColMajorMatrix resCol(lhs.rows(), rhs.cols()); + internal::conservative_sparse_sparse_product_impl(lhs, rhsCol, resCol); + res = resCol; + } +}; + +template +struct conservative_sparse_sparse_product_selector +{ + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res) + { + typedef SparseMatrix RowMajorMatrix; + typedef SparseMatrix ColMajorMatrix; + RowMajorMatrix resRow(lhs.rows(),rhs.cols()); + internal::conservative_sparse_sparse_product_impl(rhs, lhs, resRow); + // sort the non zeros: + ColMajorMatrix resCol(resRow); + res = resCol; + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CoreIterators.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CoreIterators.h similarity index 96% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/CoreIterators.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CoreIterators.h index b4beaeee6..ea51e9231 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/CoreIterators.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CoreIterators.h @@ -25,10 +25,13 @@ #ifndef EIGEN_COREITERATORS_H #define EIGEN_COREITERATORS_H +namespace Eigen { + /* This file contains the respective InnerIterator definition of the expressions defined in Eigen/Core */ -/** \class InnerIterator +/** \ingroup SparseCore_Module + * \class InnerIterator * \brief An InnerIterator allows to loop over the element of a sparse (or dense) matrix or expression * * todo @@ -68,4 +71,6 @@ template class DenseBase::InnerIterator const Index m_end; }; +} // end namespace Eigen + #endif // EIGEN_COREITERATORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/MappedSparseMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/MappedSparseMatrix.h similarity index 74% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/MappedSparseMatrix.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/MappedSparseMatrix.h index 31a431fb2..fc7f9d143 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/MappedSparseMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/MappedSparseMatrix.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MAPPED_SPARSEMATRIX_H #define EIGEN_MAPPED_SPARSEMATRIX_H +namespace Eigen { + /** \class MappedSparseMatrix * * \brief Sparse matrix @@ -46,9 +48,9 @@ class MappedSparseMatrix { public: EIGEN_SPARSE_PUBLIC_INTERFACE(MappedSparseMatrix) + enum { IsRowMajor = Base::IsRowMajor }; protected: - enum { IsRowMajor = Base::IsRowMajor }; Index m_outerSize; Index m_innerSize; @@ -63,18 +65,17 @@ class MappedSparseMatrix inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; } inline Index innerSize() const { return m_innerSize; } inline Index outerSize() const { return m_outerSize; } - inline Index innerNonZeros(Index j) const { return m_outerIndex[j+1]-m_outerIndex[j]; } //---------------------------------------- // direct access interface - inline const Scalar* _valuePtr() const { return m_values; } - inline Scalar* _valuePtr() { return m_values; } + inline const Scalar* valuePtr() const { return m_values; } + inline Scalar* valuePtr() { return m_values; } - inline const Index* _innerIndexPtr() const { return m_innerIndices; } - inline Index* _innerIndexPtr() { return m_innerIndices; } + inline const Index* innerIndexPtr() const { return m_innerIndices; } + inline Index* innerIndexPtr() { return m_innerIndices; } - inline const Index* _outerIndexPtr() const { return m_outerIndex; } - inline Index* _outerIndexPtr() { return m_outerIndex; } + inline const Index* outerIndexPtr() const { return m_outerIndex; } + inline Index* outerIndexPtr() { return m_outerIndex; } //---------------------------------------- inline Scalar coeff(Index row, Index col) const @@ -112,6 +113,7 @@ class MappedSparseMatrix } class InnerIterator; + class ReverseInnerIterator; /** \returns the number of non zero coefficients */ inline Index nonZeros() const { return m_nnz; } @@ -132,23 +134,17 @@ class MappedSparseMatrix::InnerIterator InnerIterator(const MappedSparseMatrix& mat, Index outer) : m_matrix(mat), m_outer(outer), - m_id(mat._outerIndexPtr()[outer]), + m_id(mat.outerIndexPtr()[outer]), m_start(m_id), - m_end(mat._outerIndexPtr()[outer+1]) - {} - - template - InnerIterator(const Flagged& mat, Index outer) - : m_matrix(mat._expression()), m_id(m_matrix._outerIndexPtr()[outer]), - m_start(m_id), m_end(m_matrix._outerIndexPtr()[outer+1]) + m_end(mat.outerIndexPtr()[outer+1]) {} inline InnerIterator& operator++() { m_id++; return *this; } - inline Scalar value() const { return m_matrix._valuePtr()[m_id]; } - inline Scalar& valueRef() { return const_cast(m_matrix._valuePtr()[m_id]); } + inline Scalar value() const { return m_matrix.valuePtr()[m_id]; } + inline Scalar& valueRef() { return const_cast(m_matrix.valuePtr()[m_id]); } - inline Index index() const { return m_matrix._innerIndexPtr()[m_id]; } + inline Index index() const { return m_matrix.innerIndexPtr()[m_id]; } inline Index row() const { return IsRowMajor ? m_outer : index(); } inline Index col() const { return IsRowMajor ? index() : m_outer; } @@ -162,4 +158,37 @@ class MappedSparseMatrix::InnerIterator const Index m_end; }; +template +class MappedSparseMatrix::ReverseInnerIterator +{ + public: + ReverseInnerIterator(const MappedSparseMatrix& mat, Index outer) + : m_matrix(mat), + m_outer(outer), + m_id(mat.outerIndexPtr()[outer+1]), + m_start(mat.outerIndexPtr()[outer]), + m_end(m_id) + {} + + inline ReverseInnerIterator& operator--() { m_id--; return *this; } + + inline Scalar value() const { return m_matrix.valuePtr()[m_id-1]; } + inline Scalar& valueRef() { return const_cast(m_matrix.valuePtr()[m_id-1]); } + + inline Index index() const { return m_matrix.innerIndexPtr()[m_id-1]; } + inline Index row() const { return IsRowMajor ? m_outer : index(); } + inline Index col() const { return IsRowMajor ? index() : m_outer; } + + inline operator bool() const { return (m_id <= m_end) && (m_id>m_start); } + + protected: + const MappedSparseMatrix& m_matrix; + const Index m_outer; + Index m_id; + const Index m_start; + const Index m_end; +}; + +} // end namespace Eigen + #endif // EIGEN_MAPPED_SPARSEMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseAssign.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseAssign.h similarity index 100% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseAssign.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseAssign.h diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseBlock.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h similarity index 71% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseBlock.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h index 8079c9999..189538f39 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseBlock.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSE_BLOCK_H #define EIGEN_SPARSE_BLOCK_H +namespace Eigen { + namespace internal { template struct traits > @@ -65,6 +67,17 @@ class SparseInnerVectorSet : internal::no_assignment_operator, protected: Index m_outer; }; + class ReverseInnerIterator: public MatrixType::ReverseInnerIterator + { + public: + inline ReverseInnerIterator(const SparseInnerVectorSet& xpr, Index outer) + : MatrixType::ReverseInnerIterator(xpr.m_matrix, xpr.m_outerStart + outer), m_outer(outer) + {} + inline Index row() const { return IsRowMajor ? m_outer : this->index(); } + inline Index col() const { return IsRowMajor ? this->index() : m_outer; } + protected: + Index m_outer; + }; inline SparseInnerVectorSet(const MatrixType& matrix, Index outerStart, Index outerSize) : m_matrix(matrix), m_outerStart(outerStart), m_outerSize(outerSize) @@ -101,15 +114,16 @@ class SparseInnerVectorSet : internal::no_assignment_operator, const internal::variable_if_dynamic m_outerSize; }; + /*************************************************************************** -* specialisation for DynamicSparseMatrix +* specialisation for SparseMatrix ***************************************************************************/ -template -class SparseInnerVectorSet, Size> - : public SparseMatrixBase, Size> > +template +class SparseInnerVectorSet, Size> + : public SparseMatrixBase, Size> > { - typedef DynamicSparseMatrix<_Scalar, _Options> MatrixType; + typedef SparseMatrix<_Scalar, _Options, _Index> MatrixType; public: enum { IsRowMajor = internal::traits::IsRowMajor }; @@ -126,98 +140,11 @@ class SparseInnerVectorSet, Size> protected: Index m_outer; }; - - inline SparseInnerVectorSet(const MatrixType& matrix, Index outerStart, Index outerSize) - : m_matrix(matrix), m_outerStart(outerStart), m_outerSize(outerSize) - { - eigen_assert( (outerStart>=0) && ((outerStart+outerSize)<=matrix.outerSize()) ); - } - - inline SparseInnerVectorSet(const MatrixType& matrix, Index outer) - : m_matrix(matrix), m_outerStart(outer), m_outerSize(Size) - { - eigen_assert(Size!=Dynamic); - eigen_assert( (outer>=0) && (outer - inline SparseInnerVectorSet& operator=(const SparseMatrixBase& other) - { - if (IsRowMajor != ((OtherDerived::Flags&RowMajorBit)==RowMajorBit)) - { - // need to transpose => perform a block evaluation followed by a big swap - DynamicSparseMatrix aux(other); - *this = aux.markAsRValue(); - } - else - { - // evaluate/copy vector per vector - for (Index j=0; j aux(other.innerVector(j)); - m_matrix.const_cast_derived()._data()[m_outerStart+j].swap(aux._data()); - } - } - return *this; - } - - inline SparseInnerVectorSet& operator=(const SparseInnerVectorSet& other) - { - return operator=(other); - } - - Index nonZeros() const - { - Index count = 0; - for (Index j=0; j0); - return m_matrix.data()[m_outerStart].vale(m_matrix.data()[m_outerStart].size()-1); - } - -// template -// inline SparseInnerVectorSet& operator=(const SparseMatrixBase& other) -// { -// return *this; -// } - - EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); } - - protected: - - const typename MatrixType::Nested m_matrix; - Index m_outerStart; - const internal::variable_if_dynamic m_outerSize; - -}; - - -/*************************************************************************** -* specialisation for SparseMatrix -***************************************************************************/ - -template -class SparseInnerVectorSet, Size> - : public SparseMatrixBase, Size> > -{ - typedef SparseMatrix<_Scalar, _Options> MatrixType; - public: - - enum { IsRowMajor = internal::traits::IsRowMajor }; - - EIGEN_SPARSE_PUBLIC_INTERFACE(SparseInnerVectorSet) - class InnerIterator: public MatrixType::InnerIterator + class ReverseInnerIterator: public MatrixType::ReverseInnerIterator { public: - inline InnerIterator(const SparseInnerVectorSet& xpr, Index outer) - : MatrixType::InnerIterator(xpr.m_matrix, xpr.m_outerStart + outer), m_outer(outer) + inline ReverseInnerIterator(const SparseInnerVectorSet& xpr, Index outer) + : MatrixType::ReverseInnerIterator(xpr.m_matrix, xpr.m_outerStart + outer), m_outer(outer) {} inline Index row() const { return IsRowMajor ? m_outer : this->index(); } inline Index col() const { return IsRowMajor ? this->index() : m_outer; } @@ -243,19 +170,19 @@ class SparseInnerVectorSet, Size> { typedef typename internal::remove_all::type _NestedMatrixType; _NestedMatrixType& matrix = const_cast<_NestedMatrixType&>(m_matrix);; - // This assignement is slow if this vector set not empty + // This assignement is slow if this vector set is not empty // and/or it is not at the end of the nonzeros of the underlying matrix. // 1 - eval to a temporary to avoid transposition and/or aliasing issues SparseMatrix tmp(other); // 2 - let's check whether there is enough allocated memory - Index nnz = tmp.nonZeros(); - Index nnz_previous = nonZeros(); - Index free_size = matrix.data().allocatedSize() - nnz_previous; - std::size_t nnz_head = m_outerStart==0 ? 0 : matrix._outerIndexPtr()[m_outerStart]; - std::size_t tail = m_matrix._outerIndexPtr()[m_outerStart+m_outerSize.value()]; - std::size_t nnz_tail = matrix.nonZeros() - tail; + Index nnz = tmp.nonZeros(); + Index nnz_previous = nonZeros(); + Index free_size = Index(matrix.data().allocatedSize()) + nnz_previous; + Index nnz_head = m_outerStart==0 ? 0 : matrix.outerIndexPtr()[m_outerStart]; + Index tail = m_matrix.outerIndexPtr()[m_outerStart+m_outerSize.value()]; + Index nnz_tail = matrix.nonZeros() - tail; if(nnz>free_size) { @@ -298,15 +225,15 @@ class SparseInnerVectorSet, Size> // update outer index pointers Index p = nnz_head; - for(Index k=1; k, Size> return operator=(other); } - inline const Scalar* _valuePtr() const - { return m_matrix._valuePtr() + m_matrix._outerIndexPtr()[m_outerStart]; } - inline Scalar* _valuePtr() - { return m_matrix.const_cast_derived()._valuePtr() + m_matrix._outerIndexPtr()[m_outerStart]; } + inline const Scalar* valuePtr() const + { return m_matrix.valuePtr() + m_matrix.outerIndexPtr()[m_outerStart]; } + inline Scalar* valuePtr() + { return m_matrix.const_cast_derived().valuePtr() + m_matrix.outerIndexPtr()[m_outerStart]; } - inline const Index* _innerIndexPtr() const - { return m_matrix._innerIndexPtr() + m_matrix._outerIndexPtr()[m_outerStart]; } - inline Index* _innerIndexPtr() - { return m_matrix.const_cast_derived()._innerIndexPtr() + m_matrix._outerIndexPtr()[m_outerStart]; } + inline const Index* innerIndexPtr() const + { return m_matrix.innerIndexPtr() + m_matrix.outerIndexPtr()[m_outerStart]; } + inline Index* innerIndexPtr() + { return m_matrix.const_cast_derived().innerIndexPtr() + m_matrix.outerIndexPtr()[m_outerStart]; } - inline const Index* _outerIndexPtr() const - { return m_matrix._outerIndexPtr() + m_outerStart; } - inline Index* _outerIndexPtr() - { return m_matrix.const_cast_derived()._outerIndexPtr() + m_outerStart; } + inline const Index* outerIndexPtr() const + { return m_matrix.outerIndexPtr() + m_outerStart; } + inline Index* outerIndexPtr() + { return m_matrix.const_cast_derived().outerIndexPtr() + m_outerStart; } Index nonZeros() const { - return std::size_t(m_matrix._outerIndexPtr()[m_outerStart+m_outerSize.value()]) - - std::size_t(m_matrix._outerIndexPtr()[m_outerStart]); + if(m_matrix.isCompressed()) + return std::size_t(m_matrix.outerIndexPtr()[m_outerStart+m_outerSize.value()]) + - std::size_t(m_matrix.outerIndexPtr()[m_outerStart]); + else if(m_outerSize.value()==0) + return 0; + else + return Map >(m_matrix.innerNonZeroPtr()+m_outerStart, m_outerSize.value()).sum(); } const Scalar& lastCoeff() const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(SparseInnerVectorSet); eigen_assert(nonZeros()>0); - return m_matrix._valuePtr()[m_matrix._outerIndexPtr()[m_outerStart+1]-1]; + if(m_matrix.isCompressed()) + return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart+1]-1]; + else + return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart]+m_matrix.innerNonZeroPtr()[m_outerStart]-1]; } // template @@ -356,7 +291,7 @@ class SparseInnerVectorSet, Size> protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; Index m_outerStart; const internal::variable_if_dynamic m_outerSize; @@ -412,11 +347,9 @@ template const SparseInnerVectorSet SparseMatrixBase::innerVector(Index outer) const { return SparseInnerVectorSet(derived(), outer); } -//---------- - /** \returns the i-th row of the matrix \c *this. For row-major matrix only. */ template -SparseInnerVectorSet SparseMatrixBase::subrows(Index start, Index size) +SparseInnerVectorSet SparseMatrixBase::middleRows(Index start, Index size) { EIGEN_STATIC_ASSERT(IsRowMajor,THIS_METHOD_IS_ONLY_FOR_ROW_MAJOR_MATRICES); return innerVectors(start, size); @@ -425,7 +358,7 @@ SparseInnerVectorSet SparseMatrixBase::subrows(Index s /** \returns the i-th row of the matrix \c *this. For row-major matrix only. * (read-only version) */ template -const SparseInnerVectorSet SparseMatrixBase::subrows(Index start, Index size) const +const SparseInnerVectorSet SparseMatrixBase::middleRows(Index start, Index size) const { EIGEN_STATIC_ASSERT(IsRowMajor,THIS_METHOD_IS_ONLY_FOR_ROW_MAJOR_MATRICES); return innerVectors(start, size); @@ -433,7 +366,7 @@ const SparseInnerVectorSet SparseMatrixBase::subrows(I /** \returns the i-th column of the matrix \c *this. For column-major matrix only. */ template -SparseInnerVectorSet SparseMatrixBase::subcols(Index start, Index size) +SparseInnerVectorSet SparseMatrixBase::middleCols(Index start, Index size) { EIGEN_STATIC_ASSERT(!IsRowMajor,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); return innerVectors(start, size); @@ -442,12 +375,14 @@ SparseInnerVectorSet SparseMatrixBase::subcols(Index s /** \returns the i-th column of the matrix \c *this. For column-major matrix only. * (read-only version) */ template -const SparseInnerVectorSet SparseMatrixBase::subcols(Index start, Index size) const +const SparseInnerVectorSet SparseMatrixBase::middleCols(Index start, Index size) const { EIGEN_STATIC_ASSERT(!IsRowMajor,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); return innerVectors(start, size); } + + /** \returns the \a outer -th column (resp. row) of the matrix \c *this if \c *this * is col-major (resp. row-major). */ @@ -462,4 +397,6 @@ template const SparseInnerVectorSet SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) const { return SparseInnerVectorSet(derived(), outerStart, outerSize); } +} // end namespace Eigen + #endif // EIGEN_SPARSE_BLOCK_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h similarity index 84% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseBinaryOp.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h index cde5bbc03..28167066a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSE_CWISE_BINARY_OP_H #define EIGEN_SPARSE_CWISE_BINARY_OP_H +namespace Eigen { + // Here we have to handle 3 cases: // 1 - sparse op dense // 2 - dense op sparse @@ -63,8 +65,18 @@ class CwiseBinaryOpImpl { public: class InnerIterator; + class ReverseInnerIterator; typedef CwiseBinaryOp Derived; EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) + CwiseBinaryOpImpl() + { + typedef typename internal::traits::StorageKind LhsStorageKind; + typedef typename internal::traits::StorageKind RhsStorageKind; + EIGEN_STATIC_ASSERT(( + (!internal::is_same::value) + || ((Lhs::Flags&RowMajorBit) == (Rhs::Flags&RowMajorBit))), + THE_STORAGE_ORDER_OF_BOTH_SIDES_MUST_MATCH); + } }; template @@ -76,7 +88,7 @@ class CwiseBinaryOpImpl::InnerIterator typedef internal::sparse_cwise_binary_op_inner_iterator_selector< BinaryOp,Lhs,Rhs, InnerIterator> Base; - EIGEN_STRONG_INLINE InnerIterator(const CwiseBinaryOpImpl& binOp, Index outer) + EIGEN_STRONG_INLINE InnerIterator(const CwiseBinaryOpImpl& binOp, typename CwiseBinaryOpImpl::Index outer) : Base(binOp.derived(),outer) {} }; @@ -246,7 +258,7 @@ class sparse_cwise_binary_op_inner_iterator_selector, Lhs, EIGEN_STRONG_INLINE operator bool() const { return m_lhsIter; } protected: - const RhsNested m_rhs; + RhsNested m_rhs; LhsIterator m_lhsIter; const BinaryFunc m_functor; const Index m_outer; @@ -298,16 +310,6 @@ class sparse_cwise_binary_op_inner_iterator_selector, Lhs, * Implementation of SparseMatrixBase and SparseCwise functions/operators ***************************************************************************/ -// template -// template -// EIGEN_STRONG_INLINE const CwiseBinaryOp::Scalar>, -// Derived, OtherDerived> -// SparseMatrixBase::operator-(const SparseMatrixBase &other) const -// { -// return CwiseBinaryOp, -// Derived, OtherDerived>(derived(), other.derived()); -// } - template template EIGEN_STRONG_INLINE Derived & @@ -316,14 +318,6 @@ SparseMatrixBase::operator-=(const SparseMatrixBase &othe return *this = derived() - other.derived(); } -// template -// template -// EIGEN_STRONG_INLINE const CwiseBinaryOp::Scalar>, Derived, OtherDerived> -// SparseMatrixBase::operator+(const SparseMatrixBase &other) const -// { -// return CwiseBinaryOp, Derived, OtherDerived>(derived(), other.derived()); -// } - template template EIGEN_STRONG_INLINE Derived & @@ -332,14 +326,6 @@ SparseMatrixBase::operator+=(const SparseMatrixBase& othe return *this = derived() + other.derived(); } -// template -// template -// EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE -// SparseCwise::operator*(const SparseMatrixBase &other) const -// { -// return EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE(_expression(), other.derived()); -// } - template template EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE @@ -348,28 +334,6 @@ SparseMatrixBase::cwiseProduct(const MatrixBase &other) c return EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE(derived(), other.derived()); } -// template -// template -// EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_BINOP_RETURN_TYPE(internal::scalar_quotient_op) -// SparseCwise::operator/(const SparseMatrixBase &other) const -// { -// return EIGEN_SPARSE_CWISE_BINOP_RETURN_TYPE(internal::scalar_quotient_op)(_expression(), other.derived()); -// } -// -// template -// template -// EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_BINOP_RETURN_TYPE(internal::scalar_quotient_op) -// SparseCwise::operator/(const MatrixBase &other) const -// { -// return EIGEN_SPARSE_CWISE_BINOP_RETURN_TYPE(internal::scalar_quotient_op)(_expression(), other.derived()); -// } - -// template -// template -// inline ExpressionType& SparseCwise::operator*=(const SparseMatrixBase &other) -// { -// return m_matrix.const_cast_derived() = _expression() * other.derived(); -// } - +} // end namespace Eigen #endif // EIGEN_SPARSE_CWISE_BINARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseUnaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseUnaryOp.h similarity index 50% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseUnaryOp.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseUnaryOp.h index aa068835f..2a63cf2af 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseCwiseUnaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseUnaryOp.h @@ -25,18 +25,7 @@ #ifndef EIGEN_SPARSE_CWISE_UNARY_OP_H #define EIGEN_SPARSE_CWISE_UNARY_OP_H -// template -// struct internal::traits > : internal::traits -// { -// typedef typename internal::result_of< -// UnaryOp(typename MatrixType::Scalar) -// >::type Scalar; -// typedef typename MatrixType::Nested MatrixTypeNested; -// typedef typename internal::remove_reference::type _MatrixTypeNested; -// enum { -// CoeffReadCost = _MatrixTypeNested::CoeffReadCost + internal::functor_traits::Cost -// }; -// }; +namespace Eigen { template class CwiseUnaryOpImpl @@ -45,39 +34,61 @@ class CwiseUnaryOpImpl public: class InnerIterator; -// typedef typename internal::remove_reference::type _LhsNested; + class ReverseInnerIterator; typedef CwiseUnaryOp Derived; EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) + + protected: + typedef typename internal::traits::_XprTypeNested _MatrixTypeNested; + typedef typename _MatrixTypeNested::InnerIterator MatrixTypeIterator; + typedef typename _MatrixTypeNested::ReverseInnerIterator MatrixTypeReverseIterator; }; template class CwiseUnaryOpImpl::InnerIterator + : public CwiseUnaryOpImpl::MatrixTypeIterator { typedef typename CwiseUnaryOpImpl::Scalar Scalar; - typedef typename internal::traits::_XprTypeNested _MatrixTypeNested; - typedef typename _MatrixTypeNested::InnerIterator MatrixTypeIterator; - typedef typename MatrixType::Index Index; + typedef typename CwiseUnaryOpImpl::MatrixTypeIterator Base; public: - EIGEN_STRONG_INLINE InnerIterator(const CwiseUnaryOpImpl& unaryOp, Index outer) - : m_iter(unaryOp.derived().nestedExpression(),outer), m_functor(unaryOp.derived().functor()) + EIGEN_STRONG_INLINE InnerIterator(const CwiseUnaryOpImpl& unaryOp, typename CwiseUnaryOpImpl::Index outer) + : Base(unaryOp.derived().nestedExpression(),outer), m_functor(unaryOp.derived().functor()) {} EIGEN_STRONG_INLINE InnerIterator& operator++() - { ++m_iter; return *this; } + { Base::operator++(); return *this; } - EIGEN_STRONG_INLINE Scalar value() const { return m_functor(m_iter.value()); } - - EIGEN_STRONG_INLINE Index index() const { return m_iter.index(); } - EIGEN_STRONG_INLINE Index row() const { return m_iter.row(); } - EIGEN_STRONG_INLINE Index col() const { return m_iter.col(); } - - EIGEN_STRONG_INLINE operator bool() const { return m_iter; } + EIGEN_STRONG_INLINE typename CwiseUnaryOpImpl::Scalar value() const { return m_functor(Base::value()); } protected: - MatrixTypeIterator m_iter; const UnaryOp m_functor; + private: + typename CwiseUnaryOpImpl::Scalar& valueRef(); +}; + +template +class CwiseUnaryOpImpl::ReverseInnerIterator + : public CwiseUnaryOpImpl::MatrixTypeReverseIterator +{ + typedef typename CwiseUnaryOpImpl::Scalar Scalar; + typedef typename CwiseUnaryOpImpl::MatrixTypeReverseIterator Base; + public: + + EIGEN_STRONG_INLINE ReverseInnerIterator(const CwiseUnaryOpImpl& unaryOp, typename CwiseUnaryOpImpl::Index outer) + : Base(unaryOp.derived().nestedExpression(),outer), m_functor(unaryOp.derived().functor()) + {} + + EIGEN_STRONG_INLINE ReverseInnerIterator& operator--() + { Base::operator--(); return *this; } + + EIGEN_STRONG_INLINE typename CwiseUnaryOpImpl::Scalar value() const { return m_functor(Base::value()); } + + protected: + const UnaryOp m_functor; + private: + typename CwiseUnaryOpImpl::Scalar& valueRef(); }; template @@ -87,39 +98,58 @@ class CwiseUnaryViewImpl public: class InnerIterator; -// typedef typename internal::remove_reference::type _LhsNested; + class ReverseInnerIterator; typedef CwiseUnaryView Derived; EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) + + protected: + typedef typename internal::traits::_MatrixTypeNested _MatrixTypeNested; + typedef typename _MatrixTypeNested::InnerIterator MatrixTypeIterator; + typedef typename _MatrixTypeNested::ReverseInnerIterator MatrixTypeReverseIterator; }; template class CwiseUnaryViewImpl::InnerIterator + : public CwiseUnaryViewImpl::MatrixTypeIterator { typedef typename CwiseUnaryViewImpl::Scalar Scalar; - typedef typename internal::traits::_MatrixTypeNested _MatrixTypeNested; - typedef typename _MatrixTypeNested::InnerIterator MatrixTypeIterator; - typedef typename MatrixType::Index Index; + typedef typename CwiseUnaryViewImpl::MatrixTypeIterator Base; public: - EIGEN_STRONG_INLINE InnerIterator(const CwiseUnaryViewImpl& unaryView, Index outer) - : m_iter(unaryView.derived().nestedExpression(),outer), m_functor(unaryView.derived().functor()) + EIGEN_STRONG_INLINE InnerIterator(const CwiseUnaryViewImpl& unaryOp, typename CwiseUnaryViewImpl::Index outer) + : Base(unaryOp.derived().nestedExpression(),outer), m_functor(unaryOp.derived().functor()) {} EIGEN_STRONG_INLINE InnerIterator& operator++() - { ++m_iter; return *this; } + { Base::operator++(); return *this; } - EIGEN_STRONG_INLINE Scalar value() const { return m_functor(m_iter.value()); } - EIGEN_STRONG_INLINE Scalar& valueRef() { return m_functor(m_iter.valueRef()); } - - EIGEN_STRONG_INLINE Index index() const { return m_iter.index(); } - EIGEN_STRONG_INLINE Index row() const { return m_iter.row(); } - EIGEN_STRONG_INLINE Index col() const { return m_iter.col(); } - - EIGEN_STRONG_INLINE operator bool() const { return m_iter; } + EIGEN_STRONG_INLINE typename CwiseUnaryViewImpl::Scalar value() const { return m_functor(Base::value()); } + EIGEN_STRONG_INLINE typename CwiseUnaryViewImpl::Scalar& valueRef() { return m_functor(Base::valueRef()); } + + protected: + const ViewOp m_functor; +}; + +template +class CwiseUnaryViewImpl::ReverseInnerIterator + : public CwiseUnaryViewImpl::MatrixTypeReverseIterator +{ + typedef typename CwiseUnaryViewImpl::Scalar Scalar; + typedef typename CwiseUnaryViewImpl::MatrixTypeReverseIterator Base; + public: + + EIGEN_STRONG_INLINE ReverseInnerIterator(const CwiseUnaryViewImpl& unaryOp, typename CwiseUnaryViewImpl::Index outer) + : Base(unaryOp.derived().nestedExpression(),outer), m_functor(unaryOp.derived().functor()) + {} + + EIGEN_STRONG_INLINE ReverseInnerIterator& operator--() + { Base::operator--(); return *this; } + + EIGEN_STRONG_INLINE typename CwiseUnaryViewImpl::Scalar value() const { return m_functor(Base::value()); } + EIGEN_STRONG_INLINE typename CwiseUnaryViewImpl::Scalar& valueRef() { return m_functor(Base::valueRef()); } protected: - MatrixTypeIterator m_iter; const ViewOp m_functor; }; @@ -143,4 +173,6 @@ SparseMatrixBase::operator/=(const Scalar& other) return derived(); } +} // end namespace Eigen + #endif // EIGEN_SPARSE_CWISE_UNARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDenseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h similarity index 61% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDenseProduct.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h index 0f77aa5be..00ba606be 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDenseProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSEDENSEPRODUCT_H #define EIGEN_SPARSEDENSEPRODUCT_H +namespace Eigen { + template struct SparseDenseProductReturnType { typedef SparseTimeDenseProduct Type; @@ -149,6 +151,102 @@ struct traits > typedef Dense StorageKind; typedef MatrixXpr XprKind; }; + +template +struct sparse_time_dense_product_impl; + +template +struct sparse_time_dense_product_impl +{ + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; + typedef typename internal::remove_all::type Res; + typedef typename Lhs::Index Index; + typedef typename Lhs::InnerIterator LhsInnerIterator; + static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, typename Res::Scalar alpha) + { + for(Index c=0; c +struct sparse_time_dense_product_impl +{ + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; + typedef typename internal::remove_all::type Res; + typedef typename Lhs::InnerIterator LhsInnerIterator; + typedef typename Lhs::Index Index; + static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, typename Res::Scalar alpha) + { + for(Index c=0; c +struct sparse_time_dense_product_impl +{ + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; + typedef typename internal::remove_all::type Res; + typedef typename Lhs::InnerIterator LhsInnerIterator; + typedef typename Lhs::Index Index; + static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, typename Res::Scalar alpha) + { + for(Index j=0; j +struct sparse_time_dense_product_impl +{ + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; + typedef typename internal::remove_all::type Res; + typedef typename Lhs::InnerIterator LhsInnerIterator; + typedef typename Lhs::Index Index; + static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, typename Res::Scalar alpha) + { + for(Index j=0; j +inline void sparse_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha) +{ + sparse_time_dense_product_impl::run(lhs, rhs, res, alpha); +} + } // end namespace internal template @@ -163,21 +261,7 @@ class SparseTimeDenseProduct template void scaleAndAddTo(Dest& dest, Scalar alpha) const { - typedef typename internal::remove_all::type _Lhs; - typedef typename internal::remove_all::type _Rhs; - typedef typename _Lhs::InnerIterator LhsInnerIterator; - enum { LhsIsRowMajor = (_Lhs::Flags&RowMajorBit)==RowMajorBit }; - for(Index j=0; j void scaleAndAddTo(Dest& dest, Scalar alpha) const { - typedef typename internal::remove_all::type _Rhs; - typedef typename _Rhs::InnerIterator RhsInnerIterator; - enum { RhsIsRowMajor = (_Rhs::Flags&RowMajorBit)==RowMajorBit }; - for(Index j=0; j lhs_t(m_lhs); + Transpose rhs_t(m_rhs); + Transpose dest_t(dest); + internal::sparse_time_dense_product(rhs_t, lhs_t, dest_t, alpha); } private: @@ -228,4 +310,6 @@ SparseMatrixBase::operator*(const MatrixBase &other) cons return typename SparseDenseProductReturnType::Type(derived(), other.derived()); } +} // end namespace Eigen + #endif // EIGEN_SPARSEDENSEPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDiagonalProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDiagonalProduct.h similarity index 99% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDiagonalProduct.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDiagonalProduct.h index fb9a29c05..b09c4a715 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDiagonalProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDiagonalProduct.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSE_DIAGONAL_PRODUCT_H #define EIGEN_SPARSE_DIAGONAL_PRODUCT_H +namespace Eigen { + // The product of a diagonal matrix with a sparse matrix can be easily // implemented using expression template. // We have two consider very different cases: @@ -192,4 +194,6 @@ SparseMatrixBase::operator*(const DiagonalBase &other) co return SparseDiagonalProduct(this->derived(), other.derived()); } +} // end namespace Eigen + #endif // EIGEN_SPARSE_DIAGONAL_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDot.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDot.h similarity index 86% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDot.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDot.h index 1f10f71a4..ebb63d36b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseDot.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDot.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSE_DOT_H #define EIGEN_SPARSE_DOT_H +namespace Eigen { + template template typename internal::traits::Scalar @@ -40,7 +42,7 @@ SparseMatrixBase::dot(const MatrixBase& other) const eigen_assert(other.size()>0 && "you are using a non initialized vector"); typename Derived::InnerIterator i(derived(),0); - Scalar res = 0; + Scalar res(0); while (i) { res += internal::conj(i.value()) * other.coeff(i.index()); @@ -62,9 +64,17 @@ SparseMatrixBase::dot(const SparseMatrixBase& other) cons eigen_assert(size() == other.size()); - typename Derived::InnerIterator i(derived(),0); - typename OtherDerived::InnerIterator j(other.derived(),0); - Scalar res = 0; + typedef typename Derived::Nested Nested; + typedef typename OtherDerived::Nested OtherNested; + typedef typename internal::remove_all::type NestedCleaned; + typedef typename internal::remove_all::type OtherNestedCleaned; + + const Nested nthis(derived()); + const OtherNested nother(other.derived()); + + typename NestedCleaned::InnerIterator i(nthis,0); + typename OtherNestedCleaned::InnerIterator j(nother,0); + Scalar res(0); while (i && j) { if (i.index()==j.index()) @@ -94,4 +104,6 @@ SparseMatrixBase::norm() const return internal::sqrt(squaredNorm()); } +} // end namespace Eigen + #endif // EIGEN_SPARSE_DOT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseFuzzy.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseFuzzy.h similarity index 100% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseFuzzy.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseFuzzy.h diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h new file mode 100644 index 000000000..214f130f5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h @@ -0,0 +1,1127 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2010 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSEMATRIX_H +#define EIGEN_SPARSEMATRIX_H + +namespace Eigen { + +/** \ingroup SparseCore_Module + * + * \class SparseMatrix + * + * \brief A versatible sparse matrix representation + * + * This class implements a more versatile variants of the common \em compressed row/column storage format. + * Each colmun's (resp. row) non zeros are stored as a pair of value with associated row (resp. colmiun) index. + * All the non zeros are stored in a single large buffer. Unlike the \em compressed format, there might be extra + * space inbetween the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero + * can be done with limited memory reallocation and copies. + * + * A call to the function makeCompressed() turns the matrix into the standard \em compressed format + * compatible with many library. + * + * More details on this storage sceheme are given in the \ref TutorialSparse "manual pages". + * + * \tparam _Scalar the scalar type, i.e. the type of the coefficients + * \tparam _Options Union of bit flags controlling the storage scheme. Currently the only possibility + * is RowMajor. The default is 0 which means column-major. + * \tparam _Index the type of the indices. It has to be a \b signed type (e.g., short, int, std::ptrdiff_t). Default is \c int. + * + * This class can be extended with the help of the plugin mechanism described on the page + * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_SPARSEMATRIX_PLUGIN. + */ + +namespace internal { +template +struct traits > +{ + typedef _Scalar Scalar; + typedef _Index Index; + typedef Sparse StorageKind; + typedef MatrixXpr XprKind; + enum { + RowsAtCompileTime = Dynamic, + ColsAtCompileTime = Dynamic, + MaxRowsAtCompileTime = Dynamic, + MaxColsAtCompileTime = Dynamic, + Flags = _Options | NestByRefBit | LvalueBit, + CoeffReadCost = NumTraits::ReadCost, + SupportedAccessPatterns = InnerRandomAccessPattern + }; +}; + +template +struct traits, DiagIndex> > +{ + typedef SparseMatrix<_Scalar, _Options, _Index> MatrixType; + typedef typename nested::type MatrixTypeNested; + typedef typename remove_reference::type _MatrixTypeNested; + + typedef _Scalar Scalar; + typedef Dense StorageKind; + typedef _Index Index; + typedef MatrixXpr XprKind; + + enum { + RowsAtCompileTime = Dynamic, + ColsAtCompileTime = 1, + MaxRowsAtCompileTime = Dynamic, + MaxColsAtCompileTime = 1, + Flags = 0, + CoeffReadCost = _MatrixTypeNested::CoeffReadCost*10 + }; +}; + +} // end namespace internal + +template +class SparseMatrix + : public SparseMatrixBase > +{ + public: + EIGEN_SPARSE_PUBLIC_INTERFACE(SparseMatrix) + EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseMatrix, +=) + EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseMatrix, -=) + + typedef MappedSparseMatrix Map; + using Base::IsRowMajor; + typedef internal::CompressedStorage Storage; + enum { + Options = _Options + }; + + protected: + + typedef SparseMatrix TransposedSparseMatrix; + + Index m_outerSize; + Index m_innerSize; + Index* m_outerIndex; + Index* m_innerNonZeros; // optional, if null then the data is compressed + Storage m_data; + + Eigen::Map > innerNonZeros() { return Eigen::Map >(m_innerNonZeros, m_innerNonZeros?m_outerSize:0); } + const Eigen::Map > innerNonZeros() const { return Eigen::Map >(m_innerNonZeros, m_innerNonZeros?m_outerSize:0); } + + public: + + /** \returns whether \c *this is in compressed form. */ + inline bool isCompressed() const { return m_innerNonZeros==0; } + + /** \returns the number of rows of the matrix */ + inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; } + /** \returns the number of columns of the matrix */ + inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; } + + /** \returns the number of rows (resp. columns) of the matrix if the storage order column major (resp. row major) */ + inline Index innerSize() const { return m_innerSize; } + /** \returns the number of columns (resp. rows) of the matrix if the storage order column major (resp. row major) */ + inline Index outerSize() const { return m_outerSize; } + + /** \returns a const pointer to the array of values. + * This function is aimed at interoperability with other libraries. + * \sa innerIndexPtr(), outerIndexPtr() */ + inline const Scalar* valuePtr() const { return &m_data.value(0); } + /** \returns a non-const pointer to the array of values. + * This function is aimed at interoperability with other libraries. + * \sa innerIndexPtr(), outerIndexPtr() */ + inline Scalar* valuePtr() { return &m_data.value(0); } + + /** \returns a const pointer to the array of inner indices. + * This function is aimed at interoperability with other libraries. + * \sa valuePtr(), outerIndexPtr() */ + inline const Index* innerIndexPtr() const { return &m_data.index(0); } + /** \returns a non-const pointer to the array of inner indices. + * This function is aimed at interoperability with other libraries. + * \sa valuePtr(), outerIndexPtr() */ + inline Index* innerIndexPtr() { return &m_data.index(0); } + + /** \returns a const pointer to the array of the starting positions of the inner vectors. + * This function is aimed at interoperability with other libraries. + * \sa valuePtr(), innerIndexPtr() */ + inline const Index* outerIndexPtr() const { return m_outerIndex; } + /** \returns a non-const pointer to the array of the starting positions of the inner vectors. + * This function is aimed at interoperability with other libraries. + * \sa valuePtr(), innerIndexPtr() */ + inline Index* outerIndexPtr() { return m_outerIndex; } + + /** \returns a const pointer to the array of the number of non zeros of the inner vectors. + * This function is aimed at interoperability with other libraries. + * \warning it returns the null pointer 0 in compressed mode */ + inline const Index* innerNonZeroPtr() const { return m_innerNonZeros; } + /** \returns a non-const pointer to the array of the number of non zeros of the inner vectors. + * This function is aimed at interoperability with other libraries. + * \warning it returns the null pointer 0 in compressed mode */ + inline Index* innerNonZeroPtr() { return m_innerNonZeros; } + + /** \internal */ + inline Storage& data() { return m_data; } + /** \internal */ + inline const Storage& data() const { return m_data; } + + /** \returns the value of the matrix at position \a i, \a j + * This function returns Scalar(0) if the element is an explicit \em zero */ + inline Scalar coeff(Index row, Index col) const + { + const Index outer = IsRowMajor ? row : col; + const Index inner = IsRowMajor ? col : row; + Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1]; + return m_data.atInRange(m_outerIndex[outer], end, inner); + } + + /** \returns a non-const reference to the value of the matrix at position \a i, \a j + * + * If the element does not exist then it is inserted via the insert(Index,Index) function + * which itself turns the matrix into a non compressed form if that was not the case. + * + * This is a O(log(nnz_j)) operation (binary search) plus the cost of insert(Index,Index) + * function if the element does not already exist. + */ + inline Scalar& coeffRef(Index row, Index col) + { + const Index outer = IsRowMajor ? row : col; + const Index inner = IsRowMajor ? col : row; + + Index start = m_outerIndex[outer]; + Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1]; + eigen_assert(end>=start && "you probably called coeffRef on a non finalized matrix"); + if(end<=start) + return insert(row,col); + const Index p = m_data.searchLowerIndex(start,end-1,inner); + if((p(m_data.size()); + } + + /** Preallocates \a reserveSize non zeros. + * + * Precondition: the matrix must be in compressed mode. */ + inline void reserve(Index reserveSize) + { + eigen_assert(isCompressed() && "This function does not make sense in non compressed mode."); + m_data.reserve(reserveSize); + } + + #ifdef EIGEN_PARSED_BY_DOXYGEN + /** Preallocates \a reserveSize[\c j] non zeros for each column (resp. row) \c j. + * + * This function turns the matrix in non-compressed mode */ + template + inline void reserve(const SizesType& reserveSizes); + #else + template + inline void reserve(const SizesType& reserveSizes, const typename SizesType::value_type& enableif = typename SizesType::value_type()) + { + EIGEN_UNUSED_VARIABLE(enableif); + reserveInnerVectors(reserveSizes); + } + template + inline void reserve(const SizesType& reserveSizes, const typename SizesType::Scalar& enableif = typename SizesType::Scalar()) + { + EIGEN_UNUSED_VARIABLE(enableif); + reserveInnerVectors(reserveSizes); + } + #endif // EIGEN_PARSED_BY_DOXYGEN + protected: + template + inline void reserveInnerVectors(const SizesType& reserveSizes) + { + + if(isCompressed()) + { + std::size_t totalReserveSize = 0; + // turn the matrix into non-compressed mode + m_innerNonZeros = new Index[m_outerSize]; + + // temporarily use m_innerSizes to hold the new starting points. + Index* newOuterIndex = m_innerNonZeros; + + Index count = 0; + for(Index j=0; j=0; --j) + { + ptrdiff_t innerNNZ = previousOuterIndex - m_outerIndex[j]; + for(std::ptrdiff_t i=innerNNZ-1; i>=0; --i) + { + m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i); + m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i); + } + previousOuterIndex = m_outerIndex[j]; + m_outerIndex[j] = newOuterIndex[j]; + m_innerNonZeros[j] = innerNNZ; + } + m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1]; + + m_data.resize(m_outerIndex[m_outerSize]); + } + else + { + Index* newOuterIndex = new Index[m_outerSize+1]; + Index count = 0; + for(Index j=0; j(reserveSizes[j], alreadyReserved); + count += toReserve + m_innerNonZeros[j]; + } + newOuterIndex[m_outerSize] = count; + + m_data.resize(count); + for(ptrdiff_t j=m_outerSize-1; j>=0; --j) + { + std::ptrdiff_t offset = newOuterIndex[j] - m_outerIndex[j]; + if(offset>0) + { + std::ptrdiff_t innerNNZ = m_innerNonZeros[j]; + for(std::ptrdiff_t i=innerNNZ-1; i>=0; --i) + { + m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i); + m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i); + } + } + } + + std::swap(m_outerIndex, newOuterIndex); + delete[] newOuterIndex; + } + + } + public: + + //--- low level purely coherent filling --- + + /** \internal + * \returns a reference to the non zero coefficient at position \a row, \a col assuming that: + * - the nonzero does not already exist + * - the new coefficient is the last one according to the storage order + * + * Before filling a given inner vector you must call the statVec(Index) function. + * + * After an insertion session, you should call the finalize() function. + * + * \sa insert, insertBackByOuterInner, startVec */ + inline Scalar& insertBack(Index row, Index col) + { + return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row); + } + + /** \internal + * \sa insertBack, startVec */ + inline Scalar& insertBackByOuterInner(Index outer, Index inner) + { + eigen_assert(size_t(m_outerIndex[outer+1]) == m_data.size() && "Invalid ordered insertion (invalid outer index)"); + eigen_assert( (m_outerIndex[outer+1]-m_outerIndex[outer]==0 || m_data.index(m_data.size()-1)(m_data.size()); + Index i = m_outerSize; + // find the last filled column + while (i>=0 && m_outerIndex[i]==0) + --i; + ++i; + while (i<=m_outerSize) + { + m_outerIndex[i] = size; + ++i; + } + } + } + + //--- + + template + void setFromTriplets(const InputIterators& begin, const InputIterators& end); + + void sumupDuplicates(); + + //--- + + /** \internal + * same as insert(Index,Index) except that the indices are given relative to the storage order */ + EIGEN_DONT_INLINE Scalar& insertByOuterInner(Index j, Index i) + { + return insert(IsRowMajor ? j : i, IsRowMajor ? i : j); + } + + /** Turns the matrix into the \em compressed format. + */ + void makeCompressed() + { + if(isCompressed()) + return; + + Index oldStart = m_outerIndex[1]; + m_outerIndex[1] = m_innerNonZeros[0]; + for(Index j=1; j0) + { + for(Index k=0; k::dummy_precision()) + { + prune(default_prunning_func(reference,epsilon)); + } + + /** Turns the matrix into compressed format, and suppresses all nonzeros which do not satisfy the predicate \a keep. + * The functor type \a KeepFunc must implement the following function: + * \code + * bool operator() (const Index& row, const Index& col, const Scalar& value) const; + * \endcode + * \sa prune(Scalar,RealScalar) + */ + template + void prune(const KeepFunc& keep = KeepFunc()) + { + // TODO optimize the uncompressed mode to avoid moving and allocating the data twice + // TODO also implement a unit test + makeCompressed(); + + Index k = 0; + for(Index j=0; j diagonal() const { return *this; } + + /** Default constructor yielding an empty \c 0 \c x \c 0 matrix */ + inline SparseMatrix() + : m_outerSize(-1), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0) + { + check_template_parameters(); + resize(0, 0); + } + + /** Constructs a \a rows \c x \a cols empty matrix */ + inline SparseMatrix(Index rows, Index cols) + : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0) + { + check_template_parameters(); + resize(rows, cols); + } + + /** Constructs a sparse matrix from the sparse expression \a other */ + template + inline SparseMatrix(const SparseMatrixBase& other) + : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0) + { + check_template_parameters(); + *this = other.derived(); + } + + /** Copy constructor (it performs a deep copy) */ + inline SparseMatrix(const SparseMatrix& other) + : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0) + { + check_template_parameters(); + *this = other.derived(); + } + + /** Swaps the content of two sparse matrices of the same type. + * This is a fast operation that simply swaps the underlying pointers and parameters. */ + inline void swap(SparseMatrix& other) + { + //EIGEN_DBG_SPARSE(std::cout << "SparseMatrix:: swap\n"); + std::swap(m_outerIndex, other.m_outerIndex); + std::swap(m_innerSize, other.m_innerSize); + std::swap(m_outerSize, other.m_outerSize); + std::swap(m_innerNonZeros, other.m_innerNonZeros); + m_data.swap(other.m_data); + } + + inline SparseMatrix& operator=(const SparseMatrix& other) + { + if (other.isRValue()) + { + swap(other.const_cast_derived()); + } + else + { + initAssignment(other); + if(other.isCompressed()) + { + memcpy(m_outerIndex, other.m_outerIndex, (m_outerSize+1)*sizeof(Index)); + m_data = other.m_data; + } + else + { + Base::operator=(other); + } + } + return *this; + } + + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + inline SparseMatrix& operator=(const SparseSparseProduct& product) + { return Base::operator=(product); } + + template + inline SparseMatrix& operator=(const ReturnByValue& other) + { return Base::operator=(other.derived()); } + + template + inline SparseMatrix& operator=(const EigenBase& other) + { return Base::operator=(other.derived()); } + #endif + + template + EIGEN_DONT_INLINE SparseMatrix& operator=(const SparseMatrixBase& other) + { + initAssignment(other.derived()); + const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); + if (needToTranspose) + { + // two passes algorithm: + // 1 - compute the number of coeffs per dest inner vector + // 2 - do the actual copy/eval + // Since each coeff of the rhs has to be evaluated twice, let's evaluate it if needed + typedef typename internal::nested::type OtherCopy; + typedef typename internal::remove_all::type _OtherCopy; + OtherCopy otherCopy(other.derived()); + + Eigen::Map > (m_outerIndex,outerSize()).setZero(); + // pass 1 + // FIXME the above copy could be merged with that pass + for (Index j=0; j&>(m); + return s; + } + + /** Destructor */ + inline ~SparseMatrix() + { + delete[] m_outerIndex; + delete[] m_innerNonZeros; + } + +#ifndef EIGEN_PARSED_BY_DOXYGEN + /** Overloaded for performance */ + Scalar sum() const; +#endif + +# ifdef EIGEN_SPARSEMATRIX_PLUGIN +# include EIGEN_SPARSEMATRIX_PLUGIN +# endif + +protected: + + template + void initAssignment(const Other& other) + { + resize(other.rows(), other.cols()); + if(m_innerNonZeros) + { + delete[] m_innerNonZeros; + m_innerNonZeros = 0; + } + } + + /** \internal + * \sa insert(Index,Index) */ + EIGEN_DONT_INLINE Scalar& insertCompressed(Index row, Index col) + { + eigen_assert(isCompressed()); + + const Index outer = IsRowMajor ? row : col; + const Index inner = IsRowMajor ? col : row; + + Index previousOuter = outer; + if (m_outerIndex[outer+1]==0) + { + // we start a new inner vector + while (previousOuter>=0 && m_outerIndex[previousOuter]==0) + { + m_outerIndex[previousOuter] = static_cast(m_data.size()); + --previousOuter; + } + m_outerIndex[outer+1] = m_outerIndex[outer]; + } + + // here we have to handle the tricky case where the outerIndex array + // starts with: [ 0 0 0 0 0 1 ...] and we are inserted in, e.g., + // the 2nd inner vector... + bool isLastVec = (!(previousOuter==-1 && m_data.size()!=0)) + && (size_t(m_outerIndex[outer+1]) == m_data.size()); + + size_t startId = m_outerIndex[outer]; + // FIXME let's make sure sizeof(long int) == sizeof(size_t) + size_t p = m_outerIndex[outer+1]; + ++m_outerIndex[outer+1]; + + float reallocRatio = 1; + if (m_data.allocatedSize()<=m_data.size()) + { + // if there is no preallocated memory, let's reserve a minimum of 32 elements + if (m_data.size()==0) + { + m_data.reserve(32); + } + else + { + // we need to reallocate the data, to reduce multiple reallocations + // we use a smart resize algorithm based on the current filling ratio + // in addition, we use float to avoid integers overflows + float nnzEstimate = float(m_outerIndex[outer])*float(m_outerSize)/float(outer+1); + reallocRatio = (nnzEstimate-float(m_data.size()))/float(m_data.size()); + // furthermore we bound the realloc ratio to: + // 1) reduce multiple minor realloc when the matrix is almost filled + // 2) avoid to allocate too much memory when the matrix is almost empty + reallocRatio = (std::min)((std::max)(reallocRatio,1.5f),8.f); + } + } + m_data.resize(m_data.size()+1,reallocRatio); + + if (!isLastVec) + { + if (previousOuter==-1) + { + // oops wrong guess. + // let's correct the outer offsets + for (Index k=0; k<=(outer+1); ++k) + m_outerIndex[k] = 0; + Index k=outer+1; + while(m_outerIndex[k]==0) + m_outerIndex[k++] = 1; + while (k<=m_outerSize && m_outerIndex[k]!=0) + m_outerIndex[k++]++; + p = 0; + --k; + k = m_outerIndex[k]-1; + while (k>0) + { + m_data.index(k) = m_data.index(k-1); + m_data.value(k) = m_data.value(k-1); + k--; + } + } + else + { + // we are not inserting into the last inner vec + // update outer indices: + Index j = outer+2; + while (j<=m_outerSize && m_outerIndex[j]!=0) + m_outerIndex[j++]++; + --j; + // shift data of last vecs: + Index k = m_outerIndex[j]-1; + while (k>=Index(p)) + { + m_data.index(k) = m_data.index(k-1); + m_data.value(k) = m_data.value(k-1); + k--; + } + } + } + + while ( (p > startId) && (m_data.index(p-1) > inner) ) + { + m_data.index(p) = m_data.index(p-1); + m_data.value(p) = m_data.value(p-1); + --p; + } + + m_data.index(p) = inner; + return (m_data.value(p) = 0); + } + + /** \internal + * A vector object that is equal to 0 everywhere but v at the position i */ + class SingletonVector + { + Index m_index; + Index m_value; + public: + typedef Index value_type; + SingletonVector(Index i, Index v) + : m_index(i), m_value(v) + {} + + Index operator[](Index i) const { return i==m_index ? m_value : 0; } + }; + + /** \internal + * \sa insert(Index,Index) */ + EIGEN_DONT_INLINE Scalar& insertUncompressed(Index row, Index col) + { + eigen_assert(!isCompressed()); + + const Index outer = IsRowMajor ? row : col; + const Index inner = IsRowMajor ? col : row; + + std::ptrdiff_t room = m_outerIndex[outer+1] - m_outerIndex[outer]; + std::ptrdiff_t innerNNZ = m_innerNonZeros[outer]; + if(innerNNZ>=room) + { + // this inner vector is full, we need to reallocate the whole buffer :( + reserve(SingletonVector(outer,std::max(2,innerNNZ))); + } + + Index startId = m_outerIndex[outer]; + Index p = startId + m_innerNonZeros[outer]; + while ( (p > startId) && (m_data.index(p-1) > inner) ) + { + m_data.index(p) = m_data.index(p-1); + m_data.value(p) = m_data.value(p-1); + --p; + } + + m_innerNonZeros[outer]++; + + m_data.index(p) = inner; + return (m_data.value(p) = 0); + } + +public: + /** \internal + * \sa insert(Index,Index) */ + inline Scalar& insertBackUncompressed(Index row, Index col) + { + const Index outer = IsRowMajor ? row : col; + const Index inner = IsRowMajor ? col : row; + + eigen_assert(!isCompressed()); + eigen_assert(m_innerNonZeros[outer]<=(m_outerIndex[outer+1] - m_outerIndex[outer])); + + Index p = m_outerIndex[outer] + m_innerNonZeros[outer]; + m_innerNonZeros[outer]++; + m_data.index(p) = inner; + return (m_data.value(p) = 0); + } + +private: + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT(NumTraits::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE); + } + + struct default_prunning_func { + default_prunning_func(Scalar ref, RealScalar eps) : reference(ref), epsilon(eps) {} + inline bool operator() (const Index&, const Index&, const Scalar& value) const + { + return !internal::isMuchSmallerThan(value, reference, epsilon); + } + Scalar reference; + RealScalar epsilon; + }; +}; + +template +class SparseMatrix::InnerIterator +{ + public: + InnerIterator(const SparseMatrix& mat, Index outer) + : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer), m_id(mat.m_outerIndex[outer]) + { + if(mat.isCompressed()) + m_end = mat.m_outerIndex[outer+1]; + else + m_end = m_id + mat.m_innerNonZeros[outer]; + } + + inline InnerIterator& operator++() { m_id++; return *this; } + + inline const Scalar& value() const { return m_values[m_id]; } + inline Scalar& valueRef() { return const_cast(m_values[m_id]); } + + inline Index index() const { return m_indices[m_id]; } + inline Index outer() const { return m_outer; } + inline Index row() const { return IsRowMajor ? m_outer : index(); } + inline Index col() const { return IsRowMajor ? index() : m_outer; } + + inline operator bool() const { return (m_id < m_end); } + + protected: + const Scalar* m_values; + const Index* m_indices; + const Index m_outer; + Index m_id; + Index m_end; +}; + +template +class SparseMatrix::ReverseInnerIterator +{ + public: + ReverseInnerIterator(const SparseMatrix& mat, Index outer) + : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer), m_start(mat.m_outerIndex[outer]) + { + if(mat.isCompressed()) + m_id = mat.m_outerIndex[outer+1]; + else + m_id = m_start + mat.m_innerNonZeros[outer]; + } + + inline ReverseInnerIterator& operator--() { --m_id; return *this; } + + inline const Scalar& value() const { return m_values[m_id-1]; } + inline Scalar& valueRef() { return const_cast(m_values[m_id-1]); } + + inline Index index() const { return m_indices[m_id-1]; } + inline Index outer() const { return m_outer; } + inline Index row() const { return IsRowMajor ? m_outer : index(); } + inline Index col() const { return IsRowMajor ? index() : m_outer; } + + inline operator bool() const { return (m_id > m_start); } + + protected: + const Scalar* m_values; + const Index* m_indices; + const Index m_outer; + Index m_id; + const Index m_start; +}; + +namespace internal { + +template +void set_from_triplets(const InputIterator& begin, const InputIterator& end, SparseMatrixType& mat, int Options = 0) +{ + EIGEN_UNUSED_VARIABLE(Options); + enum { IsRowMajor = SparseMatrixType::IsRowMajor }; + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::Index Index; + SparseMatrix trMat(mat.rows(),mat.cols()); + + // pass 1: count the nnz per inner-vector + VectorXi wi(trMat.outerSize()); + wi.setZero(); + for(InputIterator it(begin); it!=end; ++it) + wi(IsRowMajor ? it->col() : it->row())++; + + // pass 2: insert all the elements into trMat + trMat.reserve(wi); + for(InputIterator it(begin); it!=end; ++it) + trMat.insertBackUncompressed(it->row(),it->col()) = it->value(); + + // pass 3: + trMat.sumupDuplicates(); + + // pass 4: transposed copy -> implicit sorting + mat = trMat; +} + +} + + +/** Fill the matrix \c *this with the list of \em triplets defined by the iterator range \a begin - \b. + * + * A \em triplet is a tuple (i,j,value) defining a non-zero element. + * The input list of triplets does not have to be sorted, and can contains duplicated elements. + * In any case, the result is a \b sorted and \b compressed sparse matrix where the duplicates have been summed up. + * This is a \em O(n) operation, with \em n the number of triplet elements. + * The initial contents of \c *this is destroyed. + * The matrix \c *this must be properly resized beforehand using the SparseMatrix(Index,Index) constructor, + * or the resize(Index,Index) method. The sizes are not extracted from the triplet list. + * + * The \a InputIterators value_type must provide the following interface: + * \code + * Scalar value() const; // the value + * Scalar row() const; // the row index i + * Scalar col() const; // the column index j + * \endcode + * See for instance the Eigen::Triplet template class. + * + * Here is a typical usage example: + * \code + typedef Triplet T; + std::vector tripletList; + triplets.reserve(estimation_of_entries); + for(...) + { + // ... + tripletList.push_back(T(i,j,v_ij)); + } + SparseMatrixType m(rows,cols); + m.setFromTriplets(tripletList.begin(), tripletList.end()); + // m is ready to go! + * \endcode + * + * \warning The list of triplets is read multiple times (at least twice). Therefore, it is not recommended to define + * an abstract iterator over a complex data-structure that would be expensive to evaluate. The triplets should rather + * be explicitely stored into a std::vector for instance. + */ +template +template +void SparseMatrix::setFromTriplets(const InputIterators& begin, const InputIterators& end) +{ + internal::set_from_triplets(begin, end, *this); +} + +/** \internal */ +template +void SparseMatrix::sumupDuplicates() +{ + eigen_assert(!isCompressed()); + // TODO, in practice we should be able to use m_innerNonZeros for that task + VectorXi wi(innerSize()); + wi.fill(-1); + Index count = 0; + // for each inner-vector, wi[inner_index] will hold the position of first element into the index/value buffers + for(int j=0; j=start) + { + // we already meet this entry => accumulate it + m_data.value(wi(i)) += m_data.value(k); + } + else + { + m_data.value(count) = m_data.value(k); + m_data.index(count) = m_data.index(k); + wi(i) = count; + ++count; + } + } + m_outerIndex[j] = start; + } + m_outerIndex[m_outerSize] = count; + + // turn the matrix into compressed form + delete[] m_innerNonZeros; + m_innerNonZeros = 0; + m_data.resize(m_outerIndex[m_outerSize]); +} + +} // end namespace Eigen + +#endif // EIGEN_SPARSEMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrixBase.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h similarity index 55% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrixBase.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h index c01981bc9..9d7b83577 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseMatrixBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2009 Gael Guennebaud +// Copyright (C) 2008-2011 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -25,7 +25,9 @@ #ifndef EIGEN_SPARSEMATRIXBASE_H #define EIGEN_SPARSEMATRIXBASE_H -/** \ingroup Sparse_Module +namespace Eigen { + +/** \ingroup SparseCore_Module * * \class SparseMatrixBase * @@ -44,6 +46,9 @@ template class SparseMatrixBase : public EigenBase typedef typename internal::packet_traits::type PacketScalar; typedef typename internal::traits::StorageKind StorageKind; typedef typename internal::traits::Index Index; + typedef typename internal::add_const_on_value_type_if_arithmetic< + typename internal::packet_traits::type + >::type PacketReturnType; typedef SparseMatrixBase StorageBaseType; typedef EigenBase Base; @@ -54,8 +59,6 @@ template class SparseMatrixBase : public EigenBase other.derived().evalTo(derived()); return derived(); } - -// using Base::operator=; enum { @@ -107,15 +110,6 @@ template class SparseMatrixBase : public EigenBase #endif }; - /* \internal the return type of MatrixBase::conjugate() */ -// typedef typename internal::conditional::IsComplex, -// const SparseCwiseUnaryOp, Derived>, -// const Derived& -// >::type ConjugateReturnType; - /* \internal the return type of MatrixBase::real() */ -// typedef SparseCwiseUnaryOp, Derived> RealReturnType; - /* \internal the return type of MatrixBase::imag() */ -// typedef SparseCwiseUnaryOp, Derived> ImagReturnType; /** \internal the return type of MatrixBase::adjoint() */ typedef typename internal::conditional::IsComplex, CwiseUnaryOp, Eigen::Transpose >, @@ -125,16 +119,6 @@ template class SparseMatrixBase : public EigenBase typedef SparseMatrix PlainObject; -#define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase -# include "../plugins/CommonCwiseUnaryOps.h" -# include "../plugins/CommonCwiseBinaryOps.h" -# include "../plugins/MatrixCwiseUnaryOps.h" -# include "../plugins/MatrixCwiseBinaryOps.h" -# ifdef EIGEN_SPARSEMATRIXBASE_PLUGIN -# include EIGEN_SPARSEMATRIXBASE_PLUGIN -# endif -# undef EIGEN_CURRENT_STORAGE_BASE_CLASS -#undef EIGEN_CURRENT_STORAGE_BASE_CLASS #ifndef EIGEN_PARSED_BY_DOXYGEN /** This is the "real scalar" type; if the \a Scalar type is already real numbers @@ -162,12 +146,24 @@ template class SparseMatrixBase : public EigenBase { return *static_cast(const_cast(this)); } #endif // not EIGEN_PARSED_BY_DOXYGEN - /** \returns the number of rows. \sa cols(), RowsAtCompileTime */ +#define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase +# include "../plugins/CommonCwiseUnaryOps.h" +# include "../plugins/CommonCwiseBinaryOps.h" +# include "../plugins/MatrixCwiseUnaryOps.h" +# include "../plugins/MatrixCwiseBinaryOps.h" +# ifdef EIGEN_SPARSEMATRIXBASE_PLUGIN +# include EIGEN_SPARSEMATRIXBASE_PLUGIN +# endif +# undef EIGEN_CURRENT_STORAGE_BASE_CLASS +#undef EIGEN_CURRENT_STORAGE_BASE_CLASS + + + /** \returns the number of rows. \sa cols() */ inline Index rows() const { return derived().rows(); } - /** \returns the number of columns. \sa rows(), ColsAtCompileTime*/ + /** \returns the number of columns. \sa rows() */ inline Index cols() const { return derived().cols(); } /** \returns the number of coefficients, which is \a rows()*cols(). - * \sa rows(), cols(), SizeAtCompileTime. */ + * \sa rows(), cols(). */ inline Index size() const { return rows() * cols(); } /** \returns the number of nonzero coefficients which is in practice the number * of stored coefficients. */ @@ -188,16 +184,7 @@ template class SparseMatrixBase : public EigenBase Derived& markAsRValue() { m_isRValue = true; return derived(); } SparseMatrixBase() : m_isRValue(false) { /* TODO check flags */ } - - inline Derived& operator=(const Derived& other) - { -// std::cout << "Derived& operator=(const Derived& other)\n"; -// if (other.isRValue()) -// derived().swap(other.const_cast_derived()); -// else - this->operator=(other); - return derived(); - } + template Derived& operator=(const ReturnByValue& other) @@ -207,10 +194,54 @@ template class SparseMatrixBase : public EigenBase } + template + inline Derived& operator=(const SparseMatrixBase& other) + { + return assign(other.derived()); + } + + inline Derived& operator=(const Derived& other) + { +// if (other.isRValue()) +// derived().swap(other.const_cast_derived()); +// else + return assign(other.derived()); + } + + protected: + + template + inline Derived& assign(const OtherDerived& other) + { + const bool transpose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); + const Index outerSize = (int(OtherDerived::Flags) & RowMajorBit) ? other.rows() : other.cols(); + if ((!transpose) && other.isRValue()) + { + // eval without temporary + derived().resize(other.rows(), other.cols()); + derived().setZero(); + derived().reserve((std::max)(this->rows(),this->cols())*2); + for (Index j=0; j inline void assignGeneric(const OtherDerived& other) { -// std::cout << "Derived& operator=(const MatrixBase& other)\n"; //const bool transpose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); eigen_assert(( ((internal::traits::SupportedAccessPatterns&OuterRandomAccessPattern)==OuterRandomAccessPattern) || (!((Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit)))) && @@ -230,8 +261,7 @@ template class SparseMatrixBase : public EigenBase for (typename OtherDerived::InnerIterator it(other.derived(), j); it; ++it) { Scalar v = it.value(); - if (v!=Scalar(0)) - temp.insertBackByOuterInner(Flip?it.index():j,Flip?j:it.index()) = v; + temp.insertBackByOuterInner(Flip?it.index():j,Flip?j:it.index()) = v; } } temp.finalize(); @@ -239,54 +269,23 @@ template class SparseMatrixBase : public EigenBase derived() = temp.markAsRValue(); } - - template - inline Derived& operator=(const SparseMatrixBase& other) - { -// std::cout << typeid(OtherDerived).name() << "\n"; -// std::cout << Flags << " " << OtherDerived::Flags << "\n"; - const bool transpose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); -// std::cout << "eval transpose = " << transpose << "\n"; - const Index outerSize = (int(OtherDerived::Flags) & RowMajorBit) ? other.rows() : other.cols(); - if ((!transpose) && other.isRValue()) - { - // eval without temporary - derived().resize(other.rows(), other.cols()); - derived().setZero(); - derived().reserve((std::max)(this->rows(),this->cols())*2); - for (Index j=0; j inline Derived& operator=(const SparseSparseProduct& product); - template - inline void _experimentalNewProduct(const Lhs& lhs, const Rhs& rhs); - friend std::ostream & operator << (std::ostream & s, const SparseMatrixBase& m) { + typedef typename Derived::Nested Nested; + typedef typename internal::remove_all::type NestedCleaned; + if (Flags&RowMajorBit) { - for (Index row=0; row class SparseMatrixBase : public EigenBase } else { + const Nested nm(m.derived()); if (m.cols() == 1) { Index row = 0; - for (typename Derived::InnerIterator it(m.derived(), 0); it; ++it) + for (typename NestedCleaned::InnerIterator it(nm.derived(), 0); it; ++it) { for ( ; row class SparseMatrixBase : public EigenBase } else { - SparseMatrix trans = m.derived(); - s << trans; + SparseMatrix trans = m; + s << static_cast >&>(trans); } } return s; } -// const SparseCwiseUnaryOp::Scalar>,Derived> operator-() const; - -// template -// const CwiseBinaryOp::Scalar>, Derived, OtherDerived> -// operator+(const SparseMatrixBase &other) const; - -// template -// const CwiseBinaryOp::Scalar>, Derived, OtherDerived> -// operator-(const SparseMatrixBase &other) const; - template Derived& operator+=(const SparseMatrixBase& other); template Derived& operator-=(const SparseMatrixBase& other); -// template -// Derived& operator+=(const Flagged, 0, EvalBeforeNestingBit | EvalBeforeAssigningBit>& other); - Derived& operator*=(const Scalar& other); Derived& operator/=(const Scalar& other); @@ -358,16 +345,6 @@ template class SparseMatrixBase : public EigenBase EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE cwiseProduct(const MatrixBase &other) const; -// const SparseCwiseUnaryOp::Scalar>, Derived> -// operator*(const Scalar& scalar) const; -// const SparseCwiseUnaryOp::Scalar>, Derived> -// operator/(const Scalar& scalar) const; - -// inline friend const SparseCwiseUnaryOp::Scalar>, Derived> -// operator*(const Scalar& scalar, const SparseMatrixBase& matrix) -// { return matrix*scalar; } - - // sparse * sparse template const typename SparseSparseProductReturnType::Type @@ -394,6 +371,12 @@ template class SparseMatrixBase : public EigenBase template const typename SparseDenseProductReturnType::Type operator*(const MatrixBase &other) const; + + /** \returns an expression of P H P^-1 where H is the matrix represented by \c *this */ + SparseSymmetricPermutationProduct twistedBy(const PermutationMatrix& perm) const + { + return SparseSymmetricPermutationProduct(derived(), perm); + } template Derived& operator*=(const SparseMatrixBase& other); @@ -407,8 +390,6 @@ template class SparseMatrixBase : public EigenBase // deprecated template void solveTriangularInPlace(MatrixBase& other) const; -// template -// void solveTriangularInPlace(SparseMatrixBase& other) const; #endif // EIGEN2_SUPPORT template @@ -421,12 +402,9 @@ template class SparseMatrixBase : public EigenBase template Scalar dot(const SparseMatrixBase& other) const; RealScalar squaredNorm() const; RealScalar norm() const; -// const PlainObject normalized() const; -// void normalize(); Transpose transpose() { return derived(); } const Transpose transpose() const { return derived(); } - // void transposeInPlace(); const AdjointReturnType adjoint() const { return transpose(); } // sub-vector @@ -442,77 +420,14 @@ template class SparseMatrixBase : public EigenBase const SparseInnerVectorSet subrows(Index start, Index size) const; SparseInnerVectorSet subcols(Index start, Index size); const SparseInnerVectorSet subcols(Index start, Index size) const; + + SparseInnerVectorSet middleRows(Index start, Index size); + const SparseInnerVectorSet middleRows(Index start, Index size) const; + SparseInnerVectorSet middleCols(Index start, Index size); + const SparseInnerVectorSet middleCols(Index start, Index size) const; SparseInnerVectorSet innerVectors(Index outerStart, Index outerSize); const SparseInnerVectorSet innerVectors(Index outerStart, Index outerSize) const; -// typename BlockReturnType::Type block(int startRow, int startCol, int blockRows, int blockCols); -// const typename BlockReturnType::Type -// block(int startRow, int startCol, int blockRows, int blockCols) const; -// -// typename BlockReturnType::SubVectorType segment(int start, int size); -// const typename BlockReturnType::SubVectorType segment(int start, int size) const; -// -// typename BlockReturnType::SubVectorType start(int size); -// const typename BlockReturnType::SubVectorType start(int size) const; -// -// typename BlockReturnType::SubVectorType end(int size); -// const typename BlockReturnType::SubVectorType end(int size) const; -// -// template -// typename BlockReturnType::Type block(int startRow, int startCol); -// template -// const typename BlockReturnType::Type block(int startRow, int startCol) const; - -// template typename BlockReturnType::SubVectorType start(void); -// template const typename BlockReturnType::SubVectorType start() const; - -// template typename BlockReturnType::SubVectorType end(); -// template const typename BlockReturnType::SubVectorType end() const; - -// template typename BlockReturnType::SubVectorType segment(int start); -// template const typename BlockReturnType::SubVectorType segment(int start) const; - -// Diagonal diagonal(); -// const Diagonal diagonal() const; - -// template Part part(); -// template const Part part() const; - - -// static const ConstantReturnType Constant(int rows, int cols, const Scalar& value); -// static const ConstantReturnType Constant(int size, const Scalar& value); -// static const ConstantReturnType Constant(const Scalar& value); - -// template -// static const CwiseNullaryOp NullaryExpr(int rows, int cols, const CustomNullaryOp& func); -// template -// static const CwiseNullaryOp NullaryExpr(int size, const CustomNullaryOp& func); -// template -// static const CwiseNullaryOp NullaryExpr(const CustomNullaryOp& func); - -// static const ConstantReturnType Zero(int rows, int cols); -// static const ConstantReturnType Zero(int size); -// static const ConstantReturnType Zero(); -// static const ConstantReturnType Ones(int rows, int cols); -// static const ConstantReturnType Ones(int size); -// static const ConstantReturnType Ones(); -// static const IdentityReturnType Identity(); -// static const IdentityReturnType Identity(int rows, int cols); -// static const BasisReturnType Unit(int size, int i); -// static const BasisReturnType Unit(int i); -// static const BasisReturnType UnitX(); -// static const BasisReturnType UnitY(); -// static const BasisReturnType UnitZ(); -// static const BasisReturnType UnitW(); - -// const DiagonalMatrix asDiagonal() const; - -// Derived& setConstant(const Scalar& value); -// Derived& setZero(); -// Derived& setOnes(); -// Derived& setRandom(); -// Derived& setIdentity(); - /** \internal use operator= */ template void evalTo(MatrixBase& dst) const @@ -537,37 +452,6 @@ template class SparseMatrixBase : public EigenBase bool isApprox(const MatrixBase& other, RealScalar prec = NumTraits::dummy_precision()) const { return toDense().isApprox(other,prec); } -// bool isMuchSmallerThan(const RealScalar& other, -// RealScalar prec = NumTraits::dummy_precision()) const; -// template -// bool isMuchSmallerThan(const MatrixBase& other, -// RealScalar prec = NumTraits::dummy_precision()) const; - -// bool isApproxToConstant(const Scalar& value, RealScalar prec = NumTraits::dummy_precision()) const; -// bool isZero(RealScalar prec = NumTraits::dummy_precision()) const; -// bool isOnes(RealScalar prec = NumTraits::dummy_precision()) const; -// bool isIdentity(RealScalar prec = NumTraits::dummy_precision()) const; -// bool isDiagonal(RealScalar prec = NumTraits::dummy_precision()) const; - -// bool isUpper(RealScalar prec = NumTraits::dummy_precision()) const; -// bool isLower(RealScalar prec = NumTraits::dummy_precision()) const; - -// template -// bool isOrthogonal(const MatrixBase& other, -// RealScalar prec = NumTraits::dummy_precision()) const; -// bool isUnitary(RealScalar prec = NumTraits::dummy_precision()) const; - -// template -// inline bool operator==(const MatrixBase& other) const -// { return (cwise() == other).all(); } - -// template -// inline bool operator!=(const MatrixBase& other) const -// { return (cwise() != other).any(); } - - -// template -// const SparseCwiseUnaryOp::Scalar, NewType>, Derived> cast() const; /** \returns the matrix or vector obtained by evaluating this expression. * @@ -577,130 +461,13 @@ template class SparseMatrixBase : public EigenBase inline const typename internal::eval::type eval() const { return typename internal::eval::type(derived()); } -// template -// void swap(MatrixBase const & other); - -// template -// const SparseFlagged marked() const; -// const Flagged lazy() const; - - /** \returns number of elements to skip to pass from one row (resp. column) to another - * for a row-major (resp. column-major) matrix. - * Combined with coeffRef() and the \ref flags flags, it allows a direct access to the data - * of the underlying matrix. - */ -// inline int stride(void) const { return derived().stride(); } - -// FIXME -// ConjugateReturnType conjugate() const; -// const RealReturnType real() const; -// const ImagReturnType imag() const; - -// template -// const SparseCwiseUnaryOp unaryExpr(const CustomUnaryOp& func = CustomUnaryOp()) const; - -// template -// const CwiseBinaryOp -// binaryExpr(const MatrixBase &other, const CustomBinaryOp& func = CustomBinaryOp()) const; - - Scalar sum() const; -// Scalar trace() const; - -// typename internal::traits::Scalar minCoeff() const; -// typename internal::traits::Scalar maxCoeff() const; - -// typename internal::traits::Scalar minCoeff(int* row, int* col = 0) const; -// typename internal::traits::Scalar maxCoeff(int* row, int* col = 0) const; - -// template -// typename internal::result_of::Scalar)>::type -// redux(const BinaryOp& func) const; - -// template -// void visit(Visitor& func) const; - - -// const SparseCwise cwise() const; -// SparseCwise cwise(); - -// inline const WithFormat format(const IOFormat& fmt) const; - -/////////// Array module /////////// - /* - bool all(void) const; - bool any(void) const; - - const VectorwiseOp rowwise() const; - const VectorwiseOp colwise() const; - - static const CwiseNullaryOp,Derived> Random(int rows, int cols); - static const CwiseNullaryOp,Derived> Random(int size); - static const CwiseNullaryOp,Derived> Random(); - - template - const Select - select(const MatrixBase& thenMatrix, - const MatrixBase& elseMatrix) const; - - template - inline const Select - select(const MatrixBase& thenMatrix, typename ThenDerived::Scalar elseScalar) const; - - template - inline const Select - select(typename ElseDerived::Scalar thenScalar, const MatrixBase& elseMatrix) const; - - template RealScalar lpNorm() const; - */ - - -// template -// Scalar dot(const MatrixBase& other) const -// { -// EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) -// EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) -// EIGEN_STATIC_ASSERT((internal::is_same::value), -// YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) -// -// eigen_assert(derived().size() == other.size()); -// // short version, but the assembly looks more complicated because -// // of the CwiseBinaryOp iterator complexity -// // return res = (derived().cwise() * other.derived().conjugate()).sum(); -// -// // optimized, generic version -// typename Derived::InnerIterator i(derived(),0); -// typename OtherDerived::InnerIterator j(other.derived(),0); -// Scalar res = 0; -// while (i && j) -// { -// if (i.index()==j.index()) -// { -// // std::cerr << i.value() << " * " << j.value() << "\n"; -// res += i.value() * internal::conj(j.value()); -// ++i; ++j; -// } -// else if (i.index() +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSE_PERMUTATION_H +#define EIGEN_SPARSE_PERMUTATION_H + +// This file implements sparse * permutation products + +namespace Eigen { + +namespace internal { + +template +struct traits > +{ + typedef typename remove_all::type MatrixTypeNestedCleaned; + typedef typename MatrixTypeNestedCleaned::Scalar Scalar; + typedef typename MatrixTypeNestedCleaned::Index Index; + enum { + SrcStorageOrder = MatrixTypeNestedCleaned::Flags&RowMajorBit ? RowMajor : ColMajor, + MoveOuter = SrcStorageOrder==RowMajor ? Side==OnTheLeft : Side==OnTheRight + }; + + typedef typename internal::conditional, + SparseMatrix >::type ReturnType; +}; + +template +struct permut_sparsematrix_product_retval + : public ReturnByValue > +{ + typedef typename remove_all::type MatrixTypeNestedCleaned; + typedef typename MatrixTypeNestedCleaned::Scalar Scalar; + typedef typename MatrixTypeNestedCleaned::Index Index; + + enum { + SrcStorageOrder = MatrixTypeNestedCleaned::Flags&RowMajorBit ? RowMajor : ColMajor, + MoveOuter = SrcStorageOrder==RowMajor ? Side==OnTheLeft : Side==OnTheRight + }; + + permut_sparsematrix_product_retval(const PermutationType& perm, const MatrixType& matrix) + : m_permutation(perm), m_matrix(matrix) + {} + + inline int rows() const { return m_matrix.rows(); } + inline int cols() const { return m_matrix.cols(); } + + template inline void evalTo(Dest& dst) const + { + if(MoveOuter) + { + SparseMatrix tmp(m_matrix.rows(), m_matrix.cols()); + VectorXi sizes(m_matrix.outerSize()); + for(Index j=0; j tmp(m_matrix.rows(), m_matrix.cols()); + VectorXi sizes(tmp.outerSize()); + sizes.setZero(); + PermutationMatrix perm; + if((Side==OnTheLeft) ^ Transposed) + perm = m_permutation; + else + perm = m_permutation.transpose(); + + for(Index j=0; j +inline const internal::permut_sparsematrix_product_retval, SparseDerived, OnTheRight, false> +operator*(const SparseMatrixBase& matrix, const PermutationBase& perm) +{ + return internal::permut_sparsematrix_product_retval, SparseDerived, OnTheRight, false>(perm, matrix.derived()); +} + +/** \returns the matrix with the permutation applied to the rows + */ +template +inline const internal::permut_sparsematrix_product_retval, SparseDerived, OnTheLeft, false> +operator*( const PermutationBase& perm, const SparseMatrixBase& matrix) +{ + return internal::permut_sparsematrix_product_retval, SparseDerived, OnTheLeft, false>(perm, matrix.derived()); +} + + + +/** \returns the matrix with the inverse permutation applied to the columns. + */ +template +inline const internal::permut_sparsematrix_product_retval, SparseDerived, OnTheRight, true> +operator*(const SparseMatrixBase& matrix, const Transpose >& tperm) +{ + return internal::permut_sparsematrix_product_retval, SparseDerived, OnTheRight, true>(tperm.nestedPermutation(), matrix.derived()); +} + +/** \returns the matrix with the inverse permutation applied to the rows. + */ +template +inline const internal::permut_sparsematrix_product_retval, SparseDerived, OnTheLeft, true> +operator*(const Transpose >& tperm, const SparseMatrixBase& matrix) +{ + return internal::permut_sparsematrix_product_retval, SparseDerived, OnTheLeft, true>(tperm.nestedPermutation(), matrix.derived()); +} + +} // end namespace Eigen + +#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseProduct.h similarity index 68% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseProduct.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseProduct.h index 1c1f54706..813dbf624 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseProduct.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSEPRODUCT_H #define EIGEN_SPARSEPRODUCT_H +namespace Eigen { + template struct SparseSparseProductReturnType { @@ -38,11 +40,11 @@ struct SparseSparseProductReturnType typedef typename internal::conditional, - const typename internal::nested::type>::type LhsNested; + typename internal::nested::type>::type LhsNested; typedef typename internal::conditional, - const typename internal::nested::type>::type RhsNested; + typename internal::nested::type>::type RhsNested; typedef SparseSparseProduct Type; }; @@ -106,9 +108,42 @@ class SparseSparseProduct : internal::no_assignment_operator, template EIGEN_STRONG_INLINE SparseSparseProduct(const Lhs& lhs, const Rhs& rhs) - : m_lhs(lhs), m_rhs(rhs) + : m_lhs(lhs), m_rhs(rhs), m_tolerance(0), m_conservative(true) { - eigen_assert(lhs.cols() == rhs.rows()); + init(); + } + + template + EIGEN_STRONG_INLINE SparseSparseProduct(const Lhs& lhs, const Rhs& rhs, RealScalar tolerance) + : m_lhs(lhs), m_rhs(rhs), m_tolerance(tolerance), m_conservative(false) + { + init(); + } + + SparseSparseProduct pruned(Scalar reference = 0, RealScalar epsilon = NumTraits::dummy_precision()) const + { + return SparseSparseProduct(m_lhs,m_rhs,internal::abs(reference)*epsilon); + } + + template + void evalTo(Dest& result) const + { + if(m_conservative) + internal::conservative_sparse_sparse_product_selector<_LhsNested, _RhsNested, Dest>::run(lhs(),rhs(),result); + else + internal::sparse_sparse_product_with_pruning_selector<_LhsNested, _RhsNested, Dest>::run(lhs(),rhs(),result,m_tolerance); + } + + EIGEN_STRONG_INLINE Index rows() const { return m_lhs.rows(); } + EIGEN_STRONG_INLINE Index cols() const { return m_rhs.cols(); } + + EIGEN_STRONG_INLINE const _LhsNested& lhs() const { return m_lhs; } + EIGEN_STRONG_INLINE const _RhsNested& rhs() const { return m_rhs; } + + protected: + void init() + { + eigen_assert(m_lhs.cols() == m_rhs.rows()); enum { ProductIsValid = _LhsNested::ColsAtCompileTime==Dynamic @@ -127,15 +162,40 @@ class SparseSparseProduct : internal::no_assignment_operator, EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) } - EIGEN_STRONG_INLINE Index rows() const { return m_lhs.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_rhs.cols(); } - - EIGEN_STRONG_INLINE const _LhsNested& lhs() const { return m_lhs; } - EIGEN_STRONG_INLINE const _RhsNested& rhs() const { return m_rhs; } - - protected: LhsNested m_lhs; RhsNested m_rhs; + RealScalar m_tolerance; + bool m_conservative; }; +// sparse = sparse * sparse +template +template +inline Derived& SparseMatrixBase::operator=(const SparseSparseProduct& product) +{ + product.evalTo(derived()); + return derived(); +} + +/** \returns an expression of the product of two sparse matrices. + * By default a conservative product preserving the symbolic non zeros is performed. + * The automatic pruning of the small values can be achieved by calling the pruned() function + * in which case a totally different product algorithm is employed: + * \code + * C = (A*B).pruned(); // supress numerical zeros (exact) + * C = (A*B).pruned(ref); + * C = (A*B).pruned(ref,epsilon); + * \endcode + * where \c ref is a meaningful non zero reference value. + * */ +template +template +inline const typename SparseSparseProductReturnType::Type +SparseMatrixBase::operator*(const SparseMatrixBase &other) const +{ + return typename SparseSparseProductReturnType::Type(derived(), other.derived()); +} + +} // end namespace Eigen + #endif // EIGEN_SPARSEPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseRedux.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseRedux.h similarity index 97% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseRedux.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseRedux.h index afc49de7a..73fb9a318 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseRedux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseRedux.h @@ -25,12 +25,14 @@ #ifndef EIGEN_SPARSEREDUX_H #define EIGEN_SPARSEREDUX_H +namespace Eigen { + template typename internal::traits::Scalar SparseMatrixBase::sum() const { eigen_assert(rows()>0 && cols()>0 && "you are using a non initialized matrix"); - Scalar res = 0; + Scalar res(0); for (Index j=0; j::sum() const return Matrix::Map(&m_data.value(0), m_data.size()).sum(); } +} // end namespace Eigen + #endif // EIGEN_SPARSEREDUX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSelfAdjointView.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSelfAdjointView.h similarity index 77% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSelfAdjointView.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSelfAdjointView.h index d82044c78..c925a894d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseSelfAdjointView.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSelfAdjointView.h @@ -25,8 +25,10 @@ #ifndef EIGEN_SPARSE_SELFADJOINTVIEW_H #define EIGEN_SPARSE_SELFADJOINTVIEW_H -/** \class SparseSelfAdjointView - * +namespace Eigen { + +/** \ingroup SparseCore_Module + * \class SparseSelfAdjointView * * \brief Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix. * @@ -45,9 +47,6 @@ class SparseSelfAdjointTimeDenseProduct; template class DenseTimeSparseSelfAdjointProduct; -template -class SparseSymmetricPermutationProduct; - namespace internal { template @@ -106,9 +105,6 @@ template class SparseSelfAdjointView * * \returns a reference to \c *this * - * Note that it is faster to set alpha=0 than initializing the matrix to zero - * and then keep the default value alpha=1. - * * To perform \f$ this = this + \alpha ( u^* u ) \f$ you can simply * call this function with u.adjoint(). */ @@ -116,21 +112,21 @@ template class SparseSelfAdjointView SparseSelfAdjointView& rankUpdate(const SparseMatrixBase& u, Scalar alpha = Scalar(1)); /** \internal triggered by sparse_matrix = SparseSelfadjointView; */ - template void evalTo(SparseMatrix& _dest) const + template void evalTo(SparseMatrix& _dest) const { internal::permute_symm_to_fullsymm(m_matrix, _dest); } - template void evalTo(DynamicSparseMatrix& _dest) const + template void evalTo(DynamicSparseMatrix& _dest) const { // TODO directly evaluate into _dest; - SparseMatrix tmp(_dest.rows(),_dest.cols()); + SparseMatrix tmp(_dest.rows(),_dest.cols()); internal::permute_symm_to_fullsymm(m_matrix, tmp); _dest = tmp; } - /** \returns an expression of P^-1 H P */ - SparseSymmetricPermutationProduct<_MatrixTypeNested,UpLo> twistedBy(const PermutationMatrix& perm) const + /** \returns an expression of P H P^-1 */ + SparseSymmetricPermutationProduct<_MatrixTypeNested,UpLo> twistedBy(const PermutationMatrix& perm) const { return SparseSymmetricPermutationProduct<_MatrixTypeNested,UpLo>(m_matrix, perm); } @@ -141,6 +137,20 @@ template class SparseSelfAdjointView permutedMatrix.evalTo(*this); return *this; } + + + SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src) + { + PermutationMatrix pnull; + return *this = src.twistedBy(pnull); + } + + template + SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src) + { + PermutationMatrix pnull; + return *this = src.twistedBy(pnull); + } // const SparseLLT llt() const; @@ -148,7 +158,7 @@ template class SparseSelfAdjointView protected: - const typename MatrixType::Nested m_matrix; + typename MatrixType::Nested m_matrix; mutable VectorI m_countPerRow; mutable VectorI m_countPerCol; }; @@ -230,12 +240,15 @@ class SparseSelfAdjointTimeDenseProduct for (Index j=0; j dest_j(dest.row(LhsIsRowMajor ? j : 0)); for(; (ProcessFirstHalf ? i && i.index() < j : i) ; ++i) { Index a = LhsIsRowMajor ? j : i.index(); @@ -300,7 +313,7 @@ void permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrixj) || (UpLo==Upper && ic) || ( UpLo==Upper && rj) || (UpLo==Upper && ic) || ( (UpLo&Upper)==Upper && r -void permute_symm_to_symm(const MatrixType& mat, SparseMatrix& _dest, const typename MatrixType::Index* perm) +template +void permute_symm_to_symm(const MatrixType& mat, SparseMatrix& _dest, const typename MatrixType::Index* perm) { typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; - typedef SparseMatrix Dest; - Dest& dest(_dest.derived()); + SparseMatrix& dest(_dest.derived()); typedef Matrix VectorI; - //internal::conj_if cj; + enum { + SrcOrder = MatrixType::IsRowMajor ? RowMajor : ColMajor, + StorageOrderMatch = int(SrcOrder) == int(DstOrder), + DstUpLo = DstOrder==RowMajor ? (_DstUpLo==Upper ? Lower : Upper) : _DstUpLo, + SrcUpLo = SrcOrder==RowMajor ? (_SrcUpLo==Upper ? Lower : Upper) : _SrcUpLo + }; Index size = mat.rows(); VectorI count(size); @@ -379,37 +412,40 @@ void permute_symm_to_symm(const MatrixType& mat, SparseMatrixj)) + if((int(SrcUpLo)==int(Lower) && ij)) continue; Index ip = perm ? perm[i] : i; - count[DstUpLo==Lower ? (std::min)(ip,jp) : (std::max)(ip,jp)]++; + count[int(DstUpLo)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++; } } - dest._outerIndexPtr()[0] = 0; + dest.outerIndexPtr()[0] = 0; for(Index j=0; jj)) + if((int(SrcUpLo)==int(Lower) && ij)) continue; + Index jp = perm ? perm[j] : j; Index ip = perm? perm[i] : i; - Index k = count[DstUpLo==Lower ? (std::min)(ip,jp) : (std::max)(ip,jp)]++; - dest._innerIndexPtr()[k] = DstUpLo==Lower ? (std::max)(ip,jp) : (std::min)(ip,jp); - if((DstUpLo==Lower && ipjp)) - dest._valuePtr()[k] = conj(it.value()); + Index k = count[int(DstUpLo)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++; + dest.innerIndexPtr()[k] = int(DstUpLo)==int(Lower) ? (std::max)(ip,jp) : (std::min)(ip,jp); + + if(!StorageOrderMatch) std::swap(ip,jp); + if( ((int(DstUpLo)==int(Lower) && ipjp))) + dest.valuePtr()[k] = conj(it.value()); else - dest._valuePtr()[k] = it.value(); + dest.valuePtr()[k] = it.value(); } } } @@ -420,10 +456,12 @@ template class SparseSymmetricPermutationProduct : public EigenBase > { - typedef PermutationMatrix Perm; public: typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::Index Index; + protected: + typedef PermutationMatrix Perm; + public: typedef Matrix VectorI; typedef typename MatrixType::Nested MatrixTypeNested; typedef typename internal::remove_all::type _MatrixTypeNested; @@ -435,7 +473,8 @@ class SparseSymmetricPermutationProduct inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } - template void evalTo(SparseMatrix& _dest) const + template + void evalTo(SparseMatrix& _dest) const { internal::permute_symm_to_fullsymm(m_matrix,_dest,m_perm.indices().data()); } @@ -446,9 +485,11 @@ class SparseSymmetricPermutationProduct } protected: - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; const Perm& m_perm; }; +} // end namespace Eigen + #endif // EIGEN_SPARSE_SELFADJOINTVIEW_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSparseProductWithPruning.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSparseProductWithPruning.h new file mode 100644 index 000000000..abd4fda82 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSparseProductWithPruning.h @@ -0,0 +1,164 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H +#define EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H + +namespace Eigen { + +namespace internal { + + +// perform a pseudo in-place sparse * sparse product assuming all matrices are col major +template +static void sparse_sparse_product_with_pruning_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, typename ResultType::RealScalar tolerance) +{ + // return sparse_sparse_product_with_pruning_impl2(lhs,rhs,res); + + typedef typename remove_all::type::Scalar Scalar; + typedef typename remove_all::type::Index Index; + + // make sure to call innerSize/outerSize since we fake the storage order. + Index rows = lhs.innerSize(); + Index cols = rhs.outerSize(); + //int size = lhs.outerSize(); + eigen_assert(lhs.outerSize() == rhs.innerSize()); + + // allocate a temporary buffer + AmbiVector tempVector(rows); + + // estimate the number of non zero entries + // given a rhs column containing Y non zeros, we assume that the respective Y columns + // of the lhs differs in average of one non zeros, thus the number of non zeros for + // the product of a rhs column with the lhs is X+Y where X is the average number of non zero + // per column of the lhs. + // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs) + Index estimated_nnz_prod = lhs.nonZeros() + rhs.nonZeros(); + + // mimics a resizeByInnerOuter: + if(ResultType::IsRowMajor) + res.resize(cols, rows); + else + res.resize(rows, cols); + + res.reserve(estimated_nnz_prod); + double ratioColRes = double(estimated_nnz_prod)/double(lhs.rows()*rhs.cols()); + for (Index j=0; j::Iterator it(tempVector,tolerance); it; ++it) + res.insertBackByOuterInner(j,it.index()) = it.value(); + } + res.finalize(); +} + +template::Flags&RowMajorBit, + int RhsStorageOrder = traits::Flags&RowMajorBit, + int ResStorageOrder = traits::Flags&RowMajorBit> +struct sparse_sparse_product_with_pruning_selector; + +template +struct sparse_sparse_product_with_pruning_selector +{ + typedef typename traits::type>::Scalar Scalar; + typedef typename ResultType::RealScalar RealScalar; + + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, RealScalar tolerance) + { + typename remove_all::type _res(res.rows(), res.cols()); + internal::sparse_sparse_product_with_pruning_impl(lhs, rhs, _res, tolerance); + res.swap(_res); + } +}; + +template +struct sparse_sparse_product_with_pruning_selector +{ + typedef typename ResultType::RealScalar RealScalar; + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, RealScalar tolerance) + { + // we need a col-major matrix to hold the result + typedef SparseMatrix SparseTemporaryType; + SparseTemporaryType _res(res.rows(), res.cols()); + internal::sparse_sparse_product_with_pruning_impl(lhs, rhs, _res, tolerance); + res = _res; + } +}; + +template +struct sparse_sparse_product_with_pruning_selector +{ + typedef typename ResultType::RealScalar RealScalar; + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, RealScalar tolerance) + { + // let's transpose the product to get a column x column product + typename remove_all::type _res(res.rows(), res.cols()); + internal::sparse_sparse_product_with_pruning_impl(rhs, lhs, _res, tolerance); + res.swap(_res); + } +}; + +template +struct sparse_sparse_product_with_pruning_selector +{ + typedef typename ResultType::RealScalar RealScalar; + static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, RealScalar tolerance) + { + typedef SparseMatrix ColMajorMatrix; + ColMajorMatrix colLhs(lhs); + ColMajorMatrix colRhs(rhs); + internal::sparse_sparse_product_with_pruning_impl(colLhs, colRhs, res, tolerance); + + // let's transpose the product to get a column x column product +// typedef SparseMatrix SparseTemporaryType; +// SparseTemporaryType _res(res.cols(), res.rows()); +// sparse_sparse_product_with_pruning_impl(rhs, lhs, _res); +// res = _res.transpose(); + } +}; + +// NOTE the 2 others cases (col row *) must never occur since they are caught +// by ProductReturnType which transforms it to (col col *) by evaluating rhs. + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTranspose.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h similarity index 73% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTranspose.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h index 2aea2fa32..07d9e0bbd 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseTranspose.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSETRANSPOSE_H #define EIGEN_SPARSETRANSPOSE_H +namespace Eigen { + template class TransposeImpl : public SparseMatrixBase > { @@ -39,17 +41,21 @@ template class TransposeImpl inline Index nonZeros() const { return derived().nestedExpression().nonZeros(); } }; +// NOTE: VC10 trigger an ICE if don't put typename TransposeImpl:: in front of Index, +// a typedef typename TransposeImpl::Index Index; +// does not fix the issue. +// An alternative is to define the nested class in the parent class itself. template class TransposeImpl::InnerIterator : public _MatrixTypeNested::InnerIterator { typedef typename _MatrixTypeNested::InnerIterator Base; public: - EIGEN_STRONG_INLINE InnerIterator(const TransposeImpl& trans, Index outer) + EIGEN_STRONG_INLINE InnerIterator(const TransposeImpl& trans, typename TransposeImpl::Index outer) : Base(trans.derived().nestedExpression(), outer) {} - inline Index row() const { return Base::col(); } - inline Index col() const { return Base::row(); } + inline typename TransposeImpl::Index row() const { return Base::col(); } + inline typename TransposeImpl::Index col() const { return Base::row(); } }; template class TransposeImpl::ReverseInnerIterator @@ -58,11 +64,13 @@ template class TransposeImpl::ReverseInn typedef typename _MatrixTypeNested::ReverseInnerIterator Base; public: - EIGEN_STRONG_INLINE ReverseInnerIterator(const TransposeImpl& xpr, Index outer) + EIGEN_STRONG_INLINE ReverseInnerIterator(const TransposeImpl& xpr, typename TransposeImpl::Index outer) : Base(xpr.derived().nestedExpression(), outer) {} - inline Index row() const { return Base::col(); } - inline Index col() const { return Base::row(); } + inline typename TransposeImpl::Index row() const { return Base::col(); } + inline typename TransposeImpl::Index col() const { return Base::row(); } }; +} // end namespace Eigen + #endif // EIGEN_SPARSETRANSPOSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTriangularView.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTriangularView.h new file mode 100644 index 000000000..59aab5756 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTriangularView.h @@ -0,0 +1,179 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2009 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSE_TRIANGULARVIEW_H +#define EIGEN_SPARSE_TRIANGULARVIEW_H + +namespace Eigen { + +namespace internal { + +template +struct traits > +: public traits +{}; + +} // namespace internal + +template class SparseTriangularView + : public SparseMatrixBase > +{ + enum { SkipFirst = ((Mode&Lower) && !(MatrixType::Flags&RowMajorBit)) + || ((Mode&Upper) && (MatrixType::Flags&RowMajorBit)), + SkipLast = !SkipFirst, + HasUnitDiag = (Mode&UnitDiag) ? 1 : 0 + }; + + public: + + EIGEN_SPARSE_PUBLIC_INTERFACE(SparseTriangularView) + + class InnerIterator; + class ReverseInnerIterator; + + inline Index rows() const { return m_matrix.rows(); } + inline Index cols() const { return m_matrix.cols(); } + + typedef typename MatrixType::Nested MatrixTypeNested; + typedef typename internal::remove_reference::type MatrixTypeNestedNonRef; + typedef typename internal::remove_all::type MatrixTypeNestedCleaned; + + inline SparseTriangularView(const MatrixType& matrix) : m_matrix(matrix) {} + + /** \internal */ + inline const MatrixTypeNestedCleaned& nestedExpression() const { return m_matrix; } + + template + typename internal::plain_matrix_type_column_major::type + solve(const MatrixBase& other) const; + + template void solveInPlace(MatrixBase& other) const; + template void solveInPlace(SparseMatrixBase& other) const; + + protected: + MatrixTypeNested m_matrix; +}; + +template +class SparseTriangularView::InnerIterator : public MatrixTypeNestedCleaned::InnerIterator +{ + typedef typename MatrixTypeNestedCleaned::InnerIterator Base; + public: + + EIGEN_STRONG_INLINE InnerIterator(const SparseTriangularView& view, Index outer) + : Base(view.nestedExpression(), outer), m_returnOne(false) + { + if(SkipFirst) + { + while((*this) && (HasUnitDiag ? this->index()<=outer : this->index()=Base::outer())) + { + if((!SkipFirst) && Base::operator bool()) + Base::operator++(); + m_returnOne = true; + } + } + + EIGEN_STRONG_INLINE InnerIterator& operator++() + { + if(HasUnitDiag && m_returnOne) + m_returnOne = false; + else + { + Base::operator++(); + if(HasUnitDiag && (!SkipFirst) && ((!Base::operator bool()) || Base::index()>=Base::outer())) + { + if((!SkipFirst) && Base::operator bool()) + Base::operator++(); + m_returnOne = true; + } + } + return *this; + } + + inline Index row() const { return Base::row(); } + inline Index col() const { return Base::col(); } + inline Index index() const + { + if(HasUnitDiag && m_returnOne) return Base::outer(); + else return Base::index(); + } + inline Scalar value() const + { + if(HasUnitDiag && m_returnOne) return Scalar(1); + else return Base::value(); + } + + EIGEN_STRONG_INLINE operator bool() const + { + if(HasUnitDiag && m_returnOne) + return true; + return (SkipFirst ? Base::operator bool() : (Base::operator bool() && this->index() <= this->outer())); + } + protected: + bool m_returnOne; +}; + +template +class SparseTriangularView::ReverseInnerIterator : public MatrixTypeNestedCleaned::ReverseInnerIterator +{ + typedef typename MatrixTypeNestedCleaned::ReverseInnerIterator Base; + public: + + EIGEN_STRONG_INLINE ReverseInnerIterator(const SparseTriangularView& view, Index outer) + : Base(view.nestedExpression(), outer) + { + eigen_assert((!HasUnitDiag) && "ReverseInnerIterator does not support yet triangular views with a unit diagonal"); + if(SkipLast) + while((*this) && this->index()>outer) + --(*this); + } + + EIGEN_STRONG_INLINE InnerIterator& operator--() + { Base::operator--(); return *this; } + + inline Index row() const { return Base::row(); } + inline Index col() const { return Base::col(); } + + EIGEN_STRONG_INLINE operator bool() const + { + return SkipLast ? Base::operator bool() : (Base::operator bool() && this->index() >= this->outer()); + } +}; + +template +template +inline const SparseTriangularView +SparseMatrixBase::triangularView() const +{ + return derived(); +} + +} // end namespace Eigen + +#endif // EIGEN_SPARSE_TRIANGULARVIEW_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseUtil.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h similarity index 67% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseUtil.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h index db9ae98e7..050b65253 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseUtil.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSEUTIL_H #define EIGEN_SPARSEUTIL_H +namespace Eigen { + #ifdef NDEBUG #define EIGEN_DBG_SPARSE(X) #else @@ -58,22 +60,22 @@ EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, /=) #define _EIGEN_SPARSE_PUBLIC_INTERFACE(Derived, BaseClass) \ typedef BaseClass Base; \ - typedef typename Eigen::internal::traits::Scalar Scalar; \ + typedef typename Eigen::internal::traits::Scalar Scalar; \ typedef typename Eigen::NumTraits::Real RealScalar; \ - typedef typename Eigen::internal::nested::type Nested; \ - typedef typename Eigen::internal::traits::StorageKind StorageKind; \ - typedef typename Eigen::internal::traits::Index Index; \ - enum { RowsAtCompileTime = Eigen::internal::traits::RowsAtCompileTime, \ - ColsAtCompileTime = Eigen::internal::traits::ColsAtCompileTime, \ - Flags = Eigen::internal::traits::Flags, \ - CoeffReadCost = Eigen::internal::traits::CoeffReadCost, \ + typedef typename Eigen::internal::nested::type Nested; \ + typedef typename Eigen::internal::traits::StorageKind StorageKind; \ + typedef typename Eigen::internal::traits::Index Index; \ + enum { RowsAtCompileTime = Eigen::internal::traits::RowsAtCompileTime, \ + ColsAtCompileTime = Eigen::internal::traits::ColsAtCompileTime, \ + Flags = Eigen::internal::traits::Flags, \ + CoeffReadCost = Eigen::internal::traits::CoeffReadCost, \ SizeAtCompileTime = Base::SizeAtCompileTime, \ IsVectorAtCompileTime = Base::IsVectorAtCompileTime }; \ using Base::derived; \ using Base::const_cast_derived; #define EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) \ - _EIGEN_SPARSE_PUBLIC_INTERFACE(Derived, Eigen::SparseMatrixBase) + _EIGEN_SPARSE_PUBLIC_INTERFACE(Derived, Eigen::SparseMatrixBase) const int CoherentAccessPattern = 0x1; const int InnerRandomAccessPattern = 0x2 | CoherentAccessPattern; @@ -100,20 +102,43 @@ template class SparseDenseOuterProdu template struct SparseSparseProductReturnType; template::ColsAtCompileTime> struct DenseSparseProductReturnType; template::ColsAtCompileTime> struct SparseDenseProductReturnType; +template class SparseSymmetricPermutationProduct; namespace internal { -template struct eval -{ - typedef typename traits::Scalar _Scalar; - enum { - _Flags = traits::Flags - }; +template struct sparse_eval; +template struct eval + : public sparse_eval::RowsAtCompileTime,traits::ColsAtCompileTime> +{}; + +template struct sparse_eval { + typedef typename traits::Scalar _Scalar; + enum { _Flags = traits::Flags| RowMajorBit }; + public: + typedef SparseVector<_Scalar, _Flags> type; +}; + +template struct sparse_eval { + typedef typename traits::Scalar _Scalar; + enum { _Flags = traits::Flags & (~RowMajorBit) }; + public: + typedef SparseVector<_Scalar, _Flags> type; +}; + +template struct sparse_eval { + typedef typename traits::Scalar _Scalar; + enum { _Flags = traits::Flags }; public: typedef SparseMatrix<_Scalar, _Flags> type; }; +template struct sparse_eval { + typedef typename traits::Scalar _Scalar; + public: + typedef Matrix<_Scalar, 1, 1> type; +}; + template struct plain_matrix_type { typedef typename traits::Scalar _Scalar; @@ -127,4 +152,37 @@ template struct plain_matrix_type } // end namespace internal +/** \ingroup SparseCore_Module + * + * \class Triplet + * + * \brief A small structure to hold a non zero as a triplet (i,j,value). + * + * \sa SparseMatrix::setFromTriplets() + */ +template +class Triplet +{ +public: + Triplet() : m_row(0), m_col(0), m_value(0) {} + + Triplet(const Index& i, const Index& j, const Scalar& v = Scalar(0)) + : m_row(i), m_col(j), m_value(v) + {} + + /** \returns the row index of the element */ + const Index& row() const { return m_row; } + + /** \returns the column index of the element */ + const Index& col() const { return m_col; } + + /** \returns the value of the element */ + const Scalar& value() const { return m_value; } +protected: + Index m_row, m_col; + Scalar m_value; +}; + +} // end namespace Eigen + #endif // EIGEN_SPARSEUTIL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseVector.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h similarity index 70% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseVector.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h index ce4bb51a2..e81347705 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h @@ -25,7 +25,10 @@ #ifndef EIGEN_SPARSEVECTOR_H #define EIGEN_SPARSEVECTOR_H -/** \class SparseVector +namespace Eigen { + +/** \ingroup SparseCore_Module + * \class SparseVector * * \brief a sparse vector class * @@ -46,13 +49,13 @@ struct traits > typedef Sparse StorageKind; typedef MatrixXpr XprKind; enum { - IsColVector = _Options & RowMajorBit ? 0 : 1, + IsColVector = (_Options & RowMajorBit) ? 0 : 1, RowsAtCompileTime = IsColVector ? Dynamic : 1, ColsAtCompileTime = IsColVector ? 1 : Dynamic, MaxRowsAtCompileTime = RowsAtCompileTime, MaxColsAtCompileTime = ColsAtCompileTime, - Flags = _Options | NestByRefBit | LvalueBit, + Flags = _Options | NestByRefBit | LvalueBit | (IsColVector ? 0 : RowMajorBit), CoeffReadCost = NumTraits::ReadCost, SupportedAccessPatterns = InnerRandomAccessPattern }; @@ -67,7 +70,6 @@ class SparseVector EIGEN_SPARSE_PUBLIC_INTERFACE(SparseVector) EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, +=) EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, -=) -// EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, =) protected: public: @@ -79,11 +81,11 @@ class SparseVector Options = _Options }; - CompressedStorage m_data; + internal::CompressedStorage m_data; Index m_size; - CompressedStorage& _data() { return m_data; } - CompressedStorage& _data() const { return m_data; } + internal::CompressedStorage& _data() { return m_data; } + internal::CompressedStorage& _data() const { return m_data; } public: @@ -91,13 +93,12 @@ class SparseVector EIGEN_STRONG_INLINE Index cols() const { return IsColVector ? 1 : m_size; } EIGEN_STRONG_INLINE Index innerSize() const { return m_size; } EIGEN_STRONG_INLINE Index outerSize() const { return 1; } - EIGEN_STRONG_INLINE Index innerNonZeros(Index j) const { eigen_assert(j==0); return m_size; } - EIGEN_STRONG_INLINE const Scalar* _valuePtr() const { return &m_data.value(0); } - EIGEN_STRONG_INLINE Scalar* _valuePtr() { return &m_data.value(0); } + EIGEN_STRONG_INLINE const Scalar* valuePtr() const { return &m_data.value(0); } + EIGEN_STRONG_INLINE Scalar* valuePtr() { return &m_data.value(0); } - EIGEN_STRONG_INLINE const Index* _innerIndexPtr() const { return &m_data.index(0); } - EIGEN_STRONG_INLINE Index* _innerIndexPtr() { return &m_data.index(0); } + EIGEN_STRONG_INLINE const Index* innerIndexPtr() const { return &m_data.index(0); } + EIGEN_STRONG_INLINE Index* innerIndexPtr() { return &m_data.index(0); } inline Scalar coeff(Index row, Index col) const { @@ -126,6 +127,7 @@ class SparseVector public: class InnerIterator; + class ReverseInnerIterator; inline void setZero() { m_data.clear(); } @@ -134,11 +136,13 @@ class SparseVector inline void startVec(Index outer) { + EIGEN_UNUSED_VARIABLE(outer); eigen_assert(outer==0); } inline Scalar& insertBackByOuterInner(Index outer, Index inner) { + EIGEN_UNUSED_VARIABLE(outer); eigen_assert(outer==0); return insertBack(inner); } @@ -158,7 +162,7 @@ class SparseVector Scalar& insert(Index i) { Index startId = 0; - Index p = m_data.size() - 1; + Index p = Index(m_data.size()) - 1; // TODO smart realloc m_data.resize(p+2,1); @@ -205,13 +209,6 @@ class SparseVector inline SparseVector(Index rows, Index cols) : m_size(0) { resize(rows,cols); } - template - inline SparseVector(const MatrixBase& other) - : m_size(0) - { - *this = other.derived(); - } - template inline SparseVector(const SparseMatrixBase& other) : m_size(0) @@ -249,9 +246,9 @@ class SparseVector inline SparseVector& operator=(const SparseMatrixBase& other) { if (int(RowsAtCompileTime)!=int(OtherDerived::RowsAtCompileTime)) - return Base::operator=(other.transpose()); + return assign(other.transpose()); else - return Base::operator=(other); + return assign(other); } #ifndef EIGEN_PARSED_BY_DOXYGEN @@ -262,56 +259,6 @@ class SparseVector } #endif -// const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); -// if (needToTranspose) -// { -// // two passes algorithm: -// // 1 - compute the number of coeffs per dest inner vector -// // 2 - do the actual copy/eval -// // Since each coeff of the rhs has to be evaluated twice, let's evauluate it if needed -// typedef typename internal::nested::type OtherCopy; -// OtherCopy otherCopy(other.derived()); -// typedef typename internal::remove_all::type _OtherCopy; -// -// resize(other.rows(), other.cols()); -// Eigen::Map(m_outerIndex,outerSize()).setZero(); -// // pass 1 -// // FIXME the above copy could be merged with that pass -// for (int j=0; j::operator=(other.derived()); -// } -// } - friend std::ostream & operator << (std::ostream & s, const SparseVector& m) { for (Index i=0; i + EIGEN_DONT_INLINE SparseVector& assign(const SparseMatrixBase& _other) + { + const OtherDerived& other(_other.derived()); + const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit); + if(needToTranspose) + { + Index size = other.size(); + Index nnz = other.nonZeros(); + resize(size); + reserve(nnz); + for(Index i=0; i @@ -399,18 +351,14 @@ class SparseVector::InnerIterator InnerIterator(const SparseVector& vec, Index outer=0) : m_data(vec.m_data), m_id(0), m_end(static_cast(m_data.size())) { + EIGEN_UNUSED_VARIABLE(outer); eigen_assert(outer==0); } - InnerIterator(const CompressedStorage& data) + InnerIterator(const internal::CompressedStorage& data) : m_data(data), m_id(0), m_end(static_cast(m_data.size())) {} - template - InnerIterator(const Flagged& vec, Index ) - : m_data(vec._expression().m_data), m_id(0), m_end(m_data.size()) - {} - inline InnerIterator& operator++() { m_id++; return *this; } inline Scalar value() const { return m_data.value(m_id); } @@ -423,9 +371,43 @@ class SparseVector::InnerIterator inline operator bool() const { return (m_id < m_end); } protected: - const CompressedStorage& m_data; + const internal::CompressedStorage& m_data; Index m_id; const Index m_end; }; +template +class SparseVector::ReverseInnerIterator +{ + public: + ReverseInnerIterator(const SparseVector& vec, Index outer=0) + : m_data(vec.m_data), m_id(static_cast(m_data.size())), m_start(0) + { + EIGEN_UNUSED_VARIABLE(outer); + eigen_assert(outer==0); + } + + ReverseInnerIterator(const internal::CompressedStorage& data) + : m_data(data), m_id(static_cast(m_data.size())), m_start(0) + {} + + inline ReverseInnerIterator& operator--() { m_id--; return *this; } + + inline Scalar value() const { return m_data.value(m_id-1); } + inline Scalar& valueRef() { return const_cast(m_data.value(m_id-1)); } + + inline Index index() const { return m_data.index(m_id-1); } + inline Index row() const { return IsColVector ? index() : 0; } + inline Index col() const { return IsColVector ? 0 : index(); } + + inline operator bool() const { return (m_id > m_start); } + + protected: + const internal::CompressedStorage& m_data; + Index m_id; + const Index m_start; +}; + +} // end namespace Eigen + #endif // EIGEN_SPARSEVECTOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseView.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseView.h similarity index 91% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseView.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseView.h index 243065610..43a3adb24 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/SparseView.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseView.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2010 Gael Guennebaud +// Copyright (C) 2011 Gael Guennebaud // Copyright (C) 2010 Daniel Lowengrub // // Eigen is free software; you can redistribute it and/or @@ -26,6 +26,8 @@ #ifndef EIGEN_SPARSEVIEW_H #define EIGEN_SPARSEVIEW_H +namespace Eigen { + namespace internal { template @@ -61,7 +63,7 @@ public: inline Index outerSize() const { return m_matrix.outerSize(); } protected: - const MatrixTypeNested m_matrix; + MatrixTypeNested m_matrix; Scalar m_reference; typename NumTraits::Real m_epsilon; }; @@ -92,10 +94,10 @@ protected: private: void incrementToNonZero() { - while(internal::isMuchSmallerThan(value(), m_view.m_reference, m_view.m_epsilon) && (bool(*this))) - { - IterBase::operator++(); - } + while((bool(*this)) && internal::isMuchSmallerThan(value(), m_view.m_reference, m_view.m_epsilon)) + { + IterBase::operator++(); + } } }; @@ -106,4 +108,6 @@ const SparseView MatrixBase::sparseView(const Scalar& m_refere return SparseView(derived(), m_reference, m_epsilon); } +} // end namespace Eigen + #endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/TriangularSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h similarity index 89% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/TriangularSolver.h rename to gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h index 62bb8bb44..9a45e8f41 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/TriangularSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSETRIANGULARSOLVER_H #define EIGEN_SPARSETRIANGULARSOLVER_H +namespace Eigen { + namespace internal { template for(int i=0; i for(int i=lhs.rows()-1 ; i>=0 ; --i) { Scalar tmp = other.coeff(i,col); + Scalar l_ii = 0; typename Lhs::InnerIterator it(lhs, i); - if (it && it.index() == i) + while(it && it.index() if (Mode & UnitDiag) other.coeffRef(i,col) = tmp; else - { - typename Lhs::InnerIterator it(lhs, i); - eigen_assert(it && it.index() == i); - other.coeffRef(i,col) = tmp/it.value(); - } + other.coeffRef(i,col) = tmp/l_ii; } } } @@ -118,9 +125,11 @@ struct sparse_solve_triangular_selector if (tmp!=Scalar(0)) // optimization when other is actually sparse { typename Lhs::InnerIterator it(lhs, i); + while(it && it.index() { if(!(Mode & UnitDiag)) { - // FIXME lhs.coeff(i,i) might not be always efficient while it must simply be the - // last element of the column ! - other.coeffRef(i,col) /= lhs.innerVector(i).lastCoeff(); + // TODO replace this by a binary search. make sure the binary search is safe for partially sorted elements + typename Lhs::ReverseInnerIterator it(lhs, i); + while(it && it.index()!=i) + --it; + eigen_assert(it && it.index()==i); + other.coeffRef(i,col) /= it.value(); } typename Lhs::InnerIterator it(lhs, i); for(; it && it.index() template void SparseTriangularView::solveInPlace(MatrixBase& other) const { - eigen_assert(m_matrix.cols() == m_matrix.rows()); - eigen_assert(m_matrix.cols() == other.rows()); - eigen_assert(!(Mode & ZeroDiag)); - eigen_assert((Mode & (Upper|Lower)) != 0); + eigen_assert(m_matrix.cols() == m_matrix.rows() && m_matrix.cols() == other.rows()); + eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower))); enum { copy = internal::traits::Flags & RowMajorBit }; @@ -295,10 +305,8 @@ template template void SparseTriangularView::solveInPlace(SparseMatrixBase& other) const { - eigen_assert(m_matrix.cols() == m_matrix.rows()); - eigen_assert(m_matrix.cols() == other.rows()); - eigen_assert(!(Mode & ZeroDiag)); - eigen_assert((Mode & (Upper|Lower)) != 0); + eigen_assert(m_matrix.cols() == m_matrix.rows() && m_matrix.cols() == other.rows()); + eigen_assert( (!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower))); // enum { copy = internal::traits::Flags & RowMajorBit }; @@ -336,4 +344,6 @@ SparseMatrixBase::solveTriangular(const MatrixBase& other } #endif // EIGEN2_SUPPORT +} // end namespace Eigen + #endif // EIGEN_SPARSETRIANGULARSOLVER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/CMakeLists.txt new file mode 100644 index 000000000..b28ebe583 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_SuperLUSupport_SRCS "*.h") + +INSTALL(FILES + ${Eigen_SuperLUSupport_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/SuperLUSupport COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/SuperLUSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/SuperLUSupport.h new file mode 100644 index 000000000..6c3eb6858 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/SuperLUSupport.h @@ -0,0 +1,1040 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SUPERLUSUPPORT_H +#define EIGEN_SUPERLUSUPPORT_H + +namespace Eigen { + +#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE) \ + extern "C" { \ + typedef struct { FLOATTYPE for_lu; FLOATTYPE total_needed; int expansions; } PREFIX##mem_usage_t; \ + extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *, \ + char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *, \ + void *, int, SuperMatrix *, SuperMatrix *, \ + FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, \ + PREFIX##mem_usage_t *, SuperLUStat_t *, int *); \ + } \ + inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A, \ + int *perm_c, int *perm_r, int *etree, char *equed, \ + FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L, \ + SuperMatrix *U, void *work, int lwork, \ + SuperMatrix *B, SuperMatrix *X, \ + FLOATTYPE *recip_pivot_growth, \ + FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr, \ + SuperLUStat_t *stats, int *info, KEYTYPE) { \ + PREFIX##mem_usage_t mem_usage; \ + PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L, \ + U, work, lwork, B, X, recip_pivot_growth, rcond, \ + ferr, berr, &mem_usage, stats, info); \ + return mem_usage.for_lu; /* bytes used by the factor storage */ \ + } + +DECL_GSSVX(s,float,float) +DECL_GSSVX(c,float,std::complex) +DECL_GSSVX(d,double,double) +DECL_GSSVX(z,double,std::complex) + +#ifdef MILU_ALPHA +#define EIGEN_SUPERLU_HAS_ILU +#endif + +#ifdef EIGEN_SUPERLU_HAS_ILU + +// similarly for the incomplete factorization using gsisx +#define DECL_GSISX(PREFIX,FLOATTYPE,KEYTYPE) \ + extern "C" { \ + extern void PREFIX##gsisx(superlu_options_t *, SuperMatrix *, int *, int *, int *, \ + char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *, \ + void *, int, SuperMatrix *, SuperMatrix *, FLOATTYPE *, FLOATTYPE *, \ + PREFIX##mem_usage_t *, SuperLUStat_t *, int *); \ + } \ + inline float SuperLU_gsisx(superlu_options_t *options, SuperMatrix *A, \ + int *perm_c, int *perm_r, int *etree, char *equed, \ + FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L, \ + SuperMatrix *U, void *work, int lwork, \ + SuperMatrix *B, SuperMatrix *X, \ + FLOATTYPE *recip_pivot_growth, \ + FLOATTYPE *rcond, \ + SuperLUStat_t *stats, int *info, KEYTYPE) { \ + PREFIX##mem_usage_t mem_usage; \ + PREFIX##gsisx(options, A, perm_c, perm_r, etree, equed, R, C, L, \ + U, work, lwork, B, X, recip_pivot_growth, rcond, \ + &mem_usage, stats, info); \ + return mem_usage.for_lu; /* bytes used by the factor storage */ \ + } + +DECL_GSISX(s,float,float) +DECL_GSISX(c,float,std::complex) +DECL_GSISX(d,double,double) +DECL_GSISX(z,double,std::complex) + +#endif + +template +struct SluMatrixMapHelper; + +/** \internal + * + * A wrapper class for SuperLU matrices. It supports only compressed sparse matrices + * and dense matrices. Supernodal and other fancy format are not supported by this wrapper. + * + * This wrapper class mainly aims to avoids the need of dynamic allocation of the storage structure. + */ +struct SluMatrix : SuperMatrix +{ + SluMatrix() + { + Store = &storage; + } + + SluMatrix(const SluMatrix& other) + : SuperMatrix(other) + { + Store = &storage; + storage = other.storage; + } + + SluMatrix& operator=(const SluMatrix& other) + { + SuperMatrix::operator=(static_cast(other)); + Store = &storage; + storage = other.storage; + return *this; + } + + struct + { + union {int nnz;int lda;}; + void *values; + int *innerInd; + int *outerInd; + } storage; + + void setStorageType(Stype_t t) + { + Stype = t; + if (t==SLU_NC || t==SLU_NR || t==SLU_DN) + Store = &storage; + else + { + eigen_assert(false && "storage type not supported"); + Store = 0; + } + } + + template + void setScalarType() + { + if (internal::is_same::value) + Dtype = SLU_S; + else if (internal::is_same::value) + Dtype = SLU_D; + else if (internal::is_same >::value) + Dtype = SLU_C; + else if (internal::is_same >::value) + Dtype = SLU_Z; + else + { + eigen_assert(false && "Scalar type not supported by SuperLU"); + } + } + + template + static SluMatrix Map(MatrixBase& _mat) + { + MatrixType& mat(_mat.derived()); + eigen_assert( ((MatrixType::Flags&RowMajorBit)!=RowMajorBit) && "row-major dense matrices are not supported by SuperLU"); + SluMatrix res; + res.setStorageType(SLU_DN); + res.setScalarType(); + res.Mtype = SLU_GE; + + res.nrow = mat.rows(); + res.ncol = mat.cols(); + + res.storage.lda = MatrixType::IsVectorAtCompileTime ? mat.size() : mat.outerStride(); + res.storage.values = mat.data(); + return res; + } + + template + static SluMatrix Map(SparseMatrixBase& mat) + { + SluMatrix res; + if ((MatrixType::Flags&RowMajorBit)==RowMajorBit) + { + res.setStorageType(SLU_NR); + res.nrow = mat.cols(); + res.ncol = mat.rows(); + } + else + { + res.setStorageType(SLU_NC); + res.nrow = mat.rows(); + res.ncol = mat.cols(); + } + + res.Mtype = SLU_GE; + + res.storage.nnz = mat.nonZeros(); + res.storage.values = mat.derived().valuePtr(); + res.storage.innerInd = mat.derived().innerIndexPtr(); + res.storage.outerInd = mat.derived().outerIndexPtr(); + + res.setScalarType(); + + // FIXME the following is not very accurate + if (MatrixType::Flags & Upper) + res.Mtype = SLU_TRU; + if (MatrixType::Flags & Lower) + res.Mtype = SLU_TRL; + + eigen_assert(((MatrixType::Flags & SelfAdjoint)==0) && "SelfAdjoint matrix shape not supported by SuperLU"); + + return res; + } +}; + +template +struct SluMatrixMapHelper > +{ + typedef Matrix MatrixType; + static void run(MatrixType& mat, SluMatrix& res) + { + eigen_assert( ((Options&RowMajor)!=RowMajor) && "row-major dense matrices is not supported by SuperLU"); + res.setStorageType(SLU_DN); + res.setScalarType(); + res.Mtype = SLU_GE; + + res.nrow = mat.rows(); + res.ncol = mat.cols(); + + res.storage.lda = mat.outerStride(); + res.storage.values = mat.data(); + } +}; + +template +struct SluMatrixMapHelper > +{ + typedef Derived MatrixType; + static void run(MatrixType& mat, SluMatrix& res) + { + if ((MatrixType::Flags&RowMajorBit)==RowMajorBit) + { + res.setStorageType(SLU_NR); + res.nrow = mat.cols(); + res.ncol = mat.rows(); + } + else + { + res.setStorageType(SLU_NC); + res.nrow = mat.rows(); + res.ncol = mat.cols(); + } + + res.Mtype = SLU_GE; + + res.storage.nnz = mat.nonZeros(); + res.storage.values = mat.valuePtr(); + res.storage.innerInd = mat.innerIndexPtr(); + res.storage.outerInd = mat.outerIndexPtr(); + + res.setScalarType(); + + // FIXME the following is not very accurate + if (MatrixType::Flags & Upper) + res.Mtype = SLU_TRU; + if (MatrixType::Flags & Lower) + res.Mtype = SLU_TRL; + + eigen_assert(((MatrixType::Flags & SelfAdjoint)==0) && "SelfAdjoint matrix shape not supported by SuperLU"); + } +}; + +namespace internal { + +template +SluMatrix asSluMatrix(MatrixType& mat) +{ + return SluMatrix::Map(mat); +} + +/** View a Super LU matrix as an Eigen expression */ +template +MappedSparseMatrix map_superlu(SluMatrix& sluMat) +{ + eigen_assert((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR + || (Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC); + + Index outerSize = (Flags&RowMajor)==RowMajor ? sluMat.ncol : sluMat.nrow; + + return MappedSparseMatrix( + sluMat.nrow, sluMat.ncol, sluMat.storage.outerInd[outerSize], + sluMat.storage.outerInd, sluMat.storage.innerInd, reinterpret_cast(sluMat.storage.values) ); +} + +} // end namespace internal + +/** \ingroup SuperLUSupport_Module + * \class SuperLUBase + * \brief The base class for the direct and incomplete LU factorization of SuperLU + */ +template +class SuperLUBase : internal::noncopyable +{ + public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef Matrix Vector; + typedef Matrix IntRowVectorType; + typedef Matrix IntColVectorType; + typedef SparseMatrix LUMatrixType; + + public: + + SuperLUBase() {} + + ~SuperLUBase() + { + clearFactors(); + } + + Derived& derived() { return *static_cast(this); } + const Derived& derived() const { return *static_cast(this); } + + inline Index rows() const { return m_matrix.rows(); } + inline Index cols() const { return m_matrix.cols(); } + + /** \returns a reference to the Super LU option object to configure the Super LU algorithms. */ + inline superlu_options_t& options() { return m_sluOptions; } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "Decomposition is not initialized."); + return m_info; + } + + /** Computes the sparse Cholesky decomposition of \a matrix */ + void compute(const MatrixType& matrix) + { + derived().analyzePattern(matrix); + derived().factorize(matrix); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::solve_retval solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "SuperLU is not initialized."); + eigen_assert(rows()==b.rows() + && "SuperLU::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ +// template +// inline const internal::sparse_solve_retval solve(const SparseMatrixBase& b) const +// { +// eigen_assert(m_isInitialized && "SuperLU is not initialized."); +// eigen_assert(rows()==b.rows() +// && "SuperLU::solve(): invalid number of rows of the right hand side matrix b"); +// return internal::sparse_solve_retval(*this, b.derived()); +// } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& /*matrix*/) + { + m_isInitialized = true; + m_info = Success; + m_analysisIsOk = true; + m_factorizationIsOk = false; + } + + template + void dumpMemory(Stream& s) + {} + + protected: + + void initFactorization(const MatrixType& a) + { + set_default_options(&this->m_sluOptions); + + const int size = a.rows(); + m_matrix = a; + + m_sluA = internal::asSluMatrix(m_matrix); + clearFactors(); + + m_p.resize(size); + m_q.resize(size); + m_sluRscale.resize(size); + m_sluCscale.resize(size); + m_sluEtree.resize(size); + + // set empty B and X + m_sluB.setStorageType(SLU_DN); + m_sluB.setScalarType(); + m_sluB.Mtype = SLU_GE; + m_sluB.storage.values = 0; + m_sluB.nrow = 0; + m_sluB.ncol = 0; + m_sluB.storage.lda = size; + m_sluX = m_sluB; + + m_extractedDataAreDirty = true; + } + + void init() + { + m_info = InvalidInput; + m_isInitialized = false; + m_sluL.Store = 0; + m_sluU.Store = 0; + } + + void extractData() const; + + void clearFactors() + { + if(m_sluL.Store) + Destroy_SuperNode_Matrix(&m_sluL); + if(m_sluU.Store) + Destroy_CompCol_Matrix(&m_sluU); + + m_sluL.Store = 0; + m_sluU.Store = 0; + + memset(&m_sluL,0,sizeof m_sluL); + memset(&m_sluU,0,sizeof m_sluU); + } + + // cached data to reduce reallocation, etc. + mutable LUMatrixType m_l; + mutable LUMatrixType m_u; + mutable IntColVectorType m_p; + mutable IntRowVectorType m_q; + + mutable LUMatrixType m_matrix; // copy of the factorized matrix + mutable SluMatrix m_sluA; + mutable SuperMatrix m_sluL, m_sluU; + mutable SluMatrix m_sluB, m_sluX; + mutable SuperLUStat_t m_sluStat; + mutable superlu_options_t m_sluOptions; + mutable std::vector m_sluEtree; + mutable Matrix m_sluRscale, m_sluCscale; + mutable Matrix m_sluFerr, m_sluBerr; + mutable char m_sluEqued; + + mutable ComputationInfo m_info; + bool m_isInitialized; + int m_factorizationIsOk; + int m_analysisIsOk; + mutable bool m_extractedDataAreDirty; + + private: + SuperLUBase(SuperLUBase& ) { } +}; + + +/** \ingroup SuperLUSupport_Module + * \class SuperLU + * \brief A sparse direct LU factorization and solver based on the SuperLU library + * + * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization + * using the SuperLU library. The sparse matrix A must be squared and invertible. The vectors or matrices + * X and B can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class SuperLU : public SuperLUBase<_MatrixType,SuperLU<_MatrixType> > +{ + public: + typedef SuperLUBase<_MatrixType,SuperLU> Base; + typedef _MatrixType MatrixType; + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; + typedef typename Base::Index Index; + typedef typename Base::IntRowVectorType IntRowVectorType; + typedef typename Base::IntColVectorType IntColVectorType; + typedef typename Base::LUMatrixType LUMatrixType; + typedef TriangularView LMatrixType; + typedef TriangularView UMatrixType; + + public: + + SuperLU() : Base() { init(); } + + SuperLU(const MatrixType& matrix) : Base() + { + Base::init(); + compute(matrix); + } + + ~SuperLU() + { + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& matrix) + { + m_info = InvalidInput; + m_isInitialized = false; + Base::analyzePattern(matrix); + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + void factorize(const MatrixType& matrix); + + #ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal */ + template + void _solve(const MatrixBase &b, MatrixBase &dest) const; + #endif // EIGEN_PARSED_BY_DOXYGEN + + inline const LMatrixType& matrixL() const + { + if (m_extractedDataAreDirty) this->extractData(); + return m_l; + } + + inline const UMatrixType& matrixU() const + { + if (m_extractedDataAreDirty) this->extractData(); + return m_u; + } + + inline const IntColVectorType& permutationP() const + { + if (m_extractedDataAreDirty) this->extractData(); + return m_p; + } + + inline const IntRowVectorType& permutationQ() const + { + if (m_extractedDataAreDirty) this->extractData(); + return m_q; + } + + Scalar determinant() const; + + protected: + + using Base::m_matrix; + using Base::m_sluOptions; + using Base::m_sluA; + using Base::m_sluB; + using Base::m_sluX; + using Base::m_p; + using Base::m_q; + using Base::m_sluEtree; + using Base::m_sluEqued; + using Base::m_sluRscale; + using Base::m_sluCscale; + using Base::m_sluL; + using Base::m_sluU; + using Base::m_sluStat; + using Base::m_sluFerr; + using Base::m_sluBerr; + using Base::m_l; + using Base::m_u; + + using Base::m_analysisIsOk; + using Base::m_factorizationIsOk; + using Base::m_extractedDataAreDirty; + using Base::m_isInitialized; + using Base::m_info; + + void init() + { + Base::init(); + + set_default_options(&this->m_sluOptions); + m_sluOptions.PrintStat = NO; + m_sluOptions.ConditionNumber = NO; + m_sluOptions.Trans = NOTRANS; + m_sluOptions.ColPerm = COLAMD; + } + + + private: + SuperLU(SuperLU& ) { } +}; + +template +void SuperLU::factorize(const MatrixType& a) +{ + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + if(!m_analysisIsOk) + { + m_info = InvalidInput; + return; + } + + this->initFactorization(a); + + int info = 0; + RealScalar recip_pivot_growth, rcond; + RealScalar ferr, berr; + + StatInit(&m_sluStat); + SuperLU_gssvx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0], + &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0], + &m_sluL, &m_sluU, + NULL, 0, + &m_sluB, &m_sluX, + &recip_pivot_growth, &rcond, + &ferr, &berr, + &m_sluStat, &info, Scalar()); + StatFree(&m_sluStat); + + m_extractedDataAreDirty = true; + + // FIXME how to better check for errors ??? + m_info = info == 0 ? Success : NumericalIssue; + m_factorizationIsOk = true; +} + +template +template +void SuperLU::_solve(const MatrixBase &b, MatrixBase& x) const +{ + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()"); + + const int size = m_matrix.rows(); + const int rhsCols = b.cols(); + eigen_assert(size==b.rows()); + + m_sluOptions.Trans = NOTRANS; + m_sluOptions.Fact = FACTORED; + m_sluOptions.IterRefine = NOREFINE; + + + m_sluFerr.resize(rhsCols); + m_sluBerr.resize(rhsCols); + m_sluB = SluMatrix::Map(b.const_cast_derived()); + m_sluX = SluMatrix::Map(x.derived()); + + typename Rhs::PlainObject b_cpy; + if(m_sluEqued!='N') + { + b_cpy = b; + m_sluB = SluMatrix::Map(b_cpy.const_cast_derived()); + } + + StatInit(&m_sluStat); + int info = 0; + RealScalar recip_pivot_growth, rcond; + SuperLU_gssvx(&m_sluOptions, &m_sluA, + m_q.data(), m_p.data(), + &m_sluEtree[0], &m_sluEqued, + &m_sluRscale[0], &m_sluCscale[0], + &m_sluL, &m_sluU, + NULL, 0, + &m_sluB, &m_sluX, + &recip_pivot_growth, &rcond, + &m_sluFerr[0], &m_sluBerr[0], + &m_sluStat, &info, Scalar()); + StatFree(&m_sluStat); + m_info = info==0 ? Success : NumericalIssue; +} + +// the code of this extractData() function has been adapted from the SuperLU's Matlab support code, +// +// Copyright (c) 1994 by Xerox Corporation. All rights reserved. +// +// THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY +// EXPRESSED OR IMPLIED. ANY USE IS AT YOUR OWN RISK. +// +template +void SuperLUBase::extractData() const +{ + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for extracting factors, you must first call either compute() or analyzePattern()/factorize()"); + if (m_extractedDataAreDirty) + { + int upper; + int fsupc, istart, nsupr; + int lastl = 0, lastu = 0; + SCformat *Lstore = static_cast(m_sluL.Store); + NCformat *Ustore = static_cast(m_sluU.Store); + Scalar *SNptr; + + const int size = m_matrix.rows(); + m_l.resize(size,size); + m_l.resizeNonZeros(Lstore->nnz); + m_u.resize(size,size); + m_u.resizeNonZeros(Ustore->nnz); + + int* Lcol = m_l.outerIndexPtr(); + int* Lrow = m_l.innerIndexPtr(); + Scalar* Lval = m_l.valuePtr(); + + int* Ucol = m_u.outerIndexPtr(); + int* Urow = m_u.innerIndexPtr(); + Scalar* Uval = m_u.valuePtr(); + + Ucol[0] = 0; + Ucol[0] = 0; + + /* for each supernode */ + for (int k = 0; k <= Lstore->nsuper; ++k) + { + fsupc = L_FST_SUPC(k); + istart = L_SUB_START(fsupc); + nsupr = L_SUB_START(fsupc+1) - istart; + upper = 1; + + /* for each column in the supernode */ + for (int j = fsupc; j < L_FST_SUPC(k+1); ++j) + { + SNptr = &((Scalar*)Lstore->nzval)[L_NZ_START(j)]; + + /* Extract U */ + for (int i = U_NZ_START(j); i < U_NZ_START(j+1); ++i) + { + Uval[lastu] = ((Scalar*)Ustore->nzval)[i]; + /* Matlab doesn't like explicit zero. */ + if (Uval[lastu] != 0.0) + Urow[lastu++] = U_SUB(i); + } + for (int i = 0; i < upper; ++i) + { + /* upper triangle in the supernode */ + Uval[lastu] = SNptr[i]; + /* Matlab doesn't like explicit zero. */ + if (Uval[lastu] != 0.0) + Urow[lastu++] = L_SUB(istart+i); + } + Ucol[j+1] = lastu; + + /* Extract L */ + Lval[lastl] = 1.0; /* unit diagonal */ + Lrow[lastl++] = L_SUB(istart + upper - 1); + for (int i = upper; i < nsupr; ++i) + { + Lval[lastl] = SNptr[i]; + /* Matlab doesn't like explicit zero. */ + if (Lval[lastl] != 0.0) + Lrow[lastl++] = L_SUB(istart+i); + } + Lcol[j+1] = lastl; + + ++upper; + } /* for j ... */ + + } /* for k ... */ + + // squeeze the matrices : + m_l.resizeNonZeros(lastl); + m_u.resizeNonZeros(lastu); + + m_extractedDataAreDirty = false; + } +} + +template +typename SuperLU::Scalar SuperLU::determinant() const +{ + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for computing the determinant, you must first call either compute() or analyzePattern()/factorize()"); + + if (m_extractedDataAreDirty) + this->extractData(); + + Scalar det = Scalar(1); + for (int j=0; j 0) + { + int lastId = m_u.outerIndexPtr()[j+1]-1; + eigen_assert(m_u.innerIndexPtr()[lastId]<=j); + if (m_u.innerIndexPtr()[lastId]==j) + det *= m_u.valuePtr()[lastId]; + } + } + if(m_sluEqued!='N') + return det/m_sluRscale.prod()/m_sluCscale.prod(); + else + return det; +} + +#ifdef EIGEN_PARSED_BY_DOXYGEN +#define EIGEN_SUPERLU_HAS_ILU +#endif + +#ifdef EIGEN_SUPERLU_HAS_ILU + +/** \ingroup SuperLUSupport_Module + * \class SuperILU + * \brief A sparse direct \b incomplete LU factorization and solver based on the SuperLU library + * + * This class allows to solve for an approximate solution of A.X = B sparse linear problems via an incomplete LU factorization + * using the SuperLU library. This class is aimed to be used as a preconditioner of the iterative linear solvers. + * + * \warning This class requires SuperLU 4 or later. + * + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * + * \sa \ref TutorialSparseDirectSolvers, class ConjugateGradient, class BiCGSTAB + */ + +template +class SuperILU : public SuperLUBase<_MatrixType,SuperILU<_MatrixType> > +{ + public: + typedef SuperLUBase<_MatrixType,SuperILU> Base; + typedef _MatrixType MatrixType; + typedef typename Base::Scalar Scalar; + typedef typename Base::RealScalar RealScalar; + typedef typename Base::Index Index; + + public: + + SuperILU() : Base() { init(); } + + SuperILU(const MatrixType& matrix) : Base() + { + init(); + compute(matrix); + } + + ~SuperILU() + { + } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize() + */ + void analyzePattern(const MatrixType& matrix) + { + Base::analyzePattern(matrix); + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. + * + * \sa analyzePattern() + */ + void factorize(const MatrixType& matrix); + + #ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal */ + template + void _solve(const MatrixBase &b, MatrixBase &dest) const; + #endif // EIGEN_PARSED_BY_DOXYGEN + + protected: + + using Base::m_matrix; + using Base::m_sluOptions; + using Base::m_sluA; + using Base::m_sluB; + using Base::m_sluX; + using Base::m_p; + using Base::m_q; + using Base::m_sluEtree; + using Base::m_sluEqued; + using Base::m_sluRscale; + using Base::m_sluCscale; + using Base::m_sluL; + using Base::m_sluU; + using Base::m_sluStat; + using Base::m_sluFerr; + using Base::m_sluBerr; + using Base::m_l; + using Base::m_u; + + using Base::m_analysisIsOk; + using Base::m_factorizationIsOk; + using Base::m_extractedDataAreDirty; + using Base::m_isInitialized; + using Base::m_info; + + void init() + { + Base::init(); + + ilu_set_default_options(&m_sluOptions); + m_sluOptions.PrintStat = NO; + m_sluOptions.ConditionNumber = NO; + m_sluOptions.Trans = NOTRANS; + m_sluOptions.ColPerm = MMD_AT_PLUS_A; + + // no attempt to preserve column sum + m_sluOptions.ILU_MILU = SILU; + // only basic ILU(k) support -- no direct control over memory consumption + // better to use ILU_DropRule = DROP_BASIC | DROP_AREA + // and set ILU_FillFactor to max memory growth + m_sluOptions.ILU_DropRule = DROP_BASIC; + m_sluOptions.ILU_DropTol = NumTraits::dummy_precision()*10; + } + + private: + SuperILU(SuperILU& ) { } +}; + +template +void SuperILU::factorize(const MatrixType& a) +{ + eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); + if(!m_analysisIsOk) + { + m_info = InvalidInput; + return; + } + + this->initFactorization(a); + + int info = 0; + RealScalar recip_pivot_growth, rcond; + + StatInit(&m_sluStat); + SuperLU_gsisx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0], + &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0], + &m_sluL, &m_sluU, + NULL, 0, + &m_sluB, &m_sluX, + &recip_pivot_growth, &rcond, + &m_sluStat, &info, Scalar()); + StatFree(&m_sluStat); + + // FIXME how to better check for errors ??? + m_info = info == 0 ? Success : NumericalIssue; + m_factorizationIsOk = true; +} + +template +template +void SuperILU::_solve(const MatrixBase &b, MatrixBase& x) const +{ + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()"); + + const int size = m_matrix.rows(); + const int rhsCols = b.cols(); + eigen_assert(size==b.rows()); + + m_sluOptions.Trans = NOTRANS; + m_sluOptions.Fact = FACTORED; + m_sluOptions.IterRefine = NOREFINE; + + m_sluFerr.resize(rhsCols); + m_sluBerr.resize(rhsCols); + m_sluB = SluMatrix::Map(b.const_cast_derived()); + m_sluX = SluMatrix::Map(x.derived()); + + typename Rhs::PlainObject b_cpy; + if(m_sluEqued!='N') + { + b_cpy = b; + m_sluB = SluMatrix::Map(b_cpy.const_cast_derived()); + } + + int info = 0; + RealScalar recip_pivot_growth, rcond; + + StatInit(&m_sluStat); + SuperLU_gsisx(&m_sluOptions, &m_sluA, + m_q.data(), m_p.data(), + &m_sluEtree[0], &m_sluEqued, + &m_sluRscale[0], &m_sluCscale[0], + &m_sluL, &m_sluU, + NULL, 0, + &m_sluB, &m_sluX, + &recip_pivot_growth, &rcond, + &m_sluStat, &info, Scalar()); + StatFree(&m_sluStat); + + m_info = info==0 ? Success : NumericalIssue; +} +#endif + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef SuperLUBase<_MatrixType,Derived> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve(rhs(),dst); + } +}; + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef SuperLUBase<_MatrixType,Derived> Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec().derived()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_SUPERLUSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/CMakeLists.txt new file mode 100644 index 000000000..a57de0020 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_UmfPackSupport_SRCS "*.h") + +INSTALL(FILES + ${Eigen_UmfPackSupport_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/UmfPackSupport COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/UmfPackSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/UmfPackSupport.h new file mode 100644 index 000000000..f98a4c8c0 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/UmfPackSupport.h @@ -0,0 +1,446 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_UMFPACKSUPPORT_H +#define EIGEN_UMFPACKSUPPORT_H + +namespace Eigen { + +/* TODO extract L, extract U, compute det, etc... */ + +// generic double/complex wrapper functions: + +inline void umfpack_free_numeric(void **Numeric, double) +{ umfpack_di_free_numeric(Numeric); *Numeric = 0; } + +inline void umfpack_free_numeric(void **Numeric, std::complex) +{ umfpack_zi_free_numeric(Numeric); *Numeric = 0; } + +inline void umfpack_free_symbolic(void **Symbolic, double) +{ umfpack_di_free_symbolic(Symbolic); *Symbolic = 0; } + +inline void umfpack_free_symbolic(void **Symbolic, std::complex) +{ umfpack_zi_free_symbolic(Symbolic); *Symbolic = 0; } + +inline int umfpack_symbolic(int n_row,int n_col, + const int Ap[], const int Ai[], const double Ax[], void **Symbolic, + const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) +{ + return umfpack_di_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info); +} + +inline int umfpack_symbolic(int n_row,int n_col, + const int Ap[], const int Ai[], const std::complex Ax[], void **Symbolic, + const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) +{ + return umfpack_zi_symbolic(n_row,n_col,Ap,Ai,&internal::real_ref(Ax[0]),0,Symbolic,Control,Info); +} + +inline int umfpack_numeric( const int Ap[], const int Ai[], const double Ax[], + void *Symbolic, void **Numeric, + const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) +{ + return umfpack_di_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info); +} + +inline int umfpack_numeric( const int Ap[], const int Ai[], const std::complex Ax[], + void *Symbolic, void **Numeric, + const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) +{ + return umfpack_zi_numeric(Ap,Ai,&internal::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info); +} + +inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const double Ax[], + double X[], const double B[], void *Numeric, + const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) +{ + return umfpack_di_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info); +} + +inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const std::complex Ax[], + std::complex X[], const std::complex B[], void *Numeric, + const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) +{ + return umfpack_zi_solve(sys,Ap,Ai,&internal::real_ref(Ax[0]),0,&internal::real_ref(X[0]),0,&internal::real_ref(B[0]),0,Numeric,Control,Info); +} + +inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double) +{ + return umfpack_di_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); +} + +inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, std::complex) +{ + return umfpack_zi_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); +} + +inline int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[], + int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric) +{ + return umfpack_di_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric); +} + +inline int umfpack_get_numeric(int Lp[], int Lj[], std::complex Lx[], int Up[], int Ui[], std::complex Ux[], + int P[], int Q[], std::complex Dx[], int *do_recip, double Rs[], void *Numeric) +{ + double& lx0_real = internal::real_ref(Lx[0]); + double& ux0_real = internal::real_ref(Ux[0]); + double& dx0_real = internal::real_ref(Dx[0]); + return umfpack_zi_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q, + Dx?&dx0_real:0,0,do_recip,Rs,Numeric); +} + +inline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) +{ + return umfpack_di_get_determinant(Mx,Ex,NumericHandle,User_Info); +} + +inline int umfpack_get_determinant(std::complex *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) +{ + double& mx_real = internal::real_ref(*Mx); + return umfpack_zi_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info); +} + +/** \ingroup UmfPackSupport_Module + * \brief A sparse LU factorization and solver based on UmfPack + * + * This class allows to solve for A.X = B sparse linear problems via a LU factorization + * using the UmfPack library. The sparse matrix A must be squared and full rank. + * The vectors or matrices X and B can be either dense or sparse. + * + * \WARNING The input matrix A should be in a \b compressed and \b column-major form. + * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix. + * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> + * + * \sa \ref TutorialSparseDirectSolvers + */ +template +class UmfPackLU : internal::noncopyable +{ + public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + typedef Matrix Vector; + typedef Matrix IntRowVectorType; + typedef Matrix IntColVectorType; + typedef SparseMatrix LUMatrixType; + typedef SparseMatrix UmfpackMatrixType; + + public: + + UmfPackLU() { init(); } + + UmfPackLU(const MatrixType& matrix) + { + init(); + compute(matrix); + } + + ~UmfPackLU() + { + if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar()); + if(m_numeric) umfpack_free_numeric(&m_numeric,Scalar()); + } + + inline Index rows() const { return m_copyMatrix.rows(); } + inline Index cols() const { return m_copyMatrix.cols(); } + + /** \brief Reports whether previous computation was successful. + * + * \returns \c Success if computation was succesful, + * \c NumericalIssue if the matrix.appears to be negative. + */ + ComputationInfo info() const + { + eigen_assert(m_isInitialized && "Decomposition is not initialized."); + return m_info; + } + + inline const LUMatrixType& matrixL() const + { + if (m_extractedDataAreDirty) extractData(); + return m_l; + } + + inline const LUMatrixType& matrixU() const + { + if (m_extractedDataAreDirty) extractData(); + return m_u; + } + + inline const IntColVectorType& permutationP() const + { + if (m_extractedDataAreDirty) extractData(); + return m_p; + } + + inline const IntRowVectorType& permutationQ() const + { + if (m_extractedDataAreDirty) extractData(); + return m_q; + } + + /** Computes the sparse Cholesky decomposition of \a matrix + * Note that the matrix should be column-major, and in compressed format for best performance. + * \sa SparseMatrix::makeCompressed(). + */ + void compute(const MatrixType& matrix) + { + analyzePattern(matrix); + factorize(matrix); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ + template + inline const internal::solve_retval solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "UmfPackLU is not initialized."); + eigen_assert(rows()==b.rows() + && "UmfPackLU::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. + * + * \sa compute() + */ +// template +// inline const internal::sparse_solve_retval solve(const SparseMatrixBase& b) const +// { +// eigen_assert(m_isInitialized && "UmfPAckLU is not initialized."); +// eigen_assert(rows()==b.rows() +// && "UmfPAckLU::solve(): invalid number of rows of the right hand side matrix b"); +// return internal::sparse_solve_retval(*this, b.derived()); +// } + + /** Performs a symbolic decomposition on the sparcity of \a matrix. + * + * This function is particularly useful when solving for several problems having the same structure. + * + * \sa factorize(), compute() + */ + void analyzePattern(const MatrixType& matrix) + { + if(m_symbolic) + umfpack_free_symbolic(&m_symbolic,Scalar()); + if(m_numeric) + umfpack_free_numeric(&m_numeric,Scalar()); + + grapInput(matrix); + + int errorCode = 0; + errorCode = umfpack_symbolic(matrix.rows(), matrix.cols(), m_outerIndexPtr, m_innerIndexPtr, m_valuePtr, + &m_symbolic, 0, 0); + + m_isInitialized = true; + m_info = errorCode ? InvalidInput : Success; + m_analysisIsOk = true; + m_factorizationIsOk = false; + } + + /** Performs a numeric decomposition of \a matrix + * + * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed. + * + * \sa analyzePattern(), compute() + */ + void factorize(const MatrixType& matrix) + { + eigen_assert(m_analysisIsOk && "UmfPackLU: you must first call analyzePattern()"); + if(m_numeric) + umfpack_free_numeric(&m_numeric,Scalar()); + + grapInput(matrix); + + int errorCode; + errorCode = umfpack_numeric(m_outerIndexPtr, m_innerIndexPtr, m_valuePtr, + m_symbolic, &m_numeric, 0, 0); + + m_info = errorCode ? NumericalIssue : Success; + m_factorizationIsOk = true; + } + + #ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal */ + template + bool _solve(const MatrixBase &b, MatrixBase &x) const; + #endif + + Scalar determinant() const; + + void extractData() const; + + protected: + + + void init() + { + m_info = InvalidInput; + m_isInitialized = false; + m_numeric = 0; + m_symbolic = 0; + m_outerIndexPtr = 0; + m_innerIndexPtr = 0; + m_valuePtr = 0; + } + + void grapInput(const MatrixType& mat) + { + m_copyMatrix.resize(mat.rows(), mat.cols()); + if( ((MatrixType::Flags&RowMajorBit)==RowMajorBit) || sizeof(typename MatrixType::Index)!=sizeof(int) || !mat.isCompressed() ) + { + // non supported input -> copy + m_copyMatrix = mat; + m_outerIndexPtr = m_copyMatrix.outerIndexPtr(); + m_innerIndexPtr = m_copyMatrix.innerIndexPtr(); + m_valuePtr = m_copyMatrix.valuePtr(); + } + else + { + m_outerIndexPtr = mat.outerIndexPtr(); + m_innerIndexPtr = mat.innerIndexPtr(); + m_valuePtr = mat.valuePtr(); + } + } + + // cached data to reduce reallocation, etc. + mutable LUMatrixType m_l; + mutable LUMatrixType m_u; + mutable IntColVectorType m_p; + mutable IntRowVectorType m_q; + + UmfpackMatrixType m_copyMatrix; + const Scalar* m_valuePtr; + const int* m_outerIndexPtr; + const int* m_innerIndexPtr; + void* m_numeric; + void* m_symbolic; + + mutable ComputationInfo m_info; + bool m_isInitialized; + int m_factorizationIsOk; + int m_analysisIsOk; + mutable bool m_extractedDataAreDirty; + + private: + UmfPackLU(UmfPackLU& ) { } +}; + + +template +void UmfPackLU::extractData() const +{ + if (m_extractedDataAreDirty) + { + // get size of the data + int lnz, unz, rows, cols, nz_udiag; + umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar()); + + // allocate data + m_l.resize(rows,(std::min)(rows,cols)); + m_l.resizeNonZeros(lnz); + + m_u.resize((std::min)(rows,cols),cols); + m_u.resizeNonZeros(unz); + + m_p.resize(rows); + m_q.resize(cols); + + // extract + umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(), + m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(), + m_p.data(), m_q.data(), 0, 0, 0, m_numeric); + + m_extractedDataAreDirty = false; + } +} + +template +typename UmfPackLU::Scalar UmfPackLU::determinant() const +{ + Scalar det; + umfpack_get_determinant(&det, 0, m_numeric, 0); + return det; +} + +template +template +bool UmfPackLU::_solve(const MatrixBase &b, MatrixBase &x) const +{ + const int rhsCols = b.cols(); + eigen_assert((BDerived::Flags&RowMajorBit)==0 && "UmfPackLU backend does not support non col-major rhs yet"); + eigen_assert((XDerived::Flags&RowMajorBit)==0 && "UmfPackLU backend does not support non col-major result yet"); + + int errorCode; + for (int j=0; j +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef UmfPackLU<_MatrixType> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +template +struct sparse_solve_retval, Rhs> + : sparse_solve_retval_base, Rhs> +{ + typedef UmfPackLU<_MatrixType> Dec; + EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_UMFPACKSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/misc/Image.h b/gtsam/3rdparty/Eigen/Eigen/src/misc/Image.h index 19b3e08cb..7643a0836 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/misc/Image.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/misc/Image.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MISC_IMAGE_H #define EIGEN_MISC_IMAGE_H +namespace Eigen { + namespace internal { /** \class image_retval_base @@ -92,4 +94,6 @@ template struct image_retval_base image_retval(const DecompositionType& dec, const MatrixType& originalMatrix) \ : Base(dec, originalMatrix) {} +} // end namespace Eigen + #endif // EIGEN_MISC_IMAGE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/misc/Kernel.h b/gtsam/3rdparty/Eigen/Eigen/src/misc/Kernel.h index 0115970e8..37bc392ef 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/misc/Kernel.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/misc/Kernel.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MISC_KERNEL_H #define EIGEN_MISC_KERNEL_H +namespace Eigen { + namespace internal { /** \class kernel_retval_base @@ -89,4 +91,6 @@ template struct kernel_retval_base using Base::cols; \ kernel_retval(const DecompositionType& dec) : Base(dec) {} +} // end namespace Eigen + #endif // EIGEN_MISC_KERNEL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h b/gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h index b7cbcadb3..2afd078d4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MISC_SOLVE_H #define EIGEN_MISC_SOLVE_H +namespace Eigen { + namespace internal { /** \class solve_retval_base @@ -66,7 +68,7 @@ template struct solve_retval_base protected: const DecompositionType& m_dec; - const typename Rhs::Nested m_rhs; + typename Rhs::Nested m_rhs; }; } // end namespace internal @@ -84,4 +86,6 @@ template struct solve_retval_base solve_retval(const DecompositionType& dec, const Rhs& rhs) \ : Base(dec, rhs) {} +} // end namespace Eigen + #endif // EIGEN_MISC_SOLVE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Solve.h b/gtsam/3rdparty/Eigen/Eigen/src/misc/SparseSolve.h similarity index 70% rename from gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Solve.h rename to gtsam/3rdparty/Eigen/Eigen/src/misc/SparseSolve.h index 19449e9de..aca34b2d1 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/Solve.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/misc/SparseSolve.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SPARSE_SOLVE_H #define EIGEN_SPARSE_SOLVE_H +namespace Eigen { + namespace internal { template struct sparse_solve_retval_base; @@ -61,7 +63,7 @@ template struct sparse_solve_retval_b protected: const DecompositionType& m_dec; - const typename Rhs::Nested m_rhs; + typename Rhs::Nested m_rhs; }; #define EIGEN_MAKE_SPARSE_SOLVE_HELPERS(DecompositionType,Rhs) \ @@ -76,7 +78,49 @@ template struct sparse_solve_retval_b using Base::cols; \ sparse_solve_retval(const DecompositionType& dec, const Rhs& rhs) \ : Base(dec, rhs) {} - + + + +template struct solve_retval_with_guess; + +template +struct traits > +{ + typedef typename DecompositionType::MatrixType MatrixType; + typedef Matrix ReturnType; +}; + +template struct solve_retval_with_guess + : public ReturnByValue > +{ + typedef typename DecompositionType::Index Index; + + solve_retval_with_guess(const DecompositionType& dec, const Rhs& rhs, const Guess& guess) + : m_dec(dec), m_rhs(rhs), m_guess(guess) + {} + + inline Index rows() const { return m_dec.cols(); } + inline Index cols() const { return m_rhs.cols(); } + + template inline void evalTo(Dest& dst) const + { + dst = m_guess; + m_dec._solveWithGuess(m_rhs,dst); + } + + protected: + const DecompositionType& m_dec; + const typename Rhs::Nested m_rhs; + const typename Guess::Nested m_guess; +}; + } // namepsace internal +} // end namespace Eigen + #endif // EIGEN_SPARSE_SOLVE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/misc/blas.h b/gtsam/3rdparty/Eigen/Eigen/src/misc/blas.h new file mode 100644 index 000000000..6fce99ed5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/misc/blas.h @@ -0,0 +1,658 @@ +#ifndef BLAS_H +#define BLAS_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define BLASFUNC(FUNC) FUNC##_ + +#ifdef __WIN64__ +typedef long long BLASLONG; +typedef unsigned long long BLASULONG; +#else +typedef long BLASLONG; +typedef unsigned long BLASULONG; +#endif + +int BLASFUNC(xerbla)(const char *, int *info, int); + +float BLASFUNC(sdot) (int *, float *, int *, float *, int *); +float BLASFUNC(sdsdot)(int *, float *, float *, int *, float *, int *); + +double BLASFUNC(dsdot) (int *, float *, int *, float *, int *); +double BLASFUNC(ddot) (int *, double *, int *, double *, int *); +double BLASFUNC(qdot) (int *, double *, int *, double *, int *); + +int BLASFUNC(cdotuw) (int *, float *, int *, float *, int *, float*); +int BLASFUNC(cdotcw) (int *, float *, int *, float *, int *, float*); +int BLASFUNC(zdotuw) (int *, double *, int *, double *, int *, double*); +int BLASFUNC(zdotcw) (int *, double *, int *, double *, int *, double*); + +int BLASFUNC(saxpy) (int *, float *, float *, int *, float *, int *); +int BLASFUNC(daxpy) (int *, double *, double *, int *, double *, int *); +int BLASFUNC(qaxpy) (int *, double *, double *, int *, double *, int *); +int BLASFUNC(caxpy) (int *, float *, float *, int *, float *, int *); +int BLASFUNC(zaxpy) (int *, double *, double *, int *, double *, int *); +int BLASFUNC(xaxpy) (int *, double *, double *, int *, double *, int *); +int BLASFUNC(caxpyc)(int *, float *, float *, int *, float *, int *); +int BLASFUNC(zaxpyc)(int *, double *, double *, int *, double *, int *); +int BLASFUNC(xaxpyc)(int *, double *, double *, int *, double *, int *); + +int BLASFUNC(scopy) (int *, float *, int *, float *, int *); +int BLASFUNC(dcopy) (int *, double *, int *, double *, int *); +int BLASFUNC(qcopy) (int *, double *, int *, double *, int *); +int BLASFUNC(ccopy) (int *, float *, int *, float *, int *); +int BLASFUNC(zcopy) (int *, double *, int *, double *, int *); +int BLASFUNC(xcopy) (int *, double *, int *, double *, int *); + +int BLASFUNC(sswap) (int *, float *, int *, float *, int *); +int BLASFUNC(dswap) (int *, double *, int *, double *, int *); +int BLASFUNC(qswap) (int *, double *, int *, double *, int *); +int BLASFUNC(cswap) (int *, float *, int *, float *, int *); +int BLASFUNC(zswap) (int *, double *, int *, double *, int *); +int BLASFUNC(xswap) (int *, double *, int *, double *, int *); + +float BLASFUNC(sasum) (int *, float *, int *); +float BLASFUNC(scasum)(int *, float *, int *); +double BLASFUNC(dasum) (int *, double *, int *); +double BLASFUNC(qasum) (int *, double *, int *); +double BLASFUNC(dzasum)(int *, double *, int *); +double BLASFUNC(qxasum)(int *, double *, int *); + +int BLASFUNC(isamax)(int *, float *, int *); +int BLASFUNC(idamax)(int *, double *, int *); +int BLASFUNC(iqamax)(int *, double *, int *); +int BLASFUNC(icamax)(int *, float *, int *); +int BLASFUNC(izamax)(int *, double *, int *); +int BLASFUNC(ixamax)(int *, double *, int *); + +int BLASFUNC(ismax) (int *, float *, int *); +int BLASFUNC(idmax) (int *, double *, int *); +int BLASFUNC(iqmax) (int *, double *, int *); +int BLASFUNC(icmax) (int *, float *, int *); +int BLASFUNC(izmax) (int *, double *, int *); +int BLASFUNC(ixmax) (int *, double *, int *); + +int BLASFUNC(isamin)(int *, float *, int *); +int BLASFUNC(idamin)(int *, double *, int *); +int BLASFUNC(iqamin)(int *, double *, int *); +int BLASFUNC(icamin)(int *, float *, int *); +int BLASFUNC(izamin)(int *, double *, int *); +int BLASFUNC(ixamin)(int *, double *, int *); + +int BLASFUNC(ismin)(int *, float *, int *); +int BLASFUNC(idmin)(int *, double *, int *); +int BLASFUNC(iqmin)(int *, double *, int *); +int BLASFUNC(icmin)(int *, float *, int *); +int BLASFUNC(izmin)(int *, double *, int *); +int BLASFUNC(ixmin)(int *, double *, int *); + +float BLASFUNC(samax) (int *, float *, int *); +double BLASFUNC(damax) (int *, double *, int *); +double BLASFUNC(qamax) (int *, double *, int *); +float BLASFUNC(scamax)(int *, float *, int *); +double BLASFUNC(dzamax)(int *, double *, int *); +double BLASFUNC(qxamax)(int *, double *, int *); + +float BLASFUNC(samin) (int *, float *, int *); +double BLASFUNC(damin) (int *, double *, int *); +double BLASFUNC(qamin) (int *, double *, int *); +float BLASFUNC(scamin)(int *, float *, int *); +double BLASFUNC(dzamin)(int *, double *, int *); +double BLASFUNC(qxamin)(int *, double *, int *); + +float BLASFUNC(smax) (int *, float *, int *); +double BLASFUNC(dmax) (int *, double *, int *); +double BLASFUNC(qmax) (int *, double *, int *); +float BLASFUNC(scmax) (int *, float *, int *); +double BLASFUNC(dzmax) (int *, double *, int *); +double BLASFUNC(qxmax) (int *, double *, int *); + +float BLASFUNC(smin) (int *, float *, int *); +double BLASFUNC(dmin) (int *, double *, int *); +double BLASFUNC(qmin) (int *, double *, int *); +float BLASFUNC(scmin) (int *, float *, int *); +double BLASFUNC(dzmin) (int *, double *, int *); +double BLASFUNC(qxmin) (int *, double *, int *); + +int BLASFUNC(sscal) (int *, float *, float *, int *); +int BLASFUNC(dscal) (int *, double *, double *, int *); +int BLASFUNC(qscal) (int *, double *, double *, int *); +int BLASFUNC(cscal) (int *, float *, float *, int *); +int BLASFUNC(zscal) (int *, double *, double *, int *); +int BLASFUNC(xscal) (int *, double *, double *, int *); +int BLASFUNC(csscal)(int *, float *, float *, int *); +int BLASFUNC(zdscal)(int *, double *, double *, int *); +int BLASFUNC(xqscal)(int *, double *, double *, int *); + +float BLASFUNC(snrm2) (int *, float *, int *); +float BLASFUNC(scnrm2)(int *, float *, int *); + +double BLASFUNC(dnrm2) (int *, double *, int *); +double BLASFUNC(qnrm2) (int *, double *, int *); +double BLASFUNC(dznrm2)(int *, double *, int *); +double BLASFUNC(qxnrm2)(int *, double *, int *); + +int BLASFUNC(srot) (int *, float *, int *, float *, int *, float *, float *); +int BLASFUNC(drot) (int *, double *, int *, double *, int *, double *, double *); +int BLASFUNC(qrot) (int *, double *, int *, double *, int *, double *, double *); +int BLASFUNC(csrot) (int *, float *, int *, float *, int *, float *, float *); +int BLASFUNC(zdrot) (int *, double *, int *, double *, int *, double *, double *); +int BLASFUNC(xqrot) (int *, double *, int *, double *, int *, double *, double *); + +int BLASFUNC(srotg) (float *, float *, float *, float *); +int BLASFUNC(drotg) (double *, double *, double *, double *); +int BLASFUNC(qrotg) (double *, double *, double *, double *); +int BLASFUNC(crotg) (float *, float *, float *, float *); +int BLASFUNC(zrotg) (double *, double *, double *, double *); +int BLASFUNC(xrotg) (double *, double *, double *, double *); + +int BLASFUNC(srotmg)(float *, float *, float *, float *, float *); +int BLASFUNC(drotmg)(double *, double *, double *, double *, double *); + +int BLASFUNC(srotm) (int *, float *, int *, float *, int *, float *); +int BLASFUNC(drotm) (int *, double *, int *, double *, int *, double *); +int BLASFUNC(qrotm) (int *, double *, int *, double *, int *, double *); + +/* Level 2 routines */ + +int BLASFUNC(sger)(int *, int *, float *, float *, int *, + float *, int *, float *, int *); +int BLASFUNC(dger)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); +int BLASFUNC(qger)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); +int BLASFUNC(cgeru)(int *, int *, float *, float *, int *, + float *, int *, float *, int *); +int BLASFUNC(cgerc)(int *, int *, float *, float *, int *, + float *, int *, float *, int *); +int BLASFUNC(zgeru)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); +int BLASFUNC(zgerc)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); +int BLASFUNC(xgeru)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); +int BLASFUNC(xgerc)(int *, int *, double *, double *, int *, + double *, int *, double *, int *); + +int BLASFUNC(sgemv)(char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dgemv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(qgemv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(cgemv)(char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zgemv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xgemv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(strsv) (char *, char *, char *, int *, float *, int *, + float *, int *); +int BLASFUNC(dtrsv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(qtrsv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(ctrsv) (char *, char *, char *, int *, float *, int *, + float *, int *); +int BLASFUNC(ztrsv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(xtrsv) (char *, char *, char *, int *, double *, int *, + double *, int *); + +int BLASFUNC(stpsv) (char *, char *, char *, int *, float *, float *, int *); +int BLASFUNC(dtpsv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(qtpsv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(ctpsv) (char *, char *, char *, int *, float *, float *, int *); +int BLASFUNC(ztpsv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(xtpsv) (char *, char *, char *, int *, double *, double *, int *); + +int BLASFUNC(strmv) (char *, char *, char *, int *, float *, int *, + float *, int *); +int BLASFUNC(dtrmv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(qtrmv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(ctrmv) (char *, char *, char *, int *, float *, int *, + float *, int *); +int BLASFUNC(ztrmv) (char *, char *, char *, int *, double *, int *, + double *, int *); +int BLASFUNC(xtrmv) (char *, char *, char *, int *, double *, int *, + double *, int *); + +int BLASFUNC(stpmv) (char *, char *, char *, int *, float *, float *, int *); +int BLASFUNC(dtpmv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(qtpmv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(ctpmv) (char *, char *, char *, int *, float *, float *, int *); +int BLASFUNC(ztpmv) (char *, char *, char *, int *, double *, double *, int *); +int BLASFUNC(xtpmv) (char *, char *, char *, int *, double *, double *, int *); + +int BLASFUNC(stbmv) (char *, char *, char *, int *, int *, float *, int *, float *, int *); +int BLASFUNC(dtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(qtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(ctbmv) (char *, char *, char *, int *, int *, float *, int *, float *, int *); +int BLASFUNC(ztbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(xtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); + +int BLASFUNC(stbsv) (char *, char *, char *, int *, int *, float *, int *, float *, int *); +int BLASFUNC(dtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(qtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(ctbsv) (char *, char *, char *, int *, int *, float *, int *, float *, int *); +int BLASFUNC(ztbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); +int BLASFUNC(xtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *); + +int BLASFUNC(ssymv) (char *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dsymv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(qsymv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(csymv) (char *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zsymv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xsymv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(sspmv) (char *, int *, float *, float *, + float *, int *, float *, float *, int *); +int BLASFUNC(dspmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); +int BLASFUNC(qspmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); +int BLASFUNC(cspmv) (char *, int *, float *, float *, + float *, int *, float *, float *, int *); +int BLASFUNC(zspmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); +int BLASFUNC(xspmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); + +int BLASFUNC(ssyr) (char *, int *, float *, float *, int *, + float *, int *); +int BLASFUNC(dsyr) (char *, int *, double *, double *, int *, + double *, int *); +int BLASFUNC(qsyr) (char *, int *, double *, double *, int *, + double *, int *); +int BLASFUNC(csyr) (char *, int *, float *, float *, int *, + float *, int *); +int BLASFUNC(zsyr) (char *, int *, double *, double *, int *, + double *, int *); +int BLASFUNC(xsyr) (char *, int *, double *, double *, int *, + double *, int *); + +int BLASFUNC(ssyr2) (char *, int *, float *, + float *, int *, float *, int *, float *, int *); +int BLASFUNC(dsyr2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); +int BLASFUNC(qsyr2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); +int BLASFUNC(csyr2) (char *, int *, float *, + float *, int *, float *, int *, float *, int *); +int BLASFUNC(zsyr2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); +int BLASFUNC(xsyr2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); + +int BLASFUNC(sspr) (char *, int *, float *, float *, int *, + float *); +int BLASFUNC(dspr) (char *, int *, double *, double *, int *, + double *); +int BLASFUNC(qspr) (char *, int *, double *, double *, int *, + double *); +int BLASFUNC(cspr) (char *, int *, float *, float *, int *, + float *); +int BLASFUNC(zspr) (char *, int *, double *, double *, int *, + double *); +int BLASFUNC(xspr) (char *, int *, double *, double *, int *, + double *); + +int BLASFUNC(sspr2) (char *, int *, float *, + float *, int *, float *, int *, float *); +int BLASFUNC(dspr2) (char *, int *, double *, + double *, int *, double *, int *, double *); +int BLASFUNC(qspr2) (char *, int *, double *, + double *, int *, double *, int *, double *); +int BLASFUNC(cspr2) (char *, int *, float *, + float *, int *, float *, int *, float *); +int BLASFUNC(zspr2) (char *, int *, double *, + double *, int *, double *, int *, double *); +int BLASFUNC(xspr2) (char *, int *, double *, + double *, int *, double *, int *, double *); + +int BLASFUNC(cher) (char *, int *, float *, float *, int *, + float *, int *); +int BLASFUNC(zher) (char *, int *, double *, double *, int *, + double *, int *); +int BLASFUNC(xher) (char *, int *, double *, double *, int *, + double *, int *); + +int BLASFUNC(chpr) (char *, int *, float *, float *, int *, float *); +int BLASFUNC(zhpr) (char *, int *, double *, double *, int *, double *); +int BLASFUNC(xhpr) (char *, int *, double *, double *, int *, double *); + +int BLASFUNC(cher2) (char *, int *, float *, + float *, int *, float *, int *, float *, int *); +int BLASFUNC(zher2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); +int BLASFUNC(xher2) (char *, int *, double *, + double *, int *, double *, int *, double *, int *); + +int BLASFUNC(chpr2) (char *, int *, float *, + float *, int *, float *, int *, float *); +int BLASFUNC(zhpr2) (char *, int *, double *, + double *, int *, double *, int *, double *); +int BLASFUNC(xhpr2) (char *, int *, double *, + double *, int *, double *, int *, double *); + +int BLASFUNC(chemv) (char *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zhemv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xhemv) (char *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(chpmv) (char *, int *, float *, float *, + float *, int *, float *, float *, int *); +int BLASFUNC(zhpmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); +int BLASFUNC(xhpmv) (char *, int *, double *, double *, + double *, int *, double *, double *, int *); + +int BLASFUNC(snorm)(char *, int *, int *, float *, int *); +int BLASFUNC(dnorm)(char *, int *, int *, double *, int *); +int BLASFUNC(cnorm)(char *, int *, int *, float *, int *); +int BLASFUNC(znorm)(char *, int *, int *, double *, int *); + +int BLASFUNC(sgbmv)(char *, int *, int *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dgbmv)(char *, int *, int *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(qgbmv)(char *, int *, int *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(cgbmv)(char *, int *, int *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zgbmv)(char *, int *, int *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xgbmv)(char *, int *, int *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(ssbmv)(char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dsbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(qsbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(csbmv)(char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zsbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xsbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(chbmv)(char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zhbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xhbmv)(char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +/* Level 3 routines */ + +int BLASFUNC(sgemm)(char *, char *, int *, int *, int *, float *, + float *, int *, float *, int *, float *, float *, int *); +int BLASFUNC(dgemm)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); +int BLASFUNC(qgemm)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); +int BLASFUNC(cgemm)(char *, char *, int *, int *, int *, float *, + float *, int *, float *, int *, float *, float *, int *); +int BLASFUNC(zgemm)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); +int BLASFUNC(xgemm)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); + +int BLASFUNC(cgemm3m)(char *, char *, int *, int *, int *, float *, + float *, int *, float *, int *, float *, float *, int *); +int BLASFUNC(zgemm3m)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); +int BLASFUNC(xgemm3m)(char *, char *, int *, int *, int *, double *, + double *, int *, double *, int *, double *, double *, int *); + +int BLASFUNC(sge2mm)(char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *, + float *, float *, int *); +int BLASFUNC(dge2mm)(char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *, + double *, double *, int *); +int BLASFUNC(cge2mm)(char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *, + float *, float *, int *); +int BLASFUNC(zge2mm)(char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *, + double *, double *, int *); + +int BLASFUNC(strsm)(char *, char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *); +int BLASFUNC(dtrsm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(qtrsm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(ctrsm)(char *, char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *); +int BLASFUNC(ztrsm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(xtrsm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); + +int BLASFUNC(strmm)(char *, char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *); +int BLASFUNC(dtrmm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(qtrmm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(ctrmm)(char *, char *, char *, char *, int *, int *, + float *, float *, int *, float *, int *); +int BLASFUNC(ztrmm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); +int BLASFUNC(xtrmm)(char *, char *, char *, char *, int *, int *, + double *, double *, int *, double *, int *); + +int BLASFUNC(ssymm)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dsymm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(qsymm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(csymm)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zsymm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xsymm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(csymm3m)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zsymm3m)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xsymm3m)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(ssyrk)(char *, char *, int *, int *, float *, float *, int *, + float *, float *, int *); +int BLASFUNC(dsyrk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); +int BLASFUNC(qsyrk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); +int BLASFUNC(csyrk)(char *, char *, int *, int *, float *, float *, int *, + float *, float *, int *); +int BLASFUNC(zsyrk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); +int BLASFUNC(xsyrk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); + +int BLASFUNC(ssyr2k)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(dsyr2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(qsyr2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(csyr2k)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zsyr2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(xsyr2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); + +int BLASFUNC(chemm)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zhemm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xhemm)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(chemm3m)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zhemm3m)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); +int BLASFUNC(xhemm3m)(char *, char *, int *, int *, double *, double *, int *, + double *, int *, double *, double *, int *); + +int BLASFUNC(cherk)(char *, char *, int *, int *, float *, float *, int *, + float *, float *, int *); +int BLASFUNC(zherk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); +int BLASFUNC(xherk)(char *, char *, int *, int *, double *, double *, int *, + double *, double *, int *); + +int BLASFUNC(cher2k)(char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zher2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(xher2k)(char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(cher2m)(char *, char *, char *, int *, int *, float *, float *, int *, + float *, int *, float *, float *, int *); +int BLASFUNC(zher2m)(char *, char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); +int BLASFUNC(xher2m)(char *, char *, char *, int *, int *, double *, double *, int *, + double*, int *, double *, double *, int *); + +int BLASFUNC(sgemt)(char *, int *, int *, float *, float *, int *, + float *, int *); +int BLASFUNC(dgemt)(char *, int *, int *, double *, double *, int *, + double *, int *); +int BLASFUNC(cgemt)(char *, int *, int *, float *, float *, int *, + float *, int *); +int BLASFUNC(zgemt)(char *, int *, int *, double *, double *, int *, + double *, int *); + +int BLASFUNC(sgema)(char *, char *, int *, int *, float *, + float *, int *, float *, float *, int *, float *, int *); +int BLASFUNC(dgema)(char *, char *, int *, int *, double *, + double *, int *, double*, double *, int *, double*, int *); +int BLASFUNC(cgema)(char *, char *, int *, int *, float *, + float *, int *, float *, float *, int *, float *, int *); +int BLASFUNC(zgema)(char *, char *, int *, int *, double *, + double *, int *, double*, double *, int *, double*, int *); + +int BLASFUNC(sgems)(char *, char *, int *, int *, float *, + float *, int *, float *, float *, int *, float *, int *); +int BLASFUNC(dgems)(char *, char *, int *, int *, double *, + double *, int *, double*, double *, int *, double*, int *); +int BLASFUNC(cgems)(char *, char *, int *, int *, float *, + float *, int *, float *, float *, int *, float *, int *); +int BLASFUNC(zgems)(char *, char *, int *, int *, double *, + double *, int *, double*, double *, int *, double*, int *); + +int BLASFUNC(sgetf2)(int *, int *, float *, int *, int *, int *); +int BLASFUNC(dgetf2)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(qgetf2)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(cgetf2)(int *, int *, float *, int *, int *, int *); +int BLASFUNC(zgetf2)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(xgetf2)(int *, int *, double *, int *, int *, int *); + +int BLASFUNC(sgetrf)(int *, int *, float *, int *, int *, int *); +int BLASFUNC(dgetrf)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(qgetrf)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(cgetrf)(int *, int *, float *, int *, int *, int *); +int BLASFUNC(zgetrf)(int *, int *, double *, int *, int *, int *); +int BLASFUNC(xgetrf)(int *, int *, double *, int *, int *, int *); + +int BLASFUNC(slaswp)(int *, float *, int *, int *, int *, int *, int *); +int BLASFUNC(dlaswp)(int *, double *, int *, int *, int *, int *, int *); +int BLASFUNC(qlaswp)(int *, double *, int *, int *, int *, int *, int *); +int BLASFUNC(claswp)(int *, float *, int *, int *, int *, int *, int *); +int BLASFUNC(zlaswp)(int *, double *, int *, int *, int *, int *, int *); +int BLASFUNC(xlaswp)(int *, double *, int *, int *, int *, int *, int *); + +int BLASFUNC(sgetrs)(char *, int *, int *, float *, int *, int *, float *, int *, int *); +int BLASFUNC(dgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *); +int BLASFUNC(qgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *); +int BLASFUNC(cgetrs)(char *, int *, int *, float *, int *, int *, float *, int *, int *); +int BLASFUNC(zgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *); +int BLASFUNC(xgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *); + +int BLASFUNC(sgesv)(int *, int *, float *, int *, int *, float *, int *, int *); +int BLASFUNC(dgesv)(int *, int *, double *, int *, int *, double*, int *, int *); +int BLASFUNC(qgesv)(int *, int *, double *, int *, int *, double*, int *, int *); +int BLASFUNC(cgesv)(int *, int *, float *, int *, int *, float *, int *, int *); +int BLASFUNC(zgesv)(int *, int *, double *, int *, int *, double*, int *, int *); +int BLASFUNC(xgesv)(int *, int *, double *, int *, int *, double*, int *, int *); + +int BLASFUNC(spotf2)(char *, int *, float *, int *, int *); +int BLASFUNC(dpotf2)(char *, int *, double *, int *, int *); +int BLASFUNC(qpotf2)(char *, int *, double *, int *, int *); +int BLASFUNC(cpotf2)(char *, int *, float *, int *, int *); +int BLASFUNC(zpotf2)(char *, int *, double *, int *, int *); +int BLASFUNC(xpotf2)(char *, int *, double *, int *, int *); + +int BLASFUNC(spotrf)(char *, int *, float *, int *, int *); +int BLASFUNC(dpotrf)(char *, int *, double *, int *, int *); +int BLASFUNC(qpotrf)(char *, int *, double *, int *, int *); +int BLASFUNC(cpotrf)(char *, int *, float *, int *, int *); +int BLASFUNC(zpotrf)(char *, int *, double *, int *, int *); +int BLASFUNC(xpotrf)(char *, int *, double *, int *, int *); + +int BLASFUNC(slauu2)(char *, int *, float *, int *, int *); +int BLASFUNC(dlauu2)(char *, int *, double *, int *, int *); +int BLASFUNC(qlauu2)(char *, int *, double *, int *, int *); +int BLASFUNC(clauu2)(char *, int *, float *, int *, int *); +int BLASFUNC(zlauu2)(char *, int *, double *, int *, int *); +int BLASFUNC(xlauu2)(char *, int *, double *, int *, int *); + +int BLASFUNC(slauum)(char *, int *, float *, int *, int *); +int BLASFUNC(dlauum)(char *, int *, double *, int *, int *); +int BLASFUNC(qlauum)(char *, int *, double *, int *, int *); +int BLASFUNC(clauum)(char *, int *, float *, int *, int *); +int BLASFUNC(zlauum)(char *, int *, double *, int *, int *); +int BLASFUNC(xlauum)(char *, int *, double *, int *, int *); + +int BLASFUNC(strti2)(char *, char *, int *, float *, int *, int *); +int BLASFUNC(dtrti2)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(qtrti2)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(ctrti2)(char *, char *, int *, float *, int *, int *); +int BLASFUNC(ztrti2)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(xtrti2)(char *, char *, int *, double *, int *, int *); + +int BLASFUNC(strtri)(char *, char *, int *, float *, int *, int *); +int BLASFUNC(dtrtri)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(qtrtri)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(ctrtri)(char *, char *, int *, float *, int *, int *); +int BLASFUNC(ztrtri)(char *, char *, int *, double *, int *, int *); +int BLASFUNC(xtrtri)(char *, char *, int *, double *, int *, int *); + +int BLASFUNC(spotri)(char *, int *, float *, int *, int *); +int BLASFUNC(dpotri)(char *, int *, double *, int *, int *); +int BLASFUNC(qpotri)(char *, int *, double *, int *, int *); +int BLASFUNC(cpotri)(char *, int *, float *, int *, int *); +int BLASFUNC(zpotri)(char *, int *, double *, int *, int *); +int BLASFUNC(xpotri)(char *, int *, double *, int *, int *); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h index 7d509e78f..5b979ebf8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h @@ -29,6 +29,16 @@ operator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const */ EIGEN_MAKE_CWISE_BINARY_OP(min,internal::scalar_min_op) +/** \returns an expression of the coefficient-wise min of \c *this and scalar \a other + * + * \sa max() + */ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +(min)(const Scalar &other) const +{ + return (min)(Derived::PlainObject::Constant(rows(), cols(), other)); +} + /** \returns an expression of the coefficient-wise max of \c *this and \a other * * Example: \include Cwise_max.cpp @@ -38,6 +48,16 @@ EIGEN_MAKE_CWISE_BINARY_OP(min,internal::scalar_min_op) */ EIGEN_MAKE_CWISE_BINARY_OP(max,internal::scalar_max_op) +/** \returns an expression of the coefficient-wise max of \c *this and scalar \a other + * + * \sa min() + */ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +(max)(const Scalar &other) const +{ + return (max)(Derived::PlainObject::Constant(rows(), cols(), other)); +} + /** \returns an expression of the coefficient-wise \< operator of *this and \a other * * Example: \include Cwise_less.cpp @@ -141,3 +161,39 @@ operator-(const Scalar& scalar,const EIGEN_CURRENT_STORAGE_BASE_CLASS& { return (-other) + scalar; } + +/** \returns an expression of the coefficient-wise && operator of *this and \a other + * + * \warning this operator is for expression of bool only. + * + * Example: \include Cwise_boolean_and.cpp + * Output: \verbinclude Cwise_boolean_and.out + * + * \sa operator||(), select() + */ +template +inline const CwiseBinaryOp +operator&&(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + EIGEN_STATIC_ASSERT((internal::is_same::value && internal::is_same::value), + THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL); + return CwiseBinaryOp(derived(),other.derived()); +} + +/** \returns an expression of the coefficient-wise || operator of *this and \a other + * + * \warning this operator is for expression of bool only. + * + * Example: \include Cwise_boolean_or.cpp + * Output: \verbinclude Cwise_boolean_or.out + * + * \sa operator&&(), select() + */ +template +inline const CwiseBinaryOp +operator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const +{ + EIGEN_STATIC_ASSERT((internal::is_same::value && internal::is_same::value), + THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL); + return CwiseBinaryOp(derived(),other.derived()); +} diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h index 35183f91f..566f4c1f4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h @@ -91,6 +91,16 @@ cwiseMin(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); } +/** \returns an expression of the coefficient-wise min of *this and scalar \a other + * + * \sa class CwiseBinaryOp, min() + */ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +cwiseMin(const Scalar &other) const +{ + return cwiseMin(Derived::PlainObject::Constant(rows(), cols(), other)); +} + /** \returns an expression of the coefficient-wise max of *this and \a other * * Example: \include MatrixBase_cwiseMax.cpp @@ -105,6 +115,17 @@ cwiseMax(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); } +/** \returns an expression of the coefficient-wise max of *this and scalar \a other + * + * \sa class CwiseBinaryOp, min() + */ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const ConstantReturnType> +cwiseMax(const Scalar &other) const +{ + return cwiseMax(Derived::PlainObject::Constant(rows(), cols(), other)); +} + + /** \returns an expression of the coefficient-wise quotient of *this and \a other * * Example: \include MatrixBase_cwiseQuotient.cpp diff --git a/gtsam/3rdparty/Eigen/bench/BenchSparseUtil.h b/gtsam/3rdparty/Eigen/bench/BenchSparseUtil.h index ff836bffe..13981f6b7 100644 --- a/gtsam/3rdparty/Eigen/bench/BenchSparseUtil.h +++ b/gtsam/3rdparty/Eigen/bench/BenchSparseUtil.h @@ -26,7 +26,7 @@ typedef SparseMatrix EigenSparseMatrix; void fillMatrix(float density, int rows, int cols, EigenSparseMatrix& dst) { - dst.reserve(rows*cols*density); + dst.reserve(double(rows)*cols*density); for(int j = 0; j < cols; j++) { for(int i = 0; i < rows; i++) @@ -122,22 +122,24 @@ void eiToCSparse(const EigenSparseMatrix& src, cs* &dst) #include #include #include -// #include -// using namespace boost; -// using namespace boost::numeric; -// using namespace boost::numeric::ublas; +typedef boost::numeric::ublas::compressed_matrix UBlasSparse; -typedef boost::numeric::ublas::compressed_matrix UblasMatrix; - -void eiToUblas(const EigenSparseMatrix& src, UblasMatrix& dst) +void eiToUblas(const EigenSparseMatrix& src, UBlasSparse& dst) { + dst.resize(src.rows(), src.cols(), false); for (int j=0; j +void eiToUblasVec(const EigenType& src, UblasType& dst) +{ + dst.resize(src.size()); + for (int j=0; j +#elif defined(__APPLE__) +#include +#include #else # include #endif @@ -76,6 +79,7 @@ public: inline void reset() { m_bests.fill(1e9); + m_worsts.fill(0); m_totals.setZero(); } inline void start() @@ -89,40 +93,52 @@ public: m_times[REAL_TIMER] = getRealTime() - m_starts[REAL_TIMER]; #if EIGEN_VERSION_AT_LEAST(2,90,0) m_bests = m_bests.cwiseMin(m_times); + m_worsts = m_worsts.cwiseMax(m_times); #else m_bests(0) = std::min(m_bests(0),m_times(0)); m_bests(1) = std::min(m_bests(1),m_times(1)); + m_worsts(0) = std::max(m_worsts(0),m_times(0)); + m_worsts(1) = std::max(m_worsts(1),m_times(1)); #endif m_totals += m_times; } /** Return the elapsed time in seconds between the last start/stop pair */ - inline double value(int TIMER = CPU_TIMER) + inline double value(int TIMER = CPU_TIMER) const { return m_times[TIMER]; } /** Return the best elapsed time in seconds */ - inline double best(int TIMER = CPU_TIMER) + inline double best(int TIMER = CPU_TIMER) const { return m_bests[TIMER]; } + /** Return the worst elapsed time in seconds + */ + inline double worst(int TIMER = CPU_TIMER) const + { + return m_worsts[TIMER]; + } + /** Return the total elapsed time in seconds. */ - inline double total(int TIMER = CPU_TIMER) + inline double total(int TIMER = CPU_TIMER) const { return m_totals[TIMER]; } - inline double getCpuTime() + inline double getCpuTime() const { #ifdef _WIN32 LARGE_INTEGER query_ticks; QueryPerformanceCounter(&query_ticks); return query_ticks.QuadPart/m_frequency; +#elif __APPLE__ + return double(mach_absolute_time())*1e-9; #else timespec ts; clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &ts); @@ -130,12 +146,14 @@ public: #endif } - inline double getRealTime() + inline double getRealTime() const { #ifdef _WIN32 SYSTEMTIME st; GetSystemTime(&st); return (double)st.wSecond + 1.e-3 * (double)st.wMilliseconds; +#elif __APPLE__ + return double(mach_absolute_time())*1e-9; #else timespec ts; clock_gettime(CLOCK_REALTIME, &ts); @@ -150,8 +168,11 @@ protected: Vector2d m_starts; Vector2d m_times; Vector2d m_bests; + Vector2d m_worsts; Vector2d m_totals; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; #define BENCH(TIMER,TRIES,REP,CODE) { \ diff --git a/gtsam/3rdparty/Eigen/bench/BenchUtil.h b/gtsam/3rdparty/Eigen/bench/BenchUtil.h index 9798fa385..8883a1380 100644 --- a/gtsam/3rdparty/Eigen/bench/BenchUtil.h +++ b/gtsam/3rdparty/Eigen/bench/BenchUtil.h @@ -69,4 +69,24 @@ void eiToGsl(const EigenMatrixType& src, gsl_matrix** dst) } #endif +#ifdef BENCH_UBLAS +#include +#include +template +void eiToUblas(const EigenMatrixType& src, UblasMatrixType& dst) +{ + dst.resize(src.rows(),src.cols()); + for (int j=0; j +void eiToUblasVec(const EigenType& src, UblasType& dst) +{ + dst.resize(src.size()); + for (int j=0; j(kc, mc, nc); + internal::computeProductBlockingSizes(kc, mc, nc); std::cout << "blocking size (mc x kc) = " << mc << " x " << kc << "\n"; C r = c; @@ -188,23 +189,22 @@ int main(int argc, char ** argv) blas_gemm(a,b,r); c.noalias() += a * b; if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; -// std::cerr << r << "\n\n" << c << "\n\n"; #else gemm(a,b,c); r.noalias() += a.cast() * b.cast(); if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; -// std::cerr << c << "\n\n"; -// std::cerr << r << "\n\n"; #endif #ifdef HAVE_BLAS BenchTimer tblas; + c = rc; BENCH(tblas, tries, rep, blas_gemm(a,b,c)); std::cout << "blas cpu " << tblas.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tblas.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tblas.total(CPU_TIMER) << "s)\n"; std::cout << "blas real " << tblas.best(REAL_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tblas.best(REAL_TIMER))*1e-9 << " GFLOPS \t(" << tblas.total(REAL_TIMER) << "s)\n"; #endif BenchTimer tmt; + c = rc; BENCH(tmt, tries, rep, gemm(a,b,c)); std::cout << "eigen cpu " << tmt.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(CPU_TIMER) << "s)\n"; std::cout << "eigen real " << tmt.best(REAL_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(REAL_TIMER) << "s)\n"; @@ -213,8 +213,9 @@ int main(int argc, char ** argv) if(procs>1) { BenchTimer tmono; - //omp_set_num_threads(1); - Eigen::setNbThreads(1); + omp_set_num_threads(1); + Eigen::internal::setNbThreads(1); + c = rc; BENCH(tmono, tries, rep, gemm(a,b,c)); std::cout << "eigen mono cpu " << tmono.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmono.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmono.total(CPU_TIMER) << "s)\n"; std::cout << "eigen mono real " << tmono.best(REAL_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmono.best(REAL_TIMER))*1e-9 << " GFLOPS \t(" << tmono.total(REAL_TIMER) << "s)\n"; diff --git a/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt index 95ffbf42a..119b470d9 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt @@ -2,7 +2,7 @@ PROJECT(BTL) CMAKE_MINIMUM_REQUIRED(VERSION 2.6.2) -set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) +set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake ${Eigen_SOURCE_DIR}/cmake) include(MacroOptionalAddSubdirectory) OPTION(BTL_NOVEC "Disable SSE/Altivec optimizations when possible" OFF) @@ -90,17 +90,14 @@ endmacro(btl_add_target_property) ENABLE_TESTING() add_subdirectory(libs/eigen3) -# add_subdirectory(libs/hand_vec) +add_subdirectory(libs/eigen2) +add_subdirectory(libs/BLAS) +add_subdirectory(libs/ublas) add_subdirectory(libs/gmm) add_subdirectory(libs/mtl4) -add_subdirectory(libs/ublas) add_subdirectory(libs/blitz) add_subdirectory(libs/tvmet) -add_subdirectory(libs/C_BLAS) -add_subdirectory(libs/f77) -add_subdirectory(libs/C) add_subdirectory(libs/STL) -add_subdirectory(libs/STL_algo) add_subdirectory(data) diff --git a/gtsam/3rdparty/Eigen/bench/btl/actions/action_aat_product.hh b/gtsam/3rdparty/Eigen/bench/btl/actions/action_aat_product.hh index 92930e219..aa5b35c94 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/actions/action_aat_product.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/actions/action_aat_product.hh @@ -87,7 +87,7 @@ public : } double nb_op_base( void ){ - return 2.0*_size*_size*_size; + return double(_size)*double(_size)*double(_size); } inline void initialize( void ){ diff --git a/gtsam/3rdparty/Eigen/bench/btl/actions/action_hessenberg.hh b/gtsam/3rdparty/Eigen/bench/btl/actions/action_hessenberg.hh index a46964657..2100ebd89 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/actions/action_hessenberg.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/actions/action_hessenberg.hh @@ -136,14 +136,17 @@ public : Action_tridiagonalization( int size ):_size(size) { - MESSAGE("Action_hessenberg Ctor"); + MESSAGE("Action_tridiagonalization Ctor"); // STL vector initialization - typename Interface::stl_matrix tmp; - init_matrix(tmp,_size); - init_matrix(X_stl,_size); - STL_interface::ata_product(tmp,X_stl,_size); - + init_matrix(X_stl,_size); + + for(int i=0; i<_size; ++i) + { + for(int j=0; j(C_stl,_size); init_matrix(resu_stl,_size); @@ -155,9 +158,9 @@ public : _cost = 0; for (int j=0; j<_size-2; ++j) { - int r = std::max(0,_size-j-1); - int b = std::max(0,_size-j-2); - _cost += 6 + 3*b + r*r*8; + double r = std::max(0,_size-j-1); + double b = std::max(0,_size-j-2); + _cost += 6. + 3.*b + r*r*8.; } } diff --git a/gtsam/3rdparty/Eigen/bench/btl/actions/basic_actions.hh b/gtsam/3rdparty/Eigen/bench/btl/actions/basic_actions.hh index 62442f01f..a3333ea26 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/actions/basic_actions.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/actions/basic_actions.hh @@ -6,7 +6,7 @@ #include "action_atv_product.hh" #include "action_matrix_matrix_product.hh" -#include "action_ata_product.hh" +// #include "action_ata_product.hh" #include "action_aat_product.hh" #include "action_trisolve.hh" diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindEigen3.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindEigen3.cmake deleted file mode 100644 index 9c546a05d..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindEigen3.cmake +++ /dev/null @@ -1,81 +0,0 @@ -# - Try to find Eigen3 lib -# -# This module supports requiring a minimum version, e.g. you can do -# find_package(Eigen3 3.1.2) -# to require version 3.1.2 or newer of Eigen3. -# -# Once done this will define -# -# EIGEN3_FOUND - system has eigen lib with correct version -# EIGEN3_INCLUDE_DIR - the eigen include directory -# EIGEN3_VERSION - eigen version - -# Copyright (c) 2006, 2007 Montel Laurent, -# Copyright (c) 2008, 2009 Gael Guennebaud, -# Copyright (c) 2009 Benoit Jacob -# Redistribution and use is allowed according to the terms of the 2-clause BSD license. - -if(NOT Eigen3_FIND_VERSION) - if(NOT Eigen3_FIND_VERSION_MAJOR) - set(Eigen3_FIND_VERSION_MAJOR 2) - endif(NOT Eigen3_FIND_VERSION_MAJOR) - if(NOT Eigen3_FIND_VERSION_MINOR) - set(Eigen3_FIND_VERSION_MINOR 91) - endif(NOT Eigen3_FIND_VERSION_MINOR) - if(NOT Eigen3_FIND_VERSION_PATCH) - set(Eigen3_FIND_VERSION_PATCH 0) - endif(NOT Eigen3_FIND_VERSION_PATCH) - - set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") -endif(NOT Eigen3_FIND_VERSION) - -macro(_eigen3_check_version) - file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) - - string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") - set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") - set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") - set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") - - set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) - if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - set(EIGEN3_VERSION_OK FALSE) - else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - set(EIGEN3_VERSION_OK TRUE) - endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - - if(NOT EIGEN3_VERSION_OK) - - message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " - "but at least version ${Eigen3_FIND_VERSION} is required") - endif(NOT EIGEN3_VERSION_OK) -endmacro(_eigen3_check_version) - -if (EIGEN3_INCLUDE_DIR) - - # in cache already - _eigen3_check_version() - set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) - -else (EIGEN3_INCLUDE_DIR) - - find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library - PATHS - ${CMAKE_INSTALL_PREFIX}/include - ${KDE4_INCLUDE_DIR} - PATH_SUFFIXES eigen3 eigen - ) - - if(EIGEN3_INCLUDE_DIR) - _eigen3_check_version() - endif(EIGEN3_INCLUDE_DIR) - - include(FindPackageHandleStandardArgs) - find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) - - mark_as_advanced(EIGEN3_INCLUDE_DIR) - -endif(EIGEN3_INCLUDE_DIR) - diff --git a/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt b/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt index da80f56a0..e32213e22 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt @@ -5,6 +5,7 @@ axpby ; "{/*1.5 Y = alpha X + beta Y}" ; "vector size" ; 5:1000000 axpy ; "{/*1.5 Y += alpha X}" ; "vector size" ; 5:1000000 matrix_matrix ; "{/*1.5 matrix matrix product}" ; "matrix size" ; 4:3000 matrix_vector ; "{/*1.5 matrix vector product}" ; "matrix size" ; 4:3000 +trmm ; "{/*1.5 triangular matrix matrix product}" ; "matrix size" ; 4:3000 trisolve_vector ; "{/*1.5 triangular solver - vector (X = inv(L) X)}" ; "size" ; 4:3000 trisolve_matrix ; "{/*1.5 triangular solver - matrix (M = inv(L) M)}" ; "size" ; 4:3000 cholesky ; "{/*1.5 Cholesky decomposition}" ; "matrix size" ; 4:3000 diff --git a/gtsam/3rdparty/Eigen/bench/btl/data/go_mean b/gtsam/3rdparty/Eigen/bench/btl/data/go_mean index 37f29fa17..42338ca27 100755 --- a/gtsam/3rdparty/Eigen/bench/btl/data/go_mean +++ b/gtsam/3rdparty/Eigen/bench/btl/data/go_mean @@ -27,7 +27,7 @@ echo '
    '\ '
  • ' `cat /proc/cpuinfo | grep "model name" | head -n 1`\ ' (' `uname -m` ')
  • '\ '
  • compiler: ' `cat compiler_version.txt` '
  • '\ - '
  • eigen2: ' `svn info $EIGENDIR | grep Revision` '
  • '\ + '
  • eigen3: ' `hg identify -i $EIGENDIR` '
  • '\ '
' \ '

' >> $webpagefilename @@ -37,11 +37,11 @@ source mk_mean_script.sh matrix_vector $1 11 50 300 1000 $mode $prefix source mk_mean_script.sh atv $1 11 50 300 1000 $mode $prefix source mk_mean_script.sh matrix_matrix $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh aat $1 11 100 300 1000 $mode $prefix -source mk_mean_script.sh ata $1 11 100 300 1000 $mode $prefix +# source mk_mean_script.sh ata $1 11 100 300 1000 $mode $prefix +source mk_mean_script.sh trmm $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh trisolve_vector $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh trisolve_matrix $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh cholesky $1 11 100 300 1000 $mode $prefix -source mk_mean_script.sh complete_lu_decomp $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh partial_lu_decomp $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh tridiagonalization $1 11 100 300 1000 $mode $prefix source mk_mean_script.sh hessenberg $1 11 100 300 1000 $mode $prefix @@ -49,6 +49,7 @@ source mk_mean_script.sh symv $1 11 50 300 1000 $mode $prefix source mk_mean_script.sh syr2 $1 11 50 300 1000 $mode $prefix source mk_mean_script.sh ger $1 11 50 300 1000 $mode $prefix source mk_mean_script.sh rot $1 11 2500 100000 250000 $mode $prefix +source mk_mean_script.sh complete_lu_decomp $1 11 100 300 1000 $mode $prefix fi diff --git a/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt b/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt index 82b09ce26..6844bab28 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt @@ -1,10 +1,12 @@ eigen3 ; with lines lw 4 lt 1 lc rgbcolor "black" +eigen2 ; with lines lw 3 lt 1 lc rgbcolor "#999999" +EigenBLAS ; with lines lw 3 lt 3 lc rgbcolor "#999999" eigen3_novec ; with lines lw 2 lt 1 lc rgbcolor "#999999" eigen3_nogccvec ; with lines lw 2 lt 2 lc rgbcolor "#991010" -INTEL_MKL ; with lines lw 3 lt 2 lc rgbcolor "#00b7ff" -ATLAS ; with lines lw 3 lt 1 lc rgbcolor "#52e657" +INTEL_MKL ; with lines lw 3 lt 1 lc rgbcolor "#ff0000" +ATLAS ; with lines lw 3 lt 1 lc rgbcolor "#008000" gmm ; with lines lw 3 lt 1 lc rgbcolor "#0000ff" -ublas ; with lines lw 3 lt 1 lc rgbcolor "#ff0000" +ublas ; with lines lw 3 lt 1 lc rgbcolor "#00b7ff" mtl4 ; with lines lw 3 lt 1 lc rgbcolor "#d18847" blitz ; with lines lw 3 lt 1 lc rgbcolor "#ff00ff" F77 ; with lines lw 3 lt 3 lc rgbcolor "#e6e64c" diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt similarity index 69% rename from gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/CMakeLists.txt rename to gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt index 59065cb9b..de42fe047 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt @@ -1,7 +1,6 @@ find_package(ATLAS) if (ATLAS_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/libs/f77) btl_add_bench(btl_atlas main.cpp) if(BUILD_btl_atlas) target_link_libraries(btl_atlas ${ATLAS_LIBRARIES}) @@ -11,7 +10,6 @@ endif (ATLAS_FOUND) find_package(MKL) if (MKL_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/libs/f77) btl_add_bench(btl_mkl main.cpp) if(BUILD_btl_mkl) target_link_libraries(btl_mkl ${MKL_LIBRARIES}) @@ -19,33 +17,44 @@ if (MKL_FOUND) endif(BUILD_btl_mkl) endif (MKL_FOUND) -find_package(GOTO) -if (GOTO_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/libs/f77) - btl_add_bench(btl_goto main.cpp) - if(BUILD_btl_goto) - target_link_libraries(btl_goto ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO -DPUREBLAS") - endif(BUILD_btl_goto) -endif (GOTO_FOUND) - find_package(GOTO2) if (GOTO2_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/libs/f77) btl_add_bench(btl_goto2 main.cpp) if(BUILD_btl_goto2) target_link_libraries(btl_goto2 ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto2 PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO2 -DPUREBLAS") + set_target_properties(btl_goto2 PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO2") endif(BUILD_btl_goto2) endif (GOTO2_FOUND) +find_package(GOTO) +if (GOTO_FOUND) + if(GOTO2_FOUND) + btl_add_bench(btl_goto main.cpp OFF) + else() + btl_add_bench(btl_goto main.cpp) + endif() + if(BUILD_btl_goto) + target_link_libraries(btl_goto ${GOTO_LIBRARIES} ) + set_target_properties(btl_goto PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO") + endif(BUILD_btl_goto) +endif (GOTO_FOUND) + find_package(ACML) if (ACML_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/libs/f77) btl_add_bench(btl_acml main.cpp) if(BUILD_btl_acml) target_link_libraries(btl_acml ${ACML_LIBRARIES} ) - set_target_properties(btl_acml PROPERTIES COMPILE_FLAGS "-DCBLASNAME=ACML -DHAS_LAPACK=1 -DPUREBLAS") + set_target_properties(btl_acml PROPERTIES COMPILE_FLAGS "-DCBLASNAME=ACML -DHAS_LAPACK=1") endif(BUILD_btl_acml) endif (ACML_FOUND) + +if(Eigen_SOURCE_DIR AND CMAKE_Fortran_COMPILER_WORKS) + # we are inside Eigen and blas/lapack interface is compilable + include_directories(${Eigen_SOURCE_DIR}) + btl_add_bench(btl_eigenblas main.cpp) + if(BUILD_btl_eigenblas) + target_link_libraries(btl_eigenblas eigen_blas eigen_lapack ) + set_target_properties(btl_eigenblas PROPERTIES COMPILE_FLAGS "-DCBLASNAME=EigenBLAS") + endif() +endif() diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/blas.h b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas.h similarity index 100% rename from gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/blas.h rename to gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas.h diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface.hh new file mode 100644 index 000000000..651054632 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface.hh @@ -0,0 +1,83 @@ +//===================================================== +// File : blas_interface.hh +// Author : L. Plagne +// Copyright (C) EDF R&D, lun sep 30 14:23:28 CEST 2002 +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#ifndef blas_PRODUIT_MATRICE_VECTEUR_HH +#define blas_PRODUIT_MATRICE_VECTEUR_HH + +#include +#include +extern "C" +{ +#include "blas.h" + + // Cholesky Factorization +// void spotrf_(const char* uplo, const int* n, float *a, const int* ld, int* info); +// void dpotrf_(const char* uplo, const int* n, double *a, const int* ld, int* info); + void ssytrd_(char *uplo, const int *n, float *a, const int *lda, float *d, float *e, float *tau, float *work, int *lwork, int *info ); + void dsytrd_(char *uplo, const int *n, double *a, const int *lda, double *d, double *e, double *tau, double *work, int *lwork, int *info ); + void sgehrd_( const int *n, int *ilo, int *ihi, float *a, const int *lda, float *tau, float *work, int *lwork, int *info ); + void dgehrd_( const int *n, int *ilo, int *ihi, double *a, const int *lda, double *tau, double *work, int *lwork, int *info ); + + // LU row pivoting +// void dgetrf_( int *m, int *n, double *a, int *lda, int *ipiv, int *info ); +// void sgetrf_(const int* m, const int* n, float *a, const int* ld, int* ipivot, int* info); + // LU full pivoting + void sgetc2_(const int* n, float *a, const int *lda, int *ipiv, int *jpiv, int*info ); + void dgetc2_(const int* n, double *a, const int *lda, int *ipiv, int *jpiv, int*info ); +#ifdef HAS_LAPACK +#endif +} + +#define MAKE_STRING2(S) #S +#define MAKE_STRING(S) MAKE_STRING2(S) + +#define CAT2(A,B) A##B +#define CAT(A,B) CAT2(A,B) + + +template class blas_interface; + + +static char notrans = 'N'; +static char trans = 'T'; +static char nonunit = 'N'; +static char lower = 'L'; +static char right = 'R'; +static char left = 'L'; +static int intone = 1; + + + +#define SCALAR float +#define SCALAR_PREFIX s +#include "blas_interface_impl.hh" +#undef SCALAR +#undef SCALAR_PREFIX + + +#define SCALAR double +#define SCALAR_PREFIX d +#include "blas_interface_impl.hh" +#undef SCALAR +#undef SCALAR_PREFIX + +#endif + + + diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh new file mode 100644 index 000000000..0e84df038 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh @@ -0,0 +1,151 @@ + +#define BLAS_FUNC(NAME) CAT(CAT(SCALAR_PREFIX,NAME),_) + +template<> class blas_interface : public c_interface_base +{ + +public : + + static SCALAR fone; + static SCALAR fzero; + + static inline std::string name() + { + return MAKE_STRING(CBLASNAME); + } + + static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + BLAS_FUNC(gemv)(¬rans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone); + } + + static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + BLAS_FUNC(symv)(&lower, &N,&fone,A,&N,B,&intone,&fzero,X,&intone); + } + + static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + BLAS_FUNC(syr2)(&lower,&N,&fone,B,&intone,X,&intone,A,&N); + } + + static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ + BLAS_FUNC(ger)(&N,&N,&fone,X,&intone,Y,&intone,A,&N); + } + + static inline void rot(gene_vector & A, gene_vector & B, SCALAR c, SCALAR s, int N){ + BLAS_FUNC(rot)(&N,A,&intone,B,&intone,&c,&s); + } + + static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + BLAS_FUNC(gemv)(&trans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone); + } + + static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ + BLAS_FUNC(gemm)(¬rans,¬rans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N); + } + + static inline void transposed_matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ + BLAS_FUNC(gemm)(¬rans,¬rans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N); + } + +// static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){ +// ssyrk_(&lower,&trans,&N,&N,&fone,A,&N,&fzero,X,&N); +// } + + static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){ + BLAS_FUNC(syrk)(&lower,¬rans,&N,&N,&fone,A,&N,&fzero,X,&N); + } + + static inline void axpy(SCALAR coef, const gene_vector & X, gene_vector & Y, int N){ + BLAS_FUNC(axpy)(&N,&coef,X,&intone,Y,&intone); + } + + static inline void axpby(SCALAR a, const gene_vector & X, SCALAR b, gene_vector & Y, int N){ + BLAS_FUNC(scal)(&N,&b,Y,&intone); + BLAS_FUNC(axpy)(&N,&a,X,&intone,Y,&intone); + } + + static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ + int N2 = N*N; + BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); + char uplo = 'L'; + int info = 0; + BLAS_FUNC(potrf)(&uplo, &N, C, &N, &info); + if(info!=0) std::cerr << "potrf_ error " << info << "\n"; + } + + static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + int N2 = N*N; + BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); + char uplo = 'L'; + int info = 0; + int * ipiv = (int*)alloca(sizeof(int)*N); + BLAS_FUNC(getrf)(&N, &N, C, &N, ipiv, &info); + if(info!=0) std::cerr << "getrf_ error " << info << "\n"; + } + + static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){ + BLAS_FUNC(copy)(&N, B, &intone, X, &intone); + BLAS_FUNC(trsv)(&lower, ¬rans, &nonunit, &N, L, &N, X, &intone); + } + + static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix & X, int N){ + BLAS_FUNC(copy)(&N, B, &intone, X, &intone); + BLAS_FUNC(trsm)(&right, &lower, ¬rans, &nonunit, &N, &N, &fone, L, &N, X, &N); + } + + static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ + BLAS_FUNC(trmm)(&left, &lower, ¬rans,&nonunit, &N,&N,&fone,A,&N,B,&N); + } + + #ifdef HAS_LAPACK + + static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + int N2 = N*N; + BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); + char uplo = 'L'; + int info = 0; + int * ipiv = (int*)alloca(sizeof(int)*N); + int * jpiv = (int*)alloca(sizeof(int)*N); + BLAS_FUNC(getc2)(&N, C, &N, ipiv, jpiv, &info); + } + + + + static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){ + { + int N2 = N*N; + int inc = 1; + BLAS_FUNC(copy)(&N2, X, &inc, C, &inc); + } + int info = 0; + int ilo = 1; + int ihi = N; + int bsize = 64; + int worksize = N*bsize; + SCALAR* d = new SCALAR[N+worksize]; + BLAS_FUNC(gehrd)(&N, &ilo, &ihi, C, &N, d, d+N, &worksize, &info); + delete[] d; + } + + static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ + { + int N2 = N*N; + int inc = 1; + BLAS_FUNC(copy)(&N2, X, &inc, C, &inc); + } + char uplo = 'U'; + int info = 0; + int ilo = 1; + int ihi = N; + int bsize = 64; + int worksize = N*bsize; + SCALAR* d = new SCALAR[3*N+worksize]; + BLAS_FUNC(sytrd)(&uplo, &N, C, &N, d, d+N, d+2*N, d+3*N, &worksize, &info); + delete[] d; + } + + #endif // HAS_LAPACK + +}; + +SCALAR blas_interface::fone = SCALAR(1); +SCALAR blas_interface::fzero = SCALAR(0); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/f77_interface_base.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h similarity index 51% rename from gtsam/3rdparty/Eigen/bench/btl/libs/f77/f77_interface_base.hh rename to gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h index ab8a18295..515d8dcfc 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/f77_interface_base.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h @@ -1,38 +1,21 @@ -//===================================================== -// File : f77_interface_base.hh -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:25 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef F77_INTERFACE_BASE_HH -#define F77_INTERFACE_BASE_HH + +#ifndef BTL_C_INTERFACE_BASE_H +#define BTL_C_INTERFACE_BASE_H #include "utilities.h" #include -template -class f77_interface_base{ + +template class c_interface_base +{ public: - typedef real real_type ; - typedef std::vector stl_vector; - typedef std::vector stl_matrix; + typedef real real_type; + typedef std::vector stl_vector; + typedef std::vector stl_matrix; - typedef real * gene_matrix; - typedef real * gene_vector; + typedef real* gene_matrix; + typedef real* gene_vector; static void free_matrix(gene_matrix & A, int N){ delete A; @@ -87,5 +70,4 @@ public: }; - #endif diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp new file mode 100644 index 000000000..8347c9f0b --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp @@ -0,0 +1,73 @@ +//===================================================== +// File : main.cpp +// Author : L. Plagne +// Copyright (C) EDF R&D, lun sep 30 14:23:28 CEST 2002 +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#include "utilities.h" +#include "blas_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +#include "action_cholesky.hh" +#include "action_lu_decomp.hh" +#include "action_partial_lu.hh" +#include "action_trisolve_matrix.hh" + +#ifdef HAS_LAPACK +#include "action_hessenberg.hh" +#endif + +BTL_MAIN; + +int main() +{ + + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); + + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + + bench > >(MIN_MM,MAX_MM,NB_POINT); + + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + + #ifdef HAS_LAPACK + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + #endif + + //bench > >(MIN_LU,MAX_LU,NB_POINT); + + return 0; +} + + diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/C/CMakeLists.txt deleted file mode 100644 index 3d4d24cee..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -include_directories(${PROJECT_SOURCE_DIR}/libs/f77) -btl_add_bench(btl_C main.cpp OFF) -# set_target_properties(btl_C PROPERTIES COMPILE_FLAGS "-fpeel-loops") \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C/C_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/C/C_interface.hh deleted file mode 100755 index d6092517d..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C/C_interface.hh +++ /dev/null @@ -1,117 +0,0 @@ -//===================================================== -// File : C_interface.hh -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:23 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef C_INTERFACE_HH -#define C_INTERFACE_HH - -#include "f77_interface.hh" - -template -class C_interface : public f77_interface_base { - -public : - - typedef typename f77_interface_base::gene_matrix gene_matrix; - typedef typename f77_interface_base::gene_vector gene_vector; - - static inline std::string name() { return "C"; } - - static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N) - { -// for (int i=0;i -// Copyright (C) EDF R&D, lun sep 30 14:23:28 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef C_BLAS_PRODUIT_MATRICE_VECTEUR_HH -#define C_BLAS_PRODUIT_MATRICE_VECTEUR_HH - -#include "f77_interface.hh" -#include -extern "C" -{ -#include "cblas.h" - -// #ifdef PUREBLAS -#include "blas.h" -// #endif - -// void sgemm_(const char *transa, const char *transb, const int *m, const int *n, const int *k, -// const float *alpha, const float *a, const int *lda, const float *b, const int *ldb, -// const float *beta, float *c, const int *ldc); -// -// void sgemv_(const char *trans, const int *m, const int *n, const float *alpha, -// const float *a, const int *lda, const float *x, const int *incx, -// const float *beta, float *y, const int *incy); -// -// void ssymv_(const char *trans, const char* uplo, -// const int* N, const float* alpha, const float *A, -// const int* lda, const float *X, const int* incX, -// const float* beta, float *Y, const int* incY); -// -// void sscal_(const int *n, const float *alpha, const float *x, const int *incx); -// -// void saxpy_(const int *n, const float *alpha, const float *x, const int *incx, -// float *y, const int *incy); -// -// void strsv_(const char *uplo, const char *trans, const char *diag, const int *n, -// const float *a, const int *lda, float *x, const int *incx); -// -// void scopy_(const int *n, const float *x, const int *incx, float *y, const int *incy); - - // Cholesky Factorization -// #include "mkl_lapack.h" -// void spotrf_(const char* uplo, const int* n, float *a, const int* ld, int* info); -// void dpotrf_(const char* uplo, const int* n, double *a, const int* ld, int* info); - void ssytrd_(char *uplo, const int *n, float *a, const int *lda, float *d, float *e, float *tau, float *work, int *lwork, int *info ); - void sgehrd_( const int *n, int *ilo, int *ihi, float *a, const int *lda, float *tau, float *work, int *lwork, int *info ); - - // LU row pivoting -// void dgetrf_( int *m, int *n, double *a, int *lda, int *ipiv, int *info ); -// void sgetrf_(const int* m, const int* n, float *a, const int* ld, int* ipivot, int* info); - // LU full pivoting - void sgetc2_(const int* n, float *a, const int *lda, int *ipiv, int *jpiv, int*info ); -#ifdef HAS_LAPACK -#endif -} - -#define MAKE_STRING2(S) #S -#define MAKE_STRING(S) MAKE_STRING2(S) - -template -class C_BLAS_interface : public f77_interface_base -{ -public : - - typedef typename f77_interface_base::gene_matrix gene_matrix; - typedef typename f77_interface_base::gene_vector gene_vector; - - static inline std::string name( void ) - { - return MAKE_STRING(CBLASNAME); - } - - static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N) - { - cblas_dgemv(CblasColMajor,CblasNoTrans,N,N,1.0,A,N,B,1,0.0,X,1); - } - - static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N) - { - cblas_dgemv(CblasColMajor,CblasTrans,N,N,1.0,A,N,B,1,0.0,X,1); - } - - static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N) - { - cblas_dsymv(CblasColMajor,CblasLower,CblasTrans,N,N,1.0,A,N,B,1,0.0,X,1); - } - - static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ - cblas_dgemm(CblasColMajor,CblasNoTrans,CblasNoTrans,N,N,N,1.0,A,N,B,N,0.0,X,N); - } - - static inline void transposed_matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ - cblas_dgemm(CblasColMajor,CblasTrans,CblasTrans,N,N,N,1.0,A,N,B,N,0.0,X,N); - } - - static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){ - cblas_dgemm(CblasColMajor,CblasTrans,CblasNoTrans,N,N,N,1.0,A,N,A,N,0.0,X,N); - } - - static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){ - cblas_dgemm(CblasColMajor,CblasNoTrans,CblasTrans,N,N,N,1.0,A,N,A,N,0.0,X,N); - } - - static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){ - cblas_daxpy(N,coef,X,1,Y,1); - } - - static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){ - cblas_dscal(N,b,Y,1); - cblas_daxpy(N,a,X,1,Y,1); - } - -}; - -static float fone = 1; -static float fzero = 0; -static char notrans = 'N'; -static char trans = 'T'; -static char nonunit = 'N'; -static char lower = 'L'; -static char right = 'R'; -static char left = 'L'; -static int intone = 1; - -template<> -class C_BLAS_interface : public f77_interface_base -{ - -public : - - static inline std::string name( void ) - { - return MAKE_STRING(CBLASNAME); - } - - static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ - #ifdef PUREBLAS - sgemv_(¬rans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone); - #else - cblas_sgemv(CblasColMajor,CblasNoTrans,N,N,1.0,A,N,B,1,0.0,X,1); - #endif - } - - static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ - #ifdef PUREBLAS - ssymv_(&lower, &N,&fone,A,&N,B,&intone,&fzero,X,&intone); - #else - cblas_ssymv(CblasColMajor,CblasLower,N,1.0,A,N,B,1,0.0,X,1); - #endif - } - - static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ - #ifdef PUREBLAS - ssyr2_(&lower,&N,&fone,B,&intone,X,&intone,A,&N); - #else - cblas_ssyr2(CblasColMajor,CblasLower,N,1.0,B,1,X,1,A,N); - #endif - } - - static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ - #ifdef PUREBLAS - sger_(&N,&N,&fone,X,&intone,Y,&intone,A,&N); - #else - cblas_sger(CblasColMajor,N,N,1.0,X,1,Y,1,A,N); - #endif - } - - static inline void rot(gene_vector & A, gene_vector & B, float c, float s, int N){ - #ifdef PUREBLAS - srot_(&N,A,&intone,B,&intone,&c,&s); - #else - cblas_srot(N,A,1,B,1,c,s); - #endif - } - - static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ - #ifdef PUREBLAS - sgemv_(&trans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone); - #else - cblas_sgemv(CblasColMajor,CblasTrans,N,N,1.0,A,N,B,1,0.0,X,1); - #endif - } - - static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ - #ifdef PUREBLAS - sgemm_(¬rans,¬rans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N); - #else - cblas_sgemm(CblasColMajor,CblasNoTrans,CblasNoTrans,N,N,N,1.0,A,N,B,N,0.0,X,N); - #endif - } - - static inline void transposed_matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ - #ifdef PUREBLAS - sgemm_(¬rans,¬rans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N); - #else - cblas_sgemm(CblasColMajor,CblasNoTrans,CblasNoTrans,N,N,N,1.0,A,N,B,N,0.0,X,N); - #endif - } - - static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){ - #ifdef PUREBLAS - sgemm_(&trans,¬rans,&N,&N,&N,&fone,A,&N,A,&N,&fzero,X,&N); - #else - cblas_sgemm(CblasColMajor,CblasTrans,CblasNoTrans,N,N,N,1.0,A,N,A,N,0.0,X,N); - #endif - } - - static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){ - #ifdef PUREBLAS - sgemm_(¬rans,&trans,&N,&N,&N,&fone,A,&N,A,&N,&fzero,X,&N); - #else - cblas_sgemm(CblasColMajor,CblasNoTrans,CblasTrans,N,N,N,1.0,A,N,A,N,0.0,X,N); - #endif - } - - static inline void axpy(float coef, const gene_vector & X, gene_vector & Y, int N){ - #ifdef PUREBLAS - saxpy_(&N,&coef,X,&intone,Y,&intone); - #else - cblas_saxpy(N,coef,X,1,Y,1); - #endif - } - - static inline void axpby(float a, const gene_vector & X, float b, gene_vector & Y, int N){ - #ifdef PUREBLAS - sscal_(&N,&b,Y,&intone); - saxpy_(&N,&a,X,&intone,Y,&intone); - #else - cblas_sscal(N,b,Y,1); - cblas_saxpy(N,a,X,1,Y,1); - #endif - } - - static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ - int N2 = N*N; - scopy_(&N2, X, &intone, C, &intone); - char uplo = 'L'; - int info = 0; - spotrf_(&uplo, &N, C, &N, &info); - if(info!=0) std::cerr << "spotrf_ error " << info << "\n"; - } - - static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ - int N2 = N*N; - scopy_(&N2, X, &intone, C, &intone); - char uplo = 'L'; - int info = 0; - int * ipiv = (int*)alloca(sizeof(int)*N); - sgetrf_(&N, &N, C, &N, ipiv, &info); - if(info!=0) std::cerr << "sgetrf_ error " << info << "\n"; - } - - #ifdef HAS_LAPACK - - static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ - int N2 = N*N; - scopy_(&N2, X, &intone, C, &intone); - char uplo = 'L'; - int info = 0; - int * ipiv = (int*)alloca(sizeof(int)*N); - int * jpiv = (int*)alloca(sizeof(int)*N); - sgetc2_(&N, C, &N, ipiv, jpiv, &info); - } - - - - static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){ -#ifdef PUREBLAS - { - int N2 = N*N; - int inc = 1; - scopy_(&N2, X, &inc, C, &inc); - } -#else - cblas_scopy(N*N, X, 1, C, 1); -#endif - int info = 0; - int ilo = 1; - int ihi = N; - int bsize = 64; - int worksize = N*bsize; - float* d = new float[N+worksize]; - sgehrd_(&N, &ilo, &ihi, C, &N, d, d+N, &worksize, &info); - delete[] d; - } - - static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ -#ifdef PUREBLAS - { - int N2 = N*N; - int inc = 1; - scopy_(&N2, X, &inc, C, &inc); - } -#else - cblas_scopy(N*N, X, 1, C, 1); -#endif - char uplo = 'U'; - int info = 0; - int ilo = 1; - int ihi = N; - int bsize = 64; - int worksize = N*bsize; - float* d = new float[3*N+worksize]; - ssytrd_(&uplo, &N, C, &N, d, d+N, d+2*N, d+3*N, &worksize, &info); - delete[] d; - } - #endif - - static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){ - #ifdef PUREBLAS - scopy_(&N, B, &intone, X, &intone); - strsv_(&lower, ¬rans, &nonunit, &N, L, &N, X, &intone); - #else - cblas_scopy(N, B, 1, X, 1); - cblas_strsv(CblasColMajor, CblasLower, CblasNoTrans, CblasNonUnit, N, L, N, X, 1); - #endif - } - - static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix & X, int N){ - #ifdef PUREBLAS - scopy_(&N, B, &intone, X, &intone); - strsm_(&right, &lower, ¬rans, &nonunit, &N, &N, &fone, L, &N, X, &N); - #else - cblas_scopy(N, B, 1, X, 1); - cblas_strsm(CblasColMajor, CblasRight, CblasLower, CblasNoTrans, CblasNonUnit, N, N, 1, L, N, X, N); - #endif - } - - static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ - #ifdef PUREBLAS - strmm_(&left, &lower, ¬rans,&nonunit, &N,&N,&fone,A,&N,B,&N); - #else - cblas_strmm(CblasColMajor, CblasLeft, CblasLower, CblasNoTrans,CblasNonUnit, N,N,1,A,N,B,N); - #endif - } - -}; - - -#endif - - - diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/cblas.h b/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/cblas.h deleted file mode 100644 index 4087ffb92..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/cblas.h +++ /dev/null @@ -1,596 +0,0 @@ -#ifndef CBLAS_H - -#ifndef CBLAS_ENUM_DEFINED_H - #define CBLAS_ENUM_DEFINED_H - enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102 }; - enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113, - AtlasConj=114}; - enum CBLAS_UPLO {CblasUpper=121, CblasLower=122}; - enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; - enum CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#endif - -#ifndef CBLAS_ENUM_ONLY -#define CBLAS_H -#define CBLAS_INDEX int - -int cblas_errprn(int ierr, int info, char *form, ...); - -/* - * =========================================================================== - * Prototypes for level 1 BLAS functions (complex are recast as routines) - * =========================================================================== - */ -float cblas_sdsdot(const int N, const float alpha, const float *X, - const int incX, const float *Y, const int incY); -double cblas_dsdot(const int N, const float *X, const int incX, const float *Y, - const int incY); -float cblas_sdot(const int N, const float *X, const int incX, - const float *Y, const int incY); -double cblas_ddot(const int N, const double *X, const int incX, - const double *Y, const int incY); -/* - * Functions having prefixes Z and C only - */ -void cblas_cdotu_sub(const int N, const void *X, const int incX, - const void *Y, const int incY, void *dotu); -void cblas_cdotc_sub(const int N, const void *X, const int incX, - const void *Y, const int incY, void *dotc); - -void cblas_zdotu_sub(const int N, const void *X, const int incX, - const void *Y, const int incY, void *dotu); -void cblas_zdotc_sub(const int N, const void *X, const int incX, - const void *Y, const int incY, void *dotc); - - -/* - * Functions having prefixes S D SC DZ - */ -float cblas_snrm2(const int N, const float *X, const int incX); -float cblas_sasum(const int N, const float *X, const int incX); - -double cblas_dnrm2(const int N, const double *X, const int incX); -double cblas_dasum(const int N, const double *X, const int incX); - -float cblas_scnrm2(const int N, const void *X, const int incX); -float cblas_scasum(const int N, const void *X, const int incX); - -double cblas_dznrm2(const int N, const void *X, const int incX); -double cblas_dzasum(const int N, const void *X, const int incX); - - -/* - * Functions having standard 4 prefixes (S D C Z) - */ -CBLAS_INDEX cblas_isamax(const int N, const float *X, const int incX); -CBLAS_INDEX cblas_idamax(const int N, const double *X, const int incX); -CBLAS_INDEX cblas_icamax(const int N, const void *X, const int incX); -CBLAS_INDEX cblas_izamax(const int N, const void *X, const int incX); - -/* - * =========================================================================== - * Prototypes for level 1 BLAS routines - * =========================================================================== - */ - -/* - * Routines with standard 4 prefixes (s, d, c, z) - */ -void cblas_sswap(const int N, float *X, const int incX, - float *Y, const int incY); -void cblas_scopy(const int N, const float *X, const int incX, - float *Y, const int incY); -void cblas_saxpy(const int N, const float alpha, const float *X, - const int incX, float *Y, const int incY); -void catlas_saxpby(const int N, const float alpha, const float *X, - const int incX, const float beta, float *Y, const int incY); -void catlas_sset - (const int N, const float alpha, float *X, const int incX); - -void cblas_dswap(const int N, double *X, const int incX, - double *Y, const int incY); -void cblas_dcopy(const int N, const double *X, const int incX, - double *Y, const int incY); -void cblas_daxpy(const int N, const double alpha, const double *X, - const int incX, double *Y, const int incY); -void catlas_daxpby(const int N, const double alpha, const double *X, - const int incX, const double beta, double *Y, const int incY); -void catlas_dset - (const int N, const double alpha, double *X, const int incX); - -void cblas_cswap(const int N, void *X, const int incX, - void *Y, const int incY); -void cblas_ccopy(const int N, const void *X, const int incX, - void *Y, const int incY); -void cblas_caxpy(const int N, const void *alpha, const void *X, - const int incX, void *Y, const int incY); -void catlas_caxpby(const int N, const void *alpha, const void *X, - const int incX, const void *beta, void *Y, const int incY); -void catlas_cset - (const int N, const void *alpha, void *X, const int incX); - -void cblas_zswap(const int N, void *X, const int incX, - void *Y, const int incY); -void cblas_zcopy(const int N, const void *X, const int incX, - void *Y, const int incY); -void cblas_zaxpy(const int N, const void *alpha, const void *X, - const int incX, void *Y, const int incY); -void catlas_zaxpby(const int N, const void *alpha, const void *X, - const int incX, const void *beta, void *Y, const int incY); -void catlas_zset - (const int N, const void *alpha, void *X, const int incX); - - -/* - * Routines with S and D prefix only - */ -void cblas_srotg(float *a, float *b, float *c, float *s); -void cblas_srotmg(float *d1, float *d2, float *b1, const float b2, float *P); -void cblas_srot(const int N, float *X, const int incX, - float *Y, const int incY, const float c, const float s); -void cblas_srotm(const int N, float *X, const int incX, - float *Y, const int incY, const float *P); - -void cblas_drotg(double *a, double *b, double *c, double *s); -void cblas_drotmg(double *d1, double *d2, double *b1, const double b2, double *P); -void cblas_drot(const int N, double *X, const int incX, - double *Y, const int incY, const double c, const double s); -void cblas_drotm(const int N, double *X, const int incX, - double *Y, const int incY, const double *P); - - -/* - * Routines with S D C Z CS and ZD prefixes - */ -void cblas_sscal(const int N, const float alpha, float *X, const int incX); -void cblas_dscal(const int N, const double alpha, double *X, const int incX); -void cblas_cscal(const int N, const void *alpha, void *X, const int incX); -void cblas_zscal(const int N, const void *alpha, void *X, const int incX); -void cblas_csscal(const int N, const float alpha, void *X, const int incX); -void cblas_zdscal(const int N, const double alpha, void *X, const int incX); - -/* - * Extra reference routines provided by ATLAS, but not mandated by the standard - */ -void cblas_crotg(void *a, void *b, void *c, void *s); -void cblas_zrotg(void *a, void *b, void *c, void *s); -void cblas_csrot(const int N, void *X, const int incX, void *Y, const int incY, - const float c, const float s); -void cblas_zdrot(const int N, void *X, const int incX, void *Y, const int incY, - const double c, const double s); - -/* - * =========================================================================== - * Prototypes for level 2 BLAS - * =========================================================================== - */ - -/* - * Routines with standard 4 prefixes (S, D, C, Z) - */ -void cblas_sgemv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const float alpha, const float *A, const int lda, - const float *X, const int incX, const float beta, - float *Y, const int incY); -void cblas_sgbmv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const int KL, const int KU, const float alpha, - const float *A, const int lda, const float *X, - const int incX, const float beta, float *Y, const int incY); -void cblas_strmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const float *A, const int lda, - float *X, const int incX); -void cblas_stbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const float *A, const int lda, - float *X, const int incX); -void cblas_stpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const float *Ap, float *X, const int incX); -void cblas_strsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const float *A, const int lda, float *X, - const int incX); -void cblas_stbsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const float *A, const int lda, - float *X, const int incX); -void cblas_stpsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const float *Ap, float *X, const int incX); - -void cblas_dgemv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const double alpha, const double *A, const int lda, - const double *X, const int incX, const double beta, - double *Y, const int incY); -void cblas_dgbmv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const int KL, const int KU, const double alpha, - const double *A, const int lda, const double *X, - const int incX, const double beta, double *Y, const int incY); -void cblas_dtrmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const double *A, const int lda, - double *X, const int incX); -void cblas_dtbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const double *A, const int lda, - double *X, const int incX); -void cblas_dtpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const double *Ap, double *X, const int incX); -void cblas_dtrsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const double *A, const int lda, double *X, - const int incX); -void cblas_dtbsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const double *A, const int lda, - double *X, const int incX); -void cblas_dtpsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const double *Ap, double *X, const int incX); - -void cblas_cgemv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *X, const int incX, const void *beta, - void *Y, const int incY); -void cblas_cgbmv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const int KL, const int KU, const void *alpha, - const void *A, const int lda, const void *X, - const int incX, const void *beta, void *Y, const int incY); -void cblas_ctrmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *A, const int lda, - void *X, const int incX); -void cblas_ctbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const void *A, const int lda, - void *X, const int incX); -void cblas_ctpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *Ap, void *X, const int incX); -void cblas_ctrsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *A, const int lda, void *X, - const int incX); -void cblas_ctbsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const void *A, const int lda, - void *X, const int incX); -void cblas_ctpsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *Ap, void *X, const int incX); - -void cblas_zgemv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *X, const int incX, const void *beta, - void *Y, const int incY); -void cblas_zgbmv(const enum CBLAS_ORDER Order, - const enum CBLAS_TRANSPOSE TransA, const int M, const int N, - const int KL, const int KU, const void *alpha, - const void *A, const int lda, const void *X, - const int incX, const void *beta, void *Y, const int incY); -void cblas_ztrmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *A, const int lda, - void *X, const int incX); -void cblas_ztbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const void *A, const int lda, - void *X, const int incX); -void cblas_ztpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *Ap, void *X, const int incX); -void cblas_ztrsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *A, const int lda, void *X, - const int incX); -void cblas_ztbsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const int K, const void *A, const int lda, - void *X, const int incX); -void cblas_ztpsv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, - const int N, const void *Ap, void *X, const int incX); - - -/* - * Routines with S and D prefixes only - */ -void cblas_ssymv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *A, - const int lda, const float *X, const int incX, - const float beta, float *Y, const int incY); -void cblas_ssbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const int K, const float alpha, const float *A, - const int lda, const float *X, const int incX, - const float beta, float *Y, const int incY); -void cblas_sspmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *Ap, - const float *X, const int incX, - const float beta, float *Y, const int incY); -void cblas_sger(const enum CBLAS_ORDER Order, const int M, const int N, - const float alpha, const float *X, const int incX, - const float *Y, const int incY, float *A, const int lda); -void cblas_ssyr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *X, - const int incX, float *A, const int lda); -void cblas_sspr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *X, - const int incX, float *Ap); -void cblas_ssyr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *X, - const int incX, const float *Y, const int incY, float *A, - const int lda); -void cblas_sspr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const float *X, - const int incX, const float *Y, const int incY, float *A); - -void cblas_dsymv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *A, - const int lda, const double *X, const int incX, - const double beta, double *Y, const int incY); -void cblas_dsbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const int K, const double alpha, const double *A, - const int lda, const double *X, const int incX, - const double beta, double *Y, const int incY); -void cblas_dspmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *Ap, - const double *X, const int incX, - const double beta, double *Y, const int incY); -void cblas_dger(const enum CBLAS_ORDER Order, const int M, const int N, - const double alpha, const double *X, const int incX, - const double *Y, const int incY, double *A, const int lda); -void cblas_dsyr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *X, - const int incX, double *A, const int lda); -void cblas_dspr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *X, - const int incX, double *Ap); -void cblas_dsyr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *X, - const int incX, const double *Y, const int incY, double *A, - const int lda); -void cblas_dspr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const double *X, - const int incX, const double *Y, const int incY, double *A); - - -/* - * Routines with C and Z prefixes only - */ -void cblas_chemv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const void *alpha, const void *A, - const int lda, const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_chbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const int K, const void *alpha, const void *A, - const int lda, const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_chpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const void *alpha, const void *Ap, - const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_cgeru(const enum CBLAS_ORDER Order, const int M, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_cgerc(const enum CBLAS_ORDER Order, const int M, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_cher(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const void *X, const int incX, - void *A, const int lda); -void cblas_chpr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const float alpha, const void *X, - const int incX, void *A); -void cblas_cher2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_chpr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *Ap); - -void cblas_zhemv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const void *alpha, const void *A, - const int lda, const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_zhbmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const int K, const void *alpha, const void *A, - const int lda, const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_zhpmv(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const void *alpha, const void *Ap, - const void *X, const int incX, - const void *beta, void *Y, const int incY); -void cblas_zgeru(const enum CBLAS_ORDER Order, const int M, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_zgerc(const enum CBLAS_ORDER Order, const int M, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_zher(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const void *X, const int incX, - void *A, const int lda); -void cblas_zhpr(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const int N, const double alpha, const void *X, - const int incX, void *A); -void cblas_zher2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *A, const int lda); -void cblas_zhpr2(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, const int N, - const void *alpha, const void *X, const int incX, - const void *Y, const int incY, void *Ap); - -/* - * =========================================================================== - * Prototypes for level 3 BLAS - * =========================================================================== - */ - -/* - * Routines with standard 4 prefixes (S, D, C, Z) - */ -void cblas_sgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_TRANSPOSE TransB, const int M, const int N, - const int K, const float alpha, const float *A, - const int lda, const float *B, const int ldb, - const float beta, float *C, const int ldc); -void cblas_ssymm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const float alpha, const float *A, const int lda, - const float *B, const int ldb, const float beta, - float *C, const int ldc); -void cblas_ssyrk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const float alpha, const float *A, const int lda, - const float beta, float *C, const int ldc); -void cblas_ssyr2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const float alpha, const float *A, const int lda, - const float *B, const int ldb, const float beta, - float *C, const int ldc); -void cblas_strmm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const float alpha, const float *A, const int lda, - float *B, const int ldb); -void cblas_strsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const float alpha, const float *A, const int lda, - float *B, const int ldb); - -void cblas_dgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_TRANSPOSE TransB, const int M, const int N, - const int K, const double alpha, const double *A, - const int lda, const double *B, const int ldb, - const double beta, double *C, const int ldc); -void cblas_dsymm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const double alpha, const double *A, const int lda, - const double *B, const int ldb, const double beta, - double *C, const int ldc); -void cblas_dsyrk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const double alpha, const double *A, const int lda, - const double beta, double *C, const int ldc); -void cblas_dsyr2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const double alpha, const double *A, const int lda, - const double *B, const int ldb, const double beta, - double *C, const int ldc); -void cblas_dtrmm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const double alpha, const double *A, const int lda, - double *B, const int ldb); -void cblas_dtrsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const double alpha, const double *A, const int lda, - double *B, const int ldb); - -void cblas_cgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_TRANSPOSE TransB, const int M, const int N, - const int K, const void *alpha, const void *A, - const int lda, const void *B, const int ldb, - const void *beta, void *C, const int ldc); -void cblas_csymm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_csyrk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *beta, void *C, const int ldc); -void cblas_csyr2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_ctrmm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const void *alpha, const void *A, const int lda, - void *B, const int ldb); -void cblas_ctrsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const void *alpha, const void *A, const int lda, - void *B, const int ldb); - -void cblas_zgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_TRANSPOSE TransB, const int M, const int N, - const int K, const void *alpha, const void *A, - const int lda, const void *B, const int ldb, - const void *beta, void *C, const int ldc); -void cblas_zsymm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_zsyrk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *beta, void *C, const int ldc); -void cblas_zsyr2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_ztrmm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const void *alpha, const void *A, const int lda, - void *B, const int ldb); -void cblas_ztrsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, - const enum CBLAS_DIAG Diag, const int M, const int N, - const void *alpha, const void *A, const int lda, - void *B, const int ldb); - - -/* - * Routines with prefixes C and Z only - */ -void cblas_chemm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_cherk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const float alpha, const void *A, const int lda, - const float beta, void *C, const int ldc); -void cblas_cher2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const float beta, - void *C, const int ldc); -void cblas_zhemm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, - const enum CBLAS_UPLO Uplo, const int M, const int N, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const void *beta, - void *C, const int ldc); -void cblas_zherk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const double alpha, const void *A, const int lda, - const double beta, void *C, const int ldc); -void cblas_zher2k(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, - const enum CBLAS_TRANSPOSE Trans, const int N, const int K, - const void *alpha, const void *A, const int lda, - const void *B, const int ldb, const double beta, - void *C, const int ldc); - -int cblas_errprn(int ierr, int info, char *form, ...); - -#endif /* end #ifdef CBLAS_ENUM_ONLY */ -#endif diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/main.cpp deleted file mode 100644 index 99f512f9b..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C_BLAS/main.cpp +++ /dev/null @@ -1,73 +0,0 @@ -//===================================================== -// File : main.cpp -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:28 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#include "utilities.h" -#include "C_BLAS_interface.hh" -#include "bench.hh" -#include "basic_actions.hh" - -#include "action_cholesky.hh" -#include "action_lu_decomp.hh" -#include "action_partial_lu.hh" -#include "action_trisolve_matrix.hh" - -#ifdef HAS_LAPACK -#include "action_hessenberg.hh" -#endif - -BTL_MAIN; - -int main() -{ - - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); - - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - - #ifdef HAS_LAPACK - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - #endif - - //bench > >(MIN_LU,MAX_LU,NB_POINT); - - return 0; -} - - diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh index 0b73382f3..93e76bd55 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh @@ -78,18 +78,18 @@ public : cible[i][j]=source[i][j]; } - static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N) - { - real somme; - for (int j=0;j=j) + { + for (int k=0;k -// Copyright (C) EDF R&D, lun sep 30 14:23:24 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef STL_ALGO_INTERFACE_HH -#define STL_ALGO_INTERFACE_HH -#include -#include -#include -#include -#include "utilities.h" - - -template -class STL_algo_interface{ - -public : - - typedef real real_type ; - - typedef std::vector stl_vector; - typedef std::vector stl_matrix; - - typedef stl_matrix gene_matrix; - - typedef stl_vector gene_vector; - - static inline std::string name( void ) - { - return "STL_algo"; - } - - static void free_matrix(gene_matrix & A, int N){} - - static void free_vector(gene_vector & B){} - - static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ - A=A_stl ; - } - - static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){ - B=B_stl ; - } - - static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){ - B_stl=B ; - } - - static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){ - A_stl=A ; - } - - static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){ - for (int i=0;i -// Copyright (C) EDF R&D, lun sep 30 14:23:25 CEST 2002 +// Copyright (C) 2008 Gael Guennebaud //===================================================== // // This program is free software; you can redistribute it and/or @@ -18,28 +16,29 @@ // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. // #include "utilities.h" -#include "f77_interface.hh" -#include "bench.hh" +#include "eigen3_interface.hh" +#include "static/bench_static.hh" #include "action_matrix_vector_product.hh" #include "action_matrix_matrix_product.hh" #include "action_axpy.hh" #include "action_lu_solve.hh" #include "action_ata_product.hh" #include "action_aat_product.hh" +#include "action_atv_product.hh" +#include "action_cholesky.hh" +#include "action_trisolve.hh" BTL_MAIN; int main() { - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); - - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench_static(); + bench_static(); + bench_static(); + bench_static(); + bench_static(); + bench_static(); return 0; } diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh new file mode 100644 index 000000000..47fe58135 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh @@ -0,0 +1,168 @@ +//===================================================== +// Copyright (C) 2008 Gael Guennebaud +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#ifndef EIGEN2_INTERFACE_HH +#define EIGEN2_INTERFACE_HH +// #include +#include +#include +#include +#include +#include +#include "btl.hh" + +using namespace Eigen; + +template +class eigen2_interface +{ + +public : + + enum {IsFixedSize = (SIZE!=Dynamic)}; + + typedef real real_type; + + typedef std::vector stl_vector; + typedef std::vector stl_matrix; + + typedef Eigen::Matrix gene_matrix; + typedef Eigen::Matrix gene_vector; + + static inline std::string name( void ) + { + #if defined(EIGEN_VECTORIZE_SSE) + if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; + #elif defined(EIGEN_VECTORIZE_ALTIVEC) + if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; + #else + if (SIZE==Dynamic) return "eigen2_novec"; else return "tiny_eigen2_novec"; + #endif + } + + static void free_matrix(gene_matrix & A, int N) {} + + static void free_vector(gene_vector & B) {} + + static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ + A.resize(A_stl[0].size(), A_stl.size()); + + for (int j=0; j().solveTriangular(B); + } + + static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ + X = L.template marked().solveTriangular(B); + } + + static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ + C = X.llt().matrixL(); +// C = X; +// Cholesky::computeInPlace(C); +// Cholesky::computeInPlaceBlock(C); + } + + static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + C = X.lu().matrixLU(); +// C = X.inverse(); + } + + static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ + C = Tridiagonalization(X).packedMatrix(); + } + + static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){ + C = HessenbergDecomposition(X).packedMatrix(); + } + + + +}; + +#endif diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_adv.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_adv.cpp new file mode 100644 index 000000000..fe3368925 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_adv.cpp @@ -0,0 +1,44 @@ +//===================================================== +// Copyright (C) 2008 Gael Guennebaud +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#include "utilities.h" +#include "eigen2_interface.hh" +#include "bench.hh" +#include "action_trisolve.hh" +#include "action_trisolve_matrix.hh" +#include "action_cholesky.hh" +#include "action_hessenberg.hh" +#include "action_lu_decomp.hh" +// #include "action_partial_lu.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); + + bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); + + return 0; +} + + diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/STL_algo/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_linear.cpp similarity index 70% rename from gtsam/3rdparty/Eigen/bench/btl/libs/STL_algo/main.cpp rename to gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_linear.cpp index 9ce2d947e..c17d16c08 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/STL_algo/main.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_linear.cpp @@ -1,7 +1,5 @@ //===================================================== -// File : main.cpp -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:23 CEST 2002 +// Copyright (C) 2008 Gael Guennebaud //===================================================== // // This program is free software; you can redistribute it and/or @@ -18,21 +16,18 @@ // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. // #include "utilities.h" -#include "STL_algo_interface.hh" +#include "eigen2_interface.hh" #include "bench.hh" -#include "action_atv_product.hh" -#include "action_axpy.hh" +#include "basic_actions.hh" BTL_MAIN; int main() { - - bench > >(MIN_MV,MAX_MV,NB_POINT); - - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + return 0; } diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/test_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_matmat.cpp similarity index 59% rename from gtsam/3rdparty/Eigen/bench/btl/libs/f77/test_interface.hh rename to gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_matmat.cpp index 230c8dbc8..cd9dc9cb0 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/test_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_matmat.cpp @@ -1,14 +1,12 @@ //===================================================== -// File : test_interface.hh -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:25 CEST 2002 +// Copyright (C) 2008 Gael Guennebaud //===================================================== -// +// // This program is free software; you can redistribute it and/or // modify it under the terms of the GNU General Public License // as published by the Free Software Foundation; either version 2 // of the License, or (at your option) any later version. -// +// // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the @@ -16,21 +14,22 @@ // You should have received a copy of the GNU General Public License // along with this program; if not, write to the Free Software // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef TEST_INTERFACE_HH -#define TEST_INTERFACE_HH - -template< class Interface > -void test_interface( void ){ - - Interface::interface_name(); - - typename Interface::gene_matrix A; - - +// +#include "utilities.h" +#include "eigen2_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" +BTL_MAIN; +int main() +{ + bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); + return 0; } -#endif + diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/C/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_vecmat.cpp similarity index 50% rename from gtsam/3rdparty/Eigen/bench/btl/libs/C/main.cpp rename to gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_vecmat.cpp index f0a0e5c65..8b66cd2d9 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/C/main.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/main_vecmat.cpp @@ -1,7 +1,5 @@ //===================================================== -// File : main.cpp -// Author : L. Plagne -// Copyright (C) EDF R&D, lun sep 30 14:23:23 CEST 2002 +// Copyright (C) 2008 Gael Guennebaud //===================================================== // // This program is free software; you can redistribute it and/or @@ -18,29 +16,19 @@ // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. // #include "utilities.h" +#include "eigen2_interface.hh" #include "bench.hh" -#include "C_interface.hh" -#include "action_matrix_vector_product.hh" -#include "action_atv_product.hh" -#include "action_matrix_matrix_product.hh" -#include "action_axpy.hh" -#include "action_ata_product.hh" -#include "action_aat_product.hh" -//#include "action_lu_solve.hh" -#include "timers/mixed_perf_analyzer.hh" +#include "basic_actions.hh" BTL_MAIN; int main() { - - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); +// bench > >(MIN_MV,MAX_MV,NB_POINT); +// bench > >(MIN_MV,MAX_MV,NB_POINT); +// bench > >(MIN_MV,MAX_MV,NB_POINT); return 0; } diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/CMakeLists.txt index 334eb14a8..00cae23d3 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/CMakeLists.txt @@ -1,5 +1,13 @@ -find_package(Eigen3) + +if((NOT EIGEN3_INCLUDE_DIR) AND Eigen_SOURCE_DIR) + # unless EIGEN3_INCLUDE_DIR is defined, let's use current Eigen version + set(EIGEN3_INCLUDE_DIR ${Eigen_SOURCE_DIR}) + set(EIGEN3_FOUND TRUE) +else() + find_package(Eigen3) +endif() + if (EIGEN3_FOUND) include_directories(${EIGEN3_INCLUDE_DIR}) @@ -28,10 +36,10 @@ if (EIGEN3_FOUND) if(NOT BTL_NOVEC) - btl_add_bench(btl_eigen3_novec_linear main_linear.cpp) - btl_add_bench(btl_eigen3_novec_vecmat main_vecmat.cpp) - btl_add_bench(btl_eigen3_novec_matmat main_matmat.cpp) - btl_add_bench(btl_eigen3_novec_adv main_adv.cpp ) + btl_add_bench(btl_eigen3_novec_linear main_linear.cpp OFF) + btl_add_bench(btl_eigen3_novec_vecmat main_vecmat.cpp OFF) + btl_add_bench(btl_eigen3_novec_matmat main_matmat.cpp OFF) + btl_add_bench(btl_eigen3_novec_adv main_adv.cpp OFF) btl_add_target_property(btl_eigen3_novec_linear COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec") btl_add_target_property(btl_eigen3_novec_vecmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec") btl_add_target_property(btl_eigen3_novec_matmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec") diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh index bd5eb4b6b..31bcc1f93 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh @@ -92,12 +92,13 @@ public : X.noalias() = A.transpose()*B.transpose(); } - static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){ - X.noalias() = A.transpose()*A; - } +// static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){ +// X.noalias() = A.transpose()*A; +// } static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){ - X.noalias() = A*A.transpose(); + X.template triangularView().setZero(); + X.template selfadjointView().rankUpdate(A); } static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){ @@ -194,16 +195,16 @@ public : } static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ - X = L.template triangularView().solve(B); + X = L.template triangularView().solve(B); } static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ - X = L.template triangularView() * B; + X.noalias() = L.template triangularView() * B; } static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ C = X; - internal::llt_inplace::blocked(C); + internal::llt_inplace::blocked(C); //C = X.llt().matrixL(); // C = X; // Cholesky::computeInPlace(C); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_matmat.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_matmat.cpp index 052810a16..926fa2b01 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_matmat.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_matmat.cpp @@ -25,7 +25,7 @@ BTL_MAIN; int main() { bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/CMakeLists.txt deleted file mode 100644 index cecb9160c..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -if(CMAKE_MINOR_VERSION GREATER 4) - if(NOT MSVC) - enable_language(Fortran) - endif(NOT MSVC) - btl_add_bench(btl_f77 main.cpp dmxv.f smxv.f dmxm.f smxm.f daxpy.f saxpy.f data.f sata.f daat.f saat.f OFF) -endif(CMAKE_MINOR_VERSION GREATER 4) \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daat.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daat.f deleted file mode 100644 index a50329a66..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daat.f +++ /dev/null @@ -1,14 +0,0 @@ - SUBROUTINE DAAT(A,X,N) -** -** X = AT * A - REAL*8 A(N,N),X(N,N),R - DO 20 I=1,N - DO 20 J=1,N - R=0. - DO 10 K=1,N - R=R+A(I,K)*A(J,K) - 10 CONTINUE - X(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/data.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/data.f deleted file mode 100644 index 709211ca5..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/data.f +++ /dev/null @@ -1,14 +0,0 @@ - SUBROUTINE DATA(A,X,N) -** -** X = AT * A - REAL*8 A(N,N),X(N,N),R - DO 20 I=1,N - DO 20 J=1,N - R=0. - DO 10 K=1,N - R=R+A(K,I)*A(K,J) - 10 CONTINUE - X(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daxpy.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daxpy.f deleted file mode 100644 index 29514a222..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/daxpy.f +++ /dev/null @@ -1,18 +0,0 @@ - SUBROUTINE DAXPYF(N,A,X,Y) -** *************************************** -** CALCULE Y = Y + A*X -** *************************************** -*>N NOMBRE D'OPERATIONS A FAIRE -*>A CONSTANTE MULTIPLICATIVE -*>X TABLEAU -*=Y TABLEAU DES RESULTATS -*A R. SANCHEZ ( EARLY WINTER 1987 ) -*V M.F. ROBEAU - REAL*8 X(1),Y(1) - REAL*8 A - DO 10 I=1,N - Y(I)=Y(I)+A*X(I) - 10 CONTINUE - RETURN - END - diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f deleted file mode 100644 index eb7ef9006..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f +++ /dev/null @@ -1,32 +0,0 @@ - SUBROUTINE DMXM(A,N,B,M,C,L) -** -** C = A * B -** A ET B MATRICES A(N,M) B(M,L) ==> C(N,L) -** -*>A PREMIERE MATRICE -*>N PREMIERE DIMENSION DE A ET DE C -*>B DEUXIEME MATRICE -*>M DEUXIEME DIMENSION DE A ET PERMIERE DE B -*L DEUXIEME DIMENSION DE B ET DE C -*A R. SANCHEZ ( EARLY WINTER 1987 ) -*V M.F. ROBEAU -*M AM BAUDRON - AVRIL 94 -*: ERREUR DANS L'APPEL A L'UTILITAIRE SGEMM -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR HP -*M AM BAUDRON - NOVEMBRE 1991 -*: ERREUR ( SOMME SUR LES TERMES PAS FAITE ) -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR RISC -*M AM BAUDRON - MAI 1993 -*: CHANGEMENT DES %IF LOCAL SUN MIPS SUITE A INTRODUCTION VERSION IBM - REAL*8 A(N,M),B(M,L),C(N,L),R - DO 20 I=1,N - DO 20 J=1,L - R=0. - DO 10 K=1,M - R=R+A(I,K)*B(K,J) - 10 CONTINUE - C(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f.mfr b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f.mfr deleted file mode 100644 index 82ccac9a5..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxm.f.mfr +++ /dev/null @@ -1,36 +0,0 @@ - - SUBROUTINE DMXM(A,N,B,M,C,L) -** -** C = A * B -** A ET B MATRICES A(N,M) B(M,L) ==> C(N,L) -** -*>A PREMIERE MATRICE -*>N PREMIERE DIMENSION DE A ET DE C -*>B DEUXIEME MATRICE -*>M DEUXIEME DIMENSION DE A ET PERMIERE DE B -*L DEUXIEME DIMENSION DE B ET DE C -*A R. SANCHEZ ( EARLY WINTER 1987 ) -*V M.F. ROBEAU -*M AM BAUDRON - AVRIL 94 -*: ERREUR DANS L'APPEL A L'UTILITAIRE SGEMM -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR HP -*M AM BAUDRON - NOVEMBRE 1991 -*: ERREUR ( SOMME SUR LES TERMES PAS FAITE ) -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR RISC -*M AM BAUDRON - MAI 1993 -*: CHANGEMENT DES %IF LOCAL SUN MIPS SUITE A INTRODUCTION VERSION IBM - REAL*8 A(N,M),B(M,L),C(N,L),R - DO 5 J=1,L - DO 5 I=1,N - C(I,J)=0. - 5 CONTINUE - DO 10 K=1,M - DO 20 J=1,L - R=B(K,J) - DO 20 I=1,N - C(I,J)=C(I,J)+A(I,K)*R - 20 CONTINUE - 10 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxv.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxv.f deleted file mode 100644 index bd7e4d550..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/dmxv.f +++ /dev/null @@ -1,39 +0,0 @@ - SUBROUTINE DMXV(A,N,X,M,R) -C -** -** VERSION DOUBLE PRECISION DE MXV -** R = A * X -** A MATRICE A(N,M) -** R ET X VECTEURS -** -*>A PREMIERE MATRICE -*>N PREMIERE DIMENSION DE A -*>X VECTEUR -*>M DEUXIEME DIMENSION DE A -* -// Copyright (C) EDF R&D, lun sep 30 14:23:24 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef F77_INTERFACE_HH -#define F77_INTERFACE_HH -#include "f77_interface_base.hh" -#include - -extern "C" -{ - void dmxv_(double * A, int * N, double * X, int * M, double *R); - void smxv_(float * A, int * N, float * X, int * M, float *R); - - void dmxm_(double * A, int * N, double * B, int * M, double *C, int * K); - void smxm_(float * A, int * N, float * B, int * M, float *C, int * K); - - void data_(double * A, double *X, int * N); - void sata_(float * A, float *X, int * N); - - void daat_(double * A, double *X, int * N); - void saat_(float * A, float *X, int * N); - - void saxpyf_(int * N, float * coef, float * X, float *Y); - void daxpyf_(int * N, double * coef, double * X, double *Y); -} - -template -class f77_interface : public f77_interface_base -{ -public : - - typedef typename f77_interface_base::gene_matrix gene_matrix; - typedef typename f77_interface_base::gene_vector gene_vector; - - static inline std::string name( void ) - { - return "f77"; - } - - static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N) - { - dmxv_(A,&N,B,&N,X); - } - - static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N) - { - dmxm_(A,&N,B,&N,X,&N); - } - - static inline void ata_product(gene_matrix & A, gene_matrix & X, int N) - { - data_(A,X,&N); - } - - static inline void aat_product(gene_matrix & A, gene_matrix & X, int N) - { - daat_(A,X,&N); - } - - static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N) - { - int one=1; - daxpyf_(&N,&coef,X,Y); - } - - -}; - - -template<> -class f77_interface : public f77_interface_base -{ -public : - - static inline std::string name( void ) - { - return "F77"; - } - - - static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N) - { - smxv_(A,&N,B,&N,X); - } - - static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N) - { - smxm_(A,&N,B,&N,X,&N); - } - - static inline void ata_product(gene_matrix & A, gene_matrix & X, int N) - { - sata_(A,X,&N); - } - - static inline void aat_product(gene_matrix & A, gene_matrix & X, int N) - { - saat_(A,X,&N); - } - - - static inline void axpy(float coef, const gene_vector & X, gene_vector & Y, int N) - { - saxpyf_(&N,&coef,X,Y); - } - -}; - - -#endif - - - diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saat.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saat.f deleted file mode 100644 index 5d1855d2c..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saat.f +++ /dev/null @@ -1,14 +0,0 @@ - SUBROUTINE SAAT(A,X,N) -** -** X = AT * A - REAL*4 A(N,N),X(N,N) - DO 20 I=1,N - DO 20 J=1,N - R=0. - DO 10 K=1,N - R=R+A(I,K)*A(J,K) - 10 CONTINUE - X(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/sata.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/sata.f deleted file mode 100644 index 3ab83d958..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/sata.f +++ /dev/null @@ -1,14 +0,0 @@ - SUBROUTINE SATA(A,X,N) -** -** X = AT * A - REAL*4 A(N,N),X(N,N) - DO 20 I=1,N - DO 20 J=1,N - R=0. - DO 10 K=1,N - R=R+A(K,I)*A(K,J) - 10 CONTINUE - X(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saxpy.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saxpy.f deleted file mode 100644 index d0f74fd70..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/saxpy.f +++ /dev/null @@ -1,16 +0,0 @@ - SUBROUTINE SAXPYF(N,A,X,Y) -** *************************************** -** CALCULE Y = Y + A*X -** *************************************** -*>N NOMBRE D'OPERATIONS A FAIRE -*>A CONSTANTE MULTIPLICATIVE -*>X TABLEAU -*=Y TABLEAU DES RESULTATS -*A R. SANCHEZ ( EARLY WINTER 1987 ) -*V M.F. ROBEAU - DIMENSION X(1),Y(1) - DO 10 I=1,N - Y(I)=Y(I)+A*X(I) - 10 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxm.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxm.f deleted file mode 100644 index a1e63adca..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxm.f +++ /dev/null @@ -1,32 +0,0 @@ - SUBROUTINE SMXM(A,N,B,M,C,L) -** -** C = A * B -** A ET B MATRICES A(N,M) B(M,L) ==> C(N,L) -** -*>A PREMIERE MATRICE -*>N PREMIERE DIMENSION DE A ET DE C -*>B DEUXIEME MATRICE -*>M DEUXIEME DIMENSION DE A ET PERMIERE DE B -*L DEUXIEME DIMENSION DE B ET DE C -*A R. SANCHEZ ( EARLY WINTER 1987 ) -*V M.F. ROBEAU -*M AM BAUDRON - AVRIL 94 -*: ERREUR DANS L'APPEL A L'UTILITAIRE SGEMM -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR HP -*M AM BAUDRON - NOVEMBRE 1991 -*: ERREUR ( SOMME SUR LES TERMES PAS FAITE ) -*: APPEL A L'UTILITAIRE SGEMM DE LA LIBRAIRIE BLAS SUR RISC -*M AM BAUDRON - MAI 1993 -*: CHANGEMENT DES %IF LOCAL SUN MIPS SUITE A INTRODUCTION VERSION IBM - DIMENSION A(N,M),B(M,L),C(N,L) - DO 20 I=1,N - DO 20 J=1,L - R=0. - DO 10 K=1,M - R=R+A(I,K)*B(K,J) - 10 CONTINUE - C(I,J)=R - 20 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxv.f b/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxv.f deleted file mode 100644 index d2f7ed24e..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/f77/smxv.f +++ /dev/null @@ -1,38 +0,0 @@ - SUBROUTINE SMXV(A,N,X,M,R) -C -** -** VERSION DOUBLE PRECISION DE MXV -** R = A * X -** A MATRICE A(N,M) -** R ET X VECTEURS -** -*>A PREMIERE MATRICE -*>N PREMIERE DIMENSION DE A -*>X VECTEUR -*>M DEUXIEME DIMENSION DE A -* ipvt(N); gmm::lu_factor(R, ipvt); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/gmm/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/gmm/main.cpp index b1f51edb6..1f0c051eb 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/gmm/main.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/gmm/main.cpp @@ -20,7 +20,7 @@ #include "bench.hh" #include "basic_actions.hh" #include "action_hessenberg.hh" -#include "action_lu_decomp.hh" +#include "action_partial_lu.hh" BTL_MAIN; @@ -34,13 +34,13 @@ int main() bench > >(MIN_MV,MAX_MV,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); //bench > >(MIN_LU,MAX_LU,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/CMakeLists.txt deleted file mode 100644 index 3fffbfe8a..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -find_package(Eigen2) -if (EIGEN2_FOUND) - - include_directories(${EIGEN2_INCLUDE_DIR} ${PROJECT_SOURCE_DIR}/libs/f77) - btl_add_bench(btl_hand_vec main.cpp OFF) - - btl_add_bench(btl_hand_peeling main.cpp OFF) - if (BUILD_btl_hand_peeling) - set_target_properties(btl_hand_peeling PROPERTIES COMPILE_FLAGS "-DPEELING") - endif (BUILD_btl_hand_peeling) - -endif (EIGEN2_FOUND) \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/hand_vec_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/hand_vec_interface.hh deleted file mode 100755 index 0bb4b64ca..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/hand_vec/hand_vec_interface.hh +++ /dev/null @@ -1,886 +0,0 @@ -//===================================================== -// File : hand_vec_interface.hh -// Copyright (C) 2008 Gael Guennebaud -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#ifndef HAND_VEC_INTERFACE_HH -#define HAND_VEC_INTERFACE_HH - -#include -#include "f77_interface.hh" - -using namespace Eigen; - -template -class hand_vec_interface : public f77_interface_base { - -public : - - typedef typename internal::packet_traits::type Packet; - static const int PacketSize = internal::packet_traits::size; - - typedef typename f77_interface_base::stl_matrix stl_matrix; - typedef typename f77_interface_base::stl_vector stl_vector; - typedef typename f77_interface_base::gene_matrix gene_matrix; - typedef typename f77_interface_base::gene_vector gene_vector; - - static void free_matrix(gene_matrix & A, int N){ - internal::aligned_free(A); - } - - static void free_vector(gene_vector & B){ - internal::aligned_free(B); - } - - static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ - int N = A_stl.size(); - A = (real*)internal::aligned_malloc(N*N*sizeof(real)); - for (int j=0;j0) - { -// for (size_t j = 0;j0) - { - bool aligned0 = (iN0 % PacketSize) == 0; - if (aligned0) - for (int j = 0;j0) -// { -// // int aligned0 = (iN0 % PacketSize); -// int aligned1 = (iN1 % PacketSize); -// -// if (aligned1==0) -// { -// for (int j = 0;j0) -// { -// bool aligned0 = (iN0 % PacketSize) == 0; -// if (aligned0) -// for (int j = 0;j0) -// { -// bool aligned0 = (iN0 % PacketSize) == 0; -// bool aligned1 = (iN1 % PacketSize) == 0; -// -// if (aligned0 && aligned1) -// { -// for (int j = 0;j0) -// { -// bool aligned0 = (iN0 % PacketSize) == 0; -// if (aligned0) -// for (int j = 0;j0) -// { -// bool aligned = (iN % PacketSize) == 0; -// if (aligned) -// { -// #ifdef PEELING -// Packet A0, A1, A2, X0, X1, X2; -// int ANP = (AN/(8*PacketSize))*8*PacketSize; -// for (int j = 0;j0) - { - int align1 = (iN1 % PacketSize); - if (align1==0) - { - for (int j = 0;j0) - { - if (iN0 % PacketSize==0) - for (int j = 0;j0) -// { -// bool aligned = (iN % PacketSize) == 0; -// if (aligned) -// { -// #ifdef PEELING -// int ANP = (AN/(8*PacketSize))*8*PacketSize; -// for (int j = 0;j0) - { - Packet pcoef = internal::pset1(coef); - #ifdef PEELING - const int peelSize = 3; - int ANP = (AN/(peelSize*PacketSize))*peelSize*PacketSize; - float* X1 = X + PacketSize; - float* Y1 = Y + PacketSize; - float* X2 = X + 2*PacketSize; - float* Y2 = Y + 2*PacketSize; - Packet x0,x1,x2,y0,y1,y2; - for (int j = 0;j -// Copyright (C) EDF R&D, lun sep 30 14:23:23 CEST 2002 -//===================================================== -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// as published by the Free Software Foundation; either version 2 -// of the License, or (at your option) any later version. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. -// You should have received a copy of the GNU General Public License -// along with this program; if not, write to the Free Software -// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. -// -#include "utilities.h" -#include "bench.hh" -#include "hand_vec_interface.hh" -#include "action_matrix_vector_product.hh" -#include "action_atv_product.hh" -#include "action_matrix_matrix_product.hh" -#include "action_axpy.hh" -#include "action_ata_product.hh" -#include "action_aat_product.hh" -#include "basic_actions.hh" -//#include "action_lu_solve.hh" -// #include "timers/mixed_perf_analyzer.hh" - -BTL_MAIN; - -int main() -{ - - bench > >(MIN_MV,MAX_MV,NB_POINT); - bench > >(MIN_MV,MAX_MV,NB_POINT); -// bench > >(MIN_MM,MAX_MM,NB_POINT); -// bench > >(MIN_MM,MAX_MM,NB_POINT); -// bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); - - - return 0; -} - - diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/mtl4/mtl4_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/mtl4/mtl4_interface.hh index a2f067f73..3795ac61e 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/mtl4/mtl4_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/mtl4/mtl4_interface.hh @@ -92,9 +92,9 @@ public : X = (trans(A)*trans(B)); } - static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){ - X = (trans(A)*A); - } +// static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){ +// X = (trans(A)*A); +// } static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){ X = (A*trans(A)); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/ublas/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/ublas/main.cpp index 22d697225..e2e77ee1f 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/ublas/main.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/ublas/main.cpp @@ -33,8 +33,8 @@ int main() bench > >(MIN_MV,MAX_MV,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); bench > >(MIN_MM,MAX_MM,NB_POINT); diff --git a/gtsam/3rdparty/Eigen/bench/sparse_dense_product.cpp b/gtsam/3rdparty/Eigen/bench/sparse_dense_product.cpp index bfe46122d..f3f519406 100644 --- a/gtsam/3rdparty/Eigen/bench/sparse_dense_product.cpp +++ b/gtsam/3rdparty/Eigen/bench/sparse_dense_product.cpp @@ -4,7 +4,7 @@ // -DNOGMM -DNOMTL -DCSPARSE // -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a #ifndef SIZE -#define SIZE 10000 +#define SIZE 650000 #endif #ifndef DENSITY @@ -62,7 +62,8 @@ int main(int argc, char *argv[]) BenchTimer timer; for (float density = DENSITY; density>=MINDENSITY; density*=0.5) { - fillMatrix(density, rows, cols, sm1); + //fillMatrix(density, rows, cols, sm1); + fillMatrix2(7, rows, cols, sm1); // dense matrices #ifdef DENSEMATRIX @@ -76,14 +77,14 @@ int main(int argc, char *argv[]) for (int k=0; k uv1, uv2; + eiToUblasVec(v1,uv1); + eiToUblasVec(v2,uv2); + +// std::vector gmmV1(cols), gmmV2(cols); +// Map >(&gmmV1[0], cols) = v1; +// Map >(&gmmV2[0], cols) = v2; + + BENCH( uv2 = boost::numeric::ublas::prod(m1, uv1); ) + std::cout << " a * v:\t" << timer.value() << endl; + +// BENCH( boost::ublas::prod(gmm::transposed(m1), gmmV1, gmmV2); ) +// std::cout << " a' * v:\t" << timer.value() << endl; + } + #endif // MTL4 #ifndef NOMTL diff --git a/gtsam/3rdparty/Eigen/bench/sparse_product.cpp b/gtsam/3rdparty/Eigen/bench/sparse_product.cpp index 0b5558b89..d2fc44f0d 100644 --- a/gtsam/3rdparty/Eigen/bench/sparse_product.cpp +++ b/gtsam/3rdparty/Eigen/bench/sparse_product.cpp @@ -20,6 +20,7 @@ #include #include "BenchTimer.h" +#include "BenchUtil.h" #include "BenchSparseUtil.h" #ifndef NBTRIES @@ -228,16 +229,12 @@ int main(int argc, char *argv[]) eiToCSparse(sm1, m1); eiToCSparse(sm2, m2); -// timer.reset(); -// timer.start(); -// for (int k=0; k + +void bench_printhelp() +{ + cout<< " \nbenchsolver : performs a benchmark of all the solvers available in Eigen \n\n"; + cout<< " MATRIX FOLDER : \n"; + cout<< " The matrices for the benchmark should be collected in a folder specified with an environment variable EIGEN_MATRIXDIR \n"; + cout<< " This folder should contain the subfolders real/ and complex/ : \n"; + cout<< " The matrices are stored using the matrix market coordinate format \n"; + cout<< " The matrix and associated right-hand side (rhs) files are named respectively \n"; + cout<< " as MatrixName.mtx and MatrixName_b.mtx. If the rhs does not exist, a random one is generated. \n"; + cout<< " If a matrix is SPD, the matrix should be named as MatrixName_SPD.mtx \n"; + cout<< " If a true solution exists, it should be named as MatrixName_x.mtx; \n" ; + cout<< " it will be used to compute the norm of the error relative to the computed solutions\n\n"; + cout<< " OPTIONS : \n"; + cout<< " -h or --help \n print this help and return\n\n"; + cout<< " -d matrixdir \n Use matrixdir as the matrix folder instead of the one specified in the environment variable EIGEN_MATRIXDIR\n\n"; + cout<< " -o outputfile.html \n Output the statistics to a html file \n\n"; + cout<< " --eps Sets the relative tolerance for iterative solvers (default 1e-08) \n\n"; + cout<< " --maxits Sets the maximum number of iterations (default 1000) \n\n"; + +} +int main(int argc, char ** args) +{ + + bool help = ( get_options(argc, args, "-h") || get_options(argc, args, "--help") ); + if(help) { + bench_printhelp(); + return 0; + } + + // Get the location of the test matrices + string matrix_dir; + if (!get_options(argc, args, "-d", &matrix_dir)) + { + if(getenv("EIGEN_MATRIXDIR") == NULL){ + std::cerr << "Please, specify the location of the matrices with -d mat_folder or the environment variable EIGEN_MATRIXDIR \n"; + std::cerr << " Run with --help to see the list of all the available options \n"; + return -1; + } + matrix_dir = getenv("EIGEN_MATRIXDIR"); + } + + std::ofstream statbuf; + string statFile ; + + // Get the file to write the statistics + bool statFileExists = get_options(argc, args, "-o", &statFile); + if(statFileExists) + { + statbuf.open(statFile.c_str(), std::ios::out); + if(statbuf.good()){ + statFileExists = true; + printStatheader(statbuf); + statbuf.close(); + } + else + std::cerr << "Unable to open the provided file for writting... \n"; + } + + // Get the maximum number of iterations and the tolerance + int maxiters = 1000; + double tol = 1e-08; + string inval; + if (get_options(argc, args, "--eps", &inval)) + tol = atof(inval.c_str()); + if(get_options(argc, args, "--maxits", &inval)) + maxiters = atoi(inval.c_str()); + + string current_dir; + // Test the matrices in %EIGEN_MATRIXDIR/real + current_dir = matrix_dir + "/real"; + Browse_Matrices(current_dir, statFileExists, statFile,maxiters, tol); + + // Test the matrices in %EIGEN_MATRIXDIR/complex + current_dir = matrix_dir + "/complex"; + Browse_Matrices >(current_dir, statFileExists, statFile, maxiters, tol); + + if(statFileExists) + { + statbuf.open(statFile.c_str(), std::ios::app); + statbuf << " \n"; + cout << "\n Output written in " << statFile << " ...\n"; + statbuf.close(); + } + + return 0; +} + + diff --git a/gtsam/3rdparty/Eigen/bench/spbench/spbenchsolver.h b/gtsam/3rdparty/Eigen/bench/spbench/spbenchsolver.h new file mode 100644 index 000000000..6d765a997 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/spbench/spbenchsolver.h @@ -0,0 +1,548 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2012 Désiré Nuentsa-Wakam +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + + +#include +#include +#include "Eigen/SparseCore" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef EIGEN_CHOLMOD_SUPPORT +#include +#endif + +#ifdef EIGEN_UMFPACK_SUPPORT +#include +#endif + +#ifdef EIGEN_PARDISO_SUPPORT +#include +#endif + +#ifdef EIGEN_SUPERLU_SUPPORT +#include +#endif + +#ifdef EIGEN_PASTIX_SUPPORT +#include +#endif + +// CONSTANTS +#define EIGEN_UMFPACK 0 +#define EIGEN_SUPERLU 1 +#define EIGEN_PASTIX 2 +#define EIGEN_PARDISO 3 +#define EIGEN_BICGSTAB 4 +#define EIGEN_BICGSTAB_ILUT 5 +#define EIGEN_GMRES 6 +#define EIGEN_GMRES_ILUT 7 +#define EIGEN_SIMPLICIAL_LDLT 8 +#define EIGEN_CHOLMOD_LDLT 9 +#define EIGEN_PASTIX_LDLT 10 +#define EIGEN_PARDISO_LDLT 11 +#define EIGEN_SIMPLICIAL_LLT 12 +#define EIGEN_CHOLMOD_SUPERNODAL_LLT 13 +#define EIGEN_CHOLMOD_SIMPLICIAL_LLT 14 +#define EIGEN_PASTIX_LLT 15 +#define EIGEN_PARDISO_LLT 16 +#define EIGEN_CG 17 +#define EIGEN_CG_PRECOND 18 +#define EIGEN_ALL_SOLVERS 19 + +using namespace Eigen; +using namespace std; + +struct Stats{ + ComputationInfo info; + double total_time; + double compute_time; + double solve_time; + double rel_error; + int memory_used; + int iterations; + int isavail; + int isIterative; +}; + +// Global variables for input parameters +int MaximumIters; // Maximum number of iterations +double RelErr; // Relative error of the computed solution + +template inline typename NumTraits::Real test_precision() { return NumTraits::dummy_precision(); } +template<> inline float test_precision() { return 1e-3f; } +template<> inline double test_precision() { return 1e-6; } +template<> inline float test_precision >() { return test_precision(); } +template<> inline double test_precision >() { return test_precision(); } + +void printStatheader(std::ofstream& out) +{ + int LUcnt = 0; + string LUlist =" ", LLTlist = " LLT", LDLTlist = " LDLT "; + +#ifdef EIGEN_UMFPACK_SUPPORT + LUlist += " UMFPACK "; LUcnt++; +#endif +#ifdef EIGEN_SUPERLU_SUPPORT + LUlist += " SUPERLU "; LUcnt++; +#endif +#ifdef EIGEN_CHOLMOD_SUPPORT + LLTlist += " CHOLMOD SP LLT CHOLMOD LLT"; + LDLTlist += "CHOLMOD LDLT"; +#endif +#ifdef EIGEN_PARDISO_SUPPORT + LUlist += " PARDISO LU"; LUcnt++; + LLTlist += " PARDISO LLT"; + LDLTlist += " PARDISO LDLT"; +#endif +#ifdef EIGEN_PASTIX_SUPPORT + LUlist += " PASTIX LU"; LUcnt++; + LLTlist += " PASTIX LLT"; + LDLTlist += " PASTIX LDLT"; +#endif + + out << "\n "; + out << "
Matrix N NNZ "; + if (LUcnt) out << LUlist; + out << " BiCGSTAB BiCGSTAB+ILUT"<< "GMRES+ILUT" < CG "<< std::endl; +} + + +template +Stats call_solver(Solver &solver, const typename Solver::MatrixType& A, const Matrix& b, const Matrix& refX) +{ + Stats stat; + Matrix x; + BenchTimer timer; + timer.reset(); + timer.start(); + solver.compute(A); + if (solver.info() != Success) + { + stat.info = NumericalIssue; + std::cerr << "Solver failed ... \n"; + return stat; + } + timer.stop(); + stat.compute_time = timer.value(); + + timer.reset(); + timer.start(); + x = solver.solve(b); + if (solver.info() == NumericalIssue) + { + stat.info = NumericalIssue; + std::cerr << "Solver failed ... \n"; + return stat; + } + + timer.stop(); + stat.solve_time = timer.value(); + stat.total_time = stat.solve_time + stat.compute_time; + stat.memory_used = 0; + // Verify the relative error + if(refX.size() != 0) + stat.rel_error = (refX - x).norm()/refX.norm(); + else + { + // Compute the relative residual norm + Matrix temp; + temp = A * x; + stat.rel_error = (b-temp).norm()/b.norm(); + } + if ( stat.rel_error > RelErr ) + { + stat.info = NoConvergence; + return stat; + } + else + { + stat.info = Success; + return stat; + } +} + +template +Stats call_directsolver(Solver& solver, const typename Solver::MatrixType& A, const Matrix& b, const Matrix& refX) +{ + Stats stat; + stat = call_solver(solver, A, b, refX); + return stat; +} + +template +Stats call_itersolver(Solver &solver, const typename Solver::MatrixType& A, const Matrix& b, const Matrix& refX) +{ + Stats stat; + solver.setTolerance(RelErr); + solver.setMaxIterations(MaximumIters); + + stat = call_solver(solver, A, b, refX); + stat.iterations = solver.iterations(); + return stat; +} + +inline void printStatItem(Stats *stat, int solver_id, int& best_time_id, double& best_time_val) +{ + stat[solver_id].isavail = 1; + + if (stat[solver_id].info == NumericalIssue) + { + cout << " SOLVER FAILED ... Probably a numerical issue \n"; + return; + } + if (stat[solver_id].info == NoConvergence){ + cout << "REL. ERROR " << stat[solver_id].rel_error; + if(stat[solver_id].isIterative == 1) + cout << " (" << stat[solver_id].iterations << ") \n"; + return; + } + + // Record the best CPU time + if (!best_time_val) + { + best_time_val = stat[solver_id].total_time; + best_time_id = solver_id; + } + else if (stat[solver_id].total_time < best_time_val) + { + best_time_val = stat[solver_id].total_time; + best_time_id = solver_id; + } + // Print statistics to standard output + if (stat[solver_id].info == Success){ + cout<< "COMPUTE TIME : " << stat[solver_id].compute_time<< " \n"; + cout<< "SOLVE TIME : " << stat[solver_id].solve_time<< " \n"; + cout<< "TOTAL TIME : " << stat[solver_id].total_time<< " \n"; + cout << "REL. ERROR : " << stat[solver_id].rel_error ; + if(stat[solver_id].isIterative == 1) { + cout << " (" << stat[solver_id].iterations << ") "; + } + cout << std::endl; + } + +} + + +/* Print the results from all solvers corresponding to a particular matrix + * The best CPU time is printed in bold + */ +inline void printHtmlStatLine(Stats *stat, int best_time_id, string& statline) +{ + + string markup; + ostringstream compute,solve,total,error; + for (int i = 0; i < EIGEN_ALL_SOLVERS; i++) + { + if (stat[i].isavail == 0) continue; + if(i == best_time_id) + markup = ""; + else + markup = ""; + + if (stat[i].info == Success){ + compute << markup << stat[i].compute_time; + solve << markup << stat[i].solve_time; + total << markup << stat[i].total_time; + error << " " << stat[i].rel_error; + if(stat[i].isIterative == 1) { + error << " (" << stat[i].iterations << ") "; + } + } + else { + compute << " -" ; + solve << " -" ; + total << " -" ; + if(stat[i].info == NoConvergence){ + error << " "<< stat[i].rel_error ; + if(stat[i].isIterative == 1) + error << " (" << stat[i].iterations << ") "; + } + else error << " - "; + } + } + + statline = "Compute Time " + compute.str() + "\n" + + "
Solve Time " + solve.str() + "\n" + + "
Total Time " + total.str() + "\n" + +"
Error(Iter)" + error.str() + "\n"; + +} + +template +int SelectSolvers(const SparseMatrix&A, unsigned int sym, Matrix& b, const Matrix& refX, Stats *stat) +{ + typedef SparseMatrix SpMat; + // First, deal with Nonsymmetric and symmetric matrices + int best_time_id = 0; + double best_time_val = 0.0; + //UMFPACK + #ifdef EIGEN_UMFPACK_SUPPORT + { + cout << "Solving with UMFPACK LU ... \n"; + UmfPackLU solver; + stat[EIGEN_UMFPACK] = call_directsolver(solver, A, b, refX); + printStatItem(stat, EIGEN_UMFPACK, best_time_id, best_time_val); + } + #endif + //SuperLU + #ifdef EIGEN_SUPERLU_SUPPORT + { + cout << "\nSolving with SUPERLU ... \n"; + SuperLU solver; + stat[EIGEN_SUPERLU] = call_directsolver(solver, A, b, refX); + printStatItem(stat, EIGEN_SUPERLU, best_time_id, best_time_val); + } + #endif + + // PaStix LU + #ifdef EIGEN_PASTIX_SUPPORT + { + cout << "\nSolving with PASTIX LU ... \n"; + PastixLU solver; + stat[EIGEN_PASTIX] = call_directsolver(solver, A, b, refX) ; + printStatItem(stat, EIGEN_PASTIX, best_time_id, best_time_val); + } + #endif + + //PARDISO LU + #ifdef EIGEN_PARDISO_SUPPORT + { + cout << "\nSolving with PARDISO LU ... \n"; + PardisoLU solver; + stat[EIGEN_PARDISO] = call_directsolver(solver, A, b, refX); + printStatItem(stat, EIGEN_PARDISO, best_time_id, best_time_val); + } + #endif + + + + //BiCGSTAB + { + cout << "\nSolving with BiCGSTAB ... \n"; + BiCGSTAB solver; + stat[EIGEN_BICGSTAB] = call_itersolver(solver, A, b, refX); + stat[EIGEN_BICGSTAB].isIterative = 1; + printStatItem(stat, EIGEN_BICGSTAB, best_time_id, best_time_val); + } + //BiCGSTAB+ILUT + { + cout << "\nSolving with BiCGSTAB and ILUT ... \n"; + BiCGSTAB > solver; + stat[EIGEN_BICGSTAB_ILUT] = call_itersolver(solver, A, b, refX); + stat[EIGEN_BICGSTAB_ILUT].isIterative = 1; + printStatItem(stat, EIGEN_BICGSTAB_ILUT, best_time_id, best_time_val); + } + + + //GMRES +// { +// cout << "\nSolving with GMRES ... \n"; +// GMRES solver; +// stat[EIGEN_GMRES] = call_itersolver(solver, A, b, refX); +// stat[EIGEN_GMRES].isIterative = 1; +// printStatItem(stat, EIGEN_GMRES, best_time_id, best_time_val); +// } + //GMRES+ILUT + { + cout << "\nSolving with GMRES and ILUT ... \n"; + GMRES > solver; + stat[EIGEN_GMRES_ILUT] = call_itersolver(solver, A, b, refX); + stat[EIGEN_GMRES_ILUT].isIterative = 1; + printStatItem(stat, EIGEN_GMRES_ILUT, best_time_id, best_time_val); + } + + // Hermitian and not necessarily positive-definites + if (sym != NonSymmetric) + { + // Internal Cholesky + { + cout << "\nSolving with Simplicial LDLT ... \n"; + SimplicialLDLT solver; + stat[EIGEN_SIMPLICIAL_LDLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat, EIGEN_SIMPLICIAL_LDLT, best_time_id, best_time_val); + } + + // CHOLMOD + #ifdef EIGEN_CHOLMOD_SUPPORT + { + cout << "\nSolving with CHOLMOD LDLT ... \n"; + CholmodDecomposition solver; + solver.setMode(CholmodLDLt); + stat[EIGEN_CHOLMOD_LDLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_CHOLMOD_LDLT, best_time_id, best_time_val); + } + #endif + + //PASTIX LLT + #ifdef EIGEN_PASTIX_SUPPORT + { + cout << "\nSolving with PASTIX LDLT ... \n"; + PastixLDLT solver; + stat[EIGEN_PASTIX_LDLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_PASTIX_LDLT, best_time_id, best_time_val); + } + #endif + + //PARDISO LLT + #ifdef EIGEN_PARDISO_SUPPORT + { + cout << "\nSolving with PARDISO LDLT ... \n"; + PardisoLDLT solver; + stat[EIGEN_PARDISO_LDLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_PARDISO_LDLT, best_time_id, best_time_val); + } + #endif + } + + // Now, symmetric POSITIVE DEFINITE matrices + if (sym == SPD) + { + + //Internal Sparse Cholesky + { + cout << "\nSolving with SIMPLICIAL LLT ... \n"; + SimplicialLLT solver; + stat[EIGEN_SIMPLICIAL_LLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_SIMPLICIAL_LLT, best_time_id, best_time_val); + } + + // CHOLMOD + #ifdef EIGEN_CHOLMOD_SUPPORT + { + // CholMOD SuperNodal LLT + cout << "\nSolving with CHOLMOD LLT (Supernodal)... \n"; + CholmodDecomposition solver; + solver.setMode(CholmodSupernodalLLt); + stat[EIGEN_CHOLMOD_SUPERNODAL_LLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_CHOLMOD_SUPERNODAL_LLT, best_time_id, best_time_val); + // CholMod Simplicial LLT + cout << "\nSolving with CHOLMOD LLT (Simplicial) ... \n"; + solver.setMode(CholmodSimplicialLLt); + stat[EIGEN_CHOLMOD_SIMPLICIAL_LLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_CHOLMOD_SIMPLICIAL_LLT, best_time_id, best_time_val); + } + #endif + + //PASTIX LLT + #ifdef EIGEN_PASTIX_SUPPORT + { + cout << "\nSolving with PASTIX LLT ... \n"; + PastixLLT solver; + stat[EIGEN_PASTIX_LLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_PASTIX_LLT, best_time_id, best_time_val); + } + #endif + + //PARDISO LLT + #ifdef EIGEN_PARDISO_SUPPORT + { + cout << "\nSolving with PARDISO LLT ... \n"; + PardisoLLT solver; + stat[EIGEN_PARDISO_LLT] = call_directsolver(solver, A, b, refX); + printStatItem(stat,EIGEN_PARDISO_LLT, best_time_id, best_time_val); + } + #endif + + // Internal CG + { + cout << "\nSolving with CG ... \n"; + ConjugateGradient solver; + stat[EIGEN_CG] = call_itersolver(solver, A, b, refX); + stat[EIGEN_CG].isIterative = 1; + printStatItem(stat,EIGEN_CG, best_time_id, best_time_val); + } + //CG+IdentityPreconditioner +// { +// cout << "\nSolving with CG and IdentityPreconditioner ... \n"; +// ConjugateGradient solver; +// stat[EIGEN_CG_PRECOND] = call_itersolver(solver, A, b, refX); +// stat[EIGEN_CG_PRECOND].isIterative = 1; +// printStatItem(stat,EIGEN_CG_PRECOND, best_time_id, best_time_val); +// } + } // End SPD matrices + + return best_time_id; +} + +/* Browse all the matrices available in the specified folder + * and solve the associated linear system. + * The results of each solve are printed in the standard output + * and optionally in the provided html file + */ +template +void Browse_Matrices(const string folder, bool statFileExists, std::string& statFile, int maxiters, double tol) +{ + MaximumIters = maxiters; // Maximum number of iterations, global variable + RelErr = tol; //Relative residual error as stopping criterion for iterative solvers + MatrixMarketIterator it(folder); + Stats stat[EIGEN_ALL_SOLVERS]; + for ( ; it; ++it) + { + for (int i = 0; i < EIGEN_ALL_SOLVERS; i++) + { + stat[i].isavail = 0; + stat[i].isIterative = 0; + } + + int best_time_id; + cout<< "\n\n===================================================== \n"; + cout<< " ====== SOLVING WITH MATRIX " << it.matname() << " ====\n"; + cout<< " =================================================== \n\n"; + Matrix refX; + if(it.hasrefX()) refX = it.refX(); + best_time_id = SelectSolvers(it.matrix(), it.sym(), it.rhs(), refX, &stat[0]); + + if(statFileExists) + { + string statline; + printHtmlStatLine(&stat[0], best_time_id, statline); + std::ofstream statbuf(statFile.c_str(), std::ios::app); + statbuf << "
" << it.matname() << " " + << it.matrix().rows() << " " << it.matrix().nonZeros()<< " "<< statline ; + statbuf.close(); + } + } +} + +bool get_options(int argc, char **args, string option, string* value=0) +{ + int idx = 1, found=false; + while (idx +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_BAND_TRIANGULARSOLVER_H +#define EIGEN_BAND_TRIANGULARSOLVER_H + +namespace internal { + + /* \internal + * Solve Ax=b with A a band triangular matrix + * TODO: extend it to matrices for x abd b */ +template +struct band_solve_triangular_selector; + + +template +struct band_solve_triangular_selector +{ + typedef Map, 0, OuterStride<> > LhsMap; + typedef Map > RhsMap; + enum { IsLower = (Mode&Lower) ? 1 : 0 }; + static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other) + { + const LhsMap lhs(_lhs,size,k+1,OuterStride<>(lhsStride)); + RhsMap other(_other,size,1); + typename internal::conditional< + ConjLhs, + const CwiseUnaryOp,LhsMap>, + const LhsMap&> + ::type cjLhs(lhs); + + for(int col=0 ; col0) + other.coeffRef(i,col) -= cjLhs.row(i).segment(actual_start,actual_k).transpose() + .cwiseProduct(other.col(col).segment(IsLower ? i-actual_k : i+1,actual_k)).sum(); + + if((Mode&UnitDiag)==0) + other.coeffRef(i,col) /= cjLhs(i,IsLower ? k : 0); + } + } + } + +}; + +template +struct band_solve_triangular_selector +{ + typedef Map, 0, OuterStride<> > LhsMap; + typedef Map > RhsMap; + enum { IsLower = (Mode&Lower) ? 1 : 0 }; + static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other) + { + const LhsMap lhs(_lhs,k+1,size,OuterStride<>(lhsStride)); + RhsMap other(_other,size,1); + typename internal::conditional< + ConjLhs, + const CwiseUnaryOp,LhsMap>, + const LhsMap&> + ::type cjLhs(lhs); + + for(int col=0 ; col0) + other.col(col).segment(IsLower ? i+1 : i-actual_k, actual_k) + -= other.coeff(i,col) * cjLhs.col(i).segment(actual_start,actual_k); + + } + } + } +}; + + +} // end namespace internal + +#endif // EIGEN_BAND_TRIANGULARSOLVER_H diff --git a/gtsam/3rdparty/Eigen/blas/CMakeLists.txt b/gtsam/3rdparty/Eigen/blas/CMakeLists.txt index 5f2e3cd32..453d5874c 100644 --- a/gtsam/3rdparty/Eigen/blas/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/blas/CMakeLists.txt @@ -1,27 +1,34 @@ project(EigenBlas CXX) -if( NOT DEFINED EIGEN_Fortran_COMPILER_WORKS OR EIGEN_Fortran_COMPILER_WORKS) +include("../cmake/language_support.cmake") +workaround_9220(Fortran EIGEN_Fortran_COMPILER_WORKS) + +if(EIGEN_Fortran_COMPILER_WORKS) enable_language(Fortran OPTIONAL) - - if(CMAKE_Fortran_COMPILER_WORKS) - set(EIGEN_Fortran_COMPILER_WORKS TRUE CACHE INTERNAL "workaround cmake's enable_language issue") - else() - set(EIGEN_Fortran_COMPILER_WORKS FALSE CACHE INTERNAL "workaround cmake's enable_language issue") - endif() - endif() -if(CMAKE_Fortran_COMPILER_WORKS) - add_custom_target(blas) -set(EigenBlas_SRCS single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp +set(EigenBlas_SRCS single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp) + +if(EIGEN_Fortran_COMPILER_WORKS) + +set(EigenBlas_SRCS ${EigenBlas_SRCS} complexdots.f srotm.f srotmg.f drotm.f drotmg.f - lsame.f chpr2.f ctbsv.f dspmv.f dtbmv.f dtpsv.f ssbmv.f sspr.f stpmv.f zhpr2.f ztbsv.f chbmv.f chpr.f ctpmv.f dspr2.f dtbsv.f sspmv.f stbmv.f stpsv.f zhbmv.f zhpr.f ztpmv.f chpmv.f ctbmv.f ctpsv.f dsbmv.f dspr.f dtpmv.f sspr2.f stbsv.f zhpmv.f ztbmv.f ztpsv.f + lsame.f chpr2.f dspmv.f dtpsv.f ssbmv.f sspr.f stpmv.f + zhpr2.f chbmv.f chpr.f ctpmv.f dspr2.f sspmv.f stpsv.f + zhbmv.f zhpr.f ztpmv.f chpmv.f ctpsv.f dsbmv.f dspr.f dtpmv.f sspr2.f + zhpmv.f ztpsv.f + dtbmv.f stbmv.f ctbmv.f ztbmv.f ) +else() + +message(WARNING " No fortran compiler has been detected, the blas build will be incomplete.") + +endif() add_library(eigen_blas_static ${EigenBlas_SRCS}) add_library(eigen_blas SHARED ${EigenBlas_SRCS}) @@ -33,11 +40,12 @@ endif() add_dependencies(blas eigen_blas eigen_blas_static) -install(TARGETS eigen_blas +install(TARGETS eigen_blas eigen_blas_static RUNTIME DESTINATION bin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib) +if(EIGEN_Fortran_COMPILER_WORKS) if(EIGEN_LEAVE_TEST_IN_ALL_TARGET) add_subdirectory(testing) # can't do EXCLUDE_FROM_ALL here, breaks CTest @@ -45,4 +53,5 @@ else() add_subdirectory(testing EXCLUDE_FROM_ALL) endif() -endif(CMAKE_Fortran_COMPILER_WORKS) +endif() + diff --git a/gtsam/3rdparty/Eigen/blas/common.h b/gtsam/3rdparty/Eigen/blas/common.h index ed93642f9..ada833a90 100644 --- a/gtsam/3rdparty/Eigen/blas/common.h +++ b/gtsam/3rdparty/Eigen/blas/common.h @@ -32,16 +32,8 @@ #error the token SCALAR must be defined to compile this file #endif -#ifdef __cplusplus -extern "C" -{ -#endif +#include -#include "../bench/btl/libs/C_BLAS/blas.h" - -#ifdef __cplusplus -} -#endif #define NOTR 0 #define TR 1 @@ -93,6 +85,12 @@ inline bool check_uplo(const char* uplo) #include #include + + +namespace Eigen { +#include "BandTriangularSolver.h" +} + using namespace Eigen; typedef SCALAR Scalar; diff --git a/gtsam/3rdparty/Eigen/blas/ctbsv.f b/gtsam/3rdparty/Eigen/blas/ctbsv.f deleted file mode 100644 index 853b9d75e..000000000 --- a/gtsam/3rdparty/Eigen/blas/ctbsv.f +++ /dev/null @@ -1,370 +0,0 @@ - SUBROUTINE CTBSV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - COMPLEX A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* CTBSV solves one of the systems of equations -* -* A*x = b, or A'*x = b, or conjg( A' )*x = b, -* -* where b and x are n element vectors and A is an n by n unit, or -* non-unit, upper or lower triangular band matrix, with ( k + 1 ) -* diagonals. -* -* No test for singularity or near-singularity is included in this -* routine. Such tests must be performed before calling this routine. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the equations to be solved as -* follows: -* -* TRANS = 'N' or 'n' A*x = b. -* -* TRANS = 'T' or 't' A'*x = b. -* -* TRANS = 'C' or 'c' conjg( A' )*x = b. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - COMPLEX array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element right-hand side vector b. On exit, X is overwritten -* with the solution vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - COMPLEX ZERO - PARAMETER (ZERO= (0.0E+0,0.0E+0)) -* .. -* .. Local Scalars .. - COMPLEX TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOCONJ,NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC CONJG,MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('CTBSV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOCONJ = LSAME(TRANS,'T') - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed by sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := inv( A )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - L = KPLUS1 - J - IF (NOUNIT) X(J) = X(J)/A(KPLUS1,J) - TEMP = X(J) - DO 10 I = J - 1,MAX(1,J-K),-1 - X(I) = X(I) - TEMP*A(L+I,J) - 10 CONTINUE - END IF - 20 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 40 J = N,1,-1 - KX = KX - INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = KPLUS1 - J - IF (NOUNIT) X(JX) = X(JX)/A(KPLUS1,J) - TEMP = X(JX) - DO 30 I = J - 1,MAX(1,J-K),-1 - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX - INCX - 30 CONTINUE - END IF - JX = JX - INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = 1,N - IF (X(J).NE.ZERO) THEN - L = 1 - J - IF (NOUNIT) X(J) = X(J)/A(1,J) - TEMP = X(J) - DO 50 I = J + 1,MIN(N,J+K) - X(I) = X(I) - TEMP*A(L+I,J) - 50 CONTINUE - END IF - 60 CONTINUE - ELSE - JX = KX - DO 80 J = 1,N - KX = KX + INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = 1 - J - IF (NOUNIT) X(JX) = X(JX)/A(1,J) - TEMP = X(JX) - DO 70 I = J + 1,MIN(N,J+K) - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX + INCX - 70 CONTINUE - END IF - JX = JX + INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := inv( A' )*x or x := inv( conjg( A') )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 110 J = 1,N - TEMP = X(J) - L = KPLUS1 - J - IF (NOCONJ) THEN - DO 90 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(I) - 90 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - ELSE - DO 100 I = MAX(1,J-K),J - 1 - TEMP = TEMP - CONJG(A(L+I,J))*X(I) - 100 CONTINUE - IF (NOUNIT) TEMP = TEMP/CONJG(A(KPLUS1,J)) - END IF - X(J) = TEMP - 110 CONTINUE - ELSE - JX = KX - DO 140 J = 1,N - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - IF (NOCONJ) THEN - DO 120 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX + INCX - 120 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - ELSE - DO 130 I = MAX(1,J-K),J - 1 - TEMP = TEMP - CONJG(A(L+I,J))*X(IX) - IX = IX + INCX - 130 CONTINUE - IF (NOUNIT) TEMP = TEMP/CONJG(A(KPLUS1,J)) - END IF - X(JX) = TEMP - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 140 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 170 J = N,1,-1 - TEMP = X(J) - L = 1 - J - IF (NOCONJ) THEN - DO 150 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(I) - 150 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - ELSE - DO 160 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - CONJG(A(L+I,J))*X(I) - 160 CONTINUE - IF (NOUNIT) TEMP = TEMP/CONJG(A(1,J)) - END IF - X(J) = TEMP - 170 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 200 J = N,1,-1 - TEMP = X(JX) - IX = KX - L = 1 - J - IF (NOCONJ) THEN - DO 180 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX - INCX - 180 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - ELSE - DO 190 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - CONJG(A(L+I,J))*X(IX) - IX = IX - INCX - 190 CONTINUE - IF (NOUNIT) TEMP = TEMP/CONJG(A(1,J)) - END IF - X(JX) = TEMP - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 200 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of CTBSV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/dtbsv.f b/gtsam/3rdparty/Eigen/blas/dtbsv.f deleted file mode 100644 index cfeb0b82b..000000000 --- a/gtsam/3rdparty/Eigen/blas/dtbsv.f +++ /dev/null @@ -1,339 +0,0 @@ - SUBROUTINE DTBSV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - DOUBLE PRECISION A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* DTBSV solves one of the systems of equations -* -* A*x = b, or A'*x = b, -* -* where b and x are n element vectors and A is an n by n unit, or -* non-unit, upper or lower triangular band matrix, with ( k + 1 ) -* diagonals. -* -* No test for singularity or near-singularity is included in this -* routine. Such tests must be performed before calling this routine. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the equations to be solved as -* follows: -* -* TRANS = 'N' or 'n' A*x = b. -* -* TRANS = 'T' or 't' A'*x = b. -* -* TRANS = 'C' or 'c' A'*x = b. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - DOUBLE PRECISION array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - DOUBLE PRECISION array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element right-hand side vector b. On exit, X is overwritten -* with the solution vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE PRECISION ZERO - PARAMETER (ZERO=0.0D+0) -* .. -* .. Local Scalars .. - DOUBLE PRECISION TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('DTBSV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed by sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := inv( A )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - L = KPLUS1 - J - IF (NOUNIT) X(J) = X(J)/A(KPLUS1,J) - TEMP = X(J) - DO 10 I = J - 1,MAX(1,J-K),-1 - X(I) = X(I) - TEMP*A(L+I,J) - 10 CONTINUE - END IF - 20 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 40 J = N,1,-1 - KX = KX - INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = KPLUS1 - J - IF (NOUNIT) X(JX) = X(JX)/A(KPLUS1,J) - TEMP = X(JX) - DO 30 I = J - 1,MAX(1,J-K),-1 - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX - INCX - 30 CONTINUE - END IF - JX = JX - INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = 1,N - IF (X(J).NE.ZERO) THEN - L = 1 - J - IF (NOUNIT) X(J) = X(J)/A(1,J) - TEMP = X(J) - DO 50 I = J + 1,MIN(N,J+K) - X(I) = X(I) - TEMP*A(L+I,J) - 50 CONTINUE - END IF - 60 CONTINUE - ELSE - JX = KX - DO 80 J = 1,N - KX = KX + INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = 1 - J - IF (NOUNIT) X(JX) = X(JX)/A(1,J) - TEMP = X(JX) - DO 70 I = J + 1,MIN(N,J+K) - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX + INCX - 70 CONTINUE - END IF - JX = JX + INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := inv( A')*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 100 J = 1,N - TEMP = X(J) - L = KPLUS1 - J - DO 90 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(I) - 90 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - X(J) = TEMP - 100 CONTINUE - ELSE - JX = KX - DO 120 J = 1,N - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - DO 110 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX + INCX - 110 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - X(JX) = TEMP - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 120 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 140 J = N,1,-1 - TEMP = X(J) - L = 1 - J - DO 130 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(I) - 130 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - X(J) = TEMP - 140 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 160 J = N,1,-1 - TEMP = X(JX) - IX = KX - L = 1 - J - DO 150 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX - INCX - 150 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - X(JX) = TEMP - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 160 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of DTBSV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/level2_impl.h b/gtsam/3rdparty/Eigen/blas/level2_impl.h index 8cbc2f424..46a3e7005 100644 --- a/gtsam/3rdparty/Eigen/blas/level2_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level2_impl.h @@ -151,21 +151,21 @@ int EIGEN_BLAS_FUNC(trmv)(char *uplo, char *opa, char *diag, int *n, RealScalar for(int k=0; k<16; ++k) func[k] = 0; - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); + func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[TR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::product_triangular_matrix_vector::run); + func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[TR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); + func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[TR | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::product_triangular_matrix_vector::run); + func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[TR | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); + func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); init = true; } @@ -271,6 +271,7 @@ int EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealSca return 0; } +#if 0 /** TBMV performs one of the matrix-vector operations * * x := A*x, or x := A'*x, @@ -278,10 +279,56 @@ int EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealSca * where x is an n element vector and A is an n by n unit, or non-unit, * upper or lower triangular band matrix, with ( k + 1 ) diagonals. */ -// int EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *trans, char *diag, int *n, int *k, RealScalar *a, int *lda, RealScalar *x, int *incx) -// { -// return 1; -// } +int EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *opa, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx) +{ + Scalar* a = reinterpret_cast(pa); + Scalar* x = reinterpret_cast(px); + int coeff_rows = *k + 1; + + int info = 0; + if(UPLO(*uplo)==INVALID) info = 1; + else if(OP(*opa)==INVALID) info = 2; + else if(DIAG(*diag)==INVALID) info = 3; + else if(*n<0) info = 4; + else if(*k<0) info = 5; + else if(*lda::run); + func[TR | (UP << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); + + func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[TR | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); + + func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[TR | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + + func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[TR | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); + + init = true; + } + + Scalar* a = reinterpret_cast(pa); + Scalar* x = reinterpret_cast(px); + int coeff_rows = *k+1; + + int info = 0; + if(UPLO(*uplo)==INVALID) info = 1; + else if(OP(*op)==INVALID) info = 2; + else if(DIAG(*diag)==INVALID) info = 3; + else if(*n<0) info = 4; + else if(*k<0) info = 5; + else if(*lda=16 || func[code]==0) + return 0; + + func[code](*n, *k, a, *lda, actual_x); + + if(actual_x!=x) delete[] copy_back(actual_x,x,actual_n,*incx); + + return 0; +} /** DTPMV performs one of the matrix-vector operations * diff --git a/gtsam/3rdparty/Eigen/blas/level3_impl.h b/gtsam/3rdparty/Eigen/blas/level3_impl.h index 0a3aa98b8..4f4f39080 100644 --- a/gtsam/3rdparty/Eigen/blas/level3_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level3_impl.h @@ -81,7 +81,7 @@ int EIGEN_BLAS_FUNC(gemm)(char *opa, char *opb, int *m, int *n, int *k, RealScal int EIGEN_BLAS_FUNC(trsm)(char *side, char *uplo, char *opa, char *diag, int *m, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb) { // std::cerr << "in trsm " << *side << " " << *uplo << " " << *opa << " " << *diag << " " << *m << "," << *n << " " << *palpha << " " << *lda << " " << *ldb<< "\n"; - typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex); + typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, internal::level3_blocking&); static functype func[32]; static bool init = false; @@ -143,11 +143,17 @@ int EIGEN_BLAS_FUNC(trsm)(char *side, char *uplo, char *opa, char *diag, int *m, return xerbla_(SCALAR_SUFFIX_UP"TRSM ",&info,6); int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4); - + if(SIDE(*side)==LEFT) - func[code](*m, *n, a, *lda, b, *ldb); + { + internal::gemm_blocking_space blocking(*m,*n,*m); + func[code](*m, *n, a, *lda, b, *ldb, blocking); + } else - func[code](*n, *m, a, *lda, b, *ldb); + { + internal::gemm_blocking_space blocking(*m,*n,*n); + func[code](*n, *m, a, *lda, b, *ldb, blocking); + } if(alpha!=Scalar(1)) matrix(b,*m,*n,*ldb) *= alpha; diff --git a/gtsam/3rdparty/Eigen/blas/stbsv.f b/gtsam/3rdparty/Eigen/blas/stbsv.f deleted file mode 100644 index b846be85c..000000000 --- a/gtsam/3rdparty/Eigen/blas/stbsv.f +++ /dev/null @@ -1,339 +0,0 @@ - SUBROUTINE STBSV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - REAL A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* STBSV solves one of the systems of equations -* -* A*x = b, or A'*x = b, -* -* where b and x are n element vectors and A is an n by n unit, or -* non-unit, upper or lower triangular band matrix, with ( k + 1 ) -* diagonals. -* -* No test for singularity or near-singularity is included in this -* routine. Such tests must be performed before calling this routine. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the equations to be solved as -* follows: -* -* TRANS = 'N' or 'n' A*x = b. -* -* TRANS = 'T' or 't' A'*x = b. -* -* TRANS = 'C' or 'c' A'*x = b. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - REAL array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - REAL array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element right-hand side vector b. On exit, X is overwritten -* with the solution vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - REAL ZERO - PARAMETER (ZERO=0.0E+0) -* .. -* .. Local Scalars .. - REAL TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('STBSV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed by sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := inv( A )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - L = KPLUS1 - J - IF (NOUNIT) X(J) = X(J)/A(KPLUS1,J) - TEMP = X(J) - DO 10 I = J - 1,MAX(1,J-K),-1 - X(I) = X(I) - TEMP*A(L+I,J) - 10 CONTINUE - END IF - 20 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 40 J = N,1,-1 - KX = KX - INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = KPLUS1 - J - IF (NOUNIT) X(JX) = X(JX)/A(KPLUS1,J) - TEMP = X(JX) - DO 30 I = J - 1,MAX(1,J-K),-1 - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX - INCX - 30 CONTINUE - END IF - JX = JX - INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = 1,N - IF (X(J).NE.ZERO) THEN - L = 1 - J - IF (NOUNIT) X(J) = X(J)/A(1,J) - TEMP = X(J) - DO 50 I = J + 1,MIN(N,J+K) - X(I) = X(I) - TEMP*A(L+I,J) - 50 CONTINUE - END IF - 60 CONTINUE - ELSE - JX = KX - DO 80 J = 1,N - KX = KX + INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = 1 - J - IF (NOUNIT) X(JX) = X(JX)/A(1,J) - TEMP = X(JX) - DO 70 I = J + 1,MIN(N,J+K) - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX + INCX - 70 CONTINUE - END IF - JX = JX + INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := inv( A')*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 100 J = 1,N - TEMP = X(J) - L = KPLUS1 - J - DO 90 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(I) - 90 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - X(J) = TEMP - 100 CONTINUE - ELSE - JX = KX - DO 120 J = 1,N - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - DO 110 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX + INCX - 110 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - X(JX) = TEMP - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 120 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 140 J = N,1,-1 - TEMP = X(J) - L = 1 - J - DO 130 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(I) - 130 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - X(J) = TEMP - 140 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 160 J = N,1,-1 - TEMP = X(JX) - IX = KX - L = 1 - J - DO 150 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX - INCX - 150 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - X(JX) = TEMP - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 160 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of STBSV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/testing/runblastest.sh b/gtsam/3rdparty/Eigen/blas/testing/runblastest.sh index aa634a2ce..4ffaf0111 100755 --- a/gtsam/3rdparty/Eigen/blas/testing/runblastest.sh +++ b/gtsam/3rdparty/Eigen/blas/testing/runblastest.sh @@ -27,11 +27,17 @@ else if [ -f $1.summ ]; then if [ `grep "FATAL ERROR" $1.summ | wc -l` -gt 0 ]; then echo -e $red "Test $1 failed (FATAL ERROR, read the file $1.summ for details)" $black + echo -e $blue + cat .runtest.log + echo -e $black exit 1; fi if [ `grep "FAILED THE TESTS OF ERROR-EXITS" $1.summ | wc -l` -gt 0 ]; then echo -e $red "Test $1 failed (FAILED THE TESTS OF ERROR-EXITS, read the file $1.summ for details)" $black + echo -e $blue + cat .runtest.log + echo -e $black exit 1; fi fi diff --git a/gtsam/3rdparty/Eigen/blas/xerbla.cpp b/gtsam/3rdparty/Eigen/blas/xerbla.cpp index bda1d2f46..0d57710fe 100644 --- a/gtsam/3rdparty/Eigen/blas/xerbla.cpp +++ b/gtsam/3rdparty/Eigen/blas/xerbla.cpp @@ -1,12 +1,18 @@ #include +#if (defined __GNUC__) +#define EIGEN_WEAK_LINKING __attribute__ ((weak)) +#else +#define EIGEN_WEAK_LINKING +#endif + #ifdef __cplusplus extern "C" { #endif -int xerbla_(const char * msg, int *info, int) +EIGEN_WEAK_LINKING int xerbla_(const char * msg, int *info, int) { std::cerr << "Eigen BLAS ERROR #" << *info << ": " << msg << "\n"; return 0; diff --git a/gtsam/3rdparty/Eigen/blas/ztbsv.f b/gtsam/3rdparty/Eigen/blas/ztbsv.f deleted file mode 100644 index 42b234a77..000000000 --- a/gtsam/3rdparty/Eigen/blas/ztbsv.f +++ /dev/null @@ -1,370 +0,0 @@ - SUBROUTINE ZTBSV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - DOUBLE COMPLEX A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* ZTBSV solves one of the systems of equations -* -* A*x = b, or A'*x = b, or conjg( A' )*x = b, -* -* where b and x are n element vectors and A is an n by n unit, or -* non-unit, upper or lower triangular band matrix, with ( k + 1 ) -* diagonals. -* -* No test for singularity or near-singularity is included in this -* routine. Such tests must be performed before calling this routine. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the equations to be solved as -* follows: -* -* TRANS = 'N' or 'n' A*x = b. -* -* TRANS = 'T' or 't' A'*x = b. -* -* TRANS = 'C' or 'c' conjg( A' )*x = b. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - COMPLEX*16 array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX*16 array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element right-hand side vector b. On exit, X is overwritten -* with the solution vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE COMPLEX ZERO - PARAMETER (ZERO= (0.0D+0,0.0D+0)) -* .. -* .. Local Scalars .. - DOUBLE COMPLEX TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOCONJ,NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC DCONJG,MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('ZTBSV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOCONJ = LSAME(TRANS,'T') - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed by sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := inv( A )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - L = KPLUS1 - J - IF (NOUNIT) X(J) = X(J)/A(KPLUS1,J) - TEMP = X(J) - DO 10 I = J - 1,MAX(1,J-K),-1 - X(I) = X(I) - TEMP*A(L+I,J) - 10 CONTINUE - END IF - 20 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 40 J = N,1,-1 - KX = KX - INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = KPLUS1 - J - IF (NOUNIT) X(JX) = X(JX)/A(KPLUS1,J) - TEMP = X(JX) - DO 30 I = J - 1,MAX(1,J-K),-1 - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX - INCX - 30 CONTINUE - END IF - JX = JX - INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = 1,N - IF (X(J).NE.ZERO) THEN - L = 1 - J - IF (NOUNIT) X(J) = X(J)/A(1,J) - TEMP = X(J) - DO 50 I = J + 1,MIN(N,J+K) - X(I) = X(I) - TEMP*A(L+I,J) - 50 CONTINUE - END IF - 60 CONTINUE - ELSE - JX = KX - DO 80 J = 1,N - KX = KX + INCX - IF (X(JX).NE.ZERO) THEN - IX = KX - L = 1 - J - IF (NOUNIT) X(JX) = X(JX)/A(1,J) - TEMP = X(JX) - DO 70 I = J + 1,MIN(N,J+K) - X(IX) = X(IX) - TEMP*A(L+I,J) - IX = IX + INCX - 70 CONTINUE - END IF - JX = JX + INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := inv( A' )*x or x := inv( conjg( A') )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 110 J = 1,N - TEMP = X(J) - L = KPLUS1 - J - IF (NOCONJ) THEN - DO 90 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(I) - 90 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - ELSE - DO 100 I = MAX(1,J-K),J - 1 - TEMP = TEMP - DCONJG(A(L+I,J))*X(I) - 100 CONTINUE - IF (NOUNIT) TEMP = TEMP/DCONJG(A(KPLUS1,J)) - END IF - X(J) = TEMP - 110 CONTINUE - ELSE - JX = KX - DO 140 J = 1,N - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - IF (NOCONJ) THEN - DO 120 I = MAX(1,J-K),J - 1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX + INCX - 120 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(KPLUS1,J) - ELSE - DO 130 I = MAX(1,J-K),J - 1 - TEMP = TEMP - DCONJG(A(L+I,J))*X(IX) - IX = IX + INCX - 130 CONTINUE - IF (NOUNIT) TEMP = TEMP/DCONJG(A(KPLUS1,J)) - END IF - X(JX) = TEMP - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 140 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 170 J = N,1,-1 - TEMP = X(J) - L = 1 - J - IF (NOCONJ) THEN - DO 150 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(I) - 150 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - ELSE - DO 160 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - DCONJG(A(L+I,J))*X(I) - 160 CONTINUE - IF (NOUNIT) TEMP = TEMP/DCONJG(A(1,J)) - END IF - X(J) = TEMP - 170 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 200 J = N,1,-1 - TEMP = X(JX) - IX = KX - L = 1 - J - IF (NOCONJ) THEN - DO 180 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - A(L+I,J)*X(IX) - IX = IX - INCX - 180 CONTINUE - IF (NOUNIT) TEMP = TEMP/A(1,J) - ELSE - DO 190 I = MIN(N,J+K),J + 1,-1 - TEMP = TEMP - DCONJG(A(L+I,J))*X(IX) - IX = IX - INCX - 190 CONTINUE - IF (NOUNIT) TEMP = TEMP/DCONJG(A(1,J)) - END IF - X(JX) = TEMP - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 200 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of ZTBSV . -* - END diff --git a/gtsam/3rdparty/Eigen/cmake/CMakeDetermineVSServicePack.cmake b/gtsam/3rdparty/Eigen/cmake/CMakeDetermineVSServicePack.cmake new file mode 100644 index 000000000..b89462308 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/CMakeDetermineVSServicePack.cmake @@ -0,0 +1,103 @@ +# - Includes a public function for assisting users in trying to determine the +# Visual Studio service pack in use. +# +# Sets the passed in variable to one of the following values or an empty +# string if unknown. +# vc80 +# vc80sp1 +# vc90 +# vc90sp1 +# +# Usage: +# =========================== +# +# if(MSVC) +# include(CMakeDetermineVSServicePack) +# DetermineVSServicePack( my_service_pack ) +# +# if( my_service_pack ) +# message(STATUS "Detected: ${my_service_pack}") +# endif() +# endif() +# +# =========================== + +#============================================================================= +# Copyright 2009-2010 Kitware, Inc. +# Copyright 2009-2010 Philip Lowman +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of CMake, substitute the full +# License text for the above reference.) + +# [INTERNAL] +# Please do not call this function directly +function(_DetermineVSServicePackFromCompiler _OUT_VAR _cl_version) + if (${_cl_version} VERSION_EQUAL "14.00.50727.42") + set(_version "vc80") + elseif(${_cl_version} VERSION_EQUAL "14.00.50727.762") + set(_version "vc80sp1") + elseif(${_cl_version} VERSION_EQUAL "15.00.21022.08") + set(_version "vc90") + elseif(${_cl_version} VERSION_EQUAL "15.00.30729.01") + set(_version "vc90sp1") + elseif(${_cl_version} VERSION_EQUAL "16.00.30319.01") + set(_version "vc100") + else() + set(_version "") + endif() + set(${_OUT_VAR} ${_version} PARENT_SCOPE) +endfunction() + +# +# A function to call to determine the Visual Studio service pack +# in use. See documentation above. +function(DetermineVSServicePack _pack) + if(NOT DETERMINED_VS_SERVICE_PACK OR NOT ${_pack}) + if(${CMAKE_BUILD_TOOL} STREQUAL "nmake") + EXECUTE_PROCESS(COMMAND ${CMAKE_CXX_COMPILER} "/?" + ERROR_VARIABLE _output) + set(DETERMINED_VS_SERVICE_PACK ${_output}) + else() + file(WRITE "${CMAKE_BINARY_DIR}/return0.cc" + "int main() { return 0; }\n") + + try_compile(DETERMINED_VS_SERVICE_PACK + "${CMAKE_BINARY_DIR}" + "${CMAKE_BINARY_DIR}/return0.cc" + OUTPUT_VARIABLE _output + COPY_FILE "${CMAKE_BINARY_DIR}/return0.cc") + + file(REMOVE "${CMAKE_BINARY_DIR}/return0.cc") + endif() + + if(DETERMINED_VS_SERVICE_PACK AND _output) + string(REGEX MATCH "Compiler Version [0-9]+.[0-9]+.[0-9]+.[0-9]+" + _cl_version "${_output}") + if(_cl_version) + string(REGEX MATCHALL "[0-9]+" + _cl_version_list "${_cl_version}") + list(GET _cl_version_list 0 _major) + list(GET _cl_version_list 1 _minor) + list(GET _cl_version_list 2 _patch) + list(GET _cl_version_list 3 _tweak) + + set(_cl_version_string ${_major}.${_minor}.${_patch}.${_tweak}) + + # Call helper function to determine VS version + _DetermineVSServicePackFromCompiler(_sp "${_cl_version_string}") + if(_sp) + #set(${_pack} "${_sp}(${_cl_version_string})" CACHE INTERNAL + set(${_pack} "${_sp}" CACHE INTERNAL + "The Visual Studio Release with Service Pack") + endif() + endif() + endif() + endif() +endfunction() diff --git a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake new file mode 100644 index 000000000..cf8f32c01 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake @@ -0,0 +1,79 @@ +include(EigenTesting) +include(CheckCXXSourceCompiles) + +# configure the "site" and "buildname" +ei_set_sitename() + +# retrieve and store the build string +ei_set_build_string() + +add_custom_target(buildtests) +add_custom_target(check COMMAND "ctest") +add_dependencies(check buildtests) + +# check whether /bin/bash exists +find_file(EIGEN_BIN_BASH_EXISTS "/bin/bash" PATHS "/" NO_DEFAULT_PATH) + +# CMake/Ctest does not allow us to change the build command, +# so we have to workaround by directly editing the generated DartConfiguration.tcl file +# save CMAKE_MAKE_PROGRAM +set(CMAKE_MAKE_PROGRAM_SAVE ${CMAKE_MAKE_PROGRAM}) +# and set a fake one +set(CMAKE_MAKE_PROGRAM "@EIGEN_MAKECOMMAND_PLACEHOLDER@") + +# This call activates testing and generates the DartConfiguration.tcl +include(CTest) + +# overwrite default DartConfiguration.tcl +# The worarounds are different for each version of the MSVC IDE +if(MSVC_IDE) + if(MSVC_VERSION EQUAL 1600) # MSVC 2010 + set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests.vcxproj /p:Configuration=\${CTEST_CONFIGURATION_TYPE} \n# ") + else() # MSVC 2008 (TODO check MSVC 2005) + set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} Eigen.sln /build \"Release\" /project buildtests \n# ") + endif() +else() + # for make and nmake + set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests") +endif() + +# copy ctest properties, which currently +# o raise the warning levels +configure_file(${CMAKE_BINARY_DIR}/DartConfiguration.tcl ${CMAKE_BINARY_DIR}/DartConfiguration.tcl) + +# restore default CMAKE_MAKE_PROGRAM +set(CMAKE_MAKE_PROGRAM ${CMAKE_MAKE_PROGRAM_SAVE}) +# un-set temporary variables so that it is like they never existed. +# CMake 2.6.3 introduces the more logical unset() syntax for this. +set(CMAKE_MAKE_PROGRAM_SAVE) +set(EIGEN_MAKECOMMAND_PLACEHOLDER) + +configure_file(${CMAKE_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake) + +# some documentation of this function would be nice +ei_init_testing() + +# configure Eigen related testing options +option(EIGEN_NO_ASSERTION_CHECKING "Disable checking of assertions using exceptions" OFF) +option(EIGEN_DEBUG_ASSERTS "Enable advanced debuging of assertions" OFF) + +if(CMAKE_COMPILER_IS_GNUCXX) + option(EIGEN_COVERAGE_TESTING "Enable/disable gcov" OFF) + if(EIGEN_COVERAGE_TESTING) + set(COVERAGE_FLAGS "-fprofile-arcs -ftest-coverage") + set(CTEST_CUSTOM_COVERAGE_EXCLUDE "/test/") + else(EIGEN_COVERAGE_TESTING) + set(COVERAGE_FLAGS "") + endif(EIGEN_COVERAGE_TESTING) + if(EIGEN_TEST_C++0x) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++0x") + endif(EIGEN_TEST_C++0x) + if(CMAKE_SYSTEM_NAME MATCHES Linux) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS} -g2") + set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "${CMAKE_CXX_FLAGS_RELWITHDEBINFO} ${COVERAGE_FLAGS} -O2 -g2") + set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${COVERAGE_FLAGS} -fno-inline-functions") + set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${COVERAGE_FLAGS} -O0 -g3") + endif(CMAKE_SYSTEM_NAME MATCHES Linux) +elseif(MSVC) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /D_CRT_SECURE_NO_WARNINGS /D_SCL_SECURE_NO_WARNINGS") +endif(CMAKE_COMPILER_IS_GNUCXX) diff --git a/gtsam/3rdparty/Eigen/cmake/EigenDetermineOSVersion.cmake b/gtsam/3rdparty/Eigen/cmake/EigenDetermineOSVersion.cmake new file mode 100644 index 000000000..3c48d4c37 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/EigenDetermineOSVersion.cmake @@ -0,0 +1,46 @@ +# The utility function DetermineOSVersion aims at providing an +# improved version of the CMake variable ${CMAKE_SYSTEM} on Windows +# machines. +# +# Usage: +# include(EigenDetermineOSVersion) +# DetermineOSVersion(OS_VERSION) +# message("OS: ${OS_VERSION}") + +# - A little helper variable which should not be directly called +function(DetermineShortWindowsName WIN_VERSION win_num_version) + if (${win_num_version} VERSION_EQUAL "6.1") + set(_version "win7") + elseif(${win_num_version} VERSION_EQUAL "6.0") + set(_version "winVista") + elseif(${win_num_version} VERSION_EQUAL "5.2") + set(_version "winXpProf") + elseif(${win_num_version} VERSION_EQUAL "5.1") + set(_version "winXp") + elseif(${win_num_version} VERSION_EQUAL "5.0") + set(_version "win2000Prof") + else() + set(_version "unknownWin") + endif() + set(${WIN_VERSION} ${_version} PARENT_SCOPE) +endfunction() + +function(DetermineOSVersion OS_VERSION) + if (WIN32) + file (TO_NATIVE_PATH "$ENV{COMSPEC}" SHELL) + exec_program( ${SHELL} ARGS "/c" "ver" OUTPUT_VARIABLE ver_output) + + string(REGEX MATCHALL "[0-9]+" + ver_list "${ver_output}") + list(GET ver_list 0 _major) + list(GET ver_list 1 _minor) + + set(win_num_version ${_major}.${_minor}) + DetermineShortWindowsName(win_version "${win_num_version}") + if(win_version) + set(${OS_VERSION} ${win_version} PARENT_SCOPE) + endif() + else() + set(${OS_VERSION} ${CMAKE_SYSTEM} PARENT_SCOPE) + endif() +endfunction() diff --git a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake index 4c8039315..266043974 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake @@ -1,11 +1,11 @@ -option(EIGEN_NO_ASSERTION_CHECKING "Disable checking of assertions using exceptions" OFF) -option(EIGEN_DEBUG_ASSERTS "Enable advanced debuging of assertions" OFF) - -include(CheckCXXSourceCompiles) macro(ei_add_property prop value) - get_property(previous GLOBAL PROPERTY ${prop}) - set_property(GLOBAL PROPERTY ${prop} "${previous} ${value}") + get_property(previous GLOBAL PROPERTY ${prop}) + if ((NOT previous) OR (previous STREQUAL "")) + set_property(GLOBAL PROPERTY ${prop} "${value}") + else() + set_property(GLOBAL PROPERTY ${prop} "${previous} ${value}") + endif() endmacro(ei_add_property) #internal. See documentation of ei_add_test for details. @@ -27,6 +27,8 @@ macro(ei_add_test_internal testname testname_with_suffix) ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_DEBUG_ASSERTS=1") endif(EIGEN_DEBUG_ASSERTS) endif(EIGEN_NO_ASSERTION_CHECKING) + + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_MAX_SIZE=${EIGEN_TEST_MAX_SIZE}") ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_FUNC=${testname}") @@ -38,6 +40,10 @@ macro(ei_add_test_internal testname testname_with_suffix) if(${ARGC} GREATER 2) ei_add_target_property(${targetname} COMPILE_FLAGS "${ARGV2}") endif(${ARGC} GREATER 2) + + if(EIGEN_TEST_CUSTOM_CXX_FLAGS) + ei_add_target_property(${targetname} COMPILE_FLAGS "${EIGEN_TEST_CUSTOM_CXX_FLAGS}") + endif() if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO) target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) @@ -45,6 +51,9 @@ macro(ei_add_test_internal testname testname_with_suffix) if(EXTERNAL_LIBS) target_link_libraries(${targetname} ${EXTERNAL_LIBS}) endif() + if(EIGEN_TEST_CUSTOM_LINKER_FLAGS) + target_link_libraries(${targetname} ${EIGEN_TEST_CUSTOM_LINKER_FLAGS}) + endif() if(${ARGC} GREATER 3) set(libs_to_link ${ARGV3}) @@ -59,15 +68,11 @@ macro(ei_add_test_internal testname testname_with_suffix) endif() endif() - if(WIN32) - if(CYGWIN) - add_test(${testname_with_suffix} "${Eigen_SOURCE_DIR}/test/runtest.sh" "${testname_with_suffix}") - else(CYGWIN) - add_test(${testname_with_suffix} "${targetname}") - endif(CYGWIN) - else(WIN32) + if(EIGEN_BIN_BASH_EXISTS) add_test(${testname_with_suffix} "${Eigen_SOURCE_DIR}/test/runtest.sh" "${testname_with_suffix}") - endif(WIN32) + else() + add_test(${testname_with_suffix} "${targetname}") + endif() endmacro(ei_add_test_internal) @@ -120,9 +125,9 @@ macro(ei_add_test testname) file(READ "${testname}.cpp" test_source) set(parts 0) - string(REGEX MATCHALL "CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+" + string(REGEX MATCHALL "CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+|EIGEN_SUFFIXES(;[0-9]+)+" occurences "${test_source}") - string(REGEX REPLACE "CALL_SUBTEST_|EIGEN_TEST_PART_" "" suffixes "${occurences}") + string(REGEX REPLACE "CALL_SUBTEST_|EIGEN_TEST_PART_|EIGEN_SUFFIXES" "" suffixes "${occurences}") list(REMOVE_DUPLICATES suffixes) if(EIGEN_SPLIT_LARGE_TESTS AND suffixes) add_custom_target(${testname}) @@ -181,12 +186,13 @@ endmacro(ei_add_failtest) # print a summary of the different options macro(ei_testing_print_summary) - message(STATUS "************************************************************") message(STATUS "*** Eigen's unit tests configuration summary ***") message(STATUS "************************************************************") message(STATUS "") message(STATUS "Build type: ${CMAKE_BUILD_TYPE}") + message(STATUS "Build site: ${SITE}") + message(STATUS "Build string: ${BUILDNAME}") get_property(EIGEN_TESTING_SUMMARY GLOBAL PROPERTY EIGEN_TESTING_SUMMARY) get_property(EIGEN_TESTED_BACKENDS GLOBAL PROPERTY EIGEN_TESTED_BACKENDS) get_property(EIGEN_MISSING_BACKENDS GLOBAL PROPERTY EIGEN_MISSING_BACKENDS) @@ -204,6 +210,8 @@ macro(ei_testing_print_summary) elseif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION) message(STATUS "Explicit vectorization disabled (alignment kept enabled)") else() + + message(STATUS "Maximal matrix/vector size: ${EIGEN_TEST_MAX_SIZE}") if(EIGEN_TEST_SSE2) message(STATUS "SSE2: ON") @@ -252,7 +260,6 @@ macro(ei_testing_print_summary) message(STATUS "\n${EIGEN_TESTING_SUMMARY}") message(STATUS "************************************************************") - endmacro(ei_testing_print_summary) macro(ei_init_testing) @@ -271,25 +278,200 @@ macro(ei_init_testing) set_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT "0") set_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT "0") + + # uncomment anytime you change the ei_get_compilerver_from_cxx_version_string macro + # ei_test_get_compilerver_from_cxx_version_string() endmacro(ei_init_testing) -if(CMAKE_COMPILER_IS_GNUCXX) - option(EIGEN_COVERAGE_TESTING "Enable/disable gcov" OFF) - if(EIGEN_COVERAGE_TESTING) - set(COVERAGE_FLAGS "-fprofile-arcs -ftest-coverage") - set(CTEST_CUSTOM_COVERAGE_EXCLUDE "/test/") - else(EIGEN_COVERAGE_TESTING) - set(COVERAGE_FLAGS "") - endif(EIGEN_COVERAGE_TESTING) - if(EIGEN_TEST_C++0x) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++0x") - endif(EIGEN_TEST_C++0x) - if(CMAKE_SYSTEM_NAME MATCHES Linux) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS} -g2") - set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "${CMAKE_CXX_FLAGS_RELWITHDEBINFO} ${COVERAGE_FLAGS} -O2 -g2") - set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${COVERAGE_FLAGS} -fno-inline-functions") - set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${COVERAGE_FLAGS} -O0 -g3") - endif(CMAKE_SYSTEM_NAME MATCHES Linux) -elseif(MSVC) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /D_CRT_SECURE_NO_WARNINGS /D_SCL_SECURE_NO_WARNINGS") -endif(CMAKE_COMPILER_IS_GNUCXX) +macro(ei_set_sitename) + # if the sitename is not yet set, try to set it + if(NOT ${SITE} OR ${SITE} STREQUAL "") + set(eigen_computername $ENV{COMPUTERNAME}) + set(eigen_hostname $ENV{HOSTNAME}) + if(eigen_hostname) + set(SITE ${eigen_hostname}) + elseif(eigen_computername) + set(SITE ${eigen_computername}) + endif() + endif() + # in case it is already set, enforce lower case + if(SITE) + string(TOLOWER ${SITE} SITE) + endif() +endmacro(ei_set_sitename) + +macro(ei_get_compilerver VAR) + if(MSVC) + # on windows system, we use a modified CMake script + include(CMakeDetermineVSServicePack) + DetermineVSServicePack( my_service_pack ) + + if( my_service_pack ) + set(${VAR} ${my_service_pack}) + else() + set(${VAR} "na") + endif() + else() + # on all other system we rely on ${CMAKE_CXX_COMPILER} + # supporting a "--version" flag + execute_process(COMMAND ${CMAKE_CXX_COMPILER} --version + COMMAND head -n 1 + OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE) + + ei_get_compilerver_from_cxx_version_string(${eigen_cxx_compiler_version_string} CNAME CVER) + + set(${VAR} "${CNAME}-${CVER}") + endif() +endmacro(ei_get_compilerver) + +# Extract compiler name and version from a raw version string +# WARNING: if you edit thid macro, then please test it by uncommenting +# the testing macro call in ei_init_testing() of the EigenTesting.cmake file. +# See also the ei_test_get_compilerver_from_cxx_version_string macro at the end of the file +macro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER) + # extract possible compiler names + string(REGEX MATCH "g\\+\\+" ei_has_gpp ${VERSTRING}) + string(REGEX MATCH "llvm|LLVM" ei_has_llvm ${VERSTRING}) + string(REGEX MATCH "gcc|GCC" ei_has_gcc ${VERSTRING}) + string(REGEX MATCH "icpc|ICC" ei_has_icpc ${VERSTRING}) + string(REGEX MATCH "clang|CLANG" ei_has_clang ${VERSTRING}) + + # combine them + if((ei_has_llvm) AND (ei_has_gpp OR ei_has_gcc)) + set(${CNAME} "llvm-g++") + elseif((ei_has_llvm) AND (ei_has_clang)) + set(${CNAME} "llvm-clang++") + elseif(ei_has_icpc) + set(${CNAME} "icpc") + elseif(ei_has_gpp OR ei_has_gcc) + set(${CNAME} "g++") + else() + set(${CNAME} "_") + endif() + + # extract possible version numbers + # first try to extract 3 isolated numbers: + string(REGEX MATCH " [0-9]+\\.[0-9]+\\.[0-9]+" eicver ${VERSTRING}) + if(NOT eicver) + # try to extract 2 isolated ones: + string(REGEX MATCH " [0-9]+\\.[0-9]+" eicver ${VERSTRING}) + if(NOT eicver) + # try to extract 3: + string(REGEX MATCH "[^0-9][0-9]+\\.[0-9]+\\.[0-9]+" eicver ${VERSTRING}) + if(NOT eicver) + # try to extract 2: + string(REGEX MATCH "[^0-9][0-9]+\\.[0-9]+" eicver ${VERSTRING}) + else() + set(eicver " _") + endif() + endif() + endif() + + string(REGEX REPLACE ".(.*)" "\\1" ${CVER} ${eicver}) + +endmacro(ei_get_compilerver_from_cxx_version_string) + +macro(ei_get_cxxflags VAR) + set(${VAR} "") + ei_is_64bit_env(IS_64BIT_ENV) + if(EIGEN_TEST_NEON) + set(${VAR} NEON) + elseif(EIGEN_TEST_ALTIVEC) + set(${VAR} ALVEC) + elseif(EIGEN_TEST_SSE4_2) + set(${VAR} SSE42) + elseif(EIGEN_TEST_SSE4_1) + set(${VAR} SSE41) + elseif(EIGEN_TEST_SSSE3) + set(${VAR} SSSE3) + elseif(EIGEN_TEST_SSE3) + set(${VAR} SSE3) + elseif(EIGEN_TEST_SSE2 OR IS_64BIT_ENV) + set(${VAR} SSE2) + endif() + + if(EIGEN_TEST_OPENMP) + if (${VAR} STREQUAL "") + set(${VAR} OMP) + else() + set(${VAR} ${${VAR}}-OMP) + endif() + endif() + + if(EIGEN_DEFAULT_TO_ROW_MAJOR) + if (${VAR} STREQUAL "") + set(${VAR} ROW) + else() + set(${VAR} ${${VAR}}-ROWMAJ) + endif() + endif() +endmacro(ei_get_cxxflags) + +macro(ei_set_build_string) + ei_get_compilerver(LOCAL_COMPILER_VERSION) + ei_get_cxxflags(LOCAL_COMPILER_FLAGS) + + include(EigenDetermineOSVersion) + DetermineOSVersion(OS_VERSION) + + set(TMP_BUILD_STRING ${OS_VERSION}-${LOCAL_COMPILER_VERSION}) + + if (NOT ${LOCAL_COMPILER_FLAGS} STREQUAL "") + set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${LOCAL_COMPILER_FLAGS}) + endif() + + ei_is_64bit_env(IS_64BIT_ENV) + if(NOT IS_64BIT_ENV) + set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-32bit) + else() + set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-64bit) + endif() + + string(TOLOWER ${TMP_BUILD_STRING} BUILDNAME) +endmacro(ei_set_build_string) + +macro(ei_is_64bit_env VAR) + + file(WRITE "${CMAKE_CURRENT_BINARY_DIR}/is64.cpp" + "int main() { return (sizeof(int*) == 8 ? 1 : 0); } + ") + try_run(run_res compile_res + ${CMAKE_CURRENT_BINARY_DIR} "${CMAKE_CURRENT_BINARY_DIR}/is64.cpp" + RUN_OUTPUT_VARIABLE run_output) + + if(compile_res AND run_res) + set(${VAR} ${run_res}) + elseif(CMAKE_CL_64) + set(${VAR} 1) + elseif("$ENV{Platform}" STREQUAL "X64") # nmake 64 bit + set(${VAR} 1) + endif() +endmacro(ei_is_64bit_env) + + +# helper macro for testing ei_get_compilerver_from_cxx_version_string +# STR: raw version string +# REFNAME: expected compiler name +# REFVER: expected compiler version +macro(ei_test1_get_compilerver_from_cxx_version_string STR REFNAME REFVER) + ei_get_compilerver_from_cxx_version_string(${STR} CNAME CVER) + if((NOT ${REFNAME} STREQUAL ${CNAME}) OR (NOT ${REFVER} STREQUAL ${CVER})) + message("STATUS ei_get_compilerver_from_cxx_version_string error:") + message("Expected \"${REFNAME}-${REFVER}\", got \"${CNAME}-${CVER}\"") + endif() +endmacro(ei_test1_get_compilerver_from_cxx_version_string) + +# macro for testing ei_get_compilerver_from_cxx_version_string +# feel free to add more version strings +macro(ei_test_get_compilerver_from_cxx_version_string) + ei_test1_get_compilerver_from_cxx_version_string("g++ (SUSE Linux) 4.5.3 20110428 [gcc-4_5-branch revision 173117]" "g++" "4.5.3") + ei_test1_get_compilerver_from_cxx_version_string("c++ (GCC) 4.5.1 20100924 (Red Hat 4.5.1-4)" "g++" "4.5.1") + ei_test1_get_compilerver_from_cxx_version_string("icpc (ICC) 11.0 20081105" "icpc" "11.0") + ei_test1_get_compilerver_from_cxx_version_string("g++-3.4 (GCC) 3.4.6" "g++" "3.4.6") + ei_test1_get_compilerver_from_cxx_version_string("SUSE Linux clang version 3.0 (branches/release_30 145598) (based on LLVM 3.0)" "llvm-clang++" "3.0") + ei_test1_get_compilerver_from_cxx_version_string("icpc (ICC) 12.0.5 20110719" "icpc" "12.0.5") + ei_test1_get_compilerver_from_cxx_version_string("Apple clang version 2.1 (tags/Apple/clang-163.7.1) (based on LLVM 3.0svn)" "llvm-clang++" "2.1") + ei_test1_get_compilerver_from_cxx_version_string("i686-apple-darwin11-llvm-g++-4.2 (GCC) 4.2.1 (Based on Apple Inc. build 5658) (LLVM build 2335.15.00)" "llvm-g++" "4.2.1") + ei_test1_get_compilerver_from_cxx_version_string("g++-mp-4.4 (GCC) 4.4.6" "g++" "4.4.6") + ei_test1_get_compilerver_from_cxx_version_string("g++-mp-4.4 (GCC) 2011" "g++" "4.4") +endmacro(ei_test_get_compilerver_from_cxx_version_string) diff --git a/gtsam/3rdparty/Eigen/cmake/FindCholmod.cmake b/gtsam/3rdparty/Eigen/cmake/FindCholmod.cmake index a5e132b64..9095bea31 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindCholmod.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindCholmod.cmake @@ -13,6 +13,7 @@ find_path(CHOLMOD_INCLUDES ${INCLUDE_INSTALL_DIR} PATH_SUFFIXES suitesparse + ufsparse ) find_library(CHOLMOD_LIBRARIES cholmod PATHS $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR}) diff --git a/gtsam/3rdparty/Eigen/cmake/FindEigen2.cmake b/gtsam/3rdparty/Eigen/cmake/FindEigen2.cmake index da95bb0f5..a834b8872 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindEigen2.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindEigen2.cmake @@ -39,11 +39,11 @@ macro(_eigen2_check_version) set(EIGEN2_MINOR_VERSION "${CMAKE_MATCH_1}") set(EIGEN2_VERSION ${EIGEN2_WORLD_VERSION}.${EIGEN2_MAJOR_VERSION}.${EIGEN2_MINOR_VERSION}) - if(${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION}) + if((${EIGEN2_WORLD_VERSION} NOTEQUAL 2) OR (${EIGEN2_MAJOR_VERSION} GREATER 10) OR (${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION})) set(EIGEN2_VERSION_OK FALSE) - else(${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION}) + else() set(EIGEN2_VERSION_OK TRUE) - endif(${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION}) + endif() if(NOT EIGEN2_VERSION_OK) diff --git a/gtsam/3rdparty/Eigen/cmake/FindFFTW.cmake b/gtsam/3rdparty/Eigen/cmake/FindFFTW.cmake index 58b10ea11..a9e9925e7 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindFFTW.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindFFTW.cmake @@ -1,31 +1,119 @@ +# - Find the FFTW library +# +# Usage: +# find_package(FFTW [REQUIRED] [QUIET] ) +# +# It sets the following variables: +# FFTW_FOUND ... true if fftw is found on the system +# FFTW_LIBRARIES ... full path to fftw library +# FFTW_INCLUDES ... fftw include directory +# +# The following variables will be checked by the function +# FFTW_USE_STATIC_LIBS ... if true, only static libraries are found +# FFTW_ROOT ... if set, the libraries are exclusively searched +# under this path +# FFTW_LIBRARY ... fftw library to use +# FFTW_INCLUDE_DIR ... fftw include directory +# -if (FFTW_INCLUDES AND FFTW_LIBRARIES) - set(FFTW_FIND_QUIETLY TRUE) -endif (FFTW_INCLUDES AND FFTW_LIBRARIES) - -find_path(FFTW_INCLUDES - NAMES - fftw3.h - PATHS - $ENV{FFTWDIR} - ${INCLUDE_INSTALL_DIR} -) - -find_library(FFTWF_LIB NAMES fftw3f PATHS $ENV{FFTWDIR} ${LIB_INSTALL_DIR}) -find_library(FFTW_LIB NAMES fftw3 PATHS $ENV{FFTWDIR} ${LIB_INSTALL_DIR}) -set(FFTW_LIBRARIES "${FFTWF_LIB} ${FFTW_LIB}" ) - -find_library(FFTWL_LIB NAMES fftw3l PATHS $ENV{FFTWDIR} ${LIB_INSTALL_DIR}) - -if(FFTWL_LIB) -set(FFTW_LIBRARIES "${FFTW_LIBRARIES} ${FFTWL_LIB}") +#If environment variable FFTWDIR is specified, it has same effect as FFTW_ROOT +if( NOT FFTW_ROOT AND ENV{FFTWDIR} ) + set( FFTW_ROOT $ENV{FFTWDIR} ) endif() +# Check if we can use PkgConfig +find_package(PkgConfig) -message(STATUS "FFTW ${FFTW_LIBRARIES}" ) +#Determine from PKG +if( PKG_CONFIG_FOUND AND NOT FFTW_ROOT ) + pkg_check_modules( PKG_FFTW QUIET "fftw3" ) +endif() + +#Check whether to search static or dynamic libs +set( CMAKE_FIND_LIBRARY_SUFFIXES_SAV ${CMAKE_FIND_LIBRARY_SUFFIXES} ) + +if( ${FFTW_USE_STATIC_LIBS} ) + set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_STATIC_LIBRARY_SUFFIX} ) +else() + set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_SHARED_LIBRARY_SUFFIX} ) +endif() + +if( FFTW_ROOT ) + + #find libs + find_library( + FFTW_LIB + NAMES "fftw3" + PATHS ${FFTW_ROOT} + PATH_SUFFIXES "lib" "lib64" + NO_DEFAULT_PATH + ) + + find_library( + FFTWF_LIB + NAMES "fftw3f" + PATHS ${FFTW_ROOT} + PATH_SUFFIXES "lib" "lib64" + NO_DEFAULT_PATH + ) + + find_library( + FFTWL_LIB + NAMES "fftw3l" + PATHS ${FFTW_ROOT} + PATH_SUFFIXES "lib" "lib64" + NO_DEFAULT_PATH + ) + + #find includes + find_path( + FFTW_INCLUDES + NAMES "fftw3.h" + PATHS ${FFTW_ROOT} + PATH_SUFFIXES "include" + NO_DEFAULT_PATH + ) + +else() + + find_library( + FFTW_LIB + NAMES "fftw3" + PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR} + ) + + find_library( + FFTWF_LIB + NAMES "fftw3f" + PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR} + ) + + + find_library( + FFTWL_LIB + NAMES "fftw3l" + PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR} + ) + + find_path( + FFTW_INCLUDES + NAMES "fftw3.h" + PATHS ${PKG_FFTW_INCLUDE_DIRS} ${INCLUDE_INSTALL_DIR} + ) + +endif( FFTW_ROOT ) + +set(FFTW_LIBRARIES ${FFTW_LIB} ${FFTWF_LIB}) + +if(FFTWL_LIB) + set(FFTW_LIBRARIES ${FFTW_LIBRARIES} ${FFTWL_LIB}) +endif() + +set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES_SAV} ) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(FFTW DEFAULT_MSG FFTW_INCLUDES FFTW_LIBRARIES) mark_as_advanced(FFTW_INCLUDES FFTW_LIBRARIES) + diff --git a/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake new file mode 100644 index 000000000..e4d6ef258 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake @@ -0,0 +1,24 @@ +# Pastix requires METIS or METIS (partitioning and reordering tools) + +if (METIS_INCLUDES AND METIS_LIBRARIES) + set(METIS_FIND_QUIETLY TRUE) +endif (METIS_INCLUDES AND METIS_LIBRARIES) + +find_path(METIS_INCLUDES + NAMES + metis.h + PATHS + $ENV{METISDIR} + ${INCLUDE_INSTALL_DIR} + PATH_SUFFIXES + metis +) + + +find_library(METIS_LIBRARIES metis PATHS $ENV{METISDIR} ${LIB_INSTALL_DIR}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(METIS DEFAULT_MSG + METIS_INCLUDES METIS_LIBRARIES) + +mark_as_advanced(METIS_INCLUDES METIS_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake b/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake new file mode 100644 index 000000000..e2e6c810d --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake @@ -0,0 +1,25 @@ +# Pastix lib requires linking to a blas library. +# It is up to the user of this module to find a BLAS and link to it. +# Pastix requires SCOTCH or METIS (partitioning and reordering tools) as well + +if (PASTIX_INCLUDES AND PASTIX_LIBRARIES) + set(PASTIX_FIND_QUIETLY TRUE) +endif (PASTIX_INCLUDES AND PASTIX_LIBRARIES) + +find_path(PASTIX_INCLUDES + NAMES + pastix_nompi.h + PATHS + $ENV{PASTIXDIR} + ${INCLUDE_INSTALL_DIR} +) + +find_library(PASTIX_LIBRARIES pastix PATHS $ENV{PASTIXDIR} ${LIB_INSTALL_DIR}) + + + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(PASTIX DEFAULT_MSG + PASTIX_INCLUDES PASTIX_LIBRARIES) + +mark_as_advanced(PASTIX_INCLUDES PASTIX_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake b/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake new file mode 100644 index 000000000..530340b16 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake @@ -0,0 +1,24 @@ +# Pastix requires SCOTCH or METIS (partitioning and reordering tools) + +if (SCOTCH_INCLUDES AND SCOTCH_LIBRARIES) + set(SCOTCH_FIND_QUIETLY TRUE) +endif (SCOTCH_INCLUDES AND SCOTCH_LIBRARIES) + +find_path(SCOTCH_INCLUDES + NAMES + scotch.h + PATHS + $ENV{SCOTCHDIR} + ${INCLUDE_INSTALL_DIR} + PATH_SUFFIXES + scotch +) + + +find_library(SCOTCH_LIBRARIES scotch PATHS $ENV{SCOTCHDIR} ${LIB_INSTALL_DIR}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(SCOTCH DEFAULT_MSG + SCOTCH_INCLUDES SCOTCH_LIBRARIES) + +mark_as_advanced(SCOTCH_INCLUDES SCOTCH_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake b/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake index 4b6f24f93..d42c3c4a2 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake @@ -13,6 +13,7 @@ find_path(UMFPACK_INCLUDES ${INCLUDE_INSTALL_DIR} PATH_SUFFIXES suitesparse + ufsparse ) find_library(UMFPACK_LIBRARIES umfpack PATHS $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) diff --git a/gtsam/3rdparty/Eigen/cmake/language_support.cmake b/gtsam/3rdparty/Eigen/cmake/language_support.cmake new file mode 100644 index 000000000..3414e6ea6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/language_support.cmake @@ -0,0 +1,64 @@ +# cmake/modules/language_support.cmake +# +# Temporary additional general language support is contained within this +# file. + +# This additional function definition is needed to provide a workaround for +# CMake bug 9220. + +# On debian testing (cmake 2.6.2), I get return code zero when calling +# cmake the first time, but cmake crashes when running a second time +# as follows: +# +# -- The Fortran compiler identification is unknown +# CMake Error at /usr/share/cmake-2.6/Modules/CMakeFortranInformation.cmake:7 (GET_FILENAME_COMPONENT): +# get_filename_component called with incorrect number of arguments +# Call Stack (most recent call first): +# CMakeLists.txt:3 (enable_language) +# +# My workaround is to invoke cmake twice. If both return codes are zero, +# it is safe to invoke ENABLE_LANGUAGE(Fortran OPTIONAL) + +function(workaround_9220 language language_works) + #message("DEBUG: language = ${language}") + set(text + "project(test NONE) + cmake_minimum_required(VERSION 2.6.0) + enable_language(${language} OPTIONAL) + ") + file(REMOVE_RECURSE ${CMAKE_BINARY_DIR}/language_tests/${language}) + file(MAKE_DIRECTORY ${CMAKE_BINARY_DIR}/language_tests/${language}) + file(WRITE ${CMAKE_BINARY_DIR}/language_tests/${language}/CMakeLists.txt + ${text}) + execute_process( + COMMAND ${CMAKE_COMMAND} . + WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/language_tests/${language} + RESULT_VARIABLE return_code + OUTPUT_QUIET + ERROR_QUIET + ) + + if(return_code EQUAL 0) + # Second run + execute_process ( + COMMAND ${CMAKE_COMMAND} . + WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/language_tests/${language} + RESULT_VARIABLE return_code + OUTPUT_QUIET + ERROR_QUIET + ) + if(return_code EQUAL 0) + set(${language_works} ON PARENT_SCOPE) + else(return_code EQUAL 0) + set(${language_works} OFF PARENT_SCOPE) + endif(return_code EQUAL 0) + else(return_code EQUAL 0) + set(${language_works} OFF PARENT_SCOPE) + endif(return_code EQUAL 0) +endfunction(workaround_9220) + +# Temporary tests of the above function. +#workaround_9220(CXX CXX_language_works) +#message("CXX_language_works = ${CXX_language_works}") +#workaround_9220(CXXp CXXp_language_works) +#message("CXXp_language_works = ${CXXp_language_works}") diff --git a/gtsam/3rdparty/Eigen/debug/gdb/printers.py b/gtsam/3rdparty/Eigen/debug/gdb/printers.py index 02823b8a2..8dab8fffb 100644 --- a/gtsam/3rdparty/Eigen/debug/gdb/printers.py +++ b/gtsam/3rdparty/Eigen/debug/gdb/printers.py @@ -31,9 +31,15 @@ # To use it: # -# * create a directory and put the file as well as an empty __init__.py in that directory +# * Create a directory and put the file as well as an empty __init__.py in +# that directory. # * Create a ~/.gdbinit file, that contains the following: - +# python +# import sys +# sys.path.insert(0, '/path/to/eigen/printer/directory') +# from printers import register_eigen_printers +# register_eigen_printers (None) +# end import gdb import re @@ -41,10 +47,14 @@ import itertools class EigenMatrixPrinter: - "Print Eigen Matrix of some kind" + "Print Eigen Matrix or Array of some kind" - def __init__(self, val): + def __init__(self, variety, val): "Extract all the necessary information" + + # Save the variety (presumably "Matrix" or "Array") for later usage + self.variety = variety + # The gdb extension does not support value template arguments - need to extract them by hand type = val.type if type.code == gdb.TYPE_CODE_REF: @@ -55,7 +65,7 @@ class EigenMatrixPrinter: m = regex.findall(tag)[0][1:-1] template_params = m.split(',') template_params = map(lambda x:x.replace(" ", ""), template_params) - + if template_params[1] == '-0x00000000000000001' or template_params[1] == '-0x000000001': self.rows = val['m_storage']['m_rows'] else: @@ -71,9 +81,9 @@ class EigenMatrixPrinter: self.options = template_params[3]; self.rowMajor = (int(self.options) & 0x1) - + self.innerType = self.type.template_argument(0) - + self.val = val # Fixed size matrices have a struct as their storage, so we need to walk through this @@ -90,12 +100,12 @@ class EigenMatrixPrinter: self.currentRow = 0 self.currentCol = 0 self.rowMajor = rowMajor - + def __iter__ (self): return self - + def next(self): - + row = self.currentRow col = self.currentCol if self.rowMajor == 0: @@ -115,7 +125,7 @@ class EigenMatrixPrinter: self.currentCol = 0 self.currentRow = self.currentRow + 1 - + item = self.dataPtr.dereference() self.dataPtr = self.dataPtr + 1 if (self.cols == 1): #if it's a column vector @@ -123,17 +133,17 @@ class EigenMatrixPrinter: elif (self.rows == 1): #if it's a row vector return ('[%d]' % (col,), item) return ('[%d,%d]' % (row, col), item) - + def children(self): return self._iterator(self.rows, self.cols, self.data, self.rowMajor) - + def to_string(self): - return "Eigen::Matrix<%s,%d,%d,%s> (data ptr: %s)" % (self.innerType, self.rows, self.cols, "RowMajor" if self.rowMajor else "ColMajor", self.data) + return "Eigen::%s<%s,%d,%d,%s> (data ptr: %s)" % (self.variety, self.innerType, self.rows, self.cols, "RowMajor" if self.rowMajor else "ColMajor", self.data) class EigenQuaternionPrinter: "Print an Eigen Quaternion" - + def __init__(self, val): "Extract all the necessary information" # The gdb extension does not support value template arguments - need to extract them by hand @@ -153,18 +163,18 @@ class EigenQuaternionPrinter: self.dataPtr = dataPtr self.currentElement = 0 self.elementNames = ['x', 'y', 'z', 'w'] - + def __iter__ (self): return self - + def next(self): element = self.currentElement - + if self.currentElement >= 4: #there are 4 elements in a quanternion raise StopIteration self.currentElement = self.currentElement + 1 - + item = self.dataPtr.dereference() self.dataPtr = self.dataPtr + 1 return ('[%s]' % (self.elementNames[element],), item) @@ -172,13 +182,14 @@ class EigenQuaternionPrinter: def children(self): return self._iterator(self.data) - + def to_string(self): return "Eigen::Quaternion<%s> (data ptr: %s)" % (self.innerType, self.data) def build_eigen_dictionary (): pretty_printers_dict[re.compile('^Eigen::Quaternion<.*>$')] = lambda val: EigenQuaternionPrinter(val) - pretty_printers_dict[re.compile('^Eigen::Matrix<.*>$')] = lambda val: EigenMatrixPrinter(val) + pretty_printers_dict[re.compile('^Eigen::Matrix<.*>$')] = lambda val: EigenMatrixPrinter("Matrix", val) + pretty_printers_dict[re.compile('^Eigen::Array<.*>$')] = lambda val: EigenMatrixPrinter("Array", val) def register_eigen_printers(obj): "Register eigen pretty-printers with objfile Obj" @@ -189,22 +200,22 @@ def register_eigen_printers(obj): def lookup_function(val): "Look-up and return a pretty-printer that can print va." - + type = val.type - + if type.code == gdb.TYPE_CODE_REF: type = type.target() type = type.unqualified().strip_typedefs() - + typename = type.tag if typename == None: return None - + for function in pretty_printers_dict: if function.search(typename): return pretty_printers_dict[function](val) - + return None pretty_printers_dict = {} diff --git a/gtsam/3rdparty/Eigen/debug/msvc/eigen_autoexp_part.dat b/gtsam/3rdparty/Eigen/debug/msvc/eigen_autoexp_part.dat index ba7eefc8e..07aa43739 100644 --- a/gtsam/3rdparty/Eigen/debug/msvc/eigen_autoexp_part.dat +++ b/gtsam/3rdparty/Eigen/debug/msvc/eigen_autoexp_part.dat @@ -1,295 +1,295 @@ -; *************************************************************** -; * Eigen Visualizer -; * -; * Author: Hauke Heibel -; * -; * Support the enhanced debugging of the following Eigen -; * types (*: any, +:fixed dimension) : -; * -; * - Eigen::Matrix<*,4,1,*,*,*> and Eigen::Matrix<*,1,4,*,*,*> -; * - Eigen::Matrix<*,3,1,*,*,*> and Eigen::Matrix<*,1,3,*,*,*> -; * - Eigen::Matrix<*,2,1,*,*,*> and Eigen::Matrix<*,1,2,*,*,*> -; * - Eigen::Matrix<*,-1,-1,*,*,*> -; * - Eigen::Matrix<*,+,-1,*,*,*> -; * - Eigen::Matrix<*,-1,+,*,*,*> -; * - Eigen::Matrix<*,+,+,*,*,*> -; * -; * Matrices are displayed properly independantly of the memory -; * alignment (RowMajor vs. ColMajor). -; * -; * This file is distributed WITHOUT ANY WARRANTY. Please ensure -; * that your original autoexp.dat file is copied to a safe -; * place before proceeding with its modification. -; *************************************************************** - -[Visualizer] - -; Fixed size 4-vectors -Eigen::Matrix<*,4,1,*,*,*>|Eigen::Matrix<*,1,4,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - x : ($c.m_storage.m_data.array)[0], - y : ($c.m_storage.m_data.array)[1], - z : ($c.m_storage.m_data.array)[2], - w : ($c.m_storage.m_data.array)[3] - ) - ) - - preview - ( - #( - "[", - 4, - "](", - #array(expr: $e.m_storage.m_data.array[$i], size: 4), - ")" - ) - ) -} - -; Fixed size 3-vectors -Eigen::Matrix<*,3,1,*,*,*>|Eigen::Matrix<*,1,3,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - x : ($c.m_storage.m_data.array)[0], - y : ($c.m_storage.m_data.array)[1], - z : ($c.m_storage.m_data.array)[2] - ) - ) - - preview - ( - #( - "[", - 3, - "](", - #array(expr: $e.m_storage.m_data.array[$i], size: 3), - ")" - ) - ) -} - -; Fixed size 2-vectors -Eigen::Matrix<*,2,1,*,*,*>|Eigen::Matrix<*,1,2,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - x : ($c.m_storage.m_data.array)[0], - y : ($c.m_storage.m_data.array)[1] - ) - ) - - preview - ( - #( - "[", - 2, - "](", - #array(expr: $e.m_storage.m_data.array[$i], size: 2), - ")" - ) - ) -} - -; Fixed size 1-vectors -Eigen::Matrix<*,1,1,*,*,*>|Eigen::Matrix<*,1,1,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - x : ($c.m_storage.m_data.array)[0] - ) - ) - - preview - ( - #( - "[", - 1, - "](", - #array(expr: $e.m_storage.m_data.array[$i], size: 1), - ")" - ) - ) -} - -; Dynamic matrices (ColMajor and RowMajor support) -Eigen::Matrix<*,-1,-1,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - rows: $c.m_storage.m_rows, - cols: $c.m_storage.m_cols, - ; Check for RowMajorBit - #if ($c.Flags & 0x1) ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[($i % $c.m_storage.m_rows)*$c.m_storage.m_cols + (($i- $i % $c.m_storage.m_rows)/$c.m_storage.m_rows)], - size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.m_storage.m_cols - ) - ) #else ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[$i], - size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.m_storage.m_cols - ) - ) - ) - ) - - preview - ( - #( - "[", - $c.m_storage.m_rows, - ",", - $c.m_storage.m_cols, - "](", - #array( - expr : [($c.m_storage.m_data)[$i],g], - size : $c.m_storage.m_rows*$c.m_storage.m_cols - ), - ")" - ) - ) -} - -; Fixed rows, dynamic columns matrix (ColMajor and RowMajor support) -Eigen::Matrix<*,*,-1,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - rows: $c.RowsAtCompileTime, - cols: $c.m_storage.m_cols, - ; Check for RowMajorBit - #if ($c.Flags & 0x1) ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[($i % $c.RowsAtCompileTime)*$c.m_storage.m_cols + (($i- $i % $c.RowsAtCompileTime)/$c.RowsAtCompileTime)], - size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.m_storage.m_cols - ) - ) #else ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[$i], - size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.m_storage.m_cols - ) - ) - ) - ) - - preview - ( - #( - "[", - $c.RowsAtCompileTime, - ",", - $c.m_storage.m_cols, - "](", - #array( - expr : [($c.m_storage.m_data)[$i],g], - size : $c.RowsAtCompileTime*$c.m_storage.m_cols - ), - ")" - ) - ) -} - -; Dynamic rows, fixed columns matrix (ColMajor and RowMajor support) -Eigen::Matrix<*,-1,*,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - rows: $c.m_storage.m_rows, - cols: $c.ColsAtCompileTime, - ; Check for RowMajorBit - #if ($c.Flags & 0x1) ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[($i % $c.m_storage.m_rows)*$c.ColsAtCompileTime + (($i- $i % $c.m_storage.m_rows)/$c.m_storage.m_rows)], - size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.ColsAtCompileTime - ) - ) #else ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data)[$i], - size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.ColsAtCompileTime - ) - ) - ) - ) - - preview - ( - #( - "[", - $c.m_storage.m_rows, - ",", - $c.ColsAtCompileTime, - "](", - #array( - expr : [($c.m_storage.m_data)[$i],g], - size : $c.m_storage.m_rows*$c.ColsAtCompileTime - ), - ")" - ) - ) -} - -; Fixed size matrix (ColMajor and RowMajor support) -Eigen::Matrix<*,*,*,*,*,*>{ - children - ( - #( - [internals]: [$c,!], - rows: $c.RowsAtCompileTime, - cols: $c.ColsAtCompileTime, - ; Check for RowMajorBit - #if ($c.Flags & 0x1) ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data.array)[($i % $c.RowsAtCompileTime)*$c.ColsAtCompileTime + (($i- $i % $c.RowsAtCompileTime)/$c.RowsAtCompileTime)], - size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.ColsAtCompileTime - ) - ) #else ( - #array( - rank: 2, - base: 0, - expr: ($c.m_storage.m_data.array)[$i], - size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.ColsAtCompileTime - ) - ) - ) - ) - - preview - ( - #( - "[", - $c.RowsAtCompileTime, - ",", - $c.ColsAtCompileTime, - "](", - #array( - expr : [($c.m_storage.m_data.array)[$i],g], - size : $c.RowsAtCompileTime*$c.ColsAtCompileTime - ), - ")" - ) - ) -} +; *************************************************************** +; * Eigen Visualizer +; * +; * Author: Hauke Heibel +; * +; * Support the enhanced debugging of the following Eigen +; * types (*: any, +:fixed dimension) : +; * +; * - Eigen::Matrix<*,4,1,*,*,*> and Eigen::Matrix<*,1,4,*,*,*> +; * - Eigen::Matrix<*,3,1,*,*,*> and Eigen::Matrix<*,1,3,*,*,*> +; * - Eigen::Matrix<*,2,1,*,*,*> and Eigen::Matrix<*,1,2,*,*,*> +; * - Eigen::Matrix<*,-1,-1,*,*,*> +; * - Eigen::Matrix<*,+,-1,*,*,*> +; * - Eigen::Matrix<*,-1,+,*,*,*> +; * - Eigen::Matrix<*,+,+,*,*,*> +; * +; * Matrices are displayed properly independantly of the memory +; * alignment (RowMajor vs. ColMajor). +; * +; * This file is distributed WITHOUT ANY WARRANTY. Please ensure +; * that your original autoexp.dat file is copied to a safe +; * place before proceeding with its modification. +; *************************************************************** + +[Visualizer] + +; Fixed size 4-vectors +Eigen::Matrix<*,4,1,*,*,*>|Eigen::Matrix<*,1,4,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + x : ($c.m_storage.m_data.array)[0], + y : ($c.m_storage.m_data.array)[1], + z : ($c.m_storage.m_data.array)[2], + w : ($c.m_storage.m_data.array)[3] + ) + ) + + preview + ( + #( + "[", + 4, + "](", + #array(expr: $e.m_storage.m_data.array[$i], size: 4), + ")" + ) + ) +} + +; Fixed size 3-vectors +Eigen::Matrix<*,3,1,*,*,*>|Eigen::Matrix<*,1,3,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + x : ($c.m_storage.m_data.array)[0], + y : ($c.m_storage.m_data.array)[1], + z : ($c.m_storage.m_data.array)[2] + ) + ) + + preview + ( + #( + "[", + 3, + "](", + #array(expr: $e.m_storage.m_data.array[$i], size: 3), + ")" + ) + ) +} + +; Fixed size 2-vectors +Eigen::Matrix<*,2,1,*,*,*>|Eigen::Matrix<*,1,2,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + x : ($c.m_storage.m_data.array)[0], + y : ($c.m_storage.m_data.array)[1] + ) + ) + + preview + ( + #( + "[", + 2, + "](", + #array(expr: $e.m_storage.m_data.array[$i], size: 2), + ")" + ) + ) +} + +; Fixed size 1-vectors +Eigen::Matrix<*,1,1,*,*,*>|Eigen::Matrix<*,1,1,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + x : ($c.m_storage.m_data.array)[0] + ) + ) + + preview + ( + #( + "[", + 1, + "](", + #array(expr: $e.m_storage.m_data.array[$i], size: 1), + ")" + ) + ) +} + +; Dynamic matrices (ColMajor and RowMajor support) +Eigen::Matrix<*,-1,-1,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + rows: $c.m_storage.m_rows, + cols: $c.m_storage.m_cols, + ; Check for RowMajorBit + #if ($c.Flags & 0x1) ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[($i % $c.m_storage.m_rows)*$c.m_storage.m_cols + (($i- $i % $c.m_storage.m_rows)/$c.m_storage.m_rows)], + size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.m_storage.m_cols + ) + ) #else ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[$i], + size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.m_storage.m_cols + ) + ) + ) + ) + + preview + ( + #( + "[", + $c.m_storage.m_rows, + ",", + $c.m_storage.m_cols, + "](", + #array( + expr : [($c.m_storage.m_data)[$i],g], + size : $c.m_storage.m_rows*$c.m_storage.m_cols + ), + ")" + ) + ) +} + +; Fixed rows, dynamic columns matrix (ColMajor and RowMajor support) +Eigen::Matrix<*,*,-1,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + rows: $c.RowsAtCompileTime, + cols: $c.m_storage.m_cols, + ; Check for RowMajorBit + #if ($c.Flags & 0x1) ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[($i % $c.RowsAtCompileTime)*$c.m_storage.m_cols + (($i- $i % $c.RowsAtCompileTime)/$c.RowsAtCompileTime)], + size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.m_storage.m_cols + ) + ) #else ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[$i], + size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.m_storage.m_cols + ) + ) + ) + ) + + preview + ( + #( + "[", + $c.RowsAtCompileTime, + ",", + $c.m_storage.m_cols, + "](", + #array( + expr : [($c.m_storage.m_data)[$i],g], + size : $c.RowsAtCompileTime*$c.m_storage.m_cols + ), + ")" + ) + ) +} + +; Dynamic rows, fixed columns matrix (ColMajor and RowMajor support) +Eigen::Matrix<*,-1,*,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + rows: $c.m_storage.m_rows, + cols: $c.ColsAtCompileTime, + ; Check for RowMajorBit + #if ($c.Flags & 0x1) ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[($i % $c.m_storage.m_rows)*$c.ColsAtCompileTime + (($i- $i % $c.m_storage.m_rows)/$c.m_storage.m_rows)], + size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.ColsAtCompileTime + ) + ) #else ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data)[$i], + size: ($r==1)*$c.m_storage.m_rows+($r==0)*$c.ColsAtCompileTime + ) + ) + ) + ) + + preview + ( + #( + "[", + $c.m_storage.m_rows, + ",", + $c.ColsAtCompileTime, + "](", + #array( + expr : [($c.m_storage.m_data)[$i],g], + size : $c.m_storage.m_rows*$c.ColsAtCompileTime + ), + ")" + ) + ) +} + +; Fixed size matrix (ColMajor and RowMajor support) +Eigen::Matrix<*,*,*,*,*,*>{ + children + ( + #( + [internals]: [$c,!], + rows: $c.RowsAtCompileTime, + cols: $c.ColsAtCompileTime, + ; Check for RowMajorBit + #if ($c.Flags & 0x1) ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data.array)[($i % $c.RowsAtCompileTime)*$c.ColsAtCompileTime + (($i- $i % $c.RowsAtCompileTime)/$c.RowsAtCompileTime)], + size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.ColsAtCompileTime + ) + ) #else ( + #array( + rank: 2, + base: 0, + expr: ($c.m_storage.m_data.array)[$i], + size: ($r==1)*$c.RowsAtCompileTime+($r==0)*$c.ColsAtCompileTime + ) + ) + ) + ) + + preview + ( + #( + "[", + $c.RowsAtCompileTime, + ",", + $c.ColsAtCompileTime, + "](", + #array( + expr : [($c.m_storage.m_data.array)[$i],g], + size : $c.RowsAtCompileTime*$c.ColsAtCompileTime + ), + ")" + ) + ) +} diff --git a/gtsam/3rdparty/Eigen/doc/C00_QuickStartGuide.dox b/gtsam/3rdparty/Eigen/doc/C00_QuickStartGuide.dox index ad772b2e1..8534cb0c3 100644 --- a/gtsam/3rdparty/Eigen/doc/C00_QuickStartGuide.dox +++ b/gtsam/3rdparty/Eigen/doc/C00_QuickStartGuide.dox @@ -25,6 +25,10 @@ There is no library to link to. The only thing that you need to keep in mind whe \code g++ -I /path/to/eigen/ my_program.cpp -o my_program \endcode +On Linux or Mac OS X, another option is to symlink or copy the Eigen folder into /usr/local/include/. This way, you can compile the program with: + +\code g++ my_program.cpp -o my_program \endcode + When you run the program, it produces the following output: \include QuickStart_example.out diff --git a/gtsam/3rdparty/Eigen/doc/C06_TutorialLinearAlgebra.dox b/gtsam/3rdparty/Eigen/doc/C06_TutorialLinearAlgebra.dox index 77f13f4a0..e8b3b7953 100644 --- a/gtsam/3rdparty/Eigen/doc/C06_TutorialLinearAlgebra.dox +++ b/gtsam/3rdparty/Eigen/doc/C06_TutorialLinearAlgebra.dox @@ -144,6 +144,9 @@ You need an eigendecomposition here, see available such decompositions on \ref T Make sure to check if your matrix is self-adjoint, as is often the case in these problems. Here's an example using SelfAdjointEigenSolver, it could easily be adapted to general matrices using EigenSolver or ComplexEigenSolver. +The computation of eigenvalues and eigenvectors does not necessarily converge, but such failure to converge is +very rare. The call to info() is to check for this possibility. + diff --git a/gtsam/3rdparty/Eigen/doc/C07_TutorialReductionsVisitorsBroadcasting.dox b/gtsam/3rdparty/Eigen/doc/C07_TutorialReductionsVisitorsBroadcasting.dox index e58ff6e2c..f3879b8b9 100644 --- a/gtsam/3rdparty/Eigen/doc/C07_TutorialReductionsVisitorsBroadcasting.dox +++ b/gtsam/3rdparty/Eigen/doc/C07_TutorialReductionsVisitorsBroadcasting.dox @@ -191,12 +191,27 @@ This can be accomplished with: \verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.out
Example:Output:
+We can interpret the instruction mat.colwise() += v in two equivalent ways. It adds the vector \c v +to every column of the matrix. Alternatively, it can be interpreted as repeating the vector \c v four times to +form a four-by-two matrix which is then added to \c mat: +\f[ +\begin{bmatrix} 1 & 2 & 6 & 9 \\ 3 & 1 & 7 & 2 \end{bmatrix} ++ \begin{bmatrix} 0 & 0 & 0 & 0 \\ 1 & 1 & 1 & 1 \end{bmatrix} += \begin{bmatrix} 1 & 2 & 6 & 9 \\ 4 & 2 & 8 & 3 \end{bmatrix}. +\f] +The operators -=, + and - can also be used column-wise and row-wise. On arrays, we +can also use the operators *=, /=, * and / to perform coefficient-wise +multiplication and division column-wise or row-wise. These operators are not available on matrices because it +is not clear what they would do. If you want multiply column 0 of a matrix \c mat with \c v(0), column 1 with +\c v(1), and so on, then use mat = mat * v.asDiagonal(). + It is important to point out that the vector to be added column-wise or row-wise must be of type Vector, and cannot be a Matrix. If this is not met then you will get compile-time error. This also means that broadcasting operations can only be applied with an object of type Vector, when operating with Matrix. -The same applies for the Array class, where the equivalent for VectorXf is ArrayXf. +The same applies for the Array class, where the equivalent for VectorXf is ArrayXf. As always, you should +not mix arrays and matrices in the same expression. -Therefore, to perform the same operation row-wise we can do: +To perform the same operation row-wise we can do: diff --git a/gtsam/3rdparty/Eigen/doc/C08_TutorialGeometry.dox b/gtsam/3rdparty/Eigen/doc/C08_TutorialGeometry.dox index 452abda10..b9e9eba12 100644 --- a/gtsam/3rdparty/Eigen/doc/C08_TutorialGeometry.dox +++ b/gtsam/3rdparty/Eigen/doc/C08_TutorialGeometry.dox @@ -45,16 +45,17 @@ But note that unfortunately, because of how C++ works, you can \b not do this: Rotation2D rot2(angle_in_radian);\endcode +AngleAxis aa(angle_in_radian, Vector3f(ax,ay,az));\endcode +The axis vector must be normalized. +Scaling(sx, sy) +Scaling(sx, sy, sz) +Scaling(s) +Scaling(vecN)\endcode +Transform t = Translation3f(p) * AngleAxisf(a,axis) * Scaling(s);\endcode +Matrix t = Rotation2Df(a) * Scaling(s); +Matrix t = AngleAxisf(a,axis) * Scaling(s);\endcode
Example:Output:
3D rotation as an \ref AngleAxis "angle + axis"\code -AngleAxis aa(angle_in_radian, Vector3f(ax,ay,az));\endcode
3D rotation as a \ref Quaternion "quaternion"\code Quaternion q; q = AngleAxis(angle_in_radian, axis);\endcode
N-D Scaling\code -Scaling(sx, sy) -Scaling(sx, sy, sz) -Scaling(s) -Scaling(vecN)\endcode
N-D Translation\code Translation(tx, ty) @@ -64,13 +65,13 @@ Translation(vecN)\endcode
N-D \ref TutorialGeoTransform "Affine transformation"\code Transform t = concatenation_of_any_transformations; -Transform t = Translation3f(p) * AngleAxisf(a,axis) * Scaling3f(s);\endcode
N-D Linear transformations \n (pure rotations, \n scaling, etc.)\code Matrix t = concatenation_of_rotations_and_scalings; -Matrix t = Rotation2Df(a) * Scaling2f(s); -Matrix t = AngleAxisf(a,axis) * Scaling3f(s);\endcode
Notes on rotations\n To transform more than a single vector the preferred @@ -92,8 +93,8 @@ Rotation2Df r; r = Matrix2f(..); // assumes a pure rotation matrix AngleAxisf aa; aa = Quaternionf(..); AngleAxisf aa; aa = Matrix3f(..); // assumes a pure rotation matrix Matrix2f m; m = Rotation2Df(..); -Matrix3f m; m = Quaternionf(..); Matrix3f m; m = Scaling3f(..); -Affine3f m; m = AngleAxis3f(..); Affine3f m; m = Scaling3f(..); +Matrix3f m; m = Quaternionf(..); Matrix3f m; m = Scaling(..); +Affine3f m; m = AngleAxis3f(..); Affine3f m; m = Scaling(..); Affine3f m; m = Translation3f(..); Affine3f m; m = Matrix3f(..); \endcode
@@ -207,10 +208,10 @@ t.scale(s); t.prescale(Vector_(sx,sy,..)); t.prescale(s); \endcode\code -t *= Scaling_(sx,sy,..); -t *= Scaling_(s); -t = Scaling_(sx,sy,..) * t; -t = Scaling_(s) * t; +t *= Scaling(sx,sy,..); +t *= Scaling(s); +t = Scaling(sx,sy,..) * t; +t = Scaling(s) * t; \endcode Shear transformation \n ( \b 2D \b only ! )\code t.shear(sx,sy); @@ -224,7 +225,7 @@ Note that in both API, any many transformations can be concatenated in a single t.pretranslate(..).rotate(..).translate(..).scale(..); \endcode \code -t = Translation_(..) * t * RotationType(..) * Translation_(..) * Scaling_(..); +t = Translation_(..) * t * RotationType(..) * Translation_(..) * Scaling(..); \endcode diff --git a/gtsam/3rdparty/Eigen/doc/C09_TutorialSparse.dox b/gtsam/3rdparty/Eigen/doc/C09_TutorialSparse.dox index 737f4cc09..34154bd0d 100644 --- a/gtsam/3rdparty/Eigen/doc/C09_TutorialSparse.dox +++ b/gtsam/3rdparty/Eigen/doc/C09_TutorialSparse.dox @@ -8,82 +8,144 @@ namespace Eigen { \b Table \b of \b contents \n - \ref TutorialSparseIntro + - \ref TutorialSparseExample "Example" + - \ref TutorialSparseSparseMatrix - \ref TutorialSparseFilling - - \ref TutorialSparseFeatureSet - \ref TutorialSparseDirectSolvers + - \ref TutorialSparseFeatureSet + - \ref TutorialSparse_BasicOps + - \ref TutorialSparse_Products + - \ref TutorialSparse_TriangularSelfadjoint + - \ref TutorialSparse_Submat + +
-\section TutorialSparseIntro Sparse matrix representations +Manipulating and solving sparse problems involves various modules which are summarized below: -In many applications (e.g., finite element methods) it is common to deal with very large matrices where only a few coefficients are different than zero. Both in term of memory consumption and performance, it is fundamental to use an adequate representation storing only nonzero coefficients. Such a matrix is called a sparse matrix. - -\b Declaring \b sparse \b matrices \b and \b vectors \n -The SparseMatrix class is the main sparse matrix representation of the Eigen's sparse module which offers high performance, low memory usage, and compatibility with most of sparse linear algebra packages. Because of its limited flexibility, we also provide a DynamicSparseMatrix variante taillored for low-level sparse matrix assembly. Both of them can be either row major or column major: - -\code -#include -SparseMatrix > m1(1000,2000); // declare a 1000x2000 col-major compressed sparse matrix of complex -SparseMatrix m2(1000,2000); // declare a 1000x2000 row-major compressed sparse matrix of double -DynamicSparseMatrix > m1(1000,2000); // declare a 1000x2000 col-major dynamic sparse matrix of complex -DynamicSparseMatrix m2(1000,2000); // declare a 1000x2000 row-major dynamic sparse matrix of double -\endcode - -Although a sparse matrix could also be used to represent a sparse vector, for that purpose it is better to use the specialized SparseVector class: -\code -SparseVector > v1(1000); // declare a column sparse vector of complex of size 1000 -SparseVector v2(1000); // declare a row sparse vector of double of size 1000 -\endcode -Note that here the size of a vector denotes its dimension and not the number of nonzero coefficients which is initially zero (like sparse matrices). - - -\b Overview \b of \b the \b internal \b sparse \b storage \n -In order to get the best of the Eigen's sparse objects, it is important to have a rough idea of the way they are internally stored. The SparseMatrix class implements the common and generic Compressed Column/Row Storage scheme. It consists of three compact arrays storing the values with their respective inner coordinates, and pointer indices to the begining of each outer vector. For instance, let \c m be a column-major sparse matrix. Then its nonzero coefficients are sequentially stored in memory in a column-major order (\em values). A second array of integer stores the respective row index of each coefficient (\em inner \em indices). Finally, a third array of integer, having the same length than the number of columns, stores the index in the previous arrays of the first element of each column (\em outer \em indices). - -Here is an example, with the matrix: - - - - - + + + + +
03000
2200017
75010
00000
001408
ModuleHeader fileContents
\link Sparse_Module SparseCore \endlink\code#include \endcodeSparseMatrix and SparseVector classes, matrix assembly, basic sparse linear algebra (including sparse triangular solvers)
\link SparseCholesky_Module SparseCholesky \endlink\code#include \endcodeDirect sparse LLT and LDLT Cholesky factorization to solve sparse self-adjoint positive definite problems
\link IterativeLinearSolvers_Module IterativeLinearSolvers \endlink\code#include \endcodeIterative solvers to solve large general linear square problems (including self-adjoint positive definite problems)
\code#include \endcodeIncludes all the above modules
-and its internal representation using the Compressed Column Storage format: +\section TutorialSparseIntro Sparse matrix representation + +In many applications (e.g., finite element methods) it is common to deal with very large matrices where only a few coefficients are different from zero. In such cases, memory consumption can be reduced and performance increased by using a specialized representation storing only the nonzero coefficients. Such a matrix is called a sparse matrix. + +\b The \b %SparseMatrix \b class + +The class SparseMatrix is the main sparse matrix representation of Eigen's sparse module; it offers high performance and low memory usage. +It implements a more versatile variant of the widely-used Compressed Column (or Row) Storage scheme. +It consists of four compact arrays: + - \c Values: stores the coefficient values of the non-zeros. + - \c InnerIndices: stores the row (resp. column) indices of the non-zeros. + - \c OuterStarts: stores for each column (resp. row) the index of the first non-zero in the previous two arrays. + - \c InnerNNZs: stores the number of non-zeros of each column (resp. row). +The word \c inner refers to an \em inner \em vector that is a column for a column-major matrix, or a row for a row-major matrix. +The word \c outer refers to the other direction. + +This storage scheme is better explained on an example. The following matrix + + + + + + +
03 00 0
220 0017
75 01 0
00 00 0
00140 8
+ +and one of its possible sparse, \b column \b major representation: + + + +
Values: 227_3514__1_178
InnerIndices: 12_02 4__2_ 14
+ + + +
OuterStarts:035810\em 12
InnerNNZs: 2211 2
+ +Currently the elements of a given inner vector are guaranteed to be always sorted by increasing inner indices. +The \c "_" indicates available free space to quickly insert new elements. +Assuming no reallocation is needed, the insertion of a random element is therefore in O(nnz_j) where nnz_j is the number of nonzeros of the respective inner vector. +On the other hand, inserting elements with increasing inner indices in a given inner vector is much more efficient since this only requires to increase the respective \c InnerNNZs entry that is a O(1) operation. + +The case where no empty space is available is a special case, and is refered as the \em compressed mode. +It corresponds to the widely used Compressed Column (or Row) Storage schemes (CCS or CRS). +Any SparseMatrix can be turned to this form by calling the SparseMatrix::makeCompressed() function. +In this case, one can remark that the \c InnerNNZs array is redundant with \c OuterStarts because we the equality: \c InnerNNZs[j] = \c OuterStarts[j+1]-\c OuterStarts[j]. +Therefore, in practice a call to SparseMatrix::makeCompressed() frees this buffer. + +It is worth noting that most of our wrappers to external libraries requires compressed matrices as inputs. + +The results of %Eigen's operations always produces \b compressed sparse matrices. +On the other hand, the insertion of a new element into a SparseMatrix converts this later to the \b uncompressed mode. + +Here is the previous matrix represented in compressed mode: - + +
Values: 22735141178
Inner indices: 1202 42 14
InnerIndices: 1202 42 14
+ +
OuterStarts:02456\em 8
-Outer indices:
02456\em 7
-As you might guess, here the storage order is even more important than with dense matrices. We will therefore often make a clear difference between the \em inner and \em outer dimensions. For instance, it is efficient to loop over the coefficients of an \em inner \em vector (e.g., a column of a column-major matrix), but completely inefficient to do the same for an \em outer \em vector (e.g., a row of a column-major matrix). +A SparseVector is a special case of a SparseMatrix where only the \c Values and \c InnerIndices arrays are stored. +There is no notion of compressed/uncompressed mode for a SparseVector. -The SparseVector class implements the same compressed storage scheme but, of course, without any outer index buffer. -Since all nonzero coefficients of such a matrix are sequentially stored in memory, inserting a new nonzero near the "beginning" of the matrix can be extremely costly. As described below (\ref TutorialSparseFilling), one strategy is to fill nonzero coefficients in order. In cases where this is not possible, Eigen's sparse module also provides a DynamicSparseMatrix class which allows efficient random insertion. DynamicSparseMatrix is essentially implemented as an array of SparseVector, where the values and inner-indices arrays have been split into multiple small and resizable arrays. Assuming the number of nonzeros per inner vector is relatively small, this modification allows for very fast random insertion at the cost of a slight memory overhead (due to extra memory preallocated by each inner vector to avoid an expensive memory reallocation at every insertion) and a loss of compatibility with other sparse libraries used by some of our high-level solvers. Once complete, a DynamicSparseMatrix can be converted to a SparseMatrix to permit usage of these sparse libraries. +\section TutorialSparseExample First example -To summarize, it is recommended to use SparseMatrix whenever possible, and reserve the use of DynamicSparseMatrix to assemble a sparse matrix in cases when a SparseMatrix is not flexible enough. The respective pros/cons of both representations are summarized in the following table: +Before describing each individual class, let's start with the following typical example: solving the Lapace equation \f$ \nabla u = 0 \f$ on a regular 2D grid using a finite difference scheme and Dirichlet boundary conditions. +Such problem can be mathematically expressed as a linear problem of the form \f$ Ax=b \f$ where \f$ x \f$ is the vector of \c m unknowns (in our case, the values of the pixels), \f$ b \f$ is the right hand side vector resulting from the boundary conditions, and \f$ A \f$ is an \f$ m \times m \f$ matrix containing only a few non-zero elements resulting from the discretization of the Laplacian operator. - - - - - - - - - - - - - -
SparseMatrixDynamicSparseMatrix
memory efficiency*****
sorted insertion******
random insertion \n in sorted inner vector****
sorted insertion \n in random inner vector-***
random insertion-**
coeff wise unary operators******
coeff wise binary operators******
matrix products*****(*)
transpose*****
redux*****
*= scalar*****
Compatibility with highlevel solvers \n (TAUCS, Cholmod, SuperLU, UmfPack)***-
+ +\include Tutorial_sparse_example.cpp + + +\image html Tutorial_sparse_example.jpeg + + +In this example, we start by defining a column-major sparse matrix type of double \c SparseMatrix, and a triplet list of the same scalar type \c Triplet. A triplet is a simple object representing a non-zero entry as the triplet: \c row index, \c column index, \c value. + +In the main function, we declare a list \c coefficients of triplets (as a std vector) and the right hand side vector \f$ b \f$ which are filled by the \a buildProblem function. +The raw and flat list of non-zero entries is then converted to a true SparseMatrix object \c A. +Note that the elements of the list do not have to be sorted, and possible duplicate entries will be summed up. + +The last step consists of effectively solving the assembled problem. +Since the resulting matrix \c A is symmetric by construction, we can perform a direct Cholesky factorization via the SimplicialLDLT class which behaves like its LDLT counterpart for dense objects. + +The resulting vector \c x contains the pixel values as a 1D array which is saved to a jpeg file shown on the right of the code above. + +Describing the \a buildProblem and \a save functions is out of the scope of this tutorial. They are given \ref TutorialSparse_example_details "here" for the curious and reproducibility purpose. -\b Matrix \b and \b vector \b properties \n -Here mat and vec represent any sparse-matrix and sparse-vector type, respectively. +\section TutorialSparseSparseMatrix The SparseMatrix class + +\b %Matrix \b and \b vector \b properties \n + +The SparseMatrix and SparseVector classes take three template arguments: + * the scalar type (e.g., double) + * the storage order (ColMajor or RowMajor, the default is RowMajor) + * the inner index type (default is \c int). + +As for dense Matrix objects, constructors takes the size of the object. +Here are some examples: + +\code +SparseMatrix > mat(1000,2000); // declares a 1000x2000 column-major compressed sparse matrix of complex +SparseMatrix mat(1000,2000); // declares a 1000x2000 row-major compressed sparse matrix of double +SparseVector > vec(1000); // declares a column sparse vector of complex of size 1000 +SparseVector vec(1000); // declares a row sparse vector of double of size 1000 +\endcode + +In the rest of the tutorial, \c mat and \c vec represent any sparse-matrix and sparse-vector objects, respectively. + +The dimensions of a matrix can be queried using the following functions: \b Iterating \b over \b the \b nonzero \b coefficients \n -Iterating over the coefficients of a sparse matrix can be done only in the same order as the storage order. Here is an example: +Random access to the elements of a sparse object can be done through the \c coeffRef(i,j) function. +However, this function involves a quite expensive binary search. +In most cases, one only wants to iterate over the non-zeros elements. This is achieved by a standard loop over the outer dimension, and then by iterating over the non-zeros of the current inner vector via an InnerIterator. Thus, the non-zero entries have to be visited in the same order than the storage order. +Here is an example:
Standard \n dimensions\code mat.rows() @@ -105,13 +167,16 @@ vec.nonZeros() \endcode
\code -SparseMatrixType mat(rows,cols); -for (int k=0; k mat(rows,cols); +for (int k=0; k::InnerIterator it(mat,k); it; ++it) { it.value(); it.row(); // row index @@ -130,129 +195,258 @@ for (SparseVector::InnerIterator it(vec); it; ++it) \endcode
+For a writable expression, the referenced value can be modified using the valueRef() function. +If the type of the sparse matrix or vector depends on a template parameter, then the \c typename keyword is +required to indicate that \c InnerIterator denotes a type; see \ref TopicTemplateKeyword for details. \section TutorialSparseFilling Filling a sparse matrix -Owing to the special storage scheme of a SparseMatrix, it is obvious that for performance reasons a sparse matrix cannot be filled as easily as a dense matrix. For instance the cost of a purely random insertion into a SparseMatrix is in O(nnz) where nnz is the current number of non zeros. In order to cover all uses cases with best efficiency, Eigen provides various mechanisms, from the easiest but slowest, to the fastest but restrictive one. +Because of the special storage scheme of a SparseMatrix, special care has to be taken when adding new nonzero entries. +For instance, the cost of a single purely random insertion into a SparseMatrix is \c O(nnz), where \c nnz is the current number of non-zero coefficients. -If you don't have any prior knowledge about the order your matrix will be filled, then the best choice is to use a DynamicSparseMatrix. With a DynamicSparseMatrix, you can add or modify any coefficients at any time using the coeffRef(row,col) method. Here is an example: +The simplest way to create a sparse matrix while guaranteeing good performance is thus to first build a list of so-called \em triplets, and then convert it to a SparseMatrix. + +Here is a typical usage example: \code -DynamicSparseMatrix aux(1000,1000); -aux.reserve(estimated_number_of_non_zero); // optional -for (...) - for each j // the j can be random - for each i interacting with j // the i can be random - aux.coeffRef(i,j) += foo(i,j); -\endcode -Then the DynamicSparseMatrix object can be converted to a compact SparseMatrix to be used, e.g., by one of our supported solver: -\code -SparseMatrix mat(aux); -\endcode - -In order to optimize this process, instead of the generic coeffRef(i,j) method one can also use: - - \code m.insert(i,j) = value; \endcode which assumes the coefficient of coordinate (row,col) does not already exist (otherwise this is a programming error and your program will stop). - - \code m.insertBack(i,j) = value; \endcode which, in addition to the requirements of insert(), also assumes that the coefficient of coordinate (row,col) will be inserted at the end of the target inner-vector. More precisely, if the matrix m is column major, then the row index of the last non zero coefficient of the j-th column must be smaller than i. - - -Actually, the SparseMatrix class also supports random insertion via the insert() method. However, its uses should be reserved in cases where the inserted non zero is nearly the last one of the compact storage array. In practice, this means it should be used only to perform random (or sorted) insertion into the current inner-vector while filling the inner-vectors in an increasing order. Moreover, with a SparseMatrix an insertion session must be closed by a call to finalize() before any use of the matrix. Here is an example for a column major matrix: - -\code -SparseMatrix mat(1000,1000); -mat.reserve(estimated_number_of_non_zero); // optional -for each j // should be in increasing order for performance reasons - for each i interacting with j // the i can be random - mat.insert(i,j) = foo(i,j); // optional for a DynamicSparseMatrix -mat.finalize(); -\endcode - -Finally, the fastest way to fill a SparseMatrix object is to insert the elements in a purely coherence order (increasing inner index per increasing outer index). To this end, Eigen provides a very low but optimal API and illustrated below: - -\code -SparseMatrix mat(1000,1000); -mat.reserve(estimated_number_of_non_zero); // optional -for(int j=0; j<1000; ++j) +typedef Eigen::Triplet T; +std::vector tripletList; +triplets.reserve(estimation_of_entries); +for(...) { - mat.startVec(j); // optional for a DynamicSparseMatrix - for each i interacting with j // with increasing i - mat.insertBack(i,j) = foo(i,j); + // ... + tripletList.push_back(T(i,j,v_ij)); } -mat.finalize(); // optional for a DynamicSparseMatrix +SparseMatrixType mat(rows,cols); +mat.setFromTriplets(tripletList.begin(), tripletList.end()); +// mat is ready to go! \endcode -Note that there also exist the insertBackByOuterInner(Index outer, Index, inner) function which allows to write code agnostic to the storage order. +The \c std::vector of triplets might contain the elements in arbitrary order, and might even contain duplicated elements that will be summed up by setFromTriplets(). +See the SparseMatrix::setFromTriplets() function and class Triplet for more details. -\section TutorialSparseFeatureSet Supported operators and functions -In the following \em sm denote a sparse matrix, \em sv a sparse vector, \em dm a dense matrix, and \em dv a dense vector. -In Eigen's sparse module we chose to expose only the subset of the dense matrix API which can be efficiently implemented. Moreover, all combinations are not always possible. For instance, it is not possible to add two sparse matrices having two different storage order. On the other hand it is perfectly fine to evaluate a sparse matrix/expression to a matrix having a different storage order: +In some cases, however, slightly higher performance, and lower memory consumption can be reached by directly inserting the non-zeros into the destination matrix. +A typical scenario of this approach is illustrated bellow: \code -SparseMatrixType sm1, sm2, sm3; -sm3 = sm1.transpose() + sm2; // invalid -sm3 = SparseMatrixType(sm1.transpose()) + sm2; // correct +1: SparseMatrix mat(rows,cols); // default is column major +2: mat.reserve(VectorXi::Constant(cols,6)); +3: for each i,j such that v_ij != 0 +4: mat.insert(i,j) = v_ij; // alternative: mat.coeffRef(i,j) += v_ij; +5: mat.makeCompressed(); // optional \endcode -Here are some examples of the supported operations: +- The key ingredient here is the line 2 where we reserve room for 6 non-zeros per column. In many cases, the number of non-zeros per column or row can easily be known in advance. If it varies significantly for each inner vector, then it is possible to specify a reserve size for each inner vector by providing a vector object with an operator[](int j) returning the reserve size of the \c j-th inner vector (e.g., via a VectorXi or std::vector). If only a rought estimate of the number of nonzeros per inner-vector can be obtained, it is highly recommended to overestimate it rather than the opposite. If this line is omitted, then the first insertion of a new element will reserve room for 2 elements per inner vector. +- The line 4 performs a sorted insertion. In this example, the ideal case is when the \c j-th column is not full and contains non-zeros whose inner-indices are smaller than \c i. In this case, this operation boils down to trivial O(1) operation. +- When calling insert(i,j) the element \c i \c ,j must not already exists, otherwise use the coeffRef(i,j) method that will allow to, e.g., accumulate values. This method first performs a binary search and finally calls insert(i,j) if the element does not already exist. It is more flexible than insert() but also more costly. +- The line 5 suppresses the remaining empty space and transforms the matrix into a compressed column storage. + + +\section TutorialSparseDirectSolvers Solving linear problems + +%Eigen currently provides a limited set of built-in solvers, as well as wrappers to external solver libraries. +They are summarized in the following table: + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
ClassModuleSolver kindMatrix kindFeatures related to performanceDependencies,License

Notes

SimplicialLLT \link SparseCholesky_Module SparseCholesky \endlinkDirect LLt factorizationSPDFill-in reducingbuilt-in, LGPLSimplicialLDLT is often preferable
SimplicialLDLT \link SparseCholesky_Module SparseCholesky \endlinkDirect LDLt factorizationSPDFill-in reducingbuilt-in, LGPLRecommended for very sparse and not too large problems (e.g., 2D Poisson eq.)
ConjugateGradient\link IterativeLinearSolvers_Module IterativeLinearSolvers \endlinkClassic iterative CGSPDPreconditionningbuilt-in, LGPLRecommended for large symmetric problems (e.g., 3D Poisson eq.)
BiCGSTAB\link IterativeLinearSolvers_Module IterativeLinearSolvers \endlinkIterative stabilized bi-conjugate gradientSquarePreconditionningbuilt-in, LGPLMight not always converge
PastixLLT \n PastixLDLT \n PastixLU\link PaStiXSupport_Module PaStiXSupport \endlinkDirect LLt, LDLt, LU factorizationsSPD \n SPD \n SquareFill-in reducing, Leverage fast dense algebra, MultithreadingRequires the PaStiX package, \b CeCILL-C optimized for tough problems and symmetric patterns
CholmodSupernodalLLT\link CholmodSupport_Module CholmodSupport \endlinkDirect LLt factorizationSPDFill-in reducing, Leverage fast dense algebraRequires the SuiteSparse package, \b GPL
UmfPackLU\link UmfPackSupport_Module UmfPackSupport \endlinkDirect LU factorizationSquareFill-in reducing, Leverage fast dense algebraRequires the SuiteSparse package, \b GPL
SuperLU\link SuperLUSupport_Module SuperLUSupport \endlinkDirect LU factorizationSquareFill-in reducing, Leverage fast dense algebraRequires the SuperLU library, (BSD-like)
+ +Here \c SPD means symmetric positive definite. + +All these solvers follow the same general concept. +Here is a typical and general example: \code -s_1 *= 0.5; -sm4 = sm1 + sm2 + sm3; // only if s_1, s_2 and s_3 have the same storage order -sm3 = sm1 * sm2; -dv3 = sm1 * dv2; -dm3 = sm1 * dm2; -dm3 = dm2 * sm1; -sm3 = sm1.cwiseProduct(sm2); // only if s_1 and s_2 have the same storage order -dv2 = sm1.triangularView().solve(dv2); -\endcode - -The product of a sparse matrix A by a dense matrix/vector dv with A symmetric can be optimized by telling that to Eigen: -\code -res = A.selfadjointView<>() * dv; // if all coefficients of A are stored -res = A.selfadjointView() * dv; // if only the upper part of A is stored -res = A.selfadjointView() * dv; // if only the lower part of A is stored -\endcode - - -\section TutorialSparseDirectSolvers Using the direct solvers - -To solve a sparse problem you currently have to use one or multiple of the following "unsupported" module: -- \ref SparseExtra_Module - - \b solvers: SparseLLT, SparseLDLT (\#include ) - - \b notes: built-in basic LLT and LDLT solvers -- \ref CholmodSupport_Module - - \b solver: SparseLLT (\#include ) - - \b notes: LLT solving using Cholmod, requires a SparseMatrix object. (recommended for symmetric/selfadjoint problems) -- \ref UmfPackSupport_Module - - \b solver: SparseLU (\#include ) - - \b notes: LU solving using UmfPack, requires a SparseMatrix object (recommended for squared matrices) -- \ref SuperLUSupport_Module - - \b solver: SparseLU (\#include ) - - \b notes: (LU solving using SuperLU, requires a SparseMatrix object, recommended for squared matrices) -- \ref TaucsSupport_Module - - \b solver: SparseLLT (\#include ) - - \b notes: LLT solving using Taucs, requires a SparseMatrix object (not recommended) - -\warning Those modules are currently considered to be "unsupported" because 1) they are not documented, and 2) their API is likely to change in the future. - -Here is a typical example: -\code -#include +#include // ... SparseMatrix A; // fill A VectorXd b, x; // fill b -// solve Ax = b using UmfPack: -SparseLU,UmfPack> lu_of_A(A); -if(!lu_of_A.succeeded()) { - // decomposiiton failed +// solve Ax = b +SolverClassName > solver; +solver.compute(A); +if(solver.info()!=Succeeded) { + // decomposition failed return; } -if(!lu_of_A.solve(b,&x)) { +x = solver.solve(b); +if(solver.info()!=Succeeded) { // solving failed return; } +// solve for another right hand side: +x1 = solver.solve(b1); \endcode -See also the class SparseLLT, class SparseLU, and class SparseLDLT. +For \c SPD solvers, a second optional template argument allows to specify which triangular part have to be used, e.g.: + +\code +#include + +ConjugateGradient, Eigen::Upper> solver; +x = solver.compute(A).solve(b); +\endcode +In the above example, only the upper triangular part of the input matrix A is considered for solving. The opposite triangle might either be empty or contain arbitrary values. + +In the case where multiple problems with the same sparcity pattern have to be solved, then the "compute" step can be decomposed as follow: +\code +SolverClassName > solver; +solver.analyzePattern(A); // for this step the numerical values of A are not used +solver.factorize(A); +x1 = solver.solve(b1); +x2 = solver.solve(b2); +... +A = ...; // modify the values of the nonzeros of A, the nonzeros pattern must stay unchanged +solver.factorize(A); +x1 = solver.solve(b1); +x2 = solver.solve(b2); +... +\endcode +The compute() method is equivalent to calling both analyzePattern() and factorize(). + +Finally, each solver provides some specific features, such as determinant, access to the factors, controls of the iterations, and so on. +More details are availble in the documentations of the respective classes. + + +\section TutorialSparseFeatureSet Supported operators and functions + +Because of their special storage format, sparse matrices cannot offer the same level of flexbility than dense matrices. +In Eigen's sparse module we chose to expose only the subset of the dense matrix API which can be efficiently implemented. +In the following \em sm denotes a sparse matrix, \em sv a sparse vector, \em dm a dense matrix, and \em dv a dense vector. + +\subsection TutorialSparse_BasicOps Basic operations + +%Sparse expressions support most of the unary and binary coefficient wise operations: +\code +sm1.real() sm1.imag() -sm1 0.5*sm1 +sm1+sm2 sm1-sm2 sm1.cwiseProduct(sm2) +\endcode +However, a strong restriction is that the storage orders must match. For instance, in the following example: +\code +sm4 = sm1 + sm2 + sm3; +\endcode +sm1, sm2, and sm3 must all be row-major or all column major. +On the other hand, there is no restriction on the target matrix sm4. +For instance, this means that for computing \f$ A^T + A \f$, the matrix \f$ A^T \f$ must be evaluated into a temporary matrix of compatible storage order: +\code +SparseMatrix A, B; +B = SparseMatrix(A.transpose()) + A; +\endcode + +Binary coefficient wise operators can also mix sparse and dense expressions: +\code +sm2 = sm1.cwiseProduct(dm1); +dm2 = sm1 + dm1; +\endcode + + +%Sparse expressions also support transposition: +\code +sm1 = sm2.transpose(); +sm1 = sm2.adjoint(); +\endcode +However, there is no transposeInPlace() method. + + +\subsection TutorialSparse_Products Matrix products + +%Eigen supports various kind of sparse matrix products which are summarize below: + - \b sparse-dense: + \code +dv2 = sm1 * dv1; +dm2 = dm1 * sm1.adjoint(); +dm2 = 2. * sm1 * dm1; + \endcode + - \b symmetric \b sparse-dense. The product of a sparse symmetric matrix with a dense matrix (or vector) can also be optimized by specifying the symmetry with selfadjointView(): + \code +dm2 = sm1.selfadjointView<>() * dm1; // if all coefficients of A are stored +dm2 = A.selfadjointView() * dm1; // if only the upper part of A is stored +dm2 = A.selfadjointView() * dm1; // if only the lower part of A is stored + \endcode + - \b sparse-sparse. For sparse-sparse products, two different algorithms are available. The default one is conservative and preserve the explicit zeros that might appear: + \code +sm3 = sm1 * sm2; +sm3 = 4 * sm1.adjoint() * sm2; + \endcode + The second algorithm prunes on the fly the explicit zeros, or the values smaller than a given threshold. It is enabled and controlled through the prune() functions: + \code +sm3 = (sm1 * sm2).prune(); // removes numerical zeros +sm3 = (sm1 * sm2).prune(ref); // removes elements much smaller than ref +sm3 = (sm1 * sm2).prune(ref,epsilon); // removes elements smaller than ref*epsilon + \endcode + + - \b permutations. Finally, permutations can be applied to sparse matrices too: + \code +PermutationMatrix P = ...; +sm2 = P * sm1; +sm2 = sm1 * P.inverse(); +sm2 = sm1.transpose() * P; + \endcode + + +\subsection TutorialSparse_TriangularSelfadjoint Triangular and selfadjoint views + +Just as with dense matrices, the triangularView() function can be used to address a triangular part of the matrix, and perform triangular solves with a dense right hand side: +\code +dm2 = sm1.triangularView(dm1); +dv2 = sm1.transpose().triangularView(dv1); +\endcode + +The selfadjointView() function permits various operations: + - optimized sparse-dense matrix products: + \code +dm2 = sm1.selfadjointView<>() * dm1; // if all coefficients of A are stored +dm2 = A.selfadjointView() * dm1; // if only the upper part of A is stored +dm2 = A.selfadjointView() * dm1; // if only the lower part of A is stored + \endcode + - copy of triangular parts: + \code +sm2 = sm1.selfadjointView(); // makes a full selfadjoint matrix from the upper triangular part +sm2.selfadjointView() = sm1.selfadjointView(); // copies the upper triangular part to the lower triangular part + \endcode + - application of symmetric permutations: + \code +PermutationMatrix P = ...; +sm2 = A.selfadjointView().twistedBy(P); // compute P S P' from the upper triangular part of A, and make it a full matrix +sm2.selfadjointView() = A.selfadjointView().twistedBy(P); // compute P S P' from the lower triangular part of A, and then only compute the lower part + \endcode + +\subsection TutorialSparse_Submat Sub-matrices + +%Sparse matrices does not support yet the addressing of arbitrary sub matrices. Currently, one can only reference a set of contiguous \em inner vectors, i.e., a set of contiguous rows for a row-major matrix, or a set of contiguous columns for a column major matrix: +\code + sm1.innerVector(j); // returns an expression of the j-th column (resp. row) of the matrix if sm1 is col-major (resp. row-major) + sm1.innerVectors(j, nb); // returns an expression of the nb columns (resp. row) starting from the j-th column (resp. row) + // of the matrix if sm1 is col-major (resp. row-major) + sm1.middleRows(j, nb); // for row major matrices only, get a range of nb rows + sm1.middleCols(j, nb); // for column major matrices only, get a range of nb columns +\endcode \li \b Next: \ref TutorialMapClass diff --git a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt index 50ce7ee0c..96bff41bf 100644 --- a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt @@ -36,6 +36,7 @@ set(snippets_targets "") add_definitions("-DEIGEN_MAKING_DOCS") add_subdirectory(examples) +add_subdirectory(special_examples) add_subdirectory(snippets) add_custom_target( diff --git a/gtsam/3rdparty/Eigen/doc/D09_StructHavingEigenMembers.dox b/gtsam/3rdparty/Eigen/doc/D09_StructHavingEigenMembers.dox index d6a24d951..51789ca9c 100644 --- a/gtsam/3rdparty/Eigen/doc/D09_StructHavingEigenMembers.dox +++ b/gtsam/3rdparty/Eigen/doc/D09_StructHavingEigenMembers.dox @@ -10,6 +10,7 @@ namespace Eigen { - \ref movetotop - \ref bugineigen - \ref conditional + - \ref othersolutions \section summary Executive Summary @@ -55,6 +56,8 @@ Foo *foo = new Foo; This macro makes "new Foo" always return an aligned pointer. +If this approach is too intrusive, see also the \ref othersolutions. + \section why Why is this needed? OK let's say that your code looks like this: @@ -132,6 +135,64 @@ Foo<4> *foo4 = new Foo<4>; // foo4 is guaranteed to be 128bit-aligned Foo<3> *foo3 = new Foo<3>; // foo3 has only the system default alignment guarantee \endcode + +\section othersolutions Other solutions + +In case putting the EIGEN_MAKE_ALIGNED_OPERATOR_NEW macro everywhere is too intrusive, there exists at least two other solutions. + +\subsection othersolutions1 Disabling alignment + +The first is to disable alignment requirement for the fixed size members: +\code +class Foo +{ + ... + Eigen::Matrix v; + ... +}; +\endcode +This has for effect to disable vectorization when using \c v. +If a function of Foo uses it several times, then it still possible to re-enable vectorization by copying it into an aligned temporary vector: +\code +void Foo::bar() +{ + Eigen::Vector2d av(v); + // use av instead of v + ... + // if av changed, then do: + v = av; +} +\endcode + +\subsection othersolutions2 Private structure + +The second consist in storing the fixed-size objects into a private struct which will be dynamically allocated at the construction time of the main object: + +\code +struct Foo_d +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Vector2d v; + ... +}; + + +struct Foo { + Foo() { init_d(); } + ~Foo() { delete d; } + void bar() + { + // use d->v instead of v + ... + } +private: + void init_d() { d = new Foo_d; } + Foo_d* d; +}; +\endcode + +The clear advantage here is that the class Foo remains unchanged regarding alignment issues. The drawback is that a heap allocation will be required whatsoever. + */ } diff --git a/gtsam/3rdparty/Eigen/doc/Doxyfile.in b/gtsam/3rdparty/Eigen/doc/Doxyfile.in index 6a659d9c2..e9e89d486 100644 --- a/gtsam/3rdparty/Eigen/doc/Doxyfile.in +++ b/gtsam/3rdparty/Eigen/doc/Doxyfile.in @@ -108,7 +108,7 @@ ALWAYS_DETAILED_SEC = NO # members were ordinary class members. Constructors, destructors and assignment # operators of the base classes will not be shown. -INLINE_INHERITED_MEMB = NO +INLINE_INHERITED_MEMB = YES # If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full # path before files name in the file list and in the header files. If set @@ -206,7 +206,6 @@ ALIASES = "only_for_vectors=This is only for vectors (either row- "qr_module=This is defined in the %QR module. \code #include \endcode" \ "svd_module=This is defined in the %SVD module. \code #include \endcode" \ "label=\bug" \ - "redstar=*" \ "matrixworld=*" \ "arrayworld=*" \ "note_about_arbitrary_choice_of_solution=If there exists more than one solution, this method will arbitrarily choose one." \ @@ -303,7 +302,7 @@ TYPEDEF_HIDES_STRUCT = NO # Private class members and static file members will be hidden unless # the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES -EXTRACT_ALL = NO +EXTRACT_ALL = YES # If the EXTRACT_PRIVATE tag is set to YES all private members of a class # will be included in the documentation. @@ -561,8 +560,7 @@ WARN_LOGFILE = # with spaces. INPUT = "${Eigen_SOURCE_DIR}/Eigen" \ - "${Eigen_SOURCE_DIR}/doc" \ - "${Eigen_BINARY_DIR}/doc" + "${Eigen_SOURCE_DIR}/doc" # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is @@ -585,13 +583,17 @@ FILE_PATTERNS = * # should be searched for input files as well. Possible values are YES and NO. # If left blank NO is used. -RECURSIVE = NO +RECURSIVE = YES # The EXCLUDE tag can be used to specify files and/or directories that should # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = +EXCLUDE = "${Eigen_SOURCE_DIR}/Eigen/Eigen2Support" \ + "${Eigen_SOURCE_DIR}/Eigen/src/Eigen2Support" \ + "${Eigen_SOURCE_DIR}/doc/examples" \ + "${Eigen_SOURCE_DIR}/doc/special_examples" \ + "${Eigen_SOURCE_DIR}/doc/snippets" # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded @@ -627,10 +629,8 @@ EXCLUDE_PATTERNS = CMake* \ # wildcard * is used, a substring. Examples: ANamespace, AClass, # AClass::ANamespace, ANamespace::*Test -# This is used to clean up the "class hierarchy" page - -EXCLUDE_SYMBOLS = EigenBase<* SparseMatrixBase<* DenseBase<* MatrixBase<* Matrix<* \ - ProductReturnType<* RotationBase<* Stride<* BandMatrix<* Block<* +# This could used to clean up the "class hierarchy" page +EXCLUDE_SYMBOLS = internal::* Flagged* *InnerIterator* DenseStorage<* # The EXAMPLE_PATH tag can be used to specify one or more files or # directories that contain example code fragments that are included (see @@ -639,7 +639,9 @@ EXCLUDE_SYMBOLS = EigenBase<* SparseMatrixBase<* DenseBase<* MatrixBase<* EXAMPLE_PATH = "${Eigen_SOURCE_DIR}/doc/snippets" \ "${Eigen_BINARY_DIR}/doc/snippets" \ "${Eigen_SOURCE_DIR}/doc/examples" \ - "${Eigen_BINARY_DIR}/doc/examples" + "${Eigen_BINARY_DIR}/doc/examples" \ + "${Eigen_SOURCE_DIR}/doc/special_examples" \ + "${Eigen_BINARY_DIR}/doc/special_examples" # If the value of the EXAMPLE_PATH tag contains directories, you can use the # EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp @@ -1229,7 +1231,8 @@ EXPAND_AS_DEFINED = EIGEN_MAKE_TYPEDEFS \ EIGEN_CWISE_BINOP_RETURN_TYPE \ EIGEN_CWISE_PRODUCT_RETURN_TYPE \ EIGEN_CURRENT_STORAGE_BASE_CLASS \ - _EIGEN_GENERIC_PUBLIC_INTERFACE + _EIGEN_GENERIC_PUBLIC_INTERFACE \ + EIGEN2_SUPPORT # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then # doxygen's preprocessor will remove all function-like macros that are alone diff --git a/gtsam/3rdparty/Eigen/doc/I00_CustomizingEigen.dox b/gtsam/3rdparty/Eigen/doc/I00_CustomizingEigen.dox index 766ff6f95..623ef31e1 100644 --- a/gtsam/3rdparty/Eigen/doc/I00_CustomizingEigen.dox +++ b/gtsam/3rdparty/Eigen/doc/I00_CustomizingEigen.dox @@ -120,19 +120,22 @@ Eigen::MatrixBase, 10000, 1, 2, 10000, 1> \anchor user_defined_scalars \section CustomScalarType Using custom scalar types -By default, Eigen currently supports the following scalar types: \c int, \c float, \c double, \c std::complex, \c std::complex, \c long \c double, \c long \c long \c int (64 bits integers), and \c bool. The \c long \c double is especially useful on x86-64 systems or when the SSE2 instruction set is enabled because it enforces the use of x87 registers with extended accuracy. +By default, Eigen currently supports standard floating-point types (\c float, \c double, \c std::complex, \c std::complex, \c long \c double), as well as all integrale types (e.g., \c int, \c unsigned \c int, \c short, etc.), and \c bool. +On x86-64 systems, \c long \c double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE). In order to add support for a custom type \c T you need: - 1 - make sure the common operator (+,-,*,/,etc.) are supported by the type \c T - 2 - add a specialization of struct Eigen::NumTraits (see \ref NumTraits) - 3 - define a couple of math functions for your type such as: internal::sqrt, internal::abs, etc... +-# make sure the common operator (+,-,*,/,etc.) are supported by the type \c T +-# add a specialization of struct Eigen::NumTraits (see \ref NumTraits) +-# define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific. (see the file Eigen/src/Core/MathFunctions.h) +The math function should be defined in the same namespace than \c T, or in the \c std namespace though that second appraoch is not recommended. + Here is a concrete example adding support for the Adolc's \c adouble type. Adolc is an automatic differentiation library. The type \c adouble is basically a real value tracking the values of any number of partial derivatives. \code -#ifndef ADLOCSUPPORT_H -#define ADLOCSUPPORT_H +#ifndef ADOLCSUPPORT_H +#define ADOLCSUPPORT_H #define ADOLC_TAPELESS #include @@ -141,6 +144,7 @@ Here is a concrete example adding support for the Adolc's \c adouble type. struct NumTraits + : NumTraits // permits to get the epsilon, dummy_precision, lowest, highest functions { typedef adtl::adouble Real; typedef adtl::adouble NonInteger; @@ -149,35 +153,27 @@ template<> struct NumTraits enum { IsComplex = 0, IsInteger = 0, - IsSigned, + IsSigned = 1, + RequireInitialization = 1, ReadCost = 1, - AddCost = 1, - MulCost = 1 + AddCost = 3, + MulCost = 3 }; }; } -// the Adolc's type adouble is defined in the adtl namespace -// therefore, the following internal::* functions *must* be defined -// in the same namespace namespace adtl { - inline const adouble& internal::conj(const adouble& x) { return x; } - inline const adouble& internal::real(const adouble& x) { return x; } - inline adouble internal::imag(const adouble&) { return 0.; } - inline adouble internal::abs(const adouble& x) { return fabs(x); } - inline adouble internal::abs2(const adouble& x) { return x*x; } - inline adouble internal::sqrt(const adouble& x) { return sqrt(x); } - inline adouble internal::exp(const adouble& x) { return exp(x); } - inline adouble internal::log(const adouble& x) { return log(x); } - inline adouble internal::sin(const adouble& x) { return sin(x); } - inline adouble internal::cos(const adouble& x) { return cos(x); } - inline adouble internal::pow(const adouble& x, adouble y) { return pow(x, y); } +inline const adouble& conj(const adouble& x) { return x; } +inline const adouble& real(const adouble& x) { return x; } +inline adouble imag(const adouble&) { return 0.; } +inline adouble abs(const adouble& x) { return fabs(x); } +inline adouble abs2(const adouble& x) { return x*x; } } -#endif // ADLOCSUPPORT_H +#endif // ADOLCSUPPORT_H \endcode diff --git a/gtsam/3rdparty/Eigen/doc/I09_Vectorization.dox b/gtsam/3rdparty/Eigen/doc/I09_Vectorization.dox index 63831e59f..274d0451b 100644 --- a/gtsam/3rdparty/Eigen/doc/I09_Vectorization.dox +++ b/gtsam/3rdparty/Eigen/doc/I09_Vectorization.dox @@ -1,6 +1,6 @@ namespace Eigen { -/** \page TopicVectorization Vectorizaion +/** \page TopicVectorization Vectorization TODO: write this dox page! diff --git a/gtsam/3rdparty/Eigen/doc/I14_PreprocessorDirectives.dox b/gtsam/3rdparty/Eigen/doc/I14_PreprocessorDirectives.dox index b34fc84cf..2826a7f50 100644 --- a/gtsam/3rdparty/Eigen/doc/I14_PreprocessorDirectives.dox +++ b/gtsam/3rdparty/Eigen/doc/I14_PreprocessorDirectives.dox @@ -2,66 +2,75 @@ namespace Eigen { /** \page TopicPreprocessorDirectives Preprocessor directives -You can control some aspects of Eigen by defining the preprocessor tokens using \c \#define. These macros -should be defined before any Eigen headers are included. Often they are best set in the project options. +You can control some aspects of %Eigen by defining the preprocessor tokens using \c \#define. These macros +should be defined before any %Eigen headers are included. Often they are best set in the project options. -This page lists the preprocesor tokens recognised by Eigen. +This page lists the preprocesor tokens recognised by %Eigen. Table of contents - \ref TopicPreprocessorDirectivesMajor - \ref TopicPreprocessorDirectivesAssertions - \ref TopicPreprocessorDirectivesPerformance - \ref TopicPreprocessorDirectivesPlugins + - \ref TopicPreprocessorDirectivesDevelopers \section TopicPreprocessorDirectivesMajor Macros with major effects +These macros have a major effect and typically break the API (Application Programming Interface) and/or the +ABI (Application Binary Interface). This can be rather dangerous: if parts of your program are compiled with +one option, and other parts (or libraries that you use) are compiled with another option, your program may +fail to link or exhibit subtle bugs. Nevertheless, these options can be useful for people who know what they +are doing. + - \b EIGEN2_SUPPORT - if defined, enables the Eigen2 compatibility mode. This is meant to ease the transition of Eigen2 to Eigen3 (see \ref Eigen2ToEigen3). Not defined by default. - \b EIGEN2_SUPPORT_STAGEnn_xxx (for various values of nn and xxx) - staged migration path from Eigen2 to Eigen3; see \ref Eigen2SupportModes. - - \b EIGEN_DEFAULT_TO_ROW_MAJOR - when defined, the default storage order for matrices becomes row-major - instead of column-major. Not defined by default. - \b EIGEN_DEFAULT_DENSE_INDEX_TYPE - the type for column and row indices in matrices, vectors and array (DenseBase::Index). Set to \c std::ptrdiff_t by default. - \b EIGEN_DEFAULT_IO_FORMAT - the IOFormat to use when printing a matrix if no #IOFormat is specified. Defaults to the #IOFormat constructed by the default constructor IOFormat(). - \b EIGEN_INITIALIZE_MATRICES_BY_ZERO - if defined, all entries of newly constructed matrices and arrays are initializes to zero, as are new entries in matrices and arrays after resizing. Not defined by default. + - \b EIGEN_NO_AUTOMATIC_RESIZING - if defined, the matrices (or arrays) on both sides of an assignment + a = b have to be of the same size; otherwise, %Eigen automatically resizes \c a so that it is of + the correct size. Not defined by default. \section TopicPreprocessorDirectivesAssertions Assertions -The Eigen library contains many assertions to guard against programming errors, both at compile time and at +The %Eigen library contains many assertions to guard against programming errors, both at compile time and at run time. However, these assertions do cost time and can thus be turned off. - - \b EIGEN_NO_DEBUG - disables Eigen's assertions if defined. Not defined by default, unless the + - \b EIGEN_NO_DEBUG - disables %Eigen's assertions if defined. Not defined by default, unless the \c NDEBUG macro is defined (this is a standard C++ macro which disables all asserts). - \b EIGEN_NO_STATIC_ASSERT - if defined, compile-time static assertions are replaced by runtime assertions; this saves compilation time. Not defined by default. - - \b EIGEN_INTERNAL_DEBUGGING - if defined, enables assertions in Eigen's internal routines. This is useful - for debugging Eigen itself. Not defined by default. + - \b eigen_assert - macro with one argument that is used inside %Eigen for assertions. By default, it is + basically defined to be \c assert, which aborts the program if the assertion is violated. Redefine this + macro if you want to do something else, like throwing an exception. \section TopicPreprocessorDirectivesPerformance Alignment, vectorization and performance tweaking - - \b EIGEN_DONT_ALIGN - disables alignment completely. Eigen will not try to align its objects and does not + - \b EIGEN_DONT_ALIGN - disables alignment completely. %Eigen will not try to align its objects and does not expect that any objects passed to it are aligned. This will turn off vectorization. Not defined by default. - \b EIGEN_DONT_ALIGN_STATICALLY - disables alignment of arrays on the stack. Not defined by default, unless \c EIGEN_DONT_ALIGN is defined. - \b EIGEN_DONT_VECTORIZE - disables explicit vectorization when defined. Not defined by default, unless - alignment is disabled by Eigen's platform test or the user defining \c EIGEN_DONT_ALIGN. + alignment is disabled by %Eigen's platform test or the user defining \c EIGEN_DONT_ALIGN. - \b EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. The only optimization this currently includes is single precision sin() and cos() in the present of SSE vectorization. Defined by default. - \b EIGEN_UNROLLING_LIMIT - defines the size of a loop to enable meta unrolling. Set it to zero to disable - unrolling. The size of a loop here is expressed in Eigen's own notion of "number of FLOPS", it does not + unrolling. The size of a loop here is expressed in %Eigen's own notion of "number of FLOPS", it does not correspond to the number of iterations or the number of instructions. The default is value 100. \section TopicPreprocessorDirectivesPlugins Plugins -It is possible to add new methods to many fundamental classes in Eigen by writing a plugin. As explained in +It is possible to add new methods to many fundamental classes in %Eigen by writing a plugin. As explained in the section \ref ExtendingMatrixBase, the plugin is specified by defining a \c EIGEN_xxx_PLUGIN macro. The following macros are supported; none of them are defined by default. @@ -81,6 +90,21 @@ following macros are supported; none of them are defined by default. - \b EIGEN_FUNCTORS_PLUGIN - filename of plugin for adding new functors and specializations of functor_traits. +\section TopicPreprocessorDirectivesDevelopers Macros for Eigen developers + +These macros are mainly meant for people developing %Eigen and for testing purposes. Even though, they might be useful for power users and the curious for debugging and testing purpose, they \b should \b not \b be \b used by real-word code. + + - \b EIGEN_DEFAULT_TO_ROW_MAJOR - when defined, the default storage order for matrices becomes row-major + instead of column-major. Not defined by default. + - \b EIGEN_INTERNAL_DEBUGGING - if defined, enables assertions in %Eigen's internal routines. This is useful + for debugging %Eigen itself. Not defined by default. + - \b EIGEN_NO_MALLOC - if defined, any request from inside the %Eigen to allocate memory from the heap + results in an assertion failure. This is useful to check that some routine does not allocate memory + dynamically. Not defined by default. + - \b EIGEN_RUNTIME_NO_MALLOC - if defined, a new switch is introduced which can be turned on and off by + calling set_is_malloc_allowed(bool). If malloc is not allowed and %Eigen tries to allocate memory + dynamically anyway, an assertion failure results. Not defined by default. + */ } diff --git a/gtsam/3rdparty/Eigen/doc/I15_StorageOrders.dox b/gtsam/3rdparty/Eigen/doc/I15_StorageOrders.dox index 6b56ca8f8..7418912a6 100644 --- a/gtsam/3rdparty/Eigen/doc/I15_StorageOrders.dox +++ b/gtsam/3rdparty/Eigen/doc/I15_StorageOrders.dox @@ -60,10 +60,8 @@ parameter is set to \c RowMajor, then the matrix or array is stored in row-major \c ColMajor, then it is stored in column-major order. This mechanism is used in the above Eigen program to specify the storage order. -If the storage order is not specified, then Eigen normally defaults to storing the entry in column-major -order. This is also the case if one of the convenience typedefs (\c Matrix3f, \c ArrayXXd, etc.) is -used. However, it is possible to change the default to row-major order by defining the -\c EIGEN_DEFAULT_TO_ROW_MAJOR \ref TopicPreprocessorDirectives "preprocessor directive". +If the storage order is not specified, then Eigen defaults to storing the entry in column-major. This is also +the case if one of the convenience typedefs (\c Matrix3f, \c ArrayXXd, etc.) is used. Matrices and arrays using one storage order can be assigned to matrices and arrays using the other storage order, as happens in the above program when \c Arowmajor is initialized using \c Acolmajor. Eigen will reorder diff --git a/gtsam/3rdparty/Eigen/doc/I16_TemplateKeyword.dox b/gtsam/3rdparty/Eigen/doc/I16_TemplateKeyword.dox new file mode 100644 index 000000000..324532310 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/I16_TemplateKeyword.dox @@ -0,0 +1,136 @@ +namespace Eigen { + +/** \page TopicTemplateKeyword The template and typename keywords in C++ + +There are two uses for the \c template and \c typename keywords in C++. One of them is fairly well known +amongst programmers: to define templates. The other use is more obscure: to specify that an expression refers +to a template function or a type. This regularly trips up programmers that use the %Eigen library, often +leading to error messages from the compiler that are difficult to understand. + +Table of contents + - \ref TopicTemplateKeywordToDefineTemplates + - \ref TopicTemplateKeywordExample + - \ref TopicTemplateKeywordExplanation + - \ref TopicTemplateKeywordResources + + +\section TopicTemplateKeywordToDefineTemplates Using the template and typename keywords to define templates + +The \c template and \c typename keywords are routinely used to define templates. This is not the topic of this +page as we assume that the reader is aware of this (otherwise consult a C++ book). The following example +should illustrate this use of the \c template keyword. + +\code +template +bool isPositive(T x) +{ + return x > 0; +} +\endcode + +We could just as well have written template <class T>; the keywords \c typename and \c class have the +same meaning in this context. + + +\section TopicTemplateKeywordExample An example showing the second use of the template keyword + +Let us illustrate the second use of the \c template keyword with an example. Suppose we want to write a +function which copies all entries in the upper triangular part of a matrix into another matrix, while keeping +the lower triangular part unchanged. A straightforward implementation would be as follows: + + + + +
Example:Output:
+\include TemplateKeyword_simple.cpp + +\verbinclude TemplateKeyword_simple.out +
+ +That works fine, but it is not very flexible. First, it only works with dynamic-size matrices of +single-precision floats; the function \c copyUpperTriangularPart() does not accept static-size matrices or +matrices with double-precision numbers. Second, if you use an expression such as +mat.topLeftCorner(3,3) as the parameter \c src, then this is copied into a temporary variable of type +MatrixXf; this copy can be avoided. + +As explained in \ref TopicFunctionTakingEigenTypes, both issues can be resolved by making +\c copyUpperTriangularPart() accept any object of type MatrixBase. This leads to the following code: + + + + +
Example:Output:
+\include TemplateKeyword_flexible.cpp + +\verbinclude TemplateKeyword_flexible.out +
+ +The one line in the body of the function \c copyUpperTriangularPart() shows the second, more obscure use of +the \c template keyword in C++. Even though it may look strange, the \c template keywords are necessary +according to the standard. Without it, the compiler may reject the code with an error message like "no match +for operator<". + + +\section TopicTemplateKeywordExplanation Explanation + +The reason that the \c template keyword is necessary in the last example has to do with the rules for how +templates are supposed to be compiled in C++. The compiler has to check the code for correct syntax at the +point where the template is defined, without knowing the actual value of the template arguments (\c Derived1 +and \c Derived2 in the example). That means that the compiler cannot know that dst.triangularPart is +a member template and that the following < symbol is part of the delimiter for the template +parameter. Another possibility would be that dst.triangularPart is a member variable with the < +symbol refering to the operator<() function. In fact, the compiler should choose the second +possibility, according to the standard. If dst.triangularPart is a member template (as in our case), +the programmer should specify this explicitly with the \c template keyword and write dst.template +triangularPart. + +The precise rules are rather complicated, but ignoring some subtleties we can summarize them as follows: +- A dependent name is name that depends (directly or indirectly) on a template parameter. In the + example, \c dst is a dependent name because it is of type MatrixBase<Derived1> which depends + on the template parameter \c Derived1. +- If the code contains either one of the contructions xxx.yyy or xxx->yyy and \c xxx is a + dependent name and \c yyy refers to a member template, then the \c template keyword must be used before + \c yyy, leading to xxx.template yyy or xxx->template yyy. +- If the code contains the contruction xxx::yyy and \c xxx is a dependent name and \c yyy refers to a + member typedef, then the \c typename keyword must be used before the whole construction, leading to + typename xxx::yyy. + +As an example where the \c typename keyword is required, consider the following code in \ref TutorialSparse +for iterating over the non-zero entries of a sparse matrix type: + +\code +SparseMatrixType mat(rows,cols); +for (int k=0; k +void iterateOverSparseMatrix(const SparseMatrix& mat; +{ + for (int k=0; k::InnerIterator it(mat,k); it; ++it) + { + /* ... */ + } +} +\endcode + + +\section TopicTemplateKeywordResources Resources for further reading + +For more information and a fuller explanation of this topic, the reader may consult the following sources: +- The book "C++ Template Metaprogramming" by David Abrahams and Aleksey Gurtovoy contains a very good + explanation in Appendix B ("The typename and template Keywords") which formed the basis for this page. +- http://pages.cs.wisc.edu/~driscoll/typename.html +- http://www.parashift.com/c++-faq-lite/templates.html#faq-35.18 +- http://www.comeaucomputing.com/techtalk/templates/#templateprefix +- http://www.comeaucomputing.com/techtalk/templates/#typename + +*/ +} diff --git a/gtsam/3rdparty/Eigen/doc/Overview.dox b/gtsam/3rdparty/Eigen/doc/Overview.dox index 68e07ad63..2657c85bc 100644 --- a/gtsam/3rdparty/Eigen/doc/Overview.dox +++ b/gtsam/3rdparty/Eigen/doc/Overview.dox @@ -34,12 +34,15 @@ For a first contact with Eigen, the best place is to have a look at the \ref Get - \ref TopicLazyEvaluation - \ref TopicLinearAlgebraDecompositions - \ref TopicCustomizingEigen + - \ref TopicMultiThreading - \ref TopicPreprocessorDirectives - \ref TopicStorageOrders - \ref TopicInsideEigenExample - \ref TopicWritingEfficientProductExpression - \ref TopicClassHierarchy - \ref TopicFunctionTakingEigenTypes + - \ref TopicTemplateKeyword + - \ref TopicUsingIntelMKL - Topics related to alignment issues - \ref TopicUnalignedArrayAssert - \ref TopicFixedSizeVectorizable diff --git a/gtsam/3rdparty/Eigen/doc/QuickReference.dox b/gtsam/3rdparty/Eigen/doc/QuickReference.dox index e23ff7ce5..3310d390a 100644 --- a/gtsam/3rdparty/Eigen/doc/QuickReference.dox +++ b/gtsam/3rdparty/Eigen/doc/QuickReference.dox @@ -412,8 +412,8 @@ array1 <= array2 array1 >= array2 array1 <= scalar array1 >= scalar array1 == array2 array1 != array2 array1 == scalar array1 != scalar \endcode Trigo, power, and \n misc functions \n and the STL variants\code -array1.min(array2) std::min(array1,array2) -array1.max(array2) std::max(array1,array2) +array1.min(array2) +array1.max(array2) array1.abs2() array1.abs() std::abs(array1) array1.sqrt() std::sqrt(array1) @@ -440,10 +440,10 @@ Eigen provides several reduction methods such as: \link DenseBase::sum() sum() \endlink, \link DenseBase::prod() prod() \endlink, \link MatrixBase::trace() trace() \endlink \matrixworld, \link MatrixBase::norm() norm() \endlink \matrixworld, \link MatrixBase::squaredNorm() squaredNorm() \endlink \matrixworld, -\link DenseBase::all() all() \endlink \redstar,and \link DenseBase::any() any() \endlink \redstar. +\link DenseBase::all() all() \endlink, and \link DenseBase::any() any() \endlink. All reduction operations can be done matrix-wise, -\link DenseBase::colwise() column-wise \endlink \redstar or -\link DenseBase::rowwise() row-wise \endlink \redstar. Usage example: +\link DenseBase::colwise() column-wise \endlink or +\link DenseBase::rowwise() row-wise \endlink. Usage example:
\code 5 3 1 @@ -586,6 +586,9 @@ mat3 = mat1 * diag1.inverse() TriangularView gives a view on a triangular part of a dense matrix and allows to perform optimized operations on it. The opposite triangular part is never referenced and can be used to store other information. +\note The .triangularView() template member function requires the \c template keyword if it is used on an +object of a type that depends on a template parameter; see \ref TopicTemplateKeyword for details. +
OperationCode
@@ -630,6 +633,9 @@ Just as for triangular matrix, you can reference any triangular part of a square matrix and perform special and optimized operations. Again the opposite triangular part is never referenced and can be used to store other information. +\note The .selfadjointView() template member function requires the \c template keyword if it is used on an +object of a type that depends on a template parameter; see \ref TopicTemplateKeyword for details. + - + @@ -94,7 +94,7 @@ namespace Eigen { - + @@ -132,7 +132,7 @@ namespace Eigen { - + @@ -245,6 +245,10 @@ namespace Eigen {
Blocking
Means the algorithm can work per block, whence guaranteeing a good scaling of the performance for large matrices.
+
Implicit Multi Threading (MT)
+
Means the algorithm can take advantage of multicore processors via OpenMP. "Implicit" means the algortihm itself is not parallelized, but that it relies on parallelized matrix-matrix product rountines.
+
Explicit Multi Threading (MT)
+
Means the algorithm is explicitely parallelized to take advantage of multicore processors via OpenMP.
Meta-unroller
Means the algorithm is automatically and explicitly unrolled for very small fixed size matrices.
diff --git a/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox new file mode 100644 index 000000000..f7d082668 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox @@ -0,0 +1,46 @@ +namespace Eigen { + +/** \page TopicMultiThreading Eigen and multi-threading + +\section TopicMultiThreading_MakingEigenMT Make Eigen run in parallel + +Some Eigen's algorithms can exploit the multiple cores present in your hardware. To this end, it is enough to enable OpenMP on your compiler, for instance: + * GCC: \c -fopenmp + * ICC: \c -openmp + * MSVC: check the respective option in the build properties. +You can control the number of thread that will be used using either the OpenMP API or Eiegn's API using the following priority: +\code + OMP_NUM_THREADS=n ./my_program + omp_set_num_threads(n); + Eigen::setNbThreads(n); +\endcode +Unless setNbThreads has been called, Eigen uses the number of threads specified by OpenMP. You can restore this bahavior by calling \code setNbThreads(0); \endcode +You can query the number of threads that will be used with: +\code +n = Eigen::nbThreads(n); +\endcode +You can disable Eigen's multi threading at compile time by defining the EIGEN_DONT_PARALLELIZE preprocessor token. + +Currently, the following algorithms can make use of multi-threading: + * general matrix - matrix products + * PartialPivLU + +\section TopicMultiThreading_UsingEigenWithMT Using Eigen in a multi-threaded application + +In the case your own application is multithreaded, and multiple threads make calls to Eigen, then you have to initialize Eigen by calling the following routine \b before creating the threads: +\code +#include + +int main(int argc, char** argv) +{ + Eigen::initParallel(); + + ... +} +\endcode + +In the case your application is parallelized with OpenMP, you might want to disable Eigen's own parallization as detailed in the previous section. + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/TutorialSparse_example_details.dox b/gtsam/3rdparty/Eigen/doc/TutorialSparse_example_details.dox new file mode 100644 index 000000000..0438da8bb --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/TutorialSparse_example_details.dox @@ -0,0 +1,4 @@ +/** +\page TutorialSparse_example_details +\include Tutorial_sparse_example_details.cpp +*/ diff --git a/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox new file mode 100644 index 000000000..379ee3ffd --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox @@ -0,0 +1,168 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + Copyright (C) 2011 Gael Guennebaud + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Documentation on the use of Intel MKL through Eigen + ******************************************************************************** +*/ + +namespace Eigen { + +/** \page TopicUsingIntelMKL Using Intel® Math Kernel Library from Eigen + +\section TopicUsingIntelMKL_Intro Eigen and Intel® Math Kernel Library (Intel® MKL) + +Since Eigen version 3.1 and later, users can benefit from built-in Intel MKL optimizations with an installed copy of Intel MKL 10.3 (or later). + Intel MKL provides highly optimized multi-threaded mathematical routines for x86-compatible architectures. +Intel MKL is available on Linux, Mac and Windows for both Intel64 and IA32 architectures. + +\warning Be aware that Intel® MKL is a proprietary software. It is the responsibility of the users to buy MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL. As a consequence, this also means that Eigen has to be used through the LGPL3+ license. + +Using Intel MKL through Eigen is easy: +-# define the \c EIGEN_USE_MKL_ALL macro before including any Eigen's header +-# link your program to MKL libraries (see the MKL linking advisor) +-# on a 64bits system, you must use the LP64 interface (not the ILP64 one) + +When doing so, a number of Eigen's algorithms are silently substituted with calls to Intel MKL routines. +These substitutions apply only for \b Dynamic \b or \b large enough objects with one of the following four standard scalar types: \c float, \c double, \c complex, and \c complex. +Operations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms. + +In addition you can coarsely select choose which parts will be substituted by defining one or multiple of the following macros: + +
OperationCode
diff --git a/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox b/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox new file mode 100644 index 000000000..7d6eb0fa9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox @@ -0,0 +1,198 @@ +namespace Eigen { +/** \page SparseQuickRefPage Quick reference guide for sparse matrices + +\b Table \b of \b contents + - \ref Constructors + - \ref SparseMatrixInsertion + - \ref SparseBasicInfos + - \ref SparseBasicOps + - \ref SparseInterops + - \ref sparsepermutation + - \ref sparsesubmatrices + - \ref sparseselfadjointview +\n + +
+ +In this page, we give a quick summary of the main operations available for sparse matrices in the class SparseMatrix. First, it is recommended to read first the introductory tutorial at \ref TutorialSparse. The important point to have in mind when working on sparse matrices is how they are stored : +i.e either row major or column major. The default is column major. Most arithmetic operations on sparse matrices will assert that they have the same storage order. Moreover, when interacting with external libraries that are not yet supported by Eigen, it is important to know how to send the required matrix pointers. + +\section Constructors Constructors and assignments +SparseMatrix is the core class to build and manipulate sparse matrices in Eigen. It takes as template parameters the Scalar type and the storage order, either RowMajor or ColumnMajor. The default is ColumnMajor. + +\code + SparseMatrix sm1(1000,1000); // 1000x1000 compressed sparse matrix of double. + SparseMatrix,RowMajor> sm2; // Compressed row major matrix of complex double. +\endcode +The copy constructor and assignment can be used to convert matrices from a storage order to another +\code + SparseMatrix sm1; + // Eventually fill the matrix sm1 ... + SparseMatrix sm2(sm1), sm3; // Initialize sm2 with sm1. + sm3 = sm1; // Assignment and evaluations modify the storage order. + \endcode + +\section SparseMatrixInsertion Allocating and inserting values +resize() and reserve() are used to set the size and allocate space for nonzero elements + \code + sm1.resize(m,n); //Change sm to a mxn matrix. + sm1.reserve(nnz); // Allocate room for nnz nonzeros elements. + \endcode +Note that when calling reserve(), it is not required that nnz is the exact number of nonzero elements in the final matrix. However, an exact estimation will avoid multiple reallocations during the insertion phase. + +Insertions of values in the sparse matrix can be done directly by looping over nonzero elements and use the insert() function +\code +// Direct insertion of the value v_ij; + sm1.insert(i, j) = v_ij; // It is assumed that v_ij does not already exist in the matrix. +\endcode + +After insertion, a value at (i,j) can be modified using coeffRef() +\code + // Update the value v_ij + sm1.coeffRef(i,j) = v_ij; + sm1.coeffRef(i,j) += v_ij; + sm1.coeffRef(i,j) -= v_ij; + ... +\endcode + +The recommended way to insert values is to build a list of triplets (row, col, val) and then call setFromTriplets(). +\code + sm1.setFromTriplets(TripletList.begin(), TripletList.end()); +\endcode +A complete example is available at \ref TutorialSparseFilling. + +The following functions can be used to set constant or random values in the matrix. +\code + sm1.setZero(); // Reset the matrix with zero elements + ... +\endcode + +\section SparseBasicInfos Matrix properties +Beyond the functions rows() and cols() that are used to get the number of rows and columns, there are some useful functions that are available to easily get some informations from the matrix. + + + + +
\code + sm1.rows(); // Number of rows + sm1.cols(); // Number of columns + sm1.nonZeros(); // Number of non zero values + sm1.outerSize(); // Number of columns (resp. rows) for a column major (resp. row major ) + sm1.innerSize(); // Number of rows (resp. columns) for a row major (resp. column major) + sm1.norm(); // (Euclidian ??) norm of the matrix + sm1.squaredNorm(); // + sm1.isVector(); // Check if sm1 is a sparse vector or a sparse matrix + ... + \endcode
+ +\section SparseBasicOps Arithmetic operations +It is easy to perform arithmetic operations on sparse matrices provided that the dimensions are adequate and that the matrices have the same storage order. Note that the evaluation can always be done in a matrix with a different storage order. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Operations Code Notes
add subtract \code + sm3 = sm1 + sm2; + sm3 = sm1 - sm2; + sm2 += sm1; + sm2 -= sm1; \endcode + + sm1 and sm2 should have the same storage order +
+ scalar product\code + sm3 = sm1 * s1; sm3 *= s1; + sm3 = s1 * sm1 + s2 * sm2; sm3 /= s1;\endcode + + Many combinations are possible if the dimensions and the storage order agree. +
Product \code + sm3 = sm1 * sm2; + dm2 = sm1 * dm1; + dv2 = sm1 * dv1; + \endcode +
transposition, adjoint \code + sm2 = sm1.transpose(); + sm2 = sm1.adjoint(); + \endcode + Note that the transposition change the storage order. There is no support for transposeInPlace(). +
+ Component-wise ops + \code + sm1.cwiseProduct(sm2); + sm1.cwiseQuotient(sm2); + sm1.cwiseMin(sm2); + sm1.cwiseMax(sm2); + sm1.cwiseAbs(); + sm1.cwiseSqrt(); + \endcode + sm1 and sm2 should have the same storage order +
+ + +\section SparseInterops Low-level storage +There are a set of low-levels functions to get the standard compressed storage pointers. The matrix should be in compressed mode which can be checked by calling isCompressed(); makeCompressed() should do the job otherwise. +\code + // Scalar pointer to the values of the matrix, size nnz + sm1.valuePtr(); + // Index pointer to get the row indices (resp. column indices) for column major (resp. row major) matrix, size nnz + sm1.innerIndexPtr(); + // Index pointer to the beginning of each row (resp. column) in valuePtr() and innerIndexPtr() for column major (row major). The size is outersize()+1; + sm1.outerIndexPtr(); +\endcode +These pointers can therefore be easily used to send the matrix to some external libraries/solvers that are not yet supported by Eigen. + +\section sparsepermutation Permutations, submatrices and Selfadjoint Views +In many cases, it is necessary to reorder the rows and/or the columns of the sparse matrix for several purposes : fill-in reducing during matrix decomposition, better data locality for sparse matrix-vector products... The class PermutationMatrix is available to this end. + \code + PermutationMatrix perm; + // Reserve and fill the values of perm; + perm.inverse(n); // Compute eventually the inverse permutation + sm1.twistedBy(perm) //Apply the permutation on rows and columns + sm2 = sm1 * perm; // ??? Apply the permutation on columns ???; + sm2 = perm * sm1; // ??? Apply the permutation on rows ???; + \endcode + +\section sparsesubmatrices Sub-matrices +The following functions are useful to extract a block of rows (resp. columns) from a row-major (resp. column major) sparse matrix. Note that because of the particular storage, it is not ?? efficient ?? to extract a submatrix comprising a certain number of subrows and subcolumns. + \code + sm1.innerVector(outer); // Returns the outer -th column (resp. row) of the matrix if sm is col-major (resp. row-major) + sm1.innerVectors(outer); // Returns the outer -th column (resp. row) of the matrix if mat is col-major (resp. row-major) + sm1.middleRows(start, numRows); // For row major matrices, get a range of numRows rows + sm1.middleCols(start, numCols); // For column major matrices, get a range of numCols cols + \endcode + Examples : + +\section sparseselfadjointview Sparse triangular and selfadjoint Views + \code + sm2 = sm1.triangularview(); // Get the lower triangular part of the matrix. + dv2 = sm1.triangularView().solve(dv1); // Solve the linear system with the uppper triangular part. + sm2 = sm1.selfadjointview(); // Build a selfadjoint matrix from the lower part of sm1. + \endcode + + +*/ +} diff --git a/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox b/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox index 5684a495f..faa564b93 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox @@ -34,7 +34,7 @@ namespace Eigen {
- Yes ExcellentBlockingBlocking, Implicit MT
- Yes ExcellentBlocking \n Soon: meta unrollerBlocking
Eigenvalues/vectors - GoodSoon: specializations for 2x2 and 3x3Closed forms for 2x2 and 3x3
+ + + + + +
\c EIGEN_USE_BLAS Enables the use of external BLAS level 2 and 3 routines (currently works with Intel MKL only)
\c EIGEN_USE_LAPACKE Enables the use of external Lapack routines via the Intel Lapacke C interface to Lapack (currently works with Intel MKL only)
\c EIGEN_USE_LAPACKE_STRICT Same as \c EIGEN_USE_LAPACKE but algorithm of lower robustness are disabled. This currently concerns only JacobiSVD which otherwise would be replaced by \c gesvd that is less robust than Jacobi rotations.
\c EIGEN_USE_MKL_VML Enables the use of Intel VML (vector operations)
\c EIGEN_USE_MKL_ALL Defines \c EIGEN_USE_BLAS, \c EIGEN_USE_LAPACKE, and \c EIGEN_USE_MKL_VML
+ +Finally, the PARDISO sparse solver shipped with Intel MKL can be used through the \ref PardisoLU, \ref PardisoLLT and \ref PardisoLDLT classes of the \ref PARDISOSupport_Module. + + +\section TopicUsingIntelMKL_SupportedFeatures List of supported features + +The breadth of Eigen functionality covered by Intel MKL is listed in the table below. + + + + + + + + + + + +
Functional domainCode exampleMKL routines
Matrix-matrix operations \n \c EIGEN_USE_BLAS \code +m1*m2.transpose(); +m1.selfadjointView()*m2; +m1*m2.triangularView(); +m1.selfadjointView().rankUpdate(m2,1.0); +\endcode\code +?gemm +?symm/?hemm +?trmm +dsyrk/ssyrk +\endcode
Matrix-vector operations \n \c EIGEN_USE_BLAS \code +m1.adjoint()*b; +m1.selfadjointView()*b; +m1.triangularView()*b; +\endcode\code +?gemv +?symv/?hemv +?trmv +\endcode
LU decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +v1 = m1.lu().solve(v2); +\endcode\code +?getrf +\endcode
Cholesky decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +v1 = m2.selfadjointView().llt().solve(v2); +\endcode\code +?potrf +\endcode
QR decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +m1.householderQr(); +m1.colPivHouseholderQr(); +\endcode\code +?geqrf +?geqp3 +\endcode
Singular value decomposition \n \c EIGEN_USE_LAPACKE \code +JacobiSVD svd; +svd.compute(m1, ComputeThinV); +\endcode\code +?gesvd +\endcode
Eigen-value decompositions \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +EigenSolver es(m1); +ComplexEigenSolver ces(m1); +SelfAdjointEigenSolver saes(m1+m1.transpose()); +GeneralizedSelfAdjointEigenSolver + gsaes(m1+m1.transpose(),m2+m2.transpose()); +\endcode\code +?gees +?gees +?syev/?heev +?syev/?heev, +?potrf +\endcode
Schur decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +RealSchur schurR(m1); +ComplexSchur schurC(m1); +\endcode\code +?gees +\endcode
Vector Math \n \c EIGEN_USE_MKL_VML \code +v2=v1.array().sin(); +v2=v1.array().asin(); +v2=v1.array().cos(); +v2=v1.array().acos(); +v2=v1.array().tan(); +v2=v1.array().exp(); +v2=v1.array().log(); +v2=v1.array().sqrt(); +v2=v1.array().square(); +v2=v1.array().pow(1.5); +\endcode\code +v?Sin +v?Asin +v?Cos +v?Acos +v?Tan +v?Exp +v?Ln +v?Sqrt +v?Sqr +v?Powx +\endcode
+In the examples, m1 and m2 are dense matrices and v1 and v2 are dense vectors. + + +\section TopicUsingIntelMKL_Links Links +- Intel MKL can be purchased and downloaded here. +- Intel MKL is also bundled with Intel Composer XE. + + +*/ + +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/eigendoxy.css b/gtsam/3rdparty/Eigen/doc/eigendoxy.css index e62958831..c6c16286d 100644 --- a/gtsam/3rdparty/Eigen/doc/eigendoxy.css +++ b/gtsam/3rdparty/Eigen/doc/eigendoxy.css @@ -904,3 +904,8 @@ div.eimainmenu { h3.version { text-align: center; } + + +td.width20em p.endtd { + width: 20em; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_flexible.cpp b/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_flexible.cpp new file mode 100644 index 000000000..9d85292dd --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_flexible.cpp @@ -0,0 +1,22 @@ +#include +#include + +using namespace Eigen; + +template +void copyUpperTriangularPart(MatrixBase& dst, const MatrixBase& src) +{ + /* Note the 'template' keywords in the following line! */ + dst.template triangularView() = src.template triangularView(); +} + +int main() +{ + MatrixXi m1 = MatrixXi::Ones(5,5); + MatrixXi m2 = MatrixXi::Random(4,4); + std::cout << "m2 before copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; + copyUpperTriangularPart(m2, m1.topLeftCorner(4,4)); + std::cout << "m2 after copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_simple.cpp b/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_simple.cpp new file mode 100644 index 000000000..6998c1769 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/TemplateKeyword_simple.cpp @@ -0,0 +1,20 @@ +#include +#include + +using namespace Eigen; + +void copyUpperTriangularPart(MatrixXf& dst, const MatrixXf& src) +{ + dst.triangularView() = src.triangularView(); +} + +int main() +{ + MatrixXf m1 = MatrixXf::Ones(4,4); + MatrixXf m2 = MatrixXf::Random(4,4); + std::cout << "m2 before copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; + copyUpperTriangularPart(m2, m1); + std::cout << "m2 after copy:" << std::endl; + std::cout << m2 << std::endl << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp b/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp index 9959c7909..d87c96ab1 100644 --- a/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp +++ b/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp @@ -13,7 +13,7 @@ int main() v << 0,1,2,3; //add v to each row of m - mat.rowwise() += v; + mat.rowwise() += v.transpose(); std::cout << "Broadcasting result: " << std::endl; std::cout << mat << std::endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_and.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_and.cpp new file mode 100644 index 000000000..df6b60d92 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_and.cpp @@ -0,0 +1,2 @@ +Array3d v(-1,2,1), w(-3,2,3); +cout << ((v lltOfA(A); // compute the Cholesky decomposition of A +MatrixXd L = lltOfA.matrixL(); // retrieve factor L in the decomposition +// The previous two lines can also be written as "L = A.llt().matrixL()" + +cout << "The Cholesky factor L is" << endl << L << endl; +cout << "To check this, let us compute L * L.transpose()" << endl; +cout << L * L.transpose() << endl; +cout << "This should equal the matrix A" << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in b/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in index 474542380..894cd526c 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in +++ b/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in @@ -1,10 +1,4 @@ -#include -#include -#include -#include -#include -#include -#include +#include #include using namespace Eigen; diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt new file mode 100644 index 000000000..eeeae1d2a --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt @@ -0,0 +1,20 @@ + +if(NOT EIGEN_TEST_NOQT) + find_package(Qt4) + if(QT4_FOUND) + include(${QT_USE_FILE}) + endif() +endif(NOT EIGEN_TEST_NOQT) + + +if(QT4_FOUND) + add_executable(Tutorial_sparse_example Tutorial_sparse_example.cpp Tutorial_sparse_example_details.cpp) + target_link_libraries(Tutorial_sparse_example ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY}) + + add_custom_command( + TARGET Tutorial_sparse_example + POST_BUILD + COMMAND Tutorial_sparse_example + ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg + ) +endif(QT4_FOUND) diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp new file mode 100644 index 000000000..002f19f01 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp @@ -0,0 +1,32 @@ +#include +#include + +typedef Eigen::SparseMatrix SpMat; // declares a column-major sparse matrix type of double +typedef Eigen::Triplet T; + +void buildProblem(std::vector& coefficients, Eigen::VectorXd& b, int n); +void saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename); + +int main(int argc, char** argv) +{ + int n = 300; // size of the image + int m = n*n; // number of unknows (=number of pixels) + + // Assembly: + std::vector coefficients; // list of non-zeros coefficients + Eigen::VectorXd b(m); // the right hand side-vector resulting from the constraints + buildProblem(coefficients, b, n); + + SpMat A(m,m); + A.setFromTriplets(coefficients.begin(), coefficients.end()); + + // Solving: + Eigen::SimplicialCholesky chol(A); // performs a Cholesky factorization of A + Eigen::VectorXd x = chol.solve(b); // use the factorization to solve for the given right hand side + + // Export the result to a file: + saveAsBitmap(x, n, argv[1]); + + return 0; +} + diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp new file mode 100644 index 000000000..8c3020b63 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp @@ -0,0 +1,44 @@ +#include +#include +#include + +typedef Eigen::SparseMatrix SpMat; // declares a column-major sparse matrix type of double +typedef Eigen::Triplet T; + +void insertCoefficient(int id, int i, int j, double w, std::vector& coeffs, + Eigen::VectorXd& b, const Eigen::VectorXd& boundary) +{ + int n = boundary.size(); + int id1 = i+j*n; + + if(i==-1 || i==n) b(id) -= w * boundary(j); // constrained coeffcieint + else if(j==-1 || j==n) b(id) -= w * boundary(i); // constrained coeffcieint + else coeffs.push_back(T(id,id1,w)); // unknown coefficient +} + +void buildProblem(std::vector& coefficients, Eigen::VectorXd& b, int n) +{ + b.setZero(); + Eigen::ArrayXd boundary = Eigen::ArrayXd::LinSpaced(n, 0,M_PI).sin().pow(2); + for(int j=0; j bits = (x*255).cast(); + QImage img(bits.data(), n,n,QImage::Format_Indexed8); + img.setColorCount(256); + for(int i=0;i<256;i++) img.setColor(i,qRgb(i,i,i)); + img.save(filename); +} diff --git a/gtsam/3rdparty/Eigen/lapack/CMakeLists.txt b/gtsam/3rdparty/Eigen/lapack/CMakeLists.txt index 96d6a416d..062845a3f 100644 --- a/gtsam/3rdparty/Eigen/lapack/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/lapack/CMakeLists.txt @@ -1,27 +1,23 @@ project(EigenLapack CXX) -if( NOT DEFINED EIGEN_Fortran_COMPILER_WORKS OR EIGEN_Fortran_COMPILER_WORKS) +include("../cmake/language_support.cmake") +workaround_9220(Fortran EIGEN_Fortran_COMPILER_WORKS) + +if(EIGEN_Fortran_COMPILER_WORKS) enable_language(Fortran OPTIONAL) - - if(CMAKE_Fortran_COMPILER_WORKS) - set(EIGEN_Fortran_COMPILER_WORKS TRUE CACHE INTERNAL "workaround cmake's enable_language issue") - else() - set(EIGEN_Fortran_COMPILER_WORKS FALSE CACHE INTERNAL "workaround cmake's enable_language issue") - endif() - endif() -if(CMAKE_Fortran_COMPILER_WORKS) - add_custom_target(lapack) include_directories(../blas) set(EigenLapack_SRCS -single.cpp double.cpp complex_single.cpp complex_double.cpp +single.cpp double.cpp complex_single.cpp complex_double.cpp ../blas/xerbla.cpp ) +if(EIGEN_Fortran_COMPILER_WORKS) + get_filename_component(eigen_full_path_to_reference_to_reference_lapack "./reference/" ABSOLUTE) if(EXISTS ${eigen_full_path_to_reference_to_reference_lapack}) set(EigenLapack_SRCS ${EigenLapack_SRCS} @@ -357,6 +353,8 @@ reference/ctbcon.f reference/dormhr.f reference/sla_ ) endif() +endif(EIGEN_Fortran_COMPILER_WORKS) + add_library(eigen_lapack_static ${EigenLapack_SRCS}) add_library(eigen_lapack SHARED ${EigenLapack_SRCS}) @@ -365,14 +363,12 @@ if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO) target_link_libraries(eigen_lapack ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) endif() -# add_dependencies(lapack eigen_lapack eigen_lapack_static) -add_dependencies(lapack eigen_lapack_static) - -# install(TARGETS eigen_lapack -# RUNTIME DESTINATION bin -# LIBRARY DESTINATION lib -# ARCHIVE DESTINATION lib) +add_dependencies(lapack eigen_lapack eigen_lapack_static) +install(TARGETS eigen_lapack eigen_lapack_static + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) # add_subdirectory(testing) -endif(CMAKE_Fortran_COMPILER_WORKS) + diff --git a/gtsam/3rdparty/Eigen/lapack/cholesky.cpp b/gtsam/3rdparty/Eigen/lapack/cholesky.cpp index c3a72c3c5..c51a8a29b 100644 --- a/gtsam/3rdparty/Eigen/lapack/cholesky.cpp +++ b/gtsam/3rdparty/Eigen/lapack/cholesky.cpp @@ -41,8 +41,8 @@ EIGEN_LAPACK_FUNC(potrf,(char* uplo, int *n, RealScalar *pa, int *lda, int *info Scalar* a = reinterpret_cast(pa); MatrixType A(a,*n,*n,*lda); int ret; - if(UPLO(*uplo)==UP) ret = internal::llt_inplace::blocked(A); - else ret = internal::llt_inplace::blocked(A); + if(UPLO(*uplo)==UP) ret = internal::llt_inplace::blocked(A); + else ret = internal::llt_inplace::blocked(A); if(ret>=0) *info = ret+1; diff --git a/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs b/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs index e97e9ab8f..921d600ed 100644 --- a/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs +++ b/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs @@ -8,14 +8,15 @@ USER=${USER:-'orzel'} #ulimit -v 1024000 # step 1 : build -# todo if 'build is not there, create one: mkdir build -p (cd build && cmake .. && make doc) || { echo "make failed"; exit 1; } -#todo: n+1 where n = number of cpus #step 2 : upload -# (the '/' at the end of path are very important, see rsync documentation) -rsync -az --no-p build/doc/html/ $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/dox-3.0/ || { echo "upload failed"; exit 1; } +# (the '/' at the end of path is very important, see rsync documentation) +rsync -az --no-p --delete build/doc/html/ $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/dox-devel/ || { echo "upload failed"; exit 1; } + +#step 3 : fix the perm +ssh $USER@ssh.tuxfamily.org 'chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/dox-devel' || { echo "perm failed"; exit 1; } echo "Uploaded successfully" diff --git a/gtsam/3rdparty/Eigen/test/CMakeLists.txt b/gtsam/3rdparty/Eigen/test/CMakeLists.txt index fab7de0d4..6f8fc4ae3 100644 --- a/gtsam/3rdparty/Eigen/test/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/test/CMakeLists.txt @@ -1,17 +1,90 @@ -find_package(GSL) -if(GSL_FOUND AND GSL_VERSION_MINOR LESS 9) - set(GSL_FOUND "") -endif(GSL_FOUND AND GSL_VERSION_MINOR LESS 9) -if(GSL_FOUND) - add_definitions("-DHAS_GSL" ${GSL_DEFINITIONS}) - include_directories(${GSL_INCLUDE_DIR}) - ei_add_property(EIGEN_TESTED_BACKENDS "GSL, ") -else(GSL_FOUND) - ei_add_property(EIGEN_MISSING_BACKENDS "GSL, ") - set(GSL_LIBRARIES "") -endif(GSL_FOUND) +# generate split test header file +message(STATUS ${CMAKE_CURRENT_BINARY_DIR}) +file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h "") +foreach(i RANGE 1 999) + file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h + "#ifdef EIGEN_TEST_PART_${i}\n" + "#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\n" + "#else\n" + "#define CALL_SUBTEST_${i}(FUNC)\n" + "#endif\n\n" + ) +endforeach() +# configure blas/lapack (use Eigen's ones) +set(BLAS_FOUND TRUE) +set(LAPACK_FOUND TRUE) +set(BLAS_LIBRARIES eigen_blas) +set(LAPACK_LIBRARIES eigen_lapack) + +set(EIGEN_TEST_MATRIX_DIR "" CACHE STRING "Enable testing of realword sparse matrices contained in the specified path") +if(EIGEN_TEST_MATRIX_DIR) + if(NOT WIN32) + message(STATUS "Test realworld sparse matrices: ${EIGEN_TEST_MATRIX_DIR}") + add_definitions( -DTEST_REAL_CASES="${EIGEN_TEST_MATRIX_DIR}" ) + else(NOT WIN32) + message(STATUS "REAL CASES CAN NOT BE CURRENTLY TESTED ON WIN32") + endif(NOT WIN32) +endif(EIGEN_TEST_MATRIX_DIR) + +set(SPARSE_LIBS " ") + +find_package(Cholmod) +if(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND) + add_definitions("-DEIGEN_CHOLMOD_SUPPORT") + include_directories(${CHOLMOD_INCLUDES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + set(CHOLMOD_ALL_LIBS ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + ei_add_property(EIGEN_TESTED_BACKENDS "Cholmod, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "Cholmod, ") +endif() + +find_package(Umfpack) +if(UMFPACK_FOUND AND BLAS_FOUND) + add_definitions("-DEIGEN_UMFPACK_SUPPORT") + include_directories(${UMFPACK_INCLUDES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) + set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) + ei_add_property(EIGEN_TESTED_BACKENDS "UmfPack, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "UmfPack, ") +endif() + +find_package(SuperLU) +if(SUPERLU_FOUND AND BLAS_FOUND) + add_definitions("-DEIGEN_SUPERLU_SUPPORT") + include_directories(${SUPERLU_INCLUDES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) + set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) + ei_add_property(EIGEN_TESTED_BACKENDS "SuperLU, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "SuperLU, ") +endif() + + +find_package(Pastix) +find_package(Scotch) +find_package(Metis) +if(PASTIX_FOUND AND BLAS_FOUND) + add_definitions("-DEIGEN_PASTIX_SUPPORT") + include_directories(${PASTIX_INCLUDES}) + if(SCOTCH_FOUND) + include_directories(${SCOTCH_INCLUDES}) + set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES}) + elseif(METIS_FOUND) + include_directories(${METIS_INCLUDES}) + set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES}) + else(SCOTCH_FOUND) + ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") + endif(SCOTCH_FOUND) + set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES} ${ORDERING_LIBRARIES} ${BLAS_LIBRARIES}) + set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES} ${BLAS_LIBRARIES}) + ei_add_property(EIGEN_TESTED_BACKENDS "PaStiX, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") +endif() option(EIGEN_TEST_NOQT "Disable Qt support in unit tests" OFF) if(NOT EIGEN_TEST_NOQT) @@ -75,7 +148,7 @@ ei_add_test(product_mmtr) ei_add_test(product_notemporary) ei_add_test(stable_norm) ei_add_test(bandmatrix) -ei_add_test(cholesky "" "${GSL_LIBRARIES}") +ei_add_test(cholesky) ei_add_test(lu) ei_add_test(determinant) ei_add_test(inverse) @@ -86,8 +159,8 @@ ei_add_test(upperbidiagonalization) ei_add_test(hessenberg) ei_add_test(schur_real) ei_add_test(schur_complex) -ei_add_test(eigensolver_selfadjoint "" "${GSL_LIBRARIES}") -ei_add_test(eigensolver_generic "" "${GSL_LIBRARIES}") +ei_add_test(eigensolver_selfadjoint) +ei_add_test(eigensolver_generic) ei_add_test(eigensolver_complex) ei_add_test(jacobi) ei_add_test(jacobisvd) @@ -110,12 +183,13 @@ endif(QT4_FOUND) ei_add_test(sparse_vector) ei_add_test(sparse_basic) ei_add_test(sparse_product) -ei_add_test(sparse_solvers "" "${SPARSE_LIBS}") +ei_add_test(sparse_solvers) ei_add_test(umeyama) ei_add_test(householder) ei_add_test(swap) ei_add_test(conservative_resize) ei_add_test(permutationmatrices) +ei_add_test(sparse_permutations) ei_add_test(eigen2support) ei_add_test(nullary) ei_add_test(nesting_ops "${CMAKE_CXX_FLAGS_DEBUG}") @@ -123,6 +197,32 @@ ei_add_test(zerosized) ei_add_test(dontalign) ei_add_test(sizeoverflow) ei_add_test(prec_inverse_4x4) +ei_add_test(vectorwiseop) + +ei_add_test(simplicial_cholesky) +ei_add_test(conjugate_gradient) +ei_add_test(bicgstab) + + +if(UMFPACK_FOUND) + ei_add_test(umfpack_support "" "${UMFPACK_ALL_LIBS}") +endif() + +if(SUPERLU_FOUND) + ei_add_test(superlu_support "" "${SUPERLU_ALL_LIBS}") +endif() + +if(CHOLMOD_FOUND) + ei_add_test(cholmod_support "" "${CHOLMOD_ALL_LIBS}") +endif() + +if(PARDISO_FOUND) + ei_add_test(pardiso_support "" "${PARDISO_ALL_LIBS}") +endif() + +if(PASTIX_FOUND AND (SCOTCH_FOUND OR METIS_FOUND)) + ei_add_test(pastix_support "" "${PASTIX_ALL_LIBS}") +endif() string(TOLOWER "${CMAKE_CXX_COMPILER}" cmake_cxx_compiler_tolower) if(cmake_cxx_compiler_tolower MATCHES "qcc") diff --git a/gtsam/3rdparty/Eigen/test/adjoint.cpp b/gtsam/3rdparty/Eigen/test/adjoint.cpp index d8d2aaa1b..140283477 100644 --- a/gtsam/3rdparty/Eigen/test/adjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/adjoint.cpp @@ -43,8 +43,6 @@ template void adjoint(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols), m3(rows, cols), - mzero = MatrixType::Zero(rows, cols), - identity = SquareMatrixType::Identity(rows, rows), square = SquareMatrixType::Random(rows, rows); VectorType v1 = VectorType::Random(rows), v2 = VectorType::Random(rows), @@ -65,15 +63,23 @@ template void adjoint(const MatrixType& m) // check basic properties of dot, norm, norm2 typedef typename NumTraits::Real RealScalar; - RealScalar ref = NumTraits::IsInteger ? 0 : (std::max)((s1 * v1 + s2 * v2).norm(),v3.norm()); + RealScalar ref = NumTraits::IsInteger ? RealScalar(0) : (std::max)((s1 * v1 + s2 * v2).norm(),v3.norm()); VERIFY(test_isApproxWithRef((s1 * v1 + s2 * v2).dot(v3), internal::conj(s1) * v1.dot(v3) + internal::conj(s2) * v2.dot(v3), ref)); VERIFY(test_isApproxWithRef(v3.dot(s1 * v1 + s2 * v2), s1*v3.dot(v1)+s2*v3.dot(v2), ref)); VERIFY_IS_APPROX(internal::conj(v1.dot(v2)), v2.dot(v1)); VERIFY_IS_APPROX(internal::real(v1.dot(v1)), v1.squaredNorm()); - if(!NumTraits::IsInteger) + if(!NumTraits::IsInteger) { VERIFY_IS_APPROX(v1.squaredNorm(), v1.norm() * v1.norm()); + // check normalized() and normalize() + VERIFY_IS_APPROX(v1, v1.norm() * v1.normalized()); + v3 = v1; + v3.normalize(); + VERIFY_IS_APPROX(v1, v1.norm() * v3); + VERIFY_IS_APPROX(v3, v1.normalized()); + VERIFY_IS_APPROX(v3.norm(), RealScalar(1)); + } VERIFY_IS_MUCH_SMALLER_THAN(internal::abs(vzero.dot(v1)), static_cast(1)); - + // check compatibility of dot and adjoint ref = NumTraits::IsInteger ? 0 : (std::max)((std::max)(v1.norm(),v2.norm()),(std::max)((square * v2).norm(),(square.adjoint() * v1).norm())); @@ -119,11 +125,11 @@ void test_adjoint() CALL_SUBTEST_1( adjoint(Matrix()) ); CALL_SUBTEST_2( adjoint(Matrix3d()) ); CALL_SUBTEST_3( adjoint(Matrix4f()) ); - CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random(1,50), internal::random(1,50))) ); - CALL_SUBTEST_5( adjoint(MatrixXi(internal::random(1,50), internal::random(1,50))) ); - CALL_SUBTEST_6( adjoint(MatrixXf(internal::random(1,50), internal::random(1,50))) ); + CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_5( adjoint(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( adjoint(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } - // test a large matrix only once + // test a large static matrix only once CALL_SUBTEST_7( adjoint(Matrix()) ); #ifdef EIGEN_TEST_PART_4 diff --git a/gtsam/3rdparty/Eigen/test/array.cpp b/gtsam/3rdparty/Eigen/test/array.cpp index 6964075ea..912c28c88 100644 --- a/gtsam/3rdparty/Eigen/test/array.cpp +++ b/gtsam/3rdparty/Eigen/test/array.cpp @@ -43,7 +43,7 @@ template void array(const ArrayType& m) RowVectorType rv1 = RowVectorType::Random(cols); Scalar s1 = internal::random(), - s2 = internal::random(); + s2 = internal::random(); // scalar addition VERIFY_IS_APPROX(m1 + s1, s1 + m1); @@ -149,6 +149,12 @@ template void comparisons(const ArrayType& m) // count VERIFY(((m1.abs()+1)>RealScalar(0.1)).count() == rows*cols); + // and/or + VERIFY( (m1RealScalar(0)).count() == 0); + VERIFY( (m1=RealScalar(0)).count() == rows*cols); + RealScalar a = m1.abs().mean(); + VERIFY( (m1<-a || m1>a).count() == (m1.abs()>a).count()); + typedef Array ArrayOfIndices; // TODO allows colwise/rowwise for array @@ -169,7 +175,9 @@ template void array_real(const ArrayType& m) m2 = ArrayType::Random(rows, cols), m3(rows, cols); - // these these are mostly to check possible compilation issues. + Scalar s1 = internal::random(); + + // these tests are mostly to check possible compilation issues. VERIFY_IS_APPROX(m1.sin(), std::sin(m1)); VERIFY_IS_APPROX(m1.sin(), internal::sin(m1)); VERIFY_IS_APPROX(m1.cos(), std::cos(m1)); @@ -180,7 +188,7 @@ template void array_real(const ArrayType& m) VERIFY_IS_APPROX(m1.acos(), internal::acos(m1)); VERIFY_IS_APPROX(m1.tan(), std::tan(m1)); VERIFY_IS_APPROX(m1.tan(), internal::tan(m1)); - + VERIFY_IS_APPROX(internal::cos(m1+RealScalar(3)*m2), internal::cos((m1+RealScalar(3)*m2).eval())); VERIFY_IS_APPROX(std::cos(m1+RealScalar(3)*m2), std::cos((m1+RealScalar(3)*m2).eval())); @@ -203,9 +211,67 @@ template void array_real(const ArrayType& m) VERIFY_IS_APPROX(m1.pow(2), m1.square()); VERIFY_IS_APPROX(std::pow(m1,2), m1.square()); + + ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2)); + VERIFY_IS_APPROX(std::pow(m1,exponents), m1.square()); + m3 = m1.abs(); VERIFY_IS_APPROX(m3.pow(RealScalar(0.5)), m3.sqrt()); VERIFY_IS_APPROX(std::pow(m3,RealScalar(0.5)), m3.sqrt()); + + // scalar by array division + const RealScalar tiny = std::sqrt(std::numeric_limits::epsilon()); + s1 += Scalar(tiny); + m1 += ArrayType::Constant(rows,cols,Scalar(tiny)); + VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse()); +} + +template void array_complex(const ArrayType& m) +{ + typedef typename ArrayType::Index Index; + + Index rows = m.rows(); + Index cols = m.cols(); + + ArrayType m1 = ArrayType::Random(rows, cols), + m2(rows, cols); + + for (Index i = 0; i < m.rows(); ++i) + for (Index j = 0; j < m.cols(); ++j) + m2(i,j) = std::sqrt(m1(i,j)); + + VERIFY_IS_APPROX(m1.sqrt(), m2); + VERIFY_IS_APPROX(m1.sqrt(), std::sqrt(m1)); + VERIFY_IS_APPROX(m1.sqrt(), internal::sqrt(m1)); +} + +template void min_max(const ArrayType& m) +{ + typedef typename ArrayType::Index Index; + typedef typename ArrayType::Scalar Scalar; + + Index rows = m.rows(); + Index cols = m.cols(); + + ArrayType m1 = ArrayType::Random(rows, cols); + + // min/max with array + Scalar maxM1 = m1.maxCoeff(); + Scalar minM1 = m1.minCoeff(); + + VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)(ArrayType::Constant(rows,cols, minM1))); + VERIFY_IS_APPROX(m1, (m1.min)(ArrayType::Constant(rows,cols, maxM1))); + + VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)(ArrayType::Constant(rows,cols, maxM1))); + VERIFY_IS_APPROX(m1, (m1.max)(ArrayType::Constant(rows,cols, minM1))); + + // min/max with scalar input + VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)( minM1)); + VERIFY_IS_APPROX(m1, (m1.min)( maxM1)); + + VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)( maxM1)); + VERIFY_IS_APPROX(m1, (m1.max)( minM1)); + } void test_array() @@ -214,22 +280,32 @@ void test_array() CALL_SUBTEST_1( array(Array()) ); CALL_SUBTEST_2( array(Array22f()) ); CALL_SUBTEST_3( array(Array44d()) ); - CALL_SUBTEST_4( array(ArrayXXcf(3, 3)) ); - CALL_SUBTEST_5( array(ArrayXXf(8, 12)) ); - CALL_SUBTEST_6( array(ArrayXXi(8, 12)) ); + CALL_SUBTEST_4( array(ArrayXXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_5( array(ArrayXXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( array(ArrayXXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( comparisons(Array()) ); CALL_SUBTEST_2( comparisons(Array22f()) ); CALL_SUBTEST_3( comparisons(Array44d()) ); - CALL_SUBTEST_5( comparisons(ArrayXXf(8, 12)) ); - CALL_SUBTEST_6( comparisons(ArrayXXi(8, 12)) ); + CALL_SUBTEST_5( comparisons(ArrayXXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( comparisons(ArrayXXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( min_max(Array()) ); + CALL_SUBTEST_2( min_max(Array22f()) ); + CALL_SUBTEST_3( min_max(Array44d()) ); + CALL_SUBTEST_5( min_max(ArrayXXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( min_max(ArrayXXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( array_real(Array()) ); CALL_SUBTEST_2( array_real(Array22f()) ); CALL_SUBTEST_3( array_real(Array44d()) ); - CALL_SUBTEST_5( array_real(ArrayXXf(8, 12)) ); + CALL_SUBTEST_5( array_real(ArrayXXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_4( array_complex(ArrayXXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, int >::value)); diff --git a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp index 45e0930ce..465b8998b 100644 --- a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp +++ b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp @@ -156,30 +156,65 @@ template void lpNorm(const VectorType& v) VERIFY_IS_APPROX(internal::pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.array().abs().pow(5).sum()); } +template void cwise_min_max(const MatrixType& m) +{ + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + + Index rows = m.rows(); + Index cols = m.cols(); + + MatrixType m1 = MatrixType::Random(rows, cols); + + // min/max with array + Scalar maxM1 = m1.maxCoeff(); + Scalar minM1 = m1.minCoeff(); + + VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin(MatrixType::Constant(rows,cols, minM1))); + VERIFY_IS_APPROX(m1, m1.cwiseMin(MatrixType::Constant(rows,cols, maxM1))); + + VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax(MatrixType::Constant(rows,cols, maxM1))); + VERIFY_IS_APPROX(m1, m1.cwiseMax(MatrixType::Constant(rows,cols, minM1))); + + // min/max with scalar input + VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin( minM1)); + VERIFY_IS_APPROX(m1, m1.cwiseMin( maxM1)); + + VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax( maxM1)); + VERIFY_IS_APPROX(m1, m1.cwiseMax( minM1)); + +} + void test_array_for_matrix() { - int maxsize = 40; for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( array_for_matrix(Matrix()) ); CALL_SUBTEST_2( array_for_matrix(Matrix2f()) ); CALL_SUBTEST_3( array_for_matrix(Matrix4d()) ); - CALL_SUBTEST_4( array_for_matrix(MatrixXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); - CALL_SUBTEST_5( array_for_matrix(MatrixXf(internal::random(1,maxsize), internal::random(1,maxsize))) ); - CALL_SUBTEST_6( array_for_matrix(MatrixXi(internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_4( array_for_matrix(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_5( array_for_matrix(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( array_for_matrix(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( comparisons(Matrix()) ); CALL_SUBTEST_2( comparisons(Matrix2f()) ); CALL_SUBTEST_3( comparisons(Matrix4d()) ); - CALL_SUBTEST_5( comparisons(MatrixXf(internal::random(1,maxsize), internal::random(1,maxsize))) ); - CALL_SUBTEST_6( comparisons(MatrixXi(internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_5( comparisons(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( comparisons(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( cwise_min_max(Matrix()) ); + CALL_SUBTEST_2( cwise_min_max(Matrix2f()) ); + CALL_SUBTEST_3( cwise_min_max(Matrix4d()) ); + CALL_SUBTEST_5( cwise_min_max(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( cwise_min_max(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( lpNorm(Matrix()) ); CALL_SUBTEST_2( lpNorm(Vector2f()) ); CALL_SUBTEST_7( lpNorm(Vector3d()) ); CALL_SUBTEST_8( lpNorm(Vector4f()) ); - CALL_SUBTEST_5( lpNorm(VectorXf(internal::random(1,maxsize))) ); - CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random(1,maxsize))) ); + CALL_SUBTEST_5( lpNorm(VectorXf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } } diff --git a/gtsam/3rdparty/Eigen/test/basicstuff.cpp b/gtsam/3rdparty/Eigen/test/basicstuff.cpp index 9f3966818..76ecffd68 100644 --- a/gtsam/3rdparty/Eigen/test/basicstuff.cpp +++ b/gtsam/3rdparty/Eigen/test/basicstuff.cpp @@ -42,11 +42,8 @@ template void basicStuff(const MatrixType& m) m2 = MatrixType::Random(rows, cols), m3(rows, cols), mzero = MatrixType::Zero(rows, cols), - identity = Matrix - ::Identity(rows, rows), square = Matrix::Random(rows, rows); VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), vzero = VectorType::Zero(rows); SquareMatrixType sm1 = SquareMatrixType::Random(rows,rows), sm2(rows,rows); @@ -215,14 +212,14 @@ void test_basicstuff() for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( basicStuff(Matrix()) ); CALL_SUBTEST_2( basicStuff(Matrix4d()) ); - CALL_SUBTEST_3( basicStuff(MatrixXcf(internal::random(1,100), internal::random(1,100))) ); - CALL_SUBTEST_4( basicStuff(MatrixXi(internal::random(1,100), internal::random(1,100))) ); - CALL_SUBTEST_5( basicStuff(MatrixXcd(internal::random(1,100), internal::random(1,100))) ); + CALL_SUBTEST_3( basicStuff(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_4( basicStuff(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_5( basicStuff(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_6( basicStuff(Matrix()) ); - CALL_SUBTEST_7( basicStuff(Matrix(internal::random(1,100),internal::random(1,100))) ); + CALL_SUBTEST_7( basicStuff(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_3( basicStuffComplex(MatrixXcf(internal::random(1,100), internal::random(1,100))) ); - CALL_SUBTEST_5( basicStuffComplex(MatrixXcd(internal::random(1,100), internal::random(1,100))) ); + CALL_SUBTEST_3( basicStuffComplex(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_5( basicStuffComplex(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } CALL_SUBTEST_1(fixedSizeMatrixConstruction()); diff --git a/gtsam/3rdparty/Eigen/test/bicgstab.cpp b/gtsam/3rdparty/Eigen/test/bicgstab.cpp new file mode 100644 index 000000000..2b6403583 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/bicgstab.cpp @@ -0,0 +1,45 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" +#include + +template void test_bicgstab_T() +{ + BiCGSTAB, DiagonalPreconditioner > bicgstab_colmajor_diag; + BiCGSTAB, IdentityPreconditioner > bicgstab_colmajor_I; + BiCGSTAB, IncompleteLUT > bicgstab_colmajor_ilut; + //BiCGSTAB, SSORPreconditioner > bicgstab_colmajor_ssor; + + CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_diag) ); +// CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_I) ); + CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ilut) ); + //CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ssor) ); +} + +void test_bicgstab() +{ + CALL_SUBTEST_1(test_bicgstab_T()); + CALL_SUBTEST_2(test_bicgstab_T >()); +} diff --git a/gtsam/3rdparty/Eigen/test/block.cpp b/gtsam/3rdparty/Eigen/test/block.cpp index 70852ee48..07d5ce792 100644 --- a/gtsam/3rdparty/Eigen/test/block.cpp +++ b/gtsam/3rdparty/Eigen/test/block.cpp @@ -42,12 +42,8 @@ template void block(const MatrixType& m) m1_copy = m1, m2 = MatrixType::Random(rows, cols), m3(rows, cols), - mzero = MatrixType::Zero(rows, cols), ones = MatrixType::Ones(rows, cols); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - v3 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); + VectorType v1 = VectorType::Random(rows); Scalar s1 = internal::random(); diff --git a/gtsam/3rdparty/Eigen/test/cholesky.cpp b/gtsam/3rdparty/Eigen/test/cholesky.cpp index ae4342cee..4f2516d26 100644 --- a/gtsam/3rdparty/Eigen/test/cholesky.cpp +++ b/gtsam/3rdparty/Eigen/test/cholesky.cpp @@ -41,9 +41,37 @@ static int nb_temporaries; VERIFY( (#XPR) && nb_temporaries==N ); \ } -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif +template class CholType> void test_chol_update(const MatrixType& symm) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef Matrix VectorType; + + MatrixType symmLo = symm.template triangularView(); + MatrixType symmUp = symm.template triangularView(); + MatrixType symmCpy = symm; + + CholType chollo(symmLo); + CholType cholup(symmUp); + + for (int k=0; k<10; ++k) + { + VectorType vec = VectorType::Random(symm.rows()); + RealScalar sigma = internal::random(); + symmCpy += sigma * vec * vec.adjoint(); + + // we are doing some downdates, so it might be the case that the matrix is not SPD anymore + CholType chol(symmCpy); + if(chol.info()!=Success) + break; + + chollo.rankUpdate(vec, sigma); + VERIFY_IS_APPROX(symmCpy, chollo.reconstructedMatrix()); + + cholup.rankUpdate(vec, sigma); + VERIFY_IS_APPROX(symmCpy, cholup.reconstructedMatrix()); + } +} template void cholesky(const MatrixType& m) { @@ -77,34 +105,6 @@ template void cholesky(const MatrixType& m) // FIXME: currently that fails !! //symm.template part().setZero(); - #ifdef HAS_GSL -// if (internal::is_same::value) -// { -// typedef GslTraits Gsl; -// typename Gsl::Matrix gMatA=0, gSymm=0; -// typename Gsl::Vector gVecB=0, gVecX=0; -// convert(symm, gSymm); -// convert(symm, gMatA); -// convert(vecB, gVecB); -// convert(vecB, gVecX); -// Gsl::cholesky(gMatA); -// Gsl::cholesky_solve(gMatA, gVecB, gVecX); -// VectorType vecX(rows), _vecX, _vecB; -// convert(gVecX, _vecX); -// symm.llt().solve(vecB, &vecX); -// Gsl::prod(gSymm, gVecX, gVecB); -// convert(gVecB, _vecB); -// // test gsl itself ! -// VERIFY_IS_APPROX(vecB, _vecB); -// VERIFY_IS_APPROX(vecX, _vecX); -// -// Gsl::free(gMatA); -// Gsl::free(gSymm); -// Gsl::free(gVecB); -// Gsl::free(gVecX); -// } - #endif - { LLT chollo(symmLo); VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix()); @@ -124,6 +124,11 @@ template void cholesky(const MatrixType& m) MatrixType neg = -symmLo; chollo.compute(neg); VERIFY(chollo.info()==NumericalIssue); + + VERIFY_IS_APPROX(MatrixType(chollo.matrixL().transpose().conjugate()), MatrixType(chollo.matrixU())); + VERIFY_IS_APPROX(MatrixType(chollo.matrixU().transpose().conjugate()), MatrixType(chollo.matrixL())); + VERIFY_IS_APPROX(MatrixType(cholup.matrixL().transpose().conjugate()), MatrixType(cholup.matrixU())); + VERIFY_IS_APPROX(MatrixType(cholup.matrixU().transpose().conjugate()), MatrixType(cholup.matrixL())); } // LDLT @@ -152,6 +157,11 @@ template void cholesky(const MatrixType& m) matX = ldltup.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + VERIFY_IS_APPROX(MatrixType(ldltlo.matrixL().transpose().conjugate()), MatrixType(ldltlo.matrixU())); + VERIFY_IS_APPROX(MatrixType(ldltlo.matrixU().transpose().conjugate()), MatrixType(ldltlo.matrixL())); + VERIFY_IS_APPROX(MatrixType(ldltup.matrixL().transpose().conjugate()), MatrixType(ldltup.matrixU())); + VERIFY_IS_APPROX(MatrixType(ldltup.matrixU().transpose().conjugate()), MatrixType(ldltup.matrixL())); + if(MatrixType::RowsAtCompileTime==Dynamic) { // note : each inplace permutation requires a small temporary vector (mask) @@ -166,6 +176,10 @@ template void cholesky(const MatrixType& m) VERIFY_EVALUATION_COUNT(matX = ldltup.solve(matX), 0); VERIFY_IS_APPROX(matX, ldltup.solve(matB).eval()); } + + // restore + if(sign == -1) + symm = -symm; } // test some special use cases of SelfCwiseBinaryOp: @@ -182,7 +196,10 @@ template void cholesky(const MatrixType& m) m2 = m1; m2.noalias() -= symmLo.template selfadjointView().llt().solve(matB); VERIFY_IS_APPROX(m2, m1 - symmLo.template selfadjointView().llt().solve(matB)); - + + // update/downdate + CALL_SUBTEST(( test_chol_update(symm) )); + CALL_SUBTEST(( test_chol_update(symm) )); } template void cholesky_cplx(const MatrixType& m) @@ -242,7 +259,6 @@ template void cholesky_cplx(const MatrixType& m) // matX = ldltlo.solve(matB); // VERIFY_IS_APPROX(symm * matX, matB); } - } // regression test for bug 241 @@ -290,9 +306,9 @@ void test_cholesky() CALL_SUBTEST_3( cholesky_bug241(Matrix2d()) ); CALL_SUBTEST_4( cholesky(Matrix3f()) ); CALL_SUBTEST_5( cholesky(Matrix4d()) ); - s = internal::random(1,200); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( cholesky(MatrixXd(s,s)) ); - s = internal::random(1,100); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_6( cholesky_cplx(MatrixXcd(s,s)) ); } @@ -304,4 +320,6 @@ void test_cholesky() // Test problem size constructors CALL_SUBTEST_9( LLT(10) ); CALL_SUBTEST_9( LDLT(10) ); + + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/cholmod_support.cpp b/gtsam/3rdparty/Eigen/test/cholmod_support.cpp new file mode 100644 index 000000000..1ebba2438 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/cholmod_support.cpp @@ -0,0 +1,71 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" + +#include + +template void test_cholmod_T() +{ + CholmodDecomposition, Lower> g_chol_colmajor_lower; g_chol_colmajor_lower.setMode(CholmodSupernodalLLt); + CholmodDecomposition, Upper> g_chol_colmajor_upper; g_chol_colmajor_upper.setMode(CholmodSupernodalLLt); + CholmodDecomposition, Lower> g_llt_colmajor_lower; g_llt_colmajor_lower.setMode(CholmodSimplicialLLt); + CholmodDecomposition, Upper> g_llt_colmajor_upper; g_llt_colmajor_upper.setMode(CholmodSimplicialLLt); + CholmodDecomposition, Lower> g_ldlt_colmajor_lower; g_ldlt_colmajor_lower.setMode(CholmodLDLt); + CholmodDecomposition, Upper> g_ldlt_colmajor_upper; g_ldlt_colmajor_upper.setMode(CholmodLDLt); + + CholmodSupernodalLLT, Lower> chol_colmajor_lower; + CholmodSupernodalLLT, Upper> chol_colmajor_upper; + CholmodSimplicialLLT, Lower> llt_colmajor_lower; + CholmodSimplicialLLT, Upper> llt_colmajor_upper; + CholmodSimplicialLDLT, Lower> ldlt_colmajor_lower; + CholmodSimplicialLDLT, Upper> ldlt_colmajor_upper; + + check_sparse_spd_solving(g_chol_colmajor_lower); + check_sparse_spd_solving(g_chol_colmajor_upper); + check_sparse_spd_solving(g_llt_colmajor_lower); + check_sparse_spd_solving(g_llt_colmajor_upper); + check_sparse_spd_solving(g_ldlt_colmajor_lower); + check_sparse_spd_solving(g_ldlt_colmajor_upper); + + check_sparse_spd_solving(chol_colmajor_lower); + check_sparse_spd_solving(chol_colmajor_upper); + check_sparse_spd_solving(llt_colmajor_lower); + check_sparse_spd_solving(llt_colmajor_upper); + check_sparse_spd_solving(ldlt_colmajor_lower); + check_sparse_spd_solving(ldlt_colmajor_upper); + +// check_sparse_spd_determinant(chol_colmajor_lower); +// check_sparse_spd_determinant(chol_colmajor_upper); +// check_sparse_spd_determinant(llt_colmajor_lower); +// check_sparse_spd_determinant(llt_colmajor_upper); +// check_sparse_spd_determinant(ldlt_colmajor_lower); +// check_sparse_spd_determinant(ldlt_colmajor_upper); +} + +void test_cholmod_support() +{ + CALL_SUBTEST_1(test_cholmod_T()); + CALL_SUBTEST_2(test_cholmod_T >()); +} diff --git a/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp b/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp new file mode 100644 index 000000000..f24f35817 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp @@ -0,0 +1,45 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" +#include + +template void test_conjugate_gradient_T() +{ + ConjugateGradient, Lower> cg_colmajor_lower_diag; + ConjugateGradient, Upper> cg_colmajor_upper_diag; + ConjugateGradient, Lower, IdentityPreconditioner> cg_colmajor_lower_I; + ConjugateGradient, Upper, IdentityPreconditioner> cg_colmajor_upper_I; + + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_I) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_I) ); +} + +void test_conjugate_gradient() +{ + CALL_SUBTEST_1(test_conjugate_gradient_T()); + CALL_SUBTEST_2(test_conjugate_gradient_T >()); +} diff --git a/gtsam/3rdparty/Eigen/test/cwiseop.cpp b/gtsam/3rdparty/Eigen/test/cwiseop.cpp index 07ef599be..b3ca94e3a 100644 --- a/gtsam/3rdparty/Eigen/test/cwiseop.cpp +++ b/gtsam/3rdparty/Eigen/test/cwiseop.cpp @@ -60,11 +60,8 @@ template void cwiseops(const MatrixType& m) mzero = MatrixType::Zero(rows, cols), mones = MatrixType::Ones(rows, cols), identity = Matrix - ::Identity(rows, rows), - square = Matrix::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - vzero = VectorType::Zero(rows), + ::Identity(rows, rows); + VectorType vzero = VectorType::Zero(rows), vones = VectorType::Ones(rows), v3(rows); @@ -175,9 +172,9 @@ void test_cwiseop() for(int i = 0; i < g_repeat ; i++) { CALL_SUBTEST_1( cwiseops(Matrix()) ); CALL_SUBTEST_2( cwiseops(Matrix4d()) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(3, 3)) ); - CALL_SUBTEST_4( cwiseops(MatrixXf(22, 22)) ); - CALL_SUBTEST_5( cwiseops(MatrixXi(8, 12)) ); - CALL_SUBTEST_6( cwiseops(MatrixXd(20, 20)) ); + CALL_SUBTEST_3( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_4( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_5( cwiseops(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( cwiseops(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } } diff --git a/gtsam/3rdparty/Eigen/test/determinant.cpp b/gtsam/3rdparty/Eigen/test/determinant.cpp index dcf64387d..6c8d3baab 100644 --- a/gtsam/3rdparty/Eigen/test/determinant.cpp +++ b/gtsam/3rdparty/Eigen/test/determinant.cpp @@ -68,13 +68,15 @@ template void determinant(const MatrixType& m) void test_determinant() { + int s; for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( determinant(Matrix()) ); CALL_SUBTEST_2( determinant(Matrix()) ); CALL_SUBTEST_3( determinant(Matrix()) ); CALL_SUBTEST_4( determinant(Matrix()) ); CALL_SUBTEST_5( determinant(Matrix, 10, 10>()) ); - CALL_SUBTEST_6( determinant(MatrixXd(20, 20)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_6( determinant(MatrixXd(s, s)) ); } - CALL_SUBTEST_6( determinant(MatrixXd(200, 200)) ); + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/diagonal.cpp b/gtsam/3rdparty/Eigen/test/diagonal.cpp index 50b341dfe..94a30e2f4 100644 --- a/gtsam/3rdparty/Eigen/test/diagonal.cpp +++ b/gtsam/3rdparty/Eigen/test/diagonal.cpp @@ -74,10 +74,10 @@ void test_diagonal() for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( diagonal(Matrix()) ); CALL_SUBTEST_2( diagonal(Matrix4d()) ); - CALL_SUBTEST_2( diagonal(MatrixXcf(3, 3)) ); - CALL_SUBTEST_2( diagonal(MatrixXi(8, 12)) ); - CALL_SUBTEST_2( diagonal(MatrixXcd(20, 20)) ); - CALL_SUBTEST_1( diagonal(MatrixXf(21, 19)) ); + CALL_SUBTEST_2( diagonal(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_2( diagonal(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_2( diagonal(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_1( diagonal(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_1( diagonal(Matrix(3, 4)) ); } } diff --git a/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp b/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp index 9d6f069c6..d84f4e9f3 100644 --- a/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp +++ b/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp @@ -101,9 +101,9 @@ void test_diagonalmatrices() CALL_SUBTEST_3( diagonalmatrices(Matrix()) ); CALL_SUBTEST_4( diagonalmatrices(Matrix4d()) ); CALL_SUBTEST_5( diagonalmatrices(Matrix()) ); - CALL_SUBTEST_6( diagonalmatrices(MatrixXcf(3, 5)) ); - CALL_SUBTEST_7( diagonalmatrices(MatrixXi(10, 8)) ); - CALL_SUBTEST_8( diagonalmatrices(Matrix(20, 20)) ); - CALL_SUBTEST_9( diagonalmatrices(MatrixXf(21, 24)) ); + CALL_SUBTEST_6( diagonalmatrices(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( diagonalmatrices(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_8( diagonalmatrices(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_9( diagonalmatrices(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } } diff --git a/gtsam/3rdparty/Eigen/test/eigen2/main.h b/gtsam/3rdparty/Eigen/test/eigen2/main.h index b361a44d9..9d0defa39 100644 --- a/gtsam/3rdparty/Eigen/test/eigen2/main.h +++ b/gtsam/3rdparty/Eigen/test/eigen2/main.h @@ -29,10 +29,6 @@ #include #include -#ifdef NDEBUG -#undef NDEBUG -#endif - #ifndef EIGEN_TEST_FUNC #error EIGEN_TEST_FUNC must be defined #endif diff --git a/gtsam/3rdparty/Eigen/test/eigen2support.cpp b/gtsam/3rdparty/Eigen/test/eigen2support.cpp index a7269fed5..5d0202e34 100644 --- a/gtsam/3rdparty/Eigen/test/eigen2support.cpp +++ b/gtsam/3rdparty/Eigen/test/eigen2support.cpp @@ -35,7 +35,6 @@ template void eigen2support(const MatrixType& m) Index cols = m.cols(); MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), m3(rows, cols); Scalar s1 = internal::random(), diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp index 99e9ee864..1cd55a2cd 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp @@ -108,18 +108,23 @@ template void eigensolver_verify_assert(const MatrixType& m void test_eigensolver_complex() { + int s; for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( eigensolver(Matrix4cf()) ); - CALL_SUBTEST_2( eigensolver(MatrixXcd(14,14)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_2( eigensolver(MatrixXcd(s,s)) ); CALL_SUBTEST_3( eigensolver(Matrix, 1, 1>()) ); CALL_SUBTEST_4( eigensolver(Matrix3f()) ); } CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4cf()) ); - CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXcd(14,14)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXcd(s,s)) ); CALL_SUBTEST_3( eigensolver_verify_assert(Matrix, 1, 1>()) ); CALL_SUBTEST_4( eigensolver_verify_assert(Matrix3f()) ); // Test problem size constructors - CALL_SUBTEST_5(ComplexEigenSolver(10)); + CALL_SUBTEST_5(ComplexEigenSolver(s)); + + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp index 8476f026d..2e9cdc7a5 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp @@ -27,10 +27,6 @@ #include #include -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - template void eigensolver(const MatrixType& m) { typedef typename MatrixType::Index Index; @@ -97,9 +93,11 @@ template void eigensolver_verify_assert(const MatrixType& m void test_eigensolver_generic() { + int s; for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( eigensolver(Matrix4f()) ); - CALL_SUBTEST_2( eigensolver(MatrixXd(17,17)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_2( eigensolver(MatrixXd(s,s)) ); // some trivial but implementation-wise tricky cases CALL_SUBTEST_2( eigensolver(MatrixXd(1,1)) ); @@ -109,10 +107,24 @@ void test_eigensolver_generic() } CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4f()) ); - CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXd(17,17)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXd(s,s)) ); CALL_SUBTEST_3( eigensolver_verify_assert(Matrix()) ); CALL_SUBTEST_4( eigensolver_verify_assert(Matrix2d()) ); // Test problem size constructors - CALL_SUBTEST_5(EigenSolver(10)); + CALL_SUBTEST_5(EigenSolver(s)); + + // regression test for bug 410 + CALL_SUBTEST_2( + { + MatrixXd A(1,1); + A(0,0) = std::sqrt(-1.); + Eigen::EigenSolver solver(A); + MatrixXd V(1, 1); + V(0,0) = solver.eigenvectors()(0,0).real(); + } + ); + + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp index b85bcc289..26d3d1f70 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp @@ -27,10 +27,6 @@ #include #include -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - template void selfadjointeigensolver(const MatrixType& m) { typedef typename MatrixType::Index Index; @@ -59,64 +55,25 @@ template void selfadjointeigensolver(const MatrixType& m) symmB.template triangularView().setZero(); SelfAdjointEigenSolver eiSymm(symmA); + SelfAdjointEigenSolver eiDirect; + eiDirect.computeDirect(symmA); // generalized eigen pb GeneralizedSelfAdjointEigenSolver eiSymmGen(symmA, symmB); - #ifdef HAS_GSL - if (internal::is_same::value) - { - // restore symmA and symmB. - symmA = MatrixType(symmA.template selfadjointView()); - symmB = MatrixType(symmB.template selfadjointView()); - typedef GslTraits Gsl; - typename Gsl::Matrix gEvec=0, gSymmA=0, gSymmB=0; - typename GslTraits::Vector gEval=0; - RealVectorType _eval; - MatrixType _evec; - convert(symmA, gSymmA); - convert(symmB, gSymmB); - convert(symmA, gEvec); - gEval = GslTraits::createVector(rows); - - Gsl::eigen_symm(gSymmA, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - - // test gsl itself ! - VERIFY((symmA * _evec).isApprox(_evec * _eval.asDiagonal(), largerEps)); - - // compare with eigen - VERIFY_IS_APPROX(_eval, eiSymm.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwiseAbs(), eiSymm.eigenvectors().cwiseAbs()); - - // generalized pb - Gsl::eigen_symm_gen(gSymmA, gSymmB, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - // test GSL itself: - VERIFY((symmA * _evec).isApprox(symmB * (_evec * _eval.asDiagonal()), largerEps)); - - // compare with eigen - MatrixType normalized_eivec = eiSymmGen.eigenvectors()*eiSymmGen.eigenvectors().colwise().norm().asDiagonal().inverse(); - VERIFY_IS_APPROX(_eval, eiSymmGen.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwiseAbs(), normalized_eivec.cwiseAbs()); - - Gsl::free(gSymmA); - Gsl::free(gSymmB); - GslTraits::free(gEval); - Gsl::free(gEvec); - } - #endif - VERIFY_IS_EQUAL(eiSymm.info(), Success); VERIFY((symmA.template selfadjointView() * eiSymm.eigenvectors()).isApprox( eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal(), largerEps)); VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiSymm.eigenvalues()); + + VERIFY_IS_EQUAL(eiDirect.info(), Success); + VERIFY((symmA.template selfadjointView() * eiDirect.eigenvectors()).isApprox( + eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal(), largerEps)); + VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiDirect.eigenvalues()); SelfAdjointEigenSolver eiSymmNoEivecs(symmA, false); VERIFY_IS_EQUAL(eiSymmNoEivecs.info(), Success); VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmNoEivecs.eigenvalues()); - + // generalized eigen problem Ax = lBx eiSymmGen.compute(symmA, symmB,Ax_lBx); VERIFY_IS_EQUAL(eiSymmGen.info(), Success); @@ -171,15 +128,21 @@ template void selfadjointeigensolver(const MatrixType& m) void test_eigensolver_selfadjoint() { + int s; for(int i = 0; i < g_repeat; i++) { - // very important to test a 3x3 matrix since we provide a special path for it + // very important to test 3x3 and 2x2 matrices since we provide special paths for them + CALL_SUBTEST_1( selfadjointeigensolver(Matrix2d()) ); CALL_SUBTEST_1( selfadjointeigensolver(Matrix3f()) ); CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) ); - CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(10,10)) ); - CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(19,19)) ); - CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(17,17)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) ); - CALL_SUBTEST_9( selfadjointeigensolver(Matrix,Dynamic,Dynamic,RowMajor>(17,17)) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_9( selfadjointeigensolver(Matrix,Dynamic,Dynamic,RowMajor>(s,s)) ); // some trivial but implementation-wise tricky cases CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(1,1)) ); @@ -189,7 +152,10 @@ void test_eigensolver_selfadjoint() } // Test problem size constructors - CALL_SUBTEST_8(SelfAdjointEigenSolver(10)); - CALL_SUBTEST_8(Tridiagonalization(10)); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_8(SelfAdjointEigenSolver(s)); + CALL_SUBTEST_8(Tridiagonalization(s)); + + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp index 738ca3150..724133725 100644 --- a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp @@ -113,7 +113,7 @@ void specificTest1() Vector2f m; m << -1.0f, -2.0f; Vector2f M; M << 1.0f, 5.0f; - typedef AlignedBox BoxType; + typedef AlignedBox2f BoxType; BoxType box( m, M ); Vector2f sides = M-m; @@ -140,7 +140,7 @@ void specificTest2() Vector3i m; m << -1, -2, 0; Vector3i M; M << 1, 5, 3; - typedef AlignedBox BoxType; + typedef AlignedBox3i BoxType; BoxType box( m, M ); Vector3i sides = M-m; @@ -165,21 +165,21 @@ void test_geo_alignedbox() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( alignedbox(AlignedBox()) ); - CALL_SUBTEST_2( alignedboxCastTests(AlignedBox()) ); + CALL_SUBTEST_1( alignedbox(AlignedBox2f()) ); + CALL_SUBTEST_2( alignedboxCastTests(AlignedBox2f()) ); - CALL_SUBTEST_3( alignedbox(AlignedBox()) ); - CALL_SUBTEST_4( alignedboxCastTests(AlignedBox()) ); + CALL_SUBTEST_3( alignedbox(AlignedBox3f()) ); + CALL_SUBTEST_4( alignedboxCastTests(AlignedBox3f()) ); - CALL_SUBTEST_5( alignedbox(AlignedBox()) ); - CALL_SUBTEST_6( alignedboxCastTests(AlignedBox()) ); + CALL_SUBTEST_5( alignedbox(AlignedBox4d()) ); + CALL_SUBTEST_6( alignedboxCastTests(AlignedBox4d()) ); - CALL_SUBTEST_7( alignedbox(AlignedBox()) ); - CALL_SUBTEST_8( alignedboxCastTests(AlignedBox()) ); + CALL_SUBTEST_7( alignedbox(AlignedBox1d()) ); + CALL_SUBTEST_8( alignedboxCastTests(AlignedBox1d()) ); - CALL_SUBTEST_9( alignedbox(AlignedBox()) ); - CALL_SUBTEST_10( alignedbox(AlignedBox()) ); - CALL_SUBTEST_11( alignedbox(AlignedBox()) ); + CALL_SUBTEST_9( alignedbox(AlignedBox1i()) ); + CALL_SUBTEST_10( alignedbox(AlignedBox2i()) ); + CALL_SUBTEST_11( alignedbox(AlignedBox3i()) ); } CALL_SUBTEST_12( specificTest1() ); CALL_SUBTEST_13( specificTest2() ); diff --git a/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp b/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp index f82cb8fbe..8029a694e 100644 --- a/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp @@ -42,7 +42,6 @@ template void eulerangles(void) #define VERIFY_EULER(I,J,K, X,Y,Z) { \ Vector3 ea = m.eulerAngles(I,J,K); \ - Matrix3 m1 = Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z())); \ VERIFY_IS_APPROX(m, Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z()))); \ } VERIFY_EULER(0,1,2, X,Y,Z); diff --git a/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp b/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp index 26254b757..3efcb77db 100644 --- a/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp @@ -42,17 +42,13 @@ template void homogeneous(void) typedef Matrix T3MatrixType; VectorType v0 = VectorType::Random(), - v1 = VectorType::Random(), ones = VectorType::Ones(); - HVectorType hv0 = HVectorType::Random(), - hv1 = HVectorType::Random(); + HVectorType hv0 = HVectorType::Random(); - MatrixType m0 = MatrixType::Random(), - m1 = MatrixType::Random(); + MatrixType m0 = MatrixType::Random(); - HMatrixType hm0 = HMatrixType::Random(), - hm1 = HMatrixType::Random(); + HMatrixType hm0 = HMatrixType::Random(); hv0 << v0, 1; VERIFY_IS_APPROX(v0.homogeneous(), hv0); diff --git a/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp b/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp index 020ae7103..aa3c8b61d 100644 --- a/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp @@ -88,9 +88,7 @@ template void orthomethods(int size=Size) typedef Matrix MatrixN3; typedef Matrix Vector3; - VectorType v0 = VectorType::Random(size), - v1 = VectorType::Random(size), - v2 = VectorType::Random(size); + VectorType v0 = VectorType::Random(size); // unitOrthogonal VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().dot(v0), Scalar(1)); diff --git a/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp b/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp index 13f98fdd6..a289e70de 100644 --- a/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp @@ -40,6 +40,7 @@ template void parametrizedline(const LineType& _line) typedef Matrix VectorType; typedef Matrix MatrixType; + typedef Hyperplane HyperplaneType; VectorType p0 = VectorType::Random(dim); VectorType p1 = VectorType::Random(dim); @@ -64,6 +65,16 @@ template void parametrizedline(const LineType& _line) VERIFY_IS_APPROX(hp1f.template cast(),l0); ParametrizedLine hp1d = l0.template cast(); VERIFY_IS_APPROX(hp1d.template cast(),l0); + + // intersections + VectorType p2 = VectorType::Random(dim); + VectorType n2 = VectorType::Random(dim).normalized(); + HyperplaneType hp(p2,n2); + Scalar t = l0.intersectionParameter(hp); + VectorType pi = l0.pointAt(t); + VERIFY_IS_MUCH_SMALLER_THAN(hp.signedDistance(pi), RealScalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN(l0.distance(pi), RealScalar(1)); + VERIFY_IS_APPROX(l0.intersectionPoint(hp), pi); } template void parametrizedline_alignment() diff --git a/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp b/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp index 7adbe0b3d..b73ae9cd4 100644 --- a/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp @@ -142,6 +142,17 @@ template void quaternion(void) VERIFY_IS_APPROX(-v3.normalized(),(q2.setFromTwoVectors(v1,-v3)*v1).normalized()); } + // from two vector creation static function + VERIFY_IS_APPROX( v2.normalized(),(Quaternionx::FromTwoVectors(v1, v2)*v1).normalized()); + VERIFY_IS_APPROX( v1.normalized(),(Quaternionx::FromTwoVectors(v1, v1)*v1).normalized()); + VERIFY_IS_APPROX(-v1.normalized(),(Quaternionx::FromTwoVectors(v1,-v1)*v1).normalized()); + if (internal::is_same::value) + { + v3 = (v1.array()+eps).matrix(); + VERIFY_IS_APPROX( v3.normalized(),(Quaternionx::FromTwoVectors(v1, v3)*v1).normalized()); + VERIFY_IS_APPROX(-v3.normalized(),(Quaternionx::FromTwoVectors(v1,-v3)*v1).normalized()); + } + // inverse and conjugate VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1); VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1); diff --git a/gtsam/3rdparty/Eigen/test/geo_transformations.cpp b/gtsam/3rdparty/Eigen/test/geo_transformations.cpp index b606de2fb..e9f05cfb6 100644 --- a/gtsam/3rdparty/Eigen/test/geo_transformations.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_transformations.cpp @@ -122,9 +122,7 @@ template void transformations() typedef Translation Translation3; Vector3 v0 = Vector3::Random(), - v1 = Vector3::Random(), - v2 = Vector3::Random(); - Vector2 u0 = Vector2::Random(); + v1 = Vector3::Random(); Matrix3 matrot1, m; Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); @@ -284,9 +282,9 @@ template void transformations() // mat * aligned scaling and mat * translation t1 = (Matrix3(q1) * AlignedScaling3(v0)) * Translation3(v0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - t1 = (Matrix3(q1) * Scaling(v0)) * Translation3(v0); + t1 = (Matrix3(q1) * Eigen::Scaling(v0)) * Translation3(v0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - t1 = (q1 * Scaling(v0)) * Translation3(v0); + t1 = (q1 * Eigen::Scaling(v0)) * Translation3(v0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); // mat * transformation and aligned scaling * translation t1 = Matrix3(q1) * (AlignedScaling3(v0) * Translation3(v0)); @@ -295,18 +293,18 @@ template void transformations() t0.setIdentity(); t0.scale(s0).translate(v0); - t1 = Scaling(s0) * Translation3(v0); + t1 = Eigen::Scaling(s0) * Translation3(v0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); t0.prescale(s0); - t1 = Scaling(s0) * t1; + t1 = Eigen::Scaling(s0) * t1; VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); t0 = t3; t0.scale(s0); - t1 = t3 * Scaling(s0,s0,s0); + t1 = t3 * Eigen::Scaling(s0,s0,s0); VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); t0.prescale(s0); - t1 = Scaling(s0,s0,s0) * t1; + t1 = Eigen::Scaling(s0,s0,s0) * t1; VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); @@ -448,6 +446,29 @@ template void transform_alignment() #endif } +template void transform_products() +{ + typedef Matrix Mat; + typedef Transform Proj; + typedef Transform Aff; + typedef Transform AffC; + + Proj p; p.matrix().setRandom(); + Aff a; a.linear().setRandom(); a.translation().setRandom(); + AffC ac = a; + + Mat p_m(p.matrix()), a_m(a.matrix()); + + VERIFY_IS_APPROX((p*p).matrix(), p_m*p_m); + VERIFY_IS_APPROX((a*a).matrix(), a_m*a_m); + VERIFY_IS_APPROX((p*a).matrix(), p_m*a_m); + VERIFY_IS_APPROX((a*p).matrix(), a_m*p_m); + VERIFY_IS_APPROX((ac*a).matrix(), a_m*a_m); + VERIFY_IS_APPROX((a*ac).matrix(), a_m*a_m); + VERIFY_IS_APPROX((p*ac).matrix(), p_m*a_m); + VERIFY_IS_APPROX((ac*p).matrix(), a_m*p_m); +} + void test_geo_transformations() { for(int i = 0; i < g_repeat; i++) { @@ -470,5 +491,9 @@ void test_geo_transformations() CALL_SUBTEST_6(( transformations() )); CALL_SUBTEST_6(( transformations() )); + + + CALL_SUBTEST_7(( transform_products() )); + CALL_SUBTEST_7(( transform_products() )); } } diff --git a/gtsam/3rdparty/Eigen/test/gsl_helper.h b/gtsam/3rdparty/Eigen/test/gsl_helper.h deleted file mode 100644 index d6172d2ff..000000000 --- a/gtsam/3rdparty/Eigen/test/gsl_helper.h +++ /dev/null @@ -1,212 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_GSL_HELPER -#define EIGEN_GSL_HELPER - -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace Eigen { - -template::IsComplex> struct GslTraits -{ - typedef gsl_matrix* Matrix; - typedef gsl_vector* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_alloc(size); } - static void free(Matrix& m) { gsl_matrix_free(m); m=0; } - static void free(Vector& m) { gsl_vector_free(m); m=0; } - static void prod(const Matrix& m, const Vector& v, Vector& x) { gsl_blas_dgemv(CblasNoTrans,1,m,v,0,x); } - static void cholesky(Matrix& m) { gsl_linalg_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_cholesky_solve(m,b,x); } - static void eigen_symm(const Matrix& m, Vector& eval, Matrix& evec) - { - gsl_eigen_symmv_workspace * w = gsl_eigen_symmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_memcpy(a, m); - gsl_eigen_symmv(a,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_symmv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, Vector& eval, Matrix& evec) - { - gsl_eigen_gensymmv_workspace * w = gsl_eigen_gensymmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_memcpy(a, m); - gsl_matrix_memcpy(b, _b); - gsl_eigen_gensymmv(a,b,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_gensymmv_free(w); - free(a); - } - - template - static void eigen_poly_solve(const EIGEN_VECTOR& poly, EIGEN_ROOTS& roots ) - { - const int deg = poly.size()-1; - double *z = new double[2*deg]; - double *a = new double[poly.size()]; - for( int i=0; i struct GslTraits -{ - typedef gsl_matrix_complex* Matrix; - typedef gsl_vector_complex* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_complex_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_complex_alloc(size); } - static void free(Matrix& m) { gsl_matrix_complex_free(m); m=0; } - static void free(Vector& m) { gsl_vector_complex_free(m); m=0; } - static void cholesky(Matrix& m) { gsl_linalg_complex_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_complex_cholesky_solve(m,b,x); } - static void prod(const Matrix& m, const Vector& v, Vector& x) - { gsl_blas_zgemv(CblasNoTrans,gsl_complex_rect(1,0),m,v,gsl_complex_rect(0,0),x); } - static void eigen_symm(const Matrix& m, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_hermv_workspace * w = gsl_eigen_hermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_eigen_hermv(a,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_hermv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_genhermv_workspace * w = gsl_eigen_genhermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_matrix_complex_memcpy(b, _b); - gsl_eigen_genhermv(a,b,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_genhermv_free(w); - free(a); - } -}; - -template -void convert(const MatrixType& m, gsl_matrix* &res) -{ -// if (res) -// gsl_matrix_free(res); - res = gsl_matrix_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector* &res) -{ - if (res) gsl_vector_free(res); - res = gsl_vector_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector* m, VectorType& res) -{ - res.resize (m->size); - for (int i=0 ; i -void convert(const MatrixType& m, gsl_matrix_complex* &res) -{ - res = gsl_matrix_complex_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix_complex* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector_complex* &res) -{ - res = gsl_vector_complex_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector_complex* m, VectorType& res) -{ - res.resize(m->size); - for (int i=0 ; i,1>() )); CALL_SUBTEST_2(( hessenberg,2>() )); CALL_SUBTEST_3(( hessenberg,4>() )); - CALL_SUBTEST_4(( hessenberg(internal::random(1,320)) )); - CALL_SUBTEST_5(( hessenberg,Dynamic>(internal::random(1,320)) )); + CALL_SUBTEST_4(( hessenberg(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_5(( hessenberg,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); // Test problem size constructors CALL_SUBTEST_6(HessenbergDecomposition(10)); diff --git a/gtsam/3rdparty/Eigen/test/householder.cpp b/gtsam/3rdparty/Eigen/test/householder.cpp index e77fa7ad0..6f6f317ea 100644 --- a/gtsam/3rdparty/Eigen/test/householder.cpp +++ b/gtsam/3rdparty/Eigen/test/householder.cpp @@ -130,9 +130,9 @@ void test_householder() CALL_SUBTEST_2( householder(Matrix()) ); CALL_SUBTEST_3( householder(Matrix()) ); CALL_SUBTEST_4( householder(Matrix()) ); - CALL_SUBTEST_5( householder(MatrixXd(10,12)) ); - CALL_SUBTEST_6( householder(MatrixXcf(16,17)) ); - CALL_SUBTEST_7( householder(MatrixXf(25,7)) ); + CALL_SUBTEST_5( householder(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( householder(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( householder(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_8( householder(Matrix()) ); } } diff --git a/gtsam/3rdparty/Eigen/test/inverse.cpp b/gtsam/3rdparty/Eigen/test/inverse.cpp index f0c69e78c..81702432f 100644 --- a/gtsam/3rdparty/Eigen/test/inverse.cpp +++ b/gtsam/3rdparty/Eigen/test/inverse.cpp @@ -41,7 +41,6 @@ template void inverse(const MatrixType& m) MatrixType m1(rows, cols), m2(rows, cols), - mzero = MatrixType::Zero(rows, cols), identity = MatrixType::Identity(rows, rows); createRandomPIMatrixOfRank(rows,rows,rows,m1); m2 = m1.inverse(); @@ -114,4 +113,5 @@ void test_inverse() CALL_SUBTEST_7( inverse(Matrix4d()) ); CALL_SUBTEST_7( inverse(Matrix()) ); } + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/jacobi.cpp b/gtsam/3rdparty/Eigen/test/jacobi.cpp index 6464c63c5..4d462226c 100644 --- a/gtsam/3rdparty/Eigen/test/jacobi.cpp +++ b/gtsam/3rdparty/Eigen/test/jacobi.cpp @@ -82,8 +82,8 @@ void test_jacobi() CALL_SUBTEST_3(( jacobi() )); CALL_SUBTEST_3(( jacobi >() )); - int r = internal::random(2, 20), - c = internal::random(2, 20); + int r = internal::random(2, internal::random(1,EIGEN_TEST_MAX_SIZE)/2), + c = internal::random(2, internal::random(1,EIGEN_TEST_MAX_SIZE)/2); CALL_SUBTEST_4(( jacobi(MatrixXf(r,c)) )); CALL_SUBTEST_5(( jacobi(MatrixXcd(r,c)) )); CALL_SUBTEST_5(( jacobi >(MatrixXcd(r,c)) )); diff --git a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp index 45873832a..3012fbe75 100644 --- a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp +++ b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp @@ -131,6 +131,12 @@ void jacobisvd_test_all_computation_options(const MatrixType& m) jacobisvd_solve(m, ComputeFullU | ComputeThinV); jacobisvd_solve(m, ComputeThinU | ComputeFullV); jacobisvd_solve(m, ComputeThinU | ComputeThinV); + + // test reconstruction + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(m.rows(), m.cols()); + JacobiSVD svd(m, ComputeThinU | ComputeThinV); + VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint()); } } @@ -248,9 +254,17 @@ void jacobisvd_inf_nan() // matrices containing denormal numbers. void jacobisvd_bug286() { +#if defined __INTEL_COMPILER +// shut up warning #239: floating point underflow +#pragma warning push +#pragma warning disable 239 +#endif Matrix2d M; M << -7.90884e-313, -4.94e-324, 0, 5.60844e-313; +#if defined __INTEL_COMPILER +#pragma warning pop +#endif JacobiSVD svd; svd.compute(M); // just check we don't loop indefinitely } @@ -333,8 +347,8 @@ void test_jacobisvd() CALL_SUBTEST_7( jacobisvd_inf_nan() ); } - CALL_SUBTEST_7(( jacobisvd(MatrixXf(internal::random(100, 150), internal::random(100, 150))) )); - CALL_SUBTEST_8(( jacobisvd(MatrixXcd(internal::random(80, 100), internal::random(80, 100))) )); + CALL_SUBTEST_7(( jacobisvd(MatrixXf(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); + CALL_SUBTEST_8(( jacobisvd(MatrixXcd(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3))) )); // test matrixbase method CALL_SUBTEST_1(( jacobisvd_method() )); diff --git a/gtsam/3rdparty/Eigen/test/linearstructure.cpp b/gtsam/3rdparty/Eigen/test/linearstructure.cpp index 312102701..bbfdaacc1 100644 --- a/gtsam/3rdparty/Eigen/test/linearstructure.cpp +++ b/gtsam/3rdparty/Eigen/test/linearstructure.cpp @@ -39,8 +39,7 @@ template void linearStructure(const MatrixType& m) // to test it, hence I consider that we will have tested Random.h MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - mzero = MatrixType::Zero(rows, cols); + m3(rows, cols); Scalar s1 = internal::random(); while (internal::abs(s1)<1e-3) s1 = internal::random(); @@ -90,10 +89,10 @@ void test_linearstructure() CALL_SUBTEST_2( linearStructure(Matrix2f()) ); CALL_SUBTEST_3( linearStructure(Vector3d()) ); CALL_SUBTEST_4( linearStructure(Matrix4d()) ); - CALL_SUBTEST_5( linearStructure(MatrixXcf(3, 3)) ); - CALL_SUBTEST_6( linearStructure(MatrixXf(8, 12)) ); - CALL_SUBTEST_7( linearStructure(MatrixXi(8, 12)) ); - CALL_SUBTEST_8( linearStructure(MatrixXcd(20, 20)) ); - CALL_SUBTEST_9( linearStructure(ArrayXXf(12, 8)) ); + CALL_SUBTEST_5( linearStructure(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_6( linearStructure(MatrixXf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( linearStructure(MatrixXi (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_8( linearStructure(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_9( linearStructure(ArrayXXf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } } diff --git a/gtsam/3rdparty/Eigen/test/lu.cpp b/gtsam/3rdparty/Eigen/test/lu.cpp index 552364d29..253f68542 100644 --- a/gtsam/3rdparty/Eigen/test/lu.cpp +++ b/gtsam/3rdparty/Eigen/test/lu.cpp @@ -37,7 +37,7 @@ template void lu_non_invertible() Index rows, cols, cols2; if(MatrixType::RowsAtCompileTime==Dynamic) { - rows = internal::random(2,200); + rows = internal::random(2,EIGEN_TEST_MAX_SIZE); } else { @@ -45,8 +45,8 @@ template void lu_non_invertible() } if(MatrixType::ColsAtCompileTime==Dynamic) { - cols = internal::random(2,200); - cols2 = internal::random(2,200); + cols = internal::random(2,EIGEN_TEST_MAX_SIZE); + cols2 = internal::random(2,EIGEN_TEST_MAX_SIZE); } else { @@ -117,7 +117,7 @@ template void lu_invertible() */ typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - int size = internal::random(1,200); + int size = internal::random(1,EIGEN_TEST_MAX_SIZE); MatrixType m1(size, size), m2(size, size), m3(size, size); FullPivLU lu; diff --git a/gtsam/3rdparty/Eigen/test/main.h b/gtsam/3rdparty/Eigen/test/main.h index 4510c1905..991194e30 100644 --- a/gtsam/3rdparty/Eigen/test/main.h +++ b/gtsam/3rdparty/Eigen/test/main.h @@ -27,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -40,6 +41,13 @@ #define min(A,B) please_protect_your_min_with_parentheses #define max(A,B) please_protect_your_max_with_parentheses +#define FORBIDDEN_IDENTIFIER (this_identifier_is_forbidden_to_avoid_clashes) this_identifier_is_forbidden_to_avoid_clashes +// B0 is defined in POSIX header termios.h +#define B0 FORBIDDEN_IDENTIFIER + +// the following file is automatically generated by cmake +#include "split_test_helper.h" + #ifdef NDEBUG #undef NDEBUG #endif @@ -186,7 +194,7 @@ static void verify_impl(bool condition, const char *testname, const char *file, } } -#define VERIFY(a) verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a)) +#define VERIFY(a) ::verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a)) #define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b)) #define VERIFY_IS_APPROX(a, b) VERIFY(test_isApprox(a, b)) @@ -204,101 +212,6 @@ static void verify_impl(bool condition, const char *testname, const char *file, g_test_stack.pop_back(); \ } while (0) -#ifdef EIGEN_TEST_PART_1 -#define CALL_SUBTEST_1(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_1(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_2 -#define CALL_SUBTEST_2(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_2(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_3 -#define CALL_SUBTEST_3(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_3(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_4 -#define CALL_SUBTEST_4(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_4(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_5 -#define CALL_SUBTEST_5(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_5(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_6 -#define CALL_SUBTEST_6(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_6(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_7 -#define CALL_SUBTEST_7(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_7(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_8 -#define CALL_SUBTEST_8(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_8(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_9 -#define CALL_SUBTEST_9(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_9(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_10 -#define CALL_SUBTEST_10(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_10(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_11 -#define CALL_SUBTEST_11(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_11(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_12 -#define CALL_SUBTEST_12(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_12(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_13 -#define CALL_SUBTEST_13(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_13(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_14 -#define CALL_SUBTEST_14(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_14(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_15 -#define CALL_SUBTEST_15(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_15(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_16 -#define CALL_SUBTEST_16(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_16(FUNC) -#endif namespace Eigen { @@ -447,6 +360,23 @@ void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typenam m = qra.householderQ() * d * qrb.householderQ(); } +template +void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size) +{ + typedef typename PermutationVectorType::Index Index; + typedef typename PermutationVectorType::Scalar Scalar; + v.resize(size); + for(Index i = 0; i < size; ++i) v(i) = Scalar(i); + if(size == 1) return; + for(Index n = 0; n < 3 * size; ++n) + { + Index i = internal::random(0, size-1); + Index j; + do j = internal::random(0, size-1); while(j==i); + std::swap(v(i), v(j)); + } +} + } // end namespace Eigen template struct GetDifferentType; diff --git a/gtsam/3rdparty/Eigen/test/mixingtypes.cpp b/gtsam/3rdparty/Eigen/test/mixingtypes.cpp index 8afb733cd..6819f934e 100644 --- a/gtsam/3rdparty/Eigen/test/mixingtypes.cpp +++ b/gtsam/3rdparty/Eigen/test/mixingtypes.cpp @@ -143,5 +143,5 @@ void test_mixingtypes() { CALL_SUBTEST_1(mixingtypes<3>()); CALL_SUBTEST_2(mixingtypes<4>()); - CALL_SUBTEST_3(mixingtypes(internal::random(1,310))); + CALL_SUBTEST_3(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); } diff --git a/gtsam/3rdparty/Eigen/test/nomalloc.cpp b/gtsam/3rdparty/Eigen/test/nomalloc.cpp index 96ff16dae..1feeff4bc 100644 --- a/gtsam/3rdparty/Eigen/test/nomalloc.cpp +++ b/gtsam/3rdparty/Eigen/test/nomalloc.cpp @@ -52,15 +52,7 @@ template void nomalloc(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - mzero = MatrixType::Zero(rows, cols), - identity = Matrix - ::Identity(rows, rows), - square = Matrix - ::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); + m3(rows, cols); Scalar s1 = internal::random(); @@ -137,13 +129,20 @@ void ctms_decompositions() 0, maxSize, maxSize> ComplexMatrix; - const Matrix A(Matrix::Random(size, size)); + const Matrix A(Matrix::Random(size, size)), B(Matrix::Random(size, size)); + Matrix X(size,size); const ComplexMatrix complexA(ComplexMatrix::Random(size, size)); const Matrix saA = A.adjoint() * A; + const Vector b(Vector::Random(size)); + Vector x(size); // Cholesky module Eigen::LLT LLT; LLT.compute(A); + X = LLT.solve(B); + x = LLT.solve(b); Eigen::LDLT LDLT; LDLT.compute(A); + X = LDLT.solve(B); + x = LDLT.solve(b); // Eigenvalues module Eigen::HessenbergDecomposition hessDecomp; hessDecomp.compute(complexA); @@ -155,12 +154,22 @@ void ctms_decompositions() // LU module Eigen::PartialPivLU ppLU; ppLU.compute(A); + X = ppLU.solve(B); + x = ppLU.solve(b); Eigen::FullPivLU fpLU; fpLU.compute(A); + X = fpLU.solve(B); + x = fpLU.solve(b); // QR module Eigen::HouseholderQR hQR; hQR.compute(A); + X = hQR.solve(B); + x = hQR.solve(b); Eigen::ColPivHouseholderQR cpQR; cpQR.compute(A); + // FIXME X = cpQR.solve(B); + x = cpQR.solve(b); Eigen::FullPivHouseholderQR fpQR; fpQR.compute(A); + // FIXME X = fpQR.solve(B); + x = fpQR.solve(b); // SVD module Eigen::JacobiSVD jSVD; jSVD.compute(A, ComputeFullU | ComputeFullV); diff --git a/gtsam/3rdparty/Eigen/test/nullary.cpp b/gtsam/3rdparty/Eigen/test/nullary.cpp index 0df15c081..6c9ee5f34 100644 --- a/gtsam/3rdparty/Eigen/test/nullary.cpp +++ b/gtsam/3rdparty/Eigen/test/nullary.cpp @@ -52,11 +52,14 @@ void testVectorType(const VectorType& base) { typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; - Scalar low = internal::random(-500,500); - Scalar high = internal::random(-500,500); - if (low>high) std::swap(low,high); + const Index size = base.size(); - const Scalar step = (high-low)/(size-1); + + Scalar high = internal::random(-500,500); + Scalar low = (size == 1 ? high : internal::random(-500,500)); + if (low>high) std::swap(low,high); + + const Scalar step = ((size == 1) ? 1 : (high-low)/(size-1)); // check whether the result yields what we expect it to do VectorType m(base); @@ -76,8 +79,8 @@ void testVectorType(const VectorType& base) VERIFY( (MatrixXd(RowVectorXd::LinSpaced(3, 0, 1)) - RowVector3d(0, 0.5, 1)).norm() < std::numeric_limits::epsilon() ); // These guys sometimes fail! This is not good. Any ideas how to fix them!? -// VERIFY( m(m.size()-1) == high ); -// VERIFY( m(0) == low ); + //VERIFY( m(m.size()-1) == high ); + //VERIFY( m(0) == low ); // sequential access version m = VectorType::LinSpaced(Sequential,size,low,high); @@ -97,6 +100,12 @@ void testVectorType(const VectorType& base) Matrix size_changer(size+50); size_changer.setLinSpaced(size,low,high); VERIFY( size_changer.size() == size ); + + typedef Matrix ScalarMatrix; + ScalarMatrix scalar; + scalar.setLinSpaced(1,low,high); + VERIFY_IS_APPROX( scalar, ScalarMatrix::Constant(high) ); + VERIFY_IS_APPROX( ScalarMatrix::LinSpaced(1,low,high), ScalarMatrix::Constant(high) ); } template @@ -124,5 +133,6 @@ void test_nullary() CALL_SUBTEST_6( testVectorType(Vector3d()) ); CALL_SUBTEST_7( testVectorType(VectorXf(internal::random(1,300))) ); CALL_SUBTEST_8( testVectorType(Vector3f()) ); + CALL_SUBTEST_8( testVectorType(Matrix()) ); } } diff --git a/gtsam/3rdparty/Eigen/test/pardiso_support.cpp b/gtsam/3rdparty/Eigen/test/pardiso_support.cpp new file mode 100644 index 000000000..67efad6d8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/pardiso_support.cpp @@ -0,0 +1,29 @@ +/* + Intel Copyright (C) .... +*/ + +#include "sparse_solver.h" +#include + +template void test_pardiso_T() +{ + PardisoLLT < SparseMatrix, Lower> pardiso_llt_lower; + PardisoLLT < SparseMatrix, Upper> pardiso_llt_upper; + PardisoLDLT < SparseMatrix, Lower> pardiso_ldlt_lower; + PardisoLDLT < SparseMatrix, Upper> pardiso_ldlt_upper; + PardisoLU < SparseMatrix > pardiso_lu; + + check_sparse_spd_solving(pardiso_llt_lower); + check_sparse_spd_solving(pardiso_llt_upper); + check_sparse_spd_solving(pardiso_ldlt_lower); + check_sparse_spd_solving(pardiso_ldlt_upper); + check_sparse_square_solving(pardiso_lu); +} + +void test_pardiso_support() +{ + CALL_SUBTEST_1(test_pardiso_T()); + CALL_SUBTEST_2(test_pardiso_T()); + CALL_SUBTEST_3(test_pardiso_T< std::complex >()); + CALL_SUBTEST_4(test_pardiso_T< std::complex >()); +} diff --git a/gtsam/3rdparty/Eigen/test/pastix_support.cpp b/gtsam/3rdparty/Eigen/test/pastix_support.cpp new file mode 100644 index 000000000..dbce30d1c --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/pastix_support.cpp @@ -0,0 +1,59 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2012 Gael Guennebaud +// Copyright (C) 2012 Désiré Nuentsa-Wakam +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . +#include "sparse_solver.h" +#include +#include + + +template void test_pastix_T() +{ + PastixLLT< SparseMatrix, Eigen::Lower > pastix_llt_lower; + PastixLDLT< SparseMatrix, Eigen::Lower > pastix_ldlt_lower; + PastixLLT< SparseMatrix, Eigen::Upper > pastix_llt_upper; + PastixLDLT< SparseMatrix, Eigen::Upper > pastix_ldlt_upper; + PastixLU< SparseMatrix > pastix_lu; + + check_sparse_spd_solving(pastix_llt_lower); + check_sparse_spd_solving(pastix_ldlt_lower); + check_sparse_spd_solving(pastix_llt_upper); + check_sparse_spd_solving(pastix_ldlt_upper); + check_sparse_square_solving(pastix_lu); +} + +// There is no support for selfadjoint matrices with PaStiX. +// Complex symmetric matrices should pass though +template void test_pastix_T_LU() +{ + PastixLU< SparseMatrix > pastix_lu; + check_sparse_square_solving(pastix_lu); +} + +void test_pastix_support() +{ + CALL_SUBTEST_1(test_pastix_T()); + CALL_SUBTEST_2(test_pastix_T()); + CALL_SUBTEST_3( (test_pastix_T_LU >()) ); + CALL_SUBTEST_4(test_pastix_T_LU >()); +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp b/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp index d0fa01310..308838c70 100644 --- a/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp +++ b/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp @@ -24,23 +24,6 @@ #include "main.h" -template -void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size) -{ - typedef typename PermutationVectorType::Index Index; - typedef typename PermutationVectorType::Scalar Scalar; - v.resize(size); - for(Index i = 0; i < size; ++i) v(i) = Scalar(i); - if(size == 1) return; - for(Index n = 0; n < 3 * size; ++n) - { - Index i = internal::random(0, size-1); - Index j; - do j = internal::random(0, size-1); while(j==i); - std::swap(v(i), v(j)); - } -} - using namespace std; template void permutationmatrices(const MatrixType& m) { diff --git a/gtsam/3rdparty/Eigen/test/product.h b/gtsam/3rdparty/Eigen/test/product.h index 40ae4d51b..e77f8c41e 100644 --- a/gtsam/3rdparty/Eigen/test/product.h +++ b/gtsam/3rdparty/Eigen/test/product.h @@ -54,8 +54,7 @@ template void product(const MatrixType& m) // to test it, hence I consider that we will have tested Random.h MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - mzero = MatrixType::Zero(rows, cols); + m3(rows, cols); RowSquareMatrixType identity = RowSquareMatrixType::Identity(rows, rows), square = RowSquareMatrixType::Random(rows, rows), @@ -63,9 +62,7 @@ template void product(const MatrixType& m) ColSquareMatrixType square2 = ColSquareMatrixType::Random(cols, cols), res2 = ColSquareMatrixType::Random(cols, cols); - RowVectorType v1 = RowVectorType::Random(rows), - v2 = RowVectorType::Random(rows), - vzero = RowVectorType::Zero(rows); + RowVectorType v1 = RowVectorType::Random(rows); ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols); OtherMajorMatrixType tm1 = m1; diff --git a/gtsam/3rdparty/Eigen/test/product_extra.cpp b/gtsam/3rdparty/Eigen/test/product_extra.cpp index 15dc5ab96..ca302b469 100644 --- a/gtsam/3rdparty/Eigen/test/product_extra.cpp +++ b/gtsam/3rdparty/Eigen/test/product_extra.cpp @@ -153,11 +153,11 @@ void zero_sized_objects() void test_product_extra() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product_extra(MatrixXf(internal::random(1,320), internal::random(1,320))) ); - CALL_SUBTEST_2( product_extra(MatrixXd(internal::random(1,320), internal::random(1,320))) ); + CALL_SUBTEST_1( product_extra(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_2( product_extra(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_2( mat_mat_scalar_scalar_product() ); - CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random(1,150), internal::random(1,150))) ); - CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random(1,150), internal::random(1,150))) ); + CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_5( zero_sized_objects() ); } } diff --git a/gtsam/3rdparty/Eigen/test/product_large.cpp b/gtsam/3rdparty/Eigen/test/product_large.cpp index 8ed937068..6f7a91b84 100644 --- a/gtsam/3rdparty/Eigen/test/product_large.cpp +++ b/gtsam/3rdparty/Eigen/test/product_large.cpp @@ -27,11 +27,11 @@ void test_product_large() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product(MatrixXf(internal::random(1,320), internal::random(1,320))) ); - CALL_SUBTEST_2( product(MatrixXd(internal::random(1,320), internal::random(1,320))) ); - CALL_SUBTEST_3( product(MatrixXi(internal::random(1,320), internal::random(1,320))) ); - CALL_SUBTEST_4( product(MatrixXcf(internal::random(1,150), internal::random(1,150))) ); - CALL_SUBTEST_5( product(Matrix(internal::random(1,320), internal::random(1,320))) ); + CALL_SUBTEST_1( product(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_2( product(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_3( product(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_4( product(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_5( product(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } #if defined EIGEN_TEST_PART_6 diff --git a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp index 1048a894d..c6ceb487f 100644 --- a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp +++ b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp @@ -72,9 +72,9 @@ void test_product_mmtr() { for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1((mmtr(internal::random(1,320)))); - CALL_SUBTEST_2((mmtr(internal::random(1,320)))); - CALL_SUBTEST_3((mmtr >(internal::random(1,200)))); - CALL_SUBTEST_4((mmtr >(internal::random(1,200)))); + CALL_SUBTEST_1((mmtr(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_2((mmtr(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_3((mmtr >(internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); + CALL_SUBTEST_4((mmtr >(internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); } } diff --git a/gtsam/3rdparty/Eigen/test/product_notemporary.cpp b/gtsam/3rdparty/Eigen/test/product_notemporary.cpp index 980e2bbaf..1a9dc14d9 100644 --- a/gtsam/3rdparty/Eigen/test/product_notemporary.cpp +++ b/gtsam/3rdparty/Eigen/test/product_notemporary.cpp @@ -141,13 +141,13 @@ void test_product_notemporary() { int s; for(int i = 0; i < g_repeat; i++) { - s = internal::random(16,320); + s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( product_notemporary(MatrixXf(s, s)) ); - s = internal::random(16,320); + s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( product_notemporary(MatrixXd(s, s)) ); - s = internal::random(16,120); + s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( product_notemporary(MatrixXcf(s,s)) ); - s = internal::random(16,120); + s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_notemporary(MatrixXcd(s,s)) ); } } diff --git a/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp index ca84969eb..6c1d83bf2 100644 --- a/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp @@ -83,13 +83,14 @@ void test_product_selfadjoint() CALL_SUBTEST_1( product_selfadjoint(Matrix()) ); CALL_SUBTEST_2( product_selfadjoint(Matrix()) ); CALL_SUBTEST_3( product_selfadjoint(Matrix3d()) ); - s = internal::random(1,150); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_selfadjoint(MatrixXcf(s, s)) ); - s = internal::random(1,150); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( product_selfadjoint(MatrixXcd(s,s)) ); - s = internal::random(1,320); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( product_selfadjoint(MatrixXd(s,s)) ); - s = internal::random(1,320); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_7( product_selfadjoint(Matrix(s,s)) ); } + EIGEN_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/product_small.cpp b/gtsam/3rdparty/Eigen/test/product_small.cpp index d7f1c09ff..cf430a2d3 100644 --- a/gtsam/3rdparty/Eigen/test/product_small.cpp +++ b/gtsam/3rdparty/Eigen/test/product_small.cpp @@ -25,6 +25,25 @@ #define EIGEN_NO_STATIC_ASSERT #include "product.h" +// regression test for bug 447 +void product1x1() +{ + Matrix matAstatic; + Matrix matBstatic; + matAstatic.setRandom(); + matBstatic.setRandom(); + VERIFY_IS_APPROX( (matAstatic * matBstatic).coeff(0,0), + matAstatic.cwiseProduct(matBstatic.transpose()).sum() ); + + MatrixXf matAdynamic(1,3); + MatrixXf matBdynamic(3,1); + matAdynamic.setRandom(); + matBdynamic.setRandom(); + VERIFY_IS_APPROX( (matAdynamic * matBdynamic).coeff(0,0), + matAdynamic.cwiseProduct(matBdynamic.transpose()).sum() ); +} + + void test_product_small() { for(int i = 0; i < g_repeat; i++) { @@ -33,6 +52,7 @@ void test_product_small() CALL_SUBTEST_3( product(Matrix3d()) ); CALL_SUBTEST_4( product(Matrix4d()) ); CALL_SUBTEST_5( product(Matrix4f()) ); + CALL_SUBTEST_6( product1x1() ); } #ifdef EIGEN_TEST_PART_6 diff --git a/gtsam/3rdparty/Eigen/test/product_symm.cpp b/gtsam/3rdparty/Eigen/test/product_symm.cpp index 21c2f605b..4585c3b6a 100644 --- a/gtsam/3rdparty/Eigen/test/product_symm.cpp +++ b/gtsam/3rdparty/Eigen/test/product_symm.cpp @@ -98,14 +98,14 @@ void test_product_symm() { for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1(( symm(internal::random(1,320),internal::random(1,320)) )); - CALL_SUBTEST_2(( symm(internal::random(1,320),internal::random(1,320)) )); - CALL_SUBTEST_3(( symm,Dynamic,Dynamic>(internal::random(1,200),internal::random(1,200)) )); - CALL_SUBTEST_4(( symm,Dynamic,Dynamic>(internal::random(1,200),internal::random(1,200)) )); + CALL_SUBTEST_1(( symm(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_2(( symm(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_3(( symm,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)) )); + CALL_SUBTEST_4(( symm,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)) )); - CALL_SUBTEST_5(( symm(internal::random(1,320)) )); - CALL_SUBTEST_6(( symm(internal::random(1,320)) )); - CALL_SUBTEST_7(( symm,Dynamic,1>(internal::random(1,320)) )); - CALL_SUBTEST_8(( symm,Dynamic,1>(internal::random(1,320)) )); + CALL_SUBTEST_5(( symm(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_6(( symm(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_7(( symm,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); + CALL_SUBTEST_8(( symm,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)) )); } } diff --git a/gtsam/3rdparty/Eigen/test/product_syrk.cpp b/gtsam/3rdparty/Eigen/test/product_syrk.cpp index 553410b9b..71285acb1 100644 --- a/gtsam/3rdparty/Eigen/test/product_syrk.cpp +++ b/gtsam/3rdparty/Eigen/test/product_syrk.cpp @@ -101,13 +101,13 @@ void test_product_syrk() for(int i = 0; i < g_repeat ; i++) { int s; - s = internal::random(1,320); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( syrk(MatrixXf(s, s)) ); - s = internal::random(1,320); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( syrk(MatrixXd(s, s)) ); - s = internal::random(1,200); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( syrk(MatrixXcf(s, s)) ); - s = internal::random(1,200); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( syrk(MatrixXcd(s, s)) ); } } diff --git a/gtsam/3rdparty/Eigen/test/product_trmm.cpp b/gtsam/3rdparty/Eigen/test/product_trmm.cpp index e117f6931..dab05d8b0 100644 --- a/gtsam/3rdparty/Eigen/test/product_trmm.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trmm.cpp @@ -24,70 +24,100 @@ #include "main.h" -template void trmm(int size,int /*othersize*/) +template +void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), + int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), + int otherCols = OtherCols==Dynamic?internal::random(1,EIGEN_TEST_MAX_SIZE):OtherCols) { typedef typename NumTraits::Real RealScalar; - typedef Matrix MatrixColMaj; - typedef Matrix MatrixRowMaj; + typedef Matrix TriMatrix; + typedef Matrix OnTheRight; + typedef Matrix OnTheLeft; + + typedef Matrix ResXS; + typedef Matrix ResSX; - DenseIndex rows = size; - DenseIndex cols = internal::random(1,size); - - MatrixColMaj triV(rows,cols), triH(cols,rows), upTri(cols,rows), loTri(rows,cols), - unitUpTri(cols,rows), unitLoTri(rows,cols), strictlyUpTri(cols,rows), strictlyLoTri(rows,cols); - MatrixColMaj ge1(rows,cols), ge2(cols,rows), ge3; - MatrixRowMaj rge3; + TriMatrix mat(rows,cols), tri(rows,cols), triTr(cols,rows); + + OnTheRight ge_right(cols,otherCols); + OnTheLeft ge_left(otherCols,rows); + ResSX ge_sx, ge_sx_save; + ResXS ge_xs, ge_xs_save; Scalar s1 = internal::random(), s2 = internal::random(); - triV.setRandom(); - triH.setRandom(); - loTri = triV.template triangularView(); - upTri = triH.template triangularView(); - unitLoTri = triV.template triangularView(); - unitUpTri = triH.template triangularView(); - strictlyLoTri = triV.template triangularView(); - strictlyUpTri = triH.template triangularView(); - ge1.setRandom(); - ge2.setRandom(); + mat.setRandom(); + tri = mat.template triangularView(); + triTr = mat.transpose().template triangularView(); + ge_right.setRandom(); + ge_left.setRandom(); - VERIFY_IS_APPROX( ge3 = triV.template triangularView() * ge2, loTri * ge2); - VERIFY_IS_APPROX( ge3 = ge2 * triV.template triangularView(), ge2 * loTri); - VERIFY_IS_APPROX( ge3 = triH.template triangularView() * ge1, upTri * ge1); - VERIFY_IS_APPROX( ge3 = ge1 * triH.template triangularView(), ge1 * upTri); - VERIFY_IS_APPROX( ge3 = (s1*triV.adjoint()).template triangularView() * (s2*ge1), s1*loTri.adjoint() * (s2*ge1)); - VERIFY_IS_APPROX( ge3 = ge1 * triV.adjoint().template triangularView(), ge1 * loTri.adjoint()); - VERIFY_IS_APPROX( ge3 = triH.adjoint().template triangularView() * ge2, upTri.adjoint() * ge2); - VERIFY_IS_APPROX( ge3 = ge2 * triH.adjoint().template triangularView(), ge2 * upTri.adjoint()); - VERIFY_IS_APPROX( ge3 = triV.template triangularView() * ge1.adjoint(), loTri * ge1.adjoint()); - VERIFY_IS_APPROX( ge3 = ge1.adjoint() * triV.template triangularView(), ge1.adjoint() * loTri); - VERIFY_IS_APPROX( ge3 = triH.template triangularView() * ge2.adjoint(), upTri * ge2.adjoint()); - VERIFY_IS_APPROX(rge3.noalias() = triH.template triangularView() * ge2.adjoint(), upTri * ge2.adjoint()); - VERIFY_IS_APPROX( ge3 = (s1*triV).adjoint().template triangularView() * ge2.adjoint(), internal::conj(s1) * loTri.adjoint() * ge2.adjoint()); - VERIFY_IS_APPROX(rge3.noalias() = triV.adjoint().template triangularView() * ge2.adjoint(), loTri.adjoint() * ge2.adjoint()); - VERIFY_IS_APPROX( ge3 = triH.adjoint().template triangularView() * ge1.adjoint(), upTri.adjoint() * ge1.adjoint()); - VERIFY_IS_APPROX(rge3.noalias() = triH.adjoint().template triangularView() * ge1.adjoint(), upTri.adjoint() * ge1.adjoint()); - - VERIFY_IS_APPROX( ge3 = triV.template triangularView() * ge2, unitLoTri * ge2); - VERIFY_IS_APPROX( rge3.noalias() = ge2 * triV.template triangularView(), ge2 * unitLoTri); - VERIFY_IS_APPROX( ge3 = ge2 * triV.template triangularView(), ge2 * unitLoTri); - VERIFY_IS_APPROX( ge3 = (s1*triV).adjoint().template triangularView() * ge2.adjoint(), internal::conj(s1) * unitLoTri.adjoint() * ge2.adjoint()); - - VERIFY_IS_APPROX( ge3 = triV.template triangularView() * ge2, strictlyLoTri * ge2); - VERIFY_IS_APPROX( rge3.noalias() = ge2 * triV.template triangularView(), ge2 * strictlyLoTri); - VERIFY_IS_APPROX( ge3 = ge2 * triV.template triangularView(), ge2 * strictlyLoTri); - VERIFY_IS_APPROX( ge3 = (s1*triV).adjoint().template triangularView() * ge2.adjoint(), internal::conj(s1) * strictlyLoTri.adjoint() * ge2.adjoint()); + VERIFY_IS_APPROX( ge_xs = mat.template triangularView() * ge_right, tri * ge_right); + VERIFY_IS_APPROX( ge_sx = ge_left * mat.template triangularView(), ge_left * tri); + + VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView() * ge_right, tri * ge_right); + VERIFY_IS_APPROX( ge_sx.noalias() = ge_left * mat.template triangularView(), ge_left * tri); + + VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.transpose()), s1*triTr.conjugate() * (s2*ge_left.transpose())); + VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.transpose() * mat.adjoint().template triangularView(), ge_right.transpose() * triTr.conjugate()); + + VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()), s1*triTr.conjugate() * (s2*ge_left.adjoint())); + VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.adjoint() * mat.adjoint().template triangularView(), ge_right.adjoint() * triTr.conjugate()); + + ge_xs_save = ge_xs; + VERIFY_IS_APPROX( (ge_xs_save + s1*triTr.conjugate() * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()) ); + ge_sx_save = ge_sx; + VERIFY_IS_APPROX( ge_sx_save - (ge_right.adjoint() * (-s1 * triTr).conjugate()).eval(), ge_sx.noalias() -= (ge_right.adjoint() * (-s1 * mat).adjoint().template triangularView()).eval()); + + VERIFY_IS_APPROX( ge_xs = (s1*mat).adjoint().template triangularView() * ge_left.adjoint(), internal::conj(s1) * triTr.conjugate() * ge_left.adjoint()); + + // TODO check with sub-matrix expressions ? } +template +void trmv(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE)) +{ + trmm(rows,cols,1); +} + +template +void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), int otherCols = internal::random(1,EIGEN_TEST_MAX_SIZE)) +{ + trmm(rows,cols,otherCols); +} + +#define CALL_ALL_ORDERS(NB,SCALAR,MODE) \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + EIGEN_CAT(CALL_SUBTEST_,NB)((trmm())); \ + \ + EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv())); \ + EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv())); + + +#define CALL_ALL(NB,SCALAR) \ + CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Upper) \ + CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitUpper) \ + CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyUpper) \ + CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Lower) \ + CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitLower) \ + CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyLower) + + void test_product_trmm() { for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1((trmm(internal::random(1,320),internal::random(1,320)))); - CALL_SUBTEST_2((trmm(internal::random(1,320),internal::random(1,320)))); - CALL_SUBTEST_3((trmm >(internal::random(1,200),internal::random(1,200)))); - CALL_SUBTEST_4((trmm >(internal::random(1,200),internal::random(1,200)))); + CALL_ALL(1,float); // EIGEN_SUFFIXES;11;111;21;121;31;131 + CALL_ALL(2,double); // EIGEN_SUFFIXES;12;112;22;122;32;132 + CALL_ALL(3,std::complex); // EIGEN_SUFFIXES;13;113;23;123;33;133 + CALL_ALL(4,std::complex); // EIGEN_SUFFIXES;14;114;24;124;34;134 } } diff --git a/gtsam/3rdparty/Eigen/test/product_trmv.cpp b/gtsam/3rdparty/Eigen/test/product_trmv.cpp index cfb7355ff..52707d22b 100644 --- a/gtsam/3rdparty/Eigen/test/product_trmv.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trmv.cpp @@ -93,11 +93,12 @@ void test_product_trmv() CALL_SUBTEST_1( trmv(Matrix()) ); CALL_SUBTEST_2( trmv(Matrix()) ); CALL_SUBTEST_3( trmv(Matrix3d()) ); - s = internal::random(1,200); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( trmv(MatrixXcf(s,s)) ); - s = internal::random(1,200); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( trmv(MatrixXcd(s,s)) ); - s = internal::random(1,320); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( trmv(Matrix(s, s)) ); } + EIGEN_UNUSED_VARIABLE(s); } diff --git a/gtsam/3rdparty/Eigen/test/product_trsolve.cpp b/gtsam/3rdparty/Eigen/test/product_trsolve.cpp index c207cc500..20380accd 100644 --- a/gtsam/3rdparty/Eigen/test/product_trsolve.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trsolve.cpp @@ -93,14 +93,14 @@ void test_product_trsolve() for(int i = 0; i < g_repeat ; i++) { // matrices - CALL_SUBTEST_1((trsolve(internal::random(1,320),internal::random(1,320)))); - CALL_SUBTEST_2((trsolve(internal::random(1,320),internal::random(1,320)))); - CALL_SUBTEST_3((trsolve,Dynamic,Dynamic>(internal::random(1,200),internal::random(1,200)))); - CALL_SUBTEST_4((trsolve,Dynamic,Dynamic>(internal::random(1,200),internal::random(1,200)))); + CALL_SUBTEST_1((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_2((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_3((trsolve,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); + CALL_SUBTEST_4((trsolve,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); // vectors - CALL_SUBTEST_1((trsolve(internal::random(1,320)))); - CALL_SUBTEST_5((trsolve,Dynamic,1>(internal::random(1,320)))); + CALL_SUBTEST_1((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_5((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); CALL_SUBTEST_6((trsolve())); CALL_SUBTEST_7((trsolve())); CALL_SUBTEST_8((trsolve,4,1>())); diff --git a/gtsam/3rdparty/Eigen/test/qr.cpp b/gtsam/3rdparty/Eigen/test/qr.cpp index 7e9ac9df9..6005c0e27 100644 --- a/gtsam/3rdparty/Eigen/test/qr.cpp +++ b/gtsam/3rdparty/Eigen/test/qr.cpp @@ -114,8 +114,8 @@ template void qr_verify_assert() void test_qr() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( qr(MatrixXf(internal::random(1,200),internal::random(1,200))) ); - CALL_SUBTEST_2( qr(MatrixXcd(internal::random(1,200),internal::random(1,200))) ); + CALL_SUBTEST_1( qr(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_2( qr(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_3(( qr_fixedsize, 2 >() )); CALL_SUBTEST_4(( qr_fixedsize, 4 >() )); CALL_SUBTEST_5(( qr_fixedsize, 7 >() )); diff --git a/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp b/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp index 3cf651fa7..cdcf060ef 100644 --- a/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp +++ b/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp @@ -30,7 +30,7 @@ template void qr() { typedef typename MatrixType::Index Index; - Index rows = internal::random(2,200), cols = internal::random(2,200), cols2 = internal::random(2,200); + Index rows = internal::random(2,EIGEN_TEST_MAX_SIZE), cols = internal::random(2,EIGEN_TEST_MAX_SIZE), cols2 = internal::random(2,EIGEN_TEST_MAX_SIZE); Index rank = internal::random(1, (std::min)(rows, cols)-1); typedef typename MatrixType::Scalar Scalar; diff --git a/gtsam/3rdparty/Eigen/test/redux.cpp b/gtsam/3rdparty/Eigen/test/redux.cpp index a8bcf3b51..61d1bf911 100644 --- a/gtsam/3rdparty/Eigen/test/redux.cpp +++ b/gtsam/3rdparty/Eigen/test/redux.cpp @@ -35,6 +35,10 @@ template void matrixRedux(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols); + // The entries of m1 are uniformly distributed in [0,1], so m1.prod() is very small. This may lead to test + // failures if we underflow into denormals. Thus, we scale so that entires are close to 1. + MatrixType m1_for_prod = MatrixType::Ones(rows, cols) + Scalar(0.2) * m1; + VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1)); VERIFY_IS_APPROX(MatrixType::Ones(rows, cols).sum(), Scalar(float(rows*cols))); // the float() here to shut up excessive MSVC warning about int->complex conversion being lossy Scalar s(0), p(1), minc(internal::real(m1.coeff(0))), maxc(internal::real(m1.coeff(0))); @@ -42,7 +46,7 @@ template void matrixRedux(const MatrixType& m) for(int i = 0; i < rows; i++) { s += m1(i,j); - p *= m1(i,j); + p *= m1_for_prod(i,j); minc = (std::min)(internal::real(minc), internal::real(m1(i,j))); maxc = (std::max)(internal::real(maxc), internal::real(m1(i,j))); } @@ -50,7 +54,7 @@ template void matrixRedux(const MatrixType& m) VERIFY_IS_APPROX(m1.sum(), s); VERIFY_IS_APPROX(m1.mean(), mean); - VERIFY_IS_APPROX(m1.prod(), p); + VERIFY_IS_APPROX(m1_for_prod.prod(), p); VERIFY_IS_APPROX(m1.real().minCoeff(), internal::real(minc)); VERIFY_IS_APPROX(m1.real().maxCoeff(), internal::real(maxc)); @@ -61,7 +65,7 @@ template void matrixRedux(const MatrixType& m) Index c1 = internal::random(c0+1,cols)-c0; VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).sum(), m1.block(r0,c0,r1,c1).eval().sum()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).mean(), m1.block(r0,c0,r1,c1).eval().mean()); - VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).prod(), m1.block(r0,c0,r1,c1).eval().prod()); + VERIFY_IS_APPROX(m1_for_prod.block(r0,c0,r1,c1).prod(), m1_for_prod.block(r0,c0,r1,c1).eval().prod()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().minCoeff(), m1.block(r0,c0,r1,c1).real().eval().minCoeff()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().maxCoeff(), m1.block(r0,c0,r1,c1).real().eval().maxCoeff()); @@ -78,6 +82,8 @@ template void vectorRedux(const VectorType& w) Index size = w.size(); VectorType v = VectorType::Random(size); + VectorType v_for_prod = VectorType::Ones(size) + Scalar(0.2) * v; // see comment above declaration of m1_for_prod + for(int i = 1; i < size; i++) { Scalar s(0), p(1); @@ -85,12 +91,12 @@ template void vectorRedux(const VectorType& w) for(int j = 0; j < i; j++) { s += v[j]; - p *= v[j]; + p *= v_for_prod[j]; minc = (std::min)(minc, internal::real(v[j])); maxc = (std::max)(maxc, internal::real(v[j])); } VERIFY_IS_MUCH_SMALLER_THAN(internal::abs(s - v.head(i).sum()), Scalar(1)); - VERIFY_IS_APPROX(p, v.head(i).prod()); + VERIFY_IS_APPROX(p, v_for_prod.head(i).prod()); VERIFY_IS_APPROX(minc, v.real().head(i).minCoeff()); VERIFY_IS_APPROX(maxc, v.real().head(i).maxCoeff()); } @@ -102,12 +108,12 @@ template void vectorRedux(const VectorType& w) for(int j = i; j < size; j++) { s += v[j]; - p *= v[j]; + p *= v_for_prod[j]; minc = (std::min)(minc, internal::real(v[j])); maxc = (std::max)(maxc, internal::real(v[j])); } VERIFY_IS_MUCH_SMALLER_THAN(internal::abs(s - v.tail(size-i).sum()), Scalar(1)); - VERIFY_IS_APPROX(p, v.tail(size-i).prod()); + VERIFY_IS_APPROX(p, v_for_prod.tail(size-i).prod()); VERIFY_IS_APPROX(minc, v.real().tail(size-i).minCoeff()); VERIFY_IS_APPROX(maxc, v.real().tail(size-i).maxCoeff()); } @@ -119,12 +125,12 @@ template void vectorRedux(const VectorType& w) for(int j = i; j < size-i; j++) { s += v[j]; - p *= v[j]; + p *= v_for_prod[j]; minc = (std::min)(minc, internal::real(v[j])); maxc = (std::max)(maxc, internal::real(v[j])); } VERIFY_IS_MUCH_SMALLER_THAN(internal::abs(s - v.segment(i, size-2*i).sum()), Scalar(1)); - VERIFY_IS_APPROX(p, v.segment(i, size-2*i).prod()); + VERIFY_IS_APPROX(p, v_for_prod.segment(i, size-2*i).prod()); VERIFY_IS_APPROX(minc, v.real().segment(i, size-2*i).minCoeff()); VERIFY_IS_APPROX(maxc, v.real().segment(i, size-2*i).maxCoeff()); } @@ -139,6 +145,9 @@ template void vectorRedux(const VectorType& w) void test_redux() { + // the max size cannot be too large, otherwise reduxion operations obviously generate large errors. + int maxsize = (std::min)(100,EIGEN_TEST_MAX_SIZE); + EIGEN_UNUSED_VARIABLE(maxsize); for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( matrixRedux(Matrix()) ); CALL_SUBTEST_1( matrixRedux(Array()) ); @@ -146,19 +155,19 @@ void test_redux() CALL_SUBTEST_2( matrixRedux(Array2f()) ); CALL_SUBTEST_3( matrixRedux(Matrix4d()) ); CALL_SUBTEST_3( matrixRedux(Array4d()) ); - CALL_SUBTEST_4( matrixRedux(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( matrixRedux(ArrayXXcf(3, 3)) ); - CALL_SUBTEST_5( matrixRedux(MatrixXd(8, 12)) ); - CALL_SUBTEST_5( matrixRedux(ArrayXXd(8, 12)) ); - CALL_SUBTEST_6( matrixRedux(MatrixXi(8, 12)) ); - CALL_SUBTEST_6( matrixRedux(ArrayXXi(8, 12)) ); + CALL_SUBTEST_4( matrixRedux(MatrixXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_4( matrixRedux(ArrayXXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_5( matrixRedux(MatrixXd (internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_5( matrixRedux(ArrayXXd (internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_6( matrixRedux(MatrixXi (internal::random(1,maxsize), internal::random(1,maxsize))) ); + CALL_SUBTEST_6( matrixRedux(ArrayXXi (internal::random(1,maxsize), internal::random(1,maxsize))) ); } for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_7( vectorRedux(Vector4f()) ); CALL_SUBTEST_7( vectorRedux(Array4f()) ); - CALL_SUBTEST_5( vectorRedux(VectorXd(10)) ); - CALL_SUBTEST_5( vectorRedux(ArrayXd(10)) ); - CALL_SUBTEST_8( vectorRedux(VectorXf(33)) ); - CALL_SUBTEST_8( vectorRedux(ArrayXf(33)) ); + CALL_SUBTEST_5( vectorRedux(VectorXd(internal::random(1,maxsize))) ); + CALL_SUBTEST_5( vectorRedux(ArrayXd(internal::random(1,maxsize))) ); + CALL_SUBTEST_8( vectorRedux(VectorXf(internal::random(1,maxsize))) ); + CALL_SUBTEST_8( vectorRedux(ArrayXf(internal::random(1,maxsize))) ); } } diff --git a/gtsam/3rdparty/Eigen/test/schur_complex.cpp b/gtsam/3rdparty/Eigen/test/schur_complex.cpp index a2a89fd67..15532e2cc 100644 --- a/gtsam/3rdparty/Eigen/test/schur_complex.cpp +++ b/gtsam/3rdparty/Eigen/test/schur_complex.cpp @@ -80,7 +80,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim void test_schur_complex() { CALL_SUBTEST_1(( schur() )); - CALL_SUBTEST_2(( schur(internal::random(1,50)) )); + CALL_SUBTEST_2(( schur(internal::random(1,EIGEN_TEST_MAX_SIZE/4)) )); CALL_SUBTEST_3(( schur, 1, 1> >() )); CALL_SUBTEST_4(( schur >() )); diff --git a/gtsam/3rdparty/Eigen/test/schur_real.cpp b/gtsam/3rdparty/Eigen/test/schur_real.cpp index 58717fa1a..ba0947d8c 100644 --- a/gtsam/3rdparty/Eigen/test/schur_real.cpp +++ b/gtsam/3rdparty/Eigen/test/schur_real.cpp @@ -99,7 +99,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim void test_schur_real() { CALL_SUBTEST_1(( schur() )); - CALL_SUBTEST_2(( schur(internal::random(1,50)) )); + CALL_SUBTEST_2(( schur(internal::random(1,EIGEN_TEST_MAX_SIZE/4)) )); CALL_SUBTEST_3(( schur >() )); CALL_SUBTEST_4(( schur >() )); diff --git a/gtsam/3rdparty/Eigen/test/selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/selfadjoint.cpp index 622045f20..db66017c1 100644 --- a/gtsam/3rdparty/Eigen/test/selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/selfadjoint.cpp @@ -54,20 +54,23 @@ template void selfadjoint(const MatrixType& m) void bug_159() { - Matrix3d m = Matrix3d::Random().selfadjointView(); + Matrix3d m = Matrix3d::Random().selfadjointView(); + EIGEN_UNUSED_VARIABLE(m) } void test_selfadjoint() { for(int i = 0; i < g_repeat ; i++) { - int s = internal::random(1,20); EIGEN_UNUSED_VARIABLE(s); + int s = internal::random(1,EIGEN_TEST_MAX_SIZE); EIGEN_UNUSED_VARIABLE(s); CALL_SUBTEST_1( selfadjoint(Matrix()) ); CALL_SUBTEST_2( selfadjoint(Matrix()) ); CALL_SUBTEST_3( selfadjoint(Matrix3cf()) ); CALL_SUBTEST_4( selfadjoint(MatrixXcd(s,s)) ); CALL_SUBTEST_5( selfadjoint(Matrix(s, s)) ); + + EIGEN_UNUSED_VARIABLE(s) } CALL_SUBTEST_1( bug_159() ); diff --git a/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp new file mode 100644 index 000000000..f1af0e467 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp @@ -0,0 +1,55 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" + +template void test_simplicial_cholesky_T() +{ + SimplicialCholesky, Lower> chol_colmajor_lower; + SimplicialCholesky, Upper> chol_colmajor_upper; + SimplicialLLT, Lower> llt_colmajor_lower; + SimplicialLDLT, Upper> llt_colmajor_upper; + SimplicialLDLT, Lower> ldlt_colmajor_lower; + SimplicialLDLT, Upper> ldlt_colmajor_upper; + + check_sparse_spd_solving(chol_colmajor_lower); + check_sparse_spd_solving(chol_colmajor_upper); + check_sparse_spd_solving(llt_colmajor_lower); + check_sparse_spd_solving(llt_colmajor_upper); + check_sparse_spd_solving(ldlt_colmajor_lower); + check_sparse_spd_solving(ldlt_colmajor_upper); + + check_sparse_spd_determinant(chol_colmajor_lower); + check_sparse_spd_determinant(chol_colmajor_upper); + check_sparse_spd_determinant(llt_colmajor_lower); + check_sparse_spd_determinant(llt_colmajor_upper); + check_sparse_spd_determinant(ldlt_colmajor_lower); + check_sparse_spd_determinant(ldlt_colmajor_upper); +} + +void test_simplicial_cholesky() +{ + CALL_SUBTEST_1(test_simplicial_cholesky_T()); + CALL_SUBTEST_2(test_simplicial_cholesky_T >()); +} diff --git a/gtsam/3rdparty/Eigen/test/smallvectors.cpp b/gtsam/3rdparty/Eigen/test/smallvectors.cpp index 144944162..4c09d4ec6 100644 --- a/gtsam/3rdparty/Eigen/test/smallvectors.cpp +++ b/gtsam/3rdparty/Eigen/test/smallvectors.cpp @@ -22,6 +22,7 @@ // License and a copy of the GNU General Public License along with // Eigen. If not, see . +#define EIGEN_NO_STATIC_ASSERT #include "main.h" template void smallVectors() @@ -29,6 +30,7 @@ template void smallVectors() typedef Matrix V2; typedef Matrix V3; typedef Matrix V4; + typedef Matrix VX; Scalar x1 = internal::random(), x2 = internal::random(), x3 = internal::random(), @@ -45,6 +47,29 @@ template void smallVectors() VERIFY_IS_APPROX(x3, v3.z()); VERIFY_IS_APPROX(x3, v4.z()); VERIFY_IS_APPROX(x4, v4.w()); + + if (!NumTraits::IsInteger) + { + VERIFY_RAISES_ASSERT(V3(2, 1)) + VERIFY_RAISES_ASSERT(V3(3, 2)) + VERIFY_RAISES_ASSERT(V3(Scalar(3), 1)) + VERIFY_RAISES_ASSERT(V3(3, Scalar(1))) + VERIFY_RAISES_ASSERT(V3(Scalar(3), Scalar(1))) + VERIFY_RAISES_ASSERT(V3(Scalar(123), Scalar(123))) + + VERIFY_RAISES_ASSERT(V4(1, 3)) + VERIFY_RAISES_ASSERT(V4(2, 4)) + VERIFY_RAISES_ASSERT(V4(1, Scalar(4))) + VERIFY_RAISES_ASSERT(V4(Scalar(1), 4)) + VERIFY_RAISES_ASSERT(V4(Scalar(1), Scalar(4))) + VERIFY_RAISES_ASSERT(V4(Scalar(123), Scalar(123))) + + VERIFY_RAISES_ASSERT(VX(3, 2)) + VERIFY_RAISES_ASSERT(VX(Scalar(3), 1)) + VERIFY_RAISES_ASSERT(VX(3, Scalar(1))) + VERIFY_RAISES_ASSERT(VX(Scalar(3), Scalar(1))) + VERIFY_RAISES_ASSERT(VX(Scalar(123), Scalar(123))) + } } void test_smallvectors() diff --git a/gtsam/3rdparty/Eigen/test/sparse.h b/gtsam/3rdparty/Eigen/test/sparse.h index cc9da4855..860d9ad9c 100644 --- a/gtsam/3rdparty/Eigen/test/sparse.h +++ b/gtsam/3rdparty/Eigen/test/sparse.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Daniel Gomez Ferro +// Copyright (C) 2008-2011 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -23,6 +23,7 @@ // Eigen. If not, see . #ifndef EIGEN_TESTSPARSE_H +#define EIGEN_TESTSPARSE_H #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET @@ -67,30 +68,36 @@ enum { * \param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero, * and zero coefficients respectively. */ -template void +template void initSparse(double density, - Matrix& refMat, - SparseMatrix& sparseMat, + Matrix& refMat, + SparseMatrix& sparseMat, int flags = 0, std::vector* zeroCoords = 0, std::vector* nonzeroCoords = 0) { + enum { IsRowMajor = SparseMatrix::IsRowMajor }; sparseMat.setZero(); - sparseMat.reserve(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? internal::random() : Scalar(0); if ((flags&ForceNonZeroDiag) && (i==j)) { v = internal::random()*Scalar(3.); v = v*v + Scalar(5.); } - if ((flags & MakeLowerTriangular) && j>i) + if ((flags & MakeLowerTriangular) && aj>ai) v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); + nonzeroCoords->push_back(Vector2i(ai,aj)); } else if (zeroCoords) { - zeroCoords->push_back(Vector2i(i,j)); + zeroCoords->push_back(Vector2i(ai,aj)); } - refMat(i,j) = v; + refMat(ai,aj) = v; } } - sparseMat.finalize(); + //sparseMat.finalize(); } -template void +template void initSparse(double density, - Matrix& refMat, - DynamicSparseMatrix& sparseMat, + Matrix& refMat, + DynamicSparseMatrix& sparseMat, int flags = 0, std::vector* zeroCoords = 0, std::vector* nonzeroCoords = 0) { + enum { IsRowMajor = DynamicSparseMatrix::IsRowMajor }; sparseMat.setZero(); sparseMat.reserve(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? internal::random() : Scalar(0); if ((flags&ForceNonZeroDiag) && (i==j)) { v = internal::random()*Scalar(3.); v = v*v + Scalar(5.); } - if ((flags & MakeLowerTriangular) && j>i) + if ((flags & MakeLowerTriangular) && aj>ai) v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); + nonzeroCoords->push_back(Vector2i(ai,aj)); } else if (zeroCoords) { - zeroCoords->push_back(Vector2i(i,j)); + zeroCoords->push_back(Vector2i(ai,aj)); } - refMat(i,j) = v; + refMat(ai,aj) = v; } } sparseMat.finalize(); @@ -181,4 +193,5 @@ initSparse(double density, } } +#include #endif // EIGEN_TESTSPARSE_H diff --git a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp index 6f54d2ebc..637c5db51 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp @@ -1,6 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // +// Copyright (C) 2008-2011 Gael Guennebaud // Copyright (C) 2008 Daniel Gomez Ferro // // Eigen is free software; you can redistribute it and/or @@ -109,7 +110,8 @@ template void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - m2.reserve(10); + if(internal::random()%2) + m2.reserve(VectorXi::Constant(m2.outerSize(), 2)); for (int j=0; j void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - m2.reserve(10); + if(internal::random()%2) + m2.reserve(VectorXi::Constant(m2.outerSize(), 2)); + for (int k=0; k(0,rows-1); + int j = internal::random(0,cols-1); + if ((m1.coeff(i,j)==Scalar(0)) && (internal::random()%2)) + m2.insert(i,j) = m1(i,j) = internal::random(); + else + { + Scalar v = internal::random(); + m2.coeffRef(i,j) += v; + m1(i,j) += v; + } + } + VERIFY_IS_APPROX(m2,m1); + } + + // test insert (un-compressed) + for(int mode=0;mode<4;++mode) + { + DenseMatrix m1(rows,cols); + m1.setZero(); + SparseMatrixType m2(rows,cols); + VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? m2.innerSize() : std::max(1,m2.innerSize()/8))); + m2.reserve(r); for (int k=0; k(0,rows-1); int j = internal::random(0,cols-1); if (m1.coeff(i,j)==Scalar(0)) m2.insert(i,j) = m1(i,j) = internal::random(); + if(mode==3) + m2.reserve(r); } - m2.finalize(); + if(internal::random()%2) + m2.makeCompressed(); VERIFY_IS_APPROX(m2,m1); } @@ -166,7 +196,13 @@ template void sparse_basic(const SparseMatrixType& re VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); - VERIFY_IS_APPROX(m1.col(0).dot(refM2.row(0)), refM1.col(0).dot(refM2.row(0))); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.row(0).dot(refM2.row(0))); + else + VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.col(0).dot(refM2.row(0))); + + VERIFY_IS_APPROX(m1.conjugate(), refM1.conjugate()); + VERIFY_IS_APPROX(m1.real(), refM1.real()); refM4.setRandom(); // sparse cwise* dense @@ -190,10 +226,37 @@ template void sparse_basic(const SparseMatrixType& re DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); SparseMatrixType m2(rows, rows); initSparse(density, refMat2, m2); - int j0 = internal::random(0,rows-1); - int j1 = internal::random(0,rows-1); - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); + int j0 = internal::random(0,rows-1); + int j1 = internal::random(0,rows-1); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.row(j0)); + else + VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); + + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.row(j0)+refMat2.row(j1)); + else + VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); + + SparseMatrixType m3(rows,rows); + m3.reserve(VectorXi::Constant(rows,rows/2)); + for(int j=0; j0) + VERIFY(j==internal::real(m3.innerVector(j).lastCoeff())); + } + m3.makeCompressed(); + for(int j=0; j0) + VERIFY(j==internal::real(m3.innerVector(j).lastCoeff())); + } + //m2.innerVector(j0) = 2*m2.innerVector(j1); //refMat2.col(j0) = 2*refMat2.col(j1); //VERIFY_IS_APPROX(m2, refMat2); @@ -204,12 +267,19 @@ template void sparse_basic(const SparseMatrixType& re DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); SparseMatrixType m2(rows, rows); initSparse(density, refMat2, m2); - int j0 = internal::random(0,rows-2); - int j1 = internal::random(0,rows-2); + int j0 = internal::random(0,rows-2); + int j1 = internal::random(0,rows-2); int n0 = internal::random(1,rows-(std::max)(j0,j1)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); //m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); //refMat2.block(0,j0,rows,n0) = refMat2.block(0,j0,rows,n0) + refMat2.block(0,j1,rows,n0); } @@ -239,7 +309,11 @@ template void sparse_basic(const SparseMatrixType& re else { countTrueNonZero++; - m2.insertBackByOuterInner(j,i) = refM2(i,j) = Scalar(1); + m2.insertBackByOuterInner(j,i) = Scalar(1); + if(SparseMatrixType::IsRowMajor) + refM2(j,i) = Scalar(1); + else + refM2(i,j) = Scalar(1); } } } @@ -250,8 +324,52 @@ template void sparse_basic(const SparseMatrixType& re VERIFY(countTrueNonZero==m2.nonZeros()); VERIFY_IS_APPROX(m2, refM2); } + + // test setFromTriplets + { + typedef Triplet TripletType; + std::vector triplets; + int ntriplets = rows*cols; + triplets.reserve(ntriplets); + DenseMatrix refMat(rows,cols); + refMat.setZero(); + for(int i=0;i(0,rows-1); + int c = internal::random(0,cols-1); + Scalar v = internal::random(); + triplets.push_back(TripletType(r,c,v)); + refMat(r,c) += v; + } + SparseMatrixType m(rows,cols); + m.setFromTriplets(triplets.begin(), triplets.end()); + VERIFY_IS_APPROX(m, refMat); + } + + // test triangularView + { + DenseMatrix refMat2(rows, rows), refMat3(rows, rows); + SparseMatrixType m2(rows, rows), m3(rows, rows); + initSparse(density, refMat2, m2); + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + } // test selfadjointView + if(!SparseMatrixType::IsRowMajor) { DenseMatrix refMat2(rows, rows), refMat3(rows, rows); SparseMatrixType m2(rows, rows), m3(rows, rows); @@ -268,15 +386,25 @@ template void sparse_basic(const SparseMatrixType& re initSparse(density, refMat2, m2); VERIFY_IS_APPROX(m2.eval(), refMat2.sparseView().eval()); } + + // test diagonal + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); + SparseMatrixType m2(rows, rows); + initSparse(density, refMat2, m2); + VERIFY_IS_APPROX(m2.diagonal(), refMat2.diagonal().eval()); + } } void test_sparse_basic() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_basic(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_basic(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_basic(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_basic(DynamicSparseMatrix(8, 8)) ); + int s = Eigen::internal::random(1,50); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(8, 8)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, ColMajor>(s, s)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, RowMajor>(s, s)) )); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); } } diff --git a/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp b/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp new file mode 100644 index 000000000..4d22e358e --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp @@ -0,0 +1,202 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse.h" + +template void sparse_permutations(const SparseMatrixType& ref) +{ + typedef typename SparseMatrixType::Index Index; + + const Index rows = ref.rows(); + const Index cols = ref.cols(); + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::Index Index; + typedef SparseMatrix OtherSparseMatrixType; + typedef Matrix DenseMatrix; + typedef Matrix VectorI; + + double density = (std::max)(8./(rows*cols), 0.01); + + SparseMatrixType mat(rows, cols), up(rows,cols), lo(rows,cols); + OtherSparseMatrixType res; + DenseMatrix mat_d = DenseMatrix::Zero(rows, cols), up_sym_d, lo_sym_d, res_d; + + initSparse(density, mat_d, mat, 0); + + up = mat.template triangularView(); + lo = mat.template triangularView(); + + up_sym_d = mat_d.template selfadjointView(); + lo_sym_d = mat_d.template selfadjointView(); + + VERIFY_IS_APPROX(mat, mat_d); + VERIFY_IS_APPROX(up, DenseMatrix(mat_d.template triangularView())); + VERIFY_IS_APPROX(lo, DenseMatrix(mat_d.template triangularView())); + + PermutationMatrix p, p_null; + VectorI pi; + randomPermutationVector(pi, cols); + p.indices() = pi; + + res = mat*p; + res_d = mat_d*p; + VERIFY(res.isApprox(res_d) && "mat*p"); + + res = p*mat; + res_d = p*mat_d; + VERIFY(res.isApprox(res_d) && "p*mat"); + + res = mat*p.inverse(); + res_d = mat*p.inverse(); + VERIFY(res.isApprox(res_d) && "mat*inv(p)"); + + res = p.inverse()*mat; + res_d = p.inverse()*mat_d; + VERIFY(res.isApprox(res_d) && "inv(p)*mat"); + + res = mat.twistedBy(p); + res_d = (p * mat_d) * p.inverse(); + VERIFY(res.isApprox(res_d) && "p*mat*inv(p)"); + + + res = mat.template selfadjointView().twistedBy(p_null); + res_d = up_sym_d; + VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); + + res = mat.template selfadjointView().twistedBy(p_null); + res_d = lo_sym_d; + VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); + + + res = up.template selfadjointView().twistedBy(p_null); + res_d = up_sym_d; + VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); + + res = lo.template selfadjointView().twistedBy(p_null); + res_d = lo_sym_d; + VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); + + + res = mat.template selfadjointView(); + res_d = up_sym_d; + VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); + + res = mat.template selfadjointView(); + res_d = lo_sym_d; + VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); + + res = up.template selfadjointView(); + res_d = up_sym_d; + VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); + + res = lo.template selfadjointView(); + res_d = lo_sym_d; + VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); + + + res.template selfadjointView() = mat.template selfadjointView(); + res_d = up_sym_d.template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint upper to upper"); + + res.template selfadjointView() = mat.template selfadjointView(); + res_d = up_sym_d.template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint upper to lower"); + + res.template selfadjointView() = mat.template selfadjointView(); + res_d = lo_sym_d.template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint lower to upper"); + + res.template selfadjointView() = mat.template selfadjointView(); + res_d = lo_sym_d.template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint lower to lower"); + + + + res.template selfadjointView() = mat.template selfadjointView().twistedBy(p); + res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint upper twisted to upper"); + + res.template selfadjointView() = mat.template selfadjointView().twistedBy(p); + res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint lower twisted to upper"); + + res.template selfadjointView() = mat.template selfadjointView().twistedBy(p); + res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint lower twisted to lower"); + + res.template selfadjointView() = mat.template selfadjointView().twistedBy(p); + res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "full selfadjoint upper twisted to lower"); + + + res.template selfadjointView() = up.template selfadjointView().twistedBy(p); + res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to upper"); + + res.template selfadjointView() = lo.template selfadjointView().twistedBy(p); + res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "lower selfadjoint twisted to upper"); + + res.template selfadjointView() = lo.template selfadjointView().twistedBy(p); + res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "lower selfadjoint twisted to lower"); + + res.template selfadjointView() = up.template selfadjointView().twistedBy(p); + res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView(); + VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to lower"); + + + res = mat.template selfadjointView().twistedBy(p); + res_d = (p * up_sym_d) * p.inverse(); + VERIFY(res.isApprox(res_d) && "full selfadjoint upper twisted to full"); + + res = mat.template selfadjointView().twistedBy(p); + res_d = (p * lo_sym_d) * p.inverse(); + VERIFY(res.isApprox(res_d) && "full selfadjoint lower twisted to full"); + + res = up.template selfadjointView().twistedBy(p); + res_d = (p * up_sym_d) * p.inverse(); + VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to full"); + + res = lo.template selfadjointView().twistedBy(p); + res_d = (p * lo_sym_d) * p.inverse(); + VERIFY(res.isApprox(res_d) && "lower selfadjoint twisted to full"); +} + +template void sparse_permutations_all(int size) +{ + CALL_SUBTEST(( sparse_permutations(SparseMatrix(size,size)) )); + CALL_SUBTEST(( sparse_permutations(SparseMatrix(size,size)) )); + CALL_SUBTEST(( sparse_permutations(SparseMatrix(size,size)) )); + CALL_SUBTEST(( sparse_permutations(SparseMatrix(size,size)) )); +} + +void test_sparse_permutations() +{ + for(int i = 0; i < g_repeat; i++) { + int s = Eigen::internal::random(1,50); + CALL_SUBTEST_1(( sparse_permutations_all(s) )); + CALL_SUBTEST_2(( sparse_permutations_all >(s) )); + } +} diff --git a/gtsam/3rdparty/Eigen/test/sparse_product.cpp b/gtsam/3rdparty/Eigen/test/sparse_product.cpp index a53ab3f1b..2c28d1131 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_product.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_product.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Daniel Gomez Ferro +// Copyright (C) 2008-2011 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -24,11 +24,37 @@ #include "sparse.h" -template void sparse_product(const SparseMatrixType& ref) +template struct test_outer; + +template struct test_outer { + static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { + int c = internal::random(0,m2.cols()-1); + int c1 = internal::random(0,m2.cols()-1); + VERIFY_IS_APPROX(m4=m2.col(c)*refMat2.col(c1).transpose(), refMat4=refMat2.col(c)*refMat2.col(c1).transpose()); + VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.col(c).transpose(), refMat4=refMat2.col(c1)*refMat2.col(c).transpose()); + } +}; + +template struct test_outer { + static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { + int r = internal::random(0,m2.rows()-1); + int c1 = internal::random(0,m2.cols()-1); + VERIFY_IS_APPROX(m4=m2.row(r).transpose()*refMat2.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*refMat2.col(c1).transpose()); + VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.row(r), refMat4=refMat2.col(c1)*refMat2.row(r)); + } +}; + +// (m2,m4,refMat2,refMat4,dv1); +// VERIFY_IS_APPROX(m4=m2.innerVector(c)*dv1.transpose(), refMat4=refMat2.colVector(c)*dv1.transpose()); +// VERIFY_IS_APPROX(m4=dv1*mcm.col(c).transpose(), refMat4=dv1*refMat2.col(c).transpose()); + +template void sparse_product() { typedef typename SparseMatrixType::Index Index; - const Index rows = ref.rows(); - const Index cols = ref.cols(); + Index n = 100; + const Index rows = internal::random(1,n); + const Index cols = internal::random(1,n); + const Index depth = internal::random(1,n); typedef typename SparseMatrixType::Scalar Scalar; enum { Flags = SparseMatrixType::Flags }; @@ -41,50 +67,71 @@ template void sparse_product(const SparseMatrixType& // test matrix-matrix product { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat3 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat4 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat5 = DenseMatrix::Random(rows, rows); + DenseMatrix refMat2 = DenseMatrix::Zero(rows, depth); + DenseMatrix refMat2t = DenseMatrix::Zero(depth, rows); + DenseMatrix refMat3 = DenseMatrix::Zero(depth, cols); + DenseMatrix refMat3t = DenseMatrix::Zero(cols, depth); + DenseMatrix refMat4 = DenseMatrix::Zero(rows, cols); + DenseMatrix refMat4t = DenseMatrix::Zero(cols, rows); + DenseMatrix refMat5 = DenseMatrix::Random(depth, cols); + DenseMatrix refMat6 = DenseMatrix::Random(rows, rows); DenseMatrix dm4 = DenseMatrix::Zero(rows, rows); - DenseVector dv1 = DenseVector::Random(rows); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - SparseMatrixType m4(rows, rows); - initSparse(density, refMat2, m2); - initSparse(density, refMat3, m3); - initSparse(density, refMat4, m4); +// DenseVector dv1 = DenseVector::Random(rows); + SparseMatrixType m2 (rows, depth); + SparseMatrixType m2t(depth, rows); + SparseMatrixType m3 (depth, cols); + SparseMatrixType m3t(cols, depth); + SparseMatrixType m4 (rows, cols); + SparseMatrixType m4t(cols, rows); + SparseMatrixType m6(rows, rows); + initSparse(density, refMat2, m2); + initSparse(density, refMat2t, m2t); + initSparse(density, refMat3, m3); + initSparse(density, refMat3t, m3t); + initSparse(density, refMat4, m4); + initSparse(density, refMat4t, m4t); + initSparse(density, refMat6, m6); - int c = internal::random(0,rows-1); +// int c = internal::random(0,depth-1); + // sparse * sparse VERIFY_IS_APPROX(m4=m2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - VERIFY_IS_APPROX(m4=m2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); + VERIFY_IS_APPROX(m4=m2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(m4=m2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(m4=m2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose()); VERIFY_IS_APPROX(m4 = m2*m3/s1, refMat4 = refMat2*refMat3/s1); VERIFY_IS_APPROX(m4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1); VERIFY_IS_APPROX(m4 = s2*m2*m3*s1, refMat4 = s2*refMat2*refMat3*s1); + VERIFY_IS_APPROX(m4=(m2*m3).pruned(0), refMat4=refMat2*refMat3); + VERIFY_IS_APPROX(m4=(m2t.transpose()*m3).pruned(0), refMat4=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(m4=(m2t.transpose()*m3t.transpose()).pruned(0), refMat4=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(m4=(m2*m3t.transpose()).pruned(0), refMat4=refMat2*refMat3t.transpose()); + + // test aliasing + m4 = m2; refMat4 = refMat2; + VERIFY_IS_APPROX(m4=m4*m3, refMat4=refMat4*refMat3); + // sparse * dense VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=m2*refMat3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); + VERIFY_IS_APPROX(dm4=m2*refMat3t.transpose(), refMat4=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3, refMat4=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); VERIFY_IS_APPROX(dm4=m2*(refMat3+refMat3), refMat4=refMat2*(refMat3+refMat3)); - VERIFY_IS_APPROX(dm4=m2.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2.transpose()*(refMat3+refMat5)*0.5); + VERIFY_IS_APPROX(dm4=m2t.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2t.transpose()*(refMat3+refMat5)*0.5); // dense * sparse VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=refMat2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); + VERIFY_IS_APPROX(dm4=refMat2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); // sparse * dense and dense * sparse outer product - VERIFY_IS_APPROX(m4=m2.col(c)*dv1.transpose(), refMat4=refMat2.col(c)*dv1.transpose()); - VERIFY_IS_APPROX(m4=dv1*m2.col(c).transpose(), refMat4=dv1*refMat2.col(c).transpose()); + test_outer::run(m2,m4,refMat2,refMat4); - VERIFY_IS_APPROX(m3=m3*m3, refMat3=refMat3*refMat3); + VERIFY_IS_APPROX(m6=m6*m6, refMat6=refMat6*refMat6); } // test matrix - diagonal product @@ -116,18 +163,19 @@ template void sparse_product(const SparseMatrixType& do { initSparse(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular); } while (refUp.isZero()); - refLo = refUp.transpose().conjugate(); - mLo = mUp.transpose().conjugate(); + refLo = refUp.adjoint(); + mLo = mUp.adjoint(); refS = refUp + refLo; refS.diagonal() *= 0.5; mS = mUp + mLo; + // TODO be able to address the diagonal.... for (int k=0; k void sparse_produc void test_sparse_product() { for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_product(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_product(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_product(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_product(DynamicSparseMatrix(8, 8)) ); - + CALL_SUBTEST_1( (sparse_product >()) ); + CALL_SUBTEST_1( (sparse_product >()) ); + CALL_SUBTEST_2( (sparse_product, ColMajor > >()) ); + CALL_SUBTEST_2( (sparse_product, RowMajor > >()) ); CALL_SUBTEST_4( (sparse_product_regression_test, Matrix >()) ); } } diff --git a/gtsam/3rdparty/Eigen/test/sparse_solver.h b/gtsam/3rdparty/Eigen/test/sparse_solver.h new file mode 100644 index 000000000..69bf716ed --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/sparse_solver.h @@ -0,0 +1,324 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse.h" +#include + +template +void check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + + DenseRhs refX = dA.lu().solve(db); + + Rhs x(b.rows(), b.cols()); + Rhs oldb = b; + + solver.compute(A); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; + exit(0); + return; + } + x = solver.solve(b); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: solving failed\n"; + return; + } + VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); + + VERIFY(x.isApprox(refX,test_precision())); + + x.setZero(); + // test the analyze/factorize API + solver.analyzePattern(A); + solver.factorize(A); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; + exit(0); + return; + } + x = solver.solve(b); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: solving failed\n"; + return; + } + VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); + + VERIFY(x.isApprox(refX,test_precision())); + + // test Block as the result and rhs: + { + DenseRhs x(db.rows(), db.cols()); + DenseRhs b(db), oldb(db); + x.setZero(); + x.block(0,0,x.rows(),x.cols()) = solver.solve(b.block(0,0,b.rows(),b.cols())); + VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(x.isApprox(refX,test_precision())); + } +} + +template +void check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const Rhs& refX) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef typename Mat::RealScalar RealScalar; + + Rhs x(b.rows(), b.cols()); + + solver.compute(A); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: factorization failed (check_sparse_solving_real_cases)\n"; + exit(0); + return; + } + x = solver.solve(b); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: solving failed\n"; + return; + } + + RealScalar res_error; + // Compute the norm of the relative error + if(refX.size() != 0) + res_error = (refX - x).norm()/refX.norm(); + else + { + // Compute the relative residual norm + res_error = (b - A * x).norm()/b.norm(); + } + if (res_error > test_precision() ){ + std::cerr << "Test " << g_test_stack.back() << " failed in "EI_PP_MAKE_STRING(__FILE__) + << " (" << EI_PP_MAKE_STRING(__LINE__) << ")" << std::endl << std::endl; + abort(); + } + +} +template +void check_sparse_determinant(Solver& solver, const typename Solver::MatrixType& A, const DenseMat& dA) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef typename Mat::RealScalar RealScalar; + + solver.compute(A); + if (solver.info() != Success) + { + std::cerr << "sparse solver testing: factorization failed (check_sparse_determinant)\n"; + return; + } + + Scalar refDet = dA.determinant(); + VERIFY_IS_APPROX(refDet,solver.determinant()); +} + + +template +int generate_sparse_spd_problem(Solver& , typename Solver::MatrixType& A, typename Solver::MatrixType& halfA, DenseMat& dA, int maxSize = 300) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef Matrix DenseMatrix; + + int size = internal::random(1,maxSize); + double density = (std::max)(8./(size*size), 0.01); + + Mat M(size, size); + DenseMatrix dM(size, size); + + initSparse(density, dM, M, ForceNonZeroDiag); + + A = M * M.adjoint(); + dA = dM * dM.adjoint(); + + halfA.resize(size,size); + halfA.template selfadjointView().rankUpdate(M); + + return size; +} + + +#ifdef TEST_REAL_CASES +template +inline std::string get_matrixfolder() +{ + std::string mat_folder = TEST_REAL_CASES; + if( internal::is_same >::value || internal::is_same >::value ) + mat_folder = mat_folder + static_cast("/complex/"); + else + mat_folder = mat_folder + static_cast("/real/"); + return mat_folder; +} +#endif + +template void check_sparse_spd_solving(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef typename Mat::Index Index; + typedef SparseMatrix SpMat; + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + + // generate the problem + Mat A, halfA; + DenseMatrix dA; + int size = generate_sparse_spd_problem(solver, A, halfA, dA); + + // generate the right hand sides + int rhsCols = internal::random(1,16); + double density = (std::max)(8./(size*rhsCols), 0.1); + SpMat B(size,rhsCols); + DenseVector b = DenseVector::Random(size); + DenseMatrix dB(size,rhsCols); + initSparse(density, dB, B, ForceNonZeroDiag); + + for (int i = 0; i < g_repeat; i++) { + check_sparse_solving(solver, A, b, dA, b); + check_sparse_solving(solver, halfA, b, dA, b); + check_sparse_solving(solver, A, dB, dA, dB); + check_sparse_solving(solver, halfA, dB, dA, dB); + check_sparse_solving(solver, A, B, dA, dB); + check_sparse_solving(solver, halfA, B, dA, dB); + } + + // First, get the folder +#ifdef TEST_REAL_CASES + if (internal::is_same::value + || internal::is_same >::value) + return ; + + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + if (it.sym() == SPD){ + Mat halfA; + PermutationMatrix pnull; + halfA.template selfadjointView() = it.matrix().template triangularView().twistedBy(pnull); + + std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; + check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); + check_sparse_solving_real_cases(solver, halfA, it.rhs(), it.refX()); + } + } +#endif +} + +template void check_sparse_spd_determinant(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef Matrix DenseMatrix; + + // generate the problem + Mat A, halfA; + DenseMatrix dA; + generate_sparse_spd_problem(solver, A, halfA, dA, 30); + + for (int i = 0; i < g_repeat; i++) { + check_sparse_determinant(solver, A, dA); + check_sparse_determinant(solver, halfA, dA ); + } +} + +template +int generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef Matrix DenseMatrix; + + int size = internal::random(1,maxSize); + double density = (std::max)(8./(size*size), 0.01); + + A.resize(size,size); + dA.resize(size,size); + + initSparse(density, dA, A, ForceNonZeroDiag); + + return size; +} + +template void check_sparse_square_solving(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + + int rhsCols = internal::random(1,16); + + Mat A; + DenseMatrix dA; + int size = generate_sparse_square_problem(solver, A, dA); + + DenseVector b = DenseVector::Random(size); + DenseMatrix dB = DenseMatrix::Random(size,rhsCols); + A.makeCompressed(); + for (int i = 0; i < g_repeat; i++) { + check_sparse_solving(solver, A, b, dA, b); + check_sparse_solving(solver, A, dB, dA, dB); + } + + // First, get the folder +#ifdef TEST_REAL_CASES + if (internal::is_same::value + || internal::is_same >::value) + return ; + + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; + check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); + } +#endif + +} + +template void check_sparse_square_determinant(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef Matrix DenseMatrix; + + // generate the problem + Mat A; + DenseMatrix dA; + generate_sparse_square_problem(solver, A, dA, 30); + A.makeCompressed(); + for (int i = 0; i < g_repeat; i++) { + check_sparse_determinant(solver, A, dA); + } +} diff --git a/gtsam/3rdparty/Eigen/test/sparse_solvers.cpp b/gtsam/3rdparty/Eigen/test/sparse_solvers.cpp index 12a1cb9b6..a3d79b0ea 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_solvers.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_solvers.cpp @@ -72,6 +72,15 @@ template void sparse_solvers(int rows, int cols) initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords); VERIFY_IS_APPROX(refMat2.template triangularView().solve(vec2), m2.template triangularView().solve(vec3)); + VERIFY_IS_APPROX(refMat2.conjugate().template triangularView().solve(vec2), + m2.conjugate().template triangularView().solve(vec3)); + { + SparseMatrix cm2(m2); + //Index rows, Index cols, Index nnz, Index* outerIndexPtr, Index* innerIndexPtr, Scalar* valuePtr + MappedSparseMatrix mm2(rows, cols, cm2.nonZeros(), cm2.outerIndexPtr(), cm2.innerIndexPtr(), cm2.valuePtr()); + VERIFY_IS_APPROX(refMat2.conjugate().template triangularView().solve(vec2), + mm2.conjugate().template triangularView().solve(vec3)); + } // lower - transpose initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords); diff --git a/gtsam/3rdparty/Eigen/test/sparse_vector.cpp b/gtsam/3rdparty/Eigen/test/sparse_vector.cpp index e0c281c83..09d36a51b 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_vector.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_vector.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Daniel Gomez Ferro +// Copyright (C) 2008-2011 Gael Guennebaud // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -34,9 +34,9 @@ template void sparse_vector(int rows, int cols) typedef SparseMatrix SparseMatrixType; Scalar eps = 1e-6; - SparseMatrixType m1(rows,cols); + SparseMatrixType m1(rows,rows); SparseVectorType v1(rows), v2(rows), v3(rows); - DenseMatrix refM1 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); DenseVector refV1 = DenseVector::Random(rows), refV2 = DenseVector::Random(rows), refV3 = DenseVector::Random(rows); @@ -86,6 +86,11 @@ template void sparse_vector(int rows, int cols) VERIFY_IS_APPROX(v1.dot(v2), refV1.dot(refV2)); VERIFY_IS_APPROX(v1.dot(refV2), refV1.dot(refV2)); + VERIFY_IS_APPROX(v1.dot(m1*v2), refV1.dot(refM1*refV2)); + int i = internal::random(0,rows-1); + VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i))); + + VERIFY_IS_APPROX(v1.squaredNorm(), refV1.squaredNorm()); } diff --git a/gtsam/3rdparty/Eigen/test/superlu_support.cpp b/gtsam/3rdparty/Eigen/test/superlu_support.cpp new file mode 100644 index 000000000..ad435943b --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/superlu_support.cpp @@ -0,0 +1,37 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" + +#include + +void test_superlu_support() +{ + SuperLU > superlu_double_colmajor; + SuperLU > > superlu_cplxdouble_colmajor; + CALL_SUBTEST_1( check_sparse_square_solving(superlu_double_colmajor) ); + CALL_SUBTEST_2( check_sparse_square_solving(superlu_cplxdouble_colmajor) ); + CALL_SUBTEST_1( check_sparse_square_determinant(superlu_double_colmajor) ); + CALL_SUBTEST_2( check_sparse_square_determinant(superlu_cplxdouble_colmajor) ); +} diff --git a/gtsam/3rdparty/Eigen/test/triangular.cpp b/gtsam/3rdparty/Eigen/test/triangular.cpp index 69decb793..4db8f8482 100644 --- a/gtsam/3rdparty/Eigen/test/triangular.cpp +++ b/gtsam/3rdparty/Eigen/test/triangular.cpp @@ -42,16 +42,8 @@ template void triangular_square(const MatrixType& m) m3(rows, cols), m4(rows, cols), r1(rows, cols), - r2(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols), - identity = Matrix - ::Identity(rows, rows), - square = Matrix - ::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); + r2(rows, cols); + VectorType v2 = VectorType::Random(rows); MatrixType m1up = m1.template triangularView(); MatrixType m2up = m2.template triangularView(); @@ -113,14 +105,14 @@ template void triangular_square(const MatrixType& m) // check M * inv(L) using in place API m4 = m3; - m3.transpose().template triangularView().solveInPlace(trm4); - VERIFY(m4.cwiseAbs().isIdentity(test_precision())); + m1.transpose().template triangularView().solveInPlace(trm4); + VERIFY_IS_APPROX(m4 * m1.template triangularView(), m3); // check M * inv(U) using in place API m3 = m1.template triangularView(); m4 = m3; m3.transpose().template triangularView().solveInPlace(trm4); - VERIFY(m4.cwiseAbs().isIdentity(test_precision())); + VERIFY_IS_APPROX(m4 * m1.template triangularView(), m3); // check solve with unit diagonal m3 = m1.template triangularView(); @@ -158,21 +150,12 @@ template void triangular_rect(const MatrixType& m) m3(rows, cols), m4(rows, cols), r1(rows, cols), - r2(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols); - RMatrixType identity = Matrix - ::Identity(rows, rows), - square = Matrix - ::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); + r2(rows, cols); MatrixType m1up = m1.template triangularView(); MatrixType m2up = m2.template triangularView(); - if (rows*cols>1) + if (rows>1 && cols>1) { VERIFY(m1up.isUpperTriangular()); VERIFY(m2up.transpose().isLowerTriangular()); @@ -237,15 +220,17 @@ template void triangular_rect(const MatrixType& m) void bug_159() { - Matrix3d m = Matrix3d::Random().triangularView(); + Matrix3d m = Matrix3d::Random().triangularView(); + EIGEN_UNUSED_VARIABLE(m) } void test_triangular() { + int maxsize = (std::min)(EIGEN_TEST_MAX_SIZE,20); for(int i = 0; i < g_repeat ; i++) { - int r = internal::random(2,20); EIGEN_UNUSED_VARIABLE(r); - int c = internal::random(2,20); EIGEN_UNUSED_VARIABLE(c); + int r = internal::random(2,maxsize); EIGEN_UNUSED_VARIABLE(r); + int c = internal::random(2,maxsize); EIGEN_UNUSED_VARIABLE(c); CALL_SUBTEST_1( triangular_square(Matrix()) ); CALL_SUBTEST_2( triangular_square(Matrix()) ); diff --git a/gtsam/3rdparty/Eigen/test/umfpack_support.cpp b/gtsam/3rdparty/Eigen/test/umfpack_support.cpp new file mode 100644 index 000000000..1922aa959 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/umfpack_support.cpp @@ -0,0 +1,46 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "sparse_solver.h" + +#include + +template void test_umfpack_support_T() +{ + UmfPackLU > umfpack_colmajor; + UmfPackLU > umfpack_rowmajor; + + check_sparse_square_solving(umfpack_colmajor); + check_sparse_square_solving(umfpack_rowmajor); + + check_sparse_square_determinant(umfpack_colmajor); + check_sparse_square_determinant(umfpack_rowmajor); +} + +void test_umfpack_support() +{ + CALL_SUBTEST_1(test_umfpack_support_T()); + CALL_SUBTEST_2(test_umfpack_support_T >()); +} + diff --git a/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp new file mode 100644 index 000000000..d3518b7ec --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp @@ -0,0 +1,187 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Benoit Jacob +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#define EIGEN_NO_STATIC_ASSERT + +#include "main.h" + +template void vectorwiseop_array(const ArrayType& m) +{ + typedef typename ArrayType::Index Index; + typedef typename ArrayType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef Array ColVectorType; + typedef Array RowVectorType; + + Index rows = m.rows(); + Index cols = m.cols(); + Index r = internal::random(0, rows-1), + c = internal::random(0, cols-1); + + ArrayType m1 = ArrayType::Random(rows, cols), + m2(rows, cols), + m3(rows, cols); + + ColVectorType colvec = ColVectorType::Random(rows); + RowVectorType rowvec = RowVectorType::Random(cols); + + // test addition + + m2 = m1; + m2.colwise() += colvec; + VERIFY_IS_APPROX(m2, m1.colwise() + colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + + m2 = m1; + m2.rowwise() += rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + + // test substraction + + m2 = m1; + m2.colwise() -= colvec; + VERIFY_IS_APPROX(m2, m1.colwise() - colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + + m2 = m1; + m2.rowwise() -= rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); + + // test multiplication + + m2 = m1; + m2.colwise() *= colvec; + VERIFY_IS_APPROX(m2, m1.colwise() * colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) * colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() *= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() * colvec.transpose()); + + m2 = m1; + m2.rowwise() *= rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() * rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) * rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() *= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() * rowvec.transpose()); + + // test quotient + + m2 = m1; + m2.colwise() /= colvec; + VERIFY_IS_APPROX(m2, m1.colwise() / colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) / colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() /= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() / colvec.transpose()); + + m2 = m1; + m2.rowwise() /= rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() / rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) / rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() /= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() / rowvec.transpose()); +} + +template void vectorwiseop_matrix(const MatrixType& m) +{ + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef Matrix ColVectorType; + typedef Matrix RowVectorType; + + Index rows = m.rows(); + Index cols = m.cols(); + Index r = internal::random(0, rows-1), + c = internal::random(0, cols-1); + + MatrixType m1 = MatrixType::Random(rows, cols), + m2(rows, cols), + m3(rows, cols); + + ColVectorType colvec = ColVectorType::Random(rows); + RowVectorType rowvec = RowVectorType::Random(cols); + + // test addition + + m2 = m1; + m2.colwise() += colvec; + VERIFY_IS_APPROX(m2, m1.colwise() + colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + + m2 = m1; + m2.rowwise() += rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + + // test substraction + + m2 = m1; + m2.colwise() -= colvec; + VERIFY_IS_APPROX(m2, m1.colwise() - colvec); + VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec); + + VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + + m2 = m1; + m2.rowwise() -= rowvec; + VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec); + VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec); + + VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); +} + +void test_vectorwiseop() +{ + CALL_SUBTEST_1(vectorwiseop_array(Array22cd())); + CALL_SUBTEST_2(vectorwiseop_array(Array())); + CALL_SUBTEST_3(vectorwiseop_array(ArrayXXf(3, 4))); + CALL_SUBTEST_4(vectorwiseop_matrix(Matrix4cf())); + CALL_SUBTEST_5(vectorwiseop_matrix(Matrix())); + CALL_SUBTEST_6(vectorwiseop_matrix(MatrixXd(7,2))); +} diff --git a/gtsam/3rdparty/Eigen/test/zerosized.cpp b/gtsam/3rdparty/Eigen/test/zerosized.cpp index 06e31cc09..c5d2cc6ed 100644 --- a/gtsam/3rdparty/Eigen/test/zerosized.cpp +++ b/gtsam/3rdparty/Eigen/test/zerosized.cpp @@ -62,8 +62,13 @@ void test_zerosized() zeroSizedMatrix(); zeroSizedMatrix >(); zeroSizedMatrix(); + zeroSizedMatrix >(); + zeroSizedMatrix >(); + zeroSizedMatrix >(); + zeroSizedMatrix >(); zeroSizedVector(); zeroSizedVector(); zeroSizedVector(); + zeroSizedVector >(); } diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward b/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward index 6c0a68d67..477c75378 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward @@ -79,33 +79,22 @@ namespace Eigen { } // namespace Eigen -// the Adolc's type adouble is defined in the adtl namespace -// therefore, the following internal::* functions *must* be defined -// in the same namespace -namespace Eigen { +// Eigen's require a few additional functions which must be defined in the same namespace +// than the custom scalar type own namespace +namespace adtl { - namespace internal { - - inline const adtl::adouble& conj(const adtl::adouble& x) { return x; } - inline const adtl::adouble& real(const adtl::adouble& x) { return x; } - inline adtl::adouble imag(const adtl::adouble&) { return 0.; } - inline adtl::adouble abs(const adtl::adouble& x) { return adtl::fabs(x); } - inline adtl::adouble abs2(const adtl::adouble& x) { return x*x; } - - using adtl::sqrt; - using adtl::exp; - using adtl::log; - using adtl::sin; - using adtl::cos; - using adtl::pow; - - } +inline const adouble& conj(const adouble& x) { return x; } +inline const adouble& real(const adouble& x) { return x; } +inline adouble imag(const adouble&) { return 0.; } +inline adouble abs(const adouble& x) { return fabs(x); } +inline adouble abs2(const adouble& x) { return x*x; } } namespace Eigen { template<> struct NumTraits + : NumTraits { typedef adtl::adouble Real; typedef adtl::adouble NonInteger; diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/BVH b/gtsam/3rdparty/Eigen/unsupported/Eigen/BVH index f307da2f7..d50b2bdab 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/BVH +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/BVH @@ -97,8 +97,9 @@ namespace Eigen { * The following is a simple but complete example for how to use the BVH to accelerate the search for a closest red-blue point pair: * \include BVH_Example.cpp * Output: \verbinclude BVH_Example.out - */ +} + //@{ #include "src/BVH/BVAlgorithms.h" @@ -106,6 +107,4 @@ namespace Eigen { //@} -} - #endif // EIGEN_BVH_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt index 219ec8ead..e961e72c5 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt @@ -1,6 +1,6 @@ set(Eigen_HEADERS AdolcForward BVH IterativeSolvers MatrixFunctions MoreVectorization AutoDiff AlignedVector3 Polynomials - CholmodSupport FFT NonLinearOptimization SparseExtra SuperLUSupport UmfPackSupport IterativeSolvers - NumericalDiff Skyline MPRealSupport OpenGLSupport + FFT NonLinearOptimization SparseExtra IterativeSolvers + NumericalDiff Skyline MPRealSupport OpenGLSupport KroneckerProduct Splines ) install(FILES diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CholmodSupport b/gtsam/3rdparty/Eigen/unsupported/Eigen/CholmodSupport deleted file mode 100644 index 8a4a130c3..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/CholmodSupport +++ /dev/null @@ -1,33 +0,0 @@ -#ifndef EIGEN_CHOLMODSUPPORT_MODULE_H -#define EIGEN_CHOLMODSUPPORT_MODULE_H - -#include "SparseExtra" - -#include "../../Eigen/src/Core/util/DisableStupidWarnings.h" - -extern "C" { - #include -} - -namespace Eigen { - -/** \ingroup Unsupported_modules - * \defgroup CholmodSupport_Module Cholmod Support module - * - * - * \code - * #include - * \endcode - */ - -struct Cholmod {}; -#include "src/SparseExtra/CholmodSupportLegacy.h" -#include "src/SparseExtra/CholmodSupport.h" - - -} // namespace Eigen - -#include "../../Eigen/src/Core/util/ReenableStupidWarnings.h" - -#endif // EIGEN_CHOLMODSUPPORT_MODULE_H - diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/FFT b/gtsam/3rdparty/Eigen/unsupported/Eigen/FFT index c56bd63d6..e2ec71307 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/FFT +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/FFT @@ -86,23 +86,23 @@ #ifdef EIGEN_FFTW_DEFAULT // FFTW: faster, GPL -- incompatible with Eigen in LGPL form, bigger code size # include +# include "src/FFT/ei_fftw_impl.h" namespace Eigen { -# include "src/FFT/ei_fftw_impl.h" //template typedef struct internal::fftw_impl default_fft_impl; this does not work template struct default_fft_impl : public internal::fftw_impl {}; } #elif defined EIGEN_MKL_DEFAULT // TODO // intel Math Kernel Library: fastest, commercial -- may be incompatible with Eigen in GPL form +# include "src/FFT/ei_imklfft_impl.h" namespace Eigen { -# include "src/FFT/ei_imklfft_impl.h" template struct default_fft_impl : public internal::imklfft_impl {}; } #else // internal::kissfft_impl: small, free, reasonably efficient default, derived from kissfft // +# include "src/FFT/ei_kissfft_impl.h" namespace Eigen { -# include "src/FFT/ei_kissfft_impl.h" template struct default_fft_impl : public internal::kissfft_impl {}; } diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/IterativeSolvers b/gtsam/3rdparty/Eigen/unsupported/Eigen/IterativeSolvers index bf1a9460b..4645153aa 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/IterativeSolvers +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/IterativeSolvers @@ -25,27 +25,31 @@ #ifndef EIGEN_ITERATIVE_SOLVERS_MODULE_H #define EIGEN_ITERATIVE_SOLVERS_MODULE_H -#include - -namespace Eigen { +#include /** \ingroup Unsupported_modules * \defgroup IterativeSolvers_Module Iterative solvers module * This module aims to provide various iterative linear and non linear solver algorithms. * It currently provides: * - a constrained conjugate gradient - * + * - a Householder GMRES implementation * \code * #include * \endcode */ //@{ +#include "../../Eigen/src/misc/Solve.h" +#include "../../Eigen/src/misc/SparseSolve.h" + #include "src/IterativeSolvers/IterationController.h" #include "src/IterativeSolvers/ConstrainedConjGrad.h" +#include "src/IterativeSolvers/IncompleteLU.h" +#include "../../Eigen/Jacobi" +#include "../../Eigen/Householder" +#include "src/IterativeSolvers/GMRES.h" +//#include "src/IterativeSolvers/SSORPreconditioner.h" //@} -} - #endif // EIGEN_ITERATIVE_SOLVERS_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/KroneckerProduct b/gtsam/3rdparty/Eigen/unsupported/Eigen/KroneckerProduct new file mode 100644 index 000000000..796e386ad --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/KroneckerProduct @@ -0,0 +1,26 @@ +#ifndef EIGEN_KRONECKER_PRODUCT_MODULE_H +#define EIGEN_KRONECKER_PRODUCT_MODULE_H + +#include "../../Eigen/Core" + +#include "../../Eigen/src/Core/util/DisableStupidWarnings.h" + +namespace Eigen { + +/** \ingroup Unsupported_modules + * \defgroup KroneckerProduct_Module KroneckerProduct module + * + * This module contains an experimental Kronecker product implementation. + * + * \code + * #include + * \endcode + */ + +} // namespace Eigen + +#include "src/KroneckerProduct/KroneckerTensorProduct.h" + +#include "../../Eigen/src/Core/util/ReenableStupidWarnings.h" + +#endif // EIGEN_KRONECKER_PRODUCT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/MPRealSupport b/gtsam/3rdparty/Eigen/unsupported/Eigen/MPRealSupport index 8f2396353..b5fe5e404 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/MPRealSupport +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/MPRealSupport @@ -30,11 +30,12 @@ #ifndef EIGEN_MPREALSUPPORT_MODULE_H #define EIGEN_MPREALSUPPORT_MODULE_H +#include #include #include namespace Eigen { - + /** \ingroup Unsupported_modules * \defgroup MPRealSupport_Module MPFRC++ Support module * @@ -43,7 +44,7 @@ namespace Eigen { * \endcode * * This module provides support for multi precision floating point numbers - * via the MPFR C++ + * via the MPFR C++ * library which itself is built upon MPFR/GMP. * * You can find a copy of MPFR C++ that is known to be compatible in the unsupported/test/mpreal folder. @@ -52,7 +53,7 @@ namespace Eigen { * \code #include -#include +#include #include using namespace mpfr; using namespace Eigen; @@ -106,7 +107,7 @@ int main() } }; - namespace internal { +namespace internal { template<> mpfr::mpreal random() { @@ -146,8 +147,17 @@ int main() { return a <= b || isApprox(a, b, prec); } + + template<> inline long double cast(const mpfr::mpreal& x) + { return x.toLDouble(); } + template<> inline double cast(const mpfr::mpreal& x) + { return x.toDouble(); } + template<> inline long cast(const mpfr::mpreal& x) + { return x.toLong(); } + template<> inline int cast(const mpfr::mpreal& x) + { return int(x.toLong()); } - } // end namespace internal +} // end namespace internal } #endif // EIGEN_MPREALSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/MatrixFunctions b/gtsam/3rdparty/Eigen/unsupported/Eigen/MatrixFunctions index d39c49e53..13eda8fc8 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/MatrixFunctions +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/MatrixFunctions @@ -25,6 +25,7 @@ #ifndef EIGEN_MATRIX_FUNCTIONS #define EIGEN_MATRIX_FUNCTIONS +#include #include #include #include @@ -33,8 +34,6 @@ #include #include -namespace Eigen { - /** \ingroup Unsupported_modules * \defgroup MatrixFunctions_Module Matrix functions module * \brief This module aims to provide various methods for the computation of @@ -50,9 +49,11 @@ namespace Eigen { * - \ref matrixbase_cos "MatrixBase::cos()", for computing the matrix cosine * - \ref matrixbase_cosh "MatrixBase::cosh()", for computing the matrix hyperbolic cosine * - \ref matrixbase_exp "MatrixBase::exp()", for computing the matrix exponential + * - \ref matrixbase_log "MatrixBase::log()", for computing the matrix logarithm * - \ref matrixbase_matrixfunction "MatrixBase::matrixFunction()", for computing general matrix functions * - \ref matrixbase_sin "MatrixBase::sin()", for computing the matrix sine * - \ref matrixbase_sinh "MatrixBase::sinh()", for computing the matrix hyperbolic sine + * - \ref matrixbase_sqrt "MatrixBase::sqrt()", for computing the matrix square root * * These methods are the main entry points to this module. * @@ -69,6 +70,8 @@ namespace Eigen { #include "src/MatrixFunctions/MatrixExponential.h" #include "src/MatrixFunctions/MatrixFunction.h" +#include "src/MatrixFunctions/MatrixSquareRoot.h" +#include "src/MatrixFunctions/MatrixLogarithm.h" @@ -166,10 +169,67 @@ the z-axis. \include MatrixExponential.cpp Output: \verbinclude MatrixExponential.out -\note \p M has to be a matrix of \c float, \c double, -\c complex or \c complex . +\note \p M has to be a matrix of \c float, \c double, \c long double +\c complex, \c complex, or \c complex . +\section matrixbase_log MatrixBase::log() + +Compute the matrix logarithm. + +\code +const MatrixLogarithmReturnValue MatrixBase::log() const +\endcode + +\param[in] M invertible matrix whose logarithm is to be computed. +\returns expression representing the matrix logarithm root of \p M. + +The matrix logarithm of \f$ M \f$ is a matrix \f$ X \f$ such that +\f$ \exp(X) = M \f$ where exp denotes the matrix exponential. As for +the scalar logarithm, the equation \f$ \exp(X) = M \f$ may have +multiple solutions; this function returns a matrix whose eigenvalues +have imaginary part in the interval \f$ (-\pi,\pi] \f$. + +In the real case, the matrix \f$ M \f$ should be invertible and +it should have no eigenvalues which are real and negative (pairs of +complex conjugate eigenvalues are allowed). In the complex case, it +only needs to be invertible. + +This function computes the matrix logarithm using the Schur-Parlett +algorithm as implemented by MatrixBase::matrixFunction(). The +logarithm of an atomic block is computed by MatrixLogarithmAtomic, +which uses direct computation for 1-by-1 and 2-by-2 blocks and an +inverse scaling-and-squaring algorithm for bigger blocks, with the +square roots computed by MatrixBase::sqrt(). + +Details of the algorithm can be found in Section 11.6.2 of: +Nicholas J. Higham, +Functions of Matrices: Theory and Computation, +SIAM 2008. ISBN 978-0-898716-46-7. + +Example: The following program checks that +\f[ \log \left[ \begin{array}{ccc} + \frac12\sqrt2 & -\frac12\sqrt2 & 0 \\ + \frac12\sqrt2 & \frac12\sqrt2 & 0 \\ + 0 & 0 & 1 + \end{array} \right] = \left[ \begin{array}{ccc} + 0 & \frac14\pi & 0 \\ + -\frac14\pi & 0 & 0 \\ + 0 & 0 & 0 + \end{array} \right]. \f] +This corresponds to a rotation of \f$ \frac14\pi \f$ radians around +the z-axis. This is the inverse of the example used in the +documentation of \ref matrixbase_exp "exp()". + +\include MatrixLogarithm.cpp +Output: \verbinclude MatrixLogarithm.out + +\note \p M has to be a matrix of \c float, \c double, \c long double +\c complex, \c complex, or \c complex . + +\sa MatrixBase::exp(), MatrixBase::matrixFunction(), + class MatrixLogarithmAtomic, MatrixBase::sqrt(). + \section matrixbase_matrixfunction MatrixBase::matrixFunction() @@ -245,7 +305,7 @@ Output: \verbinclude MatrixSine.out -\section matrixbase_sinh const MatrixBase::sinh() +\section matrixbase_sinh MatrixBase::sinh() Compute the matrix hyperbolic sine. @@ -261,9 +321,75 @@ This function calls \ref matrixbase_matrixfunction "matrixFunction()" with StdSt Example: \include MatrixSinh.cpp Output: \verbinclude MatrixSinh.out -*/ -} +\section matrixbase_sqrt MatrixBase::sqrt() + +Compute the matrix square root. + +\code +const MatrixSquareRootReturnValue MatrixBase::sqrt() const +\endcode + +\param[in] M invertible matrix whose square root is to be computed. +\returns expression representing the matrix square root of \p M. + +The matrix square root of \f$ M \f$ is the matrix \f$ M^{1/2} \f$ +whose square is the original matrix; so if \f$ S = M^{1/2} \f$ then +\f$ S^2 = M \f$. + +In the real case, the matrix \f$ M \f$ should be invertible and +it should have no eigenvalues which are real and negative (pairs of +complex conjugate eigenvalues are allowed). In that case, the matrix +has a square root which is also real, and this is the square root +computed by this function. + +The matrix square root is computed by first reducing the matrix to +quasi-triangular form with the real Schur decomposition. The square +root of the quasi-triangular matrix can then be computed directly. The +cost is approximately \f$ 25 n^3 \f$ real flops for the real Schur +decomposition and \f$ 3\frac13 n^3 \f$ real flops for the remainder +(though the computation time in practice is likely more than this +indicates). + +Details of the algorithm can be found in: Nicholas J. Highan, +"Computing real square roots of a real matrix", Linear Algebra +Appl., 88/89:405–430, 1987. + +If the matrix is positive-definite symmetric, then the square +root is also positive-definite symmetric. In this case, it is best to +use SelfAdjointEigenSolver::operatorSqrt() to compute it. + +In the complex case, the matrix \f$ M \f$ should be invertible; +this is a restriction of the algorithm. The square root computed by +this algorithm is the one whose eigenvalues have an argument in the +interval \f$ (-\frac12\pi, \frac12\pi] \f$. This is the usual branch +cut. + +The computation is the same as in the real case, except that the +complex Schur decomposition is used to reduce the matrix to a +triangular matrix. The theoretical cost is the same. Details are in: +Åke Björck and Sven Hammarling, "A Schur method for the +square root of a matrix", Linear Algebra Appl., +52/53:127–140, 1983. + +Example: The following program checks that the square root of +\f[ \left[ \begin{array}{cc} + \cos(\frac13\pi) & -\sin(\frac13\pi) \\ + \sin(\frac13\pi) & \cos(\frac13\pi) + \end{array} \right], \f] +corresponding to a rotation over 60 degrees, is a rotation over 30 degrees: +\f[ \left[ \begin{array}{cc} + \cos(\frac16\pi) & -\sin(\frac16\pi) \\ + \sin(\frac16\pi) & \cos(\frac16\pi) + \end{array} \right]. \f] + +\include MatrixSquareRoot.cpp +Output: \verbinclude MatrixSquareRoot.out + +\sa class RealSchur, class ComplexSchur, class MatrixSquareRoot, + SelfAdjointEigenSolver::operatorSqrt(). + +*/ #endif // EIGEN_MATRIX_FUNCTIONS diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/MoreVectorization b/gtsam/3rdparty/Eigen/unsupported/Eigen/MoreVectorization index 26a01cd29..9f0a39f75 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/MoreVectorization +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/MoreVectorization @@ -9,8 +9,8 @@ namespace Eigen { * \defgroup MoreVectorization More vectorization module */ -#include "src/MoreVectorization/MathFunctions.h" - } +#include "src/MoreVectorization/MathFunctions.h" + #endif // EIGEN_MOREVECTORIZATION_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/NonLinearOptimization b/gtsam/3rdparty/Eigen/unsupported/Eigen/NonLinearOptimization index e19db33cc..0a384d649 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/NonLinearOptimization +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/NonLinearOptimization @@ -32,8 +32,6 @@ #include #include -namespace Eigen { - /** \ingroup Unsupported_modules * \defgroup NonLinearOptimization_Module Non linear optimization module * @@ -147,8 +145,5 @@ namespace Eigen { #include "src/NonLinearOptimization/HybridNonLinearSolver.h" #include "src/NonLinearOptimization/LevenbergMarquardt.h" -} - - #endif // EIGEN_NONLINEAROPTIMIZATION_MODULE diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/NumericalDiff b/gtsam/3rdparty/Eigen/unsupported/Eigen/NumericalDiff index 2a59c14d5..eebee076d 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/NumericalDiff +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/NumericalDiff @@ -59,12 +59,13 @@ namespace Eigen { * package. * */ +} + //@{ #include "src/NumericalDiff/NumericalDiff.h" //@} -} #endif // EIGEN_NUMERICALDIFF_MODULE diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/Polynomials b/gtsam/3rdparty/Eigen/unsupported/Eigen/Polynomials index 2c2f3e100..fa58b006d 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/Polynomials +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/Polynomials @@ -16,8 +16,6 @@ #undef EIGEN_HIDE_HEAVY_CODE #endif -namespace Eigen { - /** \ingroup Unsupported_modules * \defgroup Polynomials_Module Polynomials module * @@ -129,8 +127,6 @@ namespace Eigen { Output: \verbinclude PolynomialSolver1.out */ -} // namespace Eigen - #include #endif // EIGEN_POLYNOMIALS_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/Skyline b/gtsam/3rdparty/Eigen/unsupported/Eigen/Skyline index 5247b2eab..c9823f358 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/Skyline +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/Skyline @@ -11,15 +11,13 @@ #include #include -namespace Eigen { - - /** \ingroup Unsupported_modules - * \defgroup Skyline_Module Skyline module - * - * - * - * - */ +/** \ingroup Unsupported_modules + * \defgroup Skyline_Module Skyline module + * + * + * + * + */ #include "src/Skyline/SkylineUtil.h" #include "src/Skyline/SkylineMatrixBase.h" @@ -28,8 +26,6 @@ namespace Eigen { #include "src/Skyline/SkylineInplaceLU.h" #include "src/Skyline/SkylineProduct.h" -} // namespace Eigen - #include "Eigen/src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SKYLINE_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/SparseExtra b/gtsam/3rdparty/Eigen/unsupported/Eigen/SparseExtra index 7bab7c72b..340c34736 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/SparseExtra +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/SparseExtra @@ -10,13 +10,13 @@ #include #include #include +#include +#include #ifdef EIGEN_GOOGLEHASH_SUPPORT #include #endif -namespace Eigen { - /** \ingroup Unsupported_modules * \defgroup SparseExtra_Module SparseExtra module * @@ -27,42 +27,20 @@ namespace Eigen { * \endcode */ -struct DefaultBackend {}; - - -// solver flags -enum { - CompleteFactorization = 0x0000, // the default - IncompleteFactorization = 0x0001, - MemoryEfficient = 0x0002, - - // For LLT Cholesky: - SupernodalMultifrontal = 0x0010, - SupernodalLeftLooking = 0x0020, - - // Ordering methods: - NaturalOrdering = 0x0100, // the default - MinimumDegree_AT_PLUS_A = 0x0200, - MinimumDegree_ATA = 0x0300, - ColApproxMinimumDegree = 0x0400, - Metis = 0x0500, - Scotch = 0x0600, - Chaco = 0x0700, - OrderingMask = 0x0f00 -}; #include "../../Eigen/src/misc/Solve.h" +#include "../../Eigen/src/misc/SparseSolve.h" +#include "src/SparseExtra/DynamicSparseMatrix.h" +#include "src/SparseExtra/BlockOfDynamicSparseMatrix.h" #include "src/SparseExtra/RandomSetter.h" -#include "src/SparseExtra/Solve.h" -#include "src/SparseExtra/Amd.h" -#include "src/SparseExtra/SimplicialCholesky.h" -#include "src/SparseExtra/SparseLLT.h" -#include "src/SparseExtra/SparseLDLTLegacy.h" -#include "src/SparseExtra/SparseLU.h" +#include "src/SparseExtra/MarketIO.h" -} // namespace Eigen +#if !defined(_WIN32) +#include +#include "src/SparseExtra/MatrixMarketIterator.h" +#endif #include "../../Eigen/src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenvaluesCommon.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/Splines similarity index 63% rename from gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenvaluesCommon.h rename to gtsam/3rdparty/Eigen/unsupported/Eigen/Splines index 749bea795..33769b0e4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenvaluesCommon.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/Splines @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2010 Jitse Niesen +// Copyright (C) 20010-2011 Hauke Heibel // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -22,10 +22,25 @@ // License and a copy of the GNU General Public License along with // Eigen. If not, see . -#ifndef EIGEN_EIGENVALUES_COMMON_H -#define EIGEN_EIGENVALUES_COMMON_H +#ifndef EIGEN_SPLINES_MODULE_H +#define EIGEN_SPLINES_MODULE_H +namespace Eigen +{ +/** \ingroup Unsupported_modules + * \defgroup Splines_Module Spline and spline fitting module + * + * This module provides a simple multi-dimensional spline class while + * offering most basic functionality to fit a spline to point sets. + * + * \code + * #include + * \endcode + */ +} +#include "src/Splines/SplineFwd.h" +#include "src/Splines/Spline.h" +#include "src/Splines/SplineFitting.h" -#endif // EIGEN_EIGENVALUES_COMMON_H - +#endif // EIGEN_SPLINES_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/SuperLUSupport b/gtsam/3rdparty/Eigen/unsupported/Eigen/SuperLUSupport deleted file mode 100644 index 89cb649b2..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/SuperLUSupport +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef EIGEN_SUPERLUSUPPORT_MODULE_H -#define EIGEN_SUPERLUSUPPORT_MODULE_H - -#include "SparseExtra" - -#include "../../Eigen/src/Core/util/DisableStupidWarnings.h" - -typedef int int_t; -#include -#include -#include - -namespace Eigen { struct SluMatrix; } - -namespace Eigen { - -/** \ingroup Unsupported_modules - * \defgroup SuperLUSupport_Module Super LU support - * - * - * - * \code - * #include - * \endcode - */ - -struct SuperLU {}; - -#include "src/SparseExtra/SuperLUSupport.h" - -} // namespace Eigen - -#include "../../Eigen/src/Core/util/ReenableStupidWarnings.h" - -#endif // EIGEN_SUPERLUSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/UmfPackSupport b/gtsam/3rdparty/Eigen/unsupported/Eigen/UmfPackSupport deleted file mode 100644 index c8b1e7c1f..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/UmfPackSupport +++ /dev/null @@ -1,33 +0,0 @@ -#ifndef EIGEN_UMFPACKSUPPORT_MODULE_H -#define EIGEN_UMFPACKSUPPORT_MODULE_H - -#include "SparseExtra" - -#include "../../Eigen/src/Core/util/DisableStupidWarnings.h" - -extern "C" { -#include -} - -namespace Eigen { - -/** \ingroup Unsupported_modules - * \defgroup UmfPackSupport_Module UmfPack support module - * - * - * - * - * \code - * #include - * \endcode - */ - -struct UmfPack {}; - -#include "src/SparseExtra/UmfPackSupport.h" - -} // namespace Eigen - -#include "../../Eigen/src/Core/util/ReenableStupidWarnings.h" - -#endif // EIGEN_UMFPACKSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h index 4fe168a88..e5442a5ef 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h @@ -40,7 +40,7 @@ public: template AutoDiffJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {} template - AutoDiffJacobian(const T0& a0, const T1& a1, const T1& a2) : Functor(a0, a1, a2) {} + AutoDiffJacobian(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2) {} enum { InputsAtCompileTime = Functor::InputsAtCompileTime, diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h index 7517035d9..70d3222f5 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h @@ -101,7 +101,7 @@ class AutoDiffScalar /** Conversion from a scalar constant to an active scalar. * The derivatives are set to zero. */ - explicit AutoDiffScalar(const Real& value) + /*explicit*/ AutoDiffScalar(const Real& value) : m_value(value) { if(m_derivatives.size()>0) @@ -151,6 +151,27 @@ class AutoDiffScalar inline const DerType& derivatives() const { return m_derivatives; } inline DerType& derivatives() { return m_derivatives; } + inline bool operator< (const Scalar& other) const { return m_value < other; } + inline bool operator<=(const Scalar& other) const { return m_value <= other; } + inline bool operator> (const Scalar& other) const { return m_value > other; } + inline bool operator>=(const Scalar& other) const { return m_value >= other; } + inline bool operator==(const Scalar& other) const { return m_value == other; } + inline bool operator!=(const Scalar& other) const { return m_value != other; } + + friend inline bool operator< (const Scalar& a, const AutoDiffScalar& b) { return a < b.value(); } + friend inline bool operator<=(const Scalar& a, const AutoDiffScalar& b) { return a <= b.value(); } + friend inline bool operator> (const Scalar& a, const AutoDiffScalar& b) { return a > b.value(); } + friend inline bool operator>=(const Scalar& a, const AutoDiffScalar& b) { return a >= b.value(); } + friend inline bool operator==(const Scalar& a, const AutoDiffScalar& b) { return a == b.value(); } + friend inline bool operator!=(const Scalar& a, const AutoDiffScalar& b) { return a != b.value(); } + + template inline bool operator< (const AutoDiffScalar& b) const { return m_value < b.value(); } + template inline bool operator<=(const AutoDiffScalar& b) const { return m_value <= b.value(); } + template inline bool operator> (const AutoDiffScalar& b) const { return m_value > b.value(); } + template inline bool operator>=(const AutoDiffScalar& b) const { return m_value >= b.value(); } + template inline bool operator==(const AutoDiffScalar& b) const { return m_value == b.value(); } + template inline bool operator!=(const AutoDiffScalar& b) const { return m_value != b.value(); } + inline const AutoDiffScalar operator+(const Scalar& other) const { return AutoDiffScalar(m_value + other, m_derivatives); @@ -195,6 +216,24 @@ class AutoDiffScalar return *this; } + inline const AutoDiffScalar operator-(const Scalar& b) const + { + return AutoDiffScalar(m_value - b, m_derivatives); + } + + friend inline const AutoDiffScalar, const DerType> > + operator-(const Scalar& a, const AutoDiffScalar& b) + { + return AutoDiffScalar, const DerType> > + (a - b.value(), -b.derivatives()); + } + + inline AutoDiffScalar& operator-=(const Scalar& other) + { + value() -= other; + return *this; + } + template inline const AutoDiffScalar, const DerType,const typename internal::remove_all::type> > operator-(const AutoDiffScalar& other) const @@ -213,7 +252,6 @@ class AutoDiffScalar return *this; } - template inline const AutoDiffScalar, const DerType> > operator-() const { @@ -267,7 +305,7 @@ class AutoDiffScalar { return AutoDiffScalar, const DerType> >( other / a.value(), - a.derivatives() * (-Scalar(1)/other)); + a.derivatives() * (Scalar(-other) / (a.value()*a.value()))); } // inline const AutoDiffScalar, DerType>::Type > @@ -330,6 +368,19 @@ class AutoDiffScalar return *this; } + inline AutoDiffScalar& operator/=(const Scalar& other) + { + *this = *this / other; + return *this; + } + + template + inline AutoDiffScalar& operator/=(const AutoDiffScalar& other) + { + *this = *this / other; + return *this; + } + protected: Scalar m_value; DerType m_derivatives; @@ -463,16 +514,14 @@ template ReturnType; }; -template -struct scalar_product_traits,T> +template +struct scalar_product_traits,typename DerType::Scalar> { typedef AutoDiffScalar ReturnType; }; } // end namespace internal -} // end namespace Eigen - #define EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(FUNC,CODE) \ template \ inline const Eigen::AutoDiffScalar::type>::Scalar>, const typename Eigen::internal::remove_all::type> > \ @@ -483,87 +532,109 @@ struct scalar_product_traits,T> CODE; \ } -namespace std -{ - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs, - return ReturnType(std::abs(x.value()), x.derivatives() * (sign(x.value())));) - - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sqrt, - Scalar sqrtx = std::sqrt(x.value()); - return ReturnType(sqrtx,x.derivatives() * (Scalar(0.5) / sqrtx));) - - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cos, - return ReturnType(std::cos(x.value()), x.derivatives() * (-std::sin(x.value())));) - - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sin, - return ReturnType(std::sin(x.value()),x.derivatives() * std::cos(x.value()));) - - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(exp, - Scalar expx = std::exp(x.value()); - return ReturnType(expx,x.derivatives() * expx);) - - EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(log, - return ReturnType(std::log(x.value()),x.derivatives() * (Scalar(1)/x.value()));) - - template - inline const Eigen::AutoDiffScalar::Scalar>, const DerType> > - pow(const Eigen::AutoDiffScalar& x, typename Eigen::internal::traits::Scalar y) - { - using namespace Eigen; - typedef typename Eigen::internal::traits::Scalar Scalar; - return AutoDiffScalar, const DerType> >( - std::pow(x.value(),y), - x.derivatives() * (y * std::pow(x.value(),y-1))); - } - -} - -namespace Eigen { - -namespace internal { - template inline const AutoDiffScalar& conj(const AutoDiffScalar& x) { return x; } template inline const AutoDiffScalar& real(const AutoDiffScalar& x) { return x; } template inline typename DerType::Scalar imag(const AutoDiffScalar&) { return 0.; } +template +inline AutoDiffScalar (min)(const AutoDiffScalar& x, const T& y) { return (x <= y ? x : y); } +template +inline AutoDiffScalar (max)(const AutoDiffScalar& x, const T& y) { return (x >= y ? x : y); } +template +inline AutoDiffScalar (min)(const T& x, const AutoDiffScalar& y) { return (x < y ? x : y); } +template +inline AutoDiffScalar (max)(const T& x, const AutoDiffScalar& y) { return (x > y ? x : y); } +#define sign(x) x >= 0 ? 1 : -1 // required for abs function below + EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs, + using std::abs; return ReturnType(abs(x.value()), x.derivatives() * (sign(x.value())));) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs2, + using internal::abs2; return ReturnType(abs2(x.value()), x.derivatives() * (Scalar(2)*x.value()));) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sqrt, + using std::sqrt; Scalar sqrtx = sqrt(x.value()); return ReturnType(sqrtx,x.derivatives() * (Scalar(0.5) / sqrtx));) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cos, + using std::cos; + using std::sin; return ReturnType(cos(x.value()), x.derivatives() * (-sin(x.value())));) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sin, + using std::sin; + using std::cos; return ReturnType(sin(x.value()),x.derivatives() * cos(x.value()));) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(exp, + using std::exp; Scalar expx = exp(x.value()); return ReturnType(expx,x.derivatives() * expx);) EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(log, + using std::log; return ReturnType(log(x.value()),x.derivatives() * (Scalar(1)/x.value()));) template -inline const AutoDiffScalar::Scalar>, DerType> > -pow(const AutoDiffScalar& x, typename traits::Scalar y) -{ return std::pow(x,y);} +inline const Eigen::AutoDiffScalar::Scalar>, const DerType> > +pow(const Eigen::AutoDiffScalar& x, typename Eigen::internal::traits::Scalar y) +{ + using namespace Eigen; + typedef typename Eigen::internal::traits::Scalar Scalar; + return AutoDiffScalar, const DerType> >( + std::pow(x.value(),y), + x.derivatives() * (y * std::pow(x.value(),y-1))); +} -} // end namespace internal + +template +inline const AutoDiffScalar::Scalar,Dynamic,1> > +atan2(const AutoDiffScalar& a, const AutoDiffScalar& b) +{ + using std::atan2; + using std::max; + typedef typename internal::traits::Scalar Scalar; + typedef AutoDiffScalar > PlainADS; + PlainADS ret; + ret.value() = atan2(a.value(), b.value()); + + Scalar tmp2 = a.value() * a.value(); + Scalar tmp3 = b.value() * b.value(); + Scalar tmp4 = tmp3/(tmp2+tmp3); + + if (tmp4!=0) + ret.derivatives() = (a.derivatives() * b.value() - a.value() * b.derivatives()) * (tmp2+tmp3); + + return ret; +} + +EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tan, + using std::tan; + using std::cos; + return ReturnType(tan(x.value()),x.derivatives() * (Scalar(1)/internal::abs2(cos(x.value()))));) + +EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(asin, + using std::sqrt; + using std::asin; + return ReturnType(asin(x.value()),x.derivatives() * (Scalar(1)/sqrt(1-internal::abs2(x.value()))));) + +EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(acos, + using std::sqrt; + using std::acos; + return ReturnType(acos(x.value()),x.derivatives() * (Scalar(-1)/sqrt(1-internal::abs2(x.value()))));) #undef EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY template struct NumTraits > : NumTraits< typename NumTraits::Real > { + typedef AutoDiffScalar::Real,DerType::RowsAtCompileTime,DerType::ColsAtCompileTime> > Real; typedef AutoDiffScalar NonInteger; typedef AutoDiffScalar& Nested; enum{ diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h index d65a97740..6cba656ff 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h @@ -25,6 +25,8 @@ #ifndef EIGEN_BVALGORITHMS_H #define EIGEN_BVALGORITHMS_H +namespace Eigen { + namespace internal { #ifndef EIGEN_PARSED_BY_DOXYGEN @@ -301,4 +303,6 @@ typename Minimizer::Scalar BVMinimize(const BVH1 &tree1, const BVH2 &tree2, Mini return minimum; } +} // end namespace Eigen + #endif // EIGEN_BVALGORITHMS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/KdBVH.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/KdBVH.h index 028b4811e..13a154d5c 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/KdBVH.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/KdBVH.h @@ -25,6 +25,8 @@ #ifndef KDBVH_H_INCLUDED #define KDBVH_H_INCLUDED +namespace Eigen { + namespace internal { //internal pair class for the BVH--used instead of std::pair because of alignment @@ -69,7 +71,7 @@ struct get_boxes_helper { * * \param _Scalar The underlying scalar type of the bounding boxes * \param _Dim The dimension of the space in which the hierarchy lives - * \param _Object The object type that lives in the hierarchy. It must have value semantics. Either internal::bounding_box(_Object) must + * \param _Object The object type that lives in the hierarchy. It must have value semantics. Either bounding_box(_Object) must * be defined and return an AlignedBox<_Scalar, _Dim> or bounding boxes must be provided to the tree initializer. * * This class provides a simple (as opposed to optimized) implementation of a bounding volume hierarchy analogous to a Kd-tree. @@ -92,14 +94,14 @@ public: KdBVH() {} - /** Given an iterator range over \a Object references, constructs the BVH. Requires that internal::bounding_box(Object) return a Volume. */ + /** Given an iterator range over \a Object references, constructs the BVH. Requires that bounding_box(Object) return a Volume. */ template KdBVH(Iter begin, Iter end) { init(begin, end, 0, 0); } //int is recognized by init as not being an iterator type /** Given an iterator range over \a Object references and an iterator range over their bounding boxes, constructs the BVH */ template KdBVH(OIter begin, OIter end, BIter boxBegin, BIter boxEnd) { init(begin, end, boxBegin, boxEnd); } /** Given an iterator range over \a Object references, constructs the BVH, overwriting whatever is in there currently. - * Requires that internal::bounding_box(Object) return a Volume. */ + * Requires that bounding_box(Object) return a Volume. */ template void init(Iter begin, Iter end) { init(begin, end, 0, 0); } /** Given an iterator range over \a Object references and an iterator range over their bounding boxes, @@ -230,4 +232,6 @@ private: ObjectList objects; }; +} // end namespace Eigen + #endif //KDBVH_H_INCLUDED diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt index cd442cefa..f3180b52b 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt @@ -9,3 +9,5 @@ ADD_SUBDIRECTORY(NumericalDiff) ADD_SUBDIRECTORY(Polynomials) ADD_SUBDIRECTORY(Skyline) ADD_SUBDIRECTORY(SparseExtra) +ADD_SUBDIRECTORY(KroneckerProduct) +ADD_SUBDIRECTORY(Splines) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h index a06f6739e..5c36db70c 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h @@ -22,6 +22,8 @@ // License and a copy of the GNU General Public License along with // Eigen. If not, see . +namespace Eigen { + namespace internal { // FFTW uses non-const arguments @@ -269,4 +271,6 @@ namespace internal { } // end namespace internal +} // end namespace Eigen + /* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h index 04b98b083..c3cbb7f01 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h @@ -22,6 +22,8 @@ // License and a copy of the GNU General Public License along with // Eigen. If not, see . +namespace Eigen { + namespace internal { // This FFT implementation was derived from kissfft http:sourceforge.net/projects/kissfft @@ -426,5 +428,6 @@ struct kissfft_impl } // end namespace internal -/* vim: set filetype=cpp et sw=2 ts=2 ai: */ +} // end namespace Eigen +/* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h index 4d8e183ee..f8a550553 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h @@ -50,6 +50,8 @@ #include +namespace Eigen { + namespace internal { /** \ingroup IterativeSolvers_Module @@ -195,4 +197,6 @@ void constrained_cg(const TMatrix& A, const CMatrix& C, VectorX& x, } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_CONSTRAINEDCG_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h new file mode 100644 index 000000000..e100617d1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h @@ -0,0 +1,394 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2012 Kolja Brix +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_GMRES_H +#define EIGEN_GMRES_H + +namespace Eigen { + +namespace internal { + +/** + * Generalized Minimal Residual Algorithm based on the + * Arnoldi algorithm implemented with Householder reflections. + * + * Parameters: + * \param mat matrix of linear system of equations + * \param Rhs right hand side vector of linear system of equations + * \param x on input: initial guess, on output: solution + * \param precond preconditioner used + * \param iters on input: maximum number of iterations to perform + * on output: number of iterations performed + * \param restart number of iterations for a restart + * \param tol_error on input: residual tolerance + * on output: residuum achieved + * + * \sa IterativeMethods::bicgstab() + * + * + * For references, please see: + * + * Saad, Y. and Schultz, M. H. + * GMRES: A Generalized Minimal Residual Algorithm for Solving Nonsymmetric Linear Systems. + * SIAM J.Sci.Stat.Comp. 7, 1986, pp. 856 - 869. + * + * Saad, Y. + * Iterative Methods for Sparse Linear Systems. + * Society for Industrial and Applied Mathematics, Philadelphia, 2003. + * + * Walker, H. F. + * Implementations of the GMRES method. + * Comput.Phys.Comm. 53, 1989, pp. 311 - 320. + * + * Walker, H. F. + * Implementation of the GMRES Method using Householder Transformations. + * SIAM J.Sci.Stat.Comp. 9, 1988, pp. 152 - 163. + * + */ +template +bool gmres(const MatrixType & mat, const Rhs & rhs, Dest & x, const Preconditioner & precond, + int &iters, const int &restart, typename Dest::RealScalar & tol_error) { + + using std::sqrt; + using std::abs; + + typedef typename Dest::RealScalar RealScalar; + typedef typename Dest::Scalar Scalar; + typedef Matrix < RealScalar, Dynamic, 1 > RealVectorType; + typedef Matrix < Scalar, Dynamic, 1 > VectorType; + typedef Matrix < Scalar, Dynamic, Dynamic > FMatrixType; + + RealScalar tol = tol_error; + const int maxIters = iters; + iters = 0; + + const int m = mat.rows(); + + VectorType p0 = rhs - mat*x; + VectorType r0 = precond.solve(p0); +// RealScalar r0_sqnorm = r0.squaredNorm(); + + VectorType w = VectorType::Zero(restart + 1); + + FMatrixType H = FMatrixType::Zero(m, restart + 1); + VectorType tau = VectorType::Zero(restart + 1); + std::vector < JacobiRotation < Scalar > > G(restart); + + // generate first Householder vector + VectorType e; + RealScalar beta; + r0.makeHouseholder(e, tau.coeffRef(0), beta); + w(0)=(Scalar) beta; + H.bottomLeftCorner(m - 1, 1) = e; + + for (int k = 1; k <= restart; ++k) { + + ++iters; + + VectorType v = VectorType::Unit(m, k - 1), workspace(m); + + // apply Householder reflections H_{1} ... H_{k-1} to v + for (int i = k - 1; i >= 0; --i) { + v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data()); + } + + // apply matrix M to v: v = mat * v; + VectorType t=mat*v; + v=precond.solve(t); + + // apply Householder reflections H_{k-1} ... H_{1} to v + for (int i = 0; i < k; ++i) { + v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data()); + } + + if (v.tail(m - k).norm() != 0.0) { + + if (k <= restart) { + + // generate new Householder vector + VectorType e(m - k - 1); + RealScalar beta; + v.tail(m - k).makeHouseholder(e, tau.coeffRef(k), beta); + H.col(k).tail(m - k - 1) = e; + + // apply Householder reflection H_{k} to v + v.tail(m - k).applyHouseholderOnTheLeft(H.col(k).tail(m - k - 1), tau.coeffRef(k), workspace.data()); + + } + } + + if (k > 1) { + for (int i = 0; i < k - 1; ++i) { + // apply old Givens rotations to v + v.applyOnTheLeft(i, i + 1, G[i].adjoint()); + } + } + + if (k ().solveInPlace(y); + + // use Horner-like scheme to calculate solution vector + VectorType x_new = y(k - 1) * VectorType::Unit(m, k - 1); + + // apply Householder reflection H_{k} to x_new + x_new.tail(m - k + 1).applyHouseholderOnTheLeft(H.col(k - 1).tail(m - k), tau.coeffRef(k - 1), workspace.data()); + + for (int i = k - 2; i >= 0; --i) { + x_new += y(i) * VectorType::Unit(m, i); + // apply Householder reflection H_{i} to x_new + x_new.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data()); + } + + x += x_new; + + if (stop) { + return true; + } else { + k=0; + + // reset data for a restart r0 = rhs - mat * x; + VectorType p0=mat*x; + VectorType p1=precond.solve(p0); + r0 = rhs - p1; +// r0_sqnorm = r0.squaredNorm(); + w = VectorType::Zero(restart + 1); + H = FMatrixType::Zero(m, restart + 1); + tau = VectorType::Zero(restart + 1); + + // generate first Householder vector + RealScalar beta; + r0.makeHouseholder(e, tau.coeffRef(0), beta); + w(0)=(Scalar) beta; + H.bottomLeftCorner(m - 1, 1) = e; + + } + + } + + + + } + + return false; + +} + +} + +template< typename _MatrixType, + typename _Preconditioner = DiagonalPreconditioner > +class GMRES; + +namespace internal { + +template< typename _MatrixType, typename _Preconditioner> +struct traits > +{ + typedef _MatrixType MatrixType; + typedef _Preconditioner Preconditioner; +}; + +} + +/** \ingroup IterativeLinearSolvers_Module + * \brief A GMRES solver for sparse square problems + * + * This class allows to solve for A.x = b sparse linear problems using a generalized minimal + * residual method. The vectors x and b can be either dense or sparse. + * + * \tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix. + * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner + * + * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations() + * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations + * and NumTraits::epsilon() for the tolerance. + * + * This class can be used as the direct solver classes. Here is a typical usage example: + * \code + * int n = 10000; + * VectorXd x(n), b(n); + * SparseMatrix A(n,n); + * // fill A and b + * GMRES > solver(A); + * x = solver.solve(b); + * std::cout << "#iterations: " << solver.iterations() << std::endl; + * std::cout << "estimated error: " << solver.error() << std::endl; + * // update b, and solve again + * x = solver.solve(b); + * \endcode + * + * By default the iterations start with x=0 as an initial guess of the solution. + * One can control the start using the solveWithGuess() method. Here is a step by + * step execution example starting with a random guess and printing the evolution + * of the estimated error: + * * \code + * x = VectorXd::Random(n); + * solver.setMaxIterations(1); + * int i = 0; + * do { + * x = solver.solveWithGuess(b,x); + * std::cout << i << " : " << solver.error() << std::endl; + * ++i; + * } while (solver.info()!=Success && i<100); + * \endcode + * Note that such a step by step excution is slightly slower. + * + * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner + */ +template< typename _MatrixType, typename _Preconditioner> +class GMRES : public IterativeSolverBase > +{ + typedef IterativeSolverBase Base; + using Base::mp_matrix; + using Base::m_error; + using Base::m_iterations; + using Base::m_info; + using Base::m_isInitialized; + +private: + int m_restart; + +public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::RealScalar RealScalar; + typedef _Preconditioner Preconditioner; + +public: + + /** Default constructor. */ + GMRES() : Base(), m_restart(30) {} + + /** Initialize the solver with matrix \a A for further \c Ax=b solving. + * + * This constructor is a shortcut for the default constructor followed + * by a call to compute(). + * + * \warning this class stores a reference to the matrix A as well as some + * precomputed values that depend on it. Therefore, if \a A is changed + * this class becomes invalid. Call compute() to update it with the new + * matrix A, or modify a copy of A. + */ + GMRES(const MatrixType& A) : Base(A), m_restart(30) {} + + ~GMRES() {} + + /** Get the number of iterations after that a restart is performed. + */ + int get_restart() { return m_restart; } + + /** Set the number of iterations after that a restart is performed. + * \param restart number of iterations for a restarti, default is 30. + */ + void set_restart(const int restart) { m_restart=restart; } + + /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A + * \a x0 as an initial solution. + * + * \sa compute() + */ + template + inline const internal::solve_retval_with_guess + solveWithGuess(const MatrixBase& b, const Guess& x0) const + { + eigen_assert(m_isInitialized && "GMRES is not initialized."); + eigen_assert(Base::rows()==b.rows() + && "GMRES::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval_with_guess + (*this, b.derived(), x0); + } + + /** \internal */ + template + void _solveWithGuess(const Rhs& b, Dest& x) const + { + bool failed = false; + for(int j=0; j + void _solve(const Rhs& b, Dest& x) const + { + x.setZero(); + _solveWithGuess(b,x); + } + +protected: + +}; + + +namespace internal { + + template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef GMRES<_MatrixType, _Preconditioner> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_GMRES_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteLU.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteLU.h new file mode 100644 index 000000000..e02f1f0c8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteLU.h @@ -0,0 +1,128 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_INCOMPLETE_LU_H +#define EIGEN_INCOMPLETE_LU_H + +namespace Eigen { + +template +class IncompleteLU +{ + typedef _Scalar Scalar; + typedef Matrix Vector; + typedef typename Vector::Index Index; + typedef SparseMatrix FactorType; + + public: + typedef Matrix MatrixType; + + IncompleteLU() : m_isInitialized(false) {} + + template + IncompleteLU(const MatrixType& mat) : m_isInitialized(false) + { + compute(mat); + } + + Index rows() const { return m_lu.rows(); } + Index cols() const { return m_lu.cols(); } + + template + IncompleteLU& compute(const MatrixType& mat) + { + m_lu = mat; + int size = mat.cols(); + Vector diag(size); + for(int i=0; i + void _solve(const Rhs& b, Dest& x) const + { + x = m_lu.template triangularView().solve(b); + x = m_lu.template triangularView().solve(x); + } + + template inline const internal::solve_retval + solve(const MatrixBase& b) const + { + eigen_assert(m_isInitialized && "IncompleteLU is not initialized."); + eigen_assert(cols()==b.rows() + && "IncompleteLU::solve(): invalid number of rows of the right hand side matrix b"); + return internal::solve_retval(*this, b.derived()); + } + + protected: + FactorType m_lu; + bool m_isInitialized; +}; + +namespace internal { + +template +struct solve_retval, Rhs> + : solve_retval_base, Rhs> +{ + typedef IncompleteLU<_MatrixType> Dec; + EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) + + template void evalTo(Dest& dst) const + { + dec()._solve(rhs(),dst); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_INCOMPLETE_LU_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h index a65793cd5..dfb97e239 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h @@ -75,6 +75,8 @@ #ifndef EIGEN_ITERATION_CONTROLLER_H #define EIGEN_ITERATION_CONTROLLER_H +namespace Eigen { + /** \ingroup IterativeSolvers_Module * \class IterationController * @@ -163,4 +165,6 @@ class IterationController }; +} // end namespace Eigen + #endif // EIGEN_ITERATION_CONTROLLER_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/Scaling.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/Scaling.h new file mode 100644 index 000000000..4aad69d0e --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/Scaling.h @@ -0,0 +1,200 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2012 Desire NUENTSA WAKAM . + +#ifndef EIGEN_SCALING_H +#define EIGEN_SCALING_H +/** + * \ingroup IterativeSolvers_Module + * \brief iterative scaling algorithm to equilibrate rows and column norms in matrices + * + * This class can be used as a preprocessing tool to accelerate the convergence of iterative methods + * + * This feature is useful to limit the pivoting amount during LU/ILU factorization + * The scaling strategy as presented here preserves the symmetry of the problem + * NOTE It is assumed that the matrix does not have empty row or column, + * + * Example with key steps + * \code + * VectorXd x(n), b(n); + * SparseMatrix A; + * // fill A and b; + * Scaling > scal; + * // Compute the left and right scaling vectors. The matrix is equilibrated at output + * scal.computeRef(A); + * // Scale the right hand side + * b = scal.LeftScaling().cwiseProduct(b); + * // Now, solve the equilibrated linear system with any available solver + * + * // Scale back the computed solution + * x = scal.RightScaling().cwiseProduct(x); + * \endcode + * + * \tparam _MatrixType the type of the matrix. It should be a real square sparsematrix + * + * References : D. Ruiz and B. Ucar, A Symmetry Preserving Algorithm for Matrix Scaling, INRIA Research report RR-7552 + * + * \sa \ref IncompleteLUT + */ +using std::abs; +using namespace Eigen; +template +class Scaling +{ + public: + typedef _MatrixType MatrixType; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + + public: + Scaling() { init(); } + + Scaling(const MatrixType& matrix) + { + init(); + compute(matrix); + } + + ~Scaling() { } + + /** + * Compute the left and right diagonal matrices to scale the input matrix @p mat + * + * FIXME This algorithm will be modified such that the diagonal elements are permuted on the diagonal. + * + * \sa LeftScaling() RightScaling() + */ + void compute (const MatrixType& mat) + { + int m = mat.rows(); + int n = mat.cols(); + assert((m>0 && m == n) && "Please give a non - empty matrix"); + m_left.resize(m); + m_right.resize(n); + m_left.setOnes(); + m_right.setOnes(); + m_matrix = mat; + VectorXd Dr, Dc, DrRes, DcRes; // Temporary Left and right scaling vectors + Dr.resize(m); Dc.resize(n); + DrRes.resize(m); DcRes.resize(n); + double EpsRow = 1.0, EpsCol = 1.0; + int its = 0; + do + { // Iterate until the infinite norm of each row and column is approximately 1 + // Get the maximum value in each row and column + Dr.setZero(); Dc.setZero(); + for (int k=0; km_tol || EpsCol > m_tol) && (its < m_maxits) ); + m_isInitialized = true; + } + /** Compute the left and right vectors to scale the vectors + * the input matrix is scaled with the computed vectors at output + * + * \sa compute() + */ + void computeRef (MatrixType& mat) + { + compute (mat); + mat = m_matrix; + } + /** Get the vector to scale the rows of the matrix + */ + VectorXd& LeftScaling() + { + return m_left; + } + + /** Get the vector to scale the columns of the matrix + */ + VectorXd& RightScaling() + { + return m_right; + } + + /** Set the tolerance for the convergence of the iterative scaling algorithm + */ + void setTolerance(double tol) + { + m_tol = tol; + } + + protected: + + void init() + { + m_tol = 1e-10; + m_maxits = 5; + m_isInitialized = false; + } + + MatrixType m_matrix; + mutable ComputationInfo m_info; + bool m_isInitialized; + VectorXd m_left; // Left scaling vector + VectorXd m_right; // m_right scaling vector + double m_tol; + int m_maxits; // Maximum number of iterations allowed +}; + +#endif \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/CMakeLists.txt new file mode 100644 index 000000000..4daefebee --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_KroneckerProduct_SRCS "*.h") + +INSTALL(FILES + ${Eigen_KroneckerProduct_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/src/KroneckerProduct COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/KroneckerTensorProduct.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/KroneckerTensorProduct.h new file mode 100644 index 000000000..4627705ce --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/KroneckerTensorProduct.h @@ -0,0 +1,172 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Kolja Brix +// Copyright (C) 2011 Andreas Platen +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + + +#ifndef KRONECKER_TENSOR_PRODUCT_H +#define KRONECKER_TENSOR_PRODUCT_H + + +namespace Eigen { + +namespace internal { + +/*! + * Kronecker tensor product helper function for dense matrices + * + * \param A Dense matrix A + * \param B Dense matrix B + * \param AB_ Kronecker tensor product of A and B + */ +template +void kroneckerProduct_full(const Derived_A& A, const Derived_B& B, Derived_AB & AB) +{ + const unsigned int Ar = A.rows(), + Ac = A.cols(), + Br = B.rows(), + Bc = B.cols(); + for (unsigned int i=0; i +void kroneckerProduct_sparse(const Derived_A &A, const Derived_B &B, Derived_AB &AB) +{ + const unsigned int Ar = A.rows(), + Ac = A.cols(), + Br = B.rows(), + Bc = B.cols(); + AB.resize(Ar*Br,Ac*Bc); + AB.resizeNonZeros(0); + AB.reserve(A.nonZeros()*B.nonZeros()); + + for (int kA=0; kA +void kroneckerProduct(const MatrixBase& a, const MatrixBase& b, Matrix& c) +{ + c.resize(a.rows()*b.rows(),a.cols()*b.cols()); + internal::kroneckerProduct_full(a.derived(), b.derived(), c); +} + +/*! + * Computes Kronecker tensor product of two dense matrices + * + * Remark: this function uses the const cast hack and has been + * implemented to make the function call possible, where the + * output matrix is a submatrix, e.g. + * kroneckerProduct(A,B,AB.block(2,5,6,6)); + * + * \param a Dense matrix a + * \param b Dense matrix b + * \param c Kronecker tensor product of a and b + */ +template +void kroneckerProduct(const MatrixBase& a, const MatrixBase& b, MatrixBase const & c_) +{ + MatrixBase& c = const_cast& >(c_); + internal::kroneckerProduct_full(a.derived(), b.derived(), c.derived()); +} + +/*! + * Computes Kronecker tensor product of a dense and a sparse matrix + * + * \param a Dense matrix a + * \param b Sparse matrix b + * \param c Kronecker tensor product of a and b + */ +template +void kroneckerProduct(const MatrixBase& a, const SparseMatrixBase& b, SparseMatrixBase& c) +{ + internal::kroneckerProduct_sparse(a.derived(), b.derived(), c.derived()); +} + +/*! + * Computes Kronecker tensor product of a sparse and a dense matrix + * + * \param a Sparse matrix a + * \param b Dense matrix b + * \param c Kronecker tensor product of a and b + */ +template +void kroneckerProduct(const SparseMatrixBase& a, const MatrixBase& b, SparseMatrixBase& c) +{ + internal::kroneckerProduct_sparse(a.derived(), b.derived(), c.derived()); +} + +/*! + * Computes Kronecker tensor product of two sparse matrices + * + * \param a Sparse matrix a + * \param b Sparse matrix b + * \param c Kronecker tensor product of a and b + */ +template +void kroneckerProduct(const SparseMatrixBase& a, const SparseMatrixBase& b, SparseMatrixBase& c) +{ + internal::kroneckerProduct_sparse(a.derived(), b.derived(), c.derived()); +} + +} // end namespace Eigen + +#endif // KRONECKER_TENSOR_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h index 50c0ca84e..6cdd65748 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h @@ -2,6 +2,7 @@ // for linear algebra. // // Copyright (C) 2009, 2010 Jitse Niesen +// Copyright (C) 2011 Chen-Pang He // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -25,7 +26,11 @@ #ifndef EIGEN_MATRIX_EXPONENTIAL #define EIGEN_MATRIX_EXPONENTIAL -#ifdef _MSC_VER +#include "StemFunction.h" + +namespace Eigen { + +#if defined(_MSC_VER) || defined(__FreeBSD__) template Scalar log2(Scalar v) { using std::log; return log(v)/log(Scalar(2)); } #endif @@ -107,6 +112,17 @@ class MatrixExponential { */ void pade13(const MatrixType &A); + /** \brief Compute the (17,17)-Padé approximant to the exponential. + * + * After exit, \f$ (V+U)(V-U)^{-1} \f$ is the Padé + * approximant of \f$ \exp(A) \f$ around \f$ A = 0 \f$. + * + * This function activates only if your long double is double-double or quadruple. + * + * \param[in] A Argument of matrix exponential + */ + void pade17(const MatrixType &A); + /** \brief Compute Padé approximant to the exponential. * * Computes \c m_U, \c m_V and \c m_squarings such that @@ -127,17 +143,24 @@ class MatrixExponential { * \sa computeUV(double); */ void computeUV(float); + + /** \brief Compute Padé approximant to the exponential. + * + * \sa computeUV(double); + */ + void computeUV(long double); typedef typename internal::traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; /** \brief Reference to matrix whose exponential is to be computed. */ typename internal::nested::type m_M; - /** \brief Even-degree terms in numerator of Padé approximant. */ + /** \brief Odd-degree terms in numerator of Padé approximant. */ MatrixType m_U; - /** \brief Odd-degree terms in numerator of Padé approximant. */ + /** \brief Even-degree terms in numerator of Padé approximant. */ MatrixType m_V; /** \brief Used for temporary storage. */ @@ -153,7 +176,7 @@ class MatrixExponential { int m_squarings; /** \brief L1 norm of m_M. */ - float m_l1norm; + RealScalar m_l1norm; }; template @@ -165,7 +188,7 @@ MatrixExponential::MatrixExponential(const MatrixType &M) : m_tmp2(M.rows(),M.cols()), m_Id(MatrixType::Identity(M.rows(), M.cols())), m_squarings(0), - m_l1norm(static_cast(M.cwiseAbs().colwise().sum().maxCoeff())) + m_l1norm(M.cwiseAbs().colwise().sum().maxCoeff()) { /* empty body */ } @@ -174,18 +197,24 @@ template template void MatrixExponential::compute(ResultType &result) { +#if LDBL_MANT_DIG > 112 // rarely happens + if(sizeof(RealScalar) > 14) { + result = m_M.matrixFunction(StdStemFunctions::exp); + return; + } +#endif computeUV(RealScalar()); - m_tmp1 = m_U + m_V; // numerator of Pade approximant - m_tmp2 = -m_U + m_V; // denominator of Pade approximant + m_tmp1 = m_U + m_V; // numerator of Pade approximant + m_tmp2 = -m_U + m_V; // denominator of Pade approximant result = m_tmp2.partialPivLu().solve(m_tmp1); for (int i=0; i EIGEN_STRONG_INLINE void MatrixExponential::pade3(const MatrixType &A) { - const Scalar b[] = {120., 60., 12., 1.}; + const RealScalar b[] = {120., 60., 12., 1.}; m_tmp1.noalias() = A * A; m_tmp2 = b[3]*m_tmp1 + b[1]*m_Id; m_U.noalias() = A * m_tmp2; @@ -195,7 +224,7 @@ EIGEN_STRONG_INLINE void MatrixExponential::pade3(const MatrixType & template EIGEN_STRONG_INLINE void MatrixExponential::pade5(const MatrixType &A) { - const Scalar b[] = {30240., 15120., 3360., 420., 30., 1.}; + const RealScalar b[] = {30240., 15120., 3360., 420., 30., 1.}; MatrixType A2 = A * A; m_tmp1.noalias() = A2 * A2; m_tmp2 = b[5]*m_tmp1 + b[3]*A2 + b[1]*m_Id; @@ -206,7 +235,7 @@ EIGEN_STRONG_INLINE void MatrixExponential::pade5(const MatrixType & template EIGEN_STRONG_INLINE void MatrixExponential::pade7(const MatrixType &A) { - const Scalar b[] = {17297280., 8648640., 1995840., 277200., 25200., 1512., 56., 1.}; + const RealScalar b[] = {17297280., 8648640., 1995840., 277200., 25200., 1512., 56., 1.}; MatrixType A2 = A * A; MatrixType A4 = A2 * A2; m_tmp1.noalias() = A4 * A2; @@ -218,7 +247,7 @@ EIGEN_STRONG_INLINE void MatrixExponential::pade7(const MatrixType & template EIGEN_STRONG_INLINE void MatrixExponential::pade9(const MatrixType &A) { - const Scalar b[] = {17643225600., 8821612800., 2075673600., 302702400., 30270240., + const RealScalar b[] = {17643225600., 8821612800., 2075673600., 302702400., 30270240., 2162160., 110880., 3960., 90., 1.}; MatrixType A2 = A * A; MatrixType A4 = A2 * A2; @@ -232,7 +261,7 @@ EIGEN_STRONG_INLINE void MatrixExponential::pade9(const MatrixType & template EIGEN_STRONG_INLINE void MatrixExponential::pade13(const MatrixType &A) { - const Scalar b[] = {64764752532480000., 32382376266240000., 7771770303897600., + const RealScalar b[] = {64764752532480000., 32382376266240000., 7771770303897600., 1187353796428800., 129060195264000., 10559470521600., 670442572800., 33522128640., 1323241920., 40840800., 960960., 16380., 182., 1.}; MatrixType A2 = A * A; @@ -247,6 +276,30 @@ EIGEN_STRONG_INLINE void MatrixExponential::pade13(const MatrixType m_V += b[6]*m_tmp1 + b[4]*A4 + b[2]*A2 + b[0]*m_Id; } +#if LDBL_MANT_DIG > 64 +template +EIGEN_STRONG_INLINE void MatrixExponential::pade17(const MatrixType &A) +{ + const RealScalar b[] = {830034394580628357120000.L, 415017197290314178560000.L, + 100610229646136770560000.L, 15720348382208870400000.L, + 1774878043152614400000.L, 153822763739893248000.L, 10608466464820224000.L, + 595373117923584000.L, 27563570274240000.L, 1060137318240000.L, + 33924394183680.L, 899510451840.L, 19554575040.L, 341863200.L, 4651200.L, + 46512.L, 306.L, 1.L}; + MatrixType A2 = A * A; + MatrixType A4 = A2 * A2; + MatrixType A6 = A4 * A2; + m_tmp1.noalias() = A4 * A4; + m_V = b[17]*m_tmp1 + b[15]*A6 + b[13]*A4 + b[11]*A2; // used for temporary storage + m_tmp2.noalias() = m_tmp1 * m_V; + m_tmp2 += b[9]*m_tmp1 + b[7]*A6 + b[5]*A4 + b[3]*A2 + b[1]*m_Id; + m_U.noalias() = A * m_tmp2; + m_tmp2 = b[16]*m_tmp1 + b[14]*A6 + b[12]*A4 + b[10]*A2; + m_V.noalias() = m_tmp1 * m_tmp2; + m_V += b[8]*m_tmp1 + b[6]*A6 + b[4]*A4 + b[2]*A2 + b[0]*m_Id; +} +#endif + template void MatrixExponential::computeUV(float) { @@ -260,7 +313,7 @@ void MatrixExponential::computeUV(float) } else { const float maxnorm = 3.925724783138660f; m_squarings = (max)(0, (int)ceil(log2(m_l1norm / maxnorm))); - MatrixType A = m_M / pow(Scalar(2), Scalar(static_cast(m_squarings))); + MatrixType A = m_M / pow(Scalar(2), m_squarings); pade7(A); } } @@ -282,11 +335,74 @@ void MatrixExponential::computeUV(double) } else { const double maxnorm = 5.371920351148152; m_squarings = (max)(0, (int)ceil(log2(m_l1norm / maxnorm))); - MatrixType A = m_M / pow(Scalar(2), Scalar(m_squarings)); + MatrixType A = m_M / pow(Scalar(2), m_squarings); pade13(A); } } +template +void MatrixExponential::computeUV(long double) +{ + using std::max; + using std::pow; + using std::ceil; +#if LDBL_MANT_DIG == 53 // double precision + computeUV(double()); +#elif LDBL_MANT_DIG <= 64 // extended precision + if (m_l1norm < 4.1968497232266989671e-003L) { + pade3(m_M); + } else if (m_l1norm < 1.1848116734693823091e-001L) { + pade5(m_M); + } else if (m_l1norm < 5.5170388480686700274e-001L) { + pade7(m_M); + } else if (m_l1norm < 1.3759868875587845383e+000L) { + pade9(m_M); + } else { + const long double maxnorm = 4.0246098906697353063L; + m_squarings = (max)(0, (int)ceil(log2(m_l1norm / maxnorm))); + MatrixType A = m_M / pow(Scalar(2), m_squarings); + pade13(A); + } +#elif LDBL_MANT_DIG <= 106 // double-double + if (m_l1norm < 3.2787892205607026992947488108213e-005L) { + pade3(m_M); + } else if (m_l1norm < 6.4467025060072760084130906076332e-003L) { + pade5(m_M); + } else if (m_l1norm < 6.8988028496595374751374122881143e-002L) { + pade7(m_M); + } else if (m_l1norm < 2.7339737518502231741495857201670e-001L) { + pade9(m_M); + } else if (m_l1norm < 1.3203382096514474905666448850278e+000L) { + pade13(m_M); + } else { + const long double maxnorm = 3.2579440895405400856599663723517L; + m_squarings = (max)(0, (int)ceil(log2(m_l1norm / maxnorm))); + MatrixType A = m_M / pow(Scalar(2), m_squarings); + pade17(A); + } +#elif LDBL_MANT_DIG <= 112 // quadruple precison + if (m_l1norm < 1.639394610288918690547467954466970e-005L) { + pade3(m_M); + } else if (m_l1norm < 4.253237712165275566025884344433009e-003L) { + pade5(m_M); + } else if (m_l1norm < 5.125804063165764409885122032933142e-002L) { + pade7(m_M); + } else if (m_l1norm < 2.170000765161155195453205651889853e-001L) { + pade9(m_M); + } else if (m_l1norm < 1.125358383453143065081397882891878e+000L) { + pade13(m_M); + } else { + const long double maxnorm = 2.884233277829519311757165057717815L; + m_squarings = (max)(0, (int)ceil(log2(m_l1norm / maxnorm))); + MatrixType A = m_M / pow(Scalar(2), m_squarings); + pade17(A); + } +#else + // this case should be handled in compute() + eigen_assert(false && "Bug in MatrixExponential"); +#endif // LDBL_MANT_DIG +} + /** \ingroup MatrixFunctions_Module * * \brief Proxy for the matrix exponential of some matrix (expression). @@ -348,4 +464,6 @@ const MatrixExponentialReturnValue MatrixBase::exp() const return MatrixExponentialReturnValue(derived()); } +} // end namespace Eigen + #endif // EIGEN_MATRIX_EXPONENTIAL diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h index 4b9d8a102..859de7288 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009, 2010 Jitse Niesen +// Copyright (C) 2009-2011 Jitse Niesen // // Eigen is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public @@ -29,31 +29,39 @@ #include "MatrixFunctionAtomic.h" +namespace Eigen { + /** \ingroup MatrixFunctions_Module - * \brief Class for computing matrix exponentials. - * \tparam MatrixType type of the argument of the matrix function, - * expected to be an instantiation of the Matrix class template. + * \brief Class for computing matrix functions. + * \tparam MatrixType type of the argument of the matrix function, + * expected to be an instantiation of the Matrix class template. + * \tparam AtomicType type for computing matrix function of atomic blocks. + * \tparam IsComplex used internally to select correct specialization. + * + * This class implements the Schur-Parlett algorithm for computing matrix functions. The spectrum of the + * matrix is divided in clustered of eigenvalues that lies close together. This class delegates the + * computation of the matrix function on every block corresponding to these clusters to an object of type + * \p AtomicType and uses these results to compute the matrix function of the whole matrix. The class + * \p AtomicType should have a \p compute() member function for computing the matrix function of a block. + * + * \sa class MatrixFunctionAtomic, class MatrixLogarithmAtomic */ -template ::Scalar>::IsComplex> +template ::Scalar>::IsComplex> class MatrixFunction { - private: - - typedef typename internal::traits::Index Index; - typedef typename internal::traits::Scalar Scalar; - typedef typename internal::stem_function::type StemFunction; - public: /** \brief Constructor. * - * \param[in] A argument of matrix function, should be a square matrix. - * \param[in] f an entire function; \c f(x,n) should compute the n-th derivative of f at x. + * \param[in] A argument of matrix function, should be a square matrix. + * \param[in] atomic class for computing matrix function of atomic blocks. * - * The class stores a reference to \p A, so it should not be + * The class stores references to \p A and \p atomic, so they should not be * changed (or destroyed) before compute() is called. */ - MatrixFunction(const MatrixType& A, StemFunction f); + MatrixFunction(const MatrixType& A, AtomicType& atomic); /** \brief Compute the matrix function. * @@ -68,11 +76,11 @@ class MatrixFunction }; -/** \ingroup MatrixFunctions_Module - * \brief Partial specialization of MatrixFunction for real matrices \internal +/** \internal \ingroup MatrixFunctions_Module + * \brief Partial specialization of MatrixFunction for real matrices */ -template -class MatrixFunction +template +class MatrixFunction { private: @@ -86,16 +94,15 @@ class MatrixFunction typedef std::complex ComplexScalar; typedef Matrix ComplexMatrix; - typedef typename internal::stem_function::type StemFunction; public: /** \brief Constructor. * - * \param[in] A argument of matrix function, should be a square matrix. - * \param[in] f an entire function; \c f(x,n) should compute the n-th derivative of f at x. + * \param[in] A argument of matrix function, should be a square matrix. + * \param[in] atomic class for computing matrix function of atomic blocks. */ - MatrixFunction(const MatrixType& A, StemFunction f) : m_A(A), m_f(f) { } + MatrixFunction(const MatrixType& A, AtomicType& atomic) : m_A(A), m_atomic(atomic) { } /** \brief Compute the matrix function. * @@ -111,24 +118,24 @@ class MatrixFunction { ComplexMatrix CA = m_A.template cast(); ComplexMatrix Cresult; - MatrixFunction mf(CA, m_f); + MatrixFunction mf(CA, m_atomic); mf.compute(Cresult); result = Cresult.real(); } private: typename internal::nested::type m_A; /**< \brief Reference to argument of matrix function. */ - StemFunction *m_f; /**< \brief Stem function for matrix function under consideration */ + AtomicType& m_atomic; /**< \brief Class for computing matrix function of atomic blocks. */ MatrixFunction& operator=(const MatrixFunction&); }; -/** \ingroup MatrixFunctions_Module - * \brief Partial specialization of MatrixFunction for complex matrices \internal +/** \internal \ingroup MatrixFunctions_Module + * \brief Partial specialization of MatrixFunction for complex matrices */ -template -class MatrixFunction +template +class MatrixFunction { private: @@ -139,7 +146,6 @@ class MatrixFunction static const int ColsAtCompileTime = Traits::ColsAtCompileTime; static const int Options = MatrixType::Options; typedef typename NumTraits::Real RealScalar; - typedef typename internal::stem_function::type StemFunction; typedef Matrix VectorType; typedef Matrix IntVectorType; typedef Matrix DynamicIntVectorType; @@ -149,7 +155,7 @@ class MatrixFunction public: - MatrixFunction(const MatrixType& A, StemFunction f); + MatrixFunction(const MatrixType& A, AtomicType& atomic); template void compute(ResultType& result); private: @@ -168,7 +174,7 @@ class MatrixFunction DynMatrixType solveTriangularSylvester(const DynMatrixType& A, const DynMatrixType& B, const DynMatrixType& C); typename internal::nested::type m_A; /**< \brief Reference to argument of matrix function. */ - StemFunction *m_f; /**< \brief Stem function for matrix function under consideration */ + AtomicType& m_atomic; /**< \brief Class for computing matrix function of atomic blocks. */ MatrixType m_T; /**< \brief Triangular part of Schur decomposition */ MatrixType m_U; /**< \brief Unitary part of Schur decomposition */ MatrixType m_fT; /**< \brief %Matrix function applied to #m_T */ @@ -191,12 +197,12 @@ class MatrixFunction /** \brief Constructor. * - * \param[in] A argument of matrix function, should be a square matrix. - * \param[in] f an entire function; \c f(x,n) should compute the n-th derivative of f at x. + * \param[in] A argument of matrix function, should be a square matrix. + * \param[in] atomic class for computing matrix function of atomic blocks. */ -template -MatrixFunction::MatrixFunction(const MatrixType& A, StemFunction f) : - m_A(A), m_f(f) +template +MatrixFunction::MatrixFunction(const MatrixType& A, AtomicType& atomic) + : m_A(A), m_atomic(atomic) { /* empty body */ } @@ -206,9 +212,9 @@ MatrixFunction::MatrixFunction(const MatrixType& A, StemFunction f * \param[out] result the function \p f applied to \p A, as * specified in the constructor. */ -template +template template -void MatrixFunction::compute(ResultType& result) +void MatrixFunction::compute(ResultType& result) { computeSchurDecomposition(); partitionEigenvalues(); @@ -222,8 +228,8 @@ void MatrixFunction::compute(ResultType& result) } /** \brief Store the Schur decomposition of #m_A in #m_T and #m_U */ -template -void MatrixFunction::computeSchurDecomposition() +template +void MatrixFunction::computeSchurDecomposition() { const ComplexSchur schurOfA(m_A); m_T = schurOfA.matrixT(); @@ -241,8 +247,8 @@ void MatrixFunction::computeSchurDecomposition() * The implementation follows Algorithm 4.1 in the paper of Davies * and Higham. */ -template -void MatrixFunction::partitionEigenvalues() +template +void MatrixFunction::partitionEigenvalues() { const Index rows = m_T.rows(); VectorType diag = m_T.diagonal(); // contains eigenvalues of A @@ -278,8 +284,8 @@ void MatrixFunction::partitionEigenvalues() * \returns Iterator to cluster containing \c key, or * \c m_clusters.end() if no cluster in m_clusters contains \c key. */ -template -typename MatrixFunction::ListOfClusters::iterator MatrixFunction::findCluster(Scalar key) +template +typename MatrixFunction::ListOfClusters::iterator MatrixFunction::findCluster(Scalar key) { typename Cluster::iterator j; for (typename ListOfClusters::iterator i = m_clusters.begin(); i != m_clusters.end(); ++i) { @@ -291,8 +297,8 @@ typename MatrixFunction::ListOfClusters::iterator MatrixFunction -void MatrixFunction::computeClusterSize() +template +void MatrixFunction::computeClusterSize() { const Index rows = m_T.rows(); VectorType diag = m_T.diagonal(); @@ -313,8 +319,8 @@ void MatrixFunction::computeClusterSize() } /** \brief Compute #m_blockStart using #m_clusterSize */ -template -void MatrixFunction::computeBlockStart() +template +void MatrixFunction::computeBlockStart() { m_blockStart.resize(m_clusterSize.rows()); m_blockStart(0) = 0; @@ -324,8 +330,8 @@ void MatrixFunction::computeBlockStart() } /** \brief Compute #m_permutation using #m_eivalToCluster and #m_blockStart */ -template -void MatrixFunction::constructPermutation() +template +void MatrixFunction::constructPermutation() { DynamicIntVectorType indexNextEntry = m_blockStart; m_permutation.resize(m_T.rows()); @@ -337,8 +343,8 @@ void MatrixFunction::constructPermutation() } /** \brief Permute Schur decomposition in #m_U and #m_T according to #m_permutation */ -template -void MatrixFunction::permuteSchur() +template +void MatrixFunction::permuteSchur() { IntVectorType p = m_permutation; for (Index i = 0; i < p.rows() - 1; i++) { @@ -355,8 +361,8 @@ void MatrixFunction::permuteSchur() } /** \brief Swap rows \a index and \a index+1 in Schur decomposition in #m_U and #m_T */ -template -void MatrixFunction::swapEntriesInSchur(Index index) +template +void MatrixFunction::swapEntriesInSchur(Index index) { JacobiRotation rotation; rotation.makeGivens(m_T(index, index+1), m_T(index+1, index+1) - m_T(index, index)); @@ -367,25 +373,23 @@ void MatrixFunction::swapEntriesInSchur(Index index) /** \brief Compute block diagonal part of #m_fT. * - * This routine computes the matrix function #m_f applied to the block - * diagonal part of #m_T, with the blocking given by #m_blockStart. The - * result is stored in #m_fT. The off-diagonal parts of #m_fT are set - * to zero. + * This routine computes the matrix function applied to the block diagonal part of #m_T, with the blocking + * given by #m_blockStart. The matrix function of each diagonal block is computed by #m_atomic. The + * off-diagonal parts of #m_fT are set to zero. */ -template -void MatrixFunction::computeBlockAtomic() +template +void MatrixFunction::computeBlockAtomic() { m_fT.resize(m_T.rows(), m_T.cols()); m_fT.setZero(); - MatrixFunctionAtomic mfa(m_f); for (Index i = 0; i < m_clusterSize.rows(); ++i) { - block(m_fT, i, i) = mfa.compute(block(m_T, i, i)); + block(m_fT, i, i) = m_atomic.compute(block(m_T, i, i)); } } /** \brief Return block of matrix according to blocking given by #m_blockStart */ -template -Block MatrixFunction::block(MatrixType& A, Index i, Index j) +template +Block MatrixFunction::block(MatrixType& A, Index i, Index j) { return A.block(m_blockStart(i), m_blockStart(j), m_clusterSize(i), m_clusterSize(j)); } @@ -393,12 +397,12 @@ Block MatrixFunction::block(MatrixType& A, Index i, In /** \brief Compute part of #m_fT above block diagonal. * * This routine assumes that the block diagonal part of #m_fT (which - * equals #m_f applied to #m_T) has already been computed and computes + * equals the matrix function applied to #m_T) has already been computed and computes * the part above the block diagonal. The part below the diagonal is * zero, because #m_T is upper triangular. */ -template -void MatrixFunction::computeOffDiagonal() +template +void MatrixFunction::computeOffDiagonal() { for (Index diagIndex = 1; diagIndex < m_clusterSize.rows(); diagIndex++) { for (Index blockIndex = 0; blockIndex < m_clusterSize.rows() - diagIndex; blockIndex++) { @@ -439,8 +443,8 @@ void MatrixFunction::computeOffDiagonal() * solution). In that case, these equations can be evaluated in the * order \f$ i=m,\ldots,1 \f$ and \f$ j=1,\ldots,n \f$. */ -template -typename MatrixFunction::DynMatrixType MatrixFunction::solveTriangularSylvester( +template +typename MatrixFunction::DynMatrixType MatrixFunction::solveTriangularSylvester( const DynMatrixType& A, const DynMatrixType& B, const DynMatrixType& C) @@ -520,8 +524,18 @@ template class MatrixFunctionReturnValue template inline void evalTo(ResultType& result) const { - const typename Derived::PlainObject Aevaluated = m_A.eval(); - MatrixFunction mf(Aevaluated, m_f); + typedef typename Derived::PlainObject PlainObject; + typedef internal::traits Traits; + static const int RowsAtCompileTime = Traits::RowsAtCompileTime; + static const int ColsAtCompileTime = Traits::ColsAtCompileTime; + static const int Options = PlainObject::Options; + typedef std::complex::Real> ComplexScalar; + typedef Matrix DynMatrixType; + typedef MatrixFunctionAtomic AtomicType; + AtomicType atomic(m_f); + + const PlainObject Aevaluated = m_A.eval(); + MatrixFunction mf(Aevaluated, atomic); mf.compute(result); } @@ -586,4 +600,6 @@ const MatrixFunctionReturnValue MatrixBase::cosh() const return MatrixFunctionReturnValue(derived(), StdStemFunctions::cosh); } +} // end namespace Eigen + #endif // EIGEN_MATRIX_FUNCTION diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h index d08766921..97ab662fe 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h @@ -25,6 +25,8 @@ #ifndef EIGEN_MATRIX_FUNCTION_ATOMIC #define EIGEN_MATRIX_FUNCTION_ATOMIC +namespace Eigen { + /** \ingroup MatrixFunctions_Module * \class MatrixFunctionAtomic * \brief Helper class for computing matrix functions of atomic matrices. @@ -139,4 +141,6 @@ bool MatrixFunctionAtomic::taylorConverged(Index s, const MatrixType return false; } +} // end namespace Eigen + #endif // EIGEN_MATRIX_FUNCTION_ATOMIC diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h new file mode 100644 index 000000000..e6f25b73c --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h @@ -0,0 +1,510 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Jitse Niesen +// Copyright (C) 2011 Chen-Pang He +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_MATRIX_LOGARITHM +#define EIGEN_MATRIX_LOGARITHM + +#ifndef M_PI +#define M_PI 3.141592653589793238462643383279503L +#endif + +namespace Eigen { + +/** \ingroup MatrixFunctions_Module + * \class MatrixLogarithmAtomic + * \brief Helper class for computing matrix logarithm of atomic matrices. + * + * \internal + * Here, an atomic matrix is a triangular matrix whose diagonal + * entries are close to each other. + * + * \sa class MatrixFunctionAtomic, MatrixBase::log() + */ +template +class MatrixLogarithmAtomic +{ +public: + + typedef typename MatrixType::Scalar Scalar; + // typedef typename MatrixType::Index Index; + typedef typename NumTraits::Real RealScalar; + // typedef typename internal::stem_function::type StemFunction; + // typedef Matrix VectorType; + + /** \brief Constructor. */ + MatrixLogarithmAtomic() { } + + /** \brief Compute matrix logarithm of atomic matrix + * \param[in] A argument of matrix logarithm, should be upper triangular and atomic + * \returns The logarithm of \p A. + */ + MatrixType compute(const MatrixType& A); + +private: + + void compute2x2(const MatrixType& A, MatrixType& result); + void computeBig(const MatrixType& A, MatrixType& result); + static Scalar atanh(Scalar x); + int getPadeDegree(float normTminusI); + int getPadeDegree(double normTminusI); + int getPadeDegree(long double normTminusI); + void computePade(MatrixType& result, const MatrixType& T, int degree); + void computePade3(MatrixType& result, const MatrixType& T); + void computePade4(MatrixType& result, const MatrixType& T); + void computePade5(MatrixType& result, const MatrixType& T); + void computePade6(MatrixType& result, const MatrixType& T); + void computePade7(MatrixType& result, const MatrixType& T); + void computePade8(MatrixType& result, const MatrixType& T); + void computePade9(MatrixType& result, const MatrixType& T); + void computePade10(MatrixType& result, const MatrixType& T); + void computePade11(MatrixType& result, const MatrixType& T); + + static const int minPadeDegree = 3; + static const int maxPadeDegree = std::numeric_limits::digits<= 24? 5: // single precision + std::numeric_limits::digits<= 53? 7: // double precision + std::numeric_limits::digits<= 64? 8: // extended precision + std::numeric_limits::digits<=106? 10: 11; // double-double or quadruple precision + + // Prevent copying + MatrixLogarithmAtomic(const MatrixLogarithmAtomic&); + MatrixLogarithmAtomic& operator=(const MatrixLogarithmAtomic&); +}; + +/** \brief Compute logarithm of triangular matrix with clustered eigenvalues. */ +template +MatrixType MatrixLogarithmAtomic::compute(const MatrixType& A) +{ + using std::log; + MatrixType result(A.rows(), A.rows()); + if (A.rows() == 1) + result(0,0) = log(A(0,0)); + else if (A.rows() == 2) + compute2x2(A, result); + else + computeBig(A, result); + return result; +} + +/** \brief Compute atanh (inverse hyperbolic tangent). */ +template +typename MatrixType::Scalar MatrixLogarithmAtomic::atanh(typename MatrixType::Scalar x) +{ + using std::abs; + using std::sqrt; + if (abs(x) > sqrt(NumTraits::epsilon())) + return Scalar(0.5) * log((Scalar(1) + x) / (Scalar(1) - x)); + else + return x + x*x*x / Scalar(3); +} + +/** \brief Compute logarithm of 2x2 triangular matrix. */ +template +void MatrixLogarithmAtomic::compute2x2(const MatrixType& A, MatrixType& result) +{ + using std::abs; + using std::ceil; + using std::imag; + using std::log; + + Scalar logA00 = log(A(0,0)); + Scalar logA11 = log(A(1,1)); + + result(0,0) = logA00; + result(1,0) = Scalar(0); + result(1,1) = logA11; + + if (A(0,0) == A(1,1)) { + result(0,1) = A(0,1) / A(0,0); + } else if ((abs(A(0,0)) < 0.5*abs(A(1,1))) || (abs(A(0,0)) > 2*abs(A(1,1)))) { + result(0,1) = A(0,1) * (logA11 - logA00) / (A(1,1) - A(0,0)); + } else { + // computation in previous branch is inaccurate if A(1,1) \approx A(0,0) + int unwindingNumber = static_cast(ceil((imag(logA11 - logA00) - M_PI) / (2*M_PI))); + Scalar z = (A(1,1) - A(0,0)) / (A(1,1) + A(0,0)); + result(0,1) = A(0,1) * (Scalar(2) * atanh(z) + Scalar(0,2*M_PI*unwindingNumber)) / (A(1,1) - A(0,0)); + } +} + +/** \brief Compute logarithm of triangular matrices with size > 2. + * \details This uses a inverse scale-and-square algorithm. */ +template +void MatrixLogarithmAtomic::computeBig(const MatrixType& A, MatrixType& result) +{ + int numberOfSquareRoots = 0; + int numberOfExtraSquareRoots = 0; + int degree; + MatrixType T = A; + const RealScalar maxNormForPade = maxPadeDegree<= 5? 5.3149729967117310e-1: // single precision + maxPadeDegree<= 7? 2.6429608311114350e-1: // double precision + maxPadeDegree<= 8? 2.32777776523703892094e-1L: // extended precision + maxPadeDegree<=10? 1.05026503471351080481093652651105e-1L: // double-double + 1.1880960220216759245467951592883642e-1L; // quadruple precision + + while (true) { + RealScalar normTminusI = (T - MatrixType::Identity(T.rows(), T.rows())).cwiseAbs().colwise().sum().maxCoeff(); + if (normTminusI < maxNormForPade) { + degree = getPadeDegree(normTminusI); + int degree2 = getPadeDegree(normTminusI / RealScalar(2)); + if ((degree - degree2 <= 1) || (numberOfExtraSquareRoots == 1)) + break; + ++numberOfExtraSquareRoots; + } + MatrixType sqrtT; + MatrixSquareRootTriangular(T).compute(sqrtT); + T = sqrtT; + ++numberOfSquareRoots; + } + + computePade(result, T, degree); + result *= pow(RealScalar(2), numberOfSquareRoots); +} + +/* \brief Get suitable degree for Pade approximation. (specialized for RealScalar = float) */ +template +int MatrixLogarithmAtomic::getPadeDegree(float normTminusI) +{ + const float maxNormForPade[] = { 2.5111573934555054e-1 /* degree = 3 */ , 4.0535837411880493e-1, + 5.3149729967117310e-1 }; + for (int degree = 3; degree <= maxPadeDegree; ++degree) + if (normTminusI <= maxNormForPade[degree - minPadeDegree]) + return degree; + assert(false); // this line should never be reached +} + +/* \brief Get suitable degree for Pade approximation. (specialized for RealScalar = double) */ +template +int MatrixLogarithmAtomic::getPadeDegree(double normTminusI) +{ + const double maxNormForPade[] = { 1.6206284795015624e-2 /* degree = 3 */ , 5.3873532631381171e-2, + 1.1352802267628681e-1, 1.8662860613541288e-1, 2.642960831111435e-1 }; + for (int degree = 3; degree <= maxPadeDegree; ++degree) + if (normTminusI <= maxNormForPade[degree - minPadeDegree]) + return degree; + assert(false); // this line should never be reached +} + +/* \brief Get suitable degree for Pade approximation. (specialized for RealScalar = long double) */ +template +int MatrixLogarithmAtomic::getPadeDegree(long double normTminusI) +{ +#if LDBL_MANT_DIG == 53 // double precision + const double maxNormForPade[] = { 1.6206284795015624e-2 /* degree = 3 */ , 5.3873532631381171e-2, + 1.1352802267628681e-1, 1.8662860613541288e-1, 2.642960831111435e-1 }; +#elif LDBL_MANT_DIG <= 64 // extended precision + const double maxNormForPade[] = { 5.48256690357782863103e-3 /* degree = 3 */, 2.34559162387971167321e-2, + 5.84603923897347449857e-2, 1.08486423756725170223e-1, 1.68385767881294446649e-1, + 2.32777776523703892094e-1 }; +#elif LDBL_MANT_DIG <= 106 // double-double + const double maxNormForPade[] = { 8.58970550342939562202529664318890e-5 /* degree = 3 */, + 9.34074328446359654039446552677759e-4, 4.26117194647672175773064114582860e-3, + 1.21546224740281848743149666560464e-2, 2.61100544998339436713088248557444e-2, + 4.66170074627052749243018566390567e-2, 7.32585144444135027565872014932387e-2, + 1.05026503471351080481093652651105e-1 }; +#else // quadruple precision + const double maxNormForPade[] = { 4.7419931187193005048501568167858103e-5 /* degree = 3 */, + 5.8853168473544560470387769480192666e-4, 2.9216120366601315391789493628113520e-3, + 8.8415758124319434347116734705174308e-3, 1.9850836029449446668518049562565291e-2, + 3.6688019729653446926585242192447447e-2, 5.9290962294020186998954055264528393e-2, + 8.6998436081634343903250580992127677e-2, 1.1880960220216759245467951592883642e-1 }; +#endif + for (int degree = 3; degree <= maxPadeDegree; ++degree) + if (normTminusI <= maxNormForPade[degree - minPadeDegree]) + return degree; + assert(false); // this line should never be reached +} + +/* \brief Compute Pade approximation to matrix logarithm */ +template +void MatrixLogarithmAtomic::computePade(MatrixType& result, const MatrixType& T, int degree) +{ + switch (degree) { + case 3: computePade3(result, T); break; + case 4: computePade4(result, T); break; + case 5: computePade5(result, T); break; + case 6: computePade6(result, T); break; + case 7: computePade7(result, T); break; + case 8: computePade8(result, T); break; + case 9: computePade9(result, T); break; + case 10: computePade10(result, T); break; + case 11: computePade11(result, T); break; + default: assert(false); // should never happen + } +} + +template +void MatrixLogarithmAtomic::computePade3(MatrixType& result, const MatrixType& T) +{ + const int degree = 3; + const RealScalar nodes[] = { 0.1127016653792583114820734600217600L, 0.5000000000000000000000000000000000L, + 0.8872983346207416885179265399782400L }; + const RealScalar weights[] = { 0.2777777777777777777777777777777778L, 0.4444444444444444444444444444444444L, + 0.2777777777777777777777777777777778L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade4(MatrixType& result, const MatrixType& T) +{ + const int degree = 4; + const RealScalar nodes[] = { 0.0694318442029737123880267555535953L, 0.3300094782075718675986671204483777L, + 0.6699905217924281324013328795516223L, 0.9305681557970262876119732444464048L }; + const RealScalar weights[] = { 0.1739274225687269286865319746109997L, 0.3260725774312730713134680253890003L, + 0.3260725774312730713134680253890003L, 0.1739274225687269286865319746109997L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade5(MatrixType& result, const MatrixType& T) +{ + const int degree = 5; + const RealScalar nodes[] = { 0.0469100770306680036011865608503035L, 0.2307653449471584544818427896498956L, + 0.5000000000000000000000000000000000L, 0.7692346550528415455181572103501044L, + 0.9530899229693319963988134391496965L }; + const RealScalar weights[] = { 0.1184634425280945437571320203599587L, 0.2393143352496832340206457574178191L, + 0.2844444444444444444444444444444444L, 0.2393143352496832340206457574178191L, + 0.1184634425280945437571320203599587L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade6(MatrixType& result, const MatrixType& T) +{ + const int degree = 6; + const RealScalar nodes[] = { 0.0337652428984239860938492227530027L, 0.1693953067668677431693002024900473L, + 0.3806904069584015456847491391596440L, 0.6193095930415984543152508608403560L, + 0.8306046932331322568306997975099527L, 0.9662347571015760139061507772469973L }; + const RealScalar weights[] = { 0.0856622461895851725201480710863665L, 0.1803807865240693037849167569188581L, + 0.2339569672863455236949351719947755L, 0.2339569672863455236949351719947755L, + 0.1803807865240693037849167569188581L, 0.0856622461895851725201480710863665L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade7(MatrixType& result, const MatrixType& T) +{ + const int degree = 7; + const RealScalar nodes[] = { 0.0254460438286207377369051579760744L, 0.1292344072003027800680676133596058L, + 0.2970774243113014165466967939615193L, 0.5000000000000000000000000000000000L, + 0.7029225756886985834533032060384807L, 0.8707655927996972199319323866403942L, + 0.9745539561713792622630948420239256L }; + const RealScalar weights[] = { 0.0647424830844348466353057163395410L, 0.1398526957446383339507338857118898L, + 0.1909150252525594724751848877444876L, 0.2089795918367346938775510204081633L, + 0.1909150252525594724751848877444876L, 0.1398526957446383339507338857118898L, + 0.0647424830844348466353057163395410L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade8(MatrixType& result, const MatrixType& T) +{ + const int degree = 8; + const RealScalar nodes[] = { 0.0198550717512318841582195657152635L, 0.1016667612931866302042230317620848L, + 0.2372337950418355070911304754053768L, 0.4082826787521750975302619288199080L, + 0.5917173212478249024697380711800920L, 0.7627662049581644929088695245946232L, + 0.8983332387068133697957769682379152L, 0.9801449282487681158417804342847365L }; + const RealScalar weights[] = { 0.0506142681451881295762656771549811L, 0.1111905172266872352721779972131204L, + 0.1568533229389436436689811009933007L, 0.1813418916891809914825752246385978L, + 0.1813418916891809914825752246385978L, 0.1568533229389436436689811009933007L, + 0.1111905172266872352721779972131204L, 0.0506142681451881295762656771549811L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade9(MatrixType& result, const MatrixType& T) +{ + const int degree = 9; + const RealScalar nodes[] = { 0.0159198802461869550822118985481636L, 0.0819844463366821028502851059651326L, + 0.1933142836497048013456489803292629L, 0.3378732882980955354807309926783317L, + 0.5000000000000000000000000000000000L, 0.6621267117019044645192690073216683L, + 0.8066857163502951986543510196707371L, 0.9180155536633178971497148940348674L, + 0.9840801197538130449177881014518364L }; + const RealScalar weights[] = { 0.0406371941807872059859460790552618L, 0.0903240803474287020292360156214564L, + 0.1303053482014677311593714347093164L, 0.1561735385200014200343152032922218L, + 0.1651196775006298815822625346434870L, 0.1561735385200014200343152032922218L, + 0.1303053482014677311593714347093164L, 0.0903240803474287020292360156214564L, + 0.0406371941807872059859460790552618L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade10(MatrixType& result, const MatrixType& T) +{ + const int degree = 10; + const RealScalar nodes[] = { 0.0130467357414141399610179939577740L, 0.0674683166555077446339516557882535L, + 0.1602952158504877968828363174425632L, 0.2833023029353764046003670284171079L, + 0.4255628305091843945575869994351400L, 0.5744371694908156054424130005648600L, + 0.7166976970646235953996329715828921L, 0.8397047841495122031171636825574368L, + 0.9325316833444922553660483442117465L, 0.9869532642585858600389820060422260L }; + const RealScalar weights[] = { 0.0333356721543440687967844049466659L, 0.0747256745752902965728881698288487L, + 0.1095431812579910219977674671140816L, 0.1346333596549981775456134607847347L, + 0.1477621123573764350869464973256692L, 0.1477621123573764350869464973256692L, + 0.1346333596549981775456134607847347L, 0.1095431812579910219977674671140816L, + 0.0747256745752902965728881698288487L, 0.0333356721543440687967844049466659L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +template +void MatrixLogarithmAtomic::computePade11(MatrixType& result, const MatrixType& T) +{ + const int degree = 11; + const RealScalar nodes[] = { 0.0108856709269715035980309994385713L, 0.0564687001159523504624211153480364L, + 0.1349239972129753379532918739844233L, 0.2404519353965940920371371652706952L, + 0.3652284220238275138342340072995692L, 0.5000000000000000000000000000000000L, + 0.6347715779761724861657659927004308L, 0.7595480646034059079628628347293048L, + 0.8650760027870246620467081260155767L, 0.9435312998840476495375788846519636L, + 0.9891143290730284964019690005614287L }; + const RealScalar weights[] = { 0.0278342835580868332413768602212743L, 0.0627901847324523123173471496119701L, + 0.0931451054638671257130488207158280L, 0.1165968822959952399592618524215876L, + 0.1314022722551233310903444349452546L, 0.1364625433889503153572417641681711L, + 0.1314022722551233310903444349452546L, 0.1165968822959952399592618524215876L, + 0.0931451054638671257130488207158280L, 0.0627901847324523123173471496119701L, + 0.0278342835580868332413768602212743L }; + assert(degree <= maxPadeDegree); + MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows()); + result.setZero(T.rows(), T.rows()); + for (int k = 0; k < degree; ++k) + result += weights[k] * (MatrixType::Identity(T.rows(), T.rows()) + nodes[k] * TminusI) + .template triangularView().solve(TminusI); +} + +/** \ingroup MatrixFunctions_Module + * + * \brief Proxy for the matrix logarithm of some matrix (expression). + * + * \tparam Derived Type of the argument to the matrix function. + * + * This class holds the argument to the matrix function until it is + * assigned or evaluated for some other reason (so the argument + * should not be changed in the meantime). It is the return type of + * matrixBase::matrixLogarithm() and most of the time this is the + * only way it is used. + */ +template class MatrixLogarithmReturnValue +: public ReturnByValue > +{ +public: + + typedef typename Derived::Scalar Scalar; + typedef typename Derived::Index Index; + + /** \brief Constructor. + * + * \param[in] A %Matrix (expression) forming the argument of the matrix logarithm. + */ + MatrixLogarithmReturnValue(const Derived& A) : m_A(A) { } + + /** \brief Compute the matrix logarithm. + * + * \param[out] result Logarithm of \p A, where \A is as specified in the constructor. + */ + template + inline void evalTo(ResultType& result) const + { + typedef typename Derived::PlainObject PlainObject; + typedef internal::traits Traits; + static const int RowsAtCompileTime = Traits::RowsAtCompileTime; + static const int ColsAtCompileTime = Traits::ColsAtCompileTime; + static const int Options = PlainObject::Options; + typedef std::complex::Real> ComplexScalar; + typedef Matrix DynMatrixType; + typedef MatrixLogarithmAtomic AtomicType; + AtomicType atomic; + + const PlainObject Aevaluated = m_A.eval(); + MatrixFunction mf(Aevaluated, atomic); + mf.compute(result); + } + + Index rows() const { return m_A.rows(); } + Index cols() const { return m_A.cols(); } + +private: + typename internal::nested::type m_A; + + MatrixLogarithmReturnValue& operator=(const MatrixLogarithmReturnValue&); +}; + +namespace internal { + template + struct traits > + { + typedef typename Derived::PlainObject ReturnType; + }; +} + + +/********** MatrixBase method **********/ + + +template +const MatrixLogarithmReturnValue MatrixBase::log() const +{ + eigen_assert(rows() == cols()); + return MatrixLogarithmReturnValue(derived()); +} + +} // end namespace Eigen + +#endif // EIGEN_MATRIX_LOGARITHM diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h new file mode 100644 index 000000000..658cd334c --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h @@ -0,0 +1,499 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Jitse Niesen +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_MATRIX_SQUARE_ROOT +#define EIGEN_MATRIX_SQUARE_ROOT + +namespace Eigen { + +/** \ingroup MatrixFunctions_Module + * \brief Class for computing matrix square roots of upper quasi-triangular matrices. + * \tparam MatrixType type of the argument of the matrix square root, + * expected to be an instantiation of the Matrix class template. + * + * This class computes the square root of the upper quasi-triangular + * matrix stored in the upper Hessenberg part of the matrix passed to + * the constructor. + * + * \sa MatrixSquareRoot, MatrixSquareRootTriangular + */ +template +class MatrixSquareRootQuasiTriangular +{ + public: + + /** \brief Constructor. + * + * \param[in] A upper quasi-triangular matrix whose square root + * is to be computed. + * + * The class stores a reference to \p A, so it should not be + * changed (or destroyed) before compute() is called. + */ + MatrixSquareRootQuasiTriangular(const MatrixType& A) + : m_A(A) + { + eigen_assert(A.rows() == A.cols()); + } + + /** \brief Compute the matrix square root + * + * \param[out] result square root of \p A, as specified in the constructor. + * + * Only the upper Hessenberg part of \p result is updated, the + * rest is not touched. See MatrixBase::sqrt() for details on + * how this computation is implemented. + */ + template void compute(ResultType &result); + + private: + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + + void computeDiagonalPartOfSqrt(MatrixType& sqrtT, const MatrixType& T); + void computeOffDiagonalPartOfSqrt(MatrixType& sqrtT, const MatrixType& T); + void compute2x2diagonalBlock(MatrixType& sqrtT, const MatrixType& T, typename MatrixType::Index i); + void compute1x1offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j); + void compute1x2offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j); + void compute2x1offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j); + void compute2x2offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j); + + template + static void solveAuxiliaryEquation(SmallMatrixType& X, const SmallMatrixType& A, + const SmallMatrixType& B, const SmallMatrixType& C); + + const MatrixType& m_A; +}; + +template +template +void MatrixSquareRootQuasiTriangular::compute(ResultType &result) +{ + // Compute Schur decomposition of m_A + const RealSchur schurOfA(m_A); + const MatrixType& T = schurOfA.matrixT(); + const MatrixType& U = schurOfA.matrixU(); + + // Compute square root of T + MatrixType sqrtT = MatrixType::Zero(m_A.rows(), m_A.rows()); + computeDiagonalPartOfSqrt(sqrtT, T); + computeOffDiagonalPartOfSqrt(sqrtT, T); + + // Compute square root of m_A + result = U * sqrtT * U.adjoint(); +} + +// pre: T is quasi-upper-triangular and sqrtT is a zero matrix of the same size +// post: the diagonal blocks of sqrtT are the square roots of the diagonal blocks of T +template +void MatrixSquareRootQuasiTriangular::computeDiagonalPartOfSqrt(MatrixType& sqrtT, + const MatrixType& T) +{ + const Index size = m_A.rows(); + for (Index i = 0; i < size; i++) { + if (i == size - 1 || T.coeff(i+1, i) == 0) { + eigen_assert(T(i,i) > 0); + sqrtT.coeffRef(i,i) = internal::sqrt(T.coeff(i,i)); + } + else { + compute2x2diagonalBlock(sqrtT, T, i); + ++i; + } + } +} + +// pre: T is quasi-upper-triangular and diagonal blocks of sqrtT are square root of diagonal blocks of T. +// post: sqrtT is the square root of T. +template +void MatrixSquareRootQuasiTriangular::computeOffDiagonalPartOfSqrt(MatrixType& sqrtT, + const MatrixType& T) +{ + const Index size = m_A.rows(); + for (Index j = 1; j < size; j++) { + if (T.coeff(j, j-1) != 0) // if T(j-1:j, j-1:j) is a 2-by-2 block + continue; + for (Index i = j-1; i >= 0; i--) { + if (i > 0 && T.coeff(i, i-1) != 0) // if T(i-1:i, i-1:i) is a 2-by-2 block + continue; + bool iBlockIs2x2 = (i < size - 1) && (T.coeff(i+1, i) != 0); + bool jBlockIs2x2 = (j < size - 1) && (T.coeff(j+1, j) != 0); + if (iBlockIs2x2 && jBlockIs2x2) + compute2x2offDiagonalBlock(sqrtT, T, i, j); + else if (iBlockIs2x2 && !jBlockIs2x2) + compute2x1offDiagonalBlock(sqrtT, T, i, j); + else if (!iBlockIs2x2 && jBlockIs2x2) + compute1x2offDiagonalBlock(sqrtT, T, i, j); + else if (!iBlockIs2x2 && !jBlockIs2x2) + compute1x1offDiagonalBlock(sqrtT, T, i, j); + } + } +} + +// pre: T.block(i,i,2,2) has complex conjugate eigenvalues +// post: sqrtT.block(i,i,2,2) is square root of T.block(i,i,2,2) +template +void MatrixSquareRootQuasiTriangular + ::compute2x2diagonalBlock(MatrixType& sqrtT, const MatrixType& T, typename MatrixType::Index i) +{ + // TODO: This case (2-by-2 blocks with complex conjugate eigenvalues) is probably hidden somewhere + // in EigenSolver. If we expose it, we could call it directly from here. + Matrix block = T.template block<2,2>(i,i); + EigenSolver > es(block); + sqrtT.template block<2,2>(i,i) + = (es.eigenvectors() * es.eigenvalues().cwiseSqrt().asDiagonal() * es.eigenvectors().inverse()).real(); +} + +// pre: block structure of T is such that (i,j) is a 1x1 block, +// all blocks of sqrtT to left of and below (i,j) are correct +// post: sqrtT(i,j) has the correct value +template +void MatrixSquareRootQuasiTriangular + ::compute1x1offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j) +{ + Scalar tmp = (sqrtT.row(i).segment(i+1,j-i-1) * sqrtT.col(j).segment(i+1,j-i-1)).value(); + sqrtT.coeffRef(i,j) = (T.coeff(i,j) - tmp) / (sqrtT.coeff(i,i) + sqrtT.coeff(j,j)); +} + +// similar to compute1x1offDiagonalBlock() +template +void MatrixSquareRootQuasiTriangular + ::compute1x2offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j) +{ + Matrix rhs = T.template block<1,2>(i,j); + if (j-i > 1) + rhs -= sqrtT.block(i, i+1, 1, j-i-1) * sqrtT.block(i+1, j, j-i-1, 2); + Matrix A = sqrtT.coeff(i,i) * Matrix::Identity(); + A += sqrtT.template block<2,2>(j,j).transpose(); + sqrtT.template block<1,2>(i,j).transpose() = A.fullPivLu().solve(rhs.transpose()); +} + +// similar to compute1x1offDiagonalBlock() +template +void MatrixSquareRootQuasiTriangular + ::compute2x1offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j) +{ + Matrix rhs = T.template block<2,1>(i,j); + if (j-i > 2) + rhs -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 1); + Matrix A = sqrtT.coeff(j,j) * Matrix::Identity(); + A += sqrtT.template block<2,2>(i,i); + sqrtT.template block<2,1>(i,j) = A.fullPivLu().solve(rhs); +} + +// similar to compute1x1offDiagonalBlock() +template +void MatrixSquareRootQuasiTriangular + ::compute2x2offDiagonalBlock(MatrixType& sqrtT, const MatrixType& T, + typename MatrixType::Index i, typename MatrixType::Index j) +{ + Matrix A = sqrtT.template block<2,2>(i,i); + Matrix B = sqrtT.template block<2,2>(j,j); + Matrix C = T.template block<2,2>(i,j); + if (j-i > 2) + C -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 2); + Matrix X; + solveAuxiliaryEquation(X, A, B, C); + sqrtT.template block<2,2>(i,j) = X; +} + +// solves the equation A X + X B = C where all matrices are 2-by-2 +template +template +void MatrixSquareRootQuasiTriangular + ::solveAuxiliaryEquation(SmallMatrixType& X, const SmallMatrixType& A, + const SmallMatrixType& B, const SmallMatrixType& C) +{ + EIGEN_STATIC_ASSERT((internal::is_same >::value), + EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT); + + Matrix coeffMatrix = Matrix::Zero(); + coeffMatrix.coeffRef(0,0) = A.coeff(0,0) + B.coeff(0,0); + coeffMatrix.coeffRef(1,1) = A.coeff(0,0) + B.coeff(1,1); + coeffMatrix.coeffRef(2,2) = A.coeff(1,1) + B.coeff(0,0); + coeffMatrix.coeffRef(3,3) = A.coeff(1,1) + B.coeff(1,1); + coeffMatrix.coeffRef(0,1) = B.coeff(1,0); + coeffMatrix.coeffRef(0,2) = A.coeff(0,1); + coeffMatrix.coeffRef(1,0) = B.coeff(0,1); + coeffMatrix.coeffRef(1,3) = A.coeff(0,1); + coeffMatrix.coeffRef(2,0) = A.coeff(1,0); + coeffMatrix.coeffRef(2,3) = B.coeff(1,0); + coeffMatrix.coeffRef(3,1) = A.coeff(1,0); + coeffMatrix.coeffRef(3,2) = B.coeff(0,1); + + Matrix rhs; + rhs.coeffRef(0) = C.coeff(0,0); + rhs.coeffRef(1) = C.coeff(0,1); + rhs.coeffRef(2) = C.coeff(1,0); + rhs.coeffRef(3) = C.coeff(1,1); + + Matrix result; + result = coeffMatrix.fullPivLu().solve(rhs); + + X.coeffRef(0,0) = result.coeff(0); + X.coeffRef(0,1) = result.coeff(1); + X.coeffRef(1,0) = result.coeff(2); + X.coeffRef(1,1) = result.coeff(3); +} + + +/** \ingroup MatrixFunctions_Module + * \brief Class for computing matrix square roots of upper triangular matrices. + * \tparam MatrixType type of the argument of the matrix square root, + * expected to be an instantiation of the Matrix class template. + * + * This class computes the square root of the upper triangular matrix + * stored in the upper triangular part (including the diagonal) of + * the matrix passed to the constructor. + * + * \sa MatrixSquareRoot, MatrixSquareRootQuasiTriangular + */ +template +class MatrixSquareRootTriangular +{ + public: + MatrixSquareRootTriangular(const MatrixType& A) + : m_A(A) + { + eigen_assert(A.rows() == A.cols()); + } + + /** \brief Compute the matrix square root + * + * \param[out] result square root of \p A, as specified in the constructor. + * + * Only the upper triangular part (including the diagonal) of + * \p result is updated, the rest is not touched. See + * MatrixBase::sqrt() for details on how this computation is + * implemented. + */ + template void compute(ResultType &result); + + private: + const MatrixType& m_A; +}; + +template +template +void MatrixSquareRootTriangular::compute(ResultType &result) +{ + // Compute Schur decomposition of m_A + const ComplexSchur schurOfA(m_A); + const MatrixType& T = schurOfA.matrixT(); + const MatrixType& U = schurOfA.matrixU(); + + // Compute square root of T and store it in upper triangular part of result + // This uses that the square root of triangular matrices can be computed directly. + result.resize(m_A.rows(), m_A.cols()); + typedef typename MatrixType::Index Index; + for (Index i = 0; i < m_A.rows(); i++) { + result.coeffRef(i,i) = internal::sqrt(T.coeff(i,i)); + } + for (Index j = 1; j < m_A.cols(); j++) { + for (Index i = j-1; i >= 0; i--) { + typedef typename MatrixType::Scalar Scalar; + // if i = j-1, then segment has length 0 so tmp = 0 + Scalar tmp = (result.row(i).segment(i+1,j-i-1) * result.col(j).segment(i+1,j-i-1)).value(); + // denominator may be zero if original matrix is singular + result.coeffRef(i,j) = (T.coeff(i,j) - tmp) / (result.coeff(i,i) + result.coeff(j,j)); + } + } + + // Compute square root of m_A as U * result * U.adjoint() + MatrixType tmp; + tmp.noalias() = U * result.template triangularView(); + result.noalias() = tmp * U.adjoint(); +} + + +/** \ingroup MatrixFunctions_Module + * \brief Class for computing matrix square roots of general matrices. + * \tparam MatrixType type of the argument of the matrix square root, + * expected to be an instantiation of the Matrix class template. + * + * \sa MatrixSquareRootTriangular, MatrixSquareRootQuasiTriangular, MatrixBase::sqrt() + */ +template ::Scalar>::IsComplex> +class MatrixSquareRoot +{ + public: + + /** \brief Constructor. + * + * \param[in] A matrix whose square root is to be computed. + * + * The class stores a reference to \p A, so it should not be + * changed (or destroyed) before compute() is called. + */ + MatrixSquareRoot(const MatrixType& A); + + /** \brief Compute the matrix square root + * + * \param[out] result square root of \p A, as specified in the constructor. + * + * See MatrixBase::sqrt() for details on how this computation is + * implemented. + */ + template void compute(ResultType &result); +}; + + +// ********** Partial specialization for real matrices ********** + +template +class MatrixSquareRoot +{ + public: + + MatrixSquareRoot(const MatrixType& A) + : m_A(A) + { + eigen_assert(A.rows() == A.cols()); + } + + template void compute(ResultType &result) + { + // Compute Schur decomposition of m_A + const RealSchur schurOfA(m_A); + const MatrixType& T = schurOfA.matrixT(); + const MatrixType& U = schurOfA.matrixU(); + + // Compute square root of T + MatrixSquareRootQuasiTriangular tmp(T); + MatrixType sqrtT = MatrixType::Zero(m_A.rows(), m_A.rows()); + tmp.compute(sqrtT); + + // Compute square root of m_A + result = U * sqrtT * U.adjoint(); + } + + private: + const MatrixType& m_A; +}; + + +// ********** Partial specialization for complex matrices ********** + +template +class MatrixSquareRoot +{ + public: + + MatrixSquareRoot(const MatrixType& A) + : m_A(A) + { + eigen_assert(A.rows() == A.cols()); + } + + template void compute(ResultType &result) + { + // Compute Schur decomposition of m_A + const ComplexSchur schurOfA(m_A); + const MatrixType& T = schurOfA.matrixT(); + const MatrixType& U = schurOfA.matrixU(); + + // Compute square root of T + MatrixSquareRootTriangular tmp(T); + MatrixType sqrtT = MatrixType::Zero(m_A.rows(), m_A.rows()); + tmp.compute(sqrtT); + + // Compute square root of m_A + result = U * sqrtT * U.adjoint(); + } + + private: + const MatrixType& m_A; +}; + + +/** \ingroup MatrixFunctions_Module + * + * \brief Proxy for the matrix square root of some matrix (expression). + * + * \tparam Derived Type of the argument to the matrix square root. + * + * This class holds the argument to the matrix square root until it + * is assigned or evaluated for some other reason (so the argument + * should not be changed in the meantime). It is the return type of + * MatrixBase::sqrt() and most of the time this is the only way it is + * used. + */ +template class MatrixSquareRootReturnValue +: public ReturnByValue > +{ + typedef typename Derived::Index Index; + public: + /** \brief Constructor. + * + * \param[in] src %Matrix (expression) forming the argument of the + * matrix square root. + */ + MatrixSquareRootReturnValue(const Derived& src) : m_src(src) { } + + /** \brief Compute the matrix square root. + * + * \param[out] result the matrix square root of \p src in the + * constructor. + */ + template + inline void evalTo(ResultType& result) const + { + const typename Derived::PlainObject srcEvaluated = m_src.eval(); + MatrixSquareRoot me(srcEvaluated); + me.compute(result); + } + + Index rows() const { return m_src.rows(); } + Index cols() const { return m_src.cols(); } + + protected: + const Derived& m_src; + private: + MatrixSquareRootReturnValue& operator=(const MatrixSquareRootReturnValue&); +}; + +namespace internal { +template +struct traits > +{ + typedef typename Derived::PlainObject ReturnType; +}; +} + +template +const MatrixSquareRootReturnValue MatrixBase::sqrt() const +{ + eigen_assert(rows() == cols()); + return MatrixSquareRootReturnValue(derived()); +} + +} // end namespace Eigen + +#endif // EIGEN_MATRIX_FUNCTION diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h index 260690b63..3de68ec3a 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h @@ -25,6 +25,8 @@ #ifndef EIGEN_STEM_FUNCTION #define EIGEN_STEM_FUNCTION +namespace Eigen { + /** \ingroup MatrixFunctions_Module * \brief Stem functions corresponding to standard mathematical functions. */ @@ -113,4 +115,6 @@ class StdStemFunctions }; // end of class StdStemFunctions +} // end namespace Eigen + #endif // EIGEN_STEM_FUNCTION diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h index bc948d0bd..123f4016e 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h @@ -26,6 +26,8 @@ #ifndef EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H #define EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H +namespace Eigen { + namespace internal { /** \internal \returns the arcsin of \a a (coeff-wise) */ @@ -99,8 +101,10 @@ template<> EIGEN_DONT_INLINE Packet4f pasin(Packet4f x) return _mm_xor_ps(z, sign_bit); } +#endif // EIGEN_VECTORIZE_SSE + } // end namespace internal -#endif +} // end namespace Eigen #endif // EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h index 37abb6117..aa9430359 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h @@ -28,6 +28,8 @@ #ifndef EIGEN_HYBRIDNONLINEARSOLVER_H #define EIGEN_HYBRIDNONLINEARSOLVER_H +namespace Eigen { + namespace HybridNonLinearSolverSpace { enum Status { Running = -1, @@ -602,6 +604,8 @@ HybridNonLinearSolver::solveNumericalDiff(FVectorType &x) return status; } -//vim: ai ts=4 sts=4 et sw=4 +} // end namespace Eigen + #endif // EIGEN_HYBRIDNONLINEARSOLVER_H +//vim: ai ts=4 sts=4 et sw=4 diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h index 0ae681b1c..1cb501a66 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h @@ -28,6 +28,7 @@ #ifndef EIGEN_LEVENBERGMARQUARDT__H #define EIGEN_LEVENBERGMARQUARDT__H +namespace Eigen { namespace LevenbergMarquardtSpace { enum Status { @@ -640,7 +641,7 @@ LevenbergMarquardt::lmdif1( NumericalDiff numDiff(functor); // embedded LevenbergMarquardt - LevenbergMarquardt > lm(numDiff); + LevenbergMarquardt, Scalar > lm(numDiff); lm.parameters.ftol = tol; lm.parameters.xtol = tol; lm.parameters.maxfev = 200*(n+1); @@ -651,6 +652,8 @@ LevenbergMarquardt::lmdif1( return info; } -//vim: ai ts=4 sts=4 et sw=4 +} // end namespace Eigen + #endif // EIGEN_LEVENBERGMARQUARDT__H +//vim: ai ts=4 sts=4 et sw=4 diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h index bc0cb1880..fd3e0bc4a 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h @@ -2,6 +2,8 @@ #define chkder_log10e 0.43429448190325182765 #define chkder_factor 100. +namespace Eigen { + namespace internal { template @@ -58,3 +60,4 @@ void chkder( } // end namespace internal +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h index 6c77916f5..c73a09645 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { template @@ -63,3 +65,5 @@ void covar( } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h index cbdcf4b71..4fbc98bfc 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { template @@ -98,3 +100,5 @@ algo_end: } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h index 0a26c2061..1cabe69ae 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { template @@ -70,3 +72,5 @@ DenseIndex fdjac1( } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h index 62f4aabc9..cc1ca530f 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { template @@ -288,3 +290,5 @@ void lmpar2( } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h index cb1764a41..feafd62a8 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { // TODO : once qrsolv2 is removed, use ColPivHouseholderQR or PermutationMatrix instead of ipvt @@ -85,3 +87,5 @@ void qrsolv( } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h index ffe505cd5..36ff700e9 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { // TODO : move this to GivensQR once there's such a thing in Eigen @@ -24,3 +26,5 @@ void r1mpyq(DenseIndex m, DenseIndex n, Scalar *a, const std::vector @@ -93,3 +95,5 @@ void r1updt( } } // end namespace internal + +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h index ab83f9b25..9ce079e22 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h @@ -1,3 +1,5 @@ +namespace Eigen { + namespace internal { template @@ -44,3 +46,4 @@ void rwupdt( } // end namespace internal +} // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h index 52dc0ec01..8651585f2 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h @@ -28,6 +28,8 @@ #ifndef EIGEN_NUMERICAL_DIFF_H #define EIGEN_NUMERICAL_DIFF_H +namespace Eigen { + enum NumericalDiffMode { Forward, Central @@ -64,7 +66,7 @@ public: template NumericalDiff(const T0& a0, const T1& a1) : Functor(a0, a1), epsfcn(0) {} template - NumericalDiff(const T0& a0, const T1& a1, const T1& a2) : Functor(a0, a1, a2), epsfcn(0) {} + NumericalDiff(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2), epsfcn(0) {} enum { InputsAtCompileTime = Functor::InputsAtCompileTime, @@ -134,6 +136,8 @@ private: NumericalDiff& operator=(const NumericalDiff&); }; +} // end namespace Eigen + //vim: ai ts=4 sts=4 et sw=4 #endif // EIGEN_NUMERICAL_DIFF_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/Companion.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/Companion.h index 608951d3c..8936b8fad 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/Companion.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/Companion.h @@ -29,10 +29,12 @@ // * Eigen/Core // * Eigen/src/PolynomialSolver.h -#ifndef EIGEN_PARSED_BY_DOXYGEN +namespace Eigen { namespace internal { +#ifndef EIGEN_PARSED_BY_DOXYGEN + template T radix(){ return 2; } @@ -283,4 +285,6 @@ void companion<_Scalar,_Deg>::balance() } // end namespace internal +} // end namespace Eigen + #endif // EIGEN_COMPANION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h index 417b93df2..71295a105 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h @@ -25,6 +25,8 @@ #ifndef EIGEN_POLYNOMIAL_SOLVER_H #define EIGEN_POLYNOMIAL_SOLVER_H +namespace Eigen { + /** \ingroup Polynomials_Module * \class PolynomialSolverBase. * @@ -394,4 +396,6 @@ class PolynomialSolver<_Scalar,1> : public PolynomialSolverBase<_Scalar,1> using PS_Base::m_roots; }; +} // end namespace Eigen + #endif // EIGEN_POLYNOMIAL_SOLVER_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h index 65942c52a..1fb1ed139 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h @@ -25,6 +25,8 @@ #ifndef EIGEN_POLYNOMIAL_UTILS_H #define EIGEN_POLYNOMIAL_UTILS_H +namespace Eigen { + /** \ingroup Polynomials_Module * \returns the evaluation of the polynomial at x using Horner algorithm. * @@ -149,5 +151,6 @@ void roots_to_monicPolynomial( const RootVector& rv, Polynomial& poly ) } } +} // end namespace Eigen #endif // EIGEN_POLYNOMIAL_UTILS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h index 51537402e..ef36ac9b6 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SKYLINEINPLACELU_H #define EIGEN_SKYLINEINPLACELU_H +namespace Eigen { + /** \ingroup Skyline_Module * * \class SkylineInplaceLU @@ -360,4 +362,6 @@ bool SkylineInplaceLU::solve(const MatrixBase &b, MatrixBa return true; } +} // end namespace Eigen + #endif // EIGEN_SKYLINELU_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h index 31810df08..98a19ce53 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h @@ -28,6 +28,8 @@ #include "SkylineStorage.h" #include "SkylineMatrixBase.h" +namespace Eigen { + /** \ingroup Skyline_Module * * \class SkylineMatrix @@ -870,4 +872,6 @@ protected: const Index m_end; }; +} // end namespace Eigen + #endif // EIGEN_SkylineMatrix_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h index 4d0c2397c..72131eb3f 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h @@ -27,6 +27,8 @@ #include "SkylineUtil.h" +namespace Eigen { + /** \ingroup Skyline_Module * * \class SkylineMatrixBase @@ -220,4 +222,6 @@ protected: bool m_isRValue; }; +} // end namespace Eigen + #endif // EIGEN_SkylineMatrixBase_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h index aeedc47ec..fb653b446 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SKYLINEPRODUCT_H #define EIGEN_SKYLINEPRODUCT_H +namespace Eigen { + template struct SkylineProductReturnType { typedef const typename internal::nested::type LhsNested; @@ -303,4 +305,6 @@ SkylineMatrixBase::operator*(const MatrixBase &other) con return typename SkylineProductReturnType::Type(derived(), other.derived()); } +} // end namespace Eigen + #endif // EIGEN_SKYLINEPRODUCT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h index 62806bfb6..5721dee90 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SKYLINE_STORAGE_H #define EIGEN_SKYLINE_STORAGE_H +namespace Eigen { + /** Stores a skyline set of values in three structures : * The diagonal elements * The upper elements @@ -267,4 +269,6 @@ public: }; +} // end namespace Eigen + #endif // EIGEN_COMPRESSED_STORAGE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h index e0512476f..5c5bd8bda 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h @@ -25,6 +25,8 @@ #ifndef EIGEN_SKYLINEUTIL_H #define EIGEN_SKYLINEUTIL_H +namespace Eigen { + #ifdef NDEBUG #define EIGEN_DBG_SKYLINE(X) #else @@ -97,5 +99,6 @@ template class eval } // end namespace internal +} // end namespace Eigen #endif // EIGEN_SKYLINEUTIL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/BlockOfDynamicSparseMatrix.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/BlockOfDynamicSparseMatrix.h new file mode 100644 index 000000000..0cc6e3a06 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/BlockOfDynamicSparseMatrix.h @@ -0,0 +1,129 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2009 Gael Guennebaud +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H +#define EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H + +namespace Eigen { + +/*************************************************************************** +* specialisation for DynamicSparseMatrix +***************************************************************************/ + +template +class SparseInnerVectorSet, Size> + : public SparseMatrixBase, Size> > +{ + typedef DynamicSparseMatrix<_Scalar, _Options, _Index> MatrixType; + public: + + enum { IsRowMajor = internal::traits::IsRowMajor }; + + EIGEN_SPARSE_PUBLIC_INTERFACE(SparseInnerVectorSet) + class InnerIterator: public MatrixType::InnerIterator + { + public: + inline InnerIterator(const SparseInnerVectorSet& xpr, Index outer) + : MatrixType::InnerIterator(xpr.m_matrix, xpr.m_outerStart + outer), m_outer(outer) + {} + inline Index row() const { return IsRowMajor ? m_outer : this->index(); } + inline Index col() const { return IsRowMajor ? this->index() : m_outer; } + protected: + Index m_outer; + }; + + inline SparseInnerVectorSet(const MatrixType& matrix, Index outerStart, Index outerSize) + : m_matrix(matrix), m_outerStart(outerStart), m_outerSize(outerSize) + { + eigen_assert( (outerStart>=0) && ((outerStart+outerSize)<=matrix.outerSize()) ); + } + + inline SparseInnerVectorSet(const MatrixType& matrix, Index outer) + : m_matrix(matrix), m_outerStart(outer), m_outerSize(Size) + { + eigen_assert(Size!=Dynamic); + eigen_assert( (outer>=0) && (outer + inline SparseInnerVectorSet& operator=(const SparseMatrixBase& other) + { + if (IsRowMajor != ((OtherDerived::Flags&RowMajorBit)==RowMajorBit)) + { + // need to transpose => perform a block evaluation followed by a big swap + DynamicSparseMatrix aux(other); + *this = aux.markAsRValue(); + } + else + { + // evaluate/copy vector per vector + for (Index j=0; j aux(other.innerVector(j)); + m_matrix.const_cast_derived()._data()[m_outerStart+j].swap(aux._data()); + } + } + return *this; + } + + inline SparseInnerVectorSet& operator=(const SparseInnerVectorSet& other) + { + return operator=(other); + } + + Index nonZeros() const + { + Index count = 0; + for (Index j=0; j0); + return m_matrix.data()[m_outerStart].vale(m_matrix.data()[m_outerStart].size()-1); + } + +// template +// inline SparseInnerVectorSet& operator=(const SparseMatrixBase& other) +// { +// return *this; +// } + + EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); } + EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); } + + protected: + + const typename MatrixType::Nested m_matrix; + Index m_outerStart; + const internal::variable_if_dynamic m_outerSize; + +}; + +} // end namespace Eigen + +#endif // EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupportLegacy.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupportLegacy.h deleted file mode 100644 index 676cd8574..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CholmodSupportLegacy.h +++ /dev/null @@ -1,517 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2009 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_CHOLMODSUPPORT_LEGACY_H -#define EIGEN_CHOLMODSUPPORT_LEGACY_H - -namespace internal { - -template -void cholmod_configure_matrix_legacy(CholmodType& mat) -{ - if (internal::is_same::value) - { - mat.xtype = CHOLMOD_REAL; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same::value) - { - mat.xtype = CHOLMOD_REAL; - mat.dtype = CHOLMOD_DOUBLE; - } - else if (internal::is_same >::value) - { - mat.xtype = CHOLMOD_COMPLEX; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same >::value) - { - mat.xtype = CHOLMOD_COMPLEX; - mat.dtype = CHOLMOD_DOUBLE; - } - else - { - eigen_assert(false && "Scalar type not supported by CHOLMOD"); - } -} - -template -cholmod_sparse cholmod_map_eigen_to_sparse(_MatrixType& mat) -{ - typedef typename _MatrixType::Scalar Scalar; - cholmod_sparse res; - res.nzmax = mat.nonZeros(); - res.nrow = mat.rows();; - res.ncol = mat.cols(); - res.p = mat._outerIndexPtr(); - res.i = mat._innerIndexPtr(); - res.x = mat._valuePtr(); - res.xtype = CHOLMOD_REAL; - res.itype = CHOLMOD_INT; - res.sorted = 1; - res.packed = 1; - res.dtype = 0; - res.stype = -1; - - internal::cholmod_configure_matrix_legacy(res); - - - if (_MatrixType::Flags & SelfAdjoint) - { - if (_MatrixType::Flags & Upper) - res.stype = 1; - else if (_MatrixType::Flags & Lower) - res.stype = -1; - else - res.stype = 0; - } - else - res.stype = -1; // by default we consider the lower part - - return res; -} - -template -cholmod_dense cholmod_map_eigen_to_dense(MatrixBase& mat) -{ - EIGEN_STATIC_ASSERT((internal::traits::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES); - typedef typename Derived::Scalar Scalar; - - cholmod_dense res; - res.nrow = mat.rows(); - res.ncol = mat.cols(); - res.nzmax = res.nrow * res.ncol; - res.d = Derived::IsVectorAtCompileTime ? mat.derived().size() : mat.derived().outerStride(); - res.x = mat.derived().data(); - res.z = 0; - - internal::cholmod_configure_matrix_legacy(res); - - return res; -} - -template -MappedSparseMatrix map_cholmod_sparse_to_eigen(cholmod_sparse& cm) -{ - return MappedSparseMatrix - (cm.nrow, cm.ncol, reinterpret_cast(cm.p)[cm.ncol], - reinterpret_cast(cm.p), reinterpret_cast(cm.i),reinterpret_cast(cm.x) ); -} - -} // namespace internal - -template -class SparseLLT<_MatrixType, Cholmod> : public SparseLLT<_MatrixType> -{ - protected: - typedef SparseLLT<_MatrixType> Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; - typedef typename Base::CholMatrixType CholMatrixType; - using Base::MatrixLIsDirty; - using Base::SupernodalFactorIsDirty; - using Base::m_flags; - using Base::m_matrix; - using Base::m_status; - - public: - typedef _MatrixType MatrixType; - typedef typename MatrixType::Index Index; - - SparseLLT(int flags = 0) - : Base(flags), m_cholmodFactor(0) - { - cholmod_start(&m_cholmod); - } - - SparseLLT(const MatrixType& matrix, int flags = 0) - : Base(flags), m_cholmodFactor(0) - { - cholmod_start(&m_cholmod); - compute(matrix); - } - - ~SparseLLT() - { - if (m_cholmodFactor) - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); - cholmod_finish(&m_cholmod); - } - - inline const CholMatrixType& matrixL() const; - - template - bool solveInPlace(MatrixBase &b) const; - - template - inline const internal::solve_retval, Rhs> - solve(const MatrixBase& b) const - { - eigen_assert(true && "SparseLLT is not initialized."); - return internal::solve_retval, Rhs>(*this, b.derived()); - } - - void compute(const MatrixType& matrix); - - inline Index cols() const { return m_matrix.cols(); } - inline Index rows() const { return m_matrix.rows(); } - - inline const cholmod_factor* cholmodFactor() const - { return m_cholmodFactor; } - - inline cholmod_common* cholmodCommon() const - { return &m_cholmod; } - - bool succeeded() const; - - protected: - mutable cholmod_common m_cholmod; - cholmod_factor* m_cholmodFactor; -}; - - -namespace internal { - -template - struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SparseLLT<_MatrixType, Cholmod> SpLLTDecType; - EIGEN_MAKE_SOLVE_HELPERS(SpLLTDecType,Rhs) - - template void evalTo(Dest& dst) const - { - //Index size = dec().cholmodFactor()->n; - eigen_assert((Index)dec().cholmodFactor()->n==rhs().rows()); - - cholmod_factor* cholmodFactor = const_cast(dec().cholmodFactor()); - cholmod_common* cholmodCommon = const_cast(dec().cholmodCommon()); - // this uses Eigen's triangular sparse solver - // if (m_status & MatrixLIsDirty) - // matrixL(); - // Base::solveInPlace(b); - // as long as our own triangular sparse solver is not fully optimal, - // let's use CHOLMOD's one: - cholmod_dense cdb = internal::cholmod_map_eigen_to_dense(rhs().const_cast_derived()); - cholmod_dense* x = cholmod_solve(CHOLMOD_A, cholmodFactor, &cdb, cholmodCommon); - - dst = Matrix::Map(reinterpret_cast(x->x), rhs().rows()); - - cholmod_free_dense(&x, cholmodCommon); - - } - -}; - -} // namespace internal - - - -template -void SparseLLT<_MatrixType,Cholmod>::compute(const _MatrixType& a) -{ - if (m_cholmodFactor) - { - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); - m_cholmodFactor = 0; - } - - cholmod_sparse A = internal::cholmod_map_eigen_to_sparse(const_cast<_MatrixType&>(a)); -// m_cholmod.supernodal = CHOLMOD_AUTO; - // TODO -// if (m_flags&IncompleteFactorization) -// { -// m_cholmod.nmethods = 1; -// m_cholmod.method[0].ordering = CHOLMOD_NATURAL; -// m_cholmod.postorder = 0; -// } -// else -// { -// m_cholmod.nmethods = 1; -// m_cholmod.method[0].ordering = CHOLMOD_NATURAL; -// m_cholmod.postorder = 0; -// } -// m_cholmod.final_ll = 1; - m_cholmodFactor = cholmod_analyze(&A, &m_cholmod); - cholmod_factorize(&A, m_cholmodFactor, &m_cholmod); - - this->m_status = (this->m_status & ~Base::SupernodalFactorIsDirty) | Base::MatrixLIsDirty; -} - - -// TODO -template -bool SparseLLT<_MatrixType,Cholmod>::succeeded() const -{ return true; } - - - -template -inline const typename SparseLLT<_MatrixType,Cholmod>::CholMatrixType& -SparseLLT<_MatrixType,Cholmod>::matrixL() const -{ - if (this->m_status & Base::MatrixLIsDirty) - { - eigen_assert(!(this->m_status & Base::SupernodalFactorIsDirty)); - - cholmod_sparse* cmRes = cholmod_factor_to_sparse(m_cholmodFactor, &m_cholmod); - const_cast(this->m_matrix) = - internal::map_cholmod_sparse_to_eigen(*cmRes); - free(cmRes); - - this->m_status = (this->m_status & ~Base::MatrixLIsDirty); - } - return this->m_matrix; -} - - - - -template -template -bool SparseLLT<_MatrixType,Cholmod>::solveInPlace(MatrixBase &b) const -{ - //Index size = m_cholmodFactor->n; - eigen_assert((Index)m_cholmodFactor->n==b.rows()); - - // this uses Eigen's triangular sparse solver - // if (m_status & MatrixLIsDirty) - // matrixL(); - // Base::solveInPlace(b); - // as long as our own triangular sparse solver is not fully optimal, - // let's use CHOLMOD's one: - cholmod_dense cdb = internal::cholmod_map_eigen_to_dense(b); - - cholmod_dense* x = cholmod_solve(CHOLMOD_A, m_cholmodFactor, &cdb, &m_cholmod); - eigen_assert(x && "Eigen: cholmod_solve failed."); - - b = Matrix::Map(reinterpret_cast(x->x),b.rows()); - cholmod_free_dense(&x, &m_cholmod); - return true; -} - - - - - - - - - - - -template -class SparseLDLT<_MatrixType,Cholmod> : public SparseLDLT<_MatrixType> -{ - protected: - typedef SparseLDLT<_MatrixType> Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; - using Base::MatrixLIsDirty; - using Base::SupernodalFactorIsDirty; - using Base::m_flags; - using Base::m_matrix; - using Base::m_status; - - public: - typedef _MatrixType MatrixType; - typedef typename MatrixType::Index Index; - - SparseLDLT(int flags = 0) - : Base(flags), m_cholmodFactor(0) - { - cholmod_start(&m_cholmod); - } - - SparseLDLT(const _MatrixType& matrix, int flags = 0) - : Base(flags), m_cholmodFactor(0) - { - cholmod_start(&m_cholmod); - compute(matrix); - } - - ~SparseLDLT() - { - if (m_cholmodFactor) - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); - cholmod_finish(&m_cholmod); - } - - inline const typename Base::CholMatrixType& matrixL(void) const; - - template - void solveInPlace(MatrixBase &b) const; - - template - inline const internal::solve_retval, Rhs> - solve(const MatrixBase& b) const - { - eigen_assert(true && "SparseLDLT is not initialized."); - return internal::solve_retval, Rhs>(*this, b.derived()); - } - - void compute(const _MatrixType& matrix); - - inline Index cols() const { return m_matrix.cols(); } - inline Index rows() const { return m_matrix.rows(); } - - inline const cholmod_factor* cholmodFactor() const - { return m_cholmodFactor; } - - inline cholmod_common* cholmodCommon() const - { return &m_cholmod; } - - bool succeeded() const; - - protected: - mutable cholmod_common m_cholmod; - cholmod_factor* m_cholmodFactor; -}; - - - -namespace internal { - -template - struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SparseLDLT<_MatrixType, Cholmod> SpLDLTDecType; - EIGEN_MAKE_SOLVE_HELPERS(SpLDLTDecType,Rhs) - - template void evalTo(Dest& dst) const - { - //Index size = dec().cholmodFactor()->n; - eigen_assert((Index)dec().cholmodFactor()->n==rhs().rows()); - - cholmod_factor* cholmodFactor = const_cast(dec().cholmodFactor()); - cholmod_common* cholmodCommon = const_cast(dec().cholmodCommon()); - // this uses Eigen's triangular sparse solver - // if (m_status & MatrixLIsDirty) - // matrixL(); - // Base::solveInPlace(b); - // as long as our own triangular sparse solver is not fully optimal, - // let's use CHOLMOD's one: - cholmod_dense cdb = internal::cholmod_map_eigen_to_dense(rhs().const_cast_derived()); - cholmod_dense* x = cholmod_solve(CHOLMOD_LDLt, cholmodFactor, &cdb, cholmodCommon); - - dst = Matrix::Map(reinterpret_cast(x->x), rhs().rows()); - cholmod_free_dense(&x, cholmodCommon); - - } - -}; - - -} // namespace internal - -template -void SparseLDLT<_MatrixType,Cholmod>::compute(const _MatrixType& a) -{ - if (m_cholmodFactor) - { - cholmod_free_factor(&m_cholmodFactor, &m_cholmod); - m_cholmodFactor = 0; - } - - cholmod_sparse A = internal::cholmod_map_eigen_to_sparse(const_cast<_MatrixType&>(a)); - - //m_cholmod.supernodal = CHOLMOD_AUTO; - m_cholmod.supernodal = CHOLMOD_SIMPLICIAL; - //m_cholmod.supernodal = CHOLMOD_SUPERNODAL; - // TODO - if (this->m_flags & IncompleteFactorization) - { - m_cholmod.nmethods = 1; - //m_cholmod.method[0].ordering = CHOLMOD_NATURAL; - m_cholmod.method[0].ordering = CHOLMOD_COLAMD; - m_cholmod.postorder = 1; - } - else - { - m_cholmod.nmethods = 1; - m_cholmod.method[0].ordering = CHOLMOD_NATURAL; - m_cholmod.postorder = 0; - } - m_cholmod.final_ll = 0; - m_cholmodFactor = cholmod_analyze(&A, &m_cholmod); - cholmod_factorize(&A, m_cholmodFactor, &m_cholmod); - - this->m_status = (this->m_status & ~Base::SupernodalFactorIsDirty) | Base::MatrixLIsDirty; -} - - -// TODO -template -bool SparseLDLT<_MatrixType,Cholmod>::succeeded() const -{ return true; } - - -template -inline const typename SparseLDLT<_MatrixType>::CholMatrixType& -SparseLDLT<_MatrixType,Cholmod>::matrixL() const -{ - if (this->m_status & Base::MatrixLIsDirty) - { - eigen_assert(!(this->m_status & Base::SupernodalFactorIsDirty)); - - cholmod_sparse* cmRes = cholmod_factor_to_sparse(m_cholmodFactor, &m_cholmod); - const_cast(this->m_matrix) = MappedSparseMatrix(*cmRes); - free(cmRes); - - this->m_status = (this->m_status & ~Base::MatrixLIsDirty); - } - return this->m_matrix; -} - - - - - - -template -template -void SparseLDLT<_MatrixType,Cholmod>::solveInPlace(MatrixBase &b) const -{ - //Index size = m_cholmodFactor->n; - eigen_assert((Index)m_cholmodFactor->n == b.rows()); - - // this uses Eigen's triangular sparse solver - // if (m_status & MatrixLIsDirty) - // matrixL(); - // Base::solveInPlace(b); - // as long as our own triangular sparse solver is not fully optimal, - // let's use CHOLMOD's one: - cholmod_dense cdb = internal::cholmod_map_eigen_to_dense(b); - cholmod_dense* x = cholmod_solve(CHOLMOD_A, m_cholmodFactor, &cdb, &m_cholmod); - b = Matrix::Map(reinterpret_cast(x->x),b.rows()); - cholmod_free_dense(&x, &m_cholmod); -} - - - - - - -#endif // EIGEN_CHOLMODSUPPORT_LEGACY_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/DynamicSparseMatrix.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/DynamicSparseMatrix.h similarity index 87% rename from gtsam/3rdparty/Eigen/Eigen/src/Sparse/DynamicSparseMatrix.h rename to gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/DynamicSparseMatrix.h index 93e75f4c6..151d46538 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Sparse/DynamicSparseMatrix.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/DynamicSparseMatrix.h @@ -25,7 +25,11 @@ #ifndef EIGEN_DYNAMIC_SPARSEMATRIX_H #define EIGEN_DYNAMIC_SPARSEMATRIX_H -/** \class DynamicSparseMatrix +namespace Eigen { + +/** \deprecated use a SparseMatrix in an uncompressed mode + * + * \class DynamicSparseMatrix * * \brief A sparse matrix class designed for matrix assembly purpose * @@ -64,7 +68,7 @@ struct traits > } template -class DynamicSparseMatrix + class DynamicSparseMatrix : public SparseMatrixBase > { public: @@ -84,7 +88,7 @@ class DynamicSparseMatrix typedef DynamicSparseMatrix TransposedSparseMatrix; Index m_innerSize; - std::vector > m_data; + std::vector > m_data; public: @@ -94,8 +98,8 @@ class DynamicSparseMatrix inline Index outerSize() const { return static_cast(m_data.size()); } inline Index innerNonZeros(Index j) const { return m_data[j].size(); } - std::vector >& _data() { return m_data; } - const std::vector >& _data() const { return m_data; } + std::vector >& _data() { return m_data; } + const std::vector >& _data() const { return m_data; } /** \returns the coefficient value at given position \a row, \a col * This operation involes a log(rho*outer_size) binary search. @@ -119,6 +123,7 @@ class DynamicSparseMatrix } class InnerIterator; + class ReverseInnerIterator; void setZero() { @@ -232,20 +237,23 @@ class DynamicSparseMatrix } } - inline DynamicSparseMatrix() + /** The class DynamicSparseMatrix is deprectaed */ + EIGEN_DEPRECATED inline DynamicSparseMatrix() : m_innerSize(0), m_data(0) { eigen_assert(innerSize()==0 && outerSize()==0); } - inline DynamicSparseMatrix(Index rows, Index cols) + /** The class DynamicSparseMatrix is deprectaed */ + EIGEN_DEPRECATED inline DynamicSparseMatrix(Index rows, Index cols) : m_innerSize(0) { resize(rows, cols); } + /** The class DynamicSparseMatrix is deprectaed */ template - explicit inline DynamicSparseMatrix(const SparseMatrixBase& other) + EIGEN_DEPRECATED explicit inline DynamicSparseMatrix(const SparseMatrixBase& other) : m_innerSize(0) { Base::operator=(other.derived()); @@ -325,12 +333,12 @@ class DynamicSparseMatrix # ifdef EIGEN_DYNAMICSPARSEMATRIX_PLUGIN # include EIGEN_DYNAMICSPARSEMATRIX_PLUGIN # endif -}; + }; template -class DynamicSparseMatrix::InnerIterator : public SparseVector::InnerIterator +class DynamicSparseMatrix::InnerIterator : public SparseVector::InnerIterator { - typedef typename SparseVector::InnerIterator Base; + typedef typename SparseVector::InnerIterator Base; public: InnerIterator(const DynamicSparseMatrix& mat, Index outer) : Base(mat.m_data[outer]), m_outer(outer) @@ -343,4 +351,22 @@ class DynamicSparseMatrix::InnerIterator : public Sparse const Index m_outer; }; +template +class DynamicSparseMatrix::ReverseInnerIterator : public SparseVector::ReverseInnerIterator +{ + typedef typename SparseVector::ReverseInnerIterator Base; + public: + ReverseInnerIterator(const DynamicSparseMatrix& mat, Index outer) + : Base(mat.m_data[outer]), m_outer(outer) + {} + + inline Index row() const { return IsRowMajor ? m_outer : Base::index(); } + inline Index col() const { return IsRowMajor ? Base::index() : m_outer; } + + protected: + const Index m_outer; +}; + +} // end namespace Eigen + #endif // EIGEN_DYNAMIC_SPARSEMATRIX_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MarketIO.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MarketIO.h new file mode 100644 index 000000000..9cfe1d9f5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MarketIO.h @@ -0,0 +1,288 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2012 Desire NUENTSA WAKAM +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPARSE_MARKET_IO_H +#define EIGEN_SPARSE_MARKET_IO_H + +#include + +namespace Eigen { + +namespace internal +{ + template + inline bool GetMarketLine (std::stringstream& line, int& M, int& N, int& i, int& j, Scalar& value) + { + line >> i >> j >> value; + i--; + j--; + if(i>=0 && j>=0 && i + inline bool GetMarketLine (std::stringstream& line, int& M, int& N, int& i, int& j, std::complex& value) + { + Scalar valR, valI; + line >> i >> j >> valR >> valI; + i--; + j--; + if(i>=0 && j>=0 && i(valR, valI); + return true; + } + else + return false; + } + + template + inline void GetVectorElt (const std::string& line, RealScalar& val) + { + std::istringstream newline(line); + newline >> val; + } + + template + inline void GetVectorElt (const std::string& line, std::complex& val) + { + RealScalar valR, valI; + std::istringstream newline(line); + newline >> valR >> valI; + val = std::complex(valR, valI); + } + + template + inline void putMarketHeader(std::string& header,int sym) + { + header= "%%MatrixMarket matrix coordinate "; + if(internal::is_same >::value || internal::is_same >::value) + { + header += " complex"; + if(sym == Symmetric) header += " symmetric"; + else if (sym == SelfAdjoint) header += " Hermitian"; + else header += " general"; + } + else + { + header += " real"; + if(sym == Symmetric) header += " symmetric"; + else header += " general"; + } + } + + template + inline void PutMatrixElt(Scalar value, int row, int col, std::ofstream& out) + { + out << row << " "<< col << " " << value << "\n"; + } + template + inline void PutMatrixElt(std::complex value, int row, int col, std::ofstream& out) + { + out << row << " " << col << " " << value.real() << " " << value.imag() << "\n"; + } + + + template + inline void putVectorElt(Scalar value, std::ofstream& out) + { + out << value << "\n"; + } + template + inline void putVectorElt(std::complex value, std::ofstream& out) + { + out << value.real << " " << value.imag()<< "\n"; + } + +} // end namepsace internal + +inline bool getMarketHeader(const std::string& filename, int& sym, bool& iscomplex, bool& isvector) +{ + sym = 0; + isvector = false; + std::ifstream in(filename.c_str(),std::ios::in); + if(!in) + return false; + + std::string line; + // The matrix header is always the first line in the file + std::getline(in, line); assert(in.good()); + + std::stringstream fmtline(line); + std::string substr[5]; + fmtline>> substr[0] >> substr[1] >> substr[2] >> substr[3] >> substr[4]; + if(substr[2].compare("array") == 0) isvector = true; + if(substr[3].compare("complex") == 0) iscomplex = true; + if(substr[4].compare("symmetric") == 0) sym = Symmetric; + else if (substr[4].compare("Hermitian") == 0) sym = SelfAdjoint; + + return true; +} + +template +bool loadMarket(SparseMatrixType& mat, const std::string& filename) +{ + typedef typename SparseMatrixType::Scalar Scalar; + std::ifstream input(filename.c_str(),std::ios::in); + if(!input) + return false; + + const int maxBuffersize = 2048; + char buffer[maxBuffersize]; + + bool readsizes = false; + + typedef Triplet T; + std::vector elements; + + int M(-1), N(-1), NNZ(-1); + int count = 0; + while(input.getline(buffer, maxBuffersize)) + { + // skip comments + //NOTE An appropriate test should be done on the header to get the symmetry + if(buffer[0]=='%') + continue; + + std::stringstream line(buffer); + + if(!readsizes) + { + line >> M >> N >> NNZ; + if(M > 0 && N > 0 && NNZ > 0) + { + readsizes = true; + std::cout << "sizes: " << M << "," << N << "," << NNZ << "\n"; + mat.resize(M,N); + mat.reserve(NNZ); + } + } + else + { + int i(-1), j(-1); + Scalar value; + if( internal::GetMarketLine(line, M, N, i, j, value) ) + { + ++ count; + elements.push_back(T(i,j,value)); + } + else + std::cerr << "Invalid read: " << i << "," << j << "\n"; + } + } + mat.setFromTriplets(elements.begin(), elements.end()); + if(count!=NNZ) + std::cerr << count << "!=" << NNZ << "\n"; + + input.close(); + return true; +} + +template +bool loadMarketVector(VectorType& vec, const std::string& filename) +{ + typedef typename VectorType::Scalar Scalar; + std::ifstream in(filename.c_str(), std::ios::in); + if(!in) + return false; + + std::string line; + int n(0), col(0); + do + { // Skip comments + std::getline(in, line); assert(in.good()); + } while (line[0] == '%'); + std::istringstream newline(line); + newline >> n >> col; + assert(n>0 && col>0); + vec.resize(n); + int i = 0; + Scalar value; + while ( std::getline(in, line) && (i < n) ){ + internal::GetVectorElt(line, value); + vec(i++) = value; + } + in.close(); + if (i!=n){ + std::cerr<< "Unable to read all elements from file " << filename << "\n"; + return false; + } + return true; +} + +template +bool saveMarket(const SparseMatrixType& mat, const std::string& filename, int sym = 0) +{ + typedef typename SparseMatrixType::Scalar Scalar; + std::ofstream out(filename.c_str(),std::ios::out); + if(!out) + return false; + + out.flags(std::ios_base::scientific); + out.precision(64); + std::string header; + internal::putMarketHeader(header, sym); + out << header << std::endl; + out << mat.rows() << " " << mat.cols() << " " << mat.nonZeros() << "\n"; + int count = 0; + for(int j=0; j +bool saveMarketVector (const VectorType& vec, const std::string& filename) +{ + typedef typename VectorType::Scalar Scalar; + std::ofstream out(filename.c_str(),std::ios::out); + if(!out) + return false; + + out.flags(std::ios_base::scientific); + out.precision(64); + if(internal::is_same >::value || internal::is_same >::value) + out << "%%MatrixMarket matrix array complex general\n"; + else + out << "%%MatrixMarket matrix array real general\n"; + out << vec.size() << " "<< 1 << "\n"; + for (int i=0; i < vec.size(); i++){ + internal::putVectorElt(vec(i), out); + } + out.close(); + return true; +} + +} // end namespace Eigen + +#endif // EIGEN_SPARSE_MARKET_IO_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MatrixMarketIterator.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MatrixMarketIterator.h new file mode 100644 index 000000000..3c34effca --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/MatrixMarketIterator.h @@ -0,0 +1,236 @@ + +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2012 Desire NUENTSA WAKAM +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_BROWSE_MATRICES_H +#define EIGEN_BROWSE_MATRICES_H + +namespace Eigen { + +enum { + SPD = 0x100, + NonSymmetric = 0x0 +}; + +/** + * @brief Iterator to browse matrices from a specified folder + * + * This is used to load all the matrices from a folder. + * The matrices should be in Matrix Market format + * It is assumed that the matrices are named as matname.mtx + * and matname_SPD.mtx if the matrix is Symmetric and positive definite (or Hermitian) + * The right hand side vectors are loaded as well, if they exist. + * They should be named as matname_b.mtx. + * Note that the right hand side for a SPD matrix is named as matname_SPD_b.mtx + * + * Sometimes a reference solution is available. In this case, it should be named as matname_x.mtx + * + * Sample code + * \code + * + * \endcode + * + * \tparam Scalar The scalar type + */ +template +class MatrixMarketIterator +{ + public: + typedef Matrix VectorType; + typedef SparseMatrix MatrixType; + + public: + MatrixMarketIterator(const std::string folder):m_sym(0),m_isvalid(false),m_matIsLoaded(false),m_hasRhs(false),m_hasrefX(false),m_folder(folder) + { + m_folder_id = opendir(folder.c_str()); + if (!m_folder_id){ + m_isvalid = false; + std::cerr << "The provided Matrix folder could not be opened \n\n"; + abort(); + } + Getnextvalidmatrix(); + } + + ~MatrixMarketIterator() + { + if (m_folder_id) closedir(m_folder_id); + } + + inline MatrixMarketIterator& operator++() + { + m_matIsLoaded = false; + m_hasrefX = false; + m_hasRhs = false; + Getnextvalidmatrix(); + return *this; + } + inline operator bool() const { return m_isvalid;} + + /** Return the sparse matrix corresponding to the current file */ + inline MatrixType& matrix() + { + // Read the matrix + if (m_matIsLoaded) return m_mat; + + std::string matrix_file = m_folder + "/" + m_matname + ".mtx"; + if ( !loadMarket(m_mat, matrix_file)) + { + m_matIsLoaded = false; + return m_mat; + } + m_matIsLoaded = true; + + if (m_sym != NonSymmetric) + { // Store the upper part of the matrix. It is needed by the solvers dealing with nonsymmetric matrices ?? + MatrixType B; + B = m_mat; + m_mat = B.template selfadjointView(); + } + return m_mat; + } + + /** Return the right hand side corresponding to the current matrix. + * If the rhs file is not provided, a random rhs is generated + */ + inline VectorType& rhs() + { + // Get the right hand side + if (m_hasRhs) return m_rhs; + + std::string rhs_file; + rhs_file = m_folder + "/" + m_matname + "_b.mtx"; // The pattern is matname_b.mtx + m_hasRhs = Fileexists(rhs_file); + if (m_hasRhs) + { + m_rhs.resize(m_mat.cols()); + m_hasRhs = loadMarketVector(m_rhs, rhs_file); + } + if (!m_hasRhs) + { + // Generate a random right hand side + if (!m_matIsLoaded) this->matrix(); + m_refX.resize(m_mat.cols()); + m_refX.setRandom(); + m_rhs = m_mat * m_refX; + m_hasrefX = true; + m_hasRhs = true; + } + return m_rhs; + } + + /** Return a reference solution + * If it is not provided and if the right hand side is not available + * then refX is randomly generated such that A*refX = b + * where A and b are the matrix and the rhs. + * Note that when a rhs is provided, refX is not available + */ + inline VectorType& refX() + { + // Check if a reference solution is provided + if (m_hasrefX) return m_refX; + + std::string lhs_file; + lhs_file = m_folder + "/" + m_matname + "_x.mtx"; + m_hasrefX = Fileexists(lhs_file); + if (m_hasrefX) + { + m_refX.resize(m_mat.cols()); + m_hasrefX = loadMarketVector(m_refX, lhs_file); + } + return m_refX; + } + + inline std::string& matname() { return m_matname; } + + inline int sym() { return m_sym; } + + inline bool hasRhs() {return m_hasRhs; } + inline bool hasrefX() {return m_hasrefX; } + + protected: + + inline bool Fileexists(std::string file) + { + std::ifstream file_id(file.c_str()); + if (!file_id.good() ) + { + return false; + } + else + { + file_id.close(); + return true; + } + } + + void Getnextvalidmatrix( ) + { + m_isvalid = false; + // Here, we return with the next valid matrix in the folder + while ( (m_curs_id = readdir(m_folder_id)) != NULL) { + m_isvalid = false; + std::string curfile; + curfile = m_folder + "/" + m_curs_id->d_name; + // Discard if it is a folder + if (m_curs_id->d_type == DT_DIR) continue; //FIXME This may not be available on non BSD systems +// struct stat st_buf; +// stat (curfile.c_str(), &st_buf); +// if (S_ISDIR(st_buf.st_mode)) continue; + + // Determine from the header if it is a matrix or a right hand side + bool isvector,iscomplex; + if(!getMarketHeader(curfile,m_sym,iscomplex,isvector)) continue; + if(isvector) continue; + + // Get the matrix name + std::string filename = m_curs_id->d_name; + m_matname = filename.substr(0, filename.length()-4); + + // Find if the matrix is SPD + size_t found = m_matname.find("SPD"); + if( (found!=std::string::npos) && (m_sym != NonSymmetric) ) + m_sym = SPD; + + m_isvalid = true; + break; + } + } + int m_sym; // Symmetry of the matrix + MatrixType m_mat; // Current matrix + VectorType m_rhs; // Current vector + VectorType m_refX; // The reference solution, if exists + std::string m_matname; // Matrix Name + bool m_isvalid; + bool m_matIsLoaded; // Determine if the matrix has already been loaded from the file + bool m_hasRhs; // The right hand side exists + bool m_hasrefX; // A reference solution is provided + std::string m_folder; + DIR * m_folder_id; + struct dirent *m_curs_id; + +}; + +} // end namespace Eigen + +#endif diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h index 4ea41af85..9328c60cf 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h @@ -25,6 +25,8 @@ #ifndef EIGEN_RANDOMSETTER_H #define EIGEN_RANDOMSETTER_H +namespace Eigen { + /** Represents a std::map * * \see RandomSetter @@ -180,9 +182,7 @@ class RandomSetter enum { SwapStorage = 1 - MapTraits::IsSorted, TargetRowMajor = (SparseMatrixType::Flags & RowMajorBit) ? 1 : 0, - SetterRowMajor = SwapStorage ? 1-TargetRowMajor : TargetRowMajor, - IsUpper = SparseMatrixType::Flags & Upper, - IsLower = SparseMatrixType::Flags & Lower + SetterRowMajor = SwapStorage ? 1-TargetRowMajor : TargetRowMajor }; public: @@ -227,6 +227,7 @@ class RandomSetter if (!SwapStorage) // also means the map is sorted { mp_target->setZero(); + mp_target->makeCompressed(); mp_target->reserve(nonZeros()); Index prevOuter = -1; for (Index k=0; kouterSize(); ++j) { Index tmp = positions[j]; - mp_target->_outerIndexPtr()[j] = count; + mp_target->outerIndexPtr()[j] = count; positions[j] = count; count += tmp; } - mp_target->_outerIndexPtr()[mp_target->outerSize()] = count; + mp_target->makeCompressed(); + mp_target->outerIndexPtr()[mp_target->outerSize()] = count; mp_target->resizeNonZeros(count); // pass 2 for (Index k=0; k_outerIndexPtr()[outer]; + Index posStart = mp_target->outerIndexPtr()[outer]; Index i = (positions[outer]++) - 1; - while ( (i >= posStart) && (mp_target->_innerIndexPtr()[i] > inner) ) + while ( (i >= posStart) && (mp_target->innerIndexPtr()[i] > inner) ) { - mp_target->_valuePtr()[i+1] = mp_target->_valuePtr()[i]; - mp_target->_innerIndexPtr()[i+1] = mp_target->_innerIndexPtr()[i]; + mp_target->valuePtr()[i+1] = mp_target->valuePtr()[i]; + mp_target->innerIndexPtr()[i+1] = mp_target->innerIndexPtr()[i]; --i; } - mp_target->_innerIndexPtr()[i+1] = inner; - mp_target->_valuePtr()[i+1] = it->second.value; + mp_target->innerIndexPtr()[i+1] = inner; + mp_target->valuePtr()[i+1] = it->second.value; } } } @@ -305,8 +307,6 @@ class RandomSetter /** \returns a reference to the coefficient at given coordinates \a row, \a col */ Scalar& operator() (Index row, Index col) { - eigen_assert(((!IsUpper) || (row<=col)) && "Invalid access to an upper triangular matrix"); - eigen_assert(((!IsLower) || (col<=row)) && "Invalid access to an upper triangular matrix"); const Index outer = SetterRowMajor ? row : col; const Index inner = SetterRowMajor ? col : row; const Index outerMajor = outer >> OuterPacketBits; // index of the packet/map @@ -337,4 +337,6 @@ class RandomSetter unsigned char m_keyBitsOffset; }; +} // end namespace Eigen + #endif // EIGEN_RANDOMSETTER_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SimplicialCholesky.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SimplicialCholesky.h deleted file mode 100644 index 6af6407c7..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SimplicialCholesky.h +++ /dev/null @@ -1,477 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -/* - -NOTE: the _symbolic, and _numeric functions has been adapted from - the LDL library: - -LDL Copyright (c) 2005 by Timothy A. Davis. All Rights Reserved. - -LDL License: - - Your use or distribution of LDL or any modified version of - LDL implies that you agree to this License. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 - USA - - Permission is hereby granted to use or copy this program under the - terms of the GNU LGPL, provided that the Copyright, this License, - and the Availability of the original version is retained on all copies. - User documentation of any code that uses this code or any modified - version of this code must cite the Copyright, this License, the - Availability note, and "Used by permission." Permission to modify - the code and to distribute modified code is granted, provided the - Copyright, this License, and the Availability note are retained, - and a notice that the code was modified is included. - */ - -#ifndef EIGEN_SIMPLICIAL_CHOLESKY_H -#define EIGEN_SIMPLICIAL_CHOLESKY_H - -enum SimplicialCholeskyMode { - SimplicialCholeskyLLt, - SimplicialCholeskyLDLt -}; - -/** \brief A direct sparse Cholesky factorization - * - * This class allows to solve for A.X = B sparse linear problems via a LL^T or LDL^T Cholesky factorization. - * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices - * X and B can be either dense or sparse. - * - * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<> - * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower - * or Upper. Default is Lower. - * - */ -template -class SimplicialCholesky -{ - public: - typedef _MatrixType MatrixType; - enum { UpLo = _UpLo }; - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; - typedef SparseMatrix CholMatrixType; - typedef Matrix VectorType; - - public: - - SimplicialCholesky() - : m_info(Success), m_isInitialized(false), m_LDLt(true) - {} - - SimplicialCholesky(const MatrixType& matrix) - : m_info(Success), m_isInitialized(false), m_LDLt(true) - { - compute(matrix); - } - - ~SimplicialCholesky() - { - } - - inline Index cols() const { return m_matrix.cols(); } - inline Index rows() const { return m_matrix.rows(); } - - SimplicialCholesky& setMode(SimplicialCholeskyMode mode) - { - switch(mode) - { - case SimplicialCholeskyLLt: - m_LDLt = false; - break; - case SimplicialCholeskyLDLt: - m_LDLt = true; - break; - default: - break; - } - - return *this; - } - - /** \brief Reports whether previous computation was successful. - * - * \returns \c Success if computation was succesful, - * \c NumericalIssue if the matrix.appears to be negative. - */ - ComputationInfo info() const - { - eigen_assert(m_isInitialized && "Decomposition is not initialized."); - return m_info; - } - - /** Computes the sparse Cholesky decomposition of \a matrix */ - SimplicialCholesky& compute(const MatrixType& matrix) - { - analyzePattern(matrix); - factorize(matrix); - return *this; - } - - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ - template - inline const internal::solve_retval - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "SimplicialCholesky is not initialized."); - eigen_assert(rows()==b.rows() - && "SimplicialCholesky::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); - } - - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ -// template -// inline const internal::sparse_solve_retval -// solve(const SparseMatrixBase& b) const -// { -// eigen_assert(m_isInitialized && "SimplicialCholesky is not initialized."); -// eigen_assert(rows()==b.rows() -// && "SimplicialCholesky::solve(): invalid number of rows of the right hand side matrix b"); -// return internal::sparse_solve_retval(*this, b.derived()); -// } - - /** Performs a symbolic decomposition on the sparcity of \a matrix. - * - * This function is particularly useful when solving for several problems having the same structure. - * - * \sa factorize() - */ - void analyzePattern(const MatrixType& a); - - - /** Performs a numeric decomposition of \a matrix - * - * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed. - * - * \sa analyzePattern() - */ - void factorize(const MatrixType& a); - - /** \returns the permutation P - * \sa permutationPinv() */ - const PermutationMatrix& permutationP() const - { return m_P; } - - /** \returns the inverse P^-1 of the permutation P - * \sa permutationP() */ - const PermutationMatrix& permutationPinv() const - { return m_Pinv; } - - #ifndef EIGEN_PARSED_BY_DOXYGEN - /** \internal */ - template - void _solve(const MatrixBase &b, MatrixBase &dest) const - { - eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); - eigen_assert(m_matrix.rows()==b.rows()); - - if(m_info!=Success) - return; - - if(m_P.size()>0) - dest = m_Pinv * b; - else - dest = b; - - if(m_LDLt) - { - if(m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.template triangularView().solveInPlace(dest); - - dest = m_diag.asDiagonal().inverse() * dest; - - if (m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.adjoint().template triangularView().solveInPlace(dest); - } - else - { - if(m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.template triangularView().solveInPlace(dest); - - if (m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.adjoint().template triangularView().solveInPlace(dest); - } - - if(m_P.size()>0) - dest = m_P * dest; - } - - /** \internal */ - /* - template - void _solve(const SparseMatrix &b, SparseMatrix &dest) const - { - // TODO - } - */ - #endif // EIGEN_PARSED_BY_DOXYGEN - - template - void dumpMemory(Stream& s) - { - int total = 0; - s << " L: " << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << "Mb" << "\n"; - s << " diag: " << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << "Mb" << "\n"; - s << " tree: " << ((total+=m_parent.size() * sizeof(int)) >> 20) << "Mb" << "\n"; - s << " nonzeros: " << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << "Mb" << "\n"; - s << " perm: " << ((total+=m_P.size() * sizeof(int)) >> 20) << "Mb" << "\n"; - s << " perm^-1: " << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << "Mb" << "\n"; - s << " TOTAL: " << (total>> 20) << "Mb" << "\n"; - } - - protected: - /** keeps off-diagonal entries; drops diagonal entries */ - struct keep_diag { - inline bool operator() (const Index& row, const Index& col, const Scalar&) const - { - return row!=col; - } - }; - - mutable ComputationInfo m_info; - bool m_isInitialized; - bool m_factorizationIsOk; - bool m_analysisIsOk; - bool m_LDLt; - - CholMatrixType m_matrix; - VectorType m_diag; // the diagonal coefficients in case of a LDLt decomposition - VectorXi m_parent; // elimination tree - VectorXi m_nonZerosPerCol; - PermutationMatrix m_P; // the permutation - PermutationMatrix m_Pinv; // the inverse permutation -}; - -template -void SimplicialCholesky<_MatrixType,_UpLo>::analyzePattern(const MatrixType& a) -{ - eigen_assert(a.rows()==a.cols()); - const Index size = a.rows(); - m_matrix.resize(size, size); - m_parent.resize(size); - m_nonZerosPerCol.resize(size); - - ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); - - // TODO allows to configure the permutation - { - CholMatrixType C; - C = a.template selfadjointView(); - // remove diagonal entries: - C.prune(keep_diag()); - internal::minimum_degree_ordering(C, m_P); - } - - if(m_P.size()>0) - m_Pinv = m_P.inverse(); - else - m_Pinv.resize(0); - - SparseMatrix ap(size,size); - ap.template selfadjointView() = a.template selfadjointView().twistedBy(m_Pinv); - - for(Index k = 0; k < size; ++k) - { - /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */ - m_parent[k] = -1; /* parent of k is not yet known */ - tags[k] = k; /* mark node k as visited */ - m_nonZerosPerCol[k] = 0; /* count of nonzeros in column k of L */ - for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it) - { - Index i = it.index(); - if(i < k) - { - /* follow path from i to root of etree, stop at flagged node */ - for(; tags[i] != k; i = m_parent[i]) - { - /* find parent of i if not yet determined */ - if (m_parent[i] == -1) - m_parent[i] = k; - m_nonZerosPerCol[i]++; /* L (k,i) is nonzero */ - tags[i] = k; /* mark i as visited */ - } - } - } - } - - /* construct Lp index array from m_nonZerosPerCol column counts */ - Index* Lp = m_matrix._outerIndexPtr(); - Lp[0] = 0; - for(Index k = 0; k < size; ++k) - Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (m_LDLt ? 0 : 1); - - m_matrix.resizeNonZeros(Lp[size]); - - m_isInitialized = true; - m_info = Success; - m_analysisIsOk = true; - m_factorizationIsOk = false; -} - - -template -void SimplicialCholesky<_MatrixType,_UpLo>::factorize(const MatrixType& a) -{ - eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); - eigen_assert(a.rows()==a.cols()); - const Index size = a.rows(); - eigen_assert(m_parent.size()==size); - eigen_assert(m_nonZerosPerCol.size()==size); - - const Index* Lp = m_matrix._outerIndexPtr(); - Index* Li = m_matrix._innerIndexPtr(); - Scalar* Lx = m_matrix._valuePtr(); - - ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0); - ei_declare_aligned_stack_constructed_variable(Index, pattern, size, 0); - ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); - - SparseMatrix ap(size,size); - ap.template selfadjointView() = a.template selfadjointView().twistedBy(m_Pinv); - - bool ok = true; - m_diag.resize(m_LDLt ? size : 0); - - for(Index k = 0; k < size; ++k) - { - // compute nonzero pattern of kth row of L, in topological order - y[k] = 0.0; // Y(0:k) is now all zero - Index top = size; // stack for pattern is empty - tags[k] = k; // mark node k as visited - m_nonZerosPerCol[k] = 0; // count of nonzeros in column k of L - for(typename MatrixType::InnerIterator it(ap,k); it; ++it) - { - Index i = it.index(); - if(i <= k) - { - y[i] += internal::conj(it.value()); /* scatter A(i,k) into Y (sum duplicates) */ - Index len; - for(len = 0; tags[i] != k; i = m_parent[i]) - { - pattern[len++] = i; /* L(k,i) is nonzero */ - tags[i] = k; /* mark i as visited */ - } - while(len > 0) - pattern[--top] = pattern[--len]; - } - } - - /* compute numerical values kth row of L (a sparse triangular solve) */ - Scalar d = y[k]; // get D(k,k) and clear Y(k) - y[k] = 0.0; - for(; top < size; ++top) - { - Index i = pattern[top]; /* pattern[top:n-1] is pattern of L(:,k) */ - Scalar yi = y[i]; /* get and clear Y(i) */ - y[i] = 0.0; - - /* the nonzero entry L(k,i) */ - Scalar l_ki; - if(m_LDLt) - l_ki = yi / m_diag[i]; - else - yi = l_ki = yi / Lx[Lp[i]]; - - Index p2 = Lp[i] + m_nonZerosPerCol[i]; - Index p; - for(p = Lp[i] + (m_LDLt ? 0 : 1); p < p2; ++p) - y[Li[p]] -= internal::conj(Lx[p]) * yi; - d -= l_ki * internal::conj(yi); - Li[p] = k; /* store L(k,i) in column form of L */ - Lx[p] = l_ki; - ++m_nonZerosPerCol[i]; /* increment count of nonzeros in col i */ - } - if(m_LDLt) - m_diag[k] = d; - else - { - Index p = Lp[k]+m_nonZerosPerCol[k]++; - Li[p] = k ; /* store L(k,k) = sqrt (d) in column k */ - Lx[p] = internal::sqrt(d) ; - } - if(d == Scalar(0)) - { - ok = false; /* failure, D(k,k) is zero */ - break; - } - } - - m_info = ok ? Success : NumericalIssue; - m_factorizationIsOk = true; -} - -namespace internal { - -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SimplicialCholesky<_MatrixType,_UpLo> Dec; - EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -template -struct sparse_solve_retval, Rhs> - : sparse_solve_retval_base, Rhs> -{ - typedef SimplicialCholesky<_MatrixType,_UpLo> Dec; - EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -} - -#endif // EIGEN_SIMPLICIAL_CHOLESKY_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLDLTLegacy.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLDLTLegacy.h deleted file mode 100644 index 14283c117..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLDLTLegacy.h +++ /dev/null @@ -1,414 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -/* - -NOTE: the _symbolic, and _numeric functions has been adapted from - the LDL library: - -LDL Copyright (c) 2005 by Timothy A. Davis. All Rights Reserved. - -LDL License: - - Your use or distribution of LDL or any modified version of - LDL implies that you agree to this License. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 - USA - - Permission is hereby granted to use or copy this program under the - terms of the GNU LGPL, provided that the Copyright, this License, - and the Availability of the original version is retained on all copies. - User documentation of any code that uses this code or any modified - version of this code must cite the Copyright, this License, the - Availability note, and "Used by permission." Permission to modify - the code and to distribute modified code is granted, provided the - Copyright, this License, and the Availability note are retained, - and a notice that the code was modified is included. - */ - -#ifndef EIGEN_SPARSELDLT_LEGACY_H -#define EIGEN_SPARSELDLT_LEGACY_H - -/** \ingroup Sparse_Module - * - * \class SparseLDLT - * - * \brief LDLT Cholesky decomposition of a sparse matrix and associated features - * - * \param MatrixType the type of the matrix of which we are computing the LDLT Cholesky decomposition - * - * \warning the upper triangular part has to be specified. The rest of the matrix is not used. The input matrix must be column major. - * - * \sa class LDLT, class LDLT - */ -template -class SparseLDLT -{ - protected: - typedef typename _MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - typedef Matrix VectorType; - - enum { - SupernodalFactorIsDirty = 0x10000, - MatrixLIsDirty = 0x20000 - }; - - public: - typedef SparseMatrix CholMatrixType; - typedef _MatrixType MatrixType; - typedef typename MatrixType::Index Index; - - - /** Creates a dummy LDLT factorization object with flags \a flags. */ - SparseLDLT(int flags = 0) - : m_flags(flags), m_status(0) - { - eigen_assert((MatrixType::Flags&RowMajorBit)==0); - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - } - - /** Creates a LDLT object and compute the respective factorization of \a matrix using - * flags \a flags. */ - SparseLDLT(const MatrixType& matrix, int flags = 0) - : m_matrix(matrix.rows(), matrix.cols()), m_flags(flags), m_status(0) - { - eigen_assert((MatrixType::Flags&RowMajorBit)==0); - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - compute(matrix); - } - - /** Sets the relative threshold value used to prune zero coefficients during the decomposition. - * - * Setting a value greater than zero speeds up computation, and yields to an imcomplete - * factorization with fewer non zero coefficients. Such approximate factors are especially - * useful to initialize an iterative solver. - * - * \warning if precision is greater that zero, the LDLT factorization is not guaranteed to succeed - * even if the matrix is positive definite. - * - * Note that the exact meaning of this parameter might depends on the actual - * backend. Moreover, not all backends support this feature. - * - * \sa precision() */ - void setPrecision(RealScalar v) { m_precision = v; } - - /** \returns the current precision. - * - * \sa setPrecision() */ - RealScalar precision() const { return m_precision; } - - /** Sets the flags. Possible values are: - * - CompleteFactorization - * - IncompleteFactorization - * - MemoryEfficient (hint to use the memory most efficient method offered by the backend) - * - SupernodalMultifrontal (implies a complete factorization if supported by the backend, - * overloads the MemoryEfficient flags) - * - SupernodalLeftLooking (implies a complete factorization if supported by the backend, - * overloads the MemoryEfficient flags) - * - * \sa flags() */ - void settags(int f) { m_flags = f; } - /** \returns the current flags */ - int flags() const { return m_flags; } - - /** Computes/re-computes the LDLT factorization */ - void compute(const MatrixType& matrix); - - /** Perform a symbolic factorization */ - void _symbolic(const MatrixType& matrix); - /** Perform the actual factorization using the previously - * computed symbolic factorization */ - bool _numeric(const MatrixType& matrix); - - /** \returns the lower triangular matrix L */ - inline const CholMatrixType& matrixL(void) const { return m_matrix; } - - /** \returns the coefficients of the diagonal matrix D */ - inline VectorType vectorD(void) const { return m_diag; } - - template - bool solveInPlace(MatrixBase &b) const; - - template - inline const internal::solve_retval, Rhs> - solve(const MatrixBase& b) const - { - eigen_assert(true && "SparseLDLT is not initialized."); - return internal::solve_retval, Rhs>(*this, b.derived()); - } - - inline Index cols() const { return m_matrix.cols(); } - inline Index rows() const { return m_matrix.rows(); } - - inline const VectorType& diag() const { return m_diag; } - - /** \returns true if the factorization succeeded */ - inline bool succeeded(void) const { return m_succeeded; } - - protected: - CholMatrixType m_matrix; - VectorType m_diag; - VectorXi m_parent; // elimination tree - VectorXi m_nonZerosPerCol; -// VectorXi m_w; // workspace - PermutationMatrix m_P; - PermutationMatrix m_Pinv; - RealScalar m_precision; - int m_flags; - mutable int m_status; - bool m_succeeded; -}; - -namespace internal { - -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SparseLDLT<_MatrixType> SpLDLTDecType; - EIGEN_MAKE_SOLVE_HELPERS(SpLDLTDecType,Rhs) - - template void evalTo(Dest& dst) const - { - //Index size = dec().matrixL().rows(); - eigen_assert(dec().matrixL().rows()==rhs().rows()); - - Rhs b(rhs().rows(), rhs().cols()); - b = rhs(); - - if (dec().matrixL().nonZeros()>0) // otherwise L==I - dec().matrixL().template triangularView().solveInPlace(b); - - b = b.cwiseQuotient(dec().diag()); - if (dec().matrixL().nonZeros()>0) // otherwise L==I - dec().matrixL().adjoint().template triangularView().solveInPlace(b); - - dst = b; - - } - -}; - -} // end namespace internal - -/** Computes / recomputes the LDLT decomposition of matrix \a a - * using the default algorithm. - */ -template -void SparseLDLT<_MatrixType,Backend>::compute(const _MatrixType& a) -{ - _symbolic(a); - m_succeeded = _numeric(a); -} - -template -void SparseLDLT<_MatrixType,Backend>::_symbolic(const _MatrixType& a) -{ - assert(a.rows()==a.cols()); - const Index size = a.rows(); - m_matrix.resize(size, size); - m_parent.resize(size); - m_nonZerosPerCol.resize(size); - - ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); - - const Index* Ap = a._outerIndexPtr(); - const Index* Ai = a._innerIndexPtr(); - Index* Lp = m_matrix._outerIndexPtr(); - - const Index* P = 0; - Index* Pinv = 0; - - if(P) - { - m_P.indices() = VectorXi::Map(P,size); - m_Pinv = m_P.inverse(); - Pinv = m_Pinv.indices().data(); - } - else - { - m_P.resize(0); - m_Pinv.resize(0); - } - - for (Index k = 0; k < size; ++k) - { - /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */ - m_parent[k] = -1; /* parent of k is not yet known */ - tags[k] = k; /* mark node k as visited */ - m_nonZerosPerCol[k] = 0; /* count of nonzeros in column k of L */ - Index kk = P ? P[k] : k; /* kth original, or permuted, column */ - Index p2 = Ap[kk+1]; - for (Index p = Ap[kk]; p < p2; ++p) - { - /* A (i,k) is nonzero (original or permuted A) */ - Index i = Pinv ? Pinv[Ai[p]] : Ai[p]; - if (i < k) - { - /* follow path from i to root of etree, stop at flagged node */ - for (; tags[i] != k; i = m_parent[i]) - { - /* find parent of i if not yet determined */ - if (m_parent[i] == -1) - m_parent[i] = k; - ++m_nonZerosPerCol[i]; /* L (k,i) is nonzero */ - tags[i] = k; /* mark i as visited */ - } - } - } - } - /* construct Lp index array from m_nonZerosPerCol column counts */ - Lp[0] = 0; - for (Index k = 0; k < size; ++k) - Lp[k+1] = Lp[k] + m_nonZerosPerCol[k]; - - m_matrix.resizeNonZeros(Lp[size]); -} - -template -bool SparseLDLT<_MatrixType,Backend>::_numeric(const _MatrixType& a) -{ - assert(a.rows()==a.cols()); - const Index size = a.rows(); - assert(m_parent.size()==size); - assert(m_nonZerosPerCol.size()==size); - - const Index* Ap = a._outerIndexPtr(); - const Index* Ai = a._innerIndexPtr(); - const Scalar* Ax = a._valuePtr(); - const Index* Lp = m_matrix._outerIndexPtr(); - Index* Li = m_matrix._innerIndexPtr(); - Scalar* Lx = m_matrix._valuePtr(); - m_diag.resize(size); - - ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0); - ei_declare_aligned_stack_constructed_variable(Index, pattern, size, 0); - ei_declare_aligned_stack_constructed_variable(Index, tags, size, 0); - - Index* P = 0; - Index* Pinv = 0; - - if(m_P.size()==size) - { - P = m_P.indices().data(); - Pinv = m_Pinv.indices().data(); - } - - bool ok = true; - - for (Index k = 0; k < size; ++k) - { - /* compute nonzero pattern of kth row of L, in topological order */ - y[k] = 0.0; /* Y(0:k) is now all zero */ - Index top = size; /* stack for pattern is empty */ - tags[k] = k; /* mark node k as visited */ - m_nonZerosPerCol[k] = 0; /* count of nonzeros in column k of L */ - Index kk = (P) ? (P[k]) : (k); /* kth original, or permuted, column */ - Index p2 = Ap[kk+1]; - for (Index p = Ap[kk]; p < p2; ++p) - { - Index i = Pinv ? Pinv[Ai[p]] : Ai[p]; /* get A(i,k) */ - if (i <= k) - { - y[i] += internal::conj(Ax[p]); /* scatter A(i,k) into Y (sum duplicates) */ - Index len; - for (len = 0; tags[i] != k; i = m_parent[i]) - { - pattern[len++] = i; /* L(k,i) is nonzero */ - tags[i] = k; /* mark i as visited */ - } - while (len > 0) - pattern[--top] = pattern[--len]; - } - } - - /* compute numerical values kth row of L (a sparse triangular solve) */ - m_diag[k] = y[k]; /* get D(k,k) and clear Y(k) */ - y[k] = 0.0; - for (; top < size; ++top) - { - Index i = pattern[top]; /* pattern[top:n-1] is pattern of L(:,k) */ - Scalar yi = (y[i]); /* get and clear Y(i) */ - y[i] = 0.0; - Index p2 = Lp[i] + m_nonZerosPerCol[i]; - Index p; - for (p = Lp[i]; p < p2; ++p) - y[Li[p]] -= internal::conj(Lx[p]) * (yi); - Scalar l_ki = yi / m_diag[i]; /* the nonzero entry L(k,i) */ - m_diag[k] -= l_ki * internal::conj(yi); - Li[p] = k; /* store L(k,i) in column form of L */ - Lx[p] = (l_ki); - ++m_nonZerosPerCol[i]; /* increment count of nonzeros in col i */ - } - if (m_diag[k] == 0.0) - { - ok = false; /* failure, D(k,k) is zero */ - break; - } - } - - return ok; /* success, diagonal of D is all nonzero */ -} - -/** Computes b = L^-T D^-1 L^-1 b */ -template -template -bool SparseLDLT<_MatrixType, Backend>::solveInPlace(MatrixBase &b) const -{ - //Index size = m_matrix.rows(); - eigen_assert(m_matrix.rows()==b.rows()); - if (!m_succeeded) - return false; - - if(m_P.size()>0) - b = m_Pinv * b; - - if (m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.template triangularView().solveInPlace(b); - b = b.cwiseQuotient(m_diag); - if (m_matrix.nonZeros()>0) // otherwise L==I - m_matrix.adjoint().template triangularView().solveInPlace(b); - - if(m_P.size()>0) - b = m_P * b; - - return true; -} - -#endif // EIGEN_SPARSELDLT_LEGACY_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLLT.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLLT.h deleted file mode 100644 index ac042217b..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLLT.h +++ /dev/null @@ -1,245 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SPARSELLT_H -#define EIGEN_SPARSELLT_H - -/** \ingroup Sparse_Module - * - * \class SparseLLT - * - * \brief LLT Cholesky decomposition of a sparse matrix and associated features - * - * \param MatrixType the type of the matrix of which we are computing the LLT Cholesky decomposition - * - * \sa class LLT, class LDLT - */ -template -class SparseLLT -{ - protected: - typedef typename _MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - enum { - SupernodalFactorIsDirty = 0x10000, - MatrixLIsDirty = 0x20000 - }; - - public: - typedef SparseMatrix CholMatrixType; - typedef _MatrixType MatrixType; - typedef typename MatrixType::Index Index; - - /** Creates a dummy LLT factorization object with flags \a flags. */ - SparseLLT(int flags = 0) - : m_flags(flags), m_status(0) - { - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - } - - /** Creates a LLT object and compute the respective factorization of \a matrix using - * flags \a flags. */ - SparseLLT(const MatrixType& matrix, int flags = 0) - : m_matrix(matrix.rows(), matrix.cols()), m_flags(flags), m_status(0) - { - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - compute(matrix); - } - - /** Sets the relative threshold value used to prune zero coefficients during the decomposition. - * - * Setting a value greater than zero speeds up computation, and yields to an imcomplete - * factorization with fewer non zero coefficients. Such approximate factors are especially - * useful to initialize an iterative solver. - * - * \warning if precision is greater that zero, the LLT factorization is not guaranteed to succeed - * even if the matrix is positive definite. - * - * Note that the exact meaning of this parameter might depends on the actual - * backend. Moreover, not all backends support this feature. - * - * \sa precision() */ - void setPrecision(RealScalar v) { m_precision = v; } - - /** \returns the current precision. - * - * \sa setPrecision() */ - RealScalar precision() const { return m_precision; } - - /** Sets the flags. Possible values are: - * - CompleteFactorization - * - IncompleteFactorization - * - MemoryEfficient (hint to use the memory most efficient method offered by the backend) - * - SupernodalMultifrontal (implies a complete factorization if supported by the backend, - * overloads the MemoryEfficient flags) - * - SupernodalLeftLooking (implies a complete factorization if supported by the backend, - * overloads the MemoryEfficient flags) - * - * \sa flags() */ - void setFlags(int f) { m_flags = f; } - /** \returns the current flags */ - int flags() const { return m_flags; } - - /** Computes/re-computes the LLT factorization */ - void compute(const MatrixType& matrix); - - /** \returns the lower triangular matrix L */ - inline const CholMatrixType& matrixL(void) const { return m_matrix; } - - template - bool solveInPlace(MatrixBase &b) const; - - template - inline const internal::solve_retval, Rhs> - solve(const MatrixBase& b) const - { - eigen_assert(true && "SparseLLT is not initialized."); - return internal::solve_retval, Rhs>(*this, b.derived()); - } - - inline Index cols() const { return m_matrix.cols(); } - inline Index rows() const { return m_matrix.rows(); } - - /** \returns true if the factorization succeeded */ - inline bool succeeded(void) const { return m_succeeded; } - - protected: - CholMatrixType m_matrix; - RealScalar m_precision; - int m_flags; - mutable int m_status; - bool m_succeeded; -}; - - -namespace internal { - -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SparseLLT<_MatrixType> SpLLTDecType; - EIGEN_MAKE_SOLVE_HELPERS(SpLLTDecType,Rhs) - - template void evalTo(Dest& dst) const - { - const Index size = dec().matrixL().rows(); - eigen_assert(size==rhs().rows()); - - Rhs b(rhs().rows(), rhs().cols()); - b = rhs(); - - dec().matrixL().template triangularView().solveInPlace(b); - dec().matrixL().adjoint().template triangularView().solveInPlace(b); - - dst = b; - - } - -}; - -} // end namespace internal - - -/** Computes / recomputes the LLT decomposition of matrix \a a - * using the default algorithm. - */ -template -void SparseLLT<_MatrixType,Backend>::compute(const _MatrixType& a) -{ - assert(a.rows()==a.cols()); - const Index size = a.rows(); - m_matrix.resize(size, size); - - // allocate a temporary vector for accumulations - AmbiVector tempVector(size); - RealScalar density = a.nonZeros()/RealScalar(size*size); - - // TODO estimate the number of non zeros - m_matrix.setZero(); - m_matrix.reserve(a.nonZeros()*2); - for (Index j = 0; j < size; ++j) - { - Scalar x = internal::real(a.coeff(j,j)); - - // TODO better estimate of the density ! - tempVector.init(density>0.001? IsDense : IsSparse); - tempVector.setBounds(j+1,size); - tempVector.setZero(); - // init with current matrix a - { - typename _MatrixType::InnerIterator it(a,j); - eigen_assert(it.index()==j && - "matrix must has non zero diagonal entries and only the lower triangular part must be stored"); - ++it; // skip diagonal element - for (; it; ++it) - tempVector.coeffRef(it.index()) = it.value(); - } - for (Index k=0; k::Iterator it(tempVector, m_precision*rx); it; ++it) - { - // FIXME use insertBack - m_matrix.insert(it.index(), j) = it.value() * y; - } - } - m_matrix.finalize(); -} - -/** Computes b = L^-T L^-1 b */ -template -template -bool SparseLLT<_MatrixType, Backend>::solveInPlace(MatrixBase &b) const -{ - const Index size = m_matrix.rows(); - eigen_assert(size==b.rows()); - - m_matrix.template triangularView().solveInPlace(b); - m_matrix.adjoint().template triangularView().solveInPlace(b); - - return true; -} - -#endif // EIGEN_SPARSELLT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLU.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLU.h deleted file mode 100644 index 3d10dbbee..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SparseLU.h +++ /dev/null @@ -1,163 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SPARSELU_H -#define EIGEN_SPARSELU_H - -enum { - SvNoTrans = 0, - SvTranspose = 1, - SvAdjoint = 2 -}; - -/** \ingroup Sparse_Module - * - * \class SparseLU - * - * \brief LU decomposition of a sparse matrix and associated features - * - * \param _MatrixType the type of the matrix of which we are computing the LU factorization - * - * \sa class FullPivLU, class SparseLLT - */ -template -class SparseLU - { - protected: - typedef typename _MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef SparseMatrix LUMatrixType; - - enum { - MatrixLUIsDirty = 0x10000 - }; - - public: - typedef _MatrixType MatrixType; - - /** Creates a dummy LU factorization object with flags \a flags. */ - SparseLU(int flags = 0) - : m_flags(flags), m_status(0) - { - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - } - - /** Creates a LU object and compute the respective factorization of \a matrix using - * flags \a flags. */ - SparseLU(const _MatrixType& matrix, int flags = 0) - : /*m_matrix(matrix.rows(), matrix.cols()),*/ m_flags(flags), m_status(0) - { - m_precision = RealScalar(0.1) * Eigen::NumTraits::dummy_precision(); - compute(matrix); - } - - /** Sets the relative threshold value used to prune zero coefficients during the decomposition. - * - * Setting a value greater than zero speeds up computation, and yields to an imcomplete - * factorization with fewer non zero coefficients. Such approximate factors are especially - * useful to initialize an iterative solver. - * - * Note that the exact meaning of this parameter might depends on the actual - * backend. Moreover, not all backends support this feature. - * - * \sa precision() */ - void setPrecision(RealScalar v) { m_precision = v; } - - /** \returns the current precision. - * - * \sa setPrecision() */ - RealScalar precision() const { return m_precision; } - - /** Sets the flags. Possible values are: - * - CompleteFactorization - * - IncompleteFactorization - * - MemoryEfficient - * - one of the ordering methods - * - etc... - * - * \sa flags() */ - void setFlags(int f) { m_flags = f; } - /** \returns the current flags */ - int flags() const { return m_flags; } - - void setOrderingMethod(int m) - { - eigen_assert( (m&~OrderingMask) == 0 && m!=0 && "invalid ordering method"); - m_flags = m_flags&~OrderingMask | m&OrderingMask; - } - - int orderingMethod() const - { - return m_flags&OrderingMask; - } - - /** Computes/re-computes the LU factorization */ - void compute(const _MatrixType& matrix); - - /** \returns the lower triangular matrix L */ - //inline const _MatrixType& matrixL() const { return m_matrixL; } - - /** \returns the upper triangular matrix U */ - //inline const _MatrixType& matrixU() const { return m_matrixU; } - - template - bool solve(const MatrixBase &b, MatrixBase* x, - const int transposed = SvNoTrans) const; - - /** \returns true if the factorization succeeded */ - inline bool succeeded(void) const { return m_succeeded; } - - protected: - RealScalar m_precision; - int m_flags; - mutable int m_status; - bool m_succeeded; -}; - -/** Computes / recomputes the LU decomposition of matrix \a a - * using the default algorithm. - */ -template -void SparseLU<_MatrixType,Backend>::compute(const _MatrixType& ) -{ - eigen_assert(false && "not implemented yet"); -} - -/** Computes *x = U^-1 L^-1 b - * - * If \a transpose is set to SvTranspose or SvAdjoint, the solution - * of the transposed/adjoint system is computed instead. - * - * Not all backends implement the solution of the transposed or - * adjoint system. - */ -template -template -bool SparseLU<_MatrixType,Backend>::solve(const MatrixBase &, MatrixBase* , const int ) const -{ - eigen_assert(false && "not implemented yet"); - return false; -} - -#endif // EIGEN_SPARSELU_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SuperLUSupport.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SuperLUSupport.h deleted file mode 100644 index bb7312190..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/SuperLUSupport.h +++ /dev/null @@ -1,667 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2009 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_SUPERLUSUPPORT_H -#define EIGEN_SUPERLUSUPPORT_H - -#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE) \ - extern "C" { \ - typedef struct { FLOATTYPE for_lu; FLOATTYPE total_needed; int expansions; } PREFIX##mem_usage_t; \ - extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *, \ - char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *, \ - void *, int, SuperMatrix *, SuperMatrix *, \ - FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, \ - PREFIX##mem_usage_t *, SuperLUStat_t *, int *); \ - } \ - inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A, \ - int *perm_c, int *perm_r, int *etree, char *equed, \ - FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L, \ - SuperMatrix *U, void *work, int lwork, \ - SuperMatrix *B, SuperMatrix *X, \ - FLOATTYPE *recip_pivot_growth, \ - FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr, \ - SuperLUStat_t *stats, int *info, KEYTYPE) { \ - PREFIX##mem_usage_t mem_usage; \ - PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L, \ - U, work, lwork, B, X, recip_pivot_growth, rcond, \ - ferr, berr, &mem_usage, stats, info); \ - return mem_usage.for_lu; /* bytes used by the factor storage */ \ - } - -DECL_GSSVX(s,float,float) -DECL_GSSVX(c,float,std::complex) -DECL_GSSVX(d,double,double) -DECL_GSSVX(z,double,std::complex) - -#ifdef MILU_ALPHA -#define EIGEN_SUPERLU_HAS_ILU -#endif - -#ifdef EIGEN_SUPERLU_HAS_ILU - -// similarly for the incomplete factorization using gsisx -#define DECL_GSISX(PREFIX,FLOATTYPE,KEYTYPE) \ - extern "C" { \ - extern void PREFIX##gsisx(superlu_options_t *, SuperMatrix *, int *, int *, int *, \ - char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *, \ - void *, int, SuperMatrix *, SuperMatrix *, FLOATTYPE *, FLOATTYPE *, \ - PREFIX##mem_usage_t *, SuperLUStat_t *, int *); \ - } \ - inline float SuperLU_gsisx(superlu_options_t *options, SuperMatrix *A, \ - int *perm_c, int *perm_r, int *etree, char *equed, \ - FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L, \ - SuperMatrix *U, void *work, int lwork, \ - SuperMatrix *B, SuperMatrix *X, \ - FLOATTYPE *recip_pivot_growth, \ - FLOATTYPE *rcond, \ - SuperLUStat_t *stats, int *info, KEYTYPE) { \ - PREFIX##mem_usage_t mem_usage; \ - PREFIX##gsisx(options, A, perm_c, perm_r, etree, equed, R, C, L, \ - U, work, lwork, B, X, recip_pivot_growth, rcond, \ - &mem_usage, stats, info); \ - return mem_usage.for_lu; /* bytes used by the factor storage */ \ - } - -DECL_GSISX(s,float,float) -DECL_GSISX(c,float,std::complex) -DECL_GSISX(d,double,double) -DECL_GSISX(z,double,std::complex) - -#endif - -template -struct SluMatrixMapHelper; - -/** \internal - * - * A wrapper class for SuperLU matrices. It supports only compressed sparse matrices - * and dense matrices. Supernodal and other fancy format are not supported by this wrapper. - * - * This wrapper class mainly aims to avoids the need of dynamic allocation of the storage structure. - */ -struct SluMatrix : SuperMatrix -{ - SluMatrix() - { - Store = &storage; - } - - SluMatrix(const SluMatrix& other) - : SuperMatrix(other) - { - Store = &storage; - storage = other.storage; - } - - SluMatrix& operator=(const SluMatrix& other) - { - SuperMatrix::operator=(static_cast(other)); - Store = &storage; - storage = other.storage; - return *this; - } - - struct - { - union {int nnz;int lda;}; - void *values; - int *innerInd; - int *outerInd; - } storage; - - void setStorageType(Stype_t t) - { - Stype = t; - if (t==SLU_NC || t==SLU_NR || t==SLU_DN) - Store = &storage; - else - { - eigen_assert(false && "storage type not supported"); - Store = 0; - } - } - - template - void setScalarType() - { - if (internal::is_same::value) - Dtype = SLU_S; - else if (internal::is_same::value) - Dtype = SLU_D; - else if (internal::is_same >::value) - Dtype = SLU_C; - else if (internal::is_same >::value) - Dtype = SLU_Z; - else - { - eigen_assert(false && "Scalar type not supported by SuperLU"); - } - } - - template - static SluMatrix Map(Matrix& mat) - { - typedef Matrix MatrixType; - eigen_assert( ((Options&RowMajor)!=RowMajor) && "row-major dense matrices is not supported by SuperLU"); - SluMatrix res; - res.setStorageType(SLU_DN); - res.setScalarType(); - res.Mtype = SLU_GE; - - res.nrow = mat.rows(); - res.ncol = mat.cols(); - - res.storage.lda = MatrixType::IsVectorAtCompileTime ? mat.size() : mat.outerStride(); - res.storage.values = mat.data(); - return res; - } - - template - static SluMatrix Map(SparseMatrixBase& mat) - { - SluMatrix res; - if ((MatrixType::Flags&RowMajorBit)==RowMajorBit) - { - res.setStorageType(SLU_NR); - res.nrow = mat.cols(); - res.ncol = mat.rows(); - } - else - { - res.setStorageType(SLU_NC); - res.nrow = mat.rows(); - res.ncol = mat.cols(); - } - - res.Mtype = SLU_GE; - - res.storage.nnz = mat.nonZeros(); - res.storage.values = mat.derived()._valuePtr(); - res.storage.innerInd = mat.derived()._innerIndexPtr(); - res.storage.outerInd = mat.derived()._outerIndexPtr(); - - res.setScalarType(); - - // FIXME the following is not very accurate - if (MatrixType::Flags & Upper) - res.Mtype = SLU_TRU; - if (MatrixType::Flags & Lower) - res.Mtype = SLU_TRL; - if (MatrixType::Flags & SelfAdjoint) - eigen_assert(false && "SelfAdjoint matrix shape not supported by SuperLU"); - return res; - } -}; - -template -struct SluMatrixMapHelper > -{ - typedef Matrix MatrixType; - static void run(MatrixType& mat, SluMatrix& res) - { - eigen_assert( ((Options&RowMajor)!=RowMajor) && "row-major dense matrices is not supported by SuperLU"); - res.setStorageType(SLU_DN); - res.setScalarType(); - res.Mtype = SLU_GE; - - res.nrow = mat.rows(); - res.ncol = mat.cols(); - - res.storage.lda = mat.outerStride(); - res.storage.values = mat.data(); - } -}; - -template -struct SluMatrixMapHelper > -{ - typedef Derived MatrixType; - static void run(MatrixType& mat, SluMatrix& res) - { - if ((MatrixType::Flags&RowMajorBit)==RowMajorBit) - { - res.setStorageType(SLU_NR); - res.nrow = mat.cols(); - res.ncol = mat.rows(); - } - else - { - res.setStorageType(SLU_NC); - res.nrow = mat.rows(); - res.ncol = mat.cols(); - } - - res.Mtype = SLU_GE; - - res.storage.nnz = mat.nonZeros(); - res.storage.values = mat._valuePtr(); - res.storage.innerInd = mat._innerIndexPtr(); - res.storage.outerInd = mat._outerIndexPtr(); - - res.setScalarType(); - - // FIXME the following is not very accurate - if (MatrixType::Flags & Upper) - res.Mtype = SLU_TRU; - if (MatrixType::Flags & Lower) - res.Mtype = SLU_TRL; - if (MatrixType::Flags & SelfAdjoint) - eigen_assert(false && "SelfAdjoint matrix shape not supported by SuperLU"); - } -}; - -namespace internal { - -template -SluMatrix asSluMatrix(MatrixType& mat) -{ - return SluMatrix::Map(mat); -} - -/** View a Super LU matrix as an Eigen expression */ -template -MappedSparseMatrix map_superlu(SluMatrix& sluMat) -{ - eigen_assert((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR - || (Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC); - - Index outerSize = (Flags&RowMajor)==RowMajor ? sluMat.ncol : sluMat.nrow; - - return MappedSparseMatrix( - sluMat.nrow, sluMat.ncol, sluMat.storage.outerInd[outerSize], - sluMat.storage.outerInd, sluMat.storage.innerInd, reinterpret_cast(sluMat.storage.values) ); -} - -} // end namespace internal - -template -class SparseLU : public SparseLU -{ - protected: - typedef SparseLU Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; - typedef Matrix Vector; - typedef Matrix IntRowVectorType; - typedef Matrix IntColVectorType; - typedef SparseMatrix LMatrixType; - typedef SparseMatrix UMatrixType; - using Base::m_flags; - using Base::m_status; - - public: - - SparseLU(int flags = NaturalOrdering) - : Base(flags) - { - } - - SparseLU(const MatrixType& matrix, int flags = NaturalOrdering) - : Base(flags) - { - compute(matrix); - } - - ~SparseLU() - { - Destroy_SuperNode_Matrix(&m_sluL); - Destroy_CompCol_Matrix(&m_sluU); - } - - inline const LMatrixType& matrixL() const - { - if (m_extractedDataAreDirty) extractData(); - return m_l; - } - - inline const UMatrixType& matrixU() const - { - if (m_extractedDataAreDirty) extractData(); - return m_u; - } - - inline const IntColVectorType& permutationP() const - { - if (m_extractedDataAreDirty) extractData(); - return m_p; - } - - inline const IntRowVectorType& permutationQ() const - { - if (m_extractedDataAreDirty) extractData(); - return m_q; - } - - Scalar determinant() const; - - template - bool solve(const MatrixBase &b, MatrixBase* x, const int transposed = SvNoTrans) const; - - void compute(const MatrixType& matrix); - - protected: - - void extractData() const; - - protected: - // cached data to reduce reallocation, etc. - mutable LMatrixType m_l; - mutable UMatrixType m_u; - mutable IntColVectorType m_p; - mutable IntRowVectorType m_q; - - mutable SparseMatrix m_matrix; - mutable SluMatrix m_sluA; - mutable SuperMatrix m_sluL, m_sluU; - mutable SluMatrix m_sluB, m_sluX; - mutable SuperLUStat_t m_sluStat; - mutable superlu_options_t m_sluOptions; - mutable std::vector m_sluEtree; - mutable std::vector m_sluRscale, m_sluCscale; - mutable std::vector m_sluFerr, m_sluBerr; - mutable char m_sluEqued; - mutable bool m_extractedDataAreDirty; -}; - -template -void SparseLU::compute(const MatrixType& a) -{ - const int size = a.rows(); - m_matrix = a; - - set_default_options(&m_sluOptions); - m_sluOptions.ColPerm = NATURAL; - m_sluOptions.PrintStat = NO; - m_sluOptions.ConditionNumber = NO; - m_sluOptions.Trans = NOTRANS; - // m_sluOptions.Equil = NO; - - switch (Base::orderingMethod()) - { - case NaturalOrdering : m_sluOptions.ColPerm = NATURAL; break; - case MinimumDegree_AT_PLUS_A : m_sluOptions.ColPerm = MMD_AT_PLUS_A; break; - case MinimumDegree_ATA : m_sluOptions.ColPerm = MMD_ATA; break; - case ColApproxMinimumDegree : m_sluOptions.ColPerm = COLAMD; break; - default: - //std::cerr << "Eigen: ordering method \"" << Base::orderingMethod() << "\" not supported by the SuperLU backend\n"; - m_sluOptions.ColPerm = NATURAL; - }; - - m_sluA = internal::asSluMatrix(m_matrix); - memset(&m_sluL,0,sizeof m_sluL); - memset(&m_sluU,0,sizeof m_sluU); - //m_sluEqued = 'B'; - int info = 0; - - m_p.resize(size); - m_q.resize(size); - m_sluRscale.resize(size); - m_sluCscale.resize(size); - m_sluEtree.resize(size); - - RealScalar recip_pivot_gross, rcond; - RealScalar ferr, berr; - - // set empty B and X - m_sluB.setStorageType(SLU_DN); - m_sluB.setScalarType(); - m_sluB.Mtype = SLU_GE; - m_sluB.storage.values = 0; - m_sluB.nrow = m_sluB.ncol = 0; - m_sluB.storage.lda = size; - m_sluX = m_sluB; - - StatInit(&m_sluStat); - if (m_flags&IncompleteFactorization) - { - #ifdef EIGEN_SUPERLU_HAS_ILU - ilu_set_default_options(&m_sluOptions); - - // no attempt to preserve column sum - m_sluOptions.ILU_MILU = SILU; - - // only basic ILU(k) support -- no direct control over memory consumption - // better to use ILU_DropRule = DROP_BASIC | DROP_AREA - // and set ILU_FillFactor to max memory growth - m_sluOptions.ILU_DropRule = DROP_BASIC; - m_sluOptions.ILU_DropTol = Base::m_precision; - - SuperLU_gsisx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0], - &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0], - &m_sluL, &m_sluU, - NULL, 0, - &m_sluB, &m_sluX, - &recip_pivot_gross, &rcond, - &m_sluStat, &info, Scalar()); - #else - //std::cerr << "Incomplete factorization is only available in SuperLU v4\n"; - Base::m_succeeded = false; - return; - #endif - } - else - { - SuperLU_gssvx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0], - &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0], - &m_sluL, &m_sluU, - NULL, 0, - &m_sluB, &m_sluX, - &recip_pivot_gross, &rcond, - &ferr, &berr, - &m_sluStat, &info, Scalar()); - } - StatFree(&m_sluStat); - - m_extractedDataAreDirty = true; - - // FIXME how to better check for errors ??? - Base::m_succeeded = (info == 0); -} - -template -template -bool SparseLU::solve(const MatrixBase &b, - MatrixBase *x, const int transposed) const -{ - const int size = m_matrix.rows(); - const int rhsCols = b.cols(); - eigen_assert(size==b.rows()); - - switch (transposed) { - case SvNoTrans : m_sluOptions.Trans = NOTRANS; break; - case SvTranspose : m_sluOptions.Trans = TRANS; break; - case SvAdjoint : m_sluOptions.Trans = CONJ; break; - default: - //std::cerr << "Eigen: transposition option \"" << transposed << "\" not supported by the SuperLU backend\n"; - m_sluOptions.Trans = NOTRANS; - } - - m_sluOptions.Fact = FACTORED; - m_sluOptions.IterRefine = NOREFINE; - - m_sluFerr.resize(rhsCols); - m_sluBerr.resize(rhsCols); - m_sluB = SluMatrix::Map(b.const_cast_derived()); - m_sluX = SluMatrix::Map(x->derived()); - - StatInit(&m_sluStat); - int info = 0; - RealScalar recip_pivot_gross, rcond; - - if (m_flags&IncompleteFactorization) - { - #ifdef EIGEN_SUPERLU_HAS_ILU - SuperLU_gsisx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0], - &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0], - &m_sluL, &m_sluU, - NULL, 0, - &m_sluB, &m_sluX, - &recip_pivot_gross, &rcond, - &m_sluStat, &info, Scalar()); - #else - //std::cerr << "Incomplete factorization is only available in SuperLU v4\n"; - return false; - #endif - } - else - { - SuperLU_gssvx( - &m_sluOptions, &m_sluA, - m_q.data(), m_p.data(), - &m_sluEtree[0], &m_sluEqued, - &m_sluRscale[0], &m_sluCscale[0], - &m_sluL, &m_sluU, - NULL, 0, - &m_sluB, &m_sluX, - &recip_pivot_gross, &rcond, - &m_sluFerr[0], &m_sluBerr[0], - &m_sluStat, &info, Scalar()); - } - StatFree(&m_sluStat); - - // reset to previous state - m_sluOptions.Trans = NOTRANS; - return info==0; -} - -// -// the code of this extractData() function has been adapted from the SuperLU's Matlab support code, -// -// Copyright (c) 1994 by Xerox Corporation. All rights reserved. -// -// THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY -// EXPRESSED OR IMPLIED. ANY USE IS AT YOUR OWN RISK. -// -template -void SparseLU::extractData() const -{ - if (m_extractedDataAreDirty) - { - int upper; - int fsupc, istart, nsupr; - int lastl = 0, lastu = 0; - SCformat *Lstore = static_cast(m_sluL.Store); - NCformat *Ustore = static_cast(m_sluU.Store); - Scalar *SNptr; - - const int size = m_matrix.rows(); - m_l.resize(size,size); - m_l.resizeNonZeros(Lstore->nnz); - m_u.resize(size,size); - m_u.resizeNonZeros(Ustore->nnz); - - int* Lcol = m_l._outerIndexPtr(); - int* Lrow = m_l._innerIndexPtr(); - Scalar* Lval = m_l._valuePtr(); - - int* Ucol = m_u._outerIndexPtr(); - int* Urow = m_u._innerIndexPtr(); - Scalar* Uval = m_u._valuePtr(); - - Ucol[0] = 0; - Ucol[0] = 0; - - /* for each supernode */ - for (int k = 0; k <= Lstore->nsuper; ++k) - { - fsupc = L_FST_SUPC(k); - istart = L_SUB_START(fsupc); - nsupr = L_SUB_START(fsupc+1) - istart; - upper = 1; - - /* for each column in the supernode */ - for (int j = fsupc; j < L_FST_SUPC(k+1); ++j) - { - SNptr = &((Scalar*)Lstore->nzval)[L_NZ_START(j)]; - - /* Extract U */ - for (int i = U_NZ_START(j); i < U_NZ_START(j+1); ++i) - { - Uval[lastu] = ((Scalar*)Ustore->nzval)[i]; - /* Matlab doesn't like explicit zero. */ - if (Uval[lastu] != 0.0) - Urow[lastu++] = U_SUB(i); - } - for (int i = 0; i < upper; ++i) - { - /* upper triangle in the supernode */ - Uval[lastu] = SNptr[i]; - /* Matlab doesn't like explicit zero. */ - if (Uval[lastu] != 0.0) - Urow[lastu++] = L_SUB(istart+i); - } - Ucol[j+1] = lastu; - - /* Extract L */ - Lval[lastl] = 1.0; /* unit diagonal */ - Lrow[lastl++] = L_SUB(istart + upper - 1); - for (int i = upper; i < nsupr; ++i) - { - Lval[lastl] = SNptr[i]; - /* Matlab doesn't like explicit zero. */ - if (Lval[lastl] != 0.0) - Lrow[lastl++] = L_SUB(istart+i); - } - Lcol[j+1] = lastl; - - ++upper; - } /* for j ... */ - - } /* for k ... */ - - // squeeze the matrices : - m_l.resizeNonZeros(lastl); - m_u.resizeNonZeros(lastu); - - m_extractedDataAreDirty = false; - } -} - -template -typename SparseLU::Scalar SparseLU::determinant() const -{ - assert((!NumTraits::IsComplex) && "This function is not implemented for complex yet"); - if (m_extractedDataAreDirty) - extractData(); - - // TODO this code could be moved to the default/base backend - // FIXME perhaps we have to take into account the scale factors m_sluRscale and m_sluCscale ??? - Scalar det = Scalar(1); - for (int j=0; j 0) - { - int lastId = m_u._outerIndexPtr()[j+1]-1; - eigen_assert(m_u._innerIndexPtr()[lastId]<=j); - if (m_u._innerIndexPtr()[lastId]==j) - { - det *= m_u._valuePtr()[lastId]; - } - } -// std::cout << m_sluRscale[j] << " " << m_sluCscale[j] << " \n"; - } - return det; -} - -#endif // EIGEN_SUPERLUSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/UmfPackSupport.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/UmfPackSupport.h deleted file mode 100644 index beb18f6cd..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/UmfPackSupport.h +++ /dev/null @@ -1,350 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2009 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#ifndef EIGEN_UMFPACKSUPPORT_H -#define EIGEN_UMFPACKSUPPORT_H - -/* TODO extract L, extract U, compute det, etc... */ - -// generic double/complex wrapper functions: - -inline void umfpack_free_numeric(void **Numeric, double) -{ umfpack_di_free_numeric(Numeric); } - -inline void umfpack_free_numeric(void **Numeric, std::complex) -{ umfpack_zi_free_numeric(Numeric); } - -inline void umfpack_free_symbolic(void **Symbolic, double) -{ umfpack_di_free_symbolic(Symbolic); } - -inline void umfpack_free_symbolic(void **Symbolic, std::complex) -{ umfpack_zi_free_symbolic(Symbolic); } - -inline int umfpack_symbolic(int n_row,int n_col, - const int Ap[], const int Ai[], const double Ax[], void **Symbolic, - const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) -{ - return umfpack_di_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info); -} - -inline int umfpack_symbolic(int n_row,int n_col, - const int Ap[], const int Ai[], const std::complex Ax[], void **Symbolic, - const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO]) -{ - return umfpack_zi_symbolic(n_row,n_col,Ap,Ai,&internal::real_ref(Ax[0]),0,Symbolic,Control,Info); -} - -inline int umfpack_numeric( const int Ap[], const int Ai[], const double Ax[], - void *Symbolic, void **Numeric, - const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) -{ - return umfpack_di_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info); -} - -inline int umfpack_numeric( const int Ap[], const int Ai[], const std::complex Ax[], - void *Symbolic, void **Numeric, - const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO]) -{ - return umfpack_zi_numeric(Ap,Ai,&internal::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info); -} - -inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const double Ax[], - double X[], const double B[], void *Numeric, - const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) -{ - return umfpack_di_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info); -} - -inline int umfpack_solve( int sys, const int Ap[], const int Ai[], const std::complex Ax[], - std::complex X[], const std::complex B[], void *Numeric, - const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO]) -{ - return umfpack_zi_solve(sys,Ap,Ai,&internal::real_ref(Ax[0]),0,&internal::real_ref(X[0]),0,&internal::real_ref(B[0]),0,Numeric,Control,Info); -} - -inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double) -{ - return umfpack_di_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); -} - -inline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, std::complex) -{ - return umfpack_zi_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric); -} - -inline int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[], - int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric) -{ - return umfpack_di_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric); -} - -inline int umfpack_get_numeric(int Lp[], int Lj[], std::complex Lx[], int Up[], int Ui[], std::complex Ux[], - int P[], int Q[], std::complex Dx[], int *do_recip, double Rs[], void *Numeric) -{ - double& lx0_real = internal::real_ref(Lx[0]); - double& ux0_real = internal::real_ref(Ux[0]); - double& dx0_real = internal::real_ref(Dx[0]); - return umfpack_zi_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q, - Dx?&dx0_real:0,0,do_recip,Rs,Numeric); -} - -inline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) -{ - return umfpack_di_get_determinant(Mx,Ex,NumericHandle,User_Info); -} - -inline int umfpack_get_determinant(std::complex *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO]) -{ - double& mx_real = internal::real_ref(*Mx); - return umfpack_zi_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info); -} - - -template -class SparseLU<_MatrixType,UmfPack> : public SparseLU<_MatrixType> -{ - protected: - typedef SparseLU<_MatrixType> Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::RealScalar RealScalar; - typedef Matrix Vector; - typedef Matrix IntRowVectorType; - typedef Matrix IntColVectorType; - typedef SparseMatrix LMatrixType; - typedef SparseMatrix UMatrixType; - using Base::m_flags; - using Base::m_status; - - public: - typedef _MatrixType MatrixType; - typedef typename MatrixType::Index Index; - - SparseLU(int flags = NaturalOrdering) - : Base(flags), m_numeric(0) - { - } - - SparseLU(const MatrixType& matrix, int flags = NaturalOrdering) - : Base(flags), m_numeric(0) - { - compute(matrix); - } - - ~SparseLU() - { - if (m_numeric) - umfpack_free_numeric(&m_numeric,Scalar()); - } - - inline const LMatrixType& matrixL() const - { - if (m_extractedDataAreDirty) extractData(); - return m_l; - } - - inline const UMatrixType& matrixU() const - { - if (m_extractedDataAreDirty) extractData(); - return m_u; - } - - inline const IntColVectorType& permutationP() const - { - if (m_extractedDataAreDirty) extractData(); - return m_p; - } - - inline const IntRowVectorType& permutationQ() const - { - if (m_extractedDataAreDirty) extractData(); - return m_q; - } - - Scalar determinant() const; - - template - bool solve(const MatrixBase &b, MatrixBase* x) const; - - template - inline const internal::solve_retval, Rhs> - solve(const MatrixBase& b) const - { - eigen_assert(true && "SparseLU is not initialized."); - return internal::solve_retval, Rhs>(*this, b.derived()); - } - - void compute(const MatrixType& matrix); - - inline Index cols() const { return m_matrixRef->cols(); } - inline Index rows() const { return m_matrixRef->rows(); } - - inline const MatrixType& matrixLU() const - { - //eigen_assert(m_isInitialized && "LU is not initialized."); - return *m_matrixRef; - } - - const void* numeric() const - { - return m_numeric; - } - - protected: - - void extractData() const; - - protected: - // cached data: - void* m_numeric; - const MatrixType* m_matrixRef; - mutable LMatrixType m_l; - mutable UMatrixType m_u; - mutable IntColVectorType m_p; - mutable IntRowVectorType m_q; - mutable bool m_extractedDataAreDirty; -}; - -namespace internal { - -template - struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef SparseLU<_MatrixType, UmfPack> SpLUDecType; - EIGEN_MAKE_SOLVE_HELPERS(SpLUDecType,Rhs) - - template void evalTo(Dest& dst) const - { - const int rhsCols = rhs().cols(); - - eigen_assert((Rhs::Flags&RowMajorBit)==0 && "UmfPack backend does not support non col-major rhs yet"); - eigen_assert((Dest::Flags&RowMajorBit)==0 && "UmfPack backend does not support non col-major result yet"); - - void* numeric = const_cast(dec().numeric()); - - EIGEN_UNUSED int errorCode = 0; - for (int j=0; j -void SparseLU::compute(const MatrixType& a) -{ - typedef typename MatrixType::Index Index; - const Index rows = a.rows(); - const Index cols = a.cols(); - eigen_assert((MatrixType::Flags&RowMajorBit)==0 && "Row major matrices are not supported yet"); - - m_matrixRef = &a; - - if (m_numeric) - umfpack_free_numeric(&m_numeric,Scalar()); - - void* symbolic; - int errorCode = 0; - errorCode = umfpack_symbolic(rows, cols, a._outerIndexPtr(), a._innerIndexPtr(), a._valuePtr(), - &symbolic, 0, 0); - if (errorCode==0) - errorCode = umfpack_numeric(a._outerIndexPtr(), a._innerIndexPtr(), a._valuePtr(), - symbolic, &m_numeric, 0, 0); - - umfpack_free_symbolic(&symbolic,Scalar()); - - m_extractedDataAreDirty = true; - - Base::m_succeeded = (errorCode==0); -} - -template -void SparseLU::extractData() const -{ - if (m_extractedDataAreDirty) - { - // get size of the data - int lnz, unz, rows, cols, nz_udiag; - umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar()); - - // allocate data - m_l.resize(rows,(std::min)(rows,cols)); - m_l.resizeNonZeros(lnz); - - m_u.resize((std::min)(rows,cols),cols); - m_u.resizeNonZeros(unz); - - m_p.resize(rows); - m_q.resize(cols); - - // extract - umfpack_get_numeric(m_l._outerIndexPtr(), m_l._innerIndexPtr(), m_l._valuePtr(), - m_u._outerIndexPtr(), m_u._innerIndexPtr(), m_u._valuePtr(), - m_p.data(), m_q.data(), 0, 0, 0, m_numeric); - - m_extractedDataAreDirty = false; - } -} - -template -typename SparseLU::Scalar SparseLU::determinant() const -{ - Scalar det; - umfpack_get_determinant(&det, 0, m_numeric, 0); - return det; -} - -template -template -bool SparseLU::solve(const MatrixBase &b, MatrixBase *x) const -{ - //const int size = m_matrix.rows(); - const int rhsCols = b.cols(); -// eigen_assert(size==b.rows()); - eigen_assert((BDerived::Flags&RowMajorBit)==0 && "UmfPack backend does not support non col-major rhs yet"); - eigen_assert((XDerived::Flags&RowMajorBit)==0 && "UmfPack backend does not support non col-major result yet"); - - int errorCode; - for (int j=0; j_outerIndexPtr(), m_matrixRef->_innerIndexPtr(), m_matrixRef->_valuePtr(), - &x->col(j).coeffRef(0), &b.const_cast_derived().col(j).coeffRef(0), m_numeric, 0, 0); - if (errorCode!=0) - return false; - } -// errorCode = umfpack_di_solve(UMFPACK_A, -// m_matrixRef._outerIndexPtr(), m_matrixRef._innerIndexPtr(), m_matrixRef._valuePtr(), -// x->derived().data(), b.derived().data(), m_numeric, 0, 0); - - return true; -} - -#endif // EIGEN_UMFPACKSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/CMakeLists.txt new file mode 100644 index 000000000..55c6271e9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/CMakeLists.txt @@ -0,0 +1,6 @@ +FILE(GLOB Eigen_Splines_SRCS "*.h") + +INSTALL(FILES + ${Eigen_Splines_SRCS} + DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/src/Splines COMPONENT Devel + ) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/Spline.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/Spline.h new file mode 100644 index 000000000..4c06453f7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/Spline.h @@ -0,0 +1,479 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 20010-2011 Hauke Heibel +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPLINE_H +#define EIGEN_SPLINE_H + +#include "SplineFwd.h" + +namespace Eigen +{ + /** + * \ingroup Splines_Module + * \class Spline class + * \brief A class representing multi-dimensional spline curves. + * + * The class represents B-splines with non-uniform knot vectors. Each control + * point of the B-spline is associated with a basis function + * \f{align*} + * C(u) & = \sum_{i=0}^{n}N_{i,p}(u)P_i + * \f} + * + * \tparam _Scalar The underlying data type (typically float or double) + * \tparam _Dim The curve dimension (e.g. 2 or 3) + * \tparam _Degree Per default set to Dynamic; could be set to the actual desired + * degree for optimization purposes (would result in stack allocation + * of several temporary variables). + **/ + template + class Spline + { + public: + typedef _Scalar Scalar; /*!< The spline curve's scalar type. */ + enum { Dimension = _Dim /*!< The spline curve's dimension. */ }; + enum { Degree = _Degree /*!< The spline curve's degree. */ }; + + /** \brief The point type the spline is representing. */ + typedef typename SplineTraits::PointType PointType; + + /** \brief The data type used to store knot vectors. */ + typedef typename SplineTraits::KnotVectorType KnotVectorType; + + /** \brief The data type used to store non-zero basis functions. */ + typedef typename SplineTraits::BasisVectorType BasisVectorType; + + /** \brief The data type representing the spline's control points. */ + typedef typename SplineTraits::ControlPointVectorType ControlPointVectorType; + + /** + * \brief Creates a spline from a knot vector and control points. + * \param knots The spline's knot vector. + * \param ctrls The spline's control point vector. + **/ + template + Spline(const OtherVectorType& knots, const OtherArrayType& ctrls) : m_knots(knots), m_ctrls(ctrls) {} + + /** + * \brief Copy constructor for splines. + * \param spline The input spline. + **/ + template + Spline(const Spline& spline) : + m_knots(spline.knots()), m_ctrls(spline.ctrls()) {} + + /** + * \brief Returns the knots of the underlying spline. + **/ + const KnotVectorType& knots() const { return m_knots; } + + /** + * \brief Returns the knots of the underlying spline. + **/ + const ControlPointVectorType& ctrls() const { return m_ctrls; } + + /** + * \brief Returns the spline value at a given site \f$u\f$. + * + * The function returns + * \f{align*} + * C(u) & = \sum_{i=0}^{n}N_{i,p}P_i + * \f} + * + * \param u Parameter \f$u \in [0;1]\f$ at which the spline is evaluated. + * \return The spline value at the given location \f$u\f$. + **/ + PointType operator()(Scalar u) const; + + /** + * \brief Evaluation of spline derivatives of up-to given order. + * + * The function returns + * \f{align*} + * \frac{d^i}{du^i}C(u) & = \sum_{i=0}^{n} \frac{d^i}{du^i} N_{i,p}(u)P_i + * \f} + * for i ranging between 0 and order. + * + * \param u Parameter \f$u \in [0;1]\f$ at which the spline derivative is evaluated. + * \param order The order up to which the derivatives are computed. + **/ + typename SplineTraits::DerivativeType + derivatives(Scalar u, DenseIndex order) const; + + /** + * \copydoc Spline::derivatives + * Using the template version of this function is more efficieent since + * temporary objects are allocated on the stack whenever this is possible. + **/ + template + typename SplineTraits::DerivativeType + derivatives(Scalar u, DenseIndex order = DerivativeOrder) const; + + /** + * \brief Computes the non-zero basis functions at the given site. + * + * Splines have local support and a point from their image is defined + * by exactly \f$p+1\f$ control points \f$P_i\f$ where \f$p\f$ is the + * spline degree. + * + * This function computes the \f$p+1\f$ non-zero basis function values + * for a given parameter value \f$u\f$. It returns + * \f{align*}{ + * N_{i,p}(u), \hdots, N_{i+p+1,p}(u) + * \f} + * + * \param u Parameter \f$u \in [0;1]\f$ at which the non-zero basis functions + * are computed. + **/ + typename SplineTraits::BasisVectorType + basisFunctions(Scalar u) const; + + /** + * \brief Computes the non-zero spline basis function derivatives up to given order. + * + * The function computes + * \f{align*}{ + * \frac{d^i}{du^i} N_{i,p}(u), \hdots, \frac{d^i}{du^i} N_{i+p+1,p}(u) + * \f} + * with i ranging from 0 up to the specified order. + * + * \param u Parameter \f$u \in [0;1]\f$ at which the non-zero basis function + * derivatives are computed. + * \param order The order up to which the basis function derivatives are computes. + **/ + typename SplineTraits::BasisDerivativeType + basisFunctionDerivatives(Scalar u, DenseIndex order) const; + + /** + * \copydoc Spline::basisFunctionDerivatives + * Using the template version of this function is more efficieent since + * temporary objects are allocated on the stack whenever this is possible. + **/ + template + typename SplineTraits::BasisDerivativeType + basisFunctionDerivatives(Scalar u, DenseIndex order = DerivativeOrder) const; + + /** + * \brief Returns the spline degree. + **/ + DenseIndex degree() const; + + /** + * \brief Returns the span within the knot vector in which u is falling. + * \param u The site for which the span is determined. + **/ + DenseIndex span(Scalar u) const; + + /** + * \brief Computes the spang within the provided knot vector in which u is falling. + **/ + static DenseIndex Span(typename SplineTraits::Scalar u, DenseIndex degree, const typename SplineTraits::KnotVectorType& knots); + + /** + * \brief Returns the spline's non-zero basis functions. + * + * The function computes and returns + * \f{align*}{ + * N_{i,p}(u), \hdots, N_{i+p+1,p}(u) + * \f} + * + * \param u The site at which the basis functions are computed. + * \param degree The degree of the underlying spline. + * \param knots The underlying spline's knot vector. + **/ + static BasisVectorType BasisFunctions(Scalar u, DenseIndex degree, const KnotVectorType& knots); + + + private: + KnotVectorType m_knots; /*!< Knot vector. */ + ControlPointVectorType m_ctrls; /*!< Control points. */ + }; + + template + DenseIndex Spline<_Scalar, _Dim, _Degree>::Span( + typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::Scalar u, + DenseIndex degree, + const typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::KnotVectorType& knots) + { + // Piegl & Tiller, "The NURBS Book", A2.1 (p. 68) + if (u <= knots(0)) return degree; + const Scalar* pos = std::upper_bound(knots.data()+degree-1, knots.data()+knots.size()-degree-1, u); + return static_cast( std::distance(knots.data(), pos) - 1 ); + } + + template + typename Spline<_Scalar, _Dim, _Degree>::BasisVectorType + Spline<_Scalar, _Dim, _Degree>::BasisFunctions( + typename Spline<_Scalar, _Dim, _Degree>::Scalar u, + DenseIndex degree, + const typename Spline<_Scalar, _Dim, _Degree>::KnotVectorType& knots) + { + typedef typename Spline<_Scalar, _Dim, _Degree>::BasisVectorType BasisVectorType; + + const DenseIndex p = degree; + const DenseIndex i = Spline::Span(u, degree, knots); + + const KnotVectorType& U = knots; + + BasisVectorType left(p+1); left(0) = Scalar(0); + BasisVectorType right(p+1); right(0) = Scalar(0); + + VectorBlock(left,1,p) = u - VectorBlock(U,i+1-p,p).reverse(); + VectorBlock(right,1,p) = VectorBlock(U,i+1,p) - u; + + BasisVectorType N(1,p+1); + N(0) = Scalar(1); + for (DenseIndex j=1; j<=p; ++j) + { + Scalar saved = Scalar(0); + for (DenseIndex r=0; r + DenseIndex Spline<_Scalar, _Dim, _Degree>::degree() const + { + if (_Degree == Dynamic) + return m_knots.size() - m_ctrls.cols() - 1; + else + return _Degree; + } + + template + DenseIndex Spline<_Scalar, _Dim, _Degree>::span(Scalar u) const + { + return Spline::Span(u, degree(), knots()); + } + + template + typename Spline<_Scalar, _Dim, _Degree>::PointType Spline<_Scalar, _Dim, _Degree>::operator()(Scalar u) const + { + enum { Order = SplineTraits::OrderAtCompileTime }; + + const DenseIndex span = this->span(u); + const DenseIndex p = degree(); + const BasisVectorType basis_funcs = basisFunctions(u); + + const Replicate ctrl_weights(basis_funcs); + const Block ctrl_pts(ctrls(),0,span-p,Dimension,p+1); + return (ctrl_weights * ctrl_pts).rowwise().sum(); + } + + /* --------------------------------------------------------------------------------------------- */ + + template + void derivativesImpl(const SplineType& spline, typename SplineType::Scalar u, DenseIndex order, DerivativeType& der) + { + enum { Dimension = SplineTraits::Dimension }; + enum { Order = SplineTraits::OrderAtCompileTime }; + enum { DerivativeOrder = DerivativeType::ColsAtCompileTime }; + + typedef typename SplineTraits::Scalar Scalar; + + typedef typename SplineTraits::BasisVectorType BasisVectorType; + typedef typename SplineTraits::ControlPointVectorType ControlPointVectorType; + + typedef typename SplineTraits::BasisDerivativeType BasisDerivativeType; + typedef typename BasisDerivativeType::ConstRowXpr BasisDerivativeRowXpr; + + const DenseIndex p = spline.degree(); + const DenseIndex span = spline.span(u); + + const DenseIndex n = (std::min)(p, order); + + der.resize(Dimension,n+1); + + // Retrieve the basis function derivatives up to the desired order... + const BasisDerivativeType basis_func_ders = spline.template basisFunctionDerivatives(u, n+1); + + // ... and perform the linear combinations of the control points. + for (DenseIndex der_order=0; der_order ctrl_weights( basis_func_ders.row(der_order) ); + const Block ctrl_pts(spline.ctrls(),0,span-p,Dimension,p+1); + der.col(der_order) = (ctrl_weights * ctrl_pts).rowwise().sum(); + } + } + + template + typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::DerivativeType + Spline<_Scalar, _Dim, _Degree>::derivatives(Scalar u, DenseIndex order) const + { + typename SplineTraits< Spline >::DerivativeType res; + derivativesImpl(*this, u, order, res); + return res; + } + + template + template + typename SplineTraits< Spline<_Scalar, _Dim, _Degree>, DerivativeOrder >::DerivativeType + Spline<_Scalar, _Dim, _Degree>::derivatives(Scalar u, DenseIndex order) const + { + typename SplineTraits< Spline, DerivativeOrder >::DerivativeType res; + derivativesImpl(*this, u, order, res); + return res; + } + + template + typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::BasisVectorType + Spline<_Scalar, _Dim, _Degree>::basisFunctions(Scalar u) const + { + return Spline::BasisFunctions(u, degree(), knots()); + } + + /* --------------------------------------------------------------------------------------------- */ + + template + void basisFunctionDerivativesImpl(const SplineType& spline, typename SplineType::Scalar u, DenseIndex order, DerivativeType& N_) + { + enum { Order = SplineTraits::OrderAtCompileTime }; + + typedef typename SplineTraits::Scalar Scalar; + typedef typename SplineTraits::BasisVectorType BasisVectorType; + typedef typename SplineTraits::KnotVectorType KnotVectorType; + typedef typename SplineTraits::ControlPointVectorType ControlPointVectorType; + + const KnotVectorType& U = spline.knots(); + + const DenseIndex p = spline.degree(); + const DenseIndex span = spline.span(u); + + const DenseIndex n = (std::min)(p, order); + + N_.resize(n+1, p+1); + + BasisVectorType left = BasisVectorType::Zero(p+1); + BasisVectorType right = BasisVectorType::Zero(p+1); + + Matrix ndu(p+1,p+1); + + double saved, temp; + + ndu(0,0) = 1.0; + + DenseIndex j; + for (j=1; j<=p; ++j) + { + left[j] = u-U[span+1-j]; + right[j] = U[span+j]-u; + saved = 0.0; + + for (DenseIndex r=0; r(saved+right[r+1] * temp); + saved = left[j-r] * temp; + } + + ndu(j,j) = static_cast(saved); + } + + for (j = p; j>=0; --j) + N_(0,j) = ndu(j,p); + + // Compute the derivatives + DerivativeType a(n+1,p+1); + DenseIndex r=0; + for (; r<=p; ++r) + { + DenseIndex s1,s2; + s1 = 0; s2 = 1; // alternate rows in array a + a(0,0) = 1.0; + + // Compute the k-th derivative + for (DenseIndex k=1; k<=static_cast(n); ++k) + { + double d = 0.0; + DenseIndex rk,pk,j1,j2; + rk = r-k; pk = p-k; + + if (r>=k) + { + a(s2,0) = a(s1,0)/ndu(pk+1,rk); + d = a(s2,0)*ndu(rk,pk); + } + + if (rk>=-1) j1 = 1; + else j1 = -rk; + + if (r-1 <= pk) j2 = k-1; + else j2 = p-r; + + for (j=j1; j<=j2; ++j) + { + a(s2,j) = (a(s1,j)-a(s1,j-1))/ndu(pk+1,rk+j); + d += a(s2,j)*ndu(rk+j,pk); + } + + if (r<=pk) + { + a(s2,k) = -a(s1,k-1)/ndu(pk+1,r); + d += a(s2,k)*ndu(r,pk); + } + + N_(k,r) = static_cast(d); + j = s1; s1 = s2; s2 = j; // Switch rows + } + } + + /* Multiply through by the correct factors */ + /* (Eq. [2.9]) */ + r = p; + for (DenseIndex k=1; k<=static_cast(n); ++k) + { + for (DenseIndex j=p; j>=0; --j) N_(k,j) *= r; + r *= p-k; + } + } + + template + typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::BasisDerivativeType + Spline<_Scalar, _Dim, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const + { + typename SplineTraits< Spline >::BasisDerivativeType der; + basisFunctionDerivativesImpl(*this, u, order, der); + return der; + } + + template + template + typename SplineTraits< Spline<_Scalar, _Dim, _Degree>, DerivativeOrder >::BasisDerivativeType + Spline<_Scalar, _Dim, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const + { + typename SplineTraits< Spline, DerivativeOrder >::BasisDerivativeType der; + basisFunctionDerivativesImpl(*this, u, order, der); + return der; + } +} + +#endif // EIGEN_SPLINE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFitting.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFitting.h new file mode 100644 index 000000000..3e8abbbce --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFitting.h @@ -0,0 +1,174 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 20010-2011 Hauke Heibel +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPLINE_FITTING_H +#define EIGEN_SPLINE_FITTING_H + +#include + +#include "SplineFwd.h" + +#include + +namespace Eigen +{ + /** + * \brief Computes knot averages. + * \ingroup Splines_Module + * + * The knots are computed as + * \f{align*} + * u_0 & = \hdots = u_p = 0 \\ + * u_{m-p} & = \hdots = u_{m} = 1 \\ + * u_{j+p} & = \frac{1}{p}\sum_{i=j}^{j+p-1}\bar{u}_i \quad\quad j=1,\hdots,n-p + * \f} + * where \f$p\f$ is the degree and \f$m+1\f$ the number knots + * of the desired interpolating spline. + * + * \param[in] parameters The input parameters. During interpolation one for each data point. + * \param[in] degree The spline degree which is used during the interpolation. + * \param[out] knots The output knot vector. + * + * \sa Les Piegl and Wayne Tiller, The NURBS book (2nd ed.), 1997, 9.2.1 Global Curve Interpolation to Point Data + **/ + template + void KnotAveraging(const KnotVectorType& parameters, DenseIndex degree, KnotVectorType& knots) + { + typedef typename KnotVectorType::Scalar Scalar; + + knots.resize(parameters.size()+degree+1); + + for (DenseIndex j=1; j + void ChordLengths(const PointArrayType& pts, KnotVectorType& chord_lengths) + { + typedef typename KnotVectorType::Scalar Scalar; + + const DenseIndex n = pts.cols(); + + // 1. compute the column-wise norms + chord_lengths.resize(pts.cols()); + chord_lengths[0] = 0; + chord_lengths.rightCols(n-1) = (pts.array().leftCols(n-1) - pts.array().rightCols(n-1)).matrix().colwise().norm(); + + // 2. compute the partial sums + std::partial_sum(chord_lengths.data(), chord_lengths.data()+n, chord_lengths.data()); + + // 3. normalize the data + chord_lengths /= chord_lengths(n-1); + chord_lengths(n-1) = Scalar(1); + } + + /** + * \brief Spline fitting methods. + * \ingroup Splines_Module + **/ + template + struct SplineFitting + { + typedef typename SplineType::KnotVectorType KnotVectorType; + + /** + * \brief Fits an interpolating Spline to the given data points. + * + * \param pts The points for which an interpolating spline will be computed. + * \param degree The degree of the interpolating spline. + * + * \returns A spline interpolating the initially provided points. + **/ + template + static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree); + + /** + * \brief Fits an interpolating Spline to the given data points. + * + * \param pts The points for which an interpolating spline will be computed. + * \param degree The degree of the interpolating spline. + * \param knot_parameters The knot parameters for the interpolation. + * + * \returns A spline interpolating the initially provided points. + **/ + template + static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters); + }; + + template + template + SplineType SplineFitting::Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters) + { + typedef typename SplineType::KnotVectorType::Scalar Scalar; + typedef typename SplineType::BasisVectorType BasisVectorType; + typedef typename SplineType::ControlPointVectorType ControlPointVectorType; + + typedef Matrix MatrixType; + + KnotVectorType knots; + KnotAveraging(knot_parameters, degree, knots); + + DenseIndex n = pts.cols(); + MatrixType A = MatrixType::Zero(n,n); + for (DenseIndex i=1; i qr(A); + + // Here, we are creating a temporary due to an Eigen issue. + ControlPointVectorType ctrls = qr.solve(MatrixType(pts.transpose())).transpose(); + + return SplineType(knots, ctrls); + } + + template + template + SplineType SplineFitting::Interpolate(const PointArrayType& pts, DenseIndex degree) + { + KnotVectorType chord_lengths; // knot parameters + ChordLengths(pts, chord_lengths); + return Interpolate(pts, degree, chord_lengths); + } +} + +#endif // EIGEN_SPLINE_FITTING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFwd.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFwd.h new file mode 100644 index 000000000..0119115a6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/SplineFwd.h @@ -0,0 +1,101 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 20010-2011 Hauke Heibel +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#ifndef EIGEN_SPLINES_FWD_H +#define EIGEN_SPLINES_FWD_H + +#include + +namespace Eigen +{ + template class Spline; + + template < typename SplineType, int DerivativeOrder = Dynamic > struct SplineTraits {}; + + /** + * \ingroup Splines_Module + * \brief Compile-time attributes of the Spline class for Dynamic degree. + **/ + template + struct SplineTraits< Spline<_Scalar, _Dim, _Degree>, Dynamic > + { + typedef _Scalar Scalar; /*!< The spline curve's scalar type. */ + enum { Dimension = _Dim /*!< The spline curve's dimension. */ }; + enum { Degree = _Degree /*!< The spline curve's degree. */ }; + + enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ }; + enum { NumOfDerivativesAtCompileTime = OrderAtCompileTime /*!< The number of derivatives defined for the current spline. */ }; + + /** \brief The data type used to store non-zero basis functions. */ + typedef Array BasisVectorType; + + /** \brief The data type used to store the values of the basis function derivatives. */ + typedef Array BasisDerivativeType; + + /** \brief The data type used to store the spline's derivative values. */ + typedef Array DerivativeType; + + /** \brief The point type the spline is representing. */ + typedef Array PointType; + + /** \brief The data type used to store knot vectors. */ + typedef Array KnotVectorType; + + /** \brief The data type representing the spline's control points. */ + typedef Array ControlPointVectorType; + }; + + /** + * \ingroup Splines_Module + * \brief Compile-time attributes of the Spline class for fixed degree. + * + * The traits class inherits all attributes from the SplineTraits of Dynamic degree. + **/ + template < typename _Scalar, int _Dim, int _Degree, int _DerivativeOrder > + struct SplineTraits< Spline<_Scalar, _Dim, _Degree>, _DerivativeOrder > : public SplineTraits< Spline<_Scalar, _Dim, _Degree> > + { + enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ }; + enum { NumOfDerivativesAtCompileTime = _DerivativeOrder==Dynamic ? Dynamic : _DerivativeOrder+1 /*!< The number of derivatives defined for the current spline. */ }; + + /** \brief The data type used to store the values of the basis function derivatives. */ + typedef Array<_Scalar,Dynamic,Dynamic,RowMajor,NumOfDerivativesAtCompileTime,OrderAtCompileTime> BasisDerivativeType; + + /** \brief The data type used to store the spline's derivative values. */ + typedef Array<_Scalar,_Dim,Dynamic,ColMajor,_Dim,NumOfDerivativesAtCompileTime> DerivativeType; + }; + + /** \brief 2D float B-spline with dynamic degree. */ + typedef Spline Spline2f; + + /** \brief 3D float B-spline with dynamic degree. */ + typedef Spline Spline3f; + + /** \brief 2D double B-spline with dynamic degree. */ + typedef Spline Spline2d; + + /** \brief 3D double B-spline with dynamic degree. */ + typedef Spline Spline3d; +} + +#endif // EIGEN_SPLINES_FWD_H diff --git a/gtsam/3rdparty/Eigen/unsupported/doc/Doxyfile.in b/gtsam/3rdparty/Eigen/unsupported/doc/Doxyfile.in index 7d5f24b4e..1facf2985 100644 --- a/gtsam/3rdparty/Eigen/unsupported/doc/Doxyfile.in +++ b/gtsam/3rdparty/Eigen/unsupported/doc/Doxyfile.in @@ -203,7 +203,6 @@ ALIASES = "only_for_vectors=This is only for vectors (either row- "svd_module=This is defined in the %SVD module. \code #include \endcode" \ "geometry_module=This is defined in the %Geometry module. \code #include \endcode" \ "label=\bug" \ - "redstar=*" \ "nonstableyet=\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \ref Experimental \"Experimental parts of Eigen\"" # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C @@ -576,13 +575,14 @@ FILE_PATTERNS = * # should be searched for input files as well. Possible values are YES and NO. # If left blank NO is used. -RECURSIVE = NO +RECURSIVE = YES # The EXCLUDE tag can be used to specify files and/or directories that should # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = +EXCLUDE = "${Eigen_SOURCE_DIR}/unsupported/doc/examples" \ + "${Eigen_SOURCE_DIR}/unsupported/doc/snippets" # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded @@ -958,7 +958,8 @@ PAPER_TYPE = a4wide # The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX # packages that should be included in the LaTeX output. -EXTRA_PACKAGES = amssymb +EXTRA_PACKAGES = amssymb \ + amsmath # The LATEX_HEADER tag can be used to specify a personal LaTeX header for # the generated latex document. The header should contain everything until diff --git a/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixLogarithm.cpp b/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixLogarithm.cpp new file mode 100644 index 000000000..8c5d97054 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixLogarithm.cpp @@ -0,0 +1,15 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + using std::sqrt; + MatrixXd A(3,3); + A << 0.5*sqrt(2), -0.5*sqrt(2), 0, + 0.5*sqrt(2), 0.5*sqrt(2), 0, + 0, 0, 1; + std::cout << "The matrix A is:\n" << A << "\n\n"; + std::cout << "The matrix logarithm of A is:\n" << A.log() << "\n"; +} diff --git a/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixSquareRoot.cpp b/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixSquareRoot.cpp new file mode 100644 index 000000000..88e7557d7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/doc/examples/MatrixSquareRoot.cpp @@ -0,0 +1,16 @@ +#include +#include + +using namespace Eigen; + +int main() +{ + const double pi = std::acos(-1.0); + + MatrixXd A(2,2); + A << cos(pi/3), -sin(pi/3), + sin(pi/3), cos(pi/3); + std::cout << "The matrix A is:\n" << A << "\n\n"; + std::cout << "The matrix square root of A is:\n" << A.sqrt() << "\n\n"; + std::cout << "The square of the last matrix is:\n" << A.sqrt() * A.sqrt() << "\n"; +} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/BVH.cpp b/gtsam/3rdparty/Eigen/unsupported/test/BVH.cpp index e77e84b6d..3f9d108de 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/BVH.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/BVH.cpp @@ -24,9 +24,15 @@ #include "main.h" #include +#include #include -inline double SQR(double x) { return x * x; } +namespace Eigen { + +template AlignedBox bounding_box(const Matrix &v) { return AlignedBox(v); } + +} + template struct Ball @@ -41,16 +47,10 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(double, Dim) VectorType center; double radius; }; - -namespace Eigen { -namespace internal { - -template AlignedBox bounding_box(const Matrix &v) { return AlignedBox(v); } template AlignedBox bounding_box(const Ball &b) { return AlignedBox(b.center.array() - b.radius, b.center.array() + b.radius); } -} // end namespace internal -} +inline double SQR(double x) { return x * x; } template struct BallPointStuff //this class provides functions to be both an intersector and a minimizer, both for a ball and a point and for two trees diff --git a/gtsam/3rdparty/Eigen/unsupported/test/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/test/CMakeLists.txt index f8c0ff486..b34b151b1 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/test/CMakeLists.txt @@ -1,47 +1,6 @@ -include_directories(../../test ../../unsupported ../../Eigen) - -set(SPARSE_LIBS "") - -# configure blas/lapack -if(CMAKE_Fortran_COMPILER_WORKS) - set(BLAS_FOUND TRUE) - set(LAPACK_FOUND TRUE) - set(BLAS_LIBRARIES eigen_blas_static) - set(LAPACK_LIBRARIES eigen_lapack_static) -else() - # TODO search for default blas/lapack -endif() - -find_package(Cholmod) -if(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND) - add_definitions("-DEIGEN_CHOLMOD_SUPPORT") - include_directories(${CHOLMOD_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) - ei_add_property(EIGEN_TESTED_BACKENDS "Cholmod, ") -else() - ei_add_property(EIGEN_MISSING_BACKENDS "Cholmod, ") -endif() - -find_package(Umfpack) -if(UMFPACK_FOUND AND BLAS_FOUND) - add_definitions("-DEIGEN_UMFPACK_SUPPORT") - include_directories(${UMFPACK_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) - ei_add_property(EIGEN_TESTED_BACKENDS "UmfPack, ") -else() - ei_add_property(EIGEN_MISSING_BACKENDS "UmfPack, ") -endif() - -find_package(SuperLU) -if(SUPERLU_FOUND AND BLAS_FOUND) - add_definitions("-DEIGEN_SUPERLU_SUPPORT") - include_directories(${SUPERLU_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) - ei_add_property(EIGEN_TESTED_BACKENDS "SuperLU, ") -else() - ei_add_property(EIGEN_MISSING_BACKENDS "SuperLU, ") -endif() +include_directories(../../test ../../unsupported ../../Eigen + ${CMAKE_CURRENT_BINARY_DIR}/../../test) find_package(GoogleHash) if(GOOGLEHASH_FOUND) @@ -74,6 +33,7 @@ endif() ei_add_test(matrix_exponential) ei_add_test(matrix_function) +ei_add_test(matrix_square_root) ei_add_test(alignedvector3) ei_add_test(FFT) @@ -88,18 +48,16 @@ else() ei_add_property(EIGEN_MISSING_BACKENDS "MPFR C++, ") endif() -ei_add_test(sparse_llt "" "${SPARSE_LIBS}") -ei_add_test(sparse_ldlt "" "${SPARSE_LIBS}") -ei_add_test(sparse_lu "" "${SPARSE_LIBS}") ei_add_test(sparse_extra "" "") find_package(FFTW) if(FFTW_FOUND) ei_add_property(EIGEN_TESTED_BACKENDS "fftw, ") + include_directories( ${FFTW_INCLUDES} ) if(FFTWL_LIB) - ei_add_test(FFTW "-DEIGEN_FFTW_DEFAULT -DEIGEN_HAS_FFTWL" "fftw3;fftw3f;fftw3l" ) + ei_add_test(FFTW "-DEIGEN_FFTW_DEFAULT -DEIGEN_HAS_FFTWL" "${FFTW_LIBRARIES}" ) else() - ei_add_test(FFTW "-DEIGEN_FFTW_DEFAULT " "fftw3;fftw3f" ) + ei_add_test(FFTW "-DEIGEN_FFTW_DEFAULT" "${FFTW_LIBRARIES}" ) endif() else() ei_add_property(EIGEN_MISSING_BACKENDS "fftw, ") @@ -121,18 +79,9 @@ else() ei_add_property(EIGEN_MISSING_BACKENDS "OpenGL, ") endif() -find_package(GSL) -if(GSL_FOUND AND GSL_VERSION_MINOR LESS 9) - set(GSL_FOUND "") -endif(GSL_FOUND AND GSL_VERSION_MINOR LESS 9) -if(GSL_FOUND) - add_definitions("-DHAS_GSL" ${GSL_DEFINITIONS}) - include_directories(${GSL_INCLUDE_DIR}) - ei_add_property(EIGEN_TESTED_BACKENDS "GSL, ") -else(GSL_FOUND) - ei_add_property(EIGEN_MISSING_BACKENDS "GSL, ") - set(GSL_LIBRARIES " ") -endif(GSL_FOUND) - -ei_add_test(polynomialsolver " " "${GSL_LIBRARIES}" ) +ei_add_test(polynomialsolver) ei_add_test(polynomialutils) +ei_add_test(kronecker_product) +ei_add_test(splines) +ei_add_test(gmres) + diff --git a/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp b/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp index a32d85829..7ce4b4dee 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp @@ -28,13 +28,21 @@ template EIGEN_DONT_INLINE Scalar foo(const Scalar& x, const Scalar& y) { + using namespace std; // return x+std::sin(y); EIGEN_ASM_COMMENT("mybegin"); - return static_cast(x*2 - std::pow(x,2) + 2*std::sqrt(y*y) - 4 * std::sin(x) + 2 * std::cos(y) - std::exp(-0.5*x*x)); + return static_cast(x*2 - pow(x,2) + 2*sqrt(y*y) - 4 * sin(x) + 2 * cos(y) - exp(-0.5*x*x)); //return x+2*y*x;//x*2 -std::pow(x,2);//(2*y/x);// - y*2; EIGEN_ASM_COMMENT("myend"); } +template +EIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p) +{ + typedef typename Vector::Scalar Scalar; + return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array() * p.array()).sum() + p.dot(p); +} + template struct TestFunc1 { @@ -140,9 +148,23 @@ void test_autodiff_scalar() typedef AutoDiffScalar AD; AD ax(1,Vector2f::UnitX()); AD ay(2,Vector2f::UnitY()); - foo(ax,ay); - std::cerr << foo(ax,ay).value() << " <> " - << foo(ax,ay).derivatives().transpose() << "\n\n"; + AD res = foo(ax,ay); + std::cerr << res.value() << " <> " + << res.derivatives().transpose() << "\n\n"; +} + +void test_autodiff_vector() +{ + std::cerr << foo(Vector2f(1,2)) << "\n"; + typedef AutoDiffScalar AD; + typedef Matrix VectorAD; + VectorAD p(AD(1),AD(-1)); + p.x().derivatives() = Vector2f::UnitX(); + p.y().derivatives() = Vector2f::UnitY(); + + AD res = foo(p); + std::cerr << res.value() << " <> " + << res.derivatives().transpose() << "\n\n"; } void test_autodiff_jacobian() @@ -159,6 +181,7 @@ void test_autodiff_jacobian() void test_autodiff() { test_autodiff_scalar(); - test_autodiff_jacobian(); + test_autodiff_vector(); +// test_autodiff_jacobian(); } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/forward_adolc.cpp b/gtsam/3rdparty/Eigen/unsupported/test/forward_adolc.cpp index 1971d883b..07959a668 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/forward_adolc.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/forward_adolc.cpp @@ -23,11 +23,20 @@ // Eigen. If not, see . #include "main.h" +#include + #define NUMBER_DIRECTIONS 16 #include int adtl::ADOLC_numDir; +template +EIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p) +{ + typedef typename Vector::Scalar Scalar; + return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array().sqrt().abs() * p.array().sin()).sum() + p.dot(p); +} + template struct TestFunc1 { @@ -138,4 +147,12 @@ void test_forward_adolc() CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1()) )); CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1(3,3)) )); } + + { + // simple instanciation tests + Matrix x; + foo(x); + Matrix A(4,4);; + A.selfadjointView().eigenvalues(); + } } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/gmres.cpp b/gtsam/3rdparty/Eigen/unsupported/test/gmres.cpp new file mode 100644 index 000000000..30ebe8979 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/test/gmres.cpp @@ -0,0 +1,48 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2012 Kolja Brix +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "../../test/sparse_solver.h" +#include + +template void test_gmres_T() +{ + GMRES, DiagonalPreconditioner > gmres_colmajor_diag; + GMRES, IdentityPreconditioner > gmres_colmajor_I; + GMRES, IncompleteLUT > gmres_colmajor_ilut; + //GMRES, SSORPreconditioner > gmres_colmajor_ssor; + + CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_diag) ); +// CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_I) ); + CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ilut) ); + //CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ssor) ); +} + +void test_gmres() +{ + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(test_gmres_T()); + CALL_SUBTEST_2(test_gmres_T >()); + } +} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/kronecker_product.cpp b/gtsam/3rdparty/Eigen/unsupported/test/kronecker_product.cpp new file mode 100644 index 000000000..3c7a6629f --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/test/kronecker_product.cpp @@ -0,0 +1,194 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Kolja Brix +// Copyright (C) 2011 Andreas Platen +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + + +#include "sparse.h" +#include +#include + + +template +void check_dimension(const MatrixType& ab, const unsigned int rows, const unsigned int cols) +{ + VERIFY_IS_EQUAL(ab.rows(), rows); + VERIFY_IS_EQUAL(ab.cols(), cols); +} + + +template +void check_kronecker_product(const MatrixType& ab) +{ + VERIFY_IS_EQUAL(ab.rows(), 6); + VERIFY_IS_EQUAL(ab.cols(), 6); + VERIFY_IS_EQUAL(ab.nonZeros(), 36); + VERIFY_IS_APPROX(ab.coeff(0,0), -0.4017367630386106); + VERIFY_IS_APPROX(ab.coeff(0,1), 0.1056863433932735); + VERIFY_IS_APPROX(ab.coeff(0,2), -0.7255206194554212); + VERIFY_IS_APPROX(ab.coeff(0,3), 0.1908653336744706); + VERIFY_IS_APPROX(ab.coeff(0,4), 0.350864567234111); + VERIFY_IS_APPROX(ab.coeff(0,5), -0.0923032108308013); + VERIFY_IS_APPROX(ab.coeff(1,0), 0.415417514804677); + VERIFY_IS_APPROX(ab.coeff(1,1), -0.2369227701722048); + VERIFY_IS_APPROX(ab.coeff(1,2), 0.7502275131458511); + VERIFY_IS_APPROX(ab.coeff(1,3), -0.4278731019742696); + VERIFY_IS_APPROX(ab.coeff(1,4), -0.3628129162264507); + VERIFY_IS_APPROX(ab.coeff(1,5), 0.2069210808481275); + VERIFY_IS_APPROX(ab.coeff(2,0), 0.05465890160863986); + VERIFY_IS_APPROX(ab.coeff(2,1), -0.2634092511419858); + VERIFY_IS_APPROX(ab.coeff(2,2), 0.09871180285793758); + VERIFY_IS_APPROX(ab.coeff(2,3), -0.4757066334017702); + VERIFY_IS_APPROX(ab.coeff(2,4), -0.04773740823058334); + VERIFY_IS_APPROX(ab.coeff(2,5), 0.2300535609645254); + VERIFY_IS_APPROX(ab.coeff(3,0), -0.8172945853260133); + VERIFY_IS_APPROX(ab.coeff(3,1), 0.2150086428359221); + VERIFY_IS_APPROX(ab.coeff(3,2), 0.5825113847292743); + VERIFY_IS_APPROX(ab.coeff(3,3), -0.1532433770097174); + VERIFY_IS_APPROX(ab.coeff(3,4), -0.329383387282399); + VERIFY_IS_APPROX(ab.coeff(3,5), 0.08665207912033064); + VERIFY_IS_APPROX(ab.coeff(4,0), 0.8451267514863225); + VERIFY_IS_APPROX(ab.coeff(4,1), -0.481996458918977); + VERIFY_IS_APPROX(ab.coeff(4,2), -0.6023482390791535); + VERIFY_IS_APPROX(ab.coeff(4,3), 0.3435339347164565); + VERIFY_IS_APPROX(ab.coeff(4,4), 0.3406002157428891); + VERIFY_IS_APPROX(ab.coeff(4,5), -0.1942526344200915); + VERIFY_IS_APPROX(ab.coeff(5,0), 0.1111982482925399); + VERIFY_IS_APPROX(ab.coeff(5,1), -0.5358806424754169); + VERIFY_IS_APPROX(ab.coeff(5,2), -0.07925446559335647); + VERIFY_IS_APPROX(ab.coeff(5,3), 0.3819388757769038); + VERIFY_IS_APPROX(ab.coeff(5,4), 0.04481475387219876); + VERIFY_IS_APPROX(ab.coeff(5,5), -0.2159688616158057); +} + + +template +void check_sparse_kronecker_product(const MatrixType& ab) +{ + VERIFY_IS_EQUAL(ab.rows(), 12); + VERIFY_IS_EQUAL(ab.cols(), 10); + VERIFY_IS_EQUAL(ab.nonZeros(), 3*2); + VERIFY_IS_APPROX(ab.coeff(3,0), -0.04); + VERIFY_IS_APPROX(ab.coeff(5,1), 0.05); + VERIFY_IS_APPROX(ab.coeff(0,6), -0.08); + VERIFY_IS_APPROX(ab.coeff(2,7), 0.10); + VERIFY_IS_APPROX(ab.coeff(6,8), 0.12); + VERIFY_IS_APPROX(ab.coeff(8,9), -0.15); +} + + +void test_kronecker_product() +{ + // DM = dense matrix; SM = sparse matrix + Matrix DM_a; + MatrixXd DM_b(3,2); + SparseMatrix SM_a(2,3); + SparseMatrix SM_b(3,2); + SM_a.insert(0,0) = DM_a(0,0) = -0.4461540300782201; + SM_a.insert(0,1) = DM_a(0,1) = -0.8057364375283049; + SM_a.insert(0,2) = DM_a(0,2) = 0.3896572459516341; + SM_a.insert(1,0) = DM_a(1,0) = -0.9076572187376921; + SM_a.insert(1,1) = DM_a(1,1) = 0.6469156566545853; + SM_a.insert(1,2) = DM_a(1,2) = -0.3658010398782789; + SM_b.insert(0,0) = DM_b(0,0) = 0.9004440976767099; + SM_b.insert(0,1) = DM_b(0,1) = -0.2368830858139832; + SM_b.insert(1,0) = DM_b(1,0) = -0.9311078389941825; + SM_b.insert(1,1) = DM_b(1,1) = 0.5310335762980047; + SM_b.insert(2,0) = DM_b(2,0) = -0.1225112806872035; + SM_b.insert(2,1) = DM_b(2,1) = 0.5903998022741264; + SparseMatrix SM_row_a(SM_a), SM_row_b(SM_b); + + // test kroneckerProduct(DM_block,DM,DM_fixedSize) + Matrix DM_fix_ab; + DM_fix_ab(0,0)=37.0; + kroneckerProduct(DM_a.block(0,0,2,3),DM_b,DM_fix_ab); + CALL_SUBTEST(check_kronecker_product(DM_fix_ab)); + + // test kroneckerProduct(DM,DM,DM_block) + MatrixXd DM_block_ab(10,15); + DM_block_ab(0,0)=37.0; + kroneckerProduct(DM_a,DM_b,DM_block_ab.block(2,5,6,6)); + CALL_SUBTEST(check_kronecker_product(DM_block_ab.block(2,5,6,6))); + + // test kroneckerProduct(DM,DM,DM) + MatrixXd DM_ab(1,5); + DM_ab(0,0)=37.0; + kroneckerProduct(DM_a,DM_b,DM_ab); + CALL_SUBTEST(check_kronecker_product(DM_ab)); + + // test kroneckerProduct(SM,DM,SM) + SparseMatrix SM_ab(1,20); + SM_ab.insert(0,0)=37.0; + kroneckerProduct(SM_a,DM_b,SM_ab); + CALL_SUBTEST(check_kronecker_product(SM_ab)); + SparseMatrix SM_ab2(10,3); + SM_ab2.insert(0,0)=37.0; + kroneckerProduct(SM_a,DM_b,SM_ab2); + CALL_SUBTEST(check_kronecker_product(SM_ab2)); + + // test kroneckerProduct(DM,SM,SM) + SM_ab.insert(0,0)=37.0; + kroneckerProduct(DM_a,SM_b,SM_ab); + CALL_SUBTEST(check_kronecker_product(SM_ab)); + SM_ab2.insert(0,0)=37.0; + kroneckerProduct(DM_a,SM_b,SM_ab2); + CALL_SUBTEST(check_kronecker_product(SM_ab2)); + + // test kroneckerProduct(SM,SM,SM) + SM_ab.resize(2,33); + SM_ab.insert(0,0)=37.0; + kroneckerProduct(SM_a,SM_b,SM_ab); + CALL_SUBTEST(check_kronecker_product(SM_ab)); + SM_ab2.resize(5,11); + SM_ab2.insert(0,0)=37.0; + kroneckerProduct(SM_a,SM_b,SM_ab2); + CALL_SUBTEST(check_kronecker_product(SM_ab2)); + + // test kroneckerProduct(SM,SM,SM) with sparse pattern + SM_a.resize(4,5); + SM_b.resize(3,2); + SM_a.resizeNonZeros(0); + SM_b.resizeNonZeros(0); + SM_a.insert(1,0) = -0.1; + SM_a.insert(0,3) = -0.2; + SM_a.insert(2,4) = 0.3; + SM_a.finalize(); + SM_b.insert(0,0) = 0.4; + SM_b.insert(2,1) = -0.5; + SM_b.finalize(); + SM_ab.resize(1,1); + SM_ab.insert(0,0)=37.0; + kroneckerProduct(SM_a,SM_b,SM_ab); + CALL_SUBTEST(check_sparse_kronecker_product(SM_ab)); + + // test dimension of result of kroneckerProduct(DM,DM,DM) + MatrixXd DM_a2(2,1); + MatrixXd DM_b2(5,4); + MatrixXd DM_ab2; + kroneckerProduct(DM_a2,DM_b2,DM_ab2); + CALL_SUBTEST(check_dimension(DM_ab2,2*5,1*4)); + DM_a2.resize(10,9); + DM_b2.resize(4,8); + kroneckerProduct(DM_a2,DM_b2,DM_ab2); + CALL_SUBTEST(check_dimension(DM_ab2,10*4,9*8)); +} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/matrix_exponential.cpp b/gtsam/3rdparty/Eigen/unsupported/test/matrix_exponential.cpp index 996b42a7f..26403c4e6 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/matrix_exponential.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/matrix_exponential.cpp @@ -55,7 +55,7 @@ void test2dRotation(double tol) for (int i=0; i<=20; i++) { angle = static_cast(pow(10, i / 5. - 2)); - B << cos(angle), sin(angle), -sin(angle), cos(angle); + B << std::cos(angle), std::sin(angle), -std::sin(angle), std::cos(angle); C = (angle*A).matrixFunction(expfn); std::cout << "test2dRotation: i = " << i << " error funm = " << relerr(C, B); @@ -146,8 +146,10 @@ void test_matrix_exponential() { CALL_SUBTEST_2(test2dRotation(1e-13)); CALL_SUBTEST_1(test2dRotation(2e-5)); // was 1e-5, relaxed for clang 2.8 / linux / x86-64 + CALL_SUBTEST_8(test2dRotation(1e-13)); CALL_SUBTEST_2(test2dHyperbolicRotation(1e-14)); CALL_SUBTEST_1(test2dHyperbolicRotation(1e-5)); + CALL_SUBTEST_8(test2dHyperbolicRotation(1e-14)); CALL_SUBTEST_6(testPascal(1e-6)); CALL_SUBTEST_5(testPascal(1e-15)); CALL_SUBTEST_2(randomTest(Matrix2d(), 1e-13)); @@ -158,4 +160,5 @@ void test_matrix_exponential() CALL_SUBTEST_5(randomTest(Matrix3cf(), 1e-4)); CALL_SUBTEST_1(randomTest(Matrix4f(), 1e-4)); CALL_SUBTEST_6(randomTest(MatrixXf(8,8), 1e-4)); + CALL_SUBTEST_9(randomTest(Matrix(7,7), 1e-13)); } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/matrix_function.cpp b/gtsam/3rdparty/Eigen/unsupported/test/matrix_function.cpp index 04167abfb..c2ca5d5f1 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/matrix_function.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/matrix_function.cpp @@ -120,6 +120,26 @@ void testMatrixExponential(const MatrixType& A) VERIFY_IS_APPROX(A.exp(), A.matrixFunction(StdStemFunctions::exp)); } +template +void testMatrixLogarithm(const MatrixType& A) +{ + typedef typename internal::traits::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef std::complex ComplexScalar; + + MatrixType scaledA; + RealScalar maxImagPartOfSpectrum = A.eigenvalues().imag().cwiseAbs().maxCoeff(); + if (maxImagPartOfSpectrum >= 0.9 * M_PI) + scaledA = A * 0.9 * M_PI / maxImagPartOfSpectrum; + else + scaledA = A; + + // identity X.exp().log() = X only holds if Im(lambda) < pi for all eigenvalues of X + MatrixType expA = scaledA.exp(); + MatrixType logExpA = expA.log(); + VERIFY_IS_APPROX(logExpA, scaledA); +} + template void testHyperbolicFunctions(const MatrixType& A) { @@ -157,6 +177,7 @@ template void testMatrix(const MatrixType& A) { testMatrixExponential(A); + testMatrixLogarithm(A); testHyperbolicFunctions(A); testGonioFunctions(A); } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/matrix_square_root.cpp b/gtsam/3rdparty/Eigen/unsupported/test/matrix_square_root.cpp new file mode 100644 index 000000000..8e701aac6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/test/matrix_square_root.cpp @@ -0,0 +1,77 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Jitse Niesen +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "main.h" +#include + +template ::Scalar>::IsComplex> +struct generateTestMatrix; + +// for real matrices, make sure none of the eigenvalues are negative +template +struct generateTestMatrix +{ + static void run(MatrixType& result, typename MatrixType::Index size) + { + MatrixType mat = MatrixType::Random(size, size); + EigenSolver es(mat); + typename EigenSolver::EigenvalueType eivals = es.eigenvalues(); + for (typename MatrixType::Index i = 0; i < size; ++i) { + if (eivals(i).imag() == 0 && eivals(i).real() < 0) + eivals(i) = -eivals(i); + } + result = (es.eigenvectors() * eivals.asDiagonal() * es.eigenvectors().inverse()).real(); + } +}; + +// for complex matrices, any matrix is fine +template +struct generateTestMatrix +{ + static void run(MatrixType& result, typename MatrixType::Index size) + { + result = MatrixType::Random(size, size); + } +}; + +template +void testMatrixSqrt(const MatrixType& m) +{ + MatrixType A; + generateTestMatrix::run(A, m.rows()); + MatrixType sqrtA = A.sqrt(); + VERIFY_IS_APPROX(sqrtA * sqrtA, A); +} + +void test_matrix_square_root() +{ + for (int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(testMatrixSqrt(Matrix3cf())); + CALL_SUBTEST_2(testMatrixSqrt(MatrixXcd(12,12))); + CALL_SUBTEST_3(testMatrixSqrt(Matrix4f())); + CALL_SUBTEST_4(testMatrixSqrt(Matrix(9, 9))); + CALL_SUBTEST_5(testMatrixSqrt(Matrix())); + CALL_SUBTEST_5(testMatrixSqrt(Matrix,1,1>())); + } +} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/dlmalloc.c b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/dlmalloc.c index a2c03b533..7ce8feb07 100755 --- a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/dlmalloc.c +++ b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/dlmalloc.c @@ -1267,7 +1267,7 @@ int mspace_mallopt(int, int); #endif /* MSPACES */ #ifdef __cplusplus -}; /* end of extern "C" */ +} /* end of extern "C" */ #endif /* __cplusplus */ /* diff --git a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.cpp b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.cpp index 373f23b12..5c23544ef 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.cpp @@ -3,14 +3,15 @@ Project homepage: http://www.holoborodko.com/pavel/ Contact e-mail: pavel@holoborodko.com - Copyright (c) 2008-2010 Pavel Holoborodko + Copyright (c) 2008-2011 Pavel Holoborodko Core Developers: Pavel Holoborodko, Dmitriy Gubanov, Konstantin Holoborodko. Contributors: Brian Gladman, Helmut Jarausch, Fokko Beekhof, Ulrich Mutze, - Heinz van Saanen, Pere Constans, Peter van Hoof. + Heinz van Saanen, Pere Constans, Peter van Hoof, Gael Guennebaud, + Tsai Chia Cheng, Alexei Zubanov. **************************************************************************** This library is free software; you can redistribute it and/or @@ -27,31 +28,21 @@ License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + **************************************************************************** **************************************************************************** Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - + 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - + 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. Redistributions of any form whatsoever must retain the following - acknowledgment: - " - This product includes software developed by Pavel Holoborodko - Web: http://www.holoborodko.com/pavel/ - e-mail: pavel@holoborodko.com - " - 4. This software cannot be, by any means, used for any commercial - purpose without the prior permission of the copyright holder. - - Any of the above conditions can be waived if you get permission from - the copyright holder. + 3. The name of the author may be used to endorse or promote products + derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE @@ -66,9 +57,11 @@ SUCH DAMAGE. */ #include -#include #include "mpreal.h" + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) #include "dlmalloc.h" +#endif using std::ws; using std::cerr; @@ -79,62 +72,107 @@ using std::istream; namespace mpfr{ -mp_rnd_t mpreal::default_rnd = mpfr_get_default_rounding_mode(); -mp_prec_t mpreal::default_prec = mpfr_get_default_prec(); +mp_rnd_t mpreal::default_rnd = MPFR_RNDN; //(mpfr_get_default_rounding_mode)(); +mp_prec_t mpreal::default_prec = 64; //(mpfr_get_default_prec)(); int mpreal::default_base = 10; int mpreal::double_bits = -1; + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) bool mpreal::is_custom_malloc = false; +#endif // Default constructor: creates mp number and initializes it to 0. mpreal::mpreal() { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,default_prec); mpfr_set_ui(mp,0,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const mpreal& u) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,mpfr_get_prec(u.mp)); mpfr_set(mp,u.mp,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const mpfr_t u) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,mpfr_get_prec(u)); mpfr_set(mp,u,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const mpf_t u) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); - mpfr_init2(mp,mpf_get_prec(u)); +#endif + + mpfr_init2(mp,(mp_prec_t) mpf_get_prec(u)); // (gmp: mp_bitcnt_t) unsigned long -> long (mpfr: mp_prec_t) mpfr_set_f(mp,u,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const mpz_t u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_z(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const mpq_t u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_q(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const double u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + if(double_bits == -1 || fits_in_bits(u, double_bits)) { mpfr_init2(mp,prec); mpfr_set_d(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } else throw conversion_overflow(); @@ -142,51 +180,121 @@ mpreal::mpreal(const double u, mp_prec_t prec, mp_rnd_t mode) mpreal::mpreal(const long double u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_ld(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const unsigned long int u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_ui(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const unsigned int u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_ui(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const long int u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_si(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const int u, mp_prec_t prec, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_si(mp,u,mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } +#if defined (MPREAL_HAVE_INT64_SUPPORT) +mpreal::mpreal(const uint64_t u, mp_prec_t prec, mp_rnd_t mode) +{ + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) + set_custom_malloc(); +#endif + + mpfr_init2(mp,prec); + mpfr_set_uj(mp, u, mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; +} + +mpreal::mpreal(const int64_t u, mp_prec_t prec, mp_rnd_t mode) +{ + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) + set_custom_malloc(); +#endif + + mpfr_init2(mp,prec); + mpfr_set_sj(mp, u, mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; +} +#endif + mpreal::mpreal(const char* s, mp_prec_t prec, int base, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_str(mp, s, base, mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::mpreal(const std::string& s, mp_prec_t prec, int base, mp_rnd_t mode) { + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif + mpfr_init2(mp,prec); mpfr_set_str(mp, s.c_str(), base, mode); + + MPREAL_MSVC_DEBUGVIEW_CODE; } mpreal::~mpreal() @@ -198,18 +306,22 @@ mpreal::~mpreal() mpreal& mpreal::operator=(const char* s) { mpfr_t t; - + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); +#endif if(0==mpfr_init_set_str(t,s,default_base,default_rnd)) { - // We will rewrite mp anyway, so use flash it and resize - mpfr_set_prec(mp,mpfr_get_prec(t)); //<- added 01.04.2011 + // We will rewrite mp anyway, so flash it and resize + mpfr_set_prec(mp,mpfr_get_prec(t)); mpfr_set(mp,t,mpreal::default_rnd); mpfr_clear(t); + + MPREAL_MSVC_DEBUGVIEW_CODE; + }else{ mpfr_clear(t); - // cerr<<"fail to convert string"<xp?yp:xp); - - mpfr_hypot(a.mp, x.mp, y.mp, rnd_mode); - - return a; -} - const mpreal sum (const mpreal tab[], unsigned long int n, mp_rnd_t rnd_mode) { mpreal x; @@ -288,21 +385,6 @@ const mpreal sum (const mpreal tab[], unsigned long int n, mp_rnd_t rnd_mode) return x; } -const mpreal remainder (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode) -{ - mpreal a; - mp_prec_t yp, xp; - - yp = y.get_prec(); - xp = x.get_prec(); - - a.set_prec(yp>xp?yp:xp); - - mpfr_remainder(a.mp, x.mp, y.mp, rnd_mode); - - return a; -} - const mpreal remquo (long* q, const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode) { mpreal a; @@ -319,36 +401,71 @@ const mpreal remquo (long* q, const mpreal& x, const mpreal& y, mp_rnd_t rnd_mod } template -std::string to_string(T t, std::ios_base & (*f)(std::ios_base&)) +std::string toString(T t, std::ios_base & (*f)(std::ios_base&)) { std::ostringstream oss; oss << f << t; return oss.str(); } -mpreal::operator std::string() const +#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) + +std::string mpreal::toString(const std::string& format) const { - return to_string(); + char *s = NULL; + string out; + + if( !format.empty() ) + { + if(!(mpfr_asprintf(&s,format.c_str(),mp) < 0)) + { + out = std::string(s); + + mpfr_free_str(s); + } + } + + return out; } -std::string mpreal::to_string(size_t n, int b, mp_rnd_t mode) const +#endif + +std::string mpreal::toString(int n, int b, mp_rnd_t mode) const { - char *s, *ns = NULL; + (void)b; + (void)mode; +#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) + + // Use MPFR native function for output + char format[128]; + int digits; + + digits = n > 0 ? n : bits2digits(mpfr_get_prec(mp)); + + sprintf(format,"%%.%dRNg",digits); // Default format + + return toString(std::string(format)); + +#else + + char *s, *ns = NULL; size_t slen, nslen; mp_exp_t exp; string out; - + +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) set_custom_malloc(); - +#endif + if(mpfr_inf_p(mp)) { - if(mpfr_sgn(mp)>0) return "+@Inf@"; - else return "-@Inf@"; + if(mpfr_sgn(mp)>0) return "+Inf"; + else return "-Inf"; } if(mpfr_zero_p(mp)) return "0"; - if(mpfr_nan_p(mp)) return "@NaN@"; - + if(mpfr_nan_p(mp)) return "NaN"; + s = mpfr_get_str(NULL,&exp,b,0,mp,mode); ns = mpfr_get_str(NULL,&exp,b,n,mp,mode); @@ -419,8 +536,8 @@ std::string mpreal::to_string(size_t n, int b, mp_rnd_t mode) const // Make final string if(--exp) { - if(exp>0) out += "e+"+mpfr::to_string(exp,std::dec); - else out += "e"+mpfr::to_string(exp,std::dec); + if(exp>0) out += "e+"+mpfr::toString(exp,std::dec); + else out += "e"+mpfr::toString(exp,std::dec); } } @@ -429,79 +546,52 @@ std::string mpreal::to_string(size_t n, int b, mp_rnd_t mode) const }else{ return "conversion error!"; } +#endif } + ////////////////////////////////////////////////////////////////////////// // I/O ostream& operator<<(ostream& os, const mpreal& v) { - return os<(os.precision())); + return os<(os.precision())); } istream& operator>>(istream &is, mpreal& v) { - char c; - string s = ""; - mpfr_t t; - - mpreal::set_custom_malloc(); - - if(is.good()) - { - is>>ws; - while ((c = is.get())!=EOF) - { - if(c ==' ' || c == '\t' || c == '\n' || c == '\r') - { - is.putback(c); - break; - } - s += c; - } - - if(s.size() != 0) - { - // Protect current value from alternation in case of input error - // so some error handling(roll back) procedure can be used - - if(0==mpfr_init_set_str(t,s.c_str(),mpreal::default_base,mpreal::default_rnd)) - { - mpfr_set(v.mp,t,mpreal::default_rnd); - mpfr_clear(t); - - }else{ - mpfr_clear(t); - cerr<<"error reading from istream"<> tmp; + mpfr_set_str(v.mp, tmp.c_str(),mpreal::default_base,mpreal::default_rnd); return is; } -// Optimized dynamic memory allocation/(re-)deallocation. -void * mpreal::mpreal_allocate(size_t alloc_size) -{ - return(dlmalloc(alloc_size)); -} -void * mpreal::mpreal_reallocate(void *ptr, size_t /*old_size*/, size_t new_size) -{ - return(dlrealloc(ptr,new_size)); -} - -void mpreal::mpreal_free(void *ptr, size_t /*size*/) -{ - dlfree(ptr); -} - -inline void mpreal::set_custom_malloc(void) -{ - if(!is_custom_malloc) +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) + // Optimized dynamic memory allocation/(re-)deallocation. + void * mpreal::mpreal_allocate(size_t alloc_size) { - mp_set_memory_functions(mpreal_allocate,mpreal_reallocate,mpreal_free); - is_custom_malloc = true; + return(dlmalloc(alloc_size)); } -} + + void * mpreal::mpreal_reallocate(void *ptr, size_t old_size, size_t new_size) + { + return(dlrealloc(ptr,new_size)); + } + + void mpreal::mpreal_free(void *ptr, size_t size) + { + dlfree(ptr); + } + + inline void mpreal::set_custom_malloc(void) + { + if(!is_custom_malloc) + { + mp_set_memory_functions(mpreal_allocate,mpreal_reallocate,mpreal_free); + is_custom_malloc = true; + } + } +#endif + } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h index 96f474640..c640af947 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h +++ b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h @@ -1,16 +1,17 @@ /* - Multi-precision real number class. C++ interface fo MPFR library. + Multi-precision real number class. C++ interface for MPFR library. Project homepage: http://www.holoborodko.com/pavel/ Contact e-mail: pavel@holoborodko.com - Copyright (c) 2008-2010 Pavel Holoborodko + Copyright (c) 2008-2012 Pavel Holoborodko Core Developers: Pavel Holoborodko, Dmitriy Gubanov, Konstantin Holoborodko. Contributors: Brian Gladman, Helmut Jarausch, Fokko Beekhof, Ulrich Mutze, - Heinz van Saanen, Pere Constans, Peter van Hoof. + Heinz van Saanen, Pere Constans, Peter van Hoof, Gael Guennebaud, + Tsai Chia Cheng, Alexei Zubanov. **************************************************************************** This library is free software; you can redistribute it and/or @@ -39,19 +40,8 @@ notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Redistributions of any form whatsoever must retain the following - acknowledgment: - " - This product includes software developed by Pavel Holoborodko - Web: http://www.holoborodko.com/pavel/ - e-mail: pavel@holoborodko.com - " - - 4. This software cannot be, by any means, used for any commercial - purpose without the prior permission of the copyright holder. - - Any of the above conditions can be waived if you get permission from - the copyright holder. + 3. The name of the author may be used to endorse or promote products + derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE @@ -66,8 +56,8 @@ SUCH DAMAGE. */ -#ifndef __MP_REAL_H__ -#define __MP_REAL_H__ +#ifndef __MPREAL_H__ +#define __MPREAL_H__ #include #include @@ -76,22 +66,65 @@ #include #include -#include +// Options +#define MPREAL_HAVE_INT64_SUPPORT // int64_t support: available only for MSVC 2010 & GCC +#define MPREAL_HAVE_MSVC_DEBUGVIEW // Enable Debugger Visualizer (valid only for MSVC in "Debug" builds) // Detect compiler using signatures from http://predef.sourceforge.net/ #if defined(__GNUC__) && defined(__INTEL_COMPILER) #define IsInf(x) isinf(x) // Intel ICC compiler on Linux +#elif defined(_MSC_VER) // Microsoft Visual C++ + #define IsInf(x) (!_finite(x)) + #elif defined(__GNUC__) #define IsInf(x) std::isinf(x) // GNU C/C++ -#elif defined(_MSC_VER) - #define IsInf(x) (!_finite(x)) // Microsoft Visual C++ - #else #define IsInf(x) std::isinf(x) // Unknown compiler, just hope for C99 conformance #endif +#if defined(MPREAL_HAVE_INT64_SUPPORT) + + #define MPFR_USE_INTMAX_T // should be defined before mpfr.h + + #if defined(_MSC_VER) // is available only in msvc2010! + #if (_MSC_VER >= 1600) + #include + #else // MPFR relies on intmax_t which is available only in msvc2010 + #undef MPREAL_HAVE_INT64_SUPPORT // Besides, MPFR - MPIR have to be compiled with msvc2010 + #undef MPFR_USE_INTMAX_T // Since we cannot detect this, disable x64 by default + // Someone should change this manually if needed. + #endif + #endif + + #if defined (__MINGW32__) || defined(__MINGW64__) + #include // equivalent to msvc2010 + #elif defined (__GNUC__) + #if defined(__amd64__) || defined(__amd64) || defined(__x86_64__) || defined(__x86_64) + #undef MPREAL_HAVE_INT64_SUPPORT // remove all shaman dances for x64 builds since + #undef MPFR_USE_INTMAX_T // GCC already support x64 as of "long int" is 64-bit integer, nothing left to do + #else + #include // use int64_t, uint64_t otherwise. + #endif + #endif + +#endif + +#if defined(MPREAL_HAVE_MSVC_DEBUGVIEW) && defined(_MSC_VER) && defined(_DEBUG) +#define MPREAL_MSVC_DEBUGVIEW_CODE DebugView = toString() + #define MPREAL_MSVC_DEBUGVIEW_DATA std::string DebugView +#else + #define MPREAL_MSVC_DEBUGVIEW_CODE + #define MPREAL_MSVC_DEBUGVIEW_DATA +#endif + +#include + +#if (MPFR_VERSION < MPFR_VERSION_NUM(3,0,0)) + #include // needed for random() +#endif + namespace mpfr { class mpreal { @@ -99,19 +132,17 @@ private: mpfr_t mp; public: - static mp_rnd_t default_rnd; - static mp_prec_t default_prec; - static int default_base; - static int double_bits; - + static mp_rnd_t default_rnd; + static mp_prec_t default_prec; + static int default_base; + static int double_bits; + public: // Constructors && type conversion mpreal(); mpreal(const mpreal& u); - mpreal(const mpfr_t u); mpreal(const mpf_t u); - mpreal(const mpz_t u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); mpreal(const mpq_t u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); mpreal(const double u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); @@ -120,6 +151,12 @@ public: mpreal(const unsigned int u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); mpreal(const long int u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); mpreal(const int u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); + +#if defined (MPREAL_HAVE_INT64_SUPPORT) + mpreal(const uint64_t u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); + mpreal(const int64_t u, mp_prec_t prec = default_prec, mp_rnd_t mode = default_rnd); +#endif + mpreal(const char* s, mp_prec_t prec = default_prec, int base = default_base, mp_rnd_t mode = default_rnd); mpreal(const std::string& s, mp_prec_t prec = default_prec, int base = default_base, mp_rnd_t mode = default_rnd); @@ -155,6 +192,18 @@ public: mpreal& operator+=(const unsigned int u); mpreal& operator+=(const long int u); mpreal& operator+=(const int u); + +#if defined (MPREAL_HAVE_INT64_SUPPORT) + mpreal& operator+=(const int64_t u); + mpreal& operator+=(const uint64_t u); + mpreal& operator-=(const int64_t u); + mpreal& operator-=(const uint64_t u); + mpreal& operator*=(const int64_t u); + mpreal& operator*=(const uint64_t u); + mpreal& operator/=(const int64_t u); + mpreal& operator/=(const uint64_t u); +#endif + const mpreal operator+() const; mpreal& operator++ (); const mpreal operator++ (int); @@ -225,29 +274,49 @@ public: friend bool operator == (const mpreal& a, const mpreal& b); friend bool operator != (const mpreal& a, const mpreal& b); + // Optimized specializations for boolean operators + friend bool operator == (const mpreal& a, const unsigned long int b); + friend bool operator == (const mpreal& a, const unsigned int b); + friend bool operator == (const mpreal& a, const long int b); + friend bool operator == (const mpreal& a, const int b); + friend bool operator == (const mpreal& a, const long double b); + friend bool operator == (const mpreal& a, const double b); + // Type Conversion operators - inline operator long double() const; - inline operator double() const; - inline operator float() const; - inline operator unsigned long() const; - inline operator unsigned int() const; - inline operator long() const; - inline operator int() const; - operator std::string() const; - inline operator mpfr_ptr(); + long toLong() const; + unsigned long toULong() const; + double toDouble() const; + long double toLDouble() const; + +#if defined (MPREAL_HAVE_INT64_SUPPORT) + int64_t toInt64() const; + uint64_t toUInt64() const; +#endif + + // Get raw pointers + ::mpfr_ptr mpfr_ptr(); + ::mpfr_srcptr mpfr_srcptr() const; + + // Convert mpreal to string with n significant digits in base b + // n = 0 -> convert with the maximum available digits + std::string toString(int n = 0, int b = default_base, mp_rnd_t mode = default_rnd) const; + +#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) + std::string toString(const std::string& format) const; +#endif // Math Functions - friend const mpreal sqr(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal sqr (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal sqrt(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal sqrt(const unsigned long int v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal cbrt(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal root(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const mpreal& a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const mpreal& a, const mpz_t b, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const mpreal& a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const mpreal& a, const long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const unsigned long int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal pow(const unsigned long int a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const mpreal& a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const mpreal& a, const mpz_t b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const mpreal& a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const mpreal& a, const long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const unsigned long int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal pow (const unsigned long int a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal fabs(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal abs(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); @@ -264,8 +333,8 @@ public: friend const mpreal exp (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal exp2 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal exp10(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal log1p (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal expm1 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal log1p(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal expm1(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal cos(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal sin(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); @@ -279,15 +348,23 @@ public: friend const mpreal asin (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal atan (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal atan2 (const mpreal& y, const mpreal& x, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal acot (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal asec (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal acsc (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal cosh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal sinh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal tanh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal sech (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal csch (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal coth (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal acosh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal asinh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal atanh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal acosh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal asinh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal atanh (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal acoth (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal asech (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal acsch (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal hypot (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal fac_ui (unsigned long int v, mp_prec_t prec = mpreal::default_prec, mp_rnd_t rnd_mode = mpreal::default_rnd); @@ -299,12 +376,12 @@ public: friend const mpreal zeta (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal erf (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal erfc (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _j0 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _j1 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _jn (long n, const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _y0 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _y1 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); - friend const mpreal _yn (long n, const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal besselj0 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal besselj1 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal besseljn (long n, const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal bessely0 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal bessely1 (const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); + friend const mpreal besselyn (long n, const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal fma (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal fms (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal agm (const mpreal& v1, const mpreal& v2, mp_rnd_t rnd_mode = mpreal::default_rnd); @@ -324,9 +401,15 @@ public: friend const mpreal digamma(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal ai(const mpreal& v, mp_rnd_t rnd_mode = mpreal::default_rnd); friend const mpreal urandom (gmp_randstate_t& state,mp_rnd_t rnd_mode = mpreal::default_rnd); // use gmp_randinit_default() to init state, gmp_randclear() to clear - friend bool _isregular(const mpreal& v); + friend bool isregular(const mpreal& v); #endif - + + // Uniformly distributed random number generation in [0,1] using + // Mersenne-Twister algorithm by default. + // Use parameter to setup seed, e.g.: random((unsigned)time(NULL)) + // Check urandom() for more precise control. + friend const mpreal random(unsigned int seed = 0); + // Exponent and mantissa manipulation friend const mpreal frexp(const mpreal& v, mp_exp_t* exp); friend const mpreal ldexp(const mpreal& v, mp_exp_t exp); @@ -376,22 +459,27 @@ public: #endif // Instance Checkers - friend bool _isnan(const mpreal& v); - friend bool _isinf(const mpreal& v); - friend bool _isnum(const mpreal& v); - friend bool _iszero(const mpreal& v); - friend bool _isint(const mpreal& v); + friend bool isnan (const mpreal& v); + friend bool isinf (const mpreal& v); + friend bool isfinite(const mpreal& v); + + friend bool isnum(const mpreal& v); + friend bool iszero(const mpreal& v); + friend bool isint(const mpreal& v); // Set/Get instance properties inline mp_prec_t get_prec() const; - inline void set_prec(mp_prec_t prec, mp_rnd_t rnd_mode = default_rnd); // Change precision with rounding mode - - // Set mpreal to +-inf, NaN - void set_inf(int sign = +1); - void set_nan(); + inline void set_prec(mp_prec_t prec, mp_rnd_t rnd_mode = default_rnd); // Change precision with rounding mode - // sign = -1 or +1 - void set_sign(int sign, mp_rnd_t rnd_mode = default_rnd); + // Aliases for get_prec(), set_prec() - needed for compatibility with std::complex interface + inline mpreal& setPrecision(int Precision, mp_rnd_t RoundingMode = (mpfr_get_default_rounding_mode)()); + inline int getPrecision() const; + + // Set mpreal to +/- inf, NaN, +/-0 + mpreal& setInf (int Sign = +1); + mpreal& setNan (); + mpreal& setZero (int Sign = +1); + mpreal& setSign (int Sign, mp_rnd_t RoundingMode = (mpfr_get_default_rounding_mode)()); //Exponent mp_exp_t get_exp(); @@ -411,36 +499,25 @@ public: static int get_double_bits(); static void set_default_rnd(mp_rnd_t rnd_mode); static mp_rnd_t get_default_rnd(); - static mp_exp_t get_emin (void); - static mp_exp_t get_emax (void); - static mp_exp_t get_emin_min (void); - static mp_exp_t get_emin_max (void); - static mp_exp_t get_emax_min (void); - static mp_exp_t get_emax_max (void); - static int set_emin (mp_exp_t exp); - static int set_emax (mp_exp_t exp); + static mp_exp_t get_emin (void); + static mp_exp_t get_emax (void); + static mp_exp_t get_emin_min (void); + static mp_exp_t get_emin_max (void); + static mp_exp_t get_emax_min (void); + static mp_exp_t get_emax_max (void); + static int set_emin (mp_exp_t exp); + static int set_emax (mp_exp_t exp); - // Get/Set conversions - // Convert mpreal to string with n significant digits in base b - // n = 0 -> convert with the maximum available digits - std::string to_string(size_t n = 0, int b = default_base, mp_rnd_t mode = default_rnd) const; - // Efficient swapping of two mpreal values friend void swap(mpreal& x, mpreal& y); //Min Max - macros is evil. Needed for systems which defines max and min globally as macros (e.g. Windows) //Hope that globally defined macros use > < operations only - #ifndef max - friend const mpreal max(const mpreal& x, const mpreal& y); - #endif - - #ifndef min - friend const mpreal min(const mpreal& x, const mpreal& y); - #endif - friend const mpreal fmax(const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = default_rnd); friend const mpreal fmin(const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = default_rnd); +#if defined (MPREAL_HAVE_CUSTOM_MPFR_MALLOC) + private: // Optimized dynamic memory allocation/(re-)deallocation. static bool is_custom_malloc; @@ -448,6 +525,20 @@ private: static void *mpreal_reallocate (void *ptr, size_t old_size, size_t new_size); static void mpreal_free (void *ptr, size_t size); inline static void set_custom_malloc (void); + +#endif + + +private: + // Human friendly Debug Preview in Visual Studio. + // Put one of these lines: + // + // mpfr::mpreal= ; Show value only + // mpfr::mpreal=, bits ; Show value & precision + // + // at the beginning of + // [Visual Studio Installation Folder]\Common7\Packages\Debugger\autoexp.dat + MPREAL_MSVC_DEBUGVIEW_DATA }; ////////////////////////////////////////////////////////////////////////// @@ -457,190 +548,63 @@ public: std::string why() { return "inexact conversion from floating point"; } }; -////////////////////////////////////////////////////////////////////////// +namespace internal{ + + // Use SFINAE to restrict arithmetic operations instantiation only for numeric types + // This is needed for smooth integration with libraries based on expression templates + template struct result_type {}; + + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; + +#if defined (MPREAL_HAVE_INT64_SUPPORT) + template <> struct result_type {typedef mpreal type;}; + template <> struct result_type {typedef mpreal type;}; +#endif +} + // + Addition -const mpreal operator+(const mpreal& a, const mpreal& b); +template +inline const typename internal::result_type::type + operator+(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) += rhs; } -// + Fast specialized addition - implemented through fast += operations -const mpreal operator+(const mpreal& a, const mpz_t b); -const mpreal operator+(const mpreal& a, const mpq_t b); -const mpreal operator+(const mpreal& a, const long double b); -const mpreal operator+(const mpreal& a, const double b); -const mpreal operator+(const mpreal& a, const unsigned long int b); -const mpreal operator+(const mpreal& a, const unsigned int b); -const mpreal operator+(const mpreal& a, const long int b); -const mpreal operator+(const mpreal& a, const int b); -const mpreal operator+(const mpreal& a, const char* b); -const mpreal operator+(const char* a, const mpreal& b); -const std::string operator+(const mpreal& a, const std::string b); -const std::string operator+(const std::string a, const mpreal& b); +template +inline const typename internal::result_type::type + operator+(const Lhs& lhs, const mpreal& rhs){ return mpreal(rhs) += lhs; } -const mpreal operator+(const mpz_t b, const mpreal& a); -const mpreal operator+(const mpq_t b, const mpreal& a); -const mpreal operator+(const long double b, const mpreal& a); -const mpreal operator+(const double b, const mpreal& a); -const mpreal operator+(const unsigned long int b, const mpreal& a); -const mpreal operator+(const unsigned int b, const mpreal& a); -const mpreal operator+(const long int b, const mpreal& a); -const mpreal operator+(const int b, const mpreal& a); - -////////////////////////////////////////////////////////////////////////// // - Subtraction -const mpreal operator-(const mpreal& a, const mpreal& b); +template +inline const typename internal::result_type::type + operator-(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) -= rhs; } -// - Fast specialized subtraction - implemented through fast -= operations -const mpreal operator-(const mpreal& a, const mpz_t b); -const mpreal operator-(const mpreal& a, const mpq_t b); -const mpreal operator-(const mpreal& a, const long double b); -const mpreal operator-(const mpreal& a, const double b); -const mpreal operator-(const mpreal& a, const unsigned long int b); -const mpreal operator-(const mpreal& a, const unsigned int b); -const mpreal operator-(const mpreal& a, const long int b); -const mpreal operator-(const mpreal& a, const int b); -const mpreal operator-(const mpreal& a, const char* b); -const mpreal operator-(const char* a, const mpreal& b); +template +inline const typename internal::result_type::type + operator-(const Lhs& lhs, const mpreal& rhs){ return mpreal(lhs) -= rhs; } -const mpreal operator-(const mpz_t b, const mpreal& a); -const mpreal operator-(const mpq_t b, const mpreal& a); -const mpreal operator-(const long double b, const mpreal& a); -//const mpreal operator-(const double b, const mpreal& a); - -////////////////////////////////////////////////////////////////////////// // * Multiplication -const mpreal operator*(const mpreal& a, const mpreal& b); +template +inline const typename internal::result_type::type + operator*(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) *= rhs; } -// * Fast specialized multiplication - implemented through fast *= operations -const mpreal operator*(const mpreal& a, const mpz_t b); -const mpreal operator*(const mpreal& a, const mpq_t b); -const mpreal operator*(const mpreal& a, const long double b); -const mpreal operator*(const mpreal& a, const double b); -const mpreal operator*(const mpreal& a, const unsigned long int b); -const mpreal operator*(const mpreal& a, const unsigned int b); -const mpreal operator*(const mpreal& a, const long int b); -const mpreal operator*(const mpreal& a, const int b); +template +inline const typename internal::result_type::type + operator*(const Lhs& lhs, const mpreal& rhs){ return mpreal(rhs) *= lhs; } -const mpreal operator*(const mpz_t b, const mpreal& a); -const mpreal operator*(const mpq_t b, const mpreal& a); -const mpreal operator*(const long double b, const mpreal& a); -const mpreal operator*(const double b, const mpreal& a); -const mpreal operator*(const unsigned long int b, const mpreal& a); -const mpreal operator*(const unsigned int b, const mpreal& a); -const mpreal operator*(const long int b, const mpreal& a); -const mpreal operator*(const int b, const mpreal& a); - -////////////////////////////////////////////////////////////////////////// // / Division -const mpreal operator/(const mpreal& a, const mpreal& b); +template +inline const typename internal::result_type::type + operator/(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) /= rhs; } -// / Fast specialized division - implemented through fast /= operations -const mpreal operator/(const mpreal& a, const mpz_t b); -const mpreal operator/(const mpreal& a, const mpq_t b); -const mpreal operator/(const mpreal& a, const long double b); -const mpreal operator/(const mpreal& a, const double b); -const mpreal operator/(const mpreal& a, const unsigned long int b); -const mpreal operator/(const mpreal& a, const unsigned int b); -const mpreal operator/(const mpreal& a, const long int b); -const mpreal operator/(const mpreal& a, const int b); - -const mpreal operator/(const long double b, const mpreal& a); - -////////////////////////////////////////////////////////////////////////// -// Shifts operators - Multiplication/Division by a power of 2 -const mpreal operator<<(const mpreal& v, const unsigned long int k); -const mpreal operator<<(const mpreal& v, const unsigned int k); -const mpreal operator<<(const mpreal& v, const long int k); -const mpreal operator<<(const mpreal& v, const int k); - -const mpreal operator>>(const mpreal& v, const unsigned long int k); -const mpreal operator>>(const mpreal& v, const unsigned int k); -const mpreal operator>>(const mpreal& v, const long int k); -const mpreal operator>>(const mpreal& v, const int k); - -////////////////////////////////////////////////////////////////////////// -// Boolean operators -bool operator < (const mpreal& a, const unsigned long int b); -bool operator < (const mpreal& a, const unsigned int b); -bool operator < (const mpreal& a, const long int b); -bool operator < (const mpreal& a, const int b); -bool operator < (const mpreal& a, const long double b); -bool operator < (const mpreal& a, const double b); - -bool operator < (const unsigned long int a,const mpreal& b); -bool operator < (const unsigned int a, const mpreal& b); -bool operator < (const long int a, const mpreal& b); -bool operator < (const int a, const mpreal& b); -bool operator < (const long double a, const mpreal& b); -bool operator < (const double a, const mpreal& b); - -bool operator > (const mpreal& a, const unsigned long int b); -bool operator > (const mpreal& a, const unsigned int b); -bool operator > (const mpreal& a, const long int b); -bool operator > (const mpreal& a, const int b); -bool operator > (const mpreal& a, const long double b); -bool operator > (const mpreal& a, const double b); - -bool operator > (const unsigned long int a,const mpreal& b); -bool operator > (const unsigned int a, const mpreal& b); -bool operator > (const long int a, const mpreal& b); -bool operator > (const int a, const mpreal& b); -bool operator > (const long double a, const mpreal& b); -bool operator > (const double a, const mpreal& b); - -bool operator >= (const mpreal& a, const unsigned long int b); -bool operator >= (const mpreal& a, const unsigned int b); -bool operator >= (const mpreal& a, const long int b); -bool operator >= (const mpreal& a, const int b); -bool operator >= (const mpreal& a, const long double b); -bool operator >= (const mpreal& a, const double b); - -bool operator >= (const unsigned long int a,const mpreal& b); -bool operator >= (const unsigned int a, const mpreal& b); -bool operator >= (const long int a, const mpreal& b); -bool operator >= (const int a, const mpreal& b); -bool operator >= (const long double a, const mpreal& b); -bool operator >= (const double a, const mpreal& b); - -bool operator <= (const mpreal& a, const unsigned long int b); -bool operator <= (const mpreal& a, const unsigned int b); -bool operator <= (const mpreal& a, const long int b); -bool operator <= (const mpreal& a, const int b); -bool operator <= (const mpreal& a, const long double b); -bool operator <= (const mpreal& a, const double b); - -bool operator <= (const unsigned long int a,const mpreal& b); -bool operator <= (const unsigned int a, const mpreal& b); -bool operator <= (const long int a, const mpreal& b); -bool operator <= (const int a, const mpreal& b); -bool operator <= (const long double a, const mpreal& b); -bool operator <= (const double a, const mpreal& b); - -bool operator == (const mpreal& a, const unsigned long int b); -bool operator == (const mpreal& a, const unsigned int b); -bool operator == (const mpreal& a, const long int b); -bool operator == (const mpreal& a, const int b); -bool operator == (const mpreal& a, const long double b); -bool operator == (const mpreal& a, const double b); - -bool operator == (const unsigned long int a,const mpreal& b); -bool operator == (const unsigned int a, const mpreal& b); -bool operator == (const long int a, const mpreal& b); -bool operator == (const int a, const mpreal& b); -bool operator == (const long double a, const mpreal& b); -bool operator == (const double a, const mpreal& b); - -bool operator != (const mpreal& a, const unsigned long int b); -bool operator != (const mpreal& a, const unsigned int b); -bool operator != (const mpreal& a, const long int b); -bool operator != (const mpreal& a, const int b); -bool operator != (const mpreal& a, const long double b); -bool operator != (const mpreal& a, const double b); - -bool operator != (const unsigned long int a,const mpreal& b); -bool operator != (const unsigned int a, const mpreal& b); -bool operator != (const long int a, const mpreal& b); -bool operator != (const int a, const mpreal& b); -bool operator != (const long double a, const mpreal& b); -bool operator != (const double a, const mpreal& b); +template +inline const typename internal::result_type::type + operator/(const Lhs& lhs, const mpreal& rhs){ return mpreal(lhs) /= rhs; } ////////////////////////////////////////////////////////////////////////// // sqrt @@ -704,22 +668,45 @@ const mpreal pow(const double a, const int b, mp_rnd_t rnd_mode = mpreal::defaul ////////////////////////////////////////////////////////////////////////// // Estimate machine epsilon for the given precision -inline const mpreal machine_epsilon(mp_prec_t prec = mpreal::default_prec); -inline const mpreal mpreal_min(mp_prec_t prec = mpreal::default_prec); -inline const mpreal mpreal_max(mp_prec_t prec = mpreal::default_prec); +// Returns smallest eps such that 1.0 + eps != 1.0 +inline const mpreal machine_epsilon(mp_prec_t prec = mpreal::get_default_prec()); + +// Returns the positive distance from abs(x) to the next larger in magnitude floating point number of the same precision as x +inline const mpreal machine_epsilon(const mpreal& x); + +inline const mpreal mpreal_min(mp_prec_t prec = mpreal::get_default_prec()); +inline const mpreal mpreal_max(mp_prec_t prec = mpreal::get_default_prec()); +inline bool isEqualFuzzy(const mpreal& a, const mpreal& b, const mpreal& eps); +inline bool isEqualUlps(const mpreal& a, const mpreal& b, int maxUlps); ////////////////////////////////////////////////////////////////////////// -// Implementation of inline functions +// Bits - decimal digits relation +// bits = ceil(digits*log[2](10)) +// digits = floor(bits*log[10](2)) + +inline mp_prec_t digits2bits(int d); +inline int bits2digits(mp_prec_t b); + +////////////////////////////////////////////////////////////////////////// +// min, max +const mpreal (max)(const mpreal& x, const mpreal& y); +const mpreal (min)(const mpreal& x, const mpreal& y); + +////////////////////////////////////////////////////////////////////////// +// Implementation ////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////// // Operators - Assignment inline mpreal& mpreal::operator=(const mpreal& v) { - if (this!= &v) + if (this != &v) { - mpfr_set_prec(mp,mpfr_get_prec(v.mp)); + mpfr_clear(mp); + mpfr_init2(mp,mpfr_get_prec(v.mp)); mpfr_set(mp,v.mp,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } return *this; } @@ -727,24 +714,32 @@ inline mpreal& mpreal::operator=(const mpreal& v) inline mpreal& mpreal::operator=(const mpf_t v) { mpfr_set_f(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const mpz_t v) { mpfr_set_z(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const mpq_t v) { mpfr_set_q(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const long double v) { mpfr_set_ld(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } @@ -753,6 +748,8 @@ inline mpreal& mpreal::operator=(const double v) if(double_bits == -1 || fits_in_bits(v, double_bits)) { mpfr_set_d(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; } else throw conversion_overflow(); @@ -763,24 +760,32 @@ inline mpreal& mpreal::operator=(const double v) inline mpreal& mpreal::operator=(const unsigned long int v) { mpfr_set_ui(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const unsigned int v) { mpfr_set_ui(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const long int v) { mpfr_set_si(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator=(const int v) { mpfr_set_si(mp,v,default_rnd); + + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } @@ -789,70 +794,90 @@ inline mpreal& mpreal::operator=(const int v) inline mpreal& mpreal::operator+=(const mpreal& v) { mpfr_add(mp,mp,v.mp,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const mpf_t u) { *this += mpreal(u); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const mpz_t u) { mpfr_add_z(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const mpq_t u) { mpfr_add_q(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+= (const long double u) { - return *this += mpreal(u); + *this += mpreal(u); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator+= (const double u) { #if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) mpfr_add_d(mp,mp,u,default_rnd); - return *this; #else - return *this += mpreal(u); + *this += mpreal(u); #endif + + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator+=(const unsigned long int u) { mpfr_add_ui(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const unsigned int u) { mpfr_add_ui(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const long int u) { mpfr_add_si(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator+=(const int u) { mpfr_add_si(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } -inline const mpreal mpreal::operator+()const -{ - return mpreal(*this); -} +#if defined (MPREAL_HAVE_INT64_SUPPORT) +inline mpreal& mpreal::operator+=(const int64_t u){ *this += mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator+=(const uint64_t u){ *this += mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator-=(const int64_t u){ *this -= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator-=(const uint64_t u){ *this -= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator*=(const int64_t u){ *this *= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator*=(const uint64_t u){ *this *= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator/=(const int64_t u){ *this /= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +inline mpreal& mpreal::operator/=(const uint64_t u){ *this /= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } +#endif + +inline const mpreal mpreal::operator+()const { return mpreal(*this); } inline const mpreal operator+(const mpreal& a, const mpreal& b) { @@ -861,111 +886,9 @@ inline const mpreal operator+(const mpreal& a, const mpreal& b) else return mpreal(b) += a; } -inline const std::string operator+(const mpreal& a, const std::string b) -{ - return (std::string)a+b; -} - -inline const std::string operator+(const std::string a, const mpreal& b) -{ - return a+(std::string)b; -} - -inline const mpreal operator+(const mpreal& a, const mpz_t b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const char* b) -{ - return a+mpreal(b); -} - -inline const mpreal operator+(const char* a, const mpreal& b) -{ - return mpreal(a)+b; - -} - -inline const mpreal operator+(const mpreal& a, const mpq_t b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const long double b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const double b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const unsigned long int b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const unsigned int b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const long int b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpreal& a, const int b) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpz_t b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const mpq_t b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const long double b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const double b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const unsigned long int b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const unsigned int b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const long int b, const mpreal& a) -{ - return mpreal(a) += b; -} - -inline const mpreal operator+(const int b, const mpreal& a) -{ - return mpreal(a) += b; -} - inline mpreal& mpreal::operator++() { - *this += 1; - return *this; + return *this += 1; } inline const mpreal mpreal::operator++ (int) @@ -977,8 +900,7 @@ inline const mpreal mpreal::operator++ (int) inline mpreal& mpreal::operator--() { - *this -= 1; - return *this; + return *this -= 1; } inline const mpreal mpreal::operator-- (int) @@ -993,57 +915,68 @@ inline const mpreal mpreal::operator-- (int) inline mpreal& mpreal::operator-= (const mpreal& v) { mpfr_sub(mp,mp,v.mp,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const mpz_t v) { mpfr_sub_z(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const mpq_t v) { mpfr_sub_q(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const long double v) { - return *this -= mpreal(v); + *this -= mpreal(v); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator-=(const double v) { #if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) mpfr_sub_d(mp,mp,v,default_rnd); - return *this; #else - return *this -= mpreal(v); + *this -= mpreal(v); #endif + + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator-=(const unsigned long int v) { mpfr_sub_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const unsigned int v) { mpfr_sub_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const long int v) { mpfr_sub_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator-=(const int v) { mpfr_sub_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } @@ -1057,63 +990,14 @@ inline const mpreal mpreal::operator-()const inline const mpreal operator-(const mpreal& a, const mpreal& b) { // prec(a-b) = max(prec(a),prec(b)) - if(a.get_prec()>b.get_prec()) return mpreal(a) -= b; - else return -(mpreal(b) -= a); -} - -inline const mpreal operator-(const mpreal& a, const mpz_t b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const mpq_t b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const long double b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const double b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const unsigned long int b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const unsigned int b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const long int b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpreal& a, const int b) -{ - return mpreal(a) -= b; -} - -inline const mpreal operator-(const mpz_t b, const mpreal& a) -{ - return -(mpreal(a) -= b); -} - -inline const mpreal operator-(const mpq_t b, const mpreal& a) -{ - return -(mpreal(a) -= b); -} - -inline const mpreal operator-(const long double b, const mpreal& a) -{ - return -(mpreal(a) -= b); + if(a.getPrecision() >= b.getPrecision()) + { + return mpreal(a) -= b; + }else{ + mpreal x(a); + x.setPrecision(b.getPrecision()); + return x -= b; + } } inline const mpreal operator-(const double b, const mpreal& a) @@ -1123,7 +1007,7 @@ inline const mpreal operator-(const double b, const mpreal& a) mpfr_d_sub(x.mp,b,a.mp,mpreal::default_rnd); return x; #else - return -(mpreal(a) -= b); + return mpreal(b) -= a; #endif } @@ -1155,160 +1039,81 @@ inline const mpreal operator-(const int b, const mpreal& a) return x; } -inline const mpreal operator-(const mpreal& a, const char* b) -{ - return a-mpreal(b); -} - -inline const mpreal operator-(const char* a, const mpreal& b) -{ - return mpreal(a)-b; -} - ////////////////////////////////////////////////////////////////////////// // * Multiplication inline mpreal& mpreal::operator*= (const mpreal& v) { mpfr_mul(mp,mp,v.mp,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const mpz_t v) { mpfr_mul_z(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const mpq_t v) { mpfr_mul_q(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const long double v) { - return *this *= mpreal(v); + *this *= mpreal(v); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator*=(const double v) { #if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) mpfr_mul_d(mp,mp,v,default_rnd); - return *this; #else - return *this *= mpreal(v); + *this *= mpreal(v); #endif + + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator*=(const unsigned long int v) { mpfr_mul_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const unsigned int v) { mpfr_mul_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const long int v) { mpfr_mul_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator*=(const int v) { mpfr_mul_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline const mpreal operator*(const mpreal& a, const mpreal& b) { // prec(a*b) = max(prec(a),prec(b)) - if(a.get_prec()>b.get_prec()) return mpreal(a) *= b; - else return mpreal(b) *= a; -} - -inline const mpreal operator*(const mpreal& a, const mpz_t b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const mpq_t b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const long double b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const double b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const unsigned long int b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const unsigned int b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const long int b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpreal& a, const int b) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpz_t b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const mpq_t b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const long double b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const double b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const unsigned long int b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const unsigned int b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const long int b, const mpreal& a) -{ - return mpreal(a) *= b; -} - -inline const mpreal operator*(const int b, const mpreal& a) -{ - return mpreal(a) *= b; + if(a.getPrecision() >= b.getPrecision()) return mpreal(a) *= b; + else return mpreal(b) *= a; } ////////////////////////////////////////////////////////////////////////// @@ -1316,112 +1121,82 @@ inline const mpreal operator*(const int b, const mpreal& a) inline mpreal& mpreal::operator/=(const mpreal& v) { mpfr_div(mp,mp,v.mp,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const mpz_t v) { mpfr_div_z(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const mpq_t v) { mpfr_div_q(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const long double v) { - return *this /= mpreal(v); + *this /= mpreal(v); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator/=(const double v) { #if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) mpfr_div_d(mp,mp,v,default_rnd); - return *this; #else - return *this /= mpreal(v); + *this /= mpreal(v); #endif + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mpreal& mpreal::operator/=(const unsigned long int v) { mpfr_div_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const unsigned int v) { mpfr_div_ui(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const long int v) { mpfr_div_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator/=(const int v) { mpfr_div_si(mp,mp,v,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline const mpreal operator/(const mpreal& a, const mpreal& b) { - mpreal x(a); - mp_prec_t pb; - mp_prec_t pa; - // prec(a/b) = max(prec(a),prec(b)) - pa = a.get_prec(); - pb = b.get_prec(); - if(pb>pa) x.set_prec(pb); + if(a.getPrecision() >= b.getPrecision()) + { + return mpreal(a) /= b; + }else{ - return x /= b; -} - -inline const mpreal operator/(const mpreal& a, const mpz_t b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const mpq_t b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const long double b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const double b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const unsigned long int b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const unsigned int b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const long int b) -{ - return mpreal(a) /= b; -} - -inline const mpreal operator/(const mpreal& a, const int b) -{ - return mpreal(a) /= b; + mpreal x(a); + x.setPrecision(b.getPrecision()); + return x /= b; + } } inline const mpreal operator/(const unsigned long int b, const mpreal& a) @@ -1452,12 +1227,6 @@ inline const mpreal operator/(const int b, const mpreal& a) return x; } -inline const mpreal operator/(const long double b, const mpreal& a) -{ - mpreal x(b); - return x/a; -} - inline const mpreal operator/(const double b, const mpreal& a) { #if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0)) @@ -1465,8 +1234,7 @@ inline const mpreal operator/(const double b, const mpreal& a) mpfr_d_div(x.mp,b,a.mp,mpreal::default_rnd); return x; #else - mpreal x(b); - return x/a; + return mpreal(b) /= a; #endif } @@ -1475,48 +1243,56 @@ inline const mpreal operator/(const double b, const mpreal& a) inline mpreal& mpreal::operator<<=(const unsigned long int u) { mpfr_mul_2ui(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator<<=(const unsigned int u) { mpfr_mul_2ui(mp,mp,static_cast(u),default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator<<=(const long int u) { mpfr_mul_2si(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator<<=(const int u) { mpfr_mul_2si(mp,mp,static_cast(u),default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator>>=(const unsigned long int u) { mpfr_div_2ui(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator>>=(const unsigned int u) { mpfr_div_2ui(mp,mp,static_cast(u),default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator>>=(const long int u) { mpfr_div_2si(mp,mp,u,default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } inline mpreal& mpreal::operator>>=(const int u) { mpfr_div_2si(mp,mp,static_cast(u),default_rnd); + MPREAL_MSVC_DEBUGVIEW_CODE; return *this; } @@ -1592,468 +1368,67 @@ inline const mpreal div_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode) ////////////////////////////////////////////////////////////////////////// //Boolean operators -inline bool operator > (const mpreal& a, const mpreal& b) -{ - return (mpfr_greater_p(a.mp,b.mp)!=0); -} - -inline bool operator > (const mpreal& a, const unsigned long int b) -{ - return a>mpreal(b); -} - -inline bool operator > (const mpreal& a, const unsigned int b) -{ - return a>mpreal(b); -} - -inline bool operator > (const mpreal& a, const long int b) -{ - return a>mpreal(b); -} - -inline bool operator > (const mpreal& a, const int b) -{ - return a>mpreal(b); -} - -inline bool operator > (const mpreal& a, const long double b) -{ - return a>mpreal(b); -} - -inline bool operator > (const mpreal& a, const double b) -{ - return a>mpreal(b); -} - -inline bool operator > (const unsigned long int a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator > (const unsigned int a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator > (const long int a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator > (const int a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator > (const long double a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator > (const double a, const mpreal& b) -{ - return mpreal(a)>b; -} - -inline bool operator >= (const mpreal& a, const mpreal& b) -{ - return (mpfr_greaterequal_p(a.mp,b.mp)!=0); -} - -inline bool operator >= (const mpreal& a, const unsigned long int b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const mpreal& a, const unsigned int b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const mpreal& a, const long int b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const mpreal& a, const int b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const mpreal& a, const long double b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const mpreal& a, const double b) -{ - return a>=mpreal(b); -} - -inline bool operator >= (const unsigned long int a,const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator >= (const unsigned int a, const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator >= (const long int a, const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator >= (const int a, const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator >= (const long double a, const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator >= (const double a, const mpreal& b) -{ - return mpreal(a)>=b; -} - -inline bool operator < (const mpreal& a, const mpreal& b) -{ - return (mpfr_less_p(a.mp,b.mp)!=0); -} - -inline bool operator < (const mpreal& a, const unsigned long int b) -{ - return a (const mpreal& a, const mpreal& b){ return (mpfr_greater_p(a.mp,b.mp) !=0); } +inline bool operator >= (const mpreal& a, const mpreal& b){ return (mpfr_greaterequal_p(a.mp,b.mp) !=0); } +inline bool operator < (const mpreal& a, const mpreal& b){ return (mpfr_less_p(a.mp,b.mp) !=0); } +inline bool operator <= (const mpreal& a, const mpreal& b){ return (mpfr_lessequal_p(a.mp,b.mp) !=0); } +inline bool operator == (const mpreal& a, const mpreal& b){ return (mpfr_equal_p(a.mp,b.mp) !=0); } +inline bool operator != (const mpreal& a, const mpreal& b){ return (mpfr_lessgreater_p(a.mp,b.mp) !=0); } + +inline bool operator == (const mpreal& a, const unsigned long int b ){ return (mpfr_cmp_ui(a.mp,b) == 0); } +inline bool operator == (const mpreal& a, const unsigned int b ){ return (mpfr_cmp_ui(a.mp,b) == 0); } +inline bool operator == (const mpreal& a, const long int b ){ return (mpfr_cmp_si(a.mp,b) == 0); } +inline bool operator == (const mpreal& a, const int b ){ return (mpfr_cmp_si(a.mp,b) == 0); } +inline bool operator == (const mpreal& a, const long double b ){ return (mpfr_cmp_ld(a.mp,b) == 0); } +inline bool operator == (const mpreal& a, const double b ){ return (mpfr_cmp_d(a.mp,b) == 0); } + + +inline bool isnan (const mpreal& v){ return (mpfr_nan_p(v.mp) != 0); } +inline bool isinf (const mpreal& v){ return (mpfr_inf_p(v.mp) != 0); } +inline bool isfinite(const mpreal& v){ return (mpfr_number_p(v.mp) != 0); } +inline bool iszero (const mpreal& v){ return (mpfr_zero_p(v.mp) != 0); } +inline bool isint (const mpreal& v){ return (mpfr_integer_p(v.mp) != 0); } #if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0)) -inline bool _isregular(const mpreal& v) -{ - return (mpfr_regular_p(v.mp)); -} -#endif // MPFR 3.0.0 Specifics +inline bool isregular(const mpreal& v){ return (mpfr_regular_p(v.mp));} +#endif ////////////////////////////////////////////////////////////////////////// // Type Converters -inline mpreal::operator double() const +inline long mpreal::toLong() const { return mpfr_get_si(mp,GMP_RNDZ); } +inline unsigned long mpreal::toULong() const { return mpfr_get_ui(mp,GMP_RNDZ); } +inline double mpreal::toDouble() const { return mpfr_get_d(mp,default_rnd); } +inline long double mpreal::toLDouble() const { return mpfr_get_ld(mp,default_rnd); } + +#if defined (MPREAL_HAVE_INT64_SUPPORT) +inline int64_t mpreal::toInt64() const{ return mpfr_get_sj(mp,GMP_RNDZ); } +inline uint64_t mpreal::toUInt64() const{ return mpfr_get_uj(mp,GMP_RNDZ); } +#endif + +inline ::mpfr_ptr mpreal::mpfr_ptr() { return mp; } +inline ::mpfr_srcptr mpreal::mpfr_srcptr() const { return const_cast< ::mpfr_srcptr >(mp); } + +////////////////////////////////////////////////////////////////////////// +// Bits - decimal digits relation +// bits = ceil(digits*log[2](10)) +// digits = floor(bits*log[10](2)) + +inline mp_prec_t digits2bits(int d) { - return mpfr_get_d(mp,default_rnd); + const double LOG2_10 = 3.3219280948873624; + + d = 10>d?10:d; + + return (mp_prec_t)std::ceil((d)*LOG2_10); } -inline mpreal::operator float() const +inline int bits2digits(mp_prec_t b) { - return (float)mpfr_get_d(mp,default_rnd); -} + const double LOG10_2 = 0.30102999566398119; -inline mpreal::operator long double() const -{ - return mpfr_get_ld(mp,default_rnd); -} + b = 34>b?34:b; -inline mpreal::operator unsigned long() const -{ - return mpfr_get_ui(mp,GMP_RNDZ); -} - -inline mpreal::operator unsigned int() const -{ - return static_cast(mpfr_get_ui(mp,GMP_RNDZ)); -} - -inline mpreal::operator long() const -{ - return mpfr_get_si(mp,GMP_RNDZ); -} - -inline mpreal::operator int() const -{ - return static_cast(mpfr_get_si(mp,GMP_RNDZ)); -} - -inline mpreal::operator mpfr_ptr() -{ - return mp; + return (int)std::floor((b)*LOG10_2); } ////////////////////////////////////////////////////////////////////////// @@ -2064,9 +1439,44 @@ inline int sgn(const mpreal& v) return (r>0?-1:1); } -inline void mpreal::set_sign(int sign, mp_rnd_t rnd_mode) +inline mpreal& mpreal::setSign(int sign, mp_rnd_t RoundingMode) { - mpfr_setsign(mp,mp,(sign<0?1:0),rnd_mode); + mpfr_setsign(mp,mp,(sign<0?1:0),RoundingMode); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; +} + +inline int mpreal::getPrecision() const +{ + return mpfr_get_prec(mp); +} + +inline mpreal& mpreal::setPrecision(int Precision, mp_rnd_t RoundingMode) +{ + mpfr_prec_round(mp,Precision, RoundingMode); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; +} + +inline mpreal& mpreal::setInf(int sign) +{ + mpfr_set_inf(mp,sign); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; +} + +inline mpreal& mpreal::setNan() +{ + mpfr_set_nan(mp); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; +} + +inline mpreal& mpreal::setZero(int sign) +{ + mpfr_set_zero(mp,sign); + MPREAL_MSVC_DEBUGVIEW_CODE; + return *this; } inline mp_prec_t mpreal::get_prec() const @@ -2077,16 +1487,7 @@ inline mp_prec_t mpreal::get_prec() const inline void mpreal::set_prec(mp_prec_t prec, mp_rnd_t rnd_mode) { mpfr_prec_round(mp,prec,rnd_mode); -} - -inline void mpreal::set_inf(int sign) -{ - mpfr_set_inf(mp,sign); -} - -inline void mpreal::set_nan() -{ - mpfr_set_nan(mp); + MPREAL_MSVC_DEBUGVIEW_CODE; } inline mp_exp_t mpreal::get_exp () @@ -2096,7 +1497,9 @@ inline mp_exp_t mpreal::get_exp () inline int mpreal::set_exp (mp_exp_t e) { - return mpfr_set_exp(mp,e); + int x = mpfr_set_exp(mp, e); + MPREAL_MSVC_DEBUGVIEW_CODE; + return x; } inline const mpreal frexp(const mpreal& v, mp_exp_t* exp) @@ -2120,16 +1523,24 @@ inline const mpreal machine_epsilon(mp_prec_t prec) { // the smallest eps such that 1.0+eps != 1.0 // depends (of cause) on the precision - mpreal x(1,prec); - return nextabove(x)-x; + return machine_epsilon(mpreal(1,prec)); +} + +inline const mpreal machine_epsilon(const mpreal& x) +{ + if( x < 0) + { + return nextabove(-x)+x; + }else{ + return nextabove(x)-x; + } } inline const mpreal mpreal_min(mp_prec_t prec) { // min = 1/2*2^emin = 2^(emin-1) - - mpreal x(1,prec); - return x <<= mpreal::get_emin()-1; + + return mpreal(1,prec) << mpreal::get_emin()-1; } inline const mpreal mpreal_max(mp_prec_t prec) @@ -2138,8 +1549,25 @@ inline const mpreal mpreal_max(mp_prec_t prec) // and use emax-1 to prevent value to be +inf // max = 2^(emax-1) - mpreal x(1,prec); - return x <<= mpreal::get_emax()-1; + return mpreal(1,prec) << mpreal::get_emax()-1; +} + +inline bool isEqualUlps(const mpreal& a, const mpreal& b, int maxUlps) +{ + /* + maxUlps - a and b can be apart by maxUlps binary numbers. + */ + return abs(a - b) <= machine_epsilon((max)(abs(a), abs(b))) * maxUlps; +} + +inline bool isEqualFuzzy(const mpreal& a, const mpreal& b, const mpreal& eps) +{ + return abs(a - b) <= (min)(abs(a), abs(b)) * eps; +} + +inline bool isEqualFuzzy(const mpreal& a, const mpreal& b) +{ + return isEqualFuzzy(a,b,machine_epsilon((std::min)(abs(a), abs(b)))); } inline const mpreal modf(const mpreal& v, mpreal& n) @@ -2159,7 +1587,9 @@ inline int mpreal::check_range (int t, mp_rnd_t rnd_mode) inline int mpreal::subnormalize (int t,mp_rnd_t rnd_mode) { - return mpfr_subnormalize(mp,t,rnd_mode); + int r = mpfr_subnormalize(mp,t,rnd_mode); + MPREAL_MSVC_DEBUGVIEW_CODE; + return r; } inline mp_exp_t mpreal::get_emin (void) @@ -2234,13 +1664,13 @@ inline const mpreal sqrt(const unsigned int v, mp_rnd_t rnd_mode) inline const mpreal sqrt(const long int v, mp_rnd_t rnd_mode) { if (v>=0) return sqrt(static_cast(v),rnd_mode); - else return mpreal(); // NaN + else return mpreal().setNan(); // NaN } inline const mpreal sqrt(const int v, mp_rnd_t rnd_mode) { if (v>=0) return sqrt(static_cast(v),rnd_mode); - else return mpreal(); // NaN + else return mpreal().setNan(); // NaN } inline const mpreal sqrt(const long double v, mp_rnd_t rnd_mode) @@ -2403,6 +1833,36 @@ inline const mpreal atan (const mpreal& v, mp_rnd_t rnd_mode) return x; } +inline const mpreal acot (const mpreal& v, mp_rnd_t rnd_mode) +{ + return atan(1/v, rnd_mode); +} + +inline const mpreal asec (const mpreal& v, mp_rnd_t rnd_mode) +{ + return acos(1/v, rnd_mode); +} + +inline const mpreal acsc (const mpreal& v, mp_rnd_t rnd_mode) +{ + return asin(1/v, rnd_mode); +} + +inline const mpreal acoth (const mpreal& v, mp_rnd_t rnd_mode) +{ + return atanh(1/v, rnd_mode); +} + +inline const mpreal asech (const mpreal& v, mp_rnd_t rnd_mode) +{ + return acosh(1/v, rnd_mode); +} + +inline const mpreal acsch (const mpreal& v, mp_rnd_t rnd_mode) +{ + return asinh(1/v, rnd_mode); +} + inline const mpreal atan2 (const mpreal& y, const mpreal& x, mp_rnd_t rnd_mode) { mpreal a; @@ -2481,6 +1941,36 @@ inline const mpreal atanh (const mpreal& v, mp_rnd_t rnd_mode) return x; } +inline const mpreal hypot (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode) +{ + mpreal a; + mp_prec_t yp, xp; + + yp = y.get_prec(); + xp = x.get_prec(); + + a.set_prec(yp>xp?yp:xp); + + mpfr_hypot(a.mp, x.mp, y.mp, rnd_mode); + + return a; +} + +inline const mpreal remainder (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode) +{ + mpreal a; + mp_prec_t yp, xp; + + yp = y.get_prec(); + xp = x.get_prec(); + + a.set_prec(yp>xp?yp:xp); + + mpfr_remainder(a.mp, x.mp, y.mp, rnd_mode); + + return a; +} + inline const mpreal fac_ui (unsigned long int v, mp_prec_t prec, mp_rnd_t rnd_mode) { mpreal x(0,prec); @@ -2509,11 +1999,15 @@ inline const mpreal eint (const mpreal& v, mp_rnd_t rnd_mode) return x; } -inline const mpreal gamma (const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal gamma (const mpreal& x, mp_rnd_t rnd_mode) { - mpreal x(v); - mpfr_gamma(x.mp,v.mp,rnd_mode); - return x; + mpreal FunctionValue(x); + + // x < 0: gamma(-x) = -pi/(x * gamma(x) * sin(pi*x)) + + mpfr_gamma(FunctionValue.mp, x.mp, rnd_mode); + + return FunctionValue; } inline const mpreal lngamma (const mpreal& v, mp_rnd_t rnd_mode) @@ -2557,42 +2051,42 @@ inline const mpreal erfc (const mpreal& v, mp_rnd_t rnd_mode) return x; } -inline const mpreal _j0 (const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal besselj0 (const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_j0(x.mp,v.mp,rnd_mode); return x; } -inline const mpreal _j1 (const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal besselj1 (const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_j1(x.mp,v.mp,rnd_mode); return x; } -inline const mpreal _jn (long n, const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal besseljn (long n, const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_jn(x.mp,n,v.mp,rnd_mode); return x; } -inline const mpreal _y0 (const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal bessely0 (const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_y0(x.mp,v.mp,rnd_mode); return x; } -inline const mpreal _y1 (const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal bessely1 (const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_y1(x.mp,v.mp,rnd_mode); return x; } -inline const mpreal _yn (long n, const mpreal& v, mp_rnd_t rnd_mode) +inline const mpreal besselyn (long n, const mpreal& v, mp_rnd_t rnd_mode) { mpreal x(v); mpfr_yn(x.mp,n,v.mp,rnd_mode); @@ -2780,7 +2274,6 @@ inline void swap(mpreal& a, mpreal& b) mpfr_swap(a.mp,b.mp); } - inline const mpreal (max)(const mpreal& x, const mpreal& y) { return (x>y?x:y); @@ -2835,7 +2328,7 @@ inline const mpreal urandomb (gmp_randstate_t& state) #if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0)) // use gmp_randinit_default() to init state, gmp_randclear() to clear -inline const mpreal urandom (gmp_randstate_t& state,mp_rnd_t rnd_mode) +inline const mpreal urandom (gmp_randstate_t& state, mp_rnd_t rnd_mode) { mpreal x; mpfr_urandom(x.mp,state,rnd_mode); @@ -2852,6 +2345,34 @@ inline const mpreal random2 (mp_size_t size, mp_exp_t exp) } #endif +// Uniformly distributed random number generation +// a = random(seed); <- initialization & first random number generation +// a = random(); <- next random numbers generation +// seed != 0 +inline const mpreal random(unsigned int seed) +{ + +#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0)) + static gmp_randstate_t state; + static bool isFirstTime = true; + + if(isFirstTime) + { + gmp_randinit_default(state); + gmp_randseed_ui(state,0); + isFirstTime = false; + } + + if(seed != 0) gmp_randseed_ui(state,seed); + + return mpfr::urandom(state); +#else + if(seed != 0) std::srand(seed); + return mpfr::mpreal(std::rand()/(double)RAND_MAX); +#endif + +} + ////////////////////////////////////////////////////////////////////////// // Set/Get global properties inline void mpreal::set_default_prec(mp_prec_t prec) @@ -2862,7 +2383,7 @@ inline void mpreal::set_default_prec(mp_prec_t prec) inline mp_prec_t mpreal::get_default_prec() { - return mpfr_get_default_prec(); + return (mpfr_get_default_prec)(); } inline void mpreal::set_default_base(int base) @@ -2883,7 +2404,7 @@ inline void mpreal::set_default_rnd(mp_rnd_t rnd_mode) inline mp_rnd_t mpreal::get_default_rnd() { - return mpfr_get_default_rounding_mode(); + return static_cast((mpfr_get_default_rounding_mode)()); } inline void mpreal::set_double_bits(int dbits) @@ -3197,8 +2718,7 @@ inline const mpreal pow(const double a, const int b, mp_rnd_t rnd_mode) { return pow(mpreal(a),static_cast(b),rnd_mode); // mpfr_pow_si } - -} +} // End of mpfr namespace // Explicit specialization of std::swap for mpreal numbers // Thus standard algorithms will use efficient version of swap (due to Koenig lookup) @@ -3212,4 +2732,4 @@ namespace std } } -#endif /* __MP_REAL_H__ */ +#endif /* __MPREAL_H__ */ diff --git a/gtsam/3rdparty/Eigen/unsupported/test/mpreal_support.cpp b/gtsam/3rdparty/Eigen/unsupported/test/mpreal_support.cpp index 53d388821..551af9db8 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/mpreal_support.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/mpreal_support.cpp @@ -2,6 +2,7 @@ #include #include #include +#include using namespace mpfr; using namespace std; @@ -24,6 +25,15 @@ void test_mpreal_support() MatrixXmp B = MatrixXmp::Random(s,s); MatrixXmp S = A.adjoint() * A; MatrixXmp X; + + // Basic stuffs + VERIFY_IS_APPROX(A.real(), A); + VERIFY(Eigen::internal::isApprox(A.array().abs2().sum(), A.squaredNorm())); + VERIFY_IS_APPROX(A.array().exp(), exp(A.array())); + VERIFY_IS_APPROX(A.array().abs2().sqrt(), A.array().abs()); + VERIFY_IS_APPROX(A.array().sin(), sin(A.array())); + VERIFY_IS_APPROX(A.array().cos(), cos(A.array())); + // Cholesky X = S.selfadjointView().llt().solve(B); @@ -39,6 +49,13 @@ void test_mpreal_support() VERIFY_IS_APPROX((S.selfadjointView() * eig.eigenvectors()), eig.eigenvectors() * eig.eigenvalues().asDiagonal()); } + + { + MatrixXmp A(8,3); A.setRandom(); + // test output (interesting things happen in this code) + std::stringstream stream; + stream << A; + } } extern "C" { diff --git a/gtsam/3rdparty/Eigen/unsupported/test/polynomialsolver.cpp b/gtsam/3rdparty/Eigen/unsupported/test/polynomialsolver.cpp index 54b6657c9..28e034179 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/polynomialsolver.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/polynomialsolver.cpp @@ -27,10 +27,6 @@ #include #include -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - using namespace std; namespace Eigen { @@ -73,32 +69,6 @@ bool aux_evalSolver( const POLYNOMIAL& pols, SOLVER& psolve ) cerr << endl; } - #ifdef HAS_GSL - if (internal::is_same< Scalar, double>::value) - { - typedef GslTraits Gsl; - RootsType gslRoots(deg); - Gsl::eigen_poly_solve( pols, gslRoots ); - EvalRootsType gslEvr( deg ); - for( int i=0; i() ); - if( !evalToZero ) - { - if( !gslEvalToZero ){ - cerr << "GSL also failed" << endl; } - else{ - cerr << "GSL did NOT failed" << endl; } - cerr << "GSL roots found: " << gslRoots.transpose() << endl; - cerr << "Abs value of the polynomial at the GSL roots: " << gslEvr.transpose() << endl; - cerr << endl; - } - } - #endif //< HAS_GSL - - std::vector rootModuli( roots.size() ); Map< EvalRootsType > aux( &rootModuli[0], roots.size() ); aux = roots.array().abs(); diff --git a/gtsam/3rdparty/Eigen/unsupported/test/sparse_extra.cpp b/gtsam/3rdparty/Eigen/unsupported/test/sparse_extra.cpp index b1fd481e8..6c5c888ae 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/sparse_extra.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/sparse_extra.cpp @@ -22,7 +22,11 @@ // License and a copy of the GNU General Public License along with // Eigen. If not, see . -#include "sparse.h" + +// import basic and product tests for deprectaed DynamicSparseMatrix +#define EIGEN_NO_DEPRECATED_WARNING +#include "sparse_basic.cpp" +#include "sparse_product.cpp" #include template @@ -145,10 +149,16 @@ template void sparse_extra(const SparseMatrixType& re void test_sparse_extra() { for(int i = 0; i < g_repeat; i++) { + int s = Eigen::internal::random(1,50); CALL_SUBTEST_1( sparse_extra(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_extra(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_extra(SparseMatrix(33, 33)) ); + CALL_SUBTEST_2( sparse_extra(SparseMatrix >(s, s)) ); + CALL_SUBTEST_1( sparse_extra(SparseMatrix(s, s)) ); - CALL_SUBTEST_3( sparse_extra(DynamicSparseMatrix(8, 8)) ); + CALL_SUBTEST_3( sparse_extra(DynamicSparseMatrix(s, s)) ); +// CALL_SUBTEST_3(( sparse_basic(DynamicSparseMatrix(s, s)) )); +// CALL_SUBTEST_3(( sparse_basic(DynamicSparseMatrix(s, s)) )); + + CALL_SUBTEST_3( (sparse_product >()) ); + CALL_SUBTEST_3( (sparse_product >()) ); } } diff --git a/gtsam/3rdparty/Eigen/unsupported/test/sparse_ldlt.cpp b/gtsam/3rdparty/Eigen/unsupported/test/sparse_ldlt.cpp deleted file mode 100644 index 03a26bcd2..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/test/sparse_ldlt.cpp +++ /dev/null @@ -1,175 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#include "sparse.h" -#include - -#ifdef EIGEN_CHOLMOD_SUPPORT -#include -#endif - -template void sparse_ldlt(int rows, int cols) -{ - static bool odd = true; - odd = !odd; - double density = (std::max)(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, 0, 0); - - SparseMatrix m3 = m2 * m2.adjoint(), m3_lo(rows,rows), m3_up(rows,rows); - DenseMatrix refMat3 = refMat2 * refMat2.adjoint(); - - refX = refMat3.template selfadjointView().ldlt().solve(b); - typedef SparseMatrix SparseSelfAdjointMatrix; - x = b; - SparseLDLT ldlt(m3); - if (ldlt.succeeded()) - ldlt.solveInPlace(x); - else - std::cerr << "warning LDLT failed\n"; - - VERIFY_IS_APPROX(refMat3.template selfadjointView() * x, b); - VERIFY(refX.isApprox(x,test_precision()) && "LDLT: default"); - -#ifdef EIGEN_CHOLMOD_SUPPORT - { - x = b; - SparseLDLT ldlt2(m3); - if (ldlt2.succeeded()) - { - ldlt2.solveInPlace(x); - VERIFY_IS_APPROX(refMat3.template selfadjointView() * x, b); - VERIFY(refX.isApprox(x,test_precision()) && "LDLT: cholmod solveInPlace"); - - x = ldlt2.solve(b); - VERIFY_IS_APPROX(refMat3.template selfadjointView() * x, b); - VERIFY(refX.isApprox(x,test_precision()) && "LDLT: cholmod solve"); - } - else - std::cerr << "warning LDLT failed\n"; - } -#endif - - // new Simplicial LLT - - - // new API - { - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector ref_x(cols), x(cols); - DenseMatrix B = DenseMatrix::Random(rows,cols); - DenseMatrix ref_X(rows,cols), X(rows,cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, 0, 0); - - for(int i=0; i m3 = m2 * m2.adjoint(), m3_lo(rows,rows), m3_up(rows,rows); - DenseMatrix refMat3 = refMat2 * refMat2.adjoint(); - - m3_lo.template selfadjointView().rankUpdate(m2,0); - m3_up.template selfadjointView().rankUpdate(m2,0); - - // with a single vector as the rhs - ref_x = refMat3.template selfadjointView().llt().solve(b); - - x = SimplicialCholesky, Lower>().setMode(odd ? SimplicialCholeskyLLt : SimplicialCholeskyLDLt).compute(m3).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "SimplicialCholesky: solve, full storage, lower, single dense rhs"); - - x = SimplicialCholesky, Upper>().setMode(odd ? SimplicialCholeskyLLt : SimplicialCholeskyLDLt).compute(m3).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "SimplicialCholesky: solve, full storage, upper, single dense rhs"); - - x = SimplicialCholesky, Lower>(m3_lo).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "SimplicialCholesky: solve, lower only, single dense rhs"); - - x = SimplicialCholesky, Upper>(m3_up).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "SimplicialCholesky: solve, upper only, single dense rhs"); - - - // with multiple rhs - ref_X = refMat3.template selfadjointView().llt().solve(B); - - X = SimplicialCholesky, Lower>().setMode(odd ? SimplicialCholeskyLLt : SimplicialCholeskyLDLt).compute(m3).solve(B); - VERIFY(ref_X.isApprox(X,test_precision()) && "SimplicialCholesky: solve, full storage, lower, multiple dense rhs"); - - X = SimplicialCholesky, Upper>().setMode(odd ? SimplicialCholeskyLLt : SimplicialCholeskyLDLt).compute(m3).solve(B); - VERIFY(ref_X.isApprox(X,test_precision()) && "SimplicialCholesky: solve, full storage, upper, multiple dense rhs"); - - - // with a sparse rhs -// SparseMatrix spB(rows,cols), spX(rows,cols); -// B.diagonal().array() += 1; -// spB = B.sparseView(0.5,1); -// -// ref_X = refMat3.template selfadjointView().llt().solve(DenseMatrix(spB)); -// -// spX = SimplicialCholesky, Lower>(m3).solve(spB); -// VERIFY(ref_X.isApprox(spX.toDense(),test_precision()) && "LLT: cholmod solve, multiple sparse rhs"); -// -// spX = SimplicialCholesky, Upper>(m3).solve(spB); -// VERIFY(ref_X.isApprox(spX.toDense(),test_precision()) && "LLT: cholmod solve, multiple sparse rhs"); - } - - - -// for(int i=0; i().ldlt().solve(b); -// typedef SparseMatrix SparseSelfAdjointMatrix; -// x = b; -// SparseLDLT ldlt(m2); -// if (ldlt.succeeded()) -// ldlt.solveInPlace(x); -// else -// std::cerr << "warning LDLT failed\n"; -// -// VERIFY_IS_APPROX(refMat2.template selfadjointView() * x, b); -// VERIFY(refX.isApprox(x,test_precision()) && "LDLT: default"); - - -} - -void test_sparse_ldlt() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1(sparse_ldlt(8, 8) ); - int s = internal::random(1,300); - CALL_SUBTEST_2(sparse_ldlt >(s,s) ); - CALL_SUBTEST_1(sparse_ldlt(s,s) ); - } -} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/sparse_llt.cpp b/gtsam/3rdparty/Eigen/unsupported/test/sparse_llt.cpp deleted file mode 100644 index 5f8a7ce36..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/test/sparse_llt.cpp +++ /dev/null @@ -1,140 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#include "sparse.h" -#include - -#ifdef EIGEN_CHOLMOD_SUPPORT -#include -#endif - -template void sparse_llt(int rows, int cols) -{ - double density = (std::max)(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - - // TODO fix the issue with complex (see SparseLLT::solveInPlace) - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector ref_x(cols), x(cols); - DenseMatrix B = DenseMatrix::Random(rows,cols); - DenseMatrix ref_X(rows,cols), X(rows,cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, 0, 0); - - for(int i=0; i().llt().solve(b); - if (!NumTraits::IsComplex) - { - x = b; - SparseLLT > (m2).solveInPlace(x); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT: default"); - } - -#ifdef EIGEN_CHOLMOD_SUPPORT - // legacy API - { - // Cholmod, as configured in CholmodSupport.h, only supports self-adjoint matrices - SparseMatrix m3 = m2.adjoint()*m2; - DenseMatrix refMat3 = refMat2.adjoint()*refMat2; - - ref_x = refMat3.template selfadjointView().llt().solve(b); - - x = b; - SparseLLT, Cholmod>(m3).solveInPlace(x); - VERIFY((m3*x).isApprox(b,test_precision()) && "LLT legacy: cholmod solveInPlace"); - - x = SparseLLT, Cholmod>(m3).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT legacy: cholmod solve"); - } - - // new API - { - // Cholmod, as configured in CholmodSupport.h, only supports self-adjoint matrices - SparseMatrix m3 = m2 * m2.adjoint(), m3_lo(rows,rows), m3_up(rows,rows); - DenseMatrix refMat3 = refMat2 * refMat2.adjoint(); - - m3_lo.template selfadjointView().rankUpdate(m2,0); - m3_up.template selfadjointView().rankUpdate(m2,0); - - // with a single vector as the rhs - ref_x = refMat3.template selfadjointView().llt().solve(b); - - x = CholmodDecomposition, Lower>(m3).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT: cholmod solve, single dense rhs"); - - x = CholmodDecomposition, Upper>(m3).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT: cholmod solve, single dense rhs"); - - x = CholmodDecomposition, Lower>(m3_lo).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT: cholmod solve, single dense rhs"); - - x = CholmodDecomposition, Upper>(m3_up).solve(b); - VERIFY(ref_x.isApprox(x,test_precision()) && "LLT: cholmod solve, single dense rhs"); - - - // with multiple rhs - ref_X = refMat3.template selfadjointView().llt().solve(B); - - #ifndef EIGEN_DEFAULT_TO_ROW_MAJOR - // TODO make sure the API is properly documented about this fact - X = CholmodDecomposition, Lower>(m3).solve(B); - VERIFY(ref_X.isApprox(X,test_precision()) && "LLT: cholmod solve, multiple dense rhs"); - - X = CholmodDecomposition, Upper>(m3).solve(B); - VERIFY(ref_X.isApprox(X,test_precision()) && "LLT: cholmod solve, multiple dense rhs"); - #endif - - - // with a sparse rhs - SparseMatrix spB(rows,cols), spX(rows,cols); - B.diagonal().array() += 1; - spB = B.sparseView(0.5,1); - - ref_X = refMat3.template selfadjointView().llt().solve(DenseMatrix(spB)); - - spX = CholmodDecomposition, Lower>(m3).solve(spB); - VERIFY(ref_X.isApprox(spX.toDense(),test_precision()) && "LLT: cholmod solve, multiple sparse rhs"); - - spX = CholmodDecomposition, Upper>(m3).solve(spB); - VERIFY(ref_X.isApprox(spX.toDense(),test_precision()) && "LLT: cholmod solve, multiple sparse rhs"); - } -#endif - -} - -void test_sparse_llt() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1(sparse_llt(8, 8) ); - int s = internal::random(1,300); - CALL_SUBTEST_2(sparse_llt >(s,s) ); - CALL_SUBTEST_1(sparse_llt(s,s) ); - } -} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/sparse_lu.cpp b/gtsam/3rdparty/Eigen/unsupported/test/sparse_lu.cpp deleted file mode 100644 index d58e85a0a..000000000 --- a/gtsam/3rdparty/Eigen/unsupported/test/sparse_lu.cpp +++ /dev/null @@ -1,113 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - -#include "sparse.h" -#include - -#ifdef EIGEN_UMFPACK_SUPPORT -#include -#endif - -#ifdef EIGEN_SUPERLU_SUPPORT -#include -#endif - -template void sparse_lu(int rows, int cols) -{ - double density = (std::max)(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - - DenseVector vec1 = DenseVector::Random(rows); - - std::vector zeroCoords; - std::vector nonzeroCoords; - - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag, &zeroCoords, &nonzeroCoords); - - FullPivLU refLu(refMat2); - refX = refLu.solve(b); - #if defined(EIGEN_SUPERLU_SUPPORT) || defined(EIGEN_UMFPACK_SUPPORT) - Scalar refDet = refLu.determinant(); - #endif - x.setZero(); - // // SparseLU > (m2).solve(b,&x); - // // VERIFY(refX.isApprox(x,test_precision()) && "LU: default"); - - #ifdef EIGEN_UMFPACK_SUPPORT - { - // check solve - x.setZero(); - SparseLU,UmfPack> lu(m2); - VERIFY(lu.succeeded() && "umfpack LU decomposition failed"); - VERIFY(lu.solve(b,&x) && "umfpack LU solving failed"); - VERIFY(refX.isApprox(x,test_precision()) && "LU: umfpack"); - VERIFY_IS_APPROX(refDet,lu.determinant()); - // TODO check the extracted data - //std::cerr << slu.matrixL() << "\n"; - } - #endif - - #ifdef EIGEN_SUPERLU_SUPPORT - { - x.setZero(); - SparseLU,SuperLU> slu(m2); - if (slu.succeeded()) - { - if (slu.solve(b,&x)) { - VERIFY(refX.isApprox(x,test_precision()) && "LU: SuperLU"); - } - // std::cerr << refDet << " == " << slu.determinant() << "\n"; - if (slu.solve(b, &x, SvTranspose)) { - VERIFY(b.isApprox(m2.transpose() * x, test_precision())); - } - - if (slu.solve(b, &x, SvAdjoint)) { - VERIFY(b.isApprox(m2.adjoint() * x, test_precision())); - } - - if (!NumTraits::IsComplex) { - VERIFY_IS_APPROX(refDet,slu.determinant()); // FIXME det is not very stable for complex - } - } - } - #endif - -} - -void test_sparse_lu() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1(sparse_lu(8, 8) ); - int s = internal::random(1,300); - CALL_SUBTEST_2(sparse_lu >(s,s) ); - CALL_SUBTEST_1(sparse_lu(s,s) ); - } -} diff --git a/gtsam/3rdparty/Eigen/unsupported/test/splines.cpp b/gtsam/3rdparty/Eigen/unsupported/test/splines.cpp new file mode 100644 index 000000000..fe98bf183 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/test/splines.cpp @@ -0,0 +1,255 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2010-2011 Hauke Heibel +// +// Eigen is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 3 of the License, or (at your option) any later version. +// +// Alternatively, you can redistribute it and/or +// modify it under the terms of the GNU General Public License as +// published by the Free Software Foundation; either version 2 of +// the License, or (at your option) any later version. +// +// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY +// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS +// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public +// License and a copy of the GNU General Public License along with +// Eigen. If not, see . + +#include "main.h" + +#include + +// lets do some explicit instantiations and thus +// force the compilation of all spline functions... +template class Spline; +template class Spline; + +template class Spline; +template class Spline; +template class Spline; +template class Spline; + +template class Spline; +template class Spline; + +template class Spline; +template class Spline; +template class Spline; +template class Spline; + +Spline closed_spline2d() +{ + RowVectorXd knots(12); + knots << 0, + 0, + 0, + 0, + 0.867193179093898, + 1.660330955342408, + 2.605084834823134, + 3.484154586374428, + 4.252699478956276, + 4.252699478956276, + 4.252699478956276, + 4.252699478956276; + + MatrixXd ctrls(8,2); + ctrls << -0.370967741935484, 0.236842105263158, + -0.231401860693277, 0.442245185027632, + 0.344361228532831, 0.773369994120753, + 0.828990216203802, 0.106550882647595, + 0.407270163678382, -1.043452922172848, + -0.488467813584053, -0.390098582530090, + -0.494657189446427, 0.054804824897884, + -0.370967741935484, 0.236842105263158; + ctrls.transposeInPlace(); + + return Spline(knots, ctrls); +} + +/* create a reference spline */ +Spline spline3d() +{ + RowVectorXd knots(11); + knots << 0, + 0, + 0, + 0.118997681558377, + 0.162611735194631, + 0.498364051982143, + 0.655098003973841, + 0.679702676853675, + 1.000000000000000, + 1.000000000000000, + 1.000000000000000; + + MatrixXd ctrls(8,3); + ctrls << 0.959743958516081, 0.340385726666133, 0.585267750979777, + 0.223811939491137, 0.751267059305653, 0.255095115459269, + 0.505957051665142, 0.699076722656686, 0.890903252535799, + 0.959291425205444, 0.547215529963803, 0.138624442828679, + 0.149294005559057, 0.257508254123736, 0.840717255983663, + 0.254282178971531, 0.814284826068816, 0.243524968724989, + 0.929263623187228, 0.349983765984809, 0.196595250431208, + 0.251083857976031, 0.616044676146639, 0.473288848902729; + ctrls.transposeInPlace(); + + return Spline(knots, ctrls); +} + +/* compares evaluations against known results */ +void eval_spline3d() +{ + Spline3d spline = spline3d(); + + RowVectorXd u(10); + u << 0.351659507062997, + 0.830828627896291, + 0.585264091152724, + 0.549723608291140, + 0.917193663829810, + 0.285839018820374, + 0.757200229110721, + 0.753729094278495, + 0.380445846975357, + 0.567821640725221; + + MatrixXd pts(10,3); + pts << 0.707620811535916, 0.510258911240815, 0.417485437023409, + 0.603422256426978, 0.529498282727551, 0.270351549348981, + 0.228364197569334, 0.423745615677815, 0.637687289287490, + 0.275556796335168, 0.350856706427970, 0.684295784598905, + 0.514519311047655, 0.525077224890754, 0.351628308305896, + 0.724152914315666, 0.574461155457304, 0.469860285484058, + 0.529365063753288, 0.613328702656816, 0.237837040141739, + 0.522469395136878, 0.619099658652895, 0.237139665242069, + 0.677357023849552, 0.480655768435853, 0.422227610314397, + 0.247046593173758, 0.380604672404750, 0.670065791405019; + pts.transposeInPlace(); + + for (int i=0; i::Interpolate(points,3); + + for (Eigen::DenseIndex i=0; i::Interpolate(points,3,chord_lengths); + + for (Eigen::DenseIndex i=0; i #include -#include +#include using namespace std; diff --git a/gtsam_unstable/base/DSFVector.h b/gtsam/base/DSFVector.h similarity index 99% rename from gtsam_unstable/base/DSFVector.h rename to gtsam/base/DSFVector.h index 17e897032..3940723c4 100644 --- a/gtsam_unstable/base/DSFVector.h +++ b/gtsam/base/DSFVector.h @@ -27,7 +27,7 @@ namespace gtsam { /** * A fast implementation of disjoint set forests that uses vector as underly data structure. - * @ingroup base + * @addtogroup base */ class DSFVector { diff --git a/gtsam/base/DerivedValue.h b/gtsam/base/DerivedValue.h index 1919f9540..2dc6f3d67 100644 --- a/gtsam/base/DerivedValue.h +++ b/gtsam/base/DerivedValue.h @@ -10,14 +10,13 @@ * -------------------------------------------------------------------------- */ /* - * DerivedValue.h - * - * Created on: Jan 26, 2012 - * Author: thduynguyen + * @file DerivedValue.h + * @date Jan 26, 2012 + * @author Duy Nguyen Ta */ #pragma once - +#include #include #include @@ -25,9 +24,6 @@ namespace gtsam { template class DerivedValue : public Value { -private: - /// Fake Tag struct for singleton pool allocator. In fact, it is never used! - struct PoolTag { }; protected: DerivedValue() {} @@ -38,7 +34,8 @@ public: /** * Create a duplicate object returned as a pointer to the generic Value interface. - * For the sake of performance, this function use singleton pool allocator instead of the normal heap allocator + * For the sake of performance, this function use singleton pool allocator instead of the normal heap allocator. + * The result must be deleted with Value::deallocate_, not with the 'delete' operator. */ virtual Value* clone_() const { void *place = boost::singleton_pool::malloc(); @@ -50,10 +47,17 @@ public: * Destroy and deallocate this object, only if it was originally allocated using clone_(). */ virtual void deallocate_() const { - this->~Value(); - boost::singleton_pool::free((void*)this); + this->~DerivedValue(); // Virtual destructor cleans up the derived object + boost::singleton_pool::free((void*)this); // Release memory from pool } + /** + * Clone this value (normal clone on the heap, delete with 'delete' operator) + */ + virtual boost::shared_ptr clone() const { + return boost::make_shared(static_cast(*this)); + } + /// equals implementing generic Value interface virtual bool equals_(const Value& p, double tol = 1e-9) const { // Cast the base class Value pointer to a derived class pointer @@ -112,6 +116,10 @@ protected: return *this; } +private: + /// Fake Tag struct for singleton pool allocator. In fact, it is never used! + struct PoolTag { }; + }; } /* namespace gtsam */ diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index 60452357f..aa1ab24e8 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -31,7 +31,7 @@ namespace gtsam { * convenience to avoid having lengthy types in the code. Through timing, * we've seen that the fast_pool_allocator can lead to speedups of several * percent. - * @ingroup base + * @addtogroup base */ template class FastList: public std::list > { @@ -50,9 +50,18 @@ public: /** Copy constructor from another FastList */ FastList(const FastList& x) : Base(x) {} - /** Copy constructor from the base map class */ + /** Copy constructor from the base list class */ FastList(const Base& x) : Base(x) {} + /** Copy constructor from a standard STL container */ + FastList(const std::list& x) { + // This if statement works around a bug in boost pool allocator and/or + // STL vector where if the size is zero, the pool allocator will allocate + // huge amounts of memory. + if(x.size() > 0) + Base::assign(x.begin(), x.end()); + } + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index c9fe30646..ab448de07 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -31,7 +31,7 @@ namespace gtsam { * convenience to avoid having lengthy types in the code. Through timing, * we've seen that the fast_pool_allocator can lead to speedups of several * percent. - * @ingroup base + * @addtogroup base */ template class FastMap : public std::map, boost::fast_pool_allocator > > { diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index 6abd7efb8..123a8bb31 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -42,7 +42,7 @@ struct FastSetTestableHelper; * fast_pool_allocator instead of the default STL allocator. This is just a * convenience to avoid having lengthy types in the code. Through timing, * we've seen that the fast_pool_allocator can lead to speedups of several %. - * @ingroup base + * @addtogroup base */ template class FastSet: public std::set, boost::fast_pool_allocator > { @@ -66,11 +66,20 @@ public: Base(x) { } - /** Copy constructor from the base map class */ + /** Copy constructor from the base set class */ FastSet(const Base& x) : Base(x) { } + /** Copy constructor from a standard STL container */ + FastSet(const std::set& x) { + // This if statement works around a bug in boost pool allocator and/or + // STL vector where if the size is zero, the pool allocator will allocate + // huge amounts of memory. + if(x.size() > 0) + Base::insert(x.begin(), x.end()); + } + /** Print to implement Testable */ void print(const std::string& str = "") const { FastSetTestableHelper::print(*this, str); } diff --git a/gtsam/base/FastVector.h b/gtsam/base/FastVector.h index 18af63006..33bc5cb7c 100644 --- a/gtsam/base/FastVector.h +++ b/gtsam/base/FastVector.h @@ -23,6 +23,9 @@ #include #include +#include +#include + namespace gtsam { /** @@ -30,7 +33,7 @@ namespace gtsam { * pool_allocator instead of the default STL allocator. This is just a * convenience to avoid having lengthy types in the code. Through timing, * we've seen that the pool_allocator can lead to speedups of several % - * @ingroup base + * @addtogroup base */ template class FastVector: public std::vector > { @@ -58,9 +61,21 @@ public: Base::assign(first, last); } - /** Copy constructor from another FastSet */ + /** Copy constructor from another FastVector */ FastVector(const FastVector& x) : Base(x) {} + /** Copy constructor from a FastList */ + FastVector(const FastList& x) { + if(x.size() > 0) + Base::assign(x.begin(), x.end()); + } + + /** Copy constructor from a FastSet */ + FastVector(const FastSet& x) { + if(x.size() > 0) + Base::assign(x.begin(), x.end()); + } + /** Copy constructor from the base class */ FastVector(const Base& x) : Base(x) {} @@ -73,6 +88,11 @@ public: Base::assign(x.begin(), x.end()); } + /** Conversion to a standard STL container */ + operator std::vector() const { + return std::vector(this->begin(), this->end()); + } + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/base/LieMatrix.cpp b/gtsam/base/LieMatrix.cpp new file mode 100644 index 000000000..332401689 --- /dev/null +++ b/gtsam/base/LieMatrix.cpp @@ -0,0 +1,36 @@ +/* ---------------------------------------------------------------------------- + + * 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 LieMatrix.cpp + * @brief A wrapper around Matrix providing Lie compatibility + * @author Richard Roberts and Alex Cunningham + */ + +#include + +namespace gtsam { + + /* ************************************************************************* */ + LieMatrix::LieMatrix(size_t m, size_t n, ...) + : Matrix(m,n) { + va_list ap; + va_start(ap, n); + for(size_t i = 0; i < m; ++i) { + for(size_t j = 0; j < n; ++j) { + double value = va_arg(ap, double); + (*this)(i,j) = value; + } + } + va_end(ap); + } + +} \ No newline at end of file diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h new file mode 100644 index 000000000..5844e8201 --- /dev/null +++ b/gtsam/base/LieMatrix.h @@ -0,0 +1,153 @@ +/* ---------------------------------------------------------------------------- + + * 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 LieMatrix.h + * @brief A wrapper around Matrix providing Lie compatibility + * @author Richard Roberts and Alex Cunningham + */ + +#pragma once + +#include + +#include +#include +#include +#include + +namespace gtsam { + +/** + * LieVector is a wrapper around vector to allow it to be a Lie type + */ +struct LieMatrix : public Matrix, public DerivedValue { + + /** default constructor - should be unnecessary */ + LieMatrix() {} + + /** initialize from a normal matrix */ + LieMatrix(const Matrix& v) : Matrix(v) {} + + /** initialize from a fixed size normal vector */ + template + LieMatrix(const Eigen::Matrix& v) : Matrix(v) {} + + /** constructor with size and initial data, row order ! */ + LieMatrix(size_t m, size_t n, const double* const data) : + Matrix(Eigen::Map(data, m, n)) {} + + /** Specify arguments directly, as in Matrix_() - always force these to be doubles */ + LieMatrix(size_t m, size_t n, ...); + + /** get the underlying vector */ + inline Matrix matrix() const { + return static_cast(*this); + } + + /** print @param s optional string naming the object */ + inline void print(const std::string& name="") const { + gtsam::print(matrix(), name); + } + + /** equality up to tolerance */ + inline bool equals(const LieMatrix& expected, double tol=1e-5) const { + return gtsam::equal_with_abs_tol(matrix(), expected.matrix(), tol); + } + + // Manifold requirements + + /** Returns dimensionality of the tangent space */ + inline size_t dim() const { return this->size(); } + + /** Update the LieMatrix with a tangent space update. The elements of the + * tangent space vector correspond to the matrix entries arranged in + * *row-major* order. */ + inline LieMatrix retract(const Vector& v) const { + if(v.size() != this->rows() * this->cols()) + throw std::invalid_argument("LieMatrix::retract called with Vector of incorrect size"); + return LieMatrix(*this + Eigen::Map(&v(0), this->cols(), this->rows()).transpose()); + } + + /** @return the local coordinates of another object. The elements of the + * tangent space vector correspond to the matrix entries arranged in + * *row-major* order. */ + inline Vector localCoordinates(const LieMatrix& t2) const { + Vector result(this->rows() * this->cols()); + Eigen::Map(&result(0), this->cols(), this->rows()).transpose() = + (t2 - *this); + return result; + } + + // Group requirements + + /** identity - NOTE: no known size at compile time - so zero length */ + inline static LieMatrix identity() { + throw std::runtime_error("LieMatrix::identity(): Don't use this function"); + return LieMatrix(); + } + + // Note: Manually specifying the 'gtsam' namespace for the optional Matrix arguments + // This is a work-around for linux g++ 4.6.1 that incorrectly selects the Eigen::Matrix class + // instead of the gtsam::Matrix class. This is related to deriving this class from an Eigen Vector + // as the other geometry objects (Point3, Rot3, etc.) have this problem + /** compose with another object */ + inline LieMatrix compose(const LieMatrix& p, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = eye(dim()); + if(H2) *H2 = eye(p.dim()); + + return LieMatrix(*this + p); + } + + /** between operation */ + inline LieMatrix between(const LieMatrix& l2, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = -eye(dim()); + if(H2) *H2 = eye(l2.dim()); + return LieMatrix(l2 - *this); + } + + /** invert the object and yield a new one */ + inline LieMatrix inverse(boost::optional H=boost::none) const { + if(H) *H = -eye(dim()); + + return LieMatrix(-(*this)); + } + + // Lie functions + + /** Expmap around identity */ + static inline LieMatrix Expmap(const Vector& v) { + throw std::runtime_error("LieMatrix::Expmap(): Don't use this function"); + return LieMatrix(v); } + + /** Logmap around identity - just returns with default cast back */ + static inline Vector Logmap(const LieMatrix& p) { + return Eigen::Map(&p(0,0), p.dim()); } + +private: + + // Serialization function + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("LieMatrix", + boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Matrix", + boost::serialization::base_object(*this)); + + } + +}; +} // \namespace gtsam diff --git a/gtsam/base/LieScalar.h b/gtsam/base/LieScalar.h index 505f06921..3721492ec 100644 --- a/gtsam/base/LieScalar.h +++ b/gtsam/base/LieScalar.h @@ -31,12 +31,15 @@ namespace gtsam { LieScalar() : d_(0.0) {} /** wrap a double */ - LieScalar(double d) : d_(d) {} + explicit LieScalar(double d) : d_(d) {} /** access the underlying value */ double value() const { return d_; } - /** print @param s optional string naming the object */ + /** Automatic conversion to underlying value */ + operator double() const { return d_; } + + /** print @param name optional string naming the object */ inline void print(const std::string& name="") const { std::cout << name << ": " << d_ << std::endl; } diff --git a/gtsam/base/LieVector.cpp b/gtsam/base/LieVector.cpp index 876c8fa6e..d5ae5d504 100644 --- a/gtsam/base/LieVector.cpp +++ b/gtsam/base/LieVector.cpp @@ -15,7 +15,7 @@ * @author Alex Cunningham */ -#include +#include #include using namespace std; diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 82455e173..916730fd3 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -52,7 +52,7 @@ struct LieVector : public Vector, public DerivedValue { return static_cast(*this); } - /** print @param s optional string naming the object */ + /** print @param name optional string naming the object */ inline void print(const std::string& name="") const { gtsam::print(vector(), name); } @@ -119,5 +119,17 @@ struct LieVector : public Vector, public DerivedValue { /** Logmap around identity - just returns with default cast back */ static inline Vector Logmap(const LieVector& p) { return p; } +private: + + // Serialization function + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("LieVector", + boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Vector", + boost::serialization::base_object(*this)); + } + }; } // \namespace gtsam diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 849dc3f5a..1369f13b8 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -15,9 +15,11 @@ * @author Christian Potthast */ +#include #include #include #include +#include #include #include @@ -25,8 +27,8 @@ #include #include -#include -#include +#include +#include #include #include #include @@ -235,8 +237,41 @@ void save(const Matrix& A, const string &s, const string& filename) { } /* ************************************************************************* */ -void insertSub(Matrix& big, const Matrix& small, size_t i, size_t j) { - big.block(i, j, small.rows(), small.cols()) = small; +istream& operator>>(istream& inputStream, Matrix& destinationMatrix) { + string line; + FastList > coeffs; + bool first = true; + size_t width = 0; + size_t height = 0; + while(getline(inputStream, line)) { + // Read coefficients from file + coeffs.push_back(vector()); + if(!first) + coeffs.back().reserve(width); + stringstream lineStream(line); + std::copy(istream_iterator(lineStream), istream_iterator(), + back_insert_iterator >(coeffs.back())); + if(first) + width = coeffs.back().size(); + if(coeffs.back().size() != width) + throw runtime_error("Error reading matrix from input stream, inconsistent numbers of elements in rows"); + ++ height; + } + + // Copy coefficients to matrix + destinationMatrix.resize(height, width); + int row = 0; + BOOST_FOREACH(const vector& rowVec, coeffs) { + destinationMatrix.row(row) = Eigen::Map(&rowVec[0], width); + ++ row; + } + + return inputStream; +} + +/* ************************************************************************* */ +void insertSub(Matrix& fullMatrix, const Matrix& subMatrix, size_t i, size_t j) { + fullMatrix.block(i, j, subMatrix.rows(), subMatrix.cols()) = subMatrix; } /* ************************************************************************* */ @@ -647,31 +682,21 @@ void svd(const Matrix& A, Matrix& U, Vector& S, Matrix& V) { boost::tuple DLT(const Matrix& A, double rank_tol) { // Check size of A - int m = A.rows(), n = A.cols(); - if (m < n) throw invalid_argument( - "DLT: m svd(A, Eigen::ComputeFullV); + Vector s = svd.singularValues(); + Matrix V = svd.matrixV(); // Find rank int rank = 0; - for (int j = 0; j < n; j++) - if (S(j) > rank_tol) rank++; - // Find minimum singular value and corresponding column index - int min_j = n - 1; - double min_S = S(min_j); - for (int j = 0; j < n - 1; j++) - if (S(j) < min_S) { - min_j = j; - min_S = S(j); - } + for (int j = 0; j < m; j++) + if (s(j) > rank_tol) rank++; - // Return rank, minimum singular value, and corresponding column of V - return boost::tuple(rank, min_S, Vector(column(V, min_j))); + // Return rank, error, and corresponding column of V + double error = m

(rank, error, Vector(column(V, p-1))); } /* ************************************************************************* */ diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 3a70d9b76..e6a40f727 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -26,6 +26,7 @@ #include #include #include +#include /** * Matrix is a typedef in the gtsam namespace @@ -66,11 +67,30 @@ inline Matrix Matrix_(const Vector& v) { return Matrix_(v.size(),1,v);} */ Matrix Matrix_(size_t m, size_t n, ...); +// Matlab-like syntax + /** - * MATLAB like constructors + * Creates an zeros matrix, with matlab-like syntax + * + * Note: if assigning a block (created from an Eigen block() function) of a matrix to zeros, + * don't use this function, instead use ".setZero(m,n)" to avoid an Eigen error. */ Matrix zeros(size_t m, size_t n); + +/** + * Creates an identity matrix, with matlab-like syntax + * + * Note: if assigning a block (created from an Eigen block() function) of a matrix to identity, + * don't use this function, instead use ".setIdentity(m,n)" to avoid an Eigen error. + */ Matrix eye(size_t m, size_t n); + +/** + * Creates a square identity matrix, with matlab-like syntax + * + * Note: if assigning a block (created from an Eigen block() function) of a matrix to identity, + * don't use this function, instead use ".setIdentity(m)" to avoid an Eigen error. + */ inline Matrix eye( size_t m ) { return eye(m,m); } Matrix diag(const Vector& v); @@ -87,7 +107,7 @@ bool equal_with_abs_tol(const Eigen::DenseBase& A, const Eigen::DenseBas for(size_t i=0; i tol) return false; @@ -182,6 +202,13 @@ void print(const Matrix& A, const std::string& s = "", std::ostream& stream = st */ void save(const Matrix& A, const std::string &s, const std::string& filename); +/** + * Read a matrix from an input stream, such as a file. Entries can be either + * tab-, space-, or comma-separated, similar to the format read by the MATLAB + * dlmread command. + */ +std::istream& operator>>(std::istream& inputStream, Matrix& destinationMatrix); + /** * extract submatrix, slice semantics, i.e. range = [i1,i2[ excluding i2 * @param A matrix @@ -200,17 +227,17 @@ Eigen::Block sub(const MATRIX& A, size_t i1, size_t i2, size_t j1, /** * insert a submatrix IN PLACE at a specified location in a larger matrix * NOTE: there is no size checking - * @param large matrix to be updated - * @param small matrix to be inserted + * @param fullMatrix matrix to be updated + * @param subMatrix matrix to be inserted * @param i is the row of the upper left corner insert location * @param j is the column of the upper left corner insert location */ -void insertSub(Matrix& big, const Matrix& small, size_t i, size_t j); +void insertSub(Matrix& fullMatrix, const Matrix& subMatrix, size_t i, size_t j); /** * Extracts a column view from a matrix that avoids a copy - * @param matrix to extract column from - * @param index of the column + * @param A matrix to extract column from + * @param j index of the column * @return a const view of the matrix */ template @@ -220,8 +247,8 @@ const typename MATRIX::ConstColXpr column(const MATRIX& A, size_t j) { /** * Extracts a row view from a matrix that avoids a copy - * @param matrix to extract row from - * @param index of the row + * @param A matrix to extract row from + * @param j index of the row * @return a const view of the matrix */ template @@ -285,7 +312,7 @@ std::pair qr(const Matrix& A); * @param clear_below_diagonal enables zeroing out below diagonal */ template -void inplace_QR(MATRIX& A, bool clear_below_diagonal=true) { +void inplace_QR(MATRIX& A) { size_t rows = A.rows(); size_t cols = A.cols(); size_t size = std::min(rows,cols); @@ -354,7 +381,7 @@ Vector backSubstituteUpper(const Vector& b, const Matrix& U, bool unit=false); * @param unit, set true if unit triangular * @return the solution x of L*x=b */ -Vector backSubstituteLower(const Matrix& L, const Vector& d, bool unit=false); +Vector backSubstituteLower(const Matrix& L, const Vector& b, bool unit=false); /** * create a matrix by stacking other matrices diff --git a/gtsam/base/Testable.h b/gtsam/base/Testable.h index bcc6c8957..009d286db 100644 --- a/gtsam/base/Testable.h +++ b/gtsam/base/Testable.h @@ -46,7 +46,7 @@ namespace gtsam { * tests and in generic algorithms. * * See macros for details on using this structure - * @ingroup base + * @addtogroup base * @tparam T is the type this constrains to be testable - assumes print() and equals() */ template diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index dad1c6d20..00ab79d30 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -30,7 +30,7 @@ namespace gtsam { /** * Equals testing for basic types */ -bool assert_equal(const Index& expected, const Index& actual, double tol = 0.0) { +inline bool assert_equal(const Index& expected, const Index& actual, double tol = 0.0) { if(expected != actual) { std::cout << "Not equal:\nexpected: " << expected << "\nactual: " << actual << std::endl; return false; @@ -81,7 +81,7 @@ bool assert_equal(const V& expected, const boost::optional& actual, do /** * Version of assert_equals to work with vectors - * @DEPRECIATED: use container equals instead + * \deprecated: use container equals instead */ template bool assert_equal(const std::vector& expected, const std::vector& actual, double tol = 1e-9) { @@ -327,7 +327,7 @@ bool assert_container_equality(const V& expected, const V& actual) { /** * Compare strings for unit tests */ -bool assert_equal(const std::string& expected, const std::string& actual) { +inline bool assert_equal(const std::string& expected, const std::string& actual) { if (expected == actual) return true; printf("Not equal:\n"); diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 394a11e72..8b19a6532 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -101,12 +101,15 @@ namespace gtsam { class Value { public: - /** Allocate and construct a clone of this value */ + /** Clone this value in a special memory pool, must be deleted with Value::deallocate_, *not* with the 'delete' operator. */ virtual Value* clone_() const = 0; /** Deallocate a raw pointer of this value */ virtual void deallocate_() const = 0; + /** Clone this value (normal clone on the heap, delete with 'delete' operator) */ + virtual boost::shared_ptr clone() const = 0; + /** Compare this Value with another for equality. */ virtual bool equals_(const Value& other, double tol = 1e-9) const = 0; diff --git a/gtsam/base/Vector.cpp b/gtsam/base/Vector.cpp index 27b56830c..a7e8f2769 100644 --- a/gtsam/base/Vector.cpp +++ b/gtsam/base/Vector.cpp @@ -16,30 +16,27 @@ * @author Frank Dellaert */ -#include +#include #include #include #include #include #include #include +#include #include #include -#include - -#ifdef WIN32 -#include -#endif - -#include -#include +#include #include +#include + +//#ifdef WIN32 +//#include +//#endif using namespace std; -boost::minstd_rand generator(42u); - namespace gtsam { /* ************************************************************************* */ @@ -55,11 +52,11 @@ void odprintf_(const char *format, ostream& stream, ...) { #endif va_end(args); -#ifdef WIN32 - OutputDebugString(buf); -#else +//#ifdef WIN32 +// OutputDebugString(buf); +//#else stream << buf; -#endif +//#endif } /* ************************************************************************* */ @@ -76,11 +73,11 @@ void odprintf(const char *format, ...) { #endif va_end(args); -#ifdef WIN32 - OutputDebugString(buf); -#else +//#ifdef WIN32 +// OutputDebugString(buf); +//#else cout << buf; -#endif +//#endif } /* ************************************************************************* */ @@ -169,7 +166,7 @@ bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol) { if (vec1.size()!=vec2.size()) return false; size_t m = vec1.size(); for(size_t i=0; i tol) return false; @@ -182,7 +179,7 @@ bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol if (vec1.size()!=vec2.size()) return false; size_t m = vec1.size(); for(size_t i=0; i tol) return false; @@ -250,8 +247,8 @@ ConstSubVector sub(const Vector &v, size_t i1, size_t i2) { } /* ************************************************************************* */ -void subInsert(Vector& big, const Vector& small, size_t i) { - big.segment(i, small.size()) = small; +void subInsert(Vector& fullVector, const Vector& subVector, size_t i) { + fullVector.segment(i, subVector.size()) = subVector; } /* ************************************************************************* */ @@ -431,19 +428,6 @@ Vector concatVectors(size_t nrVectors, ...) return concatVectors(vs); } -/* ************************************************************************* */ -Vector rand_vector_norm(size_t dim, double mean, double sigma) -{ - boost::normal_distribution norm_dist(mean, sigma); - boost::variate_generator > norm(generator, norm_dist); - - Vector v(dim); - for(int i = 0; i #include -#include -#include - -/** - * Static random number generator - needs to maintain a state - * over time, hence the static generator. Be careful in - * cases where multiple processes (as is frequently the case with - * multi-robot scenarios) are using the sample() facilities - * in NoiseModel, as they will each have the same seed. - */ -// FIXME: make this go away - use the Sampler class instead -extern boost::minstd_rand generator; +#include +#include +#include namespace gtsam { @@ -72,8 +63,8 @@ Vector Vector_(const std::vector& data); /** * Create vector initialized to a constant value - * @param size - * @param constant value + * @param n is the size of the vector + * @param value is a constant value to insert into the vector */ Vector repeat(size_t n, double value); @@ -81,7 +72,7 @@ Vector repeat(size_t n, double value); * Create basis vector of dimension n, * with a constant in spot i * @param n is the size of the vector - * @param index of the one + * @param i index of the one * @param value is the value to insert into the vector * @return delta vector */ @@ -91,20 +82,20 @@ Vector delta(size_t n, size_t i, double value); * Create basis vector of dimension n, * with one in spot i * @param n is the size of the vector - * @param index of the one + * @param i index of the one * @return basis vector */ inline Vector basis(size_t n, size_t i) { return delta(n, i, 1.0); } /** * Create zero vector - * @param size + * @param n size */ inline Vector zero(size_t n) { return Vector::Zero(n);} /** * Create vector initialized to ones - * @param size + * @param n size */ inline Vector ones(size_t n) { return Vector::Ones(n); } @@ -208,11 +199,11 @@ ConstSubVector sub(const Vector &v, size_t i1, size_t i2); /** * Inserts a subvector into a vector IN PLACE - * @param big is the vector to be changed - * @param small is the vector to insert + * @param fullVector is the vector to be changed + * @param subVector is the vector to insert * @param i is the index where the subvector should be inserted */ -void subInsert(Vector& big, const Vector& small, size_t i); +void subInsert(Vector& fullVector, const Vector& subVector, size_t i); /** * elementwise multiplication @@ -248,35 +239,35 @@ double sum(const Vector &a); /** * Calculates L2 norm for a vector * modeled after boost.ublas for compatibility - * @param vector + * @param v vector * @return the L2 norm */ double norm_2(const Vector& v); /** - * elementwise reciprocal of vector elements + * Elementwise reciprocal of vector elements * @param a vector * @return [1/a(i)] */ Vector reciprocal(const Vector &a); /** - * elementwise sqrt of vector elements - * @param a vector + * Elementwise sqrt of vector elements + * @param v is a vector * @return [sqrt(a(i))] */ Vector esqrt(const Vector& v); /** - * absolut values of vector elements - * @param a vector + * Absolute values of vector elements + * @param v is a vector * @return [abs(a(i))] */ Vector abs(const Vector& v); /** - * return the max element of a vector - * @param a vector + * Return the max element of a vector + * @param a is a vector * @return max(a) */ double max(const Vector &a); @@ -299,13 +290,13 @@ inline double inner_prod(const V1 &a, const V2& b) { /** * BLAS Level 1 scal: x <- alpha*x - * @DEPRECIATED: use operators instead + * \deprecated: use operators instead */ inline void scal(double alpha, Vector& x) { x *= alpha; } /** * BLAS Level 1 axpy: y <- alpha*x + y - * @DEPRECIATED: use operators instead + * \deprecated: use operators instead */ template inline void axpy(double alpha, const V1& x, V2& y) { @@ -357,20 +348,6 @@ Vector concatVectors(const std::list& vs); */ Vector concatVectors(size_t nrVectors, ...); -/** - * random vector - */ -Vector rand_vector_norm(size_t dim, double mean = 0, double sigma = 1); - -/** - * Sets the generator to use a different seed value. - * Default argument resets the RNG - * @param seed is the new seed - */ -inline void seedRNG(unsigned int seed = 42u) { - generator.seed(seed); -} - } // namespace gtsam #include diff --git a/gtsam/base/blockMatrices.h b/gtsam/base/blockMatrices.h index a1baecd76..c0bc95a50 100644 --- a/gtsam/base/blockMatrices.h +++ b/gtsam/base/blockMatrices.h @@ -40,7 +40,7 @@ template class SymmetricBlockView; * all rows, rowEnd() should be set to the number of rows in the matrix (i.e. * one after the last true row index). * - * @ingroup base + * @addtogroup base */ template class VerticalBlockView { @@ -330,7 +330,7 @@ private: * change the apparent matrix view. firstBlock() determines the block that * appears to have index 0 for all operations (except re-setting firstBlock()). * - * @ingroup base + * @addtogroup base */ template class SymmetricBlockView { diff --git a/gtsam/base/cholesky.cpp b/gtsam/base/cholesky.cpp index 66bbbde55..e941082ae 100644 --- a/gtsam/base/cholesky.cpp +++ b/gtsam/base/cholesky.cpp @@ -24,7 +24,7 @@ #include #include -#include +#include using namespace std; @@ -33,19 +33,23 @@ namespace gtsam { static const double negativePivotThreshold = -1e-1; static const double zeroPivotThreshold = 1e-6; static const double underconstrainedPrior = 1e-5; - static const bool dampUnderconstrained = false; + static const int underconstrainedExponentDifference = 12; /* ************************************************************************* */ -static inline bool choleskyStep(Matrix& ATA, size_t k, size_t order) { +static inline int choleskyStep(Matrix& ATA, size_t k, size_t order) { + + const bool debug = ISDEBUG("choleskyCareful"); // Get pivot value double alpha = ATA(k,k); // Correct negative pivots from round-off error if(alpha < negativePivotThreshold) { - cout << "pivot = " << alpha << endl; - print(ATA, "Partially-factorized matrix: "); - throw(CarefulCholeskyNegativeMatrixException()); + if(debug) { + cout << "pivot = " << alpha << endl; + print(ATA, "Partially-factorized matrix: "); + } + return -1; } else if(alpha < 0.0) alpha = 0.0; @@ -68,14 +72,14 @@ static inline bool choleskyStep(Matrix& ATA, size_t k, size_t order) { // ATA.bottomRightCorner(order-(k+1), order-(k+1)).selfadjointView() // .rankUpdate(V.adjoint(), -1); } - - return true; + return 1; } else { // For zero pivots, add the underconstrained variable prior ATA(k,k) = underconstrainedPrior; for(size_t j=k+1; j choleskyCareful(Matrix& ATA, int order) { // Negative order means factor the entire matrix if(order < 0) - order = n; + order = int(n); assert(size_t(order) <= n); // The index of the row after the last non-zero row of the square-root factor size_t maxrank = 0; - bool fullRank = true; + bool success = true; // Factor row-by-row for(size_t k = 0; k < size_t(order); ++k) { - if(choleskyStep(ATA, k, size_t(order))) { + int stepResult = choleskyStep(ATA, k, size_t(order)); + if(stepResult == 1) { if(debug) cout << "choleskyCareful: Factored through " << k << endl; if(debug) print(ATA, "ATA: "); maxrank = k+1; - } else { - fullRank = false; - if(debug) cout << "choleskyCareful: Skipping " << k << endl; - } + } else if(stepResult == -1) { + success = false; + break; + } /* else if(stepResult == 0) Found zero pivot */ } - return make_pair(maxrank, fullRank); + return make_pair(maxrank, success); } /* ************************************************************************* */ -void choleskyPartial(Matrix& ABC, size_t nFrontal) { +bool choleskyPartial(Matrix& ABC, size_t nFrontal) { const bool debug = ISDEBUG("choleskyPartial"); @@ -127,9 +132,8 @@ void choleskyPartial(Matrix& ABC, size_t nFrontal) { // Compute Cholesky factorization of A, overwrites A. tic(1, "lld"); - ABC.block(0,0,nFrontal,nFrontal).triangularView() = - ABC.block(0,0,nFrontal,nFrontal).selfadjointView().llt().matrixU(); - assert(ABC.topLeftCorner(nFrontal,nFrontal).triangularView().toDenseMatrix().unaryExpr(&isfinite).all()); + Eigen::LLT llt = ABC.block(0,0,nFrontal,nFrontal).selfadjointView().llt(); + ABC.block(0,0,nFrontal,nFrontal).triangularView() = llt.matrixU(); toc(1, "lld"); if(debug) cout << "R:\n" << Eigen::MatrixXd(ABC.topLeftCorner(nFrontal,nFrontal).triangularView()) << endl; @@ -140,7 +144,6 @@ void choleskyPartial(Matrix& ABC, size_t nFrontal) { ABC.topLeftCorner(nFrontal,nFrontal).triangularView().transpose().solveInPlace( ABC.topRightCorner(nFrontal, n-nFrontal)); } - assert(ABC.topRightCorner(nFrontal, n-nFrontal).unaryExpr(&isfinite).all()); if(debug) cout << "S:\n" << ABC.topRightCorner(nFrontal, n-nFrontal) << endl; toc(2, "compute S"); @@ -150,9 +153,29 @@ void choleskyPartial(Matrix& ABC, size_t nFrontal) { if(n - nFrontal > 0) ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView().rankUpdate( ABC.topRightCorner(nFrontal, n-nFrontal).transpose(), -1.0); - assert(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView().toDenseMatrix().unaryExpr(&isfinite).all()); if(debug) cout << "L:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView()) << endl; toc(3, "compute L"); + + // Check last diagonal element - Eigen does not check it + bool ok; + if(llt.info() == Eigen::Success) { + if(nFrontal >= 2) { + int exp2, exp1; + (void)frexp(ABC(nFrontal-2, nFrontal-2), &exp2); + (void)frexp(ABC(nFrontal-1, nFrontal-1), &exp1); + ok = (exp2 - exp1 < underconstrainedExponentDifference); + } else if(nFrontal == 1) { + int exp1; + (void)frexp(ABC(0,0), &exp1); + ok = (exp1 > -underconstrainedExponentDifference); + } else { + ok = true; + } + } else { + ok = false; + } + + return ok; } } diff --git a/gtsam/base/cholesky.h b/gtsam/base/cholesky.h index 50d3b24a8..8b1073107 100644 --- a/gtsam/base/cholesky.h +++ b/gtsam/base/cholesky.h @@ -22,45 +22,6 @@ namespace gtsam { -/** - * An exception indicating an attempt to factor a negative or indefinite matrix. - * If detailed exceptions are enabled, then the \c detail member will contain - * the matrices leading to the problem, see documentation for - * NegativeMatrixException::Detail. - */ -struct NegativeMatrixException : public std::exception { - /// Detail for NegativeMatrixException - struct Detail { - Matrix A; ///< The original matrix attempted to factor - Matrix U; ///< The produced upper-triangular factor - Matrix D; ///< The produced diagonal factor - Detail(const Matrix& _A, const Matrix& _U, const Matrix& _D) /**< Detail constructor */ : A(_A), U(_U), D(_D) {} - void print(const std::string& str = "") const { - std::cout << str << "\n"; - gtsam::print(A, " A: "); - gtsam::print(U, " U: "); - gtsam::print(D, " D: "); - } - }; - const boost::shared_ptr detail; ///< Detail - NegativeMatrixException() /**< Constructor with no detail */ {} - NegativeMatrixException(const Detail& _detail) /**< Constructor with detail */ : detail(new Detail(_detail)) {} - NegativeMatrixException(const boost::shared_ptr& _detail) /**< Constructor with detail */ : detail(_detail) {} - virtual ~NegativeMatrixException() throw() {} -}; - -/** - * An exception indicating an attempt to factor a negative or indefinite matrix. - * If detailed exceptions are enabled, then the \c detail member will contain - * the matrices leading to the problem, see documentation for - * CarefulCholeskyNegativeMatrixException::Detail. - */ -struct CarefulCholeskyNegativeMatrixException : public std::exception { - CarefulCholeskyNegativeMatrixException() throw() {} - virtual ~CarefulCholeskyNegativeMatrixException() throw() {} - const char* what() const throw() { return "The matrix was found to be non-positive-semidefinite when factoring with careful Cholesky."; } -}; - /** * "Careful" Cholesky computes the positive square-root of a positive symmetric * semi-definite matrix (i.e. that may be rank-deficient). Unlike standard @@ -70,6 +31,10 @@ struct CarefulCholeskyNegativeMatrixException : public std::exception { * non-zero row in the computed factor, so that it may be truncated to an * upper-trapazoidal matrix. * + * The second element of the return value is \c true if the matrix was factored + * successfully, or \c false if it was non-positive-semidefinite (i.e. + * indefinite or negative-(semi-)definite. + * * Note that this returned index is the rank of the matrix if and only if all * of the zero-rows of the factor occur after any non-zero rows. This is * (always?) the case during elimination of a fully-constrained least-squares @@ -77,6 +42,8 @@ struct CarefulCholeskyNegativeMatrixException : public std::exception { * * The optional order argument specifies the size of the square upper-left * submatrix to operate on, ignoring the rest of the matrix. + * + * */ std::pair choleskyCareful(Matrix& ATA, int order = -1); @@ -87,8 +54,11 @@ std::pair choleskyCareful(Matrix& ATA, int order = -1); * [B' C] * nFrontal determines the split between A, B, and C, with A being of size * nFrontal x nFrontal. + * + * @return \c true if the decomposition is successful, \c false if \c A was + * not positive-definite. */ -void choleskyPartial(Matrix& ABC, size_t nFrontal); +bool choleskyPartial(Matrix& ABC, size_t nFrontal); } diff --git a/gtsam/base/tests/testCholesky.cpp b/gtsam/base/tests/testCholesky.cpp index 63fdec810..8e8da7a70 100644 --- a/gtsam/base/tests/testCholesky.cpp +++ b/gtsam/base/tests/testCholesky.cpp @@ -81,7 +81,47 @@ TEST(cholesky, BadScalingSVD) { double expectedCondition = 1e40; double actualCondition = S(0) / S(1); - DOUBLES_EQUAL(expectedCondition, actualCondition, 1e-41); + DOUBLES_EQUAL(expectedCondition, actualCondition, 1e30); +} + +/* ************************************************************************* */ +TEST(cholesky, underconstrained) { + Matrix L(6,6); L << + 1, 0, 0, 0, 0, 0, + 1.11177808157954, 1.06204809504665, 0.507342638873381, 1.34953401829486, 1, 0, + 0.155864888199928, 1.10933048588373, 0.501255576961674, 1, 0, 0, + 1.12108665967793, 1.01584408366945, 1, 0, 0, 0, + 0.776164062474843, 0.117617236580373, -0.0236628691347294, 0.814118199972143, 0.694309975328922, 1, + 0.1197220685104, 1, 0, 0, 0, 0; + Matrix D1(6,6); D1 << + 0.814723686393179, 0, 0, 0, 0, 0, + 0, 0.811780089277421, 0, 0, 0, 0, + 0, 0, 1.82596950680844, 0, 0, 0, + 0, 0, 0, 0.240287537694585, 0, 0, + 0, 0, 0, 0, 1.34342584865901, 0, + 0, 0, 0, 0, 0, 1e-12; + Matrix D2(6,6); D2 << + 0.814723686393179, 0, 0, 0, 0, 0, + 0, 0.811780089277421, 0, 0, 0, 0, + 0, 0, 1.82596950680844, 0, 0, 0, + 0, 0, 0, 0.240287537694585, 0, 0, + 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0; + Matrix D3(6,6); D3 << + 0.814723686393179, 0, 0, 0, 0, 0, + 0, 0.811780089277421, 0, 0, 0, 0, + 0, 0, 1.82596950680844, 0, 0, 0, + 0, 0, 0, 0.240287537694585, 0, 0, + 0, 0, 0, 0, -0.5, 0, + 0, 0, 0, 0, 0, -0.6; + + Matrix A1 = L * D1 * L.transpose(); + Matrix A2 = L * D2 * L.transpose(); + Matrix A3 = L * D3 * L.transpose(); + + LONGS_EQUAL(long(false), long(choleskyPartial(A1, 6))); + LONGS_EQUAL(long(false), long(choleskyPartial(A2, 6))); + LONGS_EQUAL(long(false), long(choleskyPartial(A3, 6))); } /* ************************************************************************* */ diff --git a/gtsam_unstable/base/tests/testDSFVector.cpp b/gtsam/base/tests/testDSFVector.cpp similarity index 99% rename from gtsam_unstable/base/tests/testDSFVector.cpp rename to gtsam/base/tests/testDSFVector.cpp index 8997559f5..c0b72f1a0 100644 --- a/gtsam_unstable/base/tests/testDSFVector.cpp +++ b/gtsam/base/tests/testDSFVector.cpp @@ -24,7 +24,7 @@ using namespace boost::assign; #include -#include +#include using namespace std; using namespace gtsam; diff --git a/gtsam/base/tests/testDebug.cpp b/gtsam/base/tests/testDebug.cpp index f399dcb3b..81e4f039b 100644 --- a/gtsam/base/tests/testDebug.cpp +++ b/gtsam/base/tests/testDebug.cpp @@ -17,6 +17,7 @@ #include +#undef NDEBUG #define NDEBUG #undef GTSAM_ENABLE_DEBUG #include diff --git a/gtsam/base/tests/testLieMatrix.cpp b/gtsam/base/tests/testLieMatrix.cpp new file mode 100644 index 000000000..aad28563c --- /dev/null +++ b/gtsam/base/tests/testLieMatrix.cpp @@ -0,0 +1,70 @@ +/* ---------------------------------------------------------------------------- + + * 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 testLieMatrix.cpp + * @author Richard Roberts + */ + +#include + +#include +#include +#include + +using namespace gtsam; + +GTSAM_CONCEPT_TESTABLE_INST(LieMatrix) +GTSAM_CONCEPT_LIE_INST(LieMatrix) + +/* ************************************************************************* */ +TEST( LieMatrix, construction ) { + Matrix m = Matrix_(2,2, 1.0, 2.0, 3.0, 4.0); + LieMatrix lie1(m), lie2(m); + + EXPECT(lie1.dim() == 4); + EXPECT(assert_equal(m, lie1.matrix())); + EXPECT(assert_equal(lie1, lie2)); +} + +/* ************************************************************************* */ +TEST( LieMatrix, other_constructors ) { + Matrix init = Matrix_(2,2, 10.0, 20.0, 30.0, 40.0); + LieMatrix exp(init); + LieMatrix a(2,2,10.0,20.0,30.0,40.0); + double data[] = {10,30,20,40}; + LieMatrix b(2,2,data); + EXPECT(assert_equal(exp, a)); + EXPECT(assert_equal(exp, b)); + EXPECT(assert_equal(b, a)); +} + +/* ************************************************************************* */ +TEST(LieMatrix, retract) { + LieMatrix init(2,2, 1.0,2.0,3.0,4.0); + Vector update = Vector_(4, 3.0, 4.0, 6.0, 7.0); + + LieMatrix expected(2,2, 4.0, 6.0, 9.0, 11.0); + LieMatrix actual = init.retract(update); + + EXPECT(assert_equal(expected, actual)); + + LieMatrix expectedUpdate = update; + LieMatrix actualUpdate = init.localCoordinates(actual); + + EXPECT(assert_equal(expectedUpdate, actualUpdate)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ + + diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index ad6742613..56be42c02 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -17,6 +17,7 @@ **/ #include +#include #include #include #include @@ -261,6 +262,26 @@ TEST( matrix, insert_sub ) EXPECT(assert_equal(expected, big)); } +/* ************************************************************************* */ +TEST( matrix, stream_read ) { + Matrix expected = Matrix_(3,4, + 1.1, 2.3, 4.2, 7.6, + -0.3, -8e-2, 5.1, 9.0, + 1.2, 3.4, 4.5, 6.7); + + string matrixAsString = + "1.1 2.3 4.2 7.6\n" + "-0.3 -8e-2 5.1 9.0\n\r" // Test extra spaces and windows newlines + "1.2 \t 3.4 4.5 6.7"; // Test tab as separator + + stringstream asStream(matrixAsString, ios::in); + + Matrix actual; + asStream >> actual; + + EXPECT(assert_equal(expected, actual)); +} + /* ************************************************************************* */ TEST( matrix, scale_columns ) { @@ -1052,32 +1073,55 @@ TEST( matrix, svd3 ) /* ************************************************************************* */ TEST( matrix, svd4 ) { - Matrix U, V; - Vector s; + Matrix U, V; + Vector s; - Matrix A = Matrix_(3,2, - 0.8147, 0.9134, - 0.9058, 0.6324, - 0.1270, 0.0975); + Matrix A = Matrix_(3,2, + 0.8147, 0.9134, + 0.9058, 0.6324, + 0.1270, 0.0975); - Matrix expectedU = Matrix_(3,2, - 0.7397, 0.6724, - 0.6659, -0.7370, - 0.0970, -0.0689); + Matrix expectedU = Matrix_(3,2, + 0.7397, 0.6724, + 0.6659, -0.7370, + 0.0970, -0.0689); - Vector expected_s = Vector_(2, 1.6455, 0.1910); + Vector expected_s = Vector_(2, 1.6455, 0.1910); - Matrix expectedV = Matrix_(2,2, - 0.7403, -0.6723, - 0.6723, 0.7403); + Matrix expectedV = Matrix_(2,2, + 0.7403, -0.6723, + 0.6723, 0.7403); - svd(A, U, s, V); - Matrix reconstructed = U * diag(s) * trans(V); + svd(A, U, s, V); + Matrix reconstructed = U * diag(s) * trans(V); - EXPECT(assert_equal(A, reconstructed, 1e-4)); - EXPECT(assert_equal(expectedU,U, 1e-3)); - EXPECT(assert_equal(expected_s,s, 1e-4)); - EXPECT(assert_equal(expectedV,V, 1e-4)); + EXPECT(assert_equal(A, reconstructed, 1e-4)); + EXPECT(assert_equal(expectedU,U, 1e-3)); + EXPECT(assert_equal(expected_s,s, 1e-4)); + EXPECT(assert_equal(expectedV,V, 1e-4)); +} + +/* ************************************************************************* */ +TEST( matrix, DLT ) +{ + Matrix A = Matrix_(8,9, + 0.21, -0.42, -10.71, 0.18, -0.36, -9.18, -0.61, 1.22, 31.11, + 0.44, -0.66, -15.84, 0.34, -0.51, -12.24, -1.64, 2.46, 59.04, + 0.69, -8.28, -12.19, -0.48, 5.76, 8.48, -1.89, 22.68, 33.39, + 0.96, -8.4, -17.76, -0.6, 5.25, 11.1, -3.36, 29.4, 62.16, + 1.25, 0.3, 2.75, -3.5, -0.84, -7.7, 16.25, 3.9, 35.75, + 1.56, 0.42, 4.56, -3.38, -0.91, -9.88, 22.36, 6.02, 65.36, + 1.89, 2.24, 3.99, 3.24, 3.84, 6.84, 18.09, 21.44, 38.19, + 2.24, 2.48, 6.24, 3.08, 3.41, 8.58, 24.64, 27.28, 68.64 + ); + int rank; + double error; + Vector actual; + boost::tie(rank,error,actual) = DLT(A); + Vector expected = Vector_(9, -0.0, 0.2357, 0.4714, -0.2357, 0.0, - 0.4714,-0.4714, 0.4714, 0.0); + EXPECT_LONGS_EQUAL(8,rank); + EXPECT_DOUBLES_EQUAL(0,error,1e-8); + EXPECT(assert_equal(expected, actual, 1e-4)); } /* ************************************************************************* */ diff --git a/gtsam/base/tests/testVector.cpp b/gtsam/base/tests/testVector.cpp index 8b8757027..b8bb0333b 100644 --- a/gtsam/base/tests/testVector.cpp +++ b/gtsam/base/tests/testVector.cpp @@ -251,7 +251,7 @@ TEST( TestVector, axpy ) /* ************************************************************************* */ TEST( TestVector, equals ) { - Vector v1 = Vector_(1, 0.0/0.0); //testing nan + Vector v1 = Vector_(1, 0.0/std::numeric_limits::quiet_NaN()); //testing nan Vector v2 = Vector_(1, 1.0); double tol = 1.; EXPECT(!equal_with_abs_tol(v1, v2, tol)); @@ -297,27 +297,6 @@ TEST( TestVector, linear_dependent3 ) EXPECT(!linear_dependent(v1, v2)); } -/* ************************************************************************* */ -TEST( TestVector, random ) -{ - // Assumes seed not previously reset during this test - seedRNG(); - Vector v1_42 = rand_vector_norm(5); - - // verify that resetting the RNG produces the same value - seedRNG(); - Vector v2_42 = rand_vector_norm(5); - - EXPECT(assert_equal(v1_42, v2_42, 1e-6)); - - // verify that different seed produces a different value - seedRNG(41u); - - Vector v3_41 = rand_vector_norm(5); - - EXPECT(assert_inequal(v1_42, v3_41, 1e-6)); -} - /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/base/tests/timeVirtual.cpp b/gtsam/base/tests/timeVirtual.cpp index a61ce7b77..697a219b1 100644 --- a/gtsam/base/tests/timeVirtual.cpp +++ b/gtsam/base/tests/timeVirtual.cpp @@ -87,13 +87,13 @@ int main(int argc, char *argv[]) { tic_("shared plain alloc, dealloc"); for(size_t i=0; i obj(new Plain(i)); + boost::shared_ptr obj(new Plain(i)); } toc_("shared plain alloc, dealloc"); tic_("shared virtual alloc, dealloc"); for(size_t i=0; i obj(new Virtual(i)); + boost::shared_ptr obj(new Virtual(i)); } toc_("shared virtual alloc, dealloc"); @@ -130,14 +130,14 @@ int main(int argc, char *argv[]) { tic_("shared plain alloc, dealloc, call"); for(size_t i=0; i obj(new Plain(i)); + boost::shared_ptr obj(new Plain(i)); obj->setData(i+1); } toc_("shared plain alloc, dealloc, call"); tic_("shared virtual alloc, dealloc, call"); for(size_t i=0; i obj(new Virtual(i)); + boost::shared_ptr obj(new Virtual(i)); obj->setData(i+1); } toc_("shared virtual alloc, dealloc, call"); diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index 1388c2f18..162a1306f 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -20,7 +20,6 @@ #include #include #include -#include #include #include #include @@ -31,7 +30,9 @@ boost::shared_ptr timingRoot(new TimingOutline("Total")); boost::weak_ptr timingCurrent(timingRoot); +#ifdef ENABLE_OLD_TIMING Timing timing; +#endif std::string timingPrefix; /* ************************************************************************* */ @@ -48,7 +49,7 @@ void TimingOutline::add(size_t usecs) { /* ************************************************************************* */ TimingOutline::TimingOutline(const std::string& label) : - t_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), label_(label), timerActive_(false) {} + t_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), label_(label) {} /* ************************************************************************* */ size_t TimingOutline::time() const { @@ -151,18 +152,28 @@ const boost::shared_ptr& TimingOutline::child(size_t child, const /* ************************************************************************* */ void TimingOutline::tic() { +#ifdef GTSAM_USING_NEW_BOOST_TIMERS + assert(timer_.is_stopped()); + timer_.start(); +#else assert(!timerActive_); - timerActive_ = true; - gettimeofday(&t0_, NULL); + timer_.restart(); + *timerActive_ = true; +#endif } /* ************************************************************************* */ void TimingOutline::toc() { - struct timeval t; - gettimeofday(&t, NULL); - assert(timerActive_); - add(t.tv_sec*1000000 + t.tv_usec - (t0_.tv_sec*1000000 + t0_.tv_usec)); - timerActive_ = false; +#ifdef GTSAM_USING_NEW_BOOST_TIMERS + assert(!timer_.is_stopped()); + timer_.stop(); + add((timer_.elapsed().user + timer_.elapsed().system) / 1000); +#else + assert(timerActive_); + double elapsed = timer_.elapsed(); + add(size_t(elapsed * 1000000.0)); + *timerActive_ = false; +#endif } /* ************************************************************************* */ @@ -196,7 +207,7 @@ void toc_(size_t id) { != current->parent_.lock()->children_.end()) std::cout << "gtsam timing: Incorrect ID passed to toc, expected " << std::find(current->parent_.lock()->children_.begin(), current->parent_.lock()->children_.end(), current) - current->parent_.lock()->children_.begin() - << ", got " << id << std::endl; + << " \"" << current->label_ << "\", got " << id << std::endl; else std::cout << "gtsam timing: Incorrect ID passed to toc, id " << id << " does not exist" << std::endl; timingRoot->print(); @@ -231,6 +242,8 @@ void toc_(size_t id, const std::string& label) { toc_(id); } +#ifdef ENABLE_OLD_TIMING + /* ************************************************************************* */ // Timing class implementation void Timing::print() { @@ -260,3 +273,5 @@ void ticPop_(const std::string& prefix, const std::string& id) { else timingPrefix.resize(timingPrefix.size() - prefix.size() - 1); } + +#endif diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index 94498c3b3..8eb99f577 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -1,202 +1,224 @@ -/* ---------------------------------------------------------------------------- - - * 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 timing.h - * @brief Timing utilities - * @author Richard Roberts, Michael Kaess - * @date Oct 5, 2010 - */ -#pragma once - -#include -#include -#include -#include -#include - -class TimingOutline; -extern boost::shared_ptr timingRoot; -extern boost::weak_ptr timingCurrent; - -class TimingOutline { -protected: - size_t t_; - double t2_ ; /* cache the \sum t_i^2 */ - size_t tIt_; - size_t tMax_; - size_t tMin_; - size_t n_; - std::string label_; - - boost::weak_ptr parent_; - std::vector > children_; - struct timeval t0_; - bool timerActive_; - - void add(size_t usecs); - -public: - - TimingOutline(const std::string& label); - - size_t time() const; - - void print(const std::string& outline = "") const; - - void print2(const std::string& outline = "", const double parentTotal = -1.0) const; - - const boost::shared_ptr& child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr); - - void tic(); - - void toc(); - - void finishedIteration(); - - friend class AutoTimer; - friend void toc_(size_t id); - friend void toc_(size_t id, const std::string& label); -}; // \TimingOutline - -void tic_(size_t id, const std::string& label); - -void toc_(size_t id); - -void toc_(size_t id, const std::string& label); - -inline void tictoc_finishedIteration_() { - timingRoot->finishedIteration(); -} - -#ifdef ENABLE_TIMING -inline void tic(size_t id, const std::string& label) { tic_(id, label); } -inline void toc(size_t id) { toc_(id); } -inline void toc(size_t id, const std::string& label) { toc_(id, label); } -inline void tictoc_finishedIteration() { tictoc_finishedIteration_(); } -#else -inline void tic(size_t, const char*) {} -inline void toc(size_t) {} -inline void toc(size_t, const char*) {} -inline void tictoc_finishedIteration() {} -#endif - -// simple class for accumulating execution timing information by name -class Timing; -extern Timing timing; -extern std::string timingPrefix; - -double _tic(); -double _toc(double t); -double tic(const std::string& id); -double toc(const std::string& id); -void ticPush(const std::string& id); -void ticPop(const std::string& id); -void tictoc_print(); -void tictoc_finishedIteration(); - -/** These underscore versions work evening when ENABLE_TIMING is not defined */ -double _tic_(); -double _toc_(double t); -double tic_(const std::string& id); -double toc_(const std::string& id); -void ticPush_(const std::string& id); -void ticPop_(const std::string& id); -void tictoc_print_(); -void tictoc_finishedIteration_(); - - - -// simple class for accumulating execution timing information by name -class Timing { - class Stats { - public: - std::string label; - double t0; - double t; - double t_max; - double t_min; - int n; - }; - std::map stats; -public: - void add_t0(const std::string& id, double t0) { - stats[id].t0 = t0; - } - double get_t0(const std::string& id) { - return stats[id].t0; - } - void add_dt(const std::string& id, double dt) { - Stats& s = stats[id]; - s.t += dt; - s.n++; - if (s.n==1 || s.t_max < dt) s.t_max = dt; - if (s.n==1 || s.t_min > dt) s.t_min = dt; - } - void print(); - - double time(const std::string& id) { - Stats& s = stats[id]; - return s.t; - } -}; - -double _tic_(); -inline double _toc_(double t) { - double s = _tic_(); - return (std::max(0., s-t)); -} -inline double tic_(const std::string& id) { - double t0 = _tic_(); - timing.add_t0(timingPrefix + " " + id, t0); - return t0; -} -inline double toc_(const std::string& id) { - std::string comb(timingPrefix + " " + id); - double dt = _toc_(timing.get_t0(comb)); - timing.add_dt(comb, dt); - return dt; -} -inline void ticPush_(const std::string& prefix, const std::string& id) { - if(timingPrefix.size() > 0) - timingPrefix += "."; - timingPrefix += prefix; - tic_(id); -} -void ticPop_(const std::string& prefix, const std::string& id); - -inline void tictoc_print_() { - timing.print(); - timingRoot->print(); -} - -/* print mean and standard deviation */ -inline void tictoc_print2_() { - timingRoot->print2(); -} - -#ifdef ENABLE_TIMING -inline double _tic() { return _tic_(); } -inline double _toc(double t) { return _toc_(t); } -inline double tic(const std::string& id) { return tic_(id); } -inline double toc(const std::string& id) { return toc_(id); } -inline void ticPush(const std::string& prefix, const std::string& id) { ticPush_(prefix, id); } -inline void ticPop(const std::string& prefix, const std::string& id) { ticPop_(prefix, id); } -inline void tictoc_print() { tictoc_print_(); } -#else -inline double _tic() {return 0.;} -inline double _toc(double) {return 0.;} -inline double tic(const std::string&) {return 0.;} -inline double toc(const std::string&) {return 0.;} -inline void ticPush(const std::string&, const std::string&) {} -inline void ticPop(const std::string&, const std::string&) {} -inline void tictoc_print() {} -#endif +/* ---------------------------------------------------------------------------- + + * 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 timing.h + * @brief Timing utilities + * @author Richard Roberts, Michael Kaess + * @date Oct 5, 2010 + */ +#pragma once + +#include +#include +#include +#include +#include +#include + +// Enabling the new Boost timers introduces dependencies on other Boost +// libraries so this is disabled for now until we modify the build scripts +// to link each component or MATLAB wrapper with only the libraries it needs. +#if 0 +#if BOOST_VERSION >= 104800 +#define GTSAM_USING_NEW_BOOST_TIMERS +#endif +#endif + +#ifdef GTSAM_USING_NEW_BOOST_TIMERS +#include +#else +#include +#endif + +class TimingOutline; +extern boost::shared_ptr timingRoot; +extern boost::weak_ptr timingCurrent; + +class TimingOutline { +protected: + size_t t_; + double t2_ ; /* cache the \sum t_i^2 */ + size_t tIt_; + size_t tMax_; + size_t tMin_; + size_t n_; + std::string label_; + + boost::weak_ptr parent_; + std::vector > children_; +#ifdef GTSAM_USING_NEW_BOOST_TIMERS + boost::timer::cpu_timer timer_; +#else + boost::timer timer_; + gtsam::ValueWithDefault timerActive_; +#endif + + void add(size_t usecs); + +public: + + TimingOutline(const std::string& label); + + size_t time() const; + + void print(const std::string& outline = "") const; + + void print2(const std::string& outline = "", const double parentTotal = -1.0) const; + + const boost::shared_ptr& child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr); + + void tic(); + + void toc(); + + void finishedIteration(); + + friend class AutoTimer; + friend void toc_(size_t id); + friend void toc_(size_t id, const std::string& label); +}; // \TimingOutline + +void tic_(size_t id, const std::string& label); + +void toc_(size_t id); + +void toc_(size_t id, const std::string& label); + +inline void tictoc_finishedIteration_() { + timingRoot->finishedIteration(); +} + +inline void tictoc_print_() { + timingRoot->print(); +} + +/* print mean and standard deviation */ +inline void tictoc_print2_() { + timingRoot->print2(); +} + +#ifdef ENABLE_TIMING +inline void tic(size_t id, const std::string& label) { tic_(id, label); } +inline void toc(size_t id) { toc_(id); } +inline void toc(size_t id, const std::string& label) { toc_(id, label); } +inline void tictoc_finishedIteration() { tictoc_finishedIteration_(); } +inline void tictoc_print() { tictoc_print_(); } +#else +inline void tic(size_t, const char*) {} +inline void toc(size_t) {} +inline void toc(size_t, const char*) {} +inline void tictoc_finishedIteration() {} +inline void tictoc_print() {} +#endif + + +#ifdef ENABLE_OLD_TIMING + +// simple class for accumulating execution timing information by name +class Timing; +extern Timing timing; +extern std::string timingPrefix; + +double _tic(); +double _toc(double t); +double tic(const std::string& id); +double toc(const std::string& id); +void ticPush(const std::string& id); +void ticPop(const std::string& id); +void tictoc_finishedIteration(); + +/** These underscore versions work evening when ENABLE_TIMING is not defined */ +double _tic_(); +double _toc_(double t); +double tic_(const std::string& id); +double toc_(const std::string& id); +void ticPush_(const std::string& id); +void ticPop_(const std::string& id); +void tictoc_finishedIteration_(); + + + +// simple class for accumulating execution timing information by name +class Timing { + class Stats { + public: + std::string label; + double t0; + double t; + double t_max; + double t_min; + int n; + }; + std::map stats; +public: + void add_t0(const std::string& id, double t0) { + stats[id].t0 = t0; + } + double get_t0(const std::string& id) { + return stats[id].t0; + } + void add_dt(const std::string& id, double dt) { + Stats& s = stats[id]; + s.t += dt; + s.n++; + if (s.n==1 || s.t_max < dt) s.t_max = dt; + if (s.n==1 || s.t_min > dt) s.t_min = dt; + } + void print(); + + double time(const std::string& id) { + Stats& s = stats[id]; + return s.t; + } +}; + +double _tic_(); +inline double _toc_(double t) { + double s = _tic_(); + return (std::max(0., s-t)); +} +inline double tic_(const std::string& id) { + double t0 = _tic_(); + timing.add_t0(timingPrefix + " " + id, t0); + return t0; +} +inline double toc_(const std::string& id) { + std::string comb(timingPrefix + " " + id); + double dt = _toc_(timing.get_t0(comb)); + timing.add_dt(comb, dt); + return dt; +} +inline void ticPush_(const std::string& prefix, const std::string& id) { + if(timingPrefix.size() > 0) + timingPrefix += "."; + timingPrefix += prefix; + tic_(id); +} +void ticPop_(const std::string& prefix, const std::string& id); + +#ifdef ENABLE_TIMING +inline double _tic() { return _tic_(); } +inline double _toc(double t) { return _toc_(t); } +inline double tic(const std::string& id) { return tic_(id); } +inline double toc(const std::string& id) { return toc_(id); } +inline void ticPush(const std::string& prefix, const std::string& id) { ticPush_(prefix, id); } +inline void ticPop(const std::string& prefix, const std::string& id) { ticPop_(prefix, id); } +#else +inline double _tic() {return 0.;} +inline double _toc(double) {return 0.;} +inline double tic(const std::string&) {return 0.;} +inline double toc(const std::string&) {return 0.;} +inline void ticPush(const std::string&, const std::string&) {} +inline void ticPop(const std::string&, const std::string&) {} +#endif + +#endif diff --git a/gtsam/base/types.cpp b/gtsam/base/types.cpp new file mode 100644 index 000000000..ea4db72c8 --- /dev/null +++ b/gtsam/base/types.cpp @@ -0,0 +1,30 @@ +/* ---------------------------------------------------------------------------- + + * 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 types.h + * @brief Typedefs for easier changing of types + * @author Richard Roberts + * @date Aug 21, 2010 + * @addtogroup base + */ + +#include + +#include + +namespace gtsam { + + std::string _defaultIndexFormatter(Index j) { + return boost::lexical_cast(j); + } + +} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index b6c5617a5..a42c2acc5 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -14,18 +14,30 @@ * @brief Typedefs for easier changing of types * @author Richard Roberts * @date Aug 21, 2010 - * @defgroup base + * @addtogroup base */ #pragma once -#include +#include + +#include +#include namespace gtsam { /// Integer variable index type typedef size_t Index; + /** A function to convert indices to strings, for example by translating back + * to a nonlinear key and then to a Symbol. */ + typedef boost::function IndexFormatter; + + std::string _defaultIndexFormatter(Index j); + + /** The default IndexFormatter outputs the index */ + static const IndexFormatter DefaultIndexFormatter = &_defaultIndexFormatter; + /** * Helper class that uses templates to select between two types based on * whether TEST_TYPE is const or not. @@ -71,3 +83,35 @@ namespace gtsam { } +#ifdef _MSC_VER + +// Define some common g++ functions and macros that MSVC does not have + +#include +namespace std { + using boost::math::isfinite; + using boost::math::isnan; + using boost::math::isinf; +} + +#include +#ifndef M_PI +#define M_PI (boost::math::constants::pi()) +#endif +#ifndef M_PI_2 +#define M_PI_2 (boost::math::constants::pi() / 2.0) +#endif +#ifndef M_PI_4 +#define M_PI_4 (boost::math::constants::pi() / 4.0) +#endif + +#endif + +#ifdef min +#undef min +#endif + +#ifdef max +#undef max +#endif + diff --git a/gtsam/discrete/Assignment.h b/gtsam/discrete/Assignment.h index 06e2ac137..f6decc359 100644 --- a/gtsam/discrete/Assignment.h +++ b/gtsam/discrete/Assignment.h @@ -20,8 +20,10 @@ #include #include +#include #include + namespace gtsam { /** @@ -29,7 +31,7 @@ namespace gtsam { * Assigns to each label a value. Implemented as a simple map. * A discrete factor takes an Assignment and returns a value. */ - template + template class Assignment: public std::map { public: void print(const std::string& s = "Assignment: ") const { @@ -42,6 +44,44 @@ namespace gtsam { bool equals(const Assignment& other, double tol = 1e-9) const { return (*this == other); } - }; + }; //Assignment + + + /** + * @brief Get Cartesian product consisting all possible configurations + * @param vector list of keys (label,cardinality) pairs. + * @return vector list of all possible value assignments + * + * This function returns a vector of Assignment values for all possible + * (Cartesian product) configurations of set of Keys which are nothing + * but (Label,cardinality) pairs. This function should NOT be called for + * more than a small number of variables and cardinalities. E.g. For 6 + * variables with each having cardinalities 4, we get 4096 possible + * configurations!! + */ + template + std::vector > cartesianProduct( + const std::vector >& keys) { + std::vector > allPossValues; + Assignment values; + typedef std::pair DiscreteKey; + BOOST_FOREACH(const DiscreteKey& key, keys) + values[key.first] = 0; //Initialize from 0 + while (1) { + allPossValues.push_back(values); + size_t j = 0; + for (j = 0; j < keys.size(); j++) { + L idx = keys[j].first; + values[idx]++; + if (values[idx] < keys[j].second) + break; + //Wrap condition + values[idx] = 0; + } + if (j == keys.size()) + break; + } + return allPossValues; + } } // namespace gtsam diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 1fa750ace..057f014bf 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -27,6 +27,7 @@ #include #include #include +using boost::assign::operator+=; #include #include @@ -37,8 +38,6 @@ namespace gtsam { - using namespace boost::assign; - /*********************************************************************************/ // Node /*********************************************************************************/ @@ -81,7 +80,7 @@ namespace gtsam { bool equals(const Node& q, double tol) const { const Leaf* other = dynamic_cast (&q); if (!other) return false; - return fabs(this->constant_ - other->constant_) < tol; + return fabs(double(this->constant_ - other->constant_)) < tol; } /** print */ diff --git a/gtsam/discrete/DecisionTreeFactor.cpp b/gtsam/discrete/DecisionTreeFactor.cpp index 23b761b3b..bb83cec16 100644 --- a/gtsam/discrete/DecisionTreeFactor.cpp +++ b/gtsam/discrete/DecisionTreeFactor.cpp @@ -22,6 +22,7 @@ #include #include +#include using namespace std; @@ -48,10 +49,11 @@ namespace gtsam { } /* ************************************************************************* */ - void DecisionTreeFactor::print(const string& s) const { - cout << s << ":\n"; - IndexFactor::print("IndexFactor:"); - Potentials::print("Potentials:"); + void DecisionTreeFactor::print(const string& s, + const IndexFormatter& formatter) const { + cout << s; + IndexFactor::print("IndexFactor:",formatter); + Potentials::print("Potentials:",formatter); } /* ************************************************************************* */ @@ -94,8 +96,7 @@ namespace gtsam { Index j = keys()[i]; dkeys.push_back(DiscreteKey(j,cardinality(j))); } - shared_ptr f(new DecisionTreeFactor(dkeys, result)); - return f; + return boost::make_shared(dkeys, result); } /* ************************************************************************* */ diff --git a/gtsam/discrete/DecisionTreeFactor.h b/gtsam/discrete/DecisionTreeFactor.h index c63e59517..64f37c174 100644 --- a/gtsam/discrete/DecisionTreeFactor.h +++ b/gtsam/discrete/DecisionTreeFactor.h @@ -72,7 +72,8 @@ namespace gtsam { bool equals(const DecisionTreeFactor& other, double tol = 1e-9) const; // print - void print(const std::string& s = "DecisionTreeFactor: ") const; + virtual void print(const std::string& s = "DecisionTreeFactor:\n", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /// @} /// @name Standard Interface @@ -94,7 +95,7 @@ namespace gtsam { } /// Convert into a decisiontree - virtual operator DecisionTreeFactor() const { + virtual DecisionTreeFactor toDecisionTreeFactor() const { return *this; } @@ -127,6 +128,18 @@ namespace gtsam { */ shared_ptr combine(size_t nrFrontals, ADT::Binary op) const; + /** + * @brief Permutes the keys in Potentials and DiscreteFactor + * + * This re-implements the permuteWithInverse() in both Potentials + * and DiscreteFactor by doing both of them together. + */ + + void permuteWithInverse(const Permutation& inversePermutation){ + DiscreteFactor::permuteWithInverse(inversePermutation); + Potentials::permuteWithInverse(inversePermutation); + } + /// @} }; // DecisionTreeFactor diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 73649dce6..029873d2c 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -46,9 +46,9 @@ namespace gtsam { const DecisionTreeFactor& marginal) : IndexConditional(joint.keys(), joint.size() - marginal.size()), Potentials( ISDEBUG("DiscreteConditional::COUNT") ? joint : joint / marginal) { - assert(nrFrontals() == 1); +// assert(nrFrontals() == 1); if (ISDEBUG("DiscreteConditional::DiscreteConditional")) cout - << (firstFrontalKey()) << endl; + << (firstFrontalKey()) << endl; //TODO Print all keys } /* ******************************************************************************** */ @@ -66,7 +66,7 @@ namespace gtsam { Index j = (key); size_t value = parentsValues.at(j); pFS = pFS.choose(j, value); - } catch (exception& e) { + } catch (exception&) { throw runtime_error( "DiscreteConditional::choose: parent value missing"); }; @@ -75,10 +75,44 @@ namespace gtsam { /* ******************************************************************************** */ void DiscreteConditional::solveInPlace(Values& values) const { - assert(nrFrontals() == 1); - Index j = (firstFrontalKey()); - size_t mpe = solve(values); // Solve for variable - values[j] = mpe; // store result in partial solution +// OLD +// assert(nrFrontals() == 1); +// Index j = (firstFrontalKey()); +// size_t mpe = solve(values); // Solve for variable +// values[j] = mpe; // store result in partial solution +// OLD + + // TODO: is this really the fastest way? I think it is. + + //The following is to make make adjustment for nFrontals \neq 1 + ADT pFS = choose(values); // P(F|S=parentsValues) + + // Initialize + Values mpe; + double maxP = 0; + + DiscreteKeys keys; + BOOST_FOREACH(Index idx, frontals()) { + DiscreteKey dk(idx,cardinality(idx)); + keys & dk; + } + // Get all Possible Configurations + vector allPosbValues = cartesianProduct(keys); + + // Find the MPE + BOOST_FOREACH(Values& frontalVals, allPosbValues) { + double pValueS = pFS(frontalVals); // P(F=value|S=parentsValues) + // Update MPE solution if better + if (pValueS > maxP) { + maxP = pValueS; + mpe = frontalVals; + } + } + + //set values (inPlace) to mpe + BOOST_FOREACH(Index j, frontals()) { + values[j] = mpe[j]; + } } /* ******************************************************************************** */ @@ -155,7 +189,14 @@ namespace gtsam { return sampled; return 0; - } + } + + /* ******************************************************************************** */ + void DiscreteConditional::permuteWithInverse(const Permutation& inversePermutation){ + IndexConditional::permuteWithInverse(inversePermutation); + Potentials::permuteWithInverse(inversePermutation); + } + /* ******************************************************************************** */ diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index f6603c195..e05bfd669 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -63,9 +63,11 @@ namespace gtsam { /// @{ /** GTSAM-style print */ - void print(const std::string& s = "Discrete Conditional: ") const { + void print(const std::string& s = "Discrete Conditional: ", + const IndexFormatter& formatter + =DefaultIndexFormatter) const { std::cout << s << std::endl; - IndexConditional::print(s); + IndexConditional::print(s, formatter); Potentials::print(s); } @@ -89,14 +91,14 @@ namespace gtsam { /** * solve a conditional - * @param parentsAssignment Known values of the parents + * @param parentsValues Known values of the parents * @return MPE value of the child (1 frontal variable). */ size_t solve(const Values& parentsValues) const; /** * sample - * @param parentsAssignment Known values of the parents + * @param parentsValues Known values of the parents * @return sample from conditional */ size_t sample(const Values& parentsValues) const; @@ -111,6 +113,11 @@ namespace gtsam { /// sample in place, stores result in partial solution void sampleInPlace(Values& parentsValues) const; + /** + * Permutes both IndexConditional and Potentials. + */ + void permuteWithInverse(const Permutation& inversePermutation); + /// @} }; diff --git a/gtsam/discrete/DiscreteFactor.h b/gtsam/discrete/DiscreteFactor.h index 8152ff726..9b1130bae 100644 --- a/gtsam/discrete/DiscreteFactor.h +++ b/gtsam/discrete/DiscreteFactor.h @@ -82,8 +82,10 @@ namespace gtsam { /// @{ // print - virtual void print(const std::string& s = "DiscreteFactor") const { - IndexFactor::print(s); + virtual void print(const std::string& s = "DiscreteFactor\n", + const IndexFormatter& formatter + =DefaultIndexFormatter) const { + IndexFactor::print(s,formatter); } /// @} @@ -96,7 +98,15 @@ namespace gtsam { /// Multiply in a DecisionTreeFactor and return the result as DecisionTreeFactor virtual DecisionTreeFactor operator*(const DecisionTreeFactor&) const = 0; - virtual operator DecisionTreeFactor() const = 0; + virtual DecisionTreeFactor toDecisionTreeFactor() const = 0; + + /** + * Permutes the factor, but for efficiency requires the permutation + * to already be inverted. + */ + virtual void permuteWithInverse(const Permutation& inversePermutation){ + IndexFactor::permuteWithInverse(inversePermutation); + } /// @} }; diff --git a/gtsam/discrete/DiscreteFactorGraph.cpp b/gtsam/discrete/DiscreteFactorGraph.cpp index f5fc7533d..f3c89721b 100644 --- a/gtsam/discrete/DiscreteFactorGraph.cpp +++ b/gtsam/discrete/DiscreteFactorGraph.cpp @@ -24,69 +24,84 @@ namespace gtsam { -// Explicitly instantiate so we don't have to include everywhere -template class FactorGraph ; -template class EliminationTree ; + // Explicitly instantiate so we don't have to include everywhere + template class FactorGraph ; + template class EliminationTree ; -/* ************************************************************************* */ -DiscreteFactorGraph::DiscreteFactorGraph() { -} + /* ************************************************************************* */ + DiscreteFactorGraph::DiscreteFactorGraph() { + } -/* ************************************************************************* */ -DiscreteFactorGraph::DiscreteFactorGraph( - const BayesNet& bayesNet) : - FactorGraph(bayesNet) { -} + /* ************************************************************************* */ + DiscreteFactorGraph::DiscreteFactorGraph( + const BayesNet& bayesNet) : + FactorGraph(bayesNet) { + } -/* ************************************************************************* */ -FastSet DiscreteFactorGraph::keys() const { - FastSet keys; - BOOST_FOREACH(const sharedFactor& factor, *this) - if (factor) keys.insert(factor->begin(), factor->end()); - return keys; -} + /* ************************************************************************* */ + FastSet DiscreteFactorGraph::keys() const { + FastSet keys; + BOOST_FOREACH(const sharedFactor& factor, *this) + if (factor) keys.insert(factor->begin(), factor->end()); + return keys; + } -/* ************************************************************************* */ -DecisionTreeFactor DiscreteFactorGraph::product() const { - DecisionTreeFactor result; - BOOST_FOREACH(const sharedFactor& factor, *this) - if (factor) result = (*factor) * result; - return result; -} + /* ************************************************************************* */ + DecisionTreeFactor DiscreteFactorGraph::product() const { + DecisionTreeFactor result; + BOOST_FOREACH(const sharedFactor& factor, *this) + if (factor) result = (*factor) * result; + return result; + } -/* ************************************************************************* */ -double DiscreteFactorGraph::operator()( - const DiscreteFactor::Values &values) const { - double product = 1.0; - BOOST_FOREACH( const sharedFactor& factor, factors_ ) - product *= (*factor)(values); - return product; -} + /* ************************************************************************* */ + double DiscreteFactorGraph::operator()( + const DiscreteFactor::Values &values) const { + double product = 1.0; + BOOST_FOREACH( const sharedFactor& factor, factors_ ) + product *= (*factor)(values); + return product; + } -/* ************************************************************************* */ -pair // -EliminateDiscrete(const FactorGraph& factors, size_t num) { + /* ************************************************************************* */ + void DiscreteFactorGraph::print(const std::string& s, + const IndexFormatter& formatter) const { + std::cout << s << std::endl; + std::cout << "size: " << size() << std::endl; + for (size_t i = 0; i < factors_.size(); i++) { + std::stringstream ss; + ss << "factor " << i << ": "; + if (factors_[i] != NULL) factors_[i]->print(ss.str(), formatter); + } + } - // PRODUCT: multiply all factors - tic(1, "product"); - DecisionTreeFactor product; - BOOST_FOREACH(const DiscreteFactor::shared_ptr& factor, factors) - product = (*factor) * product; - toc(1, "product"); + /* ************************************************************************* */ + std::pair // + EliminateDiscrete(const FactorGraph& factors, size_t num) { - // sum out frontals, this is the factor on the separator - tic(2, "sum"); - DecisionTreeFactor::shared_ptr sum = product.sum(num); - toc(2, "sum"); + // PRODUCT: multiply all factors + tic(1, "product"); + DecisionTreeFactor product; + BOOST_FOREACH(const DiscreteFactor::shared_ptr& factor, factors){ + product = (*factor) * product; + } - // now divide product/sum to get conditional - tic(3, "divide"); - DiscreteConditional::shared_ptr cond(new DiscreteConditional(product, *sum)); - toc(3, "divide"); - tictoc_finishedIteration(); + toc(1, "product"); + + // sum out frontals, this is the factor on the separator + tic(2, "sum"); + DecisionTreeFactor::shared_ptr sum = product.sum(num); + toc(2, "sum"); + + // now divide product/sum to get conditional + tic(3, "divide"); + DiscreteConditional::shared_ptr cond(new DiscreteConditional(product, *sum)); + toc(3, "divide"); + tictoc_finishedIteration(); + + return std::make_pair(cond, sum); + } - return make_pair(cond, sum); -} /* ************************************************************************* */ } // namespace diff --git a/gtsam/discrete/DiscreteFactorGraph.h b/gtsam/discrete/DiscreteFactorGraph.h index eefdfaf1d..0f399abdd 100644 --- a/gtsam/discrete/DiscreteFactorGraph.h +++ b/gtsam/discrete/DiscreteFactorGraph.h @@ -77,16 +77,8 @@ public: double operator()(const DiscreteFactor::Values & values) const; /// print - void print(const std::string& s = "DiscreteFactorGraph") const { - std::cout << s << std::endl; - std::cout << "size: " << size() << std::endl; - for (size_t i = 0; i < factors_.size(); i++) { - std::stringstream ss; - ss << "factor " << i << ": "; - if (factors_[i] != NULL) factors_[i]->print(ss.str()); - } - } - + void print(const std::string& s = "DiscreteFactorGraph", + const IndexFormatter& formatter =DefaultIndexFormatter) const; }; // DiscreteFactorGraph diff --git a/gtsam/discrete/DiscreteMarginals.h b/gtsam/discrete/DiscreteMarginals.h new file mode 100644 index 000000000..1e89286a8 --- /dev/null +++ b/gtsam/discrete/DiscreteMarginals.h @@ -0,0 +1,78 @@ +/* ---------------------------------------------------------------------------- + + * 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 DiscreteMarginals.h + * @brief A class for computing marginals in a DiscreteFactorGraph + * @author Abhijit Kundu + * @author Richard Roberts + * @author Frank Dellaert + * @date June 4, 2012 + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + + /** + * A class for computing marginals of variables in a DiscreteFactorGraph + */ + class DiscreteMarginals { + + protected: + + BayesTree bayesTree_; + + public: + + /** Construct a marginals class. + * @param graph The factor graph defining the full joint density on all variables. + */ + DiscreteMarginals(const DiscreteFactorGraph& graph) { + typedef JunctionTree DiscreteJT; + GenericMultifrontalSolver solver(graph); + bayesTree_ = *solver.eliminate(&EliminateDiscrete); + } + + /** Compute the marginal of a single variable */ + DiscreteFactor::shared_ptr operator()(Index variable) const { + // Compute marginal + DiscreteFactor::shared_ptr marginalFactor; + marginalFactor = bayesTree_.marginalFactor(variable, &EliminateDiscrete); + return marginalFactor; + } + + /** Compute the marginal of a single variable + * @param key DiscreteKey of the Variable + * @return Vector of marginal probabilities + */ + Vector marginalProbabilities(const DiscreteKey& key) const { + // Compute marginal + DiscreteFactor::shared_ptr marginalFactor; + marginalFactor = bayesTree_.marginalFactor(key.first, &EliminateDiscrete); + + //Create result + Vector vResult(key.second); + for (size_t state = 0; state < key.second ; ++ state) { + DiscreteFactor::Values values; + values[key.first] = state; + vResult(state) = (*marginalFactor)(values); + } + return vResult; + } + + }; + +} /* namespace gtsam */ diff --git a/gtsam/discrete/DiscreteSequentialSolver.cpp b/gtsam/discrete/DiscreteSequentialSolver.cpp index 1ca00875a..e4bc502c8 100644 --- a/gtsam/discrete/DiscreteSequentialSolver.cpp +++ b/gtsam/discrete/DiscreteSequentialSolver.cpp @@ -52,6 +52,24 @@ namespace gtsam { return solution; } + + /* ************************************************************************* */ + Vector DiscreteSequentialSolver::marginalProbabilities( + const DiscreteKey& key) const { + // Compute marginal + DiscreteFactor::shared_ptr marginalFactor; + marginalFactor = Base::marginalFactor(key.first, &EliminateDiscrete); + + //Create result + Vector vResult(key.second); + for (size_t state = 0; state < key.second; ++state) { + DiscreteFactor::Values values; + values[key.first] = state; + vResult(state) = (*marginalFactor)(values); + } + return vResult; + } + /* ************************************************************************* */ } diff --git a/gtsam/discrete/DiscreteSequentialSolver.h b/gtsam/discrete/DiscreteSequentialSolver.h index c453f5b96..6adb32ef6 100644 --- a/gtsam/discrete/DiscreteSequentialSolver.h +++ b/gtsam/discrete/DiscreteSequentialSolver.h @@ -74,7 +74,6 @@ namespace gtsam { return Base::eliminate(&EliminateDiscrete); } -#ifdef BROKEN /** * Compute the marginal joint over a set of variables, by integrating out * all of the other variables. This function returns the result as a factor @@ -94,7 +93,13 @@ namespace gtsam { DiscreteFactor::shared_ptr marginalFactor(Index j) const { return Base::marginalFactor(j, &EliminateDiscrete); } -#endif + + /** + * Compute the marginal density over a variable, by integrating out + * all of the other variables. This function returns the result as a + * Vector of the probability values. + */ + Vector marginalProbabilities(const DiscreteKey& key) const; /** * Compute the MPE solution of the DiscreteFactorGraph. This diff --git a/gtsam/discrete/Potentials.cpp b/gtsam/discrete/Potentials.cpp index ac6ecde10..2a2260d97 100644 --- a/gtsam/discrete/Potentials.cpp +++ b/gtsam/discrete/Potentials.cpp @@ -51,14 +51,37 @@ namespace gtsam { } /* ************************************************************************* */ - void Potentials::print(const string&s) const { + void Potentials::print(const string& s, + const IndexFormatter& formatter) const { cout << s << "\n Cardinalities: "; BOOST_FOREACH(const DiscreteKey& key, cardinalities_) - cout << key.first << "=" << key.second << " "; + cout << formatter(key.first) << "=" << formatter(key.second) << " "; cout << endl; ADT::print(" "); } /* ************************************************************************* */ + void Potentials::permuteWithInverse(const Permutation& permutation) { + // Permute the _cardinalities (TODO: Inefficient Consider Improving) + DiscreteKeys keys; + map ordering; + + // Get the orginal keys from cardinalities_ + BOOST_FOREACH(const DiscreteKey& key, cardinalities_) + keys & key; + + // Perform Permutation + BOOST_FOREACH(DiscreteKey& key, keys) { + ordering[key.first] = permutation[key.first]; + key.first = ordering[key.first]; + } + + // Change *this + AlgebraicDecisionTree permuted((*this), ordering); + *this = permuted; + cardinalities_ = keys.cardinalities(); + } + + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/discrete/Potentials.h b/gtsam/discrete/Potentials.h index 8a8c2e3bc..3ca222b5f 100644 --- a/gtsam/discrete/Potentials.h +++ b/gtsam/discrete/Potentials.h @@ -20,6 +20,7 @@ #include #include #include +#include #include #include @@ -64,10 +65,20 @@ namespace gtsam { // Testable bool equals(const Potentials& other, double tol = 1e-9) const; - void print(const std::string& s = "Potentials: ") const; + void print(const std::string& s = "Potentials: ", + const IndexFormatter& formatter = DefaultIndexFormatter) const; size_t cardinality(Index j) const { return cardinalities_.at(j);} + /** + * @brief Permutes the keys in Potentials + * + * This permutes the Indices and performs necessary re-ordering of ADD. + * This is virtual so that derived types e.g. DecisionTreeFactor can + * re-implement it. + */ + virtual void permuteWithInverse(const Permutation& inversePermutation); + }; // Potentials } // namespace gtsam diff --git a/gtsam/discrete/Signature.cpp b/gtsam/discrete/Signature.cpp index ee7c1e59a..76ccad9db 100644 --- a/gtsam/discrete/Signature.cpp +++ b/gtsam/discrete/Signature.cpp @@ -21,18 +21,15 @@ #include "Signature.h" -#ifdef BOOST_HAVE_PARSER #include // for parsing #include // for qi::_val -#endif namespace gtsam { using namespace std; - -#ifdef BOOST_HAVE_PARSER namespace qi = boost::spirit::qi; + namespace ph = boost::phoenix; // parser for strings of form "99/1 80/20" etc... namespace parser { @@ -85,9 +82,9 @@ namespace gtsam { // check for OR, AND on whole phrase It f = spec.begin(), l = spec.end(); if (qi::parse(f, l, - qi::lit("OR")[ref(table) = logic(false, true, true, true)]) || + qi::lit("OR")[ph::ref(table) = logic(false, true, true, true)]) || qi::parse(f, l, - qi::lit("AND")[ref(table) = logic(false, false, false, true)])) + qi::lit("AND")[ph::ref(table) = logic(false, false, false, true)])) return true; // tokenize into separate rows @@ -97,9 +94,9 @@ namespace gtsam { Signature::Row values; It tf = token.begin(), tl = token.end(); bool r = qi::parse(tf, tl, - qi::double_[push_back(ref(values), qi::_1)] >> +("/" >> qi::double_[push_back(ref(values), qi::_1)]) | - qi::lit("T")[ref(values) = T] | - qi::lit("F")[ref(values) = F] ); + qi::double_[push_back(ph::ref(values), qi::_1)] >> +("/" >> qi::double_[push_back(ph::ref(values), qi::_1)]) | + qi::lit("T")[ph::ref(values) = T] | + qi::lit("F")[ph::ref(values) = F] ); if (!r) return false; table.push_back(values); @@ -108,7 +105,6 @@ namespace gtsam { return true; } } // \namespace parser -#endif ostream& operator <<(ostream &os, const Signature::Row &row) { os << row[0]; @@ -168,7 +164,6 @@ namespace gtsam { Signature& Signature::operator=(const string& spec) { spec_.reset(spec); -#ifdef BOOST_HAVE_PARSER Table table; // NOTE: using simpler parse function to ensure boost back compatibility // parser::It f = spec.begin(), l = spec.end(); @@ -180,7 +175,6 @@ namespace gtsam { normalize(row); table_.reset(table); } -#endif return *this; } diff --git a/gtsam/discrete/Signature.h b/gtsam/discrete/Signature.h index 873365c24..937bd6e1b 100644 --- a/gtsam/discrete/Signature.h +++ b/gtsam/discrete/Signature.h @@ -22,11 +22,6 @@ #include #include -#include // for checking whether we are using boost 1.40 -#if BOOST_VERSION >= 104200 -#define BOOST_HAVE_PARSER -#endif - namespace gtsam { /** diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index bfeacb8e4..8ab3b6a14 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -23,10 +23,6 @@ #include #include // for convert only #define DISABLE_TIMING -#include // for checking whether we are using boost 1.40 -#if BOOST_VERSION >= 104200 -#define BOOST_HAVE_PARSER -#endif #include #include @@ -150,7 +146,6 @@ TEST(ADT, joint) { DiscreteKey A(0, 2), S(1, 2), T(2, 2), L(3, 2), B(4, 2), E(5, 2), X(6, 2), D(7, 2); -#ifdef BOOST_HAVE_PARSER resetCounts(); ADT pA = create(A % "99/1"); ADT pS = create(S % "50/50"); @@ -193,7 +188,6 @@ TEST(ADT, joint) EXPECT(assert_equal(pA, fAa)); ADT fAb = pASTL.combine(S, &add_).combine(T, &add_).combine(L, &add_); EXPECT(assert_equal(pA, fAb)); -#endif } /* ************************************************************************* */ @@ -203,7 +197,6 @@ TEST(ADT, inference) DiscreteKey A(0,2), D(1,2),// B(2,2), L(3,2), E(4,2), S(5,2), T(6,2), X(7,2); -#ifdef BOOST_HAVE_PARSER resetCounts(); ADT pA = create(A % "99/1"); ADT pS = create(S % "50/50"); @@ -247,7 +240,6 @@ TEST(ADT, inference) dot(marginal, "Joint-Sum-ADBL"); EXPECT_LONGS_EQUAL(161, adds); printCounts("Asia sum"); -#endif } /* ************************************************************************* */ @@ -255,7 +247,6 @@ TEST(ADT, factor_graph) { DiscreteKey B(0,2), L(1,2), E(2,2), S(3,2), T(4,2), X(5,2); -#ifdef BOOST_HAVE_PARSER resetCounts(); ADT pS = create(S % "50/50"); ADT pT = create(T % "95/5"); @@ -334,7 +325,6 @@ TEST(ADT, factor_graph) fB = fB.combine(L, &add_); dot(fB, "Eliminate-10-fB"); printCounts("Eliminate L"); -#endif } /* ************************************************************************* */ @@ -360,7 +350,6 @@ TEST(ADT, equality_noparser) } /* ************************************************************************* */ -#ifdef BOOST_HAVE_PARSER // test equality TEST(ADT, equality_parser) { @@ -376,7 +365,6 @@ TEST(ADT, equality_parser) ADT pAB2 = apply(pB, pA1, &mul); EXPECT(pAB2 == pAB1); } -#endif /* ******************************************************************************** */ // Factor graph construction diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index f67df51a8..1dfcd3057 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -41,6 +41,9 @@ void dot(const T&f, const string& filename) { #define DOT(x)(dot(x,#x)) +struct Crazy { int a; double b; }; +typedef DecisionTree CrazyDecisionTree; // check that DecisionTree is actually generic (as it pretends to be) + /* ******************************************************************************** */ // Test string labels and int range /* ******************************************************************************** */ diff --git a/gtsam/discrete/tests/testDiscreteBayesNet.cpp b/gtsam/discrete/tests/testDiscreteBayesNet.cpp index bc07d57ca..63f225c35 100644 --- a/gtsam/discrete/tests/testDiscreteBayesNet.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesNet.cpp @@ -25,10 +25,6 @@ #include using namespace boost::assign; -#include // for checking whether we are using boost 1.40 -#if BOOST_VERSION >= 104200 -#define BOOST_HAVE_PARSER -#endif #include @@ -44,7 +40,6 @@ TEST(DiscreteBayesNet, Asia) DiscreteKey A(0,2), S(4,2), T(3,2), L(6,2), B(7,2), E(5,2), X(2,2), D(1,2); // TODO: make a version that doesn't use the parser -#ifdef BOOST_HAVE_PARSER add_front(asia, A % "99/1"); add_front(asia, S % "50/50"); @@ -104,7 +99,6 @@ TEST(DiscreteBayesNet, Asia) S.first, 1)(E.first, 0)(L.first, 0)(B.first, 1); DiscreteFactor::sharedValues actualSample = sample(*chordal2); EXPECT(assert_equal(expectedSample, *actualSample)); -#endif } /* ************************************************************************* */ @@ -114,7 +108,6 @@ TEST_UNSAFE(DiscreteBayesNet, Sugar) DiscreteBayesNet bn; -#ifdef BOOST_HAVE_PARSER // test some mistakes // add(bn, D); // add(bn, D | E); @@ -127,7 +120,6 @@ TEST_UNSAFE(DiscreteBayesNet, Sugar) // // try multivalued add(bn, C % "1/1/2"); add(bn, C | S = "1/1/2 5/2/3"); -#endif } /* ************************************************************************* */ diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index c11dddef5..8af23e4f8 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -24,10 +24,6 @@ using namespace boost::assign; #include #include #include -#include // for checking whether we are using boost 1.40 -#if BOOST_VERSION >= 104200 -#define BOOST_HAVE_PARSER -#endif using namespace std; using namespace gtsam; @@ -37,17 +33,31 @@ TEST( DiscreteConditionalTest, constructors) { DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! -#ifdef BOOST_HAVE_PARSER DiscreteConditional::shared_ptr expected1 = // boost::make_shared(X | Y = "1/1 2/3 1/4"); -#else + EXPECT(expected1); + DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); + DiscreteConditional actual1(1, f1); + EXPECT(assert_equal(*expected1, actual1, 1e-9)); + + DecisionTreeFactor f2(X & Y & Z, + "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); + DiscreteConditional actual2(1, f2); + DecisionTreeFactor::shared_ptr actual2factor = actual2.toFactor(); +// EXPECT(assert_equal(f2, *actual2factor, 1e-9)); +} + +/* ************************************************************************* */ +TEST( DiscreteConditionalTest, constructors_alt_interface) +{ + DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! + Signature::Table table; Signature::Row r1, r2, r3; r1 += 1.0, 1.0; r2 += 2.0, 3.0; r3 += 1.0, 4.0; table += r1, r2, r3; DiscreteConditional::shared_ptr expected1 = // boost::make_shared(X | Y = table); -#endif EXPECT(expected1); DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); DiscreteConditional actual1(1, f1); @@ -63,7 +73,6 @@ TEST( DiscreteConditionalTest, constructors) /* ************************************************************************* */ TEST( DiscreteConditionalTest, constructors2) { -#ifdef BOOST_HAVE_PARSER // Declare keys and ordering DiscreteKey C(0,2), B(1,2); DecisionTreeFactor expected(C & B, "0.8 0.75 0.2 0.25"); @@ -71,13 +80,11 @@ TEST( DiscreteConditionalTest, constructors2) DiscreteConditional actual(signature); DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); EXPECT(assert_equal(expected, *actualFactor)); -#endif - } +} /* ************************************************************************* */ TEST( DiscreteConditionalTest, constructors3) { -#ifdef BOOST_HAVE_PARSER // Declare keys and ordering DiscreteKey C(0,2), B(1,2), A(2,2); DecisionTreeFactor expected(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8"); @@ -85,13 +92,9 @@ TEST( DiscreteConditionalTest, constructors3) DiscreteConditional actual(signature); DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); EXPECT(assert_equal(expected, *actualFactor)); -#endif } /* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index f3ca4b59e..8fdbc5870 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -10,8 +10,7 @@ * -------------------------------------------------------------------------- */ /* - * testDiscreteFactorGraph.cpp - * + * @file testDiscreteFactorGraph.cpp * @date Feb 14, 2011 * @author Duy-Nguyen Ta */ @@ -25,10 +24,6 @@ #include using namespace boost::assign; -#include // for checking whether we are using boost 1.40 -#if BOOST_VERSION >= 104200 -#define BOOST_HAVE_PARSER -#endif using namespace std; using namespace gtsam; @@ -137,7 +132,6 @@ TEST( DiscreteFactorGraph, test) boost::tie(conditional, newFactor) =// EliminateDiscrete(graph, 1); -#ifdef BOOST_HAVE_PARSER // Check Bayes net CHECK(conditional); DiscreteBayesNet expected; @@ -174,7 +168,6 @@ TEST( DiscreteFactorGraph, test) insert(expectedValues)(0, 0)(1, 0)(2, 0); DiscreteFactor::sharedValues actualValues = solver.optimize(); EXPECT(assert_equal(expectedValues, *actualValues)); -#endif } /* ************************************************************************* */ diff --git a/gtsam/discrete/tests/testDiscreteMarginals.cpp b/gtsam/discrete/tests/testDiscreteMarginals.cpp new file mode 100644 index 000000000..7f2b7b1b1 --- /dev/null +++ b/gtsam/discrete/tests/testDiscreteMarginals.cpp @@ -0,0 +1,105 @@ +/* ---------------------------------------------------------------------------- + + * 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 testDiscreteMarginals.cpp + * @date Jun 7, 2012 + * @author Abhijit Kundu + * @author Richard Roberts + * @author Frank Dellaert + */ + +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ + +TEST_UNSAFE( DiscreteMarginals, UGM_small ) { + size_t nrStates = 2; + DiscreteKey Cathy(1, nrStates), Heather(2, nrStates), Mark(3, nrStates), + Allison(4, nrStates); + DiscreteFactorGraph graph; + + // add node potentials + graph.add(Cathy, "1 3"); + graph.add(Heather, "9 1"); + graph.add(Mark, "1 3"); + graph.add(Allison, "9 1"); + + // add edge potentials + graph.add(Cathy & Heather, "2 1 1 2"); + graph.add(Heather & Mark, "2 1 1 2"); + graph.add(Mark & Allison, "2 1 1 2"); + + DiscreteMarginals marginals(graph); + DiscreteFactor::shared_ptr actualC = marginals(Cathy.first); + DiscreteFactor::Values values; + + values[Cathy.first] = 0; + EXPECT_DOUBLES_EQUAL( 0.359631, (*actualC)(values), 1e-6); + + Vector actualCvector = marginals.marginalProbabilities(Cathy); + EXPECT(assert_equal(Vector_(2, 0.359631, 0.640369), actualCvector, 1e-6)); + + actualCvector = marginals.marginalProbabilities(Mark); + EXPECT(assert_equal(Vector_(2, 0.48628, 0.51372), actualCvector, 1e-6)); +} + +TEST_UNSAFE( DiscreteMarginals, UGM_chain ) { + + const int nrNodes = 10; + const size_t nrStates = 7; + + // define variables + vector nodes; + for (int i = 0; i < nrNodes; i++) { + DiscreteKey dk(i, nrStates); + nodes.push_back(dk); + } + + // create graph + DiscreteFactorGraph graph; + + // add node potentials + graph.add(nodes[0], ".3 .6 .1 0 0 0 0"); + for (int i = 1; i < nrNodes; i++) + graph.add(nodes[i], "1 1 1 1 1 1 1"); + + const std::string edgePotential = ".08 .9 .01 0 0 0 .01 " + ".03 .95 .01 0 0 0 .01 " + ".06 .06 .75 .05 .05 .02 .01 " + "0 0 0 .3 .6 .09 .01 " + "0 0 0 .02 .95 .02 .01 " + "0 0 0 .01 .01 .97 .01 " + "0 0 0 0 0 0 1"; + + // add edge potentials + for (int i = 0; i < nrNodes - 1; i++) + graph.add(nodes[i] & nodes[i + 1], edgePotential); + + DiscreteMarginals marginals(graph); + DiscreteFactor::shared_ptr actualC = marginals(nodes[2].first); + DiscreteFactor::Values values; + + values[nodes[2].first] = 0; + EXPECT_DOUBLES_EQUAL( 0.03426, (*actualC)(values), 1e-4); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam/discrete/tests/testSignature.cpp b/gtsam/discrete/tests/testSignature.cpp index 66b1c61b3..bf4aabb7f 100644 --- a/gtsam/discrete/tests/testSignature.cpp +++ b/gtsam/discrete/tests/testSignature.cpp @@ -28,7 +28,6 @@ using namespace boost::assign; DiscreteKey X(0,2), Y(1,3), Z(2,2); -#ifdef BOOST_HAVE_PARSER /* ************************************************************************* */ TEST(testSignature, simple_conditional) { Signature sig(X | Y = "1/1 2/3 1/4"); @@ -43,7 +42,6 @@ TEST(testSignature, simple_conditional) { vector actCpt = sig.cpt(); EXPECT_LONGS_EQUAL(6, actCpt.size()); } -#endif /* ************************************************************************* */ TEST(testSignature, simple_conditional_nonparser) { diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 259a07c9b..7825e677e 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -25,7 +25,7 @@ namespace gtsam { /** * @brief Calibration used by Bundler - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Cal3Bundler : public DerivedValue { diff --git a/gtsam/geometry/Cal3DS2.cpp b/gtsam/geometry/Cal3DS2.cpp index dcb6d6d54..66f8d99a7 100644 --- a/gtsam/geometry/Cal3DS2.cpp +++ b/gtsam/geometry/Cal3DS2.cpp @@ -23,13 +23,6 @@ namespace gtsam { -/* ************************************************************************* */ -Cal3DS2::Cal3DS2():fx_(1), fy_(1), s_(0), u0_(0), v0_(0), k1_(0), k2_(0), k3_(0), k4_(0){} - -/* ************************************************************************* */ -Cal3DS2::Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4) : - fx_(fx), fy_(fy), s_(s), u0_(u0), v0_(v0), k1_(k1), k2_(k2), k3_(k3), k4_(k4) {} - /* ************************************************************************* */ Cal3DS2::Cal3DS2(const Vector &v): fx_(v[0]), fy_(v[1]), s_(v[2]), u0_(v[3]), v0_(v[4]), k1_(v[5]), k2_(v[6]), k3_(v[7]), k4_(v[8]){} @@ -37,14 +30,11 @@ Cal3DS2::Cal3DS2(const Vector &v): /* ************************************************************************* */ Matrix Cal3DS2::K() const { return Matrix_(3,3, fx_, s_, u0_, 0.0, fy_, v0_, 0.0, 0.0, 1.0); } -/* ************************************************************************* */ -Vector Cal3DS2::k() const { return Vector_(4, k1_, k2_, k3_, k4_); } - /* ************************************************************************* */ Vector Cal3DS2::vector() const { return Vector_(9, fx_, fy_, s_, u0_, v0_, k1_, k2_, k3_, k4_) ; } /* ************************************************************************* */ -void Cal3DS2::print(const std::string& s) const { gtsam::print(K(), s + ".K") ; gtsam::print(k(), s + ".k") ; } +void Cal3DS2::print(const std::string& s) const { gtsam::print(K(), s + ".K") ; gtsam::print(Vector(k()), s + ".k") ; } /* ************************************************************************* */ bool Cal3DS2::equals(const Cal3DS2& K, double tol) const { @@ -78,6 +68,36 @@ Point2 Cal3DS2::uncalibrate(const Point2& p, return Point2(fx_* x2 + s_ * y2 + u0_, fy_ * y2 + v0_) ; } +/* ************************************************************************* */ +Point2 Cal3DS2::calibrate(const Point2& pi, const double tol) const { + // Use the following fixed point iteration to invert the radial distortion. + // pn_{t+1} = (inv(K)*pi - dp(pn_{t})) / g(pn_{t}) + + const Point2 invKPi ((1 / fx_) * (pi.x() - u0_ - (s_ / fy_) * (pi.y() - v0_)), + (1 / fy_) * (pi.y() - v0_)); + + // initialize by ignoring the distortion at all, might be problematic for pixels around boundary + Point2 pn = invKPi; + + // iterate until the uncalibrate is close to the actual pixel coordinate + const int maxIterations = 10; + int iteration; + for ( iteration = 0 ; iteration < maxIterations ; ++iteration ) { + if ( uncalibrate(pn).dist(pi) <= tol ) break; + const double x = pn.x(), y = pn.y(), xy = x*y, xx = x*x, yy = y*y ; + const double r = xx + yy ; + const double g = (1+k1_*r+k2_*r*r) ; + const double dx = 2*k3_*xy + k4_*(r+2*xx) ; + const double dy = 2*k4_*xy + k3_*(r+2*yy) ; + pn = (invKPi - Point2(dx,dy))/g ; + } + + if ( iteration >= maxIterations ) + throw std::runtime_error("Cal3DS2::calibrate fails to converge. need a better initialization"); + + return pn; +} + /* ************************************************************************* */ Matrix Cal3DS2::D2d_intrinsic(const Point2& p) const { //const double fx = fx_, fy = fy_, s = s_ ; diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 9b94eccb5..fc5918f28 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -25,7 +25,7 @@ namespace gtsam { /** * @brief Calibration of a camera with radial distortion - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Cal3DS2 : public DerivedValue { @@ -34,7 +34,7 @@ private: double fx_, fy_, s_, u0_, v0_ ; // focal length, skew and principal point double k1_, k2_ ; // radial 2nd-order and 4th-order - double k3_, k4_ ; // tagential distortion + double k3_, k4_ ; // tangential distortion // K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] // r = Pn.x^2 + Pn.y^2 @@ -44,17 +44,18 @@ private: public: Matrix K() const ; - Vector k() const ; + Eigen::Vector4d k() const { return Eigen::Vector4d(k1_, k2_, k3_, k4_); } Vector vector() const ; /// @name Standard Constructors /// @{ /// Default Constructor with only unit focal length - Cal3DS2(); + Cal3DS2() : fx_(1), fy_(1), s_(0), u0_(0), v0_(0), k1_(0), k2_(0), k3_(0), k4_(0) {} Cal3DS2(double fx, double fy, double s, double u0, double v0, - double k1, double k2, double k3, double k4) ; + double k1, double k2, double k3 = 0.0, double k4 = 0.0) : + fx_(fx), fy_(fy), s_(s), u0_(u0), v0_(v0), k1_(k1), k2_(k2), k3_(k3), k4_(k4) {} /// @} /// @name Advanced Constructors @@ -76,31 +77,49 @@ public: /// @name Standard Interface /// @{ - ///TODO: comment + /// focal length x + inline double fx() const { return fx_;} + + /// focal length x + inline double fy() const { return fy_;} + + /// skew + inline double skew() const { return s_;} + + /// image center in x + inline double px() const { return u0_;} + + /// image center in y + inline double py() const { return v0_;} + + /// Convert ideal point p (in intrinsic coordinates) into pixel coordinates Point2 uncalibrate(const Point2& p, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const ; - ///TODO: comment + /// Conver a pixel coordinate to ideal coordinate + Point2 calibrate(const Point2& p, const double tol=1e-5) const; + + /// Derivative of uncalibrate wrpt intrinsic coordinates Matrix D2d_intrinsic(const Point2& p) const ; - ///TODO: comment + /// Derivative of uncalibrate wrpt the calibration parameters Matrix D2d_calibration(const Point2& p) const ; /// @} /// @name Manifold /// @{ - ///TODO: comment + /// Given delta vector, update calibration Cal3DS2 retract(const Vector& d) const ; - ///TODO: comment + /// Given a different calibration, calculate update to obtain it Vector localCoordinates(const Cal3DS2& T2) const ; - ///TODO: comment + /// Return dimensions of calibration manifold object virtual size_t dim() const { return 9 ; } //TODO: make a final dimension variable (also, usually size_t in other classes e.g. Pose2) - ///TODO: comment + /// Return dimensions of calibration manifold object static size_t Dim() { return 9; } //TODO: make a final dimension variable private: diff --git a/gtsam/geometry/Cal3_S2.cpp b/gtsam/geometry/Cal3_S2.cpp index 709e03493..88115929a 100644 --- a/gtsam/geometry/Cal3_S2.cpp +++ b/gtsam/geometry/Cal3_S2.cpp @@ -15,12 +15,12 @@ * @author Frank Dellaert */ +#include + #include #include #include -#include - namespace gtsam { using namespace std; @@ -51,7 +51,11 @@ namespace gtsam { } /* ************************************************************************* */ + void Cal3_S2::print(const std::string& s) const { + gtsam::print(matrix(), s); + } + /* ************************************************************************* */ bool Cal3_S2::equals(const Cal3_S2& K, double tol) const { if (fabs(fx_ - K.fx_) > tol) return false; if (fabs(fy_ - K.fy_) > tol) return false; diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index 021b1e366..3c88aaeb2 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -16,7 +16,7 @@ */ /** - * @defgroup geometry + * @addtogroup geometry */ #pragma once @@ -28,7 +28,7 @@ namespace gtsam { /** * @brief The most common 5DOF 3D->2D calibration - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Cal3_S2 : public DerivedValue { @@ -75,9 +75,7 @@ namespace gtsam { /// @{ /// print with optional string - void print(const std::string& s = "") const { - gtsam::print(matrix(), s); - } + void print(const std::string& s = "Cal3_S2") const; /// Check if equal up to specified tolerance bool equals(const Cal3_S2& K, double tol = 10e-9) const; @@ -138,8 +136,8 @@ namespace gtsam { /// convert image coordinates uv to intrinsic coordinates xy Point2 calibrate(const Point2& p) const { const double u = p.x(), v = p.y(); - return Point2((1 / fx_) * (u - u0_ - (s_ / fy_) * (v - v0_)), (1 / fy_) - * (v - v0_)); + return Point2((1 / fx_) * (u - u0_ - (s_ / fy_) * (v - v0_)), + (1 / fy_) * (v - v0_)); } /// @} diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index 7bbafd7d5..3a945e8cd 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -23,11 +23,13 @@ namespace gtsam { /** * @brief The most common 5DOF 3D->2D calibration, stereo version - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ - class Cal3_S2Stereo: public Cal3_S2 { + class Cal3_S2Stereo { private: + + Cal3_S2 K_; double b_; public: @@ -39,12 +41,12 @@ namespace gtsam { /// default calibration leaves coordinates unchanged Cal3_S2Stereo() : - Cal3_S2(1, 1, 0, 0, 0), b_(1.0) { + K_(1, 1, 0, 0, 0), b_(1.0) { } /// constructor from doubles Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b) : - Cal3_S2(fx, fy, s, u0, v0), b_(b) { + K_(fx, fy, s, u0, v0), b_(b) { } /// @} @@ -52,23 +54,45 @@ namespace gtsam { /// @{ void print(const std::string& s = "") const { - gtsam::print(matrix(), s); - std::cout << "Baseline: " << b_ << std::endl; + K_.print(s+"K: "); + std::cout << s << "Baseline: " << b_ << std::endl; } - /// @} + /// Check if equal up to specified tolerance + bool equals(const Cal3_S2Stereo& other, double tol = 10e-9) const { + if (fabs(b_ - other.b_) > tol) return false; + return K_.equals(other.K_,tol); + } + + /// @} /// @name Standard Interface /// @{ - //TODO: remove? -// /** -// * Check if equal up to specified tolerance -// */ -// bool equals(const Cal3_S2& K, double tol = 10e-9) const; + /// return calibration, same for left and right + const Cal3_S2& calibration() const { return K_;} + /// return calibration matrix K, same for left and right + Matrix matrix() const { return K_.matrix();} + /// focal length x + inline double fx() const { return K_.fx();} - ///TODO: comment + /// focal length x + inline double fy() const { return K_.fy();} + + /// skew + inline double skew() const { return K_.skew();} + + /// image center in x + inline double px() const { return K_.px();} + + /// image center in y + inline double py() const { return K_.py();} + + /// return the principal point + Point2 principalPoint() const { return K_.principalPoint();} + + /// return baseline inline double baseline() const { return b_; } /// @} @@ -81,10 +105,8 @@ namespace gtsam { template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Cal3_S2Stereo", - boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(K_); ar & BOOST_SERIALIZATION_NVP(b_); - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Cal3_S2); } /// @} diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index fa27f2f71..25a4bc57b 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -47,7 +47,7 @@ Point3 CalibratedCamera::backproject_from_camera(const Point2& p, const double s } /* ************************************************************************* */ -CalibratedCamera CalibratedCamera::level(const Pose2& pose2, double height) { +CalibratedCamera CalibratedCamera::Level(const Pose2& pose2, double height) { double st = sin(pose2.theta()), ct = cos(pose2.theta()); Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0); Rot3 wRc(x, y, z); diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 04296eba1..6a52f7cb5 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -33,7 +33,7 @@ namespace gtsam { * A Calibrated camera class [R|-R't], calibration K=I. * If calibration is known, it is more computationally efficient * to calibrate the measurements rather than try to predict in pixels. - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class CalibratedCamera : public DerivedValue { @@ -94,9 +94,10 @@ namespace gtsam { /** * Create a level camera at the given 2D pose and height * @param pose2 specifies the location and viewing direction + * @param height specifies the height of the camera (along the positive Z-axis) * (theta 0 = looking in direction of positive X axis) */ - static CalibratedCamera level(const Pose2& pose2, double height); + static CalibratedCamera Level(const Pose2& pose2, double height); /// @} /// @name Manifold @@ -126,8 +127,9 @@ namespace gtsam { /** * This function receives the camera pose and the landmark location and * returns the location the point is supposed to appear in the image - * @param camera the CalibratedCamera * @param point a 3D point to be projected + * @param D_intrinsic_pose the optionally computed Jacobian with respect to pose + * @param D_intrinsic_point the optionally computed Jacobian with respect to the 3D point * @return the intrinsic coordinates of the projected point */ Point2 project(const Point3& point, @@ -150,6 +152,8 @@ namespace gtsam { /** * Calculate range to a landmark * @param point 3D location of landmark + * @param H1 optionally computed Jacobian with respect to pose + * @param H2 optionally computed Jacobian with respect to the 3D point * @return range (double) */ double range(const Point3& point, @@ -160,6 +164,8 @@ namespace gtsam { /** * Calculate range to another pose * @param pose Other SO(3) pose + * @param H1 optionally computed Jacobian with respect to pose + * @param H2 optionally computed Jacobian with respect to the 3D point * @return range (double) */ double range(const Pose3& pose, @@ -170,6 +176,8 @@ namespace gtsam { /** * Calculate range to another camera * @param camera Other camera + * @param H1 optionally computed Jacobian with respect to pose + * @param H2 optionally computed Jacobian with respect to the 3D point * @return range (double) */ double range(const CalibratedCamera& camera, diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 943409b4b..8ec300ac6 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -33,14 +33,14 @@ namespace gtsam { /** * A pinhole camera class that has a Pose3 and a Calibration. - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ template class PinholeCamera : public DerivedValue > { private: Pose3 pose_; - Calibration k_; + Calibration K_; public: @@ -54,23 +54,82 @@ namespace gtsam { explicit PinholeCamera(const Pose3& pose):pose_(pose){} /** constructor with pose and calibration */ - PinholeCamera(const Pose3& pose, const Calibration& k):pose_(pose),k_(k) {} + PinholeCamera(const Pose3& pose, const Calibration& K):pose_(pose),K_(K) {} - /** alternative constructor with pose and calibration */ - PinholeCamera(const Calibration& k, const Pose3& pose):pose_(pose),k_(k) {} + /// @} + /// @name Named Constructors + /// @{ + + /** + * Create a level camera at the given 2D pose and height + * @param K the calibration + * @param pose2 specifies the location and viewing direction + * (theta 0 = looking in direction of positive X axis) + * @param height camera height + */ + static PinholeCamera Level(const Calibration &K, const Pose2& pose2, double height) { + const double st = sin(pose2.theta()), ct = cos(pose2.theta()); + const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0); + const Rot3 wRc(x, y, z); + const Point3 t(pose2.x(), pose2.y(), height); + const Pose3 pose3(wRc, t); + return PinholeCamera(pose3, K); + } + + /// PinholeCamera::level with default calibration + static PinholeCamera Level(const Pose2& pose2, double height) { + return PinholeCamera::Level(Calibration(), pose2, height); + } + + /** + * Create a camera at the given eye position looking at a target point in the scene + * with the specified up direction vector. + * @param eye specifies the camera position + * @param target the point to look at + * @param upVector specifies the camera up direction vector, + * doesn't need to be on the image plane nor orthogonal to the viewing axis + * @param K optional calibration parameter + */ + static PinholeCamera Lookat(const Point3& eye, const Point3& target, const Point3& upVector, const Calibration& K = Calibration()) { + Point3 zc = target-eye; + zc = zc/zc.norm(); + Point3 xc = (-upVector).cross(zc); // minus upVector since yc is pointing down + xc = xc/xc.norm(); + Point3 yc = zc.cross(xc); + Pose3 pose3(Rot3(xc,yc,zc), eye); + return PinholeCamera(pose3, K); + } /// @} /// @name Advanced Constructors /// @{ - explicit PinholeCamera(const Vector &v){ + explicit PinholeCamera(const Vector &v) { pose_ = Pose3::Expmap(v.head(Pose3::Dim())); - if ( v.size() > Pose3::Dim()) { - k_ = Calibration(v.tail(Calibration::Dim())); + if (v.size() > Pose3::Dim()) { + K_ = Calibration(v.tail(Calibration::Dim())); } } - PinholeCamera(const Vector &v, const Vector &k) : pose_(Pose3::Expmap(v)),k_(k){} + PinholeCamera(const Vector &v, const Vector &K) : + pose_(Pose3::Expmap(v)), K_(K) { + } + + /// @} + /// @name Testable + /// @{ + + /// assert equality up to a tolerance + bool equals (const PinholeCamera &camera, double tol = 1e-9) const { + return pose_.equals(camera.pose(), tol) && + K_.equals(camera.calibration(), tol) ; + } + + /// print + void print(const std::string& s = "PinholeCamera") const { + pose_.print(s+".pose"); + K_.print(s+".calibration"); + } /// @} /// @name Standard Interface @@ -85,35 +144,23 @@ namespace gtsam { inline const Pose3& pose() const { return pose_; } /// return calibration - inline Calibration& calibration() { return k_; } + inline Calibration& calibration() { return K_; } /// return calibration - inline const Calibration& calibration() const { return k_; } + inline const Calibration& calibration() const { return K_; } - /// compose two cameras + /// @} + /// @name Group ?? Frank says this might not make sense + /// @{ + + /// compose two cameras: TODO Frank says this might not make sense inline const PinholeCamera compose(const Pose3 &c) const { - return PinholeCamera( pose_ * c, k_ ) ; + return PinholeCamera( pose_ * c, K_ ) ; } - /// inverse + /// compose two cameras: TODO Frank says this might not make sense inline const PinholeCamera inverse() const { - return PinholeCamera( pose_.inverse(), k_ ) ; - } - - /// @} - /// @name Testable - /// @{ - - /// assert equality up to a tolerance - bool equals (const PinholeCamera &camera, double tol = 1e-9) const { - return pose_.equals(camera.pose(), tol) && - k_.equals(camera.calibration(), tol) ; - } - - /// print - void print(const std::string& s = "") const { - pose_.print("pose3"); - k_.print("calibration"); + return PinholeCamera( pose_.inverse(), K_ ) ; } /// @} @@ -137,39 +184,21 @@ namespace gtsam { return d; } - /// Lie group dimensionality - inline size_t dim() const { return pose_.dim() + k_.dim(); } + /// Manifold dimension + inline size_t dim() const { return pose_.dim() + K_.dim(); } - /// Lie group dimensionality + /// Manifold dimension inline static size_t Dim() { return Pose3::Dim() + Calibration::Dim(); } - /** - * Create a level camera at the given 2D pose and height - * @param pose2 specifies the location and viewing direction - * (theta 0 = looking in direction of positive X axis) - */ - static PinholeCamera level(const Pose2& pose2, double height) { - return PinholeCamera::level(Calibration(), pose2, height); - } - - static PinholeCamera level(const Calibration &K, const Pose2& pose2, double height) { - const double st = sin(pose2.theta()), ct = cos(pose2.theta()); - const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0); - const Rot3 wRc(x, y, z); - const Point3 t(pose2.x(), pose2.y(), height); - const Pose3 pose3(wRc, t); - return PinholeCamera(pose3, K); - } - /// @} /// @name Transformations and measurement functions /// @{ /** - * projects a 3-dimensional point in camera coordinates into the - * camera and returns a 2-dimensional point, no calibration applied - * With optional 2by3 derivative - */ + * projects a 3-dimensional point in camera coordinates into the + * camera and returns a 2-dimensional point, no calibration applied + * With optional 2by3 derivative + */ inline static Point2 project_to_camera(const Point3& P, boost::optional H1 = boost::none){ if (H1) { @@ -183,7 +212,7 @@ namespace gtsam { inline std::pair projectSafe(const Point3& pw) const { const Point3 pc = pose_.transform_to(pw) ; const Point2 pn = project_to_camera(pc) ; - return std::make_pair(k_.uncalibrate(pn), pc.z()>0); + return std::make_pair(K_.uncalibrate(pn), pc.z()>0); } /** project a point from world coordinate to the image @@ -201,7 +230,7 @@ namespace gtsam { const Point3 pc = pose_.transform_to(pw) ; if ( pc.z() <= 0 ) throw CheiralityException(); const Point2 pn = project_to_camera(pc) ; - return k_.uncalibrate(pn); + return K_.uncalibrate(pn); } // world to camera coordinate @@ -215,7 +244,7 @@ namespace gtsam { // uncalibration Matrix Hk, Hi; // 2*2 - const Point2 pi = k_.uncalibrate(pn, Hk, Hi); + const Point2 pi = K_.uncalibrate(pn, Hk, Hi); // chain the jacobian matrices const Matrix tmp = Hi*Hn ; @@ -238,7 +267,7 @@ namespace gtsam { const Point3 pc = pose_.transform_to(pw) ; if ( pc.z() <= 0 ) throw CheiralityException(); const Point2 pn = project_to_camera(pc) ; - return k_.uncalibrate(pn); + return K_.uncalibrate(pn); } Matrix Htmp1, Htmp2, Htmp3; @@ -252,23 +281,18 @@ namespace gtsam { return pi; } - /** - * backproject a 2-dimensional point to a 3-dimension point - */ - - inline Point3 backproject(const Point2& pi, const double scale) const { - const Point2 pn = k_.calibrate(pi); - const Point3 pc(pn.x()*scale, pn.y()*scale, scale); + /// backproject a 2-dimensional point to a 3-dimensional point at given depth + inline Point3 backproject(const Point2& p, double depth) const { + const Point2 pn = K_.calibrate(p); + const Point3 pc(pn.x()*depth, pn.y()*depth, depth); return pose_.transform_from(pc); } - inline Point3 backproject_from_camera(const Point2& pi, const double scale) const { - return backproject(pi, scale); - } - /** * Calculate range to a landmark * @param point 3D location of landmark + * @param H1 the optionally computed Jacobian with respect to pose + * @param H2 the optionally computed Jacobian with respect to the landmark * @return range (double) */ double range(const Point3& point, @@ -278,8 +302,8 @@ namespace gtsam { if(H1) { // Add columns of zeros to Jacobian for calibration Matrix& H1r(*H1); - H1r.conservativeResize(Eigen::NoChange, pose_.dim() + k_.dim()); - H1r.block(0, pose_.dim(), 1, k_.dim()) = Matrix::Zero(1, k_.dim()); + H1r.conservativeResize(Eigen::NoChange, pose_.dim() + K_.dim()); + H1r.block(0, pose_.dim(), 1, K_.dim()) = Matrix::Zero(1, K_.dim()); } return result; } @@ -287,6 +311,8 @@ namespace gtsam { /** * Calculate range to another pose * @param pose Other SO(3) pose + * @param H1 the optionally computed Jacobian with respect to pose + * @param H2 the optionally computed Jacobian with respect to the landmark * @return range (double) */ double range(const Pose3& pose, @@ -296,8 +322,8 @@ namespace gtsam { if(H1) { // Add columns of zeros to Jacobian for calibration Matrix& H1r(*H1); - H1r.conservativeResize(Eigen::NoChange, pose_.dim() + k_.dim()); - H1r.block(0, pose_.dim(), 1, k_.dim()) = Matrix::Zero(1, k_.dim()); + H1r.conservativeResize(Eigen::NoChange, pose_.dim() + K_.dim()); + H1r.block(0, pose_.dim(), 1, K_.dim()) = Matrix::Zero(1, K_.dim()); } return result; } @@ -305,6 +331,8 @@ namespace gtsam { /** * Calculate range to another camera * @param camera Other camera + * @param H1 the optionally computed Jacobian with respect to pose + * @param H2 the optionally computed Jacobian with respect to the landmark * @return range (double) */ template @@ -315,8 +343,8 @@ namespace gtsam { if(H1) { // Add columns of zeros to Jacobian for calibration Matrix& H1r(*H1); - H1r.conservativeResize(Eigen::NoChange, pose_.dim() + k_.dim()); - H1r.block(0, pose_.dim(), 1, k_.dim()) = Matrix::Zero(1, k_.dim()); + H1r.conservativeResize(Eigen::NoChange, pose_.dim() + K_.dim()); + H1r.block(0, pose_.dim(), 1, K_.dim()) = Matrix::Zero(1, K_.dim()); } if(H2) { // Add columns of zeros to Jacobian for calibration @@ -330,6 +358,8 @@ namespace gtsam { /** * Calculate range to another camera * @param camera Other camera + * @param H1 the optionally computed Jacobian with respect to pose + * @param H2 the optionally computed Jacobian with respect to the landmark * @return range (double) */ double range(const CalibratedCamera& camera, @@ -349,7 +379,7 @@ private: void serialize(Archive & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value); ar & BOOST_SERIALIZATION_NVP(pose_); - ar & BOOST_SERIALIZATION_NVP(k_); + ar & BOOST_SERIALIZATION_NVP(K_); } /// @} }; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index fe7792733..af5b1fbcd 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -29,7 +29,7 @@ namespace gtsam { * A 2D point * Complies with the Testable Concept * Functional, so no set functions: once created, a point is constant. - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Point2 : public DerivedValue { @@ -58,7 +58,12 @@ public: /// @{ /// construct from 2D vector - Point2(const Vector& v) : x_(v(0)), y_(v(1)) { assert(v.size() == 2); } + Point2(const Vector& v) { + if(v.size() != 2) + throw std::invalid_argument("Point2 constructor from Vector requires that the Vector have dimension 2"); + x_ = v(0); + y_ = v(1); + } /// @} /// @name Testable diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 9eeb748db..3e7423c0a 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -21,6 +21,7 @@ #pragma once +#include #include #include @@ -31,7 +32,7 @@ namespace gtsam { /** * A 3D point - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Point3 : public DerivedValue { @@ -47,21 +48,24 @@ namespace gtsam { /// @name Standard Constructors /// @{ - ///TODO: comment + /// Default constructor creates a zero-Point3 Point3(): x_(0), y_(0), z_(0) {} - ///TODO: comment - Point3(const Point3 &p) : x_(p.x_), y_(p.y_), z_(p.z_) {} - - ///TODO: comment + /// Construct from x, y, and z coordinates Point3(double x, double y, double z): x_(x), y_(y), z_(z) {} /// @} /// @name Advanced Constructors /// @{ - ///TODO: comment - Point3(const Vector& v) : x_(v(0)), y_(v(1)), z_(v(2)) {} + /// Construct from 3-element vector + Point3(const Vector& v) { + if(v.size() != 3) + throw std::invalid_argument("Point3 constructor from Vector requires that the Vector have dimension 3"); + x_ = v(0); + y_ = v(1); + z_ = v(2); + } /// @} /// @name Testable @@ -150,7 +154,7 @@ namespace gtsam { /** distance between two points */ double dist(const Point3& p2) const { - return sqrt(pow(x()-p2.x(),2.0) + pow(y()-p2.y(),2.0) + pow(z()-p2.z(),2.0)); + return std::sqrt(pow(x()-p2.x(),2.0) + pow(y()-p2.y(),2.0) + pow(z()-p2.z(),2.0)); } /** Distance of the point from the origin */ diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index a15929c67..fa02ecfb8 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -20,6 +20,8 @@ #include #include #include +#include +#include using namespace std; @@ -44,7 +46,7 @@ Matrix Pose2::matrix() const { /* ************************************************************************* */ void Pose2::print(const string& s) const { - cout << s << "(" << t_.x() << ", " << t_.y() << ", " << r_.theta() << ")" << endl; + cout << s << setprecision(2) << "(" << t_.x() << ", " << t_.y() << ", " << r_.theta() << ")" << endl; } /* ************************************************************************* */ @@ -106,7 +108,7 @@ Vector Pose2::localCoordinates(const Pose2& p2) const { /* ************************************************************************* */ // Calculate Adjoint map // Ad_pose is 3*3 matrix that when applied to twist xi, returns Ad_pose(xi) -Matrix Pose2::AdjointMap() const { +Matrix Pose2::adjointMap() const { double c = r_.c(), s = r_.s(), x = t_.x(), y = t_.y(); return Matrix_(3,3, c, -s, y, @@ -117,7 +119,7 @@ Matrix Pose2::AdjointMap() const { /* ************************************************************************* */ Pose2 Pose2::inverse(boost::optional H1) const { - if (H1) *H1 = -AdjointMap(); + if (H1) *H1 = -adjointMap(); return Pose2(r_.inverse(), r_.unrotate(Point2(-t_.x(), -t_.y()))); } @@ -140,7 +142,7 @@ Point2 Pose2::transform_to(const Point2& point, Pose2 Pose2::compose(const Pose2& p2, boost::optional H1, boost::optional H2) const { // TODO: inline and reuse? - if(H1) *H1 = p2.inverse().AdjointMap(); + if(H1) *H1 = p2.inverse().adjointMap(); if(H2) *H2 = I3; return (*this)*p2; } diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 877eb93a1..d091ddac8 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -30,7 +30,7 @@ namespace gtsam { /** * A 2D pose (Point2,Rot2) - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Pose2 : public DerivedValue { @@ -158,10 +158,10 @@ public: * Calculate Adjoint map * Ad_pose is 3*3 matrix that when applied to twist xi, returns Ad_pose(xi) */ - Matrix AdjointMap() const; - inline Vector Adjoint(const Vector& xi) const { + Matrix adjointMap() const; + inline Vector adjoint(const Vector& xi) const { assert(xi.size() == 3); - return AdjointMap()*xi; + return adjointMap()*xi; } /** @@ -226,7 +226,7 @@ public: /** * Calculate bearing to a landmark * @param point 2D location of landmark - * @return 2D rotation \in SO(2) + * @return 2D rotation \f$ \in SO(2) \f$ */ Rot2 bearing(const Point2& point, boost::optional H1=boost::none, @@ -235,7 +235,7 @@ public: /** * Calculate bearing to another pose * @param point SO(2) location of other pose - * @return 2D rotation \in SO(2) + * @return 2D rotation \f$ \in SO(2) \f$ */ Rot2 bearing(const Pose2& point, boost::optional H1=boost::none, @@ -259,12 +259,26 @@ public: boost::optional H1=boost::none, boost::optional H2=boost::none) const; -private: - /// @} /// @name Advanced Interface /// @{ + /** + * Return the start and end indices (inclusive) of the translation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + inline static std::pair translationInterval() { return std::make_pair(0, 1); } + + /** + * Return the start and end indices (inclusive) of the rotation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + static std::pair rotationInterval() { return std::make_pair(2, 2); } + +private: + // Serialization function friend class boost::serialization::access; template diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 59e5ceef5..be9869030 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -55,8 +55,9 @@ namespace gtsam { /* ************************************************************************* */ void Pose3::print(const string& s) const { - R_.print(s + ".R"); - t_.print(s + ".t"); + cout << s; + R_.print("R:\n"); + t_.print("t: "); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 9cfe7ba37..dfae2d7a2 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -32,7 +32,7 @@ namespace gtsam { /** * A 3D pose (R,t) : (Rot3,Point3) - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Pose3 : public DerivedValue { @@ -228,6 +228,20 @@ namespace gtsam { /// @name Advanced Interface /// @{ + /** + * Return the start and end indices (inclusive) of the translation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + inline static std::pair translationInterval() { return std::make_pair(3, 5); } + + /** + * Return the start and end indices (inclusive) of the rotation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + static std::pair rotationInterval() { return std::make_pair(0, 2); } + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 8e33794e4..9e5e6fddc 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -28,7 +28,7 @@ namespace gtsam { /** * Rotation matrix * NOTE: the angle theta is in radians unless explicitly stated - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Rot2 : public DerivedValue { @@ -83,9 +83,9 @@ namespace gtsam { /** * Named constructor with derivative * Calculate relative bearing to a landmark in local coordinate frame - * @param point 2D location of landmark + * @param d 2D location of landmark * @param H optional reference for Jacobian - * @return 2D rotation \in SO(2) + * @return 2D rotation \f$ \in SO(2) \f$ */ static Rot2 relativeBearing(const Point2& d, boost::optional H = boost::none); diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 93e276de7..e3aaa6d32 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -48,7 +48,7 @@ namespace gtsam { * @brief A 3D rotation represented as a rotation matrix if the preprocessor * symbol GTSAM_DEFAULT_QUATERNIONS is not defined, or as a quaternion if it * is defined. - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class Rot3 : public DerivedValue { @@ -104,10 +104,10 @@ namespace gtsam { /// Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. static Rot3 Rx(double t); - /// Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. + /// Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. static Rot3 Ry(double t); - /// Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. + /// Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. static Rot3 Rz(double t); /// Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. @@ -119,31 +119,17 @@ namespace gtsam { return RzRyRx(xyz(0), xyz(1), xyz(2)); } - /** - * Positive yaw is to right (as in aircraft heading). - * Tait-Bryan system from Spatial Reference Model (SRM) (x,y,z) = (roll,pitch,yaw) - * as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf. - * Assumes vehicle coordinate frame X forward, Y right, Z down. - */ + /// Positive yaw is to right (as in aircraft heading). See ypr static Rot3 yaw (double t) { return Rz(t); } - /** - * Positive pitch is up (increasing aircraft altitude). - * Tait-Bryan system from Spatial Reference Model (SRM) (x,y,z) = (roll,pitch,yaw) - * as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf. - * Assumes vehicle coordinate frame X forward, Y right, Z down. - */ + /// Positive pitch is up (increasing aircraft altitude).See ypr static Rot3 pitch(double t) { return Ry(t); } - /** - * Positive roll is to right (increasing yaw in aircraft). - * Tait-Bryan system from Spatial Reference Model (SRM) (x,y,z) = (roll,pitch,yaw) - * as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf. - * Assumes vehicle coordinate frame X forward, Y right, Z down. - */ + //// Positive roll is to right (increasing yaw in aircraft). static Rot3 roll (double t) { return Rx(t); } - /** Returns rotation nRb from body to nav frame. + /** + * Returns rotation nRb from body to nav frame. * Positive yaw is to right (as in aircraft heading). * Positive pitch is up (increasing aircraft altitude). * Positive roll is to right (increasing yaw in aircraft). @@ -394,7 +380,7 @@ namespace gtsam { * such that A = R*Q = R*Qz'*Qy'*Qx'. When A is a rotation matrix, R will * be the identity and Q is a yaw-pitch-roll decomposition of A. * The implementation uses Givens rotations and is based on Hartley-Zisserman. - * @param a 3 by 3 matrix A=RQ + * @param A 3 by 3 matrix A=RQ * @return an upper triangular matrix R * @return a vector [thetax, thetay, thetaz] in radians. */ diff --git a/gtsam/geometry/SimpleCamera.cpp b/gtsam/geometry/SimpleCamera.cpp new file mode 100644 index 000000000..d441716cb --- /dev/null +++ b/gtsam/geometry/SimpleCamera.cpp @@ -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 + + * -------------------------------------------------------------------------- */ + +/** + * @file SimpleCamera.cpp + * @brief A simple camera class with a Cal3_S2 calibration + * @date June 30, 2012 + * @author Frank Dellaert + */ + +#include +#include + +namespace gtsam { + + SimpleCamera simpleCamera(const Matrix& P) { + + // P = [A|a] = s K cRw [I|-T], with s the unknown scale + Matrix A = P.topLeftCorner(3, 3); + Vector a = P.col(3); + + // do RQ decomposition to get s*K and cRw angles + Matrix sK; + Vector xyz; + boost::tie(sK, xyz) = RQ(A); + + // Recover scale factor s and K + double s = sK(2, 2); + Matrix K = sK / s; + + // Recover cRw itself, and its inverse + Rot3 cRw = Rot3::RzRyRx(xyz); + Rot3 wRc = cRw.inverse(); + + // Now, recover T from a = - s K cRw T = - A T + Vector T = -(A.inverse() * a); + return SimpleCamera(Pose3(wRc, T), + Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2))); + } + +} diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index d3b0cdbdc..abe42f1a0 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -22,5 +22,10 @@ #include namespace gtsam { + + /// A simple camera class with a Cal3_S2 calibration typedef PinholeCamera SimpleCamera; + + /// Recover camera from 3*4 camera matrix + SimpleCamera simpleCamera(const Matrix& P); } diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index f5e07e66c..140ab1bdf 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -28,15 +28,19 @@ namespace gtsam { /** * A stereo camera class, parameterize by left camera pose and stereo calibration - * @ingroup geometry + * @addtogroup geometry */ -class StereoCamera { +class StereoCamera : public DerivedValue { private: Pose3 leftCamPose_; Cal3_S2Stereo::shared_ptr K_; public: + + /// @name Standard Constructors + /// @{ + StereoCamera() { } @@ -46,6 +50,54 @@ public: return K_; } + /// @} + /// @name Testable + /// @{ + + void print(const std::string& s = "") const { + leftCamPose_.print(s + ".camera."); + K_->print(s + ".calibration."); + } + + bool equals(const StereoCamera &camera, double tol = 1e-9) const { + return leftCamPose_.equals(camera.leftCamPose_, tol) && K_->equals( + *camera.K_, tol); + } + + /// @} + /// @name Manifold + /// @{ + + /** Dimensionality of the tangent space */ + inline size_t dim() const { + return 6; + } + + /** Dimensionality of the tangent space */ + static inline size_t Dim() { + return 6; + } + + /// Updates a with tangent space delta + inline StereoCamera retract(const Vector& v) const { + return StereoCamera(pose().retract(v), K_); + } + + /// Local coordinates of manifold neighborhood around current value + inline Vector localCoordinates(const StereoCamera& t2) const { + return Vector(leftCamPose_.localCoordinates(t2.leftCamPose_)); + } + + Pose3 between(const StereoCamera &camera, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + return leftCamPose_.between(camera.pose(), H1, H2); + } + + /// @} + /// @name Standard Interface + /// @{ + const Pose3& pose() const { return leftCamPose_; } @@ -71,16 +123,6 @@ public: return project(point, H1, H2); } - /* - * backproject using left camera calibration, up to scale only - * i.e. does not rely on baseline - */ - Point3 backproject(const Point2& projection, const double scale) const { - Point2 intrinsic = K_->calibrate(projection); - Point3 cameraPoint = Point3(intrinsic.x() * scale, intrinsic.y() * scale, scale);; - return pose().transform_from(cameraPoint); - } - Point3 backproject(const StereoPoint2& z) const { Vector measured = z.vector(); double Z = K_->baseline()*K_->fx()/(measured[0]-measured[1]); @@ -90,40 +132,7 @@ public: return world_point; } - /** Dimensionality of the tangent space */ - inline size_t dim() const { - return 6; - } - - /** Dimensionality of the tangent space */ - static inline size_t Dim() { - return 6; - } - - bool equals(const StereoCamera &camera, double tol = 1e-9) const { - return leftCamPose_.equals(camera.leftCamPose_, tol) && K_->equals( - *camera.K_, tol); - } - - // Manifold requirements - use existing expmap/logmap - inline StereoCamera retract(const Vector& v) const { - return StereoCamera(pose().retract(v), K_); - } - - inline Vector localCoordinates(const StereoCamera& t2) const { - return Vector(leftCamPose_.localCoordinates(t2.leftCamPose_)); - } - - Pose3 between(const StereoCamera &camera, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const { - return leftCamPose_.between(camera.pose(), H1, H2); - } - - void print(const std::string& s = "") const { - leftCamPose_.print(s + ".camera."); - K_->print(s + ".calibration."); - } + /// @} private: /** utility functions */ @@ -132,7 +141,9 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_NVP(leftCamPose_); + ar & boost::serialization::make_nvp("StereoCamera", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(leftCamPose_); ar & BOOST_SERIALIZATION_NVP(K_); } diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 43701e4e8..6bfdefe26 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -25,7 +25,7 @@ namespace gtsam { /** * A 2D stereo point, v will be same for rectified images - * @ingroup geometry + * @addtogroup geometry * \nosubgrouping */ class StereoPoint2 : public DerivedValue { @@ -119,6 +119,11 @@ namespace gtsam { return p.vector(); } + /** The difference between another point and this point */ + inline StereoPoint2 between(const StereoPoint2& p2) const { + return gtsam::between_default(*this, p2); + } + /// @} /// @name Standard Interface /// @{ @@ -133,11 +138,6 @@ namespace gtsam { return Point2(uL_, v_); } - ///TODO comment - inline StereoPoint2 between(const StereoPoint2& p2) const { - return gtsam::between_default(*this, p2); - } - private: /// @} diff --git a/gtsam/geometry/Tensor1.h b/gtsam/geometry/Tensor1.h deleted file mode 100644 index 685166b53..000000000 --- a/gtsam/geometry/Tensor1.h +++ /dev/null @@ -1,85 +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 Tensor1.h - * @brief Rank 1 tensors based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once -#include - -namespace tensors { - - /** - * A rank 1 tensor. Actually stores data. - * @ingroup tensors - * \nosubgrouping - */ - template - class Tensor1 { - double T[N]; ///< Storage - - public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - Tensor1() { - } - - /** construct from data */ - Tensor1(const double* data) { - for (int i = 0; i < N; i++) - T[i] = data[i]; - } - - /** construct from expression */ - template - Tensor1(const Tensor1Expression >& a) { - for (int i = 0; i < N; i++) - T[i] = a(i); - } - - /// @} - /// @name Standard Interface - /// @{ - - /** return data */ - inline int dim() const { - return N; - } - - /** return data */ - inline const double& operator()(int i) const { - return T[i]; - } - - /** return data */ - inline double& operator()(int i) { - return T[i]; - } - - /// return an expression associated with an index - template Tensor1Expression > operator()( - Index index) const { - return Tensor1Expression >(*this); - } - - /// @} - - }; -// Tensor1 - -}// namespace tensors diff --git a/gtsam/geometry/Tensor1Expression.h b/gtsam/geometry/Tensor1Expression.h deleted file mode 100644 index 4e43fff58..000000000 --- a/gtsam/geometry/Tensor1Expression.h +++ /dev/null @@ -1,181 +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 Tensor1Expression.h - * @brief Tensor expression templates based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include -#include -#include - -namespace tensors { - - /** - * Templated class to provide a rank 1 tensor interface to a class. - * This class does not store any data but the result of an expression. - * It is associated with an index. - * @ingroup tensors - * \nosubgrouping - */ - template class Tensor1Expression { - - private: - - A iter; - - typedef Tensor1Expression This; - - /** Helper class for multiplying with a double */ - class TimesDouble_ { - A iter; - const double s; - public: - /// Constructor - TimesDouble_(const A &a, double s_) : - iter(a), s(s_) { - } - /// Element access - inline double operator()(int i) const { - return iter(i) * s; - } - }; - - public: - - /// @name Standard Constructors - /// @{ - - /** constructor */ - Tensor1Expression(const A &a) : - iter(a) { - } - - /// @} - /// @name Testable - /// @{ - - /** Print */ - void print(const std::string s = "") const { - std::cout << s << "{"; - std::cout << (*this)(0); - for (int i = 1; i < I::dim; i++) - std::cout << ", "<< (*this)(i); - std::cout << "}" << std::endl; - } - - /// equality - template - bool equals(const Tensor1Expression & q, double tol) const { - for (int i = 0; i < I::dim; i++) - if (fabs((*this)(i) - q(i)) > tol) return false; - return true; - } - - /// @} - /// @name Standard Interface - /// @{ - - /** norm */ - double norm() const { - double sumsqr = 0.0; - for (int i = 0; i < I::dim; i++) - sumsqr += iter(i) * iter(i); - return sqrt(sumsqr); - } - - /// test equivalence - template - bool equivalent(const Tensor1Expression & q, double tol = 1e-9) const { - return ((*this) * (1.0 / norm())).equals(q * (1.0 / q.norm()), tol) - || ((*this) * (-1.0 / norm())).equals(q * (1.0 / q.norm()), tol); - } - - /** Check if two expressions are equal */ - template - bool operator==(const Tensor1Expression& e) const { - for (int i = 0; i < I::dim; i++) - if (iter(i) != e(i)) return false; - return true; - } - - /** element access */ - double operator()(int i) const { - return iter(i); - } - - /** mutliply with a double. */ - inline Tensor1Expression operator*(double s) const { - return TimesDouble_(iter, s); - } - - /** Class for contracting two rank 1 tensor expressions, yielding a double. */ - template - inline double operator*(const Tensor1Expression &b) const { - double sum = 0.0; - for (int i = 0; i < I::dim; i++) - sum += (*this)(i) * b(i); - return sum; - } - - }; // Tensor1Expression - - /// @} - /// @name Advanced Interface - /// @{ - - /** Print a rank 1 expression */ - template - void print(const Tensor1Expression& T, const std::string s = "") { - T.print(s); - } - - /** norm */ - template - double norm(const Tensor1Expression& T) { - return T.norm(); - } - - /** - * This template works for any two expressions - */ - template - bool assert_equality(const Tensor1Expression& expected, - const Tensor1Expression& actual, double tol = 1e-9) { - if (actual.equals(expected, tol)) return true; - std::cout << "Not equal:\n"; - expected.print("expected:\n"); - actual.print("actual:\n"); - return false; - } - - /** - * This template works for any two expressions - */ - template - bool assert_equivalent(const Tensor1Expression& expected, - const Tensor1Expression& actual, double tol = 1e-9) { - if (actual.equivalent(expected, tol)) return true; - std::cout << "Not equal:\n"; - expected.print("expected:\n"); - actual.print("actual:\n"); - return false; - } - - /// @} - -} // namespace tensors diff --git a/gtsam/geometry/Tensor2.h b/gtsam/geometry/Tensor2.h deleted file mode 100644 index 12fd1509f..000000000 --- a/gtsam/geometry/Tensor2.h +++ /dev/null @@ -1,84 +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 Tensor2.h - * @brief Rank 2 Tensor based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once -#include - -namespace tensors { - -/** - * Rank 2 Tensor - * @ingroup tensors - * \nosubgrouping - */ -template -class Tensor2 { -protected: - Tensor1 T[N2]; ///< Storage - -public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - Tensor2() { - } - - /// construct from data - expressed in row major form - Tensor2(const double data[N2][N1]) { - for (int j = 0; j < N2; j++) - T[j] = Tensor1 (data[j]); - } - - /** construct from expression */ - template - Tensor2(const Tensor2Expression , Index >& a) { - for (int j = 0; j < N2; j++) - T[j] = a(j); - } - - /// @} - /// @name Standard Interface - /// @{ - - /** dimension - TODO: is this right for anything other than 3x3? */ - size_t dim() const {return N1 * N2;} - - /// const element access - const double & operator()(int i, int j) const { - return T[j](i); - } - - /// element access - double & operator()(int i, int j) { - return T[j](i); - } - - /** convert to expression */ - template Tensor2Expression , Index< - N2, J> > operator()(Index i, Index j) const { - return Tensor2Expression , Index > (*this); - } - - /// @} - -}; - -} // namespace tensors - diff --git a/gtsam/geometry/Tensor2Expression.h b/gtsam/geometry/Tensor2Expression.h deleted file mode 100644 index 6c953a5aa..000000000 --- a/gtsam/geometry/Tensor2Expression.h +++ /dev/null @@ -1,310 +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 Tensor2Expression.h - * @brief Tensor expression templates based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include -#include - -namespace tensors { - - /** - * Templated class to hold a rank 2 tensor expression. - * @ingroup tensors - * \nosubgrouping - */ - template class Tensor2Expression { - - private: - - A iter; - - typedef Tensor2Expression This; - - /** Helper class for instantiating one index */ - class FixJ_ { - const int j; - const A iter; - public: - FixJ_(int j_, const A &a) : - j(j_), iter(a) { - } - double operator()(int i) const { - return iter(i, j); - } - }; - - /** Helper class for swapping indices */ - class Swap_ { - const A iter; - public: - /// Constructor - Swap_(const A &a) : - iter(a) { - } - /// Element access - double operator()(int j, int i) const { - return iter(i, j); - } - }; - - /** Helper class for multiplying with a double */ - class TimesDouble_ { - A iter; - const double s; - public: - /// Constructor - TimesDouble_(const A &a, double s_) : - iter(a), s(s_) { - } - /// Element access - inline double operator()(int i, int j) const { - return iter(i, j) * s; - } - }; - - /** Helper class for contracting index I with rank 1 tensor */ - template class ITimesRank1_ { - const This a; - const Tensor1Expression b; - public: - /// Constructor - ITimesRank1_(const This &a_, const Tensor1Expression &b_) : - a(a_), b(b_) { - } - /// Element access - double operator()(int j) const { - double sum = 0.0; - for (int i = 0; i < I::dim; i++) - sum += a(i, j) * b(i); - return sum; - } - }; - - /** Helper class for contracting index J with rank 1 tensor */ - template class JTimesRank1_ { - const This a; - const Tensor1Expression b; - public: - /// Constructor - JTimesRank1_(const This &a_, const Tensor1Expression &b_) : - a(a_), b(b_) { - } - /// Element access - double operator()(int i) const { - double sum = 0.0; - for (int j = 0; j < J::dim; j++) - sum += a(i, j) * b(j); - return sum; - } - }; - - /** Helper class for contracting index I with rank 2 tensor */ - template class ITimesRank2_ { - const This a; - const Tensor2Expression b; - public: - /// Constructor - ITimesRank2_(const This &a_, const Tensor2Expression &b_) : - a(a_), b(b_) { - } - /// Element access - double operator()(int j, int k) const { - double sum = 0.0; - for (int i = 0; i < I::dim; i++) - sum += a(i, j) * b(i, k); - return sum; - } - }; - - public: - - /// @name Standard Constructors - /// @{ - - /** constructor */ - Tensor2Expression(const A &a) : - iter(a) { - } - - /// @} - /// @name Testable - /// @{ - - /** Print */ - void print(const std::string& s = "Tensor2:") const { - std::cout << s << "{"; - (*this)(0).print(); - for (int j = 1; j < J::dim; j++) { - std::cout << ","; - (*this)(j).print(""); - } - std::cout << "}" << std::endl; - } - - /// test equality - template - bool equals(const Tensor2Expression & q, double tol) const { - for (int j = 0; j < J::dim; j++) - if (!(*this)(j).equals(q(j), tol)) - return false; - return true; - } - - /// @} - /// @name Standard Interface - /// @{ - - /** norm */ - double norm() const { - double sumsqr = 0.0; - for (int i = 0; i < I::dim; i++) - for (int j = 0; j < J::dim; j++) - sumsqr += iter(i, j) * iter(i, j); - return sqrt(sumsqr); - } - - /// test equivalence - template - bool equivalent(const Tensor2Expression & q, double tol) const { - return ((*this) * (1.0 / norm())).equals(q * (1.0 / q.norm()), tol) - || ((*this) * (-1.0 / norm())).equals(q * (1.0 / q.norm()), tol); - } - - /** element access */ - double operator()(int i, int j) const { - return iter(i, j); - } - - /** swap indices */ - typedef Tensor2Expression Swapped; - /// Return Swap_ helper class - Swapped swap() { - return Swap_(iter); - } - - /** mutliply with a double. */ - inline Tensor2Expression operator*(double s) const { - return TimesDouble_(iter, s); - } - - /** Fix a single index */ - Tensor1Expression operator()(int j) const { - return FixJ_(j, iter); - } - - /** Check if two expressions are equal */ - template - bool operator==(const Tensor2Expression& T) const { - for (int i = 0; i < I::dim; i++) - for (int j = 0; j < J::dim; j++) - if (iter(i, j) != T(i, j)) - return false; - return true; - } - - /// @} - /// @name Advanced Interface - /// @{ - - /** c(j) = a(i,j)*b(i) */ - template - inline Tensor1Expression, J> operator*( - const Tensor1Expression& p) { - return ITimesRank1_(*this, p); - } - - /** c(i) = a(i,j)*b(j) */ - template - inline Tensor1Expression, I> operator*( - const Tensor1Expression &p) { - return JTimesRank1_(*this, p); - } - - /** c(j,k) = a(i,j)*T(i,k) */ - template - inline Tensor2Expression , J, K> operator*( - const Tensor2Expression& p) { - return ITimesRank2_(*this, p); - } - - }; - // Tensor2Expression - - /** Print */ - template - void print(const Tensor2Expression& T, const std::string& s = - "Tensor2:") { - T.print(s); - } - - /** Helper class for multiplying two covariant tensors */ - template class Rank1Rank1_ { - const Tensor1Expression iterA; - const Tensor1Expression iterB; - public: - /// Constructor - Rank1Rank1_(const Tensor1Expression &a, - const Tensor1Expression &b) : - iterA(a), iterB(b) { - } - /// element access - double operator()(int i, int j) const { - return iterA(i) * iterB(j); - } - }; - - /** Multiplying two different indices yields an outer product */ - template - inline Tensor2Expression , I, J> operator*( - const Tensor1Expression &a, const Tensor1Expression &b) { - return Rank1Rank1_(a, b); - } - - /** - * This template works for any two expressions - */ - template - bool assert_equality(const Tensor2Expression& expected, - const Tensor2Expression& actual, double tol = 1e-9) { - if (actual.equals(expected, tol)) - return true; - std::cout << "Not equal:\n"; - expected.print("expected:\n"); - actual.print("actual:\n"); - return false; - } - - /** - * This template works for any two expressions - */ - template - bool assert_equivalent(const Tensor2Expression& expected, - const Tensor2Expression& actual, double tol = 1e-9) { - if (actual.equivalent(expected, tol)) - return true; - std::cout << "Not equal:\n"; - expected.print("expected:\n"); - actual.print("actual:\n"); - return false; - } - - /// @} - -} // namespace tensors diff --git a/gtsam/geometry/Tensor3.h b/gtsam/geometry/Tensor3.h deleted file mode 100644 index 78cdcb9f2..000000000 --- a/gtsam/geometry/Tensor3.h +++ /dev/null @@ -1,106 +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 Tensor3.h - * @brief Rank 3 tensors based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author: Frank Dellaert - */ - -#pragma once -#include - -namespace tensors { - - /** - * Rank 3 Tensor - * @ingroup tensors - * \nosubgrouping - */ - template - class Tensor3 { - Tensor2 T[N3]; ///< Storage - - public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - Tensor3() { - } - - /** construct from data */ - Tensor3(const double data[N3][N2][N1]) { - for (int k = 0; k < N3; k++) - T[k] = data[k]; - } - - /// @} - /// @name Advanced Constructors - /// @{ - - /** construct from expression */ - template - Tensor3(const Tensor3Expression , Index , Index >& a) { - for (int k = 0; k < N3; k++) - T[k] = a(k); - } - - /// @} - /// @name Standard Interface - /// @{ - - /// element access - double operator()(int i, int j, int k) const { - return T[k](i, j); - } - - /** convert to expression */ - template Tensor3Expression , - Index , Index > operator()(const Index& i, - const Index& j, const Index& k) { - return Tensor3Expression , Index , Index > (*this); - } - - /** convert to expression */ - template Tensor3Expression , - Index , Index > operator()(const Index& i, - const Index& j, const Index& k) const { - return Tensor3Expression , Index , Index > (*this); - } - }; // Tensor3 - - /** Rank 3 permutation tensor */ - struct Eta3 { - - /** calculate value. TODO: wasteful to actually use this */ - double operator()(int i, int j, int k) const { - return ((j - i) * (k - i) * (k - j)) / 2; - } - - /** create expression */ - template Tensor3Expression , - Index<3, J> , Index<3, K> > operator()(const Index<3, I>& i, - const Index<3, J>& j, const Index<3, K>& k) const { - return Tensor3Expression , Index<3, J> , Index<3, K> > ( - *this); - } - - }; // Eta - - /// @} - -} // namespace tensors diff --git a/gtsam/geometry/Tensor3Expression.h b/gtsam/geometry/Tensor3Expression.h deleted file mode 100644 index 0356caa6f..000000000 --- a/gtsam/geometry/Tensor3Expression.h +++ /dev/null @@ -1,194 +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 Tensor3Expression.h - * @brief Tensor expression templates based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include - -namespace tensors { - - /** - * templated class to interface to an object A as a rank 3 tensor - * @ingroup tensors - * \nosubgrouping - */ - template class Tensor3Expression { - A iter; - - typedef Tensor3Expression This; - - /** Helper class for instantiating one index */ - class FixK_ { - const int k; - const A iter; - public: - FixK_(int k_, const A &a) : - k(k_), iter(a) { - } - double operator()(int i, int j) const { - return iter(i, j, k); - } - }; - - /** Helper class for contracting rank3 and rank1 tensor */ - template class TimesRank1_ { - typedef Tensor1Expression Rank1; - const This T; - const Rank1 t; - public: - TimesRank1_(const This &a, const Rank1 &b) : - T(a), t(b) { - } - double operator()(int j, int k) const { - double sum = 0.0; - for (int i = 0; i < I::dim; i++) - sum += T(i, j, k) * t(i); - return sum; - } - }; - - public: - - /// @name Standard Constructors - /// @{ - - /** constructor */ - Tensor3Expression(const A &a) : - iter(a) { - } - - /// @} - /// @name Standard Interface - /// @{ - - /** Print */ - void print(const std::string& s = "Tensor3:") const { - std::cout << s << "{"; - (*this)(0).print(""); - for (int k = 1; k < K::dim; k++) { - std::cout << ","; - (*this)(k).print(""); - } - std::cout << "}" << std::endl; - } - - /// test equality - template - bool equals(const Tensor3Expression & q, double tol) const { - for (int k = 0; k < K::dim; k++) - if (!(*this)(k).equals(q(k), tol)) return false; - return true; - } - - /** element access */ - double operator()(int i, int j, int k) const { - return iter(i, j, k); - } - - /** Fix a single index */ - Tensor2Expression operator()(int k) const { - return FixK_(k, iter); - } - - /** Contracting with rank1 tensor */ - template - inline Tensor2Expression , J, K> operator*( - const Tensor1Expression &b) const { - return TimesRank1_ (*this, b); - } - - }; // Tensor3Expression - - /// @} - /// @name Advanced Interface - /// @{ - - /** Print */ - template - void print(const Tensor3Expression& T, const std::string& s = - "Tensor3:") { - T.print(s); - } - - /** Helper class for outer product of rank2 and rank1 tensor */ - template - class Rank2Rank1_ { - typedef Tensor2Expression Rank2; - typedef Tensor1Expression Rank1; - const Rank2 iterA; - const Rank1 iterB; - public: - /// Constructor - Rank2Rank1_(const Rank2 &a, const Rank1 &b) : - iterA(a), iterB(b) { - } - /// Element access - double operator()(int i, int j, int k) const { - return iterA(i, j) * iterB(k); - } - }; - - /** outer product of rank2 and rank1 tensor */ - template - inline Tensor3Expression , I, J, K> operator*( - const Tensor2Expression& a, const Tensor1Expression &b) { - return Rank2Rank1_ (a, b); - } - - /** Helper class for outer product of rank1 and rank2 tensor */ - template - class Rank1Rank2_ { - typedef Tensor1Expression Rank1; - typedef Tensor2Expression Rank2; - const Rank1 iterA; - const Rank2 iterB; - public: - /// Constructor - Rank1Rank2_(const Rank1 &a, const Rank2 &b) : - iterA(a), iterB(b) { - } - /// Element access - double operator()(int i, int j, int k) const { - return iterA(i) * iterB(j, k); - } - }; - - /** outer product of rank2 and rank1 tensor */ - template - inline Tensor3Expression , I, J, K> operator*( - const Tensor1Expression& a, const Tensor2Expression &b) { - return Rank1Rank2_ (a, b); - } - - /** - * This template works for any two expressions - */ - template - bool assert_equality(const Tensor3Expression& expected, - const Tensor3Expression& actual, double tol = 1e-9) { - if (actual.equals(expected, tol)) return true; - std::cout << "Not equal:\n"; - expected.print("expected:\n"); - actual.print("actual:\n"); - return false; - } - - /// @} - -} // namespace tensors diff --git a/gtsam/geometry/Tensor4.h b/gtsam/geometry/Tensor4.h deleted file mode 100644 index 26a52750c..000000000 --- a/gtsam/geometry/Tensor4.h +++ /dev/null @@ -1,58 +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 Tensor4.h - * @brief Rank 4 tensors based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 12, 2010 - * @author Frank Dellaert - */ - -#pragma once -#include - -namespace tensors { - - /** - * Rank 4 Tensor - * @ingroup tensors - * \nosubgrouping - */ - template - class Tensor4 { - - private: - - Tensor3 T[N4]; ///< Storage - - public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - Tensor4() { - } - - /// @} - /// @name Standard Interface - /// @{ - - /// element access - double operator()(int i, int j, int k, int l) const { - return T[l](i, j, k); - } - - /// @} - - }; // Tensor4 - -} // namespace tensors diff --git a/gtsam/geometry/Tensor5.h b/gtsam/geometry/Tensor5.h deleted file mode 100644 index e12f7d2fb..000000000 --- a/gtsam/geometry/Tensor5.h +++ /dev/null @@ -1,75 +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 Tensor5.h - * @brief Rank 5 tensors based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 12, 2010 - * @author Frank Dellaert - */ - -#pragma once -#include - -namespace tensors { - - /** - * Rank 5 Tensor - * @ingroup tensors - * \nosubgrouping - */ - template - class Tensor5 { - - private: - - Tensor4 T[N5]; ///< Storage - - public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - Tensor5() { - } - - /// @} - /// @name Standard Interface - /// @{ - - /** construct from expression */ - template - Tensor5(const Tensor5Expression , Index , Index , Index , Index >& a) { - for (int m = 0; m < N5; m++) - T[m] = a(m); - } - - /// element access - double operator()(int i, int j, int k, int l, int m) const { - return T[m](i, j, k, l); - } - - /** convert to expression */ - template Tensor5Expression , Index , Index , Index , - Index > operator()(Index i, Index j, - Index k, Index l, Index m) { - return Tensor5Expression , Index , Index , Index , Index > (*this); - } - - /// @} - - }; // Tensor5 - -} // namespace tensors diff --git a/gtsam/geometry/Tensor5Expression.h b/gtsam/geometry/Tensor5Expression.h deleted file mode 100644 index e9f0e852a..000000000 --- a/gtsam/geometry/Tensor5Expression.h +++ /dev/null @@ -1,135 +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 Tensor5Expression.h - * @brief Tensor expression templates based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include - -namespace tensors { - - /** - * templated class to interface to an object A as a rank 5 tensor - * @ingroup tensors - * \nosubgrouping - */ - template class Tensor5Expression { - A iter; - - typedef Tensor5Expression This; - - /** Helper class for swapping indices 3 and 4 :-) */ - class Swap34_ { - const A iter; - public: - /// Constructor - Swap34_(const A &a) : - iter(a) { - } - /// swapping element access - double operator()(int i, int j, int k, int l, int m) const { - return iter(i, j, l, k, m); - } - }; - - public: - - /// @name Standard Constructors - /// @{ - - /** constructor */ - Tensor5Expression(const A &a) : - iter(a) { - } - - /// @} - /// @name Standard Interface - /// @{ - - /** Print */ - void print(const std::string& s = "Tensor5:") const { - std::cout << s << std::endl; - for (int m = 0; m < M::dim; m++) - for (int l = 0; l < L::dim; l++) - for (int k = 0; k < K::dim; k++) { - std::cout << "(m,l,k) = (" << m << "," << l << "," << k << ")" - << std::endl; - for (int j = 0; j < J::dim; j++) { - for (int i = 0; i < I::dim; i++) - std::cout << " " << (*this)(i, j, k, l, m); - std::cout << std::endl; - } - } - std::cout << std::endl; - } - - /** swap indices */ - typedef Tensor5Expression Swapped; - /// create Swap34_ helper class - Swapped swap34() { - return Swap34_(iter); - } - - /** element access */ - double operator()(int i, int j, int k, int l, int m) const { - return iter(i, j, k, l, m); - } - - }; - // Tensor5Expression - - /// @} - /// @name Advanced Interface - /// @{ - - /** Print */ - template - void print(const Tensor5Expression& T, - const std::string& s = "Tensor5:") { - T.print(s); - } - - /** Helper class for outer product of rank3 and rank2 tensor */ - template - class Rank3Rank2_ { - typedef Tensor3Expression Rank3; - typedef Tensor2Expression Rank2; - const Rank3 iterA; - const Rank2 iterB; - public: - /// Constructor - Rank3Rank2_(const Rank3 &a, const Rank2 &b) : - iterA(a), iterB(b) { - } - /// Element access - double operator()(int i, int j, int k, int l, int m) const { - return iterA(i, j, k) * iterB(l, m); - } - }; - - /** outer product of rank2 and rank1 tensor */ - template - inline Tensor5Expression , I, J, K, L, M> operator*( - const Tensor3Expression& a, - const Tensor2Expression &b) { - return Rank3Rank2_(a, b); - } - - /// @} - -} // namespace tensors diff --git a/gtsam/geometry/concepts.h b/gtsam/geometry/concepts.h index 3000530e5..bde16ee6e 100644 --- a/gtsam/geometry/concepts.h +++ b/gtsam/geometry/concepts.h @@ -49,6 +49,14 @@ private: static Translation checkTranslationMemberAccess(const POSE& p) { return p.translation(); } + + static std::pair checkTranslationInterval() { + return POSE::translationInterval(); + } + + static std::pair checkRotationInterval() { + return POSE::rotationInterval(); + } }; /** diff --git a/gtsam/geometry/projectiveGeometry.cpp b/gtsam/geometry/projectiveGeometry.cpp deleted file mode 100644 index 31c975c43..000000000 --- a/gtsam/geometry/projectiveGeometry.cpp +++ /dev/null @@ -1,71 +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 projectiveGeometry.cpp - * @brief Projective geometry, implemented using tensor library - * @date Feb 12, 2010 - * @author: Frank Dellaert - */ - -#include -#include - -#include -#include - -namespace gtsam { - - using namespace std; - using namespace tensors; - - /* ************************************************************************* */ - Point2h point2h(double x, double y, double w) { - double data[3]; - data[0] = x; - data[1] = y; - data[2] = w; - return data; - } - - /* ************************************************************************* */ - Line2h line2h(double a, double b, double c) { - double data[3]; - data[0] = a; - data[1] = b; - data[2] = c; - return data; - } - - /* ************************************************************************* */ - Point3h point3h(double X, double Y, double Z, double W) { - double data[4]; - data[0] = X; - data[1] = Y; - data[2] = Z; - data[3] = W; - return data; - } - - /* ************************************************************************* */ - Plane3h plane3h(double a, double b, double c, double d) { - double data[4]; - data[0] = a; - data[1] = b; - data[2] = c; - data[3] = d; - return data; - } - - - /* ************************************************************************* */ - -} // namespace gtsam diff --git a/gtsam/geometry/projectiveGeometry.h b/gtsam/geometry/projectiveGeometry.h deleted file mode 100644 index cfad515ac..000000000 --- a/gtsam/geometry/projectiveGeometry.h +++ /dev/null @@ -1,124 +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 projectiveGeometry.h - * @brief Projective geometry, implemented using tensor library - * @date Feb 12, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include - -namespace gtsam { - - /** - * 2D Point in homogeneous coordinates - * @ingroup geometry - */ - typedef tensors::Tensor1<3> Point2h; - Point2h point2h(double x, double y, double w); ///< create Point2h - - /** - * 2D Line in homogeneous coordinates - * @ingroup geometry - */ - typedef tensors::Tensor1<3> Line2h; - Line2h line2h(double a, double b, double c); ///< create Line2h - - /** - * 2D (homegeneous) Point correspondence - * @ingroup geometry - */ - struct Correspondence { - Point2h first; ///< First point - Point2h second; ///< Second point - - /// Create a correspondence pair - Correspondence(const Point2h &p1, const Point2h &p2) : - first(p1), second(p2) { - } - /// Swap points - Correspondence swap() const { - return Correspondence(second, first); - } - /// print - void print() { - tensors::Index<3, 'i'> i; - tensors::print(first(i), "first :"); - tensors::print(second(i), "second:"); - } - }; - - /** - * 2D-2D Homography - * @ingroup geometry - */ - typedef tensors::Tensor2<3, 3> Homography2; - - /** - * Fundamental Matrix - * @ingroup geometry - */ - typedef tensors::Tensor2<3, 3> FundamentalMatrix; - - /** - * Triplet of (homogeneous) 2D points - * @ingroup geometry - */ - struct Triplet { - Point2h first; ///< First point - Point2h second; ///< Second point - Point2h third; ///< Third point - - /// Create a Triplet correspondence - Triplet(const Point2h &p1, const Point2h &p2, const Point2h &p3) : - first(p1), second(p2), third(p3) { - } - /// print - void print() { - tensors::Index<3, 'i'> i; - tensors::print(first(i), "first :"); - tensors::print(second(i), "second:"); - tensors::print(third(i), "third :"); - } - }; - - /** - * Trifocal Tensor - * @ingroup geometry - */ - typedef tensors::Tensor3<3, 3, 3> TrifocalTensor; - - /** - * 3D Point in homogeneous coordinates - * @ingroup geometry - */ - typedef tensors::Tensor1<4> Point3h; - Point3h point3h(double X, double Y, double Z, double W); ///< create Point3h - - /** - * 3D Plane in homogeneous coordinates - * @ingroup geometry - */ - typedef tensors::Tensor1<4> Plane3h; - Plane3h plane3h(double a, double b, double c, double d); ///< create Plane3h - - /** - * 3D to 2D projective camera - * @ingroup geometry - */ - typedef tensors::Tensor2<3, 4> ProjectiveCamera; - -} // namespace gtsam diff --git a/gtsam/geometry/tensorInterface.h b/gtsam/geometry/tensorInterface.h deleted file mode 100644 index 61212e2c9..000000000 --- a/gtsam/geometry/tensorInterface.h +++ /dev/null @@ -1,108 +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 tensorInterface.h - * @brief Interfacing tensors template library and gtsam - * @date Feb 12, 2010 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include - -namespace gtsam { - - /** Reshape rank 2 tensor into Matrix */ - template - Matrix reshape(const tensors::Tensor2Expression& T, int m, int n) { - if (m * n != I::dim * J::dim) throw std::invalid_argument( - "reshape: incompatible dimensions"); - MatrixRowMajor M(m, n); - size_t t = 0; - for (int j = 0; j < J::dim; j++) - for (int i = 0; i < I::dim; i++) - M.data()[t++] = T(i, j); - return Matrix(M); - } - - /** Reshape rank 2 tensor into Vector */ - template - Vector toVector(const tensors::Tensor2Expression& T) { - Vector v(I::dim * J::dim); - size_t t = 0; - for (int j = 0; j < J::dim; j++) - for (int i = 0; i < I::dim; i++) - v(t++) = T(i, j); - return v; - } - - /** Reshape Vector into rank 2 tensor */ - template - tensors::Tensor2 reshape2(const Vector& v) { - if (v.size() != N1 * N2) throw std::invalid_argument( - "reshape2: incompatible dimensions"); - double data[N2][N1]; - int t = 0; - for (int j = 0; j < N2; j++) - for (int i = 0; i < N1; i++) - data[j][i] = v(t++); - return tensors::Tensor2(data); - } - - /** Reshape rank 3 tensor into Matrix */ - template - Matrix reshape(const tensors::Tensor3Expression& T, int m, int n) { - if (m * n != I::dim * J::dim * K::dim) throw std::invalid_argument( - "reshape: incompatible dimensions"); - Matrix M(m, n); - int t = 0; - for (int k = 0; k < K::dim; k++) - for (int i = 0; i < I::dim; i++) - for (int j = 0; j < J::dim; j++) - M.data()[t++] = T(i, j, k); - return M; - } - - /** Reshape Vector into rank 3 tensor */ - template - tensors::Tensor3 reshape3(const Vector& v) { - if (v.size() != N1 * N2 * N3) throw std::invalid_argument( - "reshape3: incompatible dimensions"); - double data[N3][N2][N1]; - int t = 0; - for (int k = 0; k < N3; k++) - for (int j = 0; j < N2; j++) - for (int i = 0; i < N1; i++) - data[k][j][i] = v(t++); - return tensors::Tensor3(data); - } - - /** Reshape rank 5 tensor into Matrix */ - template - Matrix reshape(const tensors::Tensor5Expression& T, int m, - int n) { - if (m * n != I::dim * J::dim * K::dim * L::dim * M::dim) throw std::invalid_argument( - "reshape: incompatible dimensions"); - Matrix R(m, n); - int t = 0; - for (int m = 0; m < M::dim; m++) - for (int l = 0; l < L::dim; l++) - for (int k = 0; k < K::dim; k++) - for (int i = 0; i < I::dim; i++) - for (int j = 0; j < J::dim; j++) - R.data()[t++] = T(i, j, k, l, m); - return R; - } - -} // namespace gtsam diff --git a/gtsam/geometry/tensors.h b/gtsam/geometry/tensors.h deleted file mode 100644 index 1441a7823..000000000 --- a/gtsam/geometry/tensors.h +++ /dev/null @@ -1,45 +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 tensors.h - * @brief Tensor expression templates based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 10, 2010 - * @author Frank Dellaert - * @defgroup tensors - */ - -#pragma once - -namespace tensors { - - /** index */ - template struct Index { - static const int dim = Dim; ///< dimension - }; - -} // namespace tensors - -// Expression templates -#include -#include -#include -// Tensor4 not needed so far -#include - -// Actual tensor classes -#include -#include -#include -#include -#include - - diff --git a/gtsam/geometry/tests/testCal3Bundler.cpp b/gtsam/geometry/tests/testCal3Bundler.cpp index bb1bd861d..e354796fa 100644 --- a/gtsam/geometry/tests/testCal3Bundler.cpp +++ b/gtsam/geometry/tests/testCal3Bundler.cpp @@ -25,8 +25,8 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3Bundler) GTSAM_CONCEPT_MANIFOLD_INST(Cal3Bundler) -Cal3Bundler K(500, 1e-3, 1e-3); -Point2 p(2,3); +static Cal3Bundler K(500, 1e-3, 1e-3); +static Point2 p(2,3); /* ************************************************************************* */ TEST( Cal3Bundler, calibrate) diff --git a/gtsam/geometry/tests/testCal3DS2.cpp b/gtsam/geometry/tests/testCal3DS2.cpp index 4c79a447b..c73ae1182 100644 --- a/gtsam/geometry/tests/testCal3DS2.cpp +++ b/gtsam/geometry/tests/testCal3DS2.cpp @@ -25,11 +25,11 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3DS2) GTSAM_CONCEPT_MANIFOLD_INST(Cal3DS2) -Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3); -Point2 p(2,3); +static Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3); +static Point2 p(2,3); /* ************************************************************************* */ -TEST( Cal3DS2, calibrate) +TEST( Cal3DS2, uncalibrate) { Vector k = K.k() ; double r = p.x()*p.x() + p.y()*p.y() ; @@ -43,6 +43,14 @@ TEST( Cal3DS2, calibrate) CHECK(assert_equal(q,p_i)); } +TEST( Cal3DS2, calibrate ) +{ + Point2 pn(0.5, 0.5); + Point2 pi = K.uncalibrate(pn); + Point2 pn_hat = K.calibrate(pi); + CHECK( pn.equals(pn_hat, 1e-5)); +} + Point2 uncalibrate_(const Cal3DS2& k, const Point2& pt) { return k.uncalibrate(pt); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testCal3_S2.cpp b/gtsam/geometry/tests/testCal3_S2.cpp index fd82557a3..8995a3a14 100644 --- a/gtsam/geometry/tests/testCal3_S2.cpp +++ b/gtsam/geometry/tests/testCal3_S2.cpp @@ -24,8 +24,8 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3_S2) GTSAM_CONCEPT_MANIFOLD_INST(Cal3_S2) -Cal3_S2 K(500, 500, 0.1, 640 / 2, 480 / 2); -Point2 p(1, -2); +static Cal3_S2 K(500, 500, 0.1, 640 / 2, 480 / 2); +static Point2 p(1, -2); /* ************************************************************************* */ TEST( Cal3_S2, easy_constructor) diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index 5bb1ebe65..57ccc0260 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -27,19 +27,19 @@ using namespace gtsam; GTSAM_CONCEPT_MANIFOLD_INST(CalibratedCamera) -const Pose3 pose1(Matrix_(3,3, +static const Pose3 pose1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,0.5)); -const CalibratedCamera camera(pose1); +static const CalibratedCamera camera(pose1); -const Point3 point1(-0.08,-0.08, 0.0); -const Point3 point2(-0.08, 0.08, 0.0); -const Point3 point3( 0.08, 0.08, 0.0); -const Point3 point4( 0.08,-0.08, 0.0); +static const Point3 point1(-0.08,-0.08, 0.0); +static const Point3 point2(-0.08, 0.08, 0.0); +static const Point3 point3( 0.08, 0.08, 0.0); +static const Point3 point4( 0.08,-0.08, 0.0); /* ************************************************************************* */ TEST( CalibratedCamera, constructor) @@ -52,7 +52,7 @@ TEST( CalibratedCamera, level1) { // Create a level camera, looking in X-direction Pose2 pose2(0.1,0.2,0); - CalibratedCamera camera = CalibratedCamera::level(pose2, 0.3); + CalibratedCamera camera = CalibratedCamera::Level(pose2, 0.3); // expected Point3 x(0,-1,0),y(0,0,-1),z(1,0,0); @@ -65,8 +65,8 @@ TEST( CalibratedCamera, level1) TEST( CalibratedCamera, level2) { // Create a level camera, looking in Y-direction - Pose2 pose2(0.4,0.3,M_PI_2); - CalibratedCamera camera = CalibratedCamera::level(pose2, 0.1); + Pose2 pose2(0.4,0.3,M_PI/2.0); + CalibratedCamera camera = CalibratedCamera::Level(pose2, 0.1); // expected Point3 x(1,0,0),y(0,0,-1),z(0,1,0); @@ -95,7 +95,7 @@ TEST( CalibratedCamera, Dproject_to_camera1) { } /* ************************************************************************* */ -Point2 project2(const Pose3& pose, const Point3& point) { +static Point2 project2(const Pose3& pose, const Point3& point) { return CalibratedCamera(pose).project(point); } diff --git a/gtsam/geometry/tests/testFundamental.cpp b/gtsam/geometry/tests/testFundamental.cpp deleted file mode 100644 index 297b36036..000000000 --- a/gtsam/geometry/tests/testFundamental.cpp +++ /dev/null @@ -1,73 +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 testFundamental.cpp - * @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 13, 2010 - * @author: Frank Dellaert - */ - -#include -#include -#include // for operator += -using namespace boost::assign; - -#include - -#include -#include -#include - -using namespace std; -using namespace gtsam; -using namespace tensors; - -/* ************************************************************************* */ -// Indices - -Index<3, 'a'> a; -Index<3, 'b'> b; - -Index<4, 'A'> A; -Index<4, 'B'> B; - -/* ************************************************************************* */ -TEST( Tensors, FundamentalMatrix) -{ - double f[3][3] = { { 1, 0, 0 }, { 1, 2, 3 }, { 1, 2, 3 } }; - FundamentalMatrix F(f); - - Point2h p = point2h(1, 2, 3); // point p in view one - Point2h q = point2h(14, -1, 0); // point q in view two - - // points p and q are in correspondence - CHECK(F(a,b)*p(a)*q(b) == 0) - - // in detail, l1(b)*q(b)==0 - Line2h l1 = line2h(1, 14, 14); - CHECK(F(a,b)*p(a) == l1(b)) - CHECK(l1(b)*q(b) == 0); // q is on line l1 - - // and l2(a)*p(a)==0 - Line2h l2 = line2h(13, -2, -3); - CHECK(F(a,b)*q(b) == l2(a)) - CHECK(l2(a)*p(a) == 0); // p is on line l2 -} - - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ - diff --git a/gtsam/geometry/tests/testHomography2.cpp b/gtsam/geometry/tests/testHomography2.cpp deleted file mode 100644 index 417d41977..000000000 --- a/gtsam/geometry/tests/testHomography2.cpp +++ /dev/null @@ -1,188 +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 testHomography2.cpp - * @brief Test and estimate 2D homographies - * @date Feb 13, 2010 - * @author Frank Dellaert - */ - -#include -#include -#include // for operator += -using namespace boost::assign; - -#include - -#include -#include -#include -#include -#include - -using namespace std; -using namespace gtsam; -using namespace tensors; - -/* ************************************************************************* */ -// Indices - -Index<3, 'a'> a, _a; -Index<3, 'b'> b, _b; -Index<3, 'c'> c, _c; - -/* ************************************************************************* */ -TEST( Homography2, RealImages) -{ - // 4 point correspondences MATLAB from the floor of bt001.png and bt002.png - Correspondence p1(point2h(216.841, 443.220, 1), point2h(213.528, 414.671, 1)); - Correspondence p2(point2h(252.119, 363.481, 1), point2h(244.614, 348.842, 1)); - Correspondence p3(point2h(316.614, 414.768, 1), point2h(303.128, 390.000, 1)); - Correspondence p4(point2h(324.165, 465.463, 1), point2h(308.614, 431.129, 1)); - - // Homography obtained using MATLAB code - double h[3][3] = { { 0.9075, 0.0031, -0 }, { -0.1165, 0.8288, -0.0004 }, { - 30.8472, 16.0449, 1 } }; - Homography2 H(h); - - // CHECK whether they are equivalent - CHECK(assert_equivalent(p1.second(b),H(b,a)*p1.first(a),0.05)) - CHECK(assert_equivalent(p2.second(b),H(b,a)*p2.first(a),0.05)) - CHECK(assert_equivalent(p3.second(b),H(b,a)*p3.first(a),0.05)) - CHECK(assert_equivalent(p4.second(b),H(b,a)*p4.first(a),0.05)) -} - -/* ************************************************************************* */ -// Homography test case -// 4 trivial correspondences of a translating square -Correspondence p1(point2h(0, 0, 1), point2h(4, 5, 1)); -Correspondence p2(point2h(1, 0, 1), point2h(5, 5, 1)); -Correspondence p3(point2h(1, 1, 1), point2h(5, 6, 1)); -Correspondence p4(point2h(0, 1, 1), point2h(4, 6, 1)); - -double h[3][3] = { { 1, 0, 4 }, { 0, 1, 5 }, { 0, 0, 1 } }; -Homography2 H(h); - -/* ************************************************************************* */ -TEST( Homography2, TestCase) -{ - // Check homography - list correspondences; - correspondences += p1, p2, p3, p4; - BOOST_FOREACH(const Correspondence& p, correspondences) - CHECK(assert_equality(p.second(b),H(_a,b) * p.first(a))) - - // Check a line - Line2h l1 = line2h(1, 0, -1); // in a - Line2h l2 = line2h(1, 0, -5); // x==5 in b - CHECK(assert_equality(l1(a), H(a,b)*l2(b))) -} - -/* ************************************************************************* */ -/** - * Computes the homography H(I,_T) from template to image - * given the pose tEc of the camera in the template coordinate frame. - * Assumption is Z is normal to the template, template texture in X-Y plane. - */ -Homography2 patchH(const Pose3& tEc) { - Pose3 cEt = tEc.inverse(); - Rot3 cRt = cEt.rotation(); - Point3 r1 = cRt.r1(), r2 = cRt.r2(), t = cEt.translation(); - - // TODO cleanup !!!! - // column 1 - double H11 = r1.x(); - double H21 = r1.y(); - double H31 = r1.z(); - // column 2 - double H12 = r2.x(); - double H22 = r2.y(); - double H32 = r2.z(); - // column 3 - double H13 = t.x(); - double H23 = t.y(); - double H33 = t.z(); - double data2[3][3] = { { H11, H21, H31 }, { H12, H22, H32 }, - { H13, H23, H33 } }; - return Homography2(data2); -} - -/* ************************************************************************* */ -namespace gtsam { -// size_t dim(const tensors::Tensor2<3, 3>& H) {return 9;} - Vector toVector(const tensors::Tensor2<3, 3>& H) { - Index<3, 'T'> _T; // covariant 2D template - Index<3, 'C'> I; // contravariant 2D camera - return toVector(H(I,_T)); - } - Vector localCoordinates(const tensors::Tensor2<3, 3>& A, const tensors::Tensor2<3, 3>& B) { - return toVector(A)-toVector(B); // TODO correct order ? - } -} - -#include - -/* ************************************************************************* */ -TEST( Homography2, patchH) -{ - Index<3, 'T'> _T; // covariant 2D template - Index<3, 'C'> I; // contravariant 2D camera - - // data[_T][I] - double data1[3][3] = {{1,0,0},{0,-1,0},{0,0,10}}; - Homography2 expected(data1); - - // camera rotation, looking in negative Z - Rot3 gRc(Point3(1,0,0),Point3(0,-1,0),Point3(0,0,-1)); - Point3 gTc(0,0,10); // Camera location, out on the Z axis - Pose3 gEc(gRc,gTc); // Camera pose - - Homography2 actual = patchH(gEc); - -// GTSAM_PRINT(expected(I,_T)); -// GTSAM_PRINT(actual(I,_T)); - CHECK(assert_equality(expected(I,_T),actual(I,_T))); - - // FIXME: this doesn't appear to be tested, and requires that Tensor2 be a Lie object -// Matrix D = numericalDerivative11(patchH, gEc); -// print(D,"D"); -} - -/* ************************************************************************* */ -TEST( Homography2, patchH2) -{ - Index<3, 'T'> _T; // covariant 2D template - Index<3, 'C'> I; // contravariant 2D camera - - // data[_T][I] - double data1[3][3] = {{1,0,0},{0,-1,0},{0,0,10}}; - Homography2 expected(data1); - - // camera rotation, looking in negative Z - Rot3 gRc(Point3(1,0,0),Point3(0,-1,0),Point3(0,0,-1)); - Point3 gTc(0,0,10); // Camera location, out on the Z axis - Pose3 gEc(gRc,gTc); // Camera pose - - Homography2 actual = patchH(gEc); - -// GTSAM_PRINT(expected(I,_T)); -// GTSAM_PRINT(actual(I,_T)); - CHECK(assert_equality(expected(I,_T),actual(I,_T))); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ - diff --git a/gtsam/geometry/tests/testPoint2.cpp b/gtsam/geometry/tests/testPoint2.cpp index 3416361cd..f7fee0418 100644 --- a/gtsam/geometry/tests/testPoint2.cpp +++ b/gtsam/geometry/tests/testPoint2.cpp @@ -72,7 +72,7 @@ TEST( Point2, arithmetic) /* ************************************************************************* */ TEST( Point2, norm) { - Point2 p0(cos(5), sin(5)); + Point2 p0(cos(5.0), sin(5.0)); DOUBLES_EQUAL(1,p0.norm(),1e-6); Point2 p1(4, 5), p2(1, 1); DOUBLES_EQUAL( 5,p1.dist(p2),1e-6); @@ -85,7 +85,7 @@ TEST( Point2, unit) Point2 p0(10.0, 0.0), p1(0.0,-10.0), p2(10.0, 10.0); EXPECT(assert_equal(Point2(1.0, 0.0), p0.unit(), 1e-6)); EXPECT(assert_equal(Point2(0.0,-1.0), p1.unit(), 1e-6)); - EXPECT(assert_equal(Point2(sqrt(2)/2.0, sqrt(2)/2.0), p2.unit(), 1e-6)); + EXPECT(assert_equal(Point2(sqrt(2.0)/2.0, sqrt(2.0)/2.0), p2.unit(), 1e-6)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index c7e25f7a9..492d65e42 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -23,7 +23,7 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Point3) GTSAM_CONCEPT_LIE_INST(Point3) -Point3 P(0.2,0.7,-2); +static Point3 P(0.2,0.7,-2); /* ************************************************************************* */ TEST(Point3, Lie) { diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index 14e529613..a79371e63 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -44,14 +44,14 @@ TEST(Pose2, constructors) { Pose2 pose(0,p); Pose2 origin; assert_equal(pose,origin); - Pose2 t(M_PI_2+0.018, Point2(1.015, 2.01)); + Pose2 t(M_PI/2.0+0.018, Point2(1.015, 2.01)); EXPECT(assert_equal(t,Pose2(t.matrix()))); } /* ************************************************************************* */ TEST(Pose2, manifold) { - Pose2 t1(M_PI_2, Point2(1, 2)); - Pose2 t2(M_PI_2+0.018, Point2(1.015, 2.01)); + Pose2 t1(M_PI/2.0, Point2(1, 2)); + Pose2 t2(M_PI/2.0+0.018, Point2(1.015, 2.01)); Pose2 origin; Vector d12 = t1.localCoordinates(t2); EXPECT(assert_equal(t2, t1.retract(d12))); @@ -63,11 +63,11 @@ TEST(Pose2, manifold) { /* ************************************************************************* */ TEST(Pose2, retract) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); #ifdef SLOW_BUT_CORRECT_EXPMAP Pose2 expected(1.00811, 2.01528, 2.5608); #else - Pose2 expected(M_PI_2+0.99, Point2(1.015, 2.01)); + Pose2 expected(M_PI/2.0+0.99, Point2(1.015, 2.01)); #endif Pose2 actual = pose.retract(Vector_(3, 0.01, -0.015, 0.99)); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -75,7 +75,7 @@ TEST(Pose2, retract) { /* ************************************************************************* */ TEST(Pose2, expmap) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); Pose2 expected(1.00811, 2.01528, 2.5608); Pose2 actual = expmap_default(pose, Vector_(3, 0.01, -0.015, 0.99)); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -83,7 +83,7 @@ TEST(Pose2, expmap) { /* ************************************************************************* */ TEST(Pose2, expmap2) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); Pose2 expected(1.00811, 2.01528, 2.5608); Pose2 actual = expmap_default(pose, Vector_(3, 0.01, -0.015, 0.99)); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -110,11 +110,11 @@ TEST(Pose2, expmap3) { /* ************************************************************************* */ TEST(Pose2, expmap0) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); //#ifdef SLOW_BUT_CORRECT_EXPMAP Pose2 expected(1.01491, 2.01013, 1.5888); //#else -// Pose2 expected(M_PI_2+0.018, Point2(1.015, 2.01)); +// Pose2 expected(M_PI/2.0+0.018, Point2(1.015, 2.01)); //#endif Pose2 actual = pose * (Pose2::Expmap(Vector_(3, 0.01, -0.015, 0.018))); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -122,7 +122,7 @@ TEST(Pose2, expmap0) { /* ************************************************************************* */ TEST(Pose2, expmap0_full) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); Pose2 expected(1.01491, 2.01013, 1.5888); Pose2 actual = pose * Pose2::Expmap(Vector_(3, 0.01, -0.015, 0.018)); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -130,7 +130,7 @@ TEST(Pose2, expmap0_full) { /* ************************************************************************* */ TEST(Pose2, expmap0_full2) { - Pose2 pose(M_PI_2, Point2(1, 2)); + Pose2 pose(M_PI/2.0, Point2(1, 2)); Pose2 expected(1.01491, 2.01013, 1.5888); Pose2 actual = pose * Pose2::Expmap(Vector_(3, 0.01, -0.015, 0.018)); EXPECT(assert_equal(expected, actual, 1e-5)); @@ -156,7 +156,7 @@ TEST(Pose3, expmap_c) #endif /* ************************************************************************* */ -TEST(Pose3, expmap_c_full) +TEST(Pose2, expmap_c_full) { double w=0.3; Vector xi = Vector_(3, 0.0, w, w); @@ -170,8 +170,8 @@ TEST(Pose3, expmap_c_full) /* ************************************************************************* */ TEST(Pose2, logmap) { - Pose2 pose0(M_PI_2, Point2(1, 2)); - Pose2 pose(M_PI_2+0.018, Point2(1.015, 2.01)); + Pose2 pose0(M_PI/2.0, Point2(1, 2)); + Pose2 pose(M_PI/2.0+0.018, Point2(1.015, 2.01)); #ifdef SLOW_BUT_CORRECT_EXPMAP Vector expected = Vector_(3, 0.00986473, -0.0150896, 0.018); #else @@ -183,21 +183,21 @@ TEST(Pose2, logmap) { /* ************************************************************************* */ TEST(Pose2, logmap_full) { - Pose2 pose0(M_PI_2, Point2(1, 2)); - Pose2 pose(M_PI_2+0.018, Point2(1.015, 2.01)); + Pose2 pose0(M_PI/2.0, Point2(1, 2)); + Pose2 pose(M_PI/2.0+0.018, Point2(1.015, 2.01)); Vector expected = Vector_(3, 0.00986473, -0.0150896, 0.018); Vector actual = logmap_default(pose0, pose); EXPECT(assert_equal(expected, actual, 1e-5)); } /* ************************************************************************* */ -Point2 transform_to_proxy(const Pose2& pose, const Point2& point) { +static Point2 transform_to_proxy(const Pose2& pose, const Point2& point) { return pose.transform_to(point); } TEST( Pose2, transform_to ) { - Pose2 pose(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y + Pose2 pose(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y Point2 point(-1,4); // landmark at (-1,4) // expected @@ -220,13 +220,13 @@ TEST( Pose2, transform_to ) } /* ************************************************************************* */ -Point2 transform_from_proxy(const Pose2& pose, const Point2& point) { +static Point2 transform_from_proxy(const Pose2& pose, const Point2& point) { return pose.transform_from(point); } TEST (Pose2, transform_from) { - Pose2 pose(1., 0., M_PI_2); + Pose2 pose(1., 0., M_PI/2.0); Point2 pt(2., 1.); Matrix H1, H2; Point2 actual = pose.transform_from(pt, H1, H2); @@ -326,7 +326,7 @@ TEST(Pose2, compose_c) TEST(Pose2, inverse ) { Point2 origin, t(1,2); - Pose2 gTl(M_PI_2, t); // robot at (1,2) looking towards y + Pose2 gTl(M_PI/2.0, t); // robot at (1,2) looking towards y Pose2 identity, lTg = gTl.inverse(); EXPECT(assert_equal(identity,lTg.compose(gTl))); @@ -362,7 +362,7 @@ Matrix matrix(const Pose2& gTl) { TEST( Pose2, matrix ) { Point2 origin, t(1,2); - Pose2 gTl(M_PI_2, t); // robot at (1,2) looking towards y + Pose2 gTl(M_PI/2.0, t); // robot at (1,2) looking towards y Matrix gMl = matrix(gTl); EXPECT(assert_equal(Matrix_(3,3, 0.0, -1.0, 1.0, @@ -393,7 +393,7 @@ TEST( Pose2, matrix ) /* ************************************************************************* */ TEST( Pose2, compose_matrix ) { - Pose2 gT1(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y + Pose2 gT1(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y Pose2 _1T2(M_PI, Point2(-1,4)); // local robot at (-1,4) loooking at negative x Matrix gM1(matrix(gT1)),_1M2(matrix(_1T2)); EXPECT(assert_equal(gM1*_1M2,matrix(gT1.compose(_1T2)))); // RIGHT DOES NOT @@ -407,11 +407,11 @@ TEST( Pose2, between ) // ^ // // *--0--*--* - Pose2 gT1(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y + Pose2 gT1(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y Pose2 gT2(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x Matrix actualH1,actualH2; - Pose2 expected(M_PI_2, Point2(2,2)); + Pose2 expected(M_PI/2.0, Point2(2,2)); Pose2 actual1 = gT1.between(gT2); Pose2 actual2 = gT1.between(gT2,actualH1,actualH2); EXPECT(assert_equal(expected,actual1)); @@ -426,7 +426,7 @@ TEST( Pose2, between ) EXPECT(assert_equal(expectedH1,actualH1)); EXPECT(assert_equal(numericalH1,actualH1)); // Assert H1 = -AdjointMap(between(p2,p1)) as in doc/math.lyx - EXPECT(assert_equal(-gT2.between(gT1).AdjointMap(),actualH1)); + EXPECT(assert_equal(-gT2.between(gT1).adjointMap(),actualH1)); Matrix expectedH2 = Matrix_(3,3, 1.0, 0.0, 0.0, @@ -443,7 +443,7 @@ TEST( Pose2, between ) // reverse situation for extra test TEST( Pose2, between2 ) { - Pose2 p2(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y + Pose2 p2(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y Pose2 p1(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x Matrix actualH1,actualH2; @@ -472,7 +472,7 @@ TEST(Pose2, members) /* ************************************************************************* */ // some shared test values -Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI_4); +Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI/4.0); Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3); /* ************************************************************************* */ @@ -488,11 +488,11 @@ TEST( Pose2, bearing ) EXPECT(assert_equal(Rot2(),x1.bearing(l1))); // establish bearing is indeed 45 degrees - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),x1.bearing(l2))); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),x1.bearing(l2))); // establish bearing is indeed 45 degrees even if shifted Rot2 actual23 = x2.bearing(l3, actualH1, actualH2); - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),actual23)); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual23)); // Check numerical derivatives expectedH1 = numericalDerivative21(bearing_proxy, x2, l3); @@ -502,7 +502,7 @@ TEST( Pose2, bearing ) // establish bearing is indeed 45 degrees even if rotated Rot2 actual34 = x3.bearing(l4, actualH1, actualH2); - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),actual34)); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual34)); // Check numerical derivatives expectedH1 = numericalDerivative21(bearing_proxy, x3, l4); @@ -518,7 +518,7 @@ Rot2 bearing_pose_proxy(const Pose2& pose, const Pose2& pt) { TEST( Pose2, bearing_pose ) { - Pose2 xl1(1, 0, M_PI_2), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI_2), xl4(1, 3, 0); + Pose2 xl1(1, 0, M_PI/2.0), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI/2.0), xl4(1, 3, 0); Matrix expectedH1, actualH1, expectedH2, actualH2; @@ -526,11 +526,11 @@ TEST( Pose2, bearing_pose ) EXPECT(assert_equal(Rot2(),x1.bearing(xl1))); // establish bearing is indeed 45 degrees - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),x1.bearing(xl2))); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),x1.bearing(xl2))); // establish bearing is indeed 45 degrees even if shifted Rot2 actual23 = x2.bearing(xl3, actualH1, actualH2); - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),actual23)); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual23)); // Check numerical derivatives expectedH1 = numericalDerivative21(bearing_pose_proxy, x2, xl3); @@ -540,7 +540,7 @@ TEST( Pose2, bearing_pose ) // establish bearing is indeed 45 degrees even if rotated Rot2 actual34 = x3.bearing(xl4, actualH1, actualH2); - EXPECT(assert_equal(Rot2::fromAngle(M_PI_4),actual34)); + EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual34)); // Check numerical derivatives expectedH1 = numericalDerivative21(bearing_pose_proxy, x3, xl4); @@ -561,11 +561,11 @@ TEST( Pose2, range ) EXPECT_DOUBLES_EQUAL(1,x1.range(l1),1e-9); // establish range is indeed 45 degrees - EXPECT_DOUBLES_EQUAL(sqrt(2),x1.range(l2),1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(l2),1e-9); // Another pair double actual23 = x2.range(l3, actualH1, actualH2); - EXPECT_DOUBLES_EQUAL(sqrt(2),actual23,1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9); // Check numerical derivatives expectedH1 = numericalDerivative21(range_proxy, x2, l3); @@ -590,7 +590,7 @@ LieVector range_pose_proxy(const Pose2& pose, const Pose2& point) { } TEST( Pose2, range_pose ) { - Pose2 xl1(1, 0, M_PI_2), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI_2), xl4(1, 3, 0); + Pose2 xl1(1, 0, M_PI/2.0), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI/2.0), xl4(1, 3, 0); Matrix expectedH1, actualH1, expectedH2, actualH2; @@ -598,11 +598,11 @@ TEST( Pose2, range_pose ) EXPECT_DOUBLES_EQUAL(1,x1.range(xl1),1e-9); // establish range is indeed 45 degrees - EXPECT_DOUBLES_EQUAL(sqrt(2),x1.range(xl2),1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(xl2),1e-9); // Another pair double actual23 = x2.range(xl3, actualH1, actualH2); - EXPECT_DOUBLES_EQUAL(sqrt(2),actual23,1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9); // Check numerical derivatives expectedH1 = numericalDerivative21(range_pose_proxy, x2, xl3); @@ -637,7 +637,7 @@ TEST(Pose2, align_1) { TEST(Pose2, align_2) { Point2 t(20,10); - Rot2 R = Rot2::fromAngle(M_PI_2); + Rot2 R = Rot2::fromAngle(M_PI/2.0); Pose2 expected(R, t); vector correspondences; diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index eb2d410f8..4ec1c6aee 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -535,7 +535,7 @@ TEST( Pose3, between ) /* ************************************************************************* */ // some shared test values - pulled from equivalent test in Pose2 Point3 l1(1, 0, 0), l2(1, 1, 0), l3(2, 2, 0), l4(1, 4,-4); -Pose3 x1, x2(Rot3::ypr(0.0, 0.0, 0.0), l2), x3(Rot3::ypr(M_PI_4, 0.0, 0.0), l2); +Pose3 x1, x2(Rot3::ypr(0.0, 0.0, 0.0), l2), x3(Rot3::ypr(M_PI/4.0, 0.0, 0.0), l2); Pose3 xl1(Rot3::ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)), xl2(Rot3::ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)), @@ -554,11 +554,11 @@ TEST( Pose3, range ) EXPECT_DOUBLES_EQUAL(1,x1.range(l1),1e-9); // establish range is indeed sqrt2 - EXPECT_DOUBLES_EQUAL(sqrt(2),x1.range(l2),1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(l2),1e-9); // Another pair double actual23 = x2.range(l3, actualH1, actualH2); - EXPECT_DOUBLES_EQUAL(sqrt(2),actual23,1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9); // Check numerical derivatives expectedH1 = numericalDerivative21(range_proxy, x2, l3); @@ -589,11 +589,11 @@ TEST( Pose3, range_pose ) EXPECT_DOUBLES_EQUAL(1,x1.range(xl1),1e-9); // establish range is indeed sqrt2 - EXPECT_DOUBLES_EQUAL(sqrt(2),x1.range(xl2),1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(xl2),1e-9); // Another pair double actual23 = x2.range(xl3, actualH1, actualH2); - EXPECT_DOUBLES_EQUAL(sqrt(2),actual23,1e-9); + EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9); // Check numerical derivatives expectedH1 = numericalDerivative21(range_pose_proxy, x2, xl3); @@ -619,7 +619,7 @@ TEST( Pose3, unicycle ) Vector x_step = delta(6,3,1.0); EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), l1), expmap_default(x1, x_step), tol)); EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), Point3(2,1,0)), expmap_default(x2, x_step), tol)); - EXPECT(assert_equal(Pose3(Rot3::ypr(M_PI_4,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2) * x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2.0) * x_step), tol)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot2.cpp b/gtsam/geometry/tests/testRot2.cpp index e23224898..acf385fab 100644 --- a/gtsam/geometry/tests/testRot2.cpp +++ b/gtsam/geometry/tests/testRot2.cpp @@ -43,7 +43,7 @@ TEST( Rot2, constructors_and_angle) TEST( Rot2, unit) { EXPECT(assert_equal(Point2(1.0, 0.0), Rot2::fromAngle(0).unit())); - EXPECT(assert_equal(Point2(0.0, 1.0), Rot2::fromAngle(M_PI_2).unit())); + EXPECT(assert_equal(Point2(0.0, 1.0), Rot2::fromAngle(M_PI/2.0).unit())); } /* ************************************************************************* */ @@ -94,9 +94,9 @@ TEST( Rot2, expmap) /* ************************************************************************* */ TEST(Rot2, logmap) { - Rot2 rot0(Rot2::fromAngle(M_PI_2)); + Rot2 rot0(Rot2::fromAngle(M_PI/2.0)); Rot2 rot(Rot2::fromAngle(M_PI)); - Vector expected = Vector_(1, M_PI_2); + Vector expected = Vector_(1, M_PI/2.0); Vector actual = rot0.localCoordinates(rot); CHECK(assert_equal(expected, actual)); } @@ -146,7 +146,7 @@ TEST( Rot2, relativeBearing ) // establish relativeBearing is indeed 45 degrees Rot2 actual2 = Rot2::relativeBearing(l2, actualH); - CHECK(assert_equal(Rot2::fromAngle(M_PI_4),actual2)); + CHECK(assert_equal(Rot2::fromAngle(M_PI/4.0),actual2)); // Check numerical derivative expectedH = numericalDerivative11(relativeBearing_, l2); diff --git a/gtsam/geometry/tests/testRot3M.cpp b/gtsam/geometry/tests/testRot3M.cpp index a5047f14b..449ed9cd7 100644 --- a/gtsam/geometry/tests/testRot3M.cpp +++ b/gtsam/geometry/tests/testRot3M.cpp @@ -31,9 +31,9 @@ using namespace std; using namespace gtsam; -Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); -Point3 P(0.2, 0.7, -2.0); -double error = 1e-9, epsilon = 0.001; +static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Point3 P(0.2, 0.7, -2.0); +static double error = 1e-9, epsilon = 0.001; static const Matrix I3 = eye(3); /* ************************************************************************* */ @@ -131,7 +131,7 @@ TEST( Rot3, rodriguez3) TEST( Rot3, rodriguez4) { Vector axis = Vector_(3,0.,0.,1.); // rotation around Z - double angle = M_PI_2; + double angle = M_PI/2.0; Rot3 actual = Rot3::rodriguez(axis, angle); double c=cos(angle),s=sin(angle); Rot3 expected(c,-s, 0, diff --git a/gtsam/geometry/tests/testRot3Q.cpp b/gtsam/geometry/tests/testRot3Q.cpp index 02056eb2d..7268eed55 100644 --- a/gtsam/geometry/tests/testRot3Q.cpp +++ b/gtsam/geometry/tests/testRot3Q.cpp @@ -27,9 +27,9 @@ using namespace gtsam; -Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); -Point3 P(0.2, 0.7, -2.0); -double error = 1e-9, epsilon = 0.001; +static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Point3 P(0.2, 0.7, -2.0); +static double error = 1e-9, epsilon = 0.001; /* ************************************************************************* */ TEST( Rot3, constructor) diff --git a/gtsam/geometry/tests/testSerializationGeometry.cpp b/gtsam/geometry/tests/testSerializationGeometry.cpp index c1fba6b2c..17a0b1eca 100644 --- a/gtsam/geometry/tests/testSerializationGeometry.cpp +++ b/gtsam/geometry/tests/testSerializationGeometry.cpp @@ -36,37 +36,20 @@ using namespace gtsam; using namespace gtsam::serializationTestHelpers; /* ************************************************************************* */ -// Export all classes derived from Value -BOOST_CLASS_EXPORT(gtsam::Cal3_S2) -BOOST_CLASS_EXPORT(gtsam::Cal3_S2Stereo) -BOOST_CLASS_EXPORT(gtsam::Cal3Bundler) -BOOST_CLASS_EXPORT(gtsam::CalibratedCamera) -BOOST_CLASS_EXPORT(gtsam::Point2) -BOOST_CLASS_EXPORT(gtsam::Point3) -BOOST_CLASS_EXPORT(gtsam::Pose2) -BOOST_CLASS_EXPORT(gtsam::Pose3) -BOOST_CLASS_EXPORT(gtsam::Rot2) -BOOST_CLASS_EXPORT(gtsam::Rot3) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) -BOOST_CLASS_EXPORT(gtsam::StereoPoint2) +static Point3 pt3(1.0, 2.0, 3.0); +static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); +static Pose3 pose3(rt3, pt3); -/* ************************************************************************* */ -Point3 pt3(1.0, 2.0, 3.0); -Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); -Pose3 pose3(rt3, pt3); +static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); +static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0); +static Cal3Bundler cal3(1.0, 2.0, 3.0); +static Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0); +static Cal3_S2Stereo::shared_ptr cal4ptr(new Cal3_S2Stereo(cal4)); +static CalibratedCamera cal5(Pose3(rt3, pt3)); -Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); -Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0); -Cal3Bundler cal3(1.0, 2.0, 3.0); -Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0); -Cal3_S2Stereo::shared_ptr cal4ptr(new Cal3_S2Stereo(cal4)); -CalibratedCamera cal5(Pose3(rt3, pt3)); - -PinholeCamera cam1(pose3, cal1); -StereoCamera cam2(pose3, cal4ptr); -StereoPoint2 spt(1.0, 2.0, 3.0); +static PinholeCamera cam1(pose3, cal1); +static StereoCamera cam2(pose3, cal4ptr); +static StereoPoint2 spt(1.0, 2.0, 3.0); /* ************************************************************************* */ TEST (Serialization, text_geometry) { diff --git a/gtsam/geometry/tests/testSimpleCamera.cpp b/gtsam/geometry/tests/testSimpleCamera.cpp index b3df0d8f8..5e8918215 100644 --- a/gtsam/geometry/tests/testSimpleCamera.cpp +++ b/gtsam/geometry/tests/testSimpleCamera.cpp @@ -26,21 +26,21 @@ using namespace std; using namespace gtsam; -const Cal3_S2 K(625, 625, 0, 0, 0); +static const Cal3_S2 K(625, 625, 0, 0, 0); -const Pose3 pose1(Matrix_(3,3, +static const Pose3 pose1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,0.5)); -const SimpleCamera camera(K, pose1); +static const SimpleCamera camera(pose1, K); -const Point3 point1(-0.08,-0.08, 0.0); -const Point3 point2(-0.08, 0.08, 0.0); -const Point3 point3( 0.08, 0.08, 0.0); -const Point3 point4( 0.08,-0.08, 0.0); +static const Point3 point1(-0.08,-0.08, 0.0); +static const Point3 point2(-0.08, 0.08, 0.0); +static const Point3 point3( 0.08, 0.08, 0.0); +static const Point3 point4( 0.08,-0.08, 0.0); /* ************************************************************************* */ TEST( SimpleCamera, constructor) @@ -53,8 +53,8 @@ TEST( SimpleCamera, constructor) TEST( SimpleCamera, level2) { // Create a level camera, looking in Y-direction - Pose2 pose2(0.4,0.3,M_PI_2); - SimpleCamera camera = SimpleCamera::level(K, pose2, 0.1); + Pose2 pose2(0.4,0.3,M_PI/2.0); + SimpleCamera camera = SimpleCamera::Level(K, pose2, 0.1); // expected Point3 x(1,0,0),y(0,0,-1),z(0,1,0); @@ -63,6 +63,26 @@ TEST( SimpleCamera, level2) CHECK(assert_equal( camera.pose(), expected)); } +/* ************************************************************************* */ +TEST( SimpleCamera, lookat) +{ + // Create a level camera, looking in Y-direction + Point3 C(10.0,0.0,0.0); + SimpleCamera camera = SimpleCamera::Lookat(C, Point3(), Point3(0.0,0.0,1.0)); + + // expected + Point3 xc(0,1,0),yc(0,0,-1),zc(-1,0,0); + Pose3 expected(Rot3(xc,yc,zc),C); + CHECK(assert_equal( camera.pose(), expected)); + + Point3 C2(30.0,0.0,10.0); + SimpleCamera camera2 = SimpleCamera::Lookat(C2, Point3(), Point3(0.0,0.0,1.0)); + + Matrix R = camera2.pose().rotation().matrix(); + Matrix I = trans(R)*R; + CHECK(assert_equal(I, eye(3))); +} + /* ************************************************************************* */ TEST( SimpleCamera, project) { @@ -86,7 +106,7 @@ TEST( SimpleCamera, backproject2) { Point3 origin; Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera looking down - SimpleCamera camera(K, Pose3(rot, origin)); + SimpleCamera camera(Pose3(rot, origin), K); Point3 actual = camera.backproject(Point2(), 1.); Point3 expected(0., 1., 0.); @@ -98,8 +118,8 @@ TEST( SimpleCamera, backproject2) } /* ************************************************************************* */ -Point2 project2(const Pose3& pose, const Point3& point) { - return SimpleCamera(K,pose).project(point); +static Point2 project2(const Pose3& pose, const Point3& point) { + return SimpleCamera(pose,K).project(point); } TEST( SimpleCamera, Dproject_point_pose) @@ -113,6 +133,26 @@ TEST( SimpleCamera, Dproject_point_pose) CHECK(assert_equal(Dpoint, numerical_point,1e-7)); } +/* ************************************************************************* */ +TEST( SimpleCamera, simpleCamera) +{ + Cal3_S2 K(468.2,427.2,91.2,300,200); + Rot3 R( + 0.41380,0.90915,0.04708, + -0.57338,0.22011,0.78917, + 0.70711,-0.35355,0.61237); + Point3 T(1000,2000,1500); + SimpleCamera expected(Pose3(R.inverse(),T),K); + // H&Z example, 2nd edition, page 163 + Matrix P = Matrix_(3,4, + 3.53553e2, 3.39645e2, 2.77744e2, -1.44946e6, + -1.03528e2, 2.33212e1, 4.59607e2, -6.32525e5, + 7.07107e-1, -3.53553e-1,6.12372e-1, -9.18559e2); + SimpleCamera actual = simpleCamera(P); + // Note precision of numbers given in book + CHECK(assert_equal(expected, actual,1e-1)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testStereoCamera.cpp b/gtsam/geometry/tests/testStereoCamera.cpp index 2446ff122..29a8344d4 100644 --- a/gtsam/geometry/tests/testStereoCamera.cpp +++ b/gtsam/geometry/tests/testStereoCamera.cpp @@ -74,21 +74,21 @@ TEST( StereoCamera, project) /* ************************************************************************* */ -Pose3 camera1(Matrix_(3,3, +static Pose3 camera1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,6.25)); -Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1500, 1500, 0, 320, 240, 0.5)); -StereoCamera stereoCam(Pose3(), K); +static Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1500, 1500, 0, 320, 240, 0.5)); +static StereoCamera stereoCam(Pose3(), K); // point X Y Z in meters -Point3 p(0, 0, 5); +static Point3 p(0, 0, 5); /* ************************************************************************* */ -StereoPoint2 project_(const StereoCamera& cam, const Point3& point) { return cam.project(point); } +static StereoPoint2 project_(const StereoCamera& cam, const Point3& point) { return cam.project(point); } TEST( StereoCamera, Dproject_stereo_pose) { Matrix expected = numericalDerivative21(project_,stereoCam, p); diff --git a/gtsam/geometry/tests/testTensors.cpp b/gtsam/geometry/tests/testTensors.cpp deleted file mode 100644 index 755b274a6..000000000 --- a/gtsam/geometry/tests/testTensors.cpp +++ /dev/null @@ -1,240 +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 testTensors.cpp - * @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf - * @date Feb 9, 2010 - * @author Frank Dellaert - */ - -#include -#include -#include // for operator += -using namespace boost::assign; - -#include - -#include -#include -#include - -using namespace std; -using namespace gtsam; -using namespace tensors; - -/* ************************************************************************* */ -// Indices - -Index<3, 'a'> a, _a; -Index<3, 'b'> b, _b; -Index<3, 'c'> c, _c; - -Index<4, 'A'> A; -Index<4, 'B'> B; - -/* ************************************************************************* */ -// Tensor1 -/* ************************************************************************* */ -TEST(Tensor1, Basics) -{ - // you can create 1-tensors corresponding to 2D homogeneous points - // using the function point2h in projectiveGeometry.* - Point2h p = point2h(1, 2, 3), q = point2h(2, 4, 6); - - // equality tests always take tensor expressions, not tensors themselves - // the difference is that a tensor expression has indices - CHECK(p(a)==p(a)) - CHECK(assert_equality(p(a),p(a))) - CHECK(assert_equality(p(a)*2,q(a))) - CHECK(assert_equivalent(p(a),q(a))) // projectively equivalent - - // and you can take a norm, typically for normalization to the sphere - DOUBLES_EQUAL(sqrt(14),norm(p(a)),1e-9) -} - -/* ************************************************************************* */ -TEST( Tensor1, Incidence2D) -{ - // 2D lines are created with line2h - Line2h l = line2h(-13, 5, 1); - Point2h p = point2h(1, 2, 3), q = point2h(2, 5, 1); - - // Incidence between a line and a point is checked with simple contraction - // It does not matter which index you use, but it has to be of dimension 3 - DOUBLES_EQUAL(l(a)*p(a),0,1e-9) - DOUBLES_EQUAL(l(b)*q(b),0,1e-9) - DOUBLES_EQUAL(p(a)*l(a),0,1e-9) - DOUBLES_EQUAL(q(a)*l(a),0,1e-9) -} - -/* ************************************************************************* */ -TEST( Tensor1, Incidence3D) -{ - // similar constructs exist for 3D points and planes - Plane3h pi = plane3h(0, 1, 0, -2); - Point3h P = point3h(0, 2, 0, 1), Q = point3h(1, 2, 0, 1); - - // Incidence is checked similarly - DOUBLES_EQUAL(pi(A)*P(A),0,1e-9) - DOUBLES_EQUAL(pi(A)*Q(A),0,1e-9) - DOUBLES_EQUAL(P(A)*pi(A),0,1e-9) - DOUBLES_EQUAL(Q(A)*pi(A),0,1e-9) -} - -/* ************************************************************************* */ -// Tensor2 -/* ************************************************************************* */ -TEST( Tensor2, Outer33) -{ - Line2h l1 = line2h(1, 2, 3), l2 = line2h(1, 3, 5); - - // We can also create tensors directly from data - double data[3][3] = { { 1, 2, 3 }, { 3, 6, 9 }, {5, 10, 15} }; - Tensor2<3, 3> expected(data); - // in this case expected(0) == {1,2,3} - Line2h l0 = expected(a,b)(0); - CHECK(l0(a) == l1(a)) - - // And we create rank 2 tensors from the outer product of two rank 1 tensors - CHECK(expected(a,b) == l1(a) * l2(b)) - - // swap just swaps how you access a tensor, but note the data is the same - CHECK(assert_equality(expected(a,b).swap(), l2(b) * l1(a))); -} - -/* ************************************************************************* */ -TEST( Tensor2, AnotherOuter33) -{ - // first cube point from testFundamental, projected in left and right -// Point2h p = point2h(0, -1, 2), q = point2h(-2, -1, 2); -// print(p(a)*q(b)); -// print(p(b)*q(a)); -// print(q(a)*p(b)); -// print(q(b)*p(a)); -} - -/* ************************************************************************* */ -TEST( Tensor2, Outer34) -{ - Line2h l = line2h(1, 2, 3); - Plane3h pi = plane3h(1, 3, 5, 7); - double - data[4][3] = { { 1, 2, 3 }, { 3, 6, 9 }, { 5, 10, 15 }, { 7, 14, 21 } }; - Tensor2<3, 4> expected(data); - CHECK(assert_equality(expected(a,B),l(a) * pi(B))) - CHECK(assert_equality(expected(a,B).swap(),pi(B) * l(a))) -} - -/* ************************************************************************* */ -TEST( Tensor2, SpecialContract) -{ - double data[3][3] = { { 1, 2, 3 }, { 2, 4, 6 }, { 3, 6, 9 } }; - Tensor2<3, 3> S(data), T(data); - //print(S(a, b) * T(a, c)); // contract a -> b,c - // S(a,0)*T(a,0) = [1 2 3] . [1 2 3] = 14 - // S(a,0)*T(a,2) = [1 2 3] . [3 6 9] = 3+12+27 = 42 - double data2[3][3] = { { 14, 28, 42 }, { 28, 56, 84 }, { 42, 84, 126 } }; - Tensor2<3, 3> expected(data2); - CHECK(assert_equality(expected(b,c), S(a, b) * T(a, c))); -} - -/* ************************************************************************* */ -TEST( Tensor2, ProjectiveCamera) -{ - Point2h p = point2h(1 + 2, 2, 5); - Point3h P = point3h(1, 2, 5, 1); - double data[4][3] = { { 1, 0, 0 }, { 0, 1, 0 }, { 0, 0, 1 }, { 2, 0, 0 } }; - ProjectiveCamera M(data); - CHECK(assert_equality(p(a),M(a,A)*P(A))) -} - -/* ************************************************************************* */ -namespace camera { - // to specify the tensor M(a,A), we need to give four 2D points - double data[4][3] = { { 1, 2, 3 }, { 4, 5, 6 }, { 7, 8, 9 }, { 10, 11, 12 } }; - ProjectiveCamera M(data); - Matrix matrix = Matrix_(4,3,1.,2.,3.,4.,5.,6.,7.,8.,9.,10.,11.,12.); - Vector vector = Vector_( 12,1.,2.,3.,4.,5.,6.,7.,8.,9.,10.,11.,12.); -} - -/* ************************************************************************* */ -TEST( Tensor2, reshape ) -{ - // it is annoying that a camera can only be reshaped to a 4*3 -// print(camera::M(a,A)); - Matrix actual = reshape(camera::M(a,A),4,3); - EQUALITY(camera::matrix,actual); -} - -/* ************************************************************************* */ -TEST( Tensor2, toVector ) -{ - // Vectors are created with the leftmost indices iterating the fastest - Vector actual = toVector(camera::M(a,A)); - CHECK(assert_equal(camera::vector,actual)); -} - -/* ************************************************************************* */ -TEST( Tensor2, reshape2 ) -{ - Tensor2<3,4> actual = reshape2<3,4>(camera::vector); - CHECK(assert_equality(camera::M(a,A),actual(a,A))); -} - -/* ************************************************************************* */ -TEST( Tensor2, reshape_33_to_9 ) -{ - double data[3][3] = { { 1, 2, 3 }, { 4, 5, 6 }, { 7, 8, 9 } }; - FundamentalMatrix F(data); - Matrix matrix = Matrix_(1,9,1.,2.,3.,4.,5.,6.,7.,8.,9.); - Matrix actual = reshape(F(a,b),1,9); - EQUALITY(matrix,actual); - Vector v = Vector_( 9,1.,2.,3.,4.,5.,6.,7.,8.,9.); - CHECK(assert_equality(F(a,b),reshape2<3, 3> (v)(a,b))); -} - -/* ************************************************************************* */ -// Tensor3 -/* ************************************************************************* */ -TEST( Tensor3, Join) -{ - Line2h l = line2h(-13, 5, 1); - Point2h p = point2h(1, 2, 3), q = point2h(2, 5, 1); - - // join points into line - Eta3 e; - CHECK(assert_equality(e(a, b, c) * p(a) * q(b), l(c))) -} - -/* ************************************************************************* */ -TEST( Tensor5, Outer32) -{ - double t[3][3][3] = { { { 0, 0, 3 }, { 0, 8, -125 }, { -3, 125, 1 } }, { { 0, - 0, 3 }, { 0, 8, -125 }, { -3, 125, 1 } }, { { 0, 0, 3 }, { 0, 8, -125 }, - { -3, 125, 1 } } }; - TrifocalTensor T(t); - - double data[3][3] = { { 0, 0, 3 }, { 0, 8, -125 }, { -3, 125, 1 } }; - FundamentalMatrix F(data); - - //Index<3, 'd'> d, _d; - //Index<3, 'e'> e, _e; - //print(T(_a,b,c)*F(_d,_e)); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ - diff --git a/gtsam/inference/BayesNet-inl.h b/gtsam/inference/BayesNet-inl.h index 7ff8fc076..c306cb39d 100644 --- a/gtsam/inference/BayesNet-inl.h +++ b/gtsam/inference/BayesNet-inl.h @@ -19,57 +19,80 @@ #include -#include -#include #include #include #include -#include -#include #include // for += -using namespace boost::assign; +using boost::assign::operator+=; -using namespace std; +#include +#include +#include namespace gtsam { /* ************************************************************************* */ template - void BayesNet::print(const string& s) const { - cout << s << ":\n"; - BOOST_REVERSE_FOREACH(sharedConditional conditional,conditionals_) - conditional->print(); - } - - /* ************************************************************************* */ - template - bool BayesNet::equals(const BayesNet& cbn, double tol) const { - if(size() != cbn.size()) return false; - return equal(conditionals_.begin(),conditionals_.end(),cbn.conditionals_.begin(),equals_star(tol)); - } - - /* ************************************************************************* */ - template - typename BayesNet::const_iterator BayesNet::find(Index key) const { - for(const_iterator it = begin(); it != end(); ++it) - if(std::find((*it)->beginFrontals(), (*it)->endFrontals(), key) != (*it)->endFrontals()) - return it; - return end(); + void BayesNet::print(const std::string& s, + const IndexFormatter& formatter) const { + std::cout << s; + BOOST_REVERSE_FOREACH(sharedConditional conditional, conditionals_) + conditional->print("Conditional", formatter); } /* ************************************************************************* */ template - typename BayesNet::iterator BayesNet::find(Index key) { - for(iterator it = begin(); it != end(); ++it) - if(std::find((*it)->beginFrontals(), (*it)->endFrontals(), key) != (*it)->endFrontals()) + void BayesNet::printStats(const std::string& s) const { + + const size_t n = conditionals_.size(); + size_t max_size = 0; + size_t total = 0; + BOOST_REVERSE_FOREACH(sharedConditional conditional, conditionals_) { + max_size = std::max(max_size, conditional->size()); + total += conditional->size(); + } + std::cout << s + << "maximum conditional size = " << max_size << std::endl + << "average conditional size = " << total / n << std::endl + << "density = " << 100.0 * total / (double) (n*(n+1)/2) << " %" << std::endl; + } + + /* ************************************************************************* */ + template + bool BayesNet::equals(const BayesNet& cbn, double tol) const { + if (size() != cbn.size()) + return false; + return std::equal(conditionals_.begin(), conditionals_.end(), + cbn.conditionals_.begin(), equals_star(tol)); + } + + /* ************************************************************************* */ + template + typename BayesNet::const_iterator BayesNet::find( + Index key) const { + for (const_iterator it = begin(); it != end(); ++it) + if (std::find((*it)->beginFrontals(), (*it)->endFrontals(), key) + != (*it)->endFrontals()) return it; return end(); } /* ************************************************************************* */ template - void BayesNet::permuteWithInverse(const Permutation& inversePermutation) { + typename BayesNet::iterator BayesNet::find( + Index key) { + for (iterator it = begin(); it != end(); ++it) + if (std::find((*it)->beginFrontals(), (*it)->endFrontals(), key) + != (*it)->endFrontals()) + return it; + return end(); + } + + /* ************************************************************************* */ + template + void BayesNet::permuteWithInverse( + const Permutation& inversePermutation) { BOOST_FOREACH(sharedConditional conditional, conditionals_) { conditional->permuteWithInverse(inversePermutation); } @@ -77,52 +100,54 @@ namespace gtsam { /* ************************************************************************* */ template - bool BayesNet::permuteSeparatorWithInverse(const Permutation& inversePermutation) { + bool BayesNet::permuteSeparatorWithInverse( + const Permutation& inversePermutation) { bool separatorChanged = false; BOOST_FOREACH(sharedConditional conditional, conditionals_) { - if(conditional->permuteSeparatorWithInverse(inversePermutation)) + if (conditional->permuteSeparatorWithInverse(inversePermutation)) separatorChanged = true; } return separatorChanged; } - /* ************************************************************************* */ - template - void BayesNet::push_back(const BayesNet bn) { - BOOST_FOREACH(sharedConditional conditional,bn.conditionals_) - push_back(conditional); - } - - /* ************************************************************************* */ - template - void BayesNet::push_front(const BayesNet bn) { - BOOST_FOREACH(sharedConditional conditional,bn.conditionals_) - push_front(conditional); - } + /* ************************************************************************* */ + template + void BayesNet::push_back(const BayesNet bn) { + BOOST_FOREACH(sharedConditional conditional,bn.conditionals_) + push_back(conditional); + } /* ************************************************************************* */ template - void BayesNet::popLeaf(iterator conditional) { + void BayesNet::push_front(const BayesNet bn) { + BOOST_FOREACH(sharedConditional conditional,bn.conditionals_) + push_front(conditional); + } + + /* ************************************************************************* */ + template + void BayesNet::popLeaf(iterator conditional) { #ifndef NDEBUG BOOST_FOREACH(typename CONDITIONAL::shared_ptr checkConditional, conditionals_) { BOOST_FOREACH(Index key, (*conditional)->frontals()) { if(std::find(checkConditional->beginParents(), checkConditional->endParents(), key) != checkConditional->endParents()) - throw std::invalid_argument( - "Debug mode exception: in BayesNet::popLeaf, the requested conditional is not a leaf."); + throw std::invalid_argument( + "Debug mode exception: in BayesNet::popLeaf, the requested conditional is not a leaf."); } } #endif conditionals_.erase(conditional); - } + } - /* ************************************************************************* */ - template - FastList BayesNet::ordering() const { - FastList ord; - BOOST_FOREACH(sharedConditional conditional,conditionals_) - ord.insert(ord.begin(), conditional->beginFrontals(), conditional->endFrontals()); - return ord; - } + /* ************************************************************************* */ + template + FastList BayesNet::ordering() const { + FastList ord; + BOOST_FOREACH(sharedConditional conditional,conditionals_) + ord.insert(ord.begin(), conditional->beginFrontals(), + conditional->endFrontals()); + return ord; + } // /* ************************************************************************* */ // template @@ -139,21 +164,22 @@ namespace gtsam { // of.close(); // } // - /* ************************************************************************* */ + /* ************************************************************************* */ - template - typename BayesNet::sharedConditional - BayesNet::operator[](Index key) const { - BOOST_FOREACH(typename CONDITIONAL::shared_ptr conditional, conditionals_) { - typename CONDITIONAL::const_iterator it = std::find(conditional->beginFrontals(), conditional->endFrontals(), key); - if (it!=conditional->endFrontals()) { + template + typename BayesNet::sharedConditional BayesNet::operator[]( + Index key) const { + BOOST_FOREACH(typename CONDITIONAL::shared_ptr conditional, conditionals_) { + typename CONDITIONAL::const_iterator it = std::find( + conditional->beginFrontals(), conditional->endFrontals(), key); + if (it != conditional->endFrontals()) { return conditional; } - } - throw(invalid_argument((boost::format( - "BayesNet::operator['%1%']: not found") % key).str())); - } + } + throw(std::invalid_argument( + (boost::format("BayesNet::operator['%1%']: not found") % key).str())); + } - /* ************************************************************************* */ +/* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/inference/BayesNet.h b/gtsam/inference/BayesNet.h index 0f78a15e3..67d59c48d 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 */ @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -48,6 +49,7 @@ public: typedef typename boost::shared_ptr > shared_ptr; /** We store shared pointers to Conditional densities */ + typedef typename CONDITIONAL::KeyType KeyType; typedef typename boost::shared_ptr sharedConditional; typedef typename boost::shared_ptr const_sharedConditional; typedef typename std::list Conditionals; @@ -88,7 +90,11 @@ public: /// @{ /** print */ - void print(const std::string& s = "") const; + void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; + + /** print statistics */ + void printStats(const std::string& s = "") const; /** check equality */ bool equals(const BayesNet& other, double tol = 1e-9) const; diff --git a/gtsam/inference/BayesTree-inl.h b/gtsam/inference/BayesTree-inl.h index 95b070739..3d5276be8 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 @@ -26,22 +26,17 @@ #include #include +#include #include #include #include #include // for operator += +using boost::assign::operator+=; #include -#include -#include -#include -using namespace boost::assign; -namespace lam = boost::lambda; namespace gtsam { - using namespace std; - /* ************************************************************************* */ template typename BayesTree::CliqueData @@ -51,9 +46,9 @@ namespace gtsam { return data; } + /* ************************************************************************* */ template - void BayesTree::getCliqueData(CliqueData& data, - BayesTree::sharedClique clique) const { + void BayesTree::getCliqueData(CliqueData& data, sharedClique clique) const { data.conditionalSizes.push_back((*clique)->nrFrontals()); data.separatorSizes.push_back((*clique)->nrParents()); BOOST_FOREACH(sharedClique c, clique->children_) { @@ -63,29 +58,28 @@ namespace gtsam { /* ************************************************************************* */ template - void BayesTree::saveGraph(const std::string &s) const { - if (!root_.get()) throw invalid_argument("the root of bayes tree has not been initialized!"); - ofstream of(s.c_str()); + void BayesTree::saveGraph(const std::string &s, const IndexFormatter& indexFormatter) const { + if (!root_.get()) throw std::invalid_argument("the root of Bayes tree has not been initialized!"); + std::ofstream of(s.c_str()); of<< "digraph G{\n"; - saveGraph(of, root_); + saveGraph(of, root_, indexFormatter); of<<"}"; of.close(); } + /* ************************************************************************* */ template - void BayesTree::saveGraph(ostream &s, - BayesTree::sharedClique clique, - int parentnum) const { + void BayesTree::saveGraph(std::ostream &s, sharedClique clique, const IndexFormatter& indexFormatter, int parentnum) const { static int num = 0; bool first = true; std::stringstream out; out << num; - string parent = out.str(); + std::string parent = out.str(); parent += "[label=\""; - BOOST_FOREACH(boost::shared_ptr c, clique->conditionals_) { + BOOST_FOREACH(Index index, clique->conditional_->frontals()) { if(!first) parent += ","; first = false; - parent += (string(c->key())).c_str(); + parent += indexFormatter(index); } if( clique != root_){ @@ -94,9 +88,9 @@ namespace gtsam { } first = true; - BOOST_FOREACH(Index sep, clique->separator_) { + BOOST_FOREACH(Index sep, clique->conditional_->parents()) { if(!first) parent += ","; first = false; - parent += (boost::format("%1%")%sep).str(); + parent += indexFormatter(sep); } parent += "\"];\n"; s << parent; @@ -104,11 +98,22 @@ namespace gtsam { BOOST_FOREACH(sharedClique c, clique->children_) { num++; - saveGraph(s, c, parentnum); + saveGraph(s, c, indexFormatter, parentnum); } } + /* ************************************************************************* */ + template + void BayesTree::CliqueStats::print(const std::string& s) const { + std::cout << s + <<"avg Conditional Size: " << avgConditionalSize << std::endl + << "max Conditional Size: " << maxConditionalSize << std::endl + << "avg Separator Size: " << avgSeparatorSize << std::endl + << "max Separator Size: " << maxSeparatorSize << std::endl; + } + + /* ************************************************************************* */ template typename BayesTree::CliqueStats BayesTree::CliqueData::getStats() const { @@ -137,10 +142,10 @@ namespace gtsam { /* ************************************************************************* */ template - void BayesTree::Cliques::print(const std::string& s) const { - cout << s << ":\n"; + void BayesTree::Cliques::print(const std::string& s, const IndexFormatter& indexFormatter) const { + std::cout << s << ":\n"; BOOST_FOREACH(sharedClique clique, *this) - clique->printTree(); + clique->printTree("", indexFormatter); } /* ************************************************************************* */ @@ -162,8 +167,8 @@ namespace gtsam { template void BayesTree::addClique(const sharedClique& clique, const sharedClique& parent_clique) { nodes_.resize(std::max((*clique)->lastFrontalKey()+1, nodes_.size())); - BOOST_FOREACH(Index key, (*clique)->frontals()) - nodes_[key] = clique; + BOOST_FOREACH(Index j, (*clique)->frontals()) + nodes_[j] = clique; if (parent_clique != NULL) { clique->parent_ = parent_clique; parent_clique->children_.push_back(clique); @@ -177,11 +182,11 @@ namespace gtsam { /* ************************************************************************* */ template typename BayesTree::sharedClique BayesTree::addClique( - const sharedConditional& conditional, list& child_cliques) { + const sharedConditional& conditional, std::list& child_cliques) { sharedClique new_clique(new Clique(conditional)); nodes_.resize(std::max(conditional->lastFrontalKey()+1, nodes_.size())); - BOOST_FOREACH(Index key, conditional->frontals()) - nodes_[key] = new_clique; + BOOST_FOREACH(Index j, conditional->frontals()) + nodes_[j] = new_clique; new_clique->children_ = child_cliques; BOOST_FOREACH(sharedClique& child, child_cliques) child->parent_ = new_clique; @@ -205,13 +210,13 @@ namespace gtsam { #endif if(debug) conditional->print("Adding conditional "); if(debug) clique->print("To clique "); - Index key = conditional->lastFrontalKey(); - bayesTree.nodes_.resize(std::max(key+1, bayesTree.nodes_.size())); - bayesTree.nodes_[key] = clique; - FastVector newKeys((*clique)->size() + 1); - newKeys[0] = key; - std::copy((*clique)->begin(), (*clique)->end(), newKeys.begin()+1); - clique->conditional_ = CONDITIONAL::FromKeys(newKeys, (*clique)->nrFrontals() + 1); + Index j = conditional->lastFrontalKey(); + bayesTree.nodes_.resize(std::max(j+1, bayesTree.nodes_.size())); + bayesTree.nodes_[j] = clique; + FastVector newIndices((*clique)->size() + 1); + newIndices[0] = j; + std::copy((*clique)->begin(), (*clique)->end(), newIndices.begin()+1); + clique->conditional_ = CONDITIONAL::FromKeys(newIndices, (*clique)->nrFrontals() + 1); if(debug) clique->print("Expanded clique is "); clique->assertInvariants(); } @@ -229,8 +234,8 @@ namespace gtsam { BOOST_FOREACH(sharedClique child, clique->children_) child->parent_ = typename Clique::weak_ptr(); - BOOST_FOREACH(Index key, (*clique->conditional())) { - nodes_[key].reset(); + BOOST_FOREACH(Index j, (*clique->conditional())) { + nodes_[j].reset(); } } @@ -292,10 +297,10 @@ namespace gtsam { template BayesTree::BayesTree(const BayesNet& bayesNet, std::list > subtrees) { if (bayesNet.size() == 0) - throw invalid_argument("BayesTree::insert: empty bayes net!"); + throw std::invalid_argument("BayesTree::insert: empty bayes net!"); // get the roots of child subtrees and merge their nodes_ - list childRoots; + std::list childRoots; typedef BayesTree Tree; BOOST_FOREACH(const Tree& subtree, subtrees) { nodes_.insert(subtree.nodes_.begin(), subtree.nodes_.end()); @@ -331,14 +336,14 @@ namespace gtsam { /* ************************************************************************* */ template - void BayesTree::print(const string& s) const { + void BayesTree::print(const std::string& s, const IndexFormatter& indexFormatter) const { if (root_.use_count() == 0) { - printf("WARNING: BayesTree.print encountered a forest...\n"); + std::cout << "WARNING: BayesTree.print encountered a forest..." << std::endl; return; } - cout << s << ": clique size == " << size() << ", node size == " << nodes_.size() << endl; + std::cout << s << ": clique size == " << size() << ", node size == " << nodes_.size() << std::endl; if (nodes_.empty()) return; - root_->printTree(""); + root_->printTree("", indexFormatter); } /* ************************************************************************* */ @@ -374,14 +379,14 @@ namespace gtsam { { static const bool debug = false; - // get key and parents + // get indices and parents const typename CONDITIONAL::Parents& parents = conditional->parents(); if(debug) conditional->print("Adding conditional "); // if no parents, start a new root clique if (parents.empty()) { - if(debug) cout << "No parents so making root" << endl; + if(debug) std::cout << "No parents so making root" << std::endl; bayesTree.root_ = bayesTree.addClique(conditional); return; } @@ -389,15 +394,15 @@ namespace gtsam { // otherwise, find the parent clique by using the index data structure // to find the lowest-ordered parent Index parentRepresentative = bayesTree.findParentClique(parents); - if(debug) cout << "First-eliminated parent is " << parentRepresentative << ", have " << bayesTree.nodes_.size() << " nodes." << endl; + if(debug) std::cout << "First-eliminated parent is " << parentRepresentative << ", have " << bayesTree.nodes_.size() << " nodes." << std::endl; sharedClique parent_clique = bayesTree[parentRepresentative]; if(debug) parent_clique->print("Parent clique is "); // if the parents and parent clique have the same size, add to parent clique if ((*parent_clique)->size() == size_t(parents.size())) { - if(debug) cout << "Adding to parent clique" << endl; + if(debug) std::cout << "Adding to parent clique" << std::endl; #ifndef NDEBUG - // Debug check that the parent keys of the new conditional match the keys + // Debug check that the parent indices of the new conditional match the indices // currently in the clique. // list::const_iterator parent = parents.begin(); // typename Clique::const_iterator cond = parent_clique->begin(); @@ -410,7 +415,7 @@ namespace gtsam { #endif addToCliqueFront(bayesTree, conditional, parent_clique); } else { - if(debug) cout << "Starting new clique" << endl; + if(debug) std::cout << "Starting new clique" << std::endl; // otherwise, start a new clique and add it to the tree bayesTree.addClique(conditional,parent_clique); } @@ -420,10 +425,10 @@ namespace gtsam { //TODO: remove this function after removing TSAM.cpp template typename BayesTree::sharedClique BayesTree::insert( - const sharedConditional& clique, list& children, bool isRootClique) { + const sharedConditional& clique, std::list& children, bool isRootClique) { if (clique->nrFrontals() == 0) - throw invalid_argument("BayesTree::insert: empty clique!"); + throw std::invalid_argument("BayesTree::insert: empty clique!"); // create a new clique and add all the conditionals to the clique sharedClique new_clique = addClique(clique, children); @@ -436,7 +441,7 @@ namespace gtsam { template void BayesTree::fillNodesIndex(const sharedClique& subtree) { // Add each frontal variable of this root node - BOOST_FOREACH(const Index& key, subtree->conditional()->frontals()) { nodes_[key] = subtree; } + BOOST_FOREACH(const Index& j, subtree->conditional()->frontals()) { nodes_[j] = subtree; } // Fill index for each child typedef typename BayesTree::sharedClique sharedClique; BOOST_FOREACH(const sharedClique& child, subtree->children_) { @@ -475,26 +480,26 @@ namespace gtsam { /* ************************************************************************* */ template typename CONDITIONAL::FactorType::shared_ptr BayesTree::marginalFactor( - Index key, Eliminate function) const { + Index j, Eliminate function) const { - // get clique containing key - sharedClique clique = (*this)[key]; + // get clique containing Index j + sharedClique clique = (*this)[j]; // calculate or retrieve its marginal FactorGraph cliqueMarginal = clique->marginal(root_,function); return GenericSequentialSolver(cliqueMarginal).marginalFactor( - key, function); + j, function); } /* ************************************************************************* */ template typename BayesNet::shared_ptr BayesTree::marginalBayesNet( - Index key, Eliminate function) const { + Index j, Eliminate function) const { // calculate marginal as a factor graph FactorGraph fg; - fg.push_back(this->marginalFactor(key,function)); + fg.push_back(this->marginalFactor(j,function)); // eliminate factor graph marginal to a Bayes net return GenericSequentialSolver(fg).eliminate(function); @@ -505,28 +510,28 @@ namespace gtsam { /* ************************************************************************* */ template typename FactorGraph::shared_ptr - BayesTree::joint(Index key1, Index key2, Eliminate function) const { + BayesTree::joint(Index j1, Index j2, Eliminate function) const { // get clique C1 and C2 - sharedClique C1 = (*this)[key1], C2 = (*this)[key2]; + sharedClique C1 = (*this)[j1], C2 = (*this)[j2]; // calculate joint FactorGraph p_C1C2(C1->joint(C2, root_, function)); // eliminate remaining factor graph to get requested joint - vector key12(2); key12[0] = key1; key12[1] = key2; + std::vector j12(2); j12[0] = j1; j12[1] = j2; GenericSequentialSolver solver(p_C1C2); - return solver.jointFactorGraph(key12,function); + return solver.jointFactorGraph(j12,function); } /* ************************************************************************* */ template typename BayesNet::shared_ptr BayesTree::jointBayesNet( - Index key1, Index key2, Eliminate function) const { + Index j1, Index j2, Eliminate function) const { // eliminate factor graph marginal to a Bayes net return GenericSequentialSolver ( - *this->joint(key1, key2, function)).eliminate(function); + *this->joint(j1, j2, function)).eliminate(function); } /* ************************************************************************* */ @@ -564,22 +569,27 @@ namespace gtsam { /* ************************************************************************* */ template - template - void BayesTree::removeTop(const CONTAINER& keys, + template + void BayesTree::removeTop(const CONTAINER& keys, BayesNet& bn, typename BayesTree::Cliques& orphans) { // process each key of the new factor - BOOST_FOREACH(const Index& key, keys) { + BOOST_FOREACH(const Index& j, keys) { // get the clique - if(key < nodes_.size()) { - const sharedClique& clique(nodes_[key]); + if(j < nodes_.size()) { + const sharedClique& clique(nodes_[j]); if(clique) { // remove path from clique to root this->removePath(clique, bn, orphans); } } } + + // Delete cachedShorcuts for each orphan subtree + //TODO: Consider Improving + BOOST_FOREACH(sharedClique& orphan, orphans) + orphan->deleteCachedShorcuts(); } /* ************************************************************************* */ diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index a9ed53ee9..1e87ca141 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 */ @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -46,7 +47,7 @@ namespace gtsam { * @tparam CLIQUE The type of the clique data structure, defaults to BayesTreeClique, normally do not change this * as it is only used when developing special versions of BayesTree, e.g. for ISAM2. * - * \ingroup Multifrontal + * \addtogroup Multifrontal * \nosubgrouping */ template > @@ -69,7 +70,8 @@ namespace gtsam { // A convenience class for a list of shared cliques struct Cliques : public std::list { - void print(const std::string& s = "Cliques") const; + void print(const std::string& s = "Cliques", + const IndexFormatter& indexFormatter = DefaultIndexFormatter) const; bool equals(const Cliques& other, double tol = 1e-9) const; }; @@ -79,6 +81,7 @@ namespace gtsam { std::size_t maxConditionalSize; double avgSeparatorSize; std::size_t maxSeparatorSize; + void print(const std::string& s = "") const ; }; /** store all the sizes */ @@ -88,55 +91,18 @@ namespace gtsam { CliqueStats getStats() const; }; - /** Map from keys to Clique */ + /** Map from indices to Clique */ typedef std::deque Nodes; protected: - /** Map from keys to Clique */ - Nodes nodes_; + /** Map from indices to Clique */ + Nodes nodes_; - /** private helper method for saving the Tree to a text file in GraphViz format */ - void saveGraph(std::ostream &s, sharedClique clique, - int parentnum = 0) const; + /** Root clique */ + sharedClique root_; - /** Gather data on a single clique */ - void getCliqueData(CliqueData& stats, sharedClique clique) const; - - /** Root clique */ - sharedClique root_; - - /** remove a clique: warning, can result in a forest */ - void removeClique(sharedClique clique); - - /** add a clique (top down) */ - sharedClique addClique(const sharedConditional& conditional, const sharedClique& parent_clique = sharedClique()); - - /** add a clique (top down) */ - void addClique(const sharedClique& clique, const sharedClique& parent_clique = sharedClique()); - - /** add a clique (bottom up) */ - sharedClique addClique(const sharedConditional& conditional, std::list& child_cliques); - - /** - * Add a conditional to the front of a clique, i.e. a conditional whose - * parents are already in the clique or its separators. This function does - * not check for this condition, it just updates the data structures. - */ - static void addToCliqueFront(BayesTree& bayesTree, - const sharedConditional& conditional, const sharedClique& clique); - - /** Fill the nodes index for a subtree */ - void fillNodesIndex(const sharedClique& subtree); - - /** Helper function to build a non-symbolic tree (e.g. Gaussian) using a - * symbolic tree, used in the BT(BN) constructor. - */ - void recursiveTreeBuild(const boost::shared_ptr >& symbolic, - const std::vector >& conditionals, - const typename BayesTree::sharedClique& parent); - - public: + public: /// @name Standard Constructors /// @{ @@ -174,14 +140,13 @@ namespace gtsam { bool equals(const BayesTree& other, double tol = 1e-9) const; /** print */ - void print(const std::string& s = "") const; + void print(const std::string& s = "", + const IndexFormatter& indexFormatter = DefaultIndexFormatter ) const; /// @} /// @name Standard Interface /// @{ - public: - /** * Find parent clique of a conditional. It will look at all parents and * return the one with the lowest index in the ordering. @@ -198,41 +163,41 @@ namespace gtsam { } /** return nodes */ - Nodes nodes() const { return nodes_; } + const Nodes& nodes() const { return nodes_; } /** return root clique */ const sharedClique& root() const { return root_; } - /** find the clique to which key belongs */ - sharedClique operator[](Index key) const { - return nodes_.at(key); + /** find the clique that contains the variable with Index j */ + sharedClique operator[](Index j) const { + return nodes_.at(j); } /** Gather data on all cliques */ CliqueData getCliqueData() const; /** return marginal on any variable */ - typename FactorType::shared_ptr marginalFactor(Index key, Eliminate function) const; + typename FactorType::shared_ptr marginalFactor(Index j, Eliminate function) const; /** * return marginal on any variable, as a Bayes Net * NOTE: this function calls marginal, and then eliminates it into a Bayes Net * This is more expensive than the above function */ - typename BayesNet::shared_ptr marginalBayesNet(Index key, Eliminate function) const; + typename BayesNet::shared_ptr marginalBayesNet(Index j, Eliminate function) const; /** return joint on two variables */ - typename FactorGraph::shared_ptr joint(Index key1, Index key2, Eliminate function) const; + typename FactorGraph::shared_ptr joint(Index j1, Index j2, Eliminate function) const; /** return joint on two variables as a BayesNet */ - typename BayesNet::shared_ptr jointBayesNet(Index key1, Index key2, Eliminate function) const; + typename BayesNet::shared_ptr jointBayesNet(Index j1, Index j2, Eliminate function) const; /** * Read only with side effects */ /** saves the Tree to a text file in GraphViz format */ - void saveGraph(const std::string& s) const; + void saveGraph(const std::string& s, const IndexFormatter& indexFormatter = DefaultIndexFormatter ) const; /// @} /// @name Advanced Interface @@ -241,6 +206,9 @@ namespace gtsam { /** Access the root clique (non-const version) */ sharedClique& root() { return root_; } + /** Access the nodes (non-cost version) */ + Nodes& nodes() { return nodes_; } + /** Remove all nodes */ void clear(); @@ -251,11 +219,11 @@ namespace gtsam { void removePath(sharedClique clique, BayesNet& bn, Cliques& orphans); /** - * Given a list of keys, turn "contaminated" part of the tree back into a factor graph. + * Given a list of indices, turn "contaminated" part of the tree back into a factor graph. * Factors and orphans are added to the in/out arguments. */ template - void removeTop(const CONTAINER& keys, BayesNet& bn, Cliques& orphans); + void removeTop(const CONTAINER& indices, BayesNet& bn, Cliques& orphans); /** * Hang a new subtree off of the existing tree. This finds the appropriate @@ -280,6 +248,46 @@ namespace gtsam { sharedClique insert(const sharedConditional& clique, std::list& children, bool isRootClique = false); + + protected: + + /** private helper method for saving the Tree to a text file in GraphViz format */ + void saveGraph(std::ostream &s, sharedClique clique, const IndexFormatter& indexFormatter, + int parentnum = 0) const; + + /** Gather data on a single clique */ + void getCliqueData(CliqueData& stats, sharedClique clique) const; + + /** remove a clique: warning, can result in a forest */ + void removeClique(sharedClique clique); + + /** add a clique (top down) */ + sharedClique addClique(const sharedConditional& conditional, const sharedClique& parent_clique = sharedClique()); + + /** add a clique (top down) */ + void addClique(const sharedClique& clique, const sharedClique& parent_clique = sharedClique()); + + /** add a clique (bottom up) */ + sharedClique addClique(const sharedConditional& conditional, std::list& child_cliques); + + /** + * Add a conditional to the front of a clique, i.e. a conditional whose + * parents are already in the clique or its separators. This function does + * not check for this condition, it just updates the data structures. + */ + static void addToCliqueFront(BayesTree& bayesTree, + const sharedConditional& conditional, const sharedClique& clique); + + /** Fill the nodes index for a subtree */ + void fillNodesIndex(const sharedClique& subtree); + + /** Helper function to build a non-symbolic tree (e.g. Gaussian) using a + * symbolic tree, used in the BT(BN) constructor. + */ + void recursiveTreeBuild(const boost::shared_ptr >& symbolic, + const std::vector >& conditionals, + const typename BayesTree::sharedClique& parent); + private: /** deep copy to another tree */ diff --git a/gtsam/inference/BayesTreeCliqueBase-inl.h b/gtsam/inference/BayesTreeCliqueBase-inl.h index dfc8864f7..344f845ac 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 */ @@ -50,8 +50,8 @@ namespace gtsam { /* ************************************************************************* */ template - void BayesTreeCliqueBase::print(const std::string& s) const { - conditional_->print(s); + void BayesTreeCliqueBase::print(const std::string& s, const IndexFormatter& indexFormatter) const { + conditional_->print(s, indexFormatter); } /* ************************************************************************* */ @@ -65,10 +65,10 @@ namespace gtsam { /* ************************************************************************* */ template - void BayesTreeCliqueBase::printTree(const std::string& indent) const { - asDerived(this)->print(indent); + void BayesTreeCliqueBase::printTree(const std::string& indent, const IndexFormatter& indexFormatter) const { + asDerived(this)->print(indent, indexFormatter); BOOST_FOREACH(const derived_ptr& child, children_) - child->printTree(indent+" "); + child->printTree(indent+" ", indexFormatter); } /* ************************************************************************* */ @@ -108,98 +108,106 @@ namespace gtsam { // P(Sp|R) as \int P(Fp|Sp) P(Sp|R), where Fp are the frontal nodes in p /* ************************************************************************* */ template - BayesNet BayesTreeCliqueBase::shortcut(derived_ptr R, Eliminate function) { + BayesNet BayesTreeCliqueBase::shortcut( + derived_ptr R, Eliminate function) const{ - static const bool debug = false; + static const bool debug = false; - // A first base case is when this clique or its parent is the root, - // in which case we return an empty Bayes net. + BayesNet p_S_R; //shortcut P(S|R) This is empty now - derived_ptr parent(parent_.lock()); + //Check if the ShortCut already exists + if(!cachedShortcut_){ - if (R.get()==this || parent==R) { - BayesNet empty; - return empty; - } + // A first base case is when this clique or its parent is the root, + // in which case we return an empty Bayes net. - // The root conditional - FactorGraph p_R(BayesNet(R->conditional())); + derived_ptr parent(parent_.lock()); + if (R.get() != this && parent != R) { - // The parent clique has a ConditionalType for each frontal node in Fp - // so we can obtain P(Fp|Sp) in factor graph form - FactorGraph p_Fp_Sp(BayesNet(parent->conditional())); + // The root conditional + FactorGraph p_R(BayesNet(R->conditional())); - // If not the base case, obtain the parent shortcut P(Sp|R) as factors - FactorGraph p_Sp_R(parent->shortcut(R, function)); + // The parent clique has a ConditionalType for each frontal node in Fp + // so we can obtain P(Fp|Sp) in factor graph form + FactorGraph p_Fp_Sp(BayesNet(parent->conditional())); - // now combine P(Cp|R) = P(Fp|Sp) * P(Sp|R) - FactorGraph p_Cp_R; - p_Cp_R.push_back(p_R); - p_Cp_R.push_back(p_Fp_Sp); - p_Cp_R.push_back(p_Sp_R); + // If not the base case, obtain the parent shortcut P(Sp|R) as factors + FactorGraph p_Sp_R(parent->shortcut(R, function)); - // Eliminate into a Bayes net with ordering designed to integrate out - // any variables not in *our* separator. Variables to integrate out must be - // eliminated first hence the desired ordering is [Cp\S S]. - // However, an added wrinkle is that Cp might overlap with the root. - // Keys corresponding to the root should not be added to the ordering at all. + // now combine P(Cp|R) = P(Fp|Sp) * P(Sp|R) + FactorGraph p_Cp_R; + p_Cp_R.push_back(p_R); + p_Cp_R.push_back(p_Fp_Sp); + p_Cp_R.push_back(p_Sp_R); - if(debug) { - p_R.print("p_R: "); - p_Fp_Sp.print("p_Fp_Sp: "); - p_Sp_R.print("p_Sp_R: "); - } + // Eliminate into a Bayes net with ordering designed to integrate out + // any variables not in *our* separator. Variables to integrate out must be + // eliminated first hence the desired ordering is [Cp\S S]. + // However, an added wrinkle is that Cp might overlap with the root. + // Keys corresponding to the root should not be added to the ordering at all. - // We want to factor into a conditional of the clique variables given the - // root and the marginal on the root, integrating out all other variables. - // The integrands include any parents of this clique and the variables of - // the parent clique. - FastSet variablesAtBack; - FastSet separator; - size_t uniqueRootVariables = 0; - BOOST_FOREACH(const Index separatorIndex, this->conditional()->parents()) { - variablesAtBack.insert(separatorIndex); - separator.insert(separatorIndex); - if(debug) std::cout << "At back (this): " << separatorIndex << std::endl; - } - BOOST_FOREACH(const Index key, R->conditional()->keys()) { - if(variablesAtBack.insert(key).second) - ++ uniqueRootVariables; - if(debug) std::cout << "At back (root): " << key << std::endl; - } + if(debug) { + p_R.print("p_R: "); + p_Fp_Sp.print("p_Fp_Sp: "); + p_Sp_R.print("p_Sp_R: "); + } - Permutation toBack = Permutation::PushToBack( - std::vector(variablesAtBack.begin(), variablesAtBack.end()), - R->conditional()->lastFrontalKey() + 1); - Permutation::shared_ptr toBackInverse(toBack.inverse()); - BOOST_FOREACH(const typename FactorType::shared_ptr& factor, p_Cp_R) { - factor->permuteWithInverse(*toBackInverse); } - typename BayesNet::shared_ptr eliminated(EliminationTree< - FactorType>::Create(p_Cp_R)->eliminate(function)); + // We want to factor into a conditional of the clique variables given the + // root and the marginal on the root, integrating out all other variables. + // The integrands include any parents of this clique and the variables of + // the parent clique. + FastSet variablesAtBack; + FastSet separator; + size_t uniqueRootVariables = 0; + BOOST_FOREACH(const Index separatorIndex, this->conditional()->parents()) { + variablesAtBack.insert(separatorIndex); + separator.insert(separatorIndex); + if(debug) std::cout << "At back (this): " << separatorIndex << std::endl; + } + BOOST_FOREACH(const Index key, R->conditional()->keys()) { + if(variablesAtBack.insert(key).second) + ++ uniqueRootVariables; + if(debug) std::cout << "At back (root): " << key << std::endl; + } - // Take only the conditionals for p(S|R). We check for each variable being - // in the separator set because if some separator variables overlap with - // root variables, we cannot rely on the number of root variables, and also - // want to include those variables in the conditional. - BayesNet p_S_R; - BOOST_REVERSE_FOREACH(typename ConditionalType::shared_ptr conditional, *eliminated) { - assert(conditional->nrFrontals() == 1); - if(separator.find(toBack[conditional->firstFrontalKey()]) != separator.end()) { - if(debug) - conditional->print("Taking C|R conditional: "); - p_S_R.push_front(conditional); - } - if(p_S_R.size() == separator.size()) - break; - } + Permutation toBack = Permutation::PushToBack( + std::vector(variablesAtBack.begin(), variablesAtBack.end()), + R->conditional()->lastFrontalKey() + 1); + Permutation::shared_ptr toBackInverse(toBack.inverse()); + BOOST_FOREACH(const typename FactorType::shared_ptr& factor, p_Cp_R) { + factor->permuteWithInverse(*toBackInverse); } + typename BayesNet::shared_ptr eliminated(EliminationTree< + FactorType>::Create(p_Cp_R)->eliminate(function)); - // Undo the permutation - if(debug) toBack.print("toBack: "); - p_S_R.permuteWithInverse(toBack); + // Take only the conditionals for p(S|R). We check for each variable being + // in the separator set because if some separator variables overlap with + // root variables, we cannot rely on the number of root variables, and also + // want to include those variables in the conditional. + BOOST_REVERSE_FOREACH(typename ConditionalType::shared_ptr conditional, *eliminated) { + assert(conditional->nrFrontals() == 1); + if(separator.find(toBack[conditional->firstFrontalKey()]) != separator.end()) { + if(debug) + conditional->print("Taking C|R conditional: "); + p_S_R.push_front(conditional); + } + if(p_S_R.size() == separator.size()) + break; + } - // return the parent shortcut P(Sp|R) - assertInvariants(); - return p_S_R; + // Undo the permutation + if(debug) toBack.print("toBack: "); + p_S_R.permuteWithInverse(toBack); + } + + cachedShortcut_ = p_S_R; + } + else + p_S_R = *cachedShortcut_; // return the cached version + + assertInvariants(); + + // return the shortcut P(S|R) + return p_S_R; } /* ************************************************************************* */ @@ -210,7 +218,7 @@ namespace gtsam { /* ************************************************************************* */ template FactorGraph::FactorType> BayesTreeCliqueBase::marginal( - derived_ptr R, Eliminate function) { + derived_ptr R, Eliminate function) const{ // If we are the root, just return this root // NOTE: immediately cast to a factor graph BayesNet bn(R->conditional()); @@ -231,7 +239,7 @@ namespace gtsam { /* ************************************************************************* */ template FactorGraph::FactorType> BayesTreeCliqueBase::joint( - derived_ptr C2, derived_ptr R, Eliminate function) { + derived_ptr C2, derived_ptr R, Eliminate function) const { // For now, assume neither is the root // Combine P(F1|S1), P(S1|R), P(F2|S2), P(S2|R), and P(R) @@ -257,4 +265,22 @@ namespace gtsam { return *solver.jointFactorGraph(keys12vector, function); } + /* ************************************************************************* */ + template + void BayesTreeCliqueBase::deleteCachedShorcuts() { + + // When a shortcut is requested, all of the shortcuts between it and the + // root are also generated. So, if this clique's cached shortcut is set, + // recursively call over all child cliques. Otherwise, it is unnecessary. + if(cachedShortcut_) { + BOOST_FOREACH(derived_ptr& child, children_) { + child->deleteCachedShorcuts(); + } + + //Delete CachedShortcut for this clique + this->resetCachedShortcut(); + } + + } + } diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index 194b616b7..a2fb8feef 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 */ @@ -75,6 +75,9 @@ namespace gtsam { /// @} + /// This stores the Cached Shortcut value + mutable boost::optional > cachedShortcut_; + public: sharedConditional conditional_; derived_weak_ptr parent_; @@ -90,10 +93,10 @@ namespace gtsam { } /** print this node */ - void print(const std::string& s = "") const; + void print(const std::string& s = "", const IndexFormatter& indexFormatter = DefaultIndexFormatter ) const; /** print this node and entire subtree below it */ - void printTree(const std::string& indent="") const; + void printTree(const std::string& indent="", const IndexFormatter& indexFormatter = DefaultIndexFormatter ) const; /// @} /// @name Standard Interface @@ -111,9 +114,12 @@ namespace gtsam { /** The arrow operator accesses the conditional */ const ConditionalType* operator->() const { return conditional_.get(); } - ///TODO: comment + /** return the const reference of children */ const std::list& children() const { return children_; } + /** return a shared_ptr to the parent clique */ + derived_ptr parent() const { return parent_.lock(); } + /// @} /// @name Advanced Interface /// @{ @@ -121,7 +127,7 @@ namespace gtsam { /** The arrow operator accesses the conditional */ ConditionalType* operator->() { return conditional_.get(); } - /** return the const reference of children */ + /** return the reference of children non-const version*/ std::list& children() { return children_; } /** Construct shared_ptr from a conditional, leaving parent and child pointers uninitialized */ @@ -130,7 +136,7 @@ namespace gtsam { /** Construct shared_ptr from a FactorGraph::EliminationResult. In this class * the conditional part is kept and the factor part is ignored, but in derived clique * types, such as ISAM2Clique, the factor part is kept as a cached factor. - * @param An elimination result, which is a pair + * @param result An elimination result, which is a pair */ static derived_ptr Create(const std::pair >& result) { return boost::make_shared(result); } @@ -150,14 +156,22 @@ namespace gtsam { bool permuteSeparatorWithInverse(const Permutation& inversePermutation); /** return the conditional P(S|Root) on the separator given the root */ - // TODO: create a cached version - BayesNet shortcut(derived_ptr root, Eliminate function); + BayesNet shortcut(derived_ptr root, Eliminate function) const; /** return the marginal P(C) of the clique */ - FactorGraph marginal(derived_ptr root, Eliminate function); + FactorGraph marginal(derived_ptr root, Eliminate function) const; /** return the joint P(C1,C2), where C1==this. TODO: not a method? */ - FactorGraph joint(derived_ptr C2, derived_ptr root, Eliminate function); + FactorGraph joint(derived_ptr C2, derived_ptr root, Eliminate function) const; + + /** + * This deletes the cached shortcuts of all cliques (subtree) below this clique. + * This is performed when the bayes tree is modified. + */ + void deleteCachedShorcuts(); + + /** return cached shortcut of the clique */ + const boost::optional > cachedShortcut() const { return cachedShortcut_; } friend class BayesTree; @@ -166,6 +180,9 @@ namespace gtsam { ///TODO: comment void assertInvariants() const; + /// Reset the computed shortcut of this clique. Used by friend BayesTree + void resetCachedShortcut() { cachedShortcut_ = boost::none; } + private: /** Cliques cannot be copied except by the clone() method, which does not diff --git a/gtsam/inference/ClusterTree-inl.h b/gtsam/inference/ClusterTree-inl.h index 0f1f823af..3b8deb316 100644 --- a/gtsam/inference/ClusterTree-inl.h +++ b/gtsam/inference/ClusterTree-inl.h @@ -26,8 +26,6 @@ namespace gtsam { - using namespace std; - /* ************************************************************************* * * Cluster * ************************************************************************* */ @@ -58,13 +56,13 @@ namespace gtsam { /* ************************************************************************* */ template - bool ClusterTree::Cluster::equals(const ClusterTree::Cluster& other) const { + bool ClusterTree::Cluster::equals(const Cluster& other) const { if (frontal != other.frontal) return false; if (separator != other.separator) return false; if (children_.size() != other.children_.size()) return false; - typename list::const_iterator it1 = children_.begin(); - typename list::const_iterator it2 = other.children_.begin(); + typename std::list::const_iterator it1 = children_.begin(); + typename std::list::const_iterator it2 = other.children_.begin(); for (; it1 != children_.end(); it1++, it2++) if (!(*it1)->equals(**it2)) return false; @@ -73,31 +71,34 @@ namespace gtsam { /* ************************************************************************* */ template - void ClusterTree::Cluster::print(const string& indent) const { - cout << indent; + void ClusterTree::Cluster::print(const std::string& indent, + const IndexFormatter& formatter) const { + std::cout << indent; BOOST_FOREACH(const Index key, frontal) - cout << key << " "; - cout << ": "; + std::cout << formatter(key) << " "; + std::cout << ": "; BOOST_FOREACH(const Index key, separator) - cout << key << " "; - cout << endl; + std::cout << key << " "; + std::cout << std::endl; } /* ************************************************************************* */ template - void ClusterTree::Cluster::printTree(const string& indent) const { - print(indent); + void ClusterTree::Cluster::printTree(const std::string& indent, + const IndexFormatter& formatter) const { + print(indent, formatter); BOOST_FOREACH(const shared_ptr& child, children_) - child->printTree(indent + " "); + child->printTree(indent + " ", formatter); } /* ************************************************************************* * * ClusterTree * ************************************************************************* */ template - void ClusterTree::print(const string& str) const { - cout << str << endl; - if (root_) root_->printTree(""); + void ClusterTree::print(const std::string& str, + const IndexFormatter& formatter) const { + std::cout << str << std::endl; + if (root_) root_->printTree("", formatter); } /* ************************************************************************* */ diff --git a/gtsam/inference/ClusterTree.h b/gtsam/inference/ClusterTree.h index c5301f030..276ef374d 100644 --- a/gtsam/inference/ClusterTree.h +++ b/gtsam/inference/ClusterTree.h @@ -25,6 +25,7 @@ #include #include +#include #include @@ -32,12 +33,15 @@ namespace gtsam { /** * A cluster-tree is associated with a factor graph and is defined as in Koller-Friedman: - * each node k represents a subset C_k \sub X, and the tree is family preserving, in that - * each factor f_i is associated with a single cluster and scope(f_i) \sub C_k. + * each node k represents a subset \f$ C_k \sub X \f$, and the tree is family preserving, in that + * each factor \f$ f_i \f$ is associated with a single cluster and \f$ scope(f_i) \sub C_k \f$. * \nosubgrouping */ template class ClusterTree { + public: + // Access to factor types + typedef typename FG::KeyType KeyType; protected: @@ -74,10 +78,10 @@ namespace gtsam { Cluster(FRONTALIT firstFrontal, FRONTALIT lastFrontal, SEPARATORIT firstSeparator, SEPARATORIT lastSeparator); /// print - void print(const std::string& indent) const; + void print(const std::string& indent, const IndexFormatter& formatter = DefaultIndexFormatter) const; /// print the enire tree - void printTree(const std::string& indent) const; + void printTree(const std::string& indent, const IndexFormatter& formatter = DefaultIndexFormatter) const; /// check equality bool equals(const Cluster& other) const; @@ -123,7 +127,7 @@ namespace gtsam { /// @{ /// print the object - void print(const std::string& str="") const; + void print(const std::string& str="", const IndexFormatter& formatter = DefaultIndexFormatter) const; /** check equality */ bool equals(const ClusterTree& other, double tol = 1e-9) const; diff --git a/gtsam/inference/Conditional.h b/gtsam/inference/Conditional.h index 0b5fca660..8363c1800 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -23,6 +23,7 @@ #include // for noncopyable #include #include +#include #include #include @@ -98,13 +99,16 @@ public: Conditional(KeyType key) : FactorType(key), nrFrontals_(1) { assertInvariants(); } /** Single parent */ - Conditional(KeyType key, KeyType parent) : FactorType(key, parent), nrFrontals_(1) { assertInvariants(); } + Conditional(KeyType key, KeyType parent) + : FactorType(key, parent), nrFrontals_(1) { assertInvariants(); } /** Two parents */ - Conditional(KeyType key, KeyType parent1, KeyType parent2) : FactorType(key, parent1, parent2), nrFrontals_(1) { assertInvariants(); } + Conditional(KeyType key, KeyType parent1, KeyType parent2) + : FactorType(key, parent1, parent2), nrFrontals_(1) { assertInvariants(); } /** Three parents */ - Conditional(KeyType key, KeyType parent1, KeyType parent2, KeyType parent3) : FactorType(key, parent1, parent2, parent3), nrFrontals_(1) { assertInvariants(); } + Conditional(KeyType key, KeyType parent1, KeyType parent2, KeyType parent3) + : FactorType(key, parent1, parent2, parent3), nrFrontals_(1) { assertInvariants(); } /// @} /// @name Advanced Constructors @@ -126,8 +130,8 @@ public: /// @name Testable /// @{ - /** print */ - void print(const std::string& s = "Conditional") const; + /** print with optional formatter */ + void print(const std::string& s = "Conditional", const IndexFormatter& formatter = DefaultIndexFormatter) const; /** check equality */ template @@ -196,12 +200,12 @@ private: /* ************************************************************************* */ template -void Conditional::print(const std::string& s) const { +void Conditional::print(const std::string& s, const IndexFormatter& formatter) const { std::cout << s << " P("; - BOOST_FOREACH(KeyType key, frontals()) std::cout << " " << key; - if (nrParents()>0) std::cout << " |"; - BOOST_FOREACH(KeyType parent, parents()) std::cout << " " << parent; - std::cout << ")" << std::endl; + BOOST_FOREACH(KeyType key, frontals()) std::cout << " " << formatter(key); + if (nrParents()>0) std::cout << " |"; + BOOST_FOREACH(KeyType parent, parents()) std::cout << " " << formatter(parent); + std::cout << ")" << std::endl; } } // gtsam diff --git a/gtsam/inference/EliminationTree-inl.h b/gtsam/inference/EliminationTree-inl.h index 488911127..2e977aa4b 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 */ @@ -24,14 +24,12 @@ #include #include -#include #include + #include #include #include -using namespace std; - namespace gtsam { /* ************************************************************************* */ @@ -41,7 +39,7 @@ typename EliminationTree::sharedFactor EliminationTree::eliminat static const bool debug = false; - if(debug) cout << "ETree: eliminating " << this->key_ << endl; + if(debug) std::cout << "ETree: eliminating " << this->key_ << std::endl; // Create the list of factors to be eliminated, initially empty, and reserve space FactorGraph factors; @@ -60,7 +58,7 @@ typename EliminationTree::sharedFactor EliminationTree::eliminat eliminated(function(factors, 1)); conditionals[this->key_] = eliminated.first; - if(debug) cout << "Eliminated " << this->key_ << " to get:\n"; + if(debug) std::cout << "Eliminated " << this->key_ << " to get:\n"; if(debug) eliminated.first->print("Conditional: "); if(debug) eliminated.second->print("Factor: "); @@ -69,17 +67,17 @@ typename EliminationTree::sharedFactor EliminationTree::eliminat /* ************************************************************************* */ template -vector EliminationTree::ComputeParents(const VariableIndex& structure) { +std::vector EliminationTree::ComputeParents(const VariableIndex& structure) { // Number of factors and variables const size_t m = structure.nFactors(); const size_t n = structure.size(); - static const Index none = numeric_limits::max(); + static const Index none = std::numeric_limits::max(); // Allocate result parent vector and vector of last factor columns - vector parents(n, none); - vector prevCol(m, none); + std::vector parents(n, none); + std::vector prevCol(m, none); // for column j \in 1 to n do for (Index j = 0; j < n; j++) { @@ -111,17 +109,17 @@ typename EliminationTree::shared_ptr EliminationTree::Create( tic(1, "ET ComputeParents"); // Compute the tree structure - vector parents(ComputeParents(structure)); + std::vector parents(ComputeParents(structure)); toc(1, "ET ComputeParents"); // Number of variables const size_t n = structure.size(); - static const Index none = numeric_limits::max(); + static const Index none = std::numeric_limits::max(); // Create tree structure tic(2, "assemble tree"); - vector trees(n); + std::vector trees(n); for (Index k = 1; k <= n; k++) { Index j = n - k; // Start at the last variable and loop down to 0 trees[j].reset(new EliminationTree(j)); // Create a new node on this variable @@ -134,7 +132,7 @@ typename EliminationTree::shared_ptr EliminationTree::Create( // Hang factors in right places tic(3, "hang factors"); - BOOST_FOREACH(const typename DERIVEDFACTOR::shared_ptr& derivedFactor, factorGraph) { + BOOST_FOREACH(const typename boost::shared_ptr& derivedFactor, factorGraph) { // Here we upwards-cast to the factor type of this EliminationTree. This // allows performing symbolic elimination on, for example, GaussianFactors. if(derivedFactor) { @@ -168,12 +166,13 @@ EliminationTree::Create(const FactorGraph& factorGraph) { /* ************************************************************************* */ template -void EliminationTree::print(const std::string& name) const { - cout << name << " (" << key_ << ")" << endl; +void EliminationTree::print(const std::string& name, + const IndexFormatter& formatter) const { + std::cout << name << " (" << formatter(key_) << ")" << std::endl; BOOST_FOREACH(const sharedFactor& factor, factors_) { - factor->print(name + " "); } + factor->print(name + " ", formatter); } BOOST_FOREACH(const shared_ptr& child, subTrees_) { - child->print(name + " "); } + child->print(name + " ", formatter); } } /* ************************************************************************* */ diff --git a/gtsam/inference/EliminationTree.h b/gtsam/inference/EliminationTree.h index 0b01f0586..f2b0c1eaf 100644 --- a/gtsam/inference/EliminationTree.h +++ b/gtsam/inference/EliminationTree.h @@ -52,8 +52,10 @@ public: typedef EliminationTree This; ///< This class typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class - typedef typename FACTOR::shared_ptr sharedFactor; ///< Shared pointer to a factor + typedef typename boost::shared_ptr sharedFactor; ///< Shared pointer to a factor typedef gtsam::BayesNet BayesNet; ///< The BayesNet corresponding to FACTOR + typedef FACTOR Factor; + typedef typename FACTOR::KeyType KeyType; /** Typedef for an eliminate subroutine */ typedef typename FactorGraph::Eliminate Eliminate; @@ -67,43 +69,15 @@ private: typedef FastList SubTrees; typedef std::vector Conditionals; - Index key_; ///< index associated with root + Index key_; ///< index associated with root // FIXME: doesn't this require that "Index" is the type of keys in the generic factor? Factors factors_; ///< factors associated with root SubTrees subTrees_; ///< sub-trees +public: + /// @name Standard Constructors /// @{ - /** default constructor, private, as you should use Create below */ - EliminationTree(Index key = 0) : key_(key) {} - - /// @} - /// @name Advanced Interface - /// @{ - - /** - * Static internal function to build a vector of parent pointers using the - * algorithm of Gilbert et al., 2001, BIT. - */ - static std::vector ComputeParents(const VariableIndex& structure); - - /** add a factor, for Create use only */ - void add(const sharedFactor& factor) { factors_.push_back(factor); } - - /** add a subtree, for Create use only */ - void add(const shared_ptr& child) { subTrees_.push_back(child); } - - /** - * Recursive routine that eliminates the factors arranged in an elimination tree - * @param Conditionals is a vector of shared pointers that will be modified in place - */ - sharedFactor eliminate_(Eliminate function, Conditionals& conditionals) const; - - /// Allow access to constructor and add methods for testing purposes - friend class ::EliminationTreeTester; - -public: - /** * Named constructor to build the elimination tree of a factor graph using * pre-computed column structure. @@ -141,13 +115,40 @@ public: /// @{ /** Print the tree to cout */ - void print(const std::string& name = "EliminationTree: ") const; + void print(const std::string& name = "EliminationTree: ", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /** Test whether the tree is equal to another */ bool equals(const EliminationTree& other, double tol = 1e-9) const; /// @} +private: + + /** default constructor, private, as you should use Create below */ + EliminationTree(Index key = 0) : key_(key) {} + + /** + * Static internal function to build a vector of parent pointers using the + * algorithm of Gilbert et al., 2001, BIT. + */ + static std::vector ComputeParents(const VariableIndex& structure); + + /** add a factor, for Create use only */ + void add(const sharedFactor& factor) { factors_.push_back(factor); } + + /** add a subtree, for Create use only */ + void add(const shared_ptr& child) { subTrees_.push_back(child); } + + /** + * Recursive routine that eliminates the factors arranged in an elimination tree + * @param Conditionals is a vector of shared pointers that will be modified in place + */ + sharedFactor eliminate_(Eliminate function, Conditionals& conditionals) const; + + /// Allow access to constructor and add methods for testing purposes + friend class ::EliminationTreeTester; + }; @@ -157,7 +158,7 @@ public: * disconnected graphs, a workaround is to create zero-information factors to * bridge the disconnects. To do this, create any factor type (e.g. * BetweenFactor or RangeFactor) with the noise model - * \ref sharedPrecision(dim, 0.0), where \c dim is the appropriate + * sharedPrecision(dim, 0.0), where \c dim is the appropriate * dimensionality for that factor. */ struct DisconnectedGraphException : public std::exception { @@ -166,7 +167,12 @@ struct DisconnectedGraphException : public std::exception { /// Returns the string "Attempting to eliminate a disconnected graph - this is not currently possible in gtsam." virtual const char* what() const throw() { - return "Attempting to eliminate a disconnected graph - this is not currently possible in gtsam."; } + return + "Attempting to eliminate a disconnected graph - this is not currently possible in\n" + "GTSAM. You may add \"empty\" BetweenFactor's to join disconnected graphs, these\n" + "will affect the symbolic structure and solving complexity of the graph but not\n" + "the solution. To do this, create BetweenFactor's with zero-precision noise\n" + "models, i.e. noiseModel::Isotropic::Precision(n, 0.0);\n"; } }; } diff --git a/gtsam/inference/Factor-inl.h b/gtsam/inference/Factor-inl.h index d9fb1e0de..b2099aa3e 100644 --- a/gtsam/inference/Factor-inl.h +++ b/gtsam/inference/Factor-inl.h @@ -56,12 +56,19 @@ namespace gtsam { /* ************************************************************************* */ template - void Factor::print(const std::string& s) const { - std::cout << s << " "; - BOOST_FOREACH(KEY key, keys_) std::cout << " " << key; - std::cout << std::endl; + void Factor::print(const std::string& s, + const IndexFormatter& formatter) const { + printKeys(s,formatter); } + /* ************************************************************************* */ + template + void Factor::printKeys(const std::string& s, const IndexFormatter& formatter) const { + std::cout << s << " "; + BOOST_FOREACH(KEY key, keys_) std::cout << " " << formatter(key); + std::cout << std::endl; + } + /* ************************************************************************* */ template bool Factor::equals(const This& other, double tol) const { diff --git a/gtsam/inference/Factor.h b/gtsam/inference/Factor.h index 87c1f3860..4c31664d7 100644 --- a/gtsam/inference/Factor.h +++ b/gtsam/inference/Factor.h @@ -25,6 +25,9 @@ #include #include #include +#include +#include +#include #include namespace gtsam { @@ -36,7 +39,7 @@ template class Conditional; * which will be the type used to label variables. Key types currently in use * in gtsam are Index with symbolic (IndexFactor, SymbolicFactorGraph) and * Gaussian factors (GaussianFactor, JacobianFactor, HessianFactor, GaussianFactorGraph), - * and Symbol with nonlinear factors (NonlinearFactor, NonlinearFactorGraph). + * and Key with nonlinear factors (NonlinearFactor, NonlinearFactorGraph). * though currently only IndexFactor and IndexConditional derive from this * class, using Index keys. This class does not store any data other than its * keys. Derived classes store data such as matrices and probability tables. @@ -45,7 +48,7 @@ template class Conditional; * typedefs to refer to the associated conditional and shared_ptr types of the * derived class. See IndexFactor, JacobianFactor, etc. for examples. * - * This class is \bold{not} virtual for performance reasons - derived symbolic classes, + * This class is \b not virtual for performance reasons - derived symbolic classes, * IndexFactor and IndexConditional, need to be created and destroyed quickly * during symbolic elimination. GaussianFactor and NonlinearFactor are virtual. * \nosubgrouping @@ -78,15 +81,6 @@ protected: /// The keys involved in this factor std::vector keys_; - friend class JacobianFactor; - friend class HessianFactor; - -protected: - - /// Internal consistency check that is run frequently when in debug mode. - /// If NDEBUG is defined, this is empty and optimized out. - void assertInvariants() const; - public: /// @name Standard Constructors @@ -190,7 +184,12 @@ public: /// @{ /// print - void print(const std::string& s = "Factor") const; + void print(const std::string& s = "Factor", + const IndexFormatter& formatter = DefaultIndexFormatter) const; + + /// print only keys + void printKeys(const std::string& s = "Factor", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /// check equality bool equals(const This& other, double tol = 1e-9) const; @@ -208,9 +207,15 @@ public: iterator begin() { return keys_.begin(); } ///TODO: comment iterator end() { return keys_.end(); } ///TODO: comment +protected: + friend class JacobianFactor; + friend class HessianFactor; + + /// Internal consistency check that is run frequently when in debug mode. + /// If NDEBUG is defined, this is empty and optimized out. + void assertInvariants() const; private: - /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/inference/FactorGraph-inl.h b/gtsam/inference/FactorGraph-inl.h index ea92cb791..04490dbc6 100644 --- a/gtsam/inference/FactorGraph-inl.h +++ b/gtsam/inference/FactorGraph-inl.h @@ -23,38 +23,46 @@ #pragma once #include +#include #include #include #include -#include #include #include #include #include #include -#include - -using namespace std; namespace gtsam { + /* ************************************************************************* */ + template + template + FactorGraph::FactorGraph(const BayesNet& bayesNet) { + factors_.reserve(bayesNet.size()); + BOOST_FOREACH(const typename CONDITIONAL::shared_ptr& cond, bayesNet) { + this->push_back(cond->toFactor()); + } + } + /* ************************************************************************* */ template - void FactorGraph::print(const string& s) const { - cout << s << endl; - cout << "size: " << size() << endl; + void FactorGraph::print(const std::string& s, + const IndexFormatter& formatter) const { + std::cout << s << std::endl; + std::cout << "size: " << size() << std::endl; for (size_t i = 0; i < factors_.size(); i++) { - stringstream ss; + std::stringstream ss; ss << "factor " << i << ": "; - if (factors_[i] != NULL) factors_[i]->print(ss.str()); + if (factors_[i] != NULL) factors_[i]->print(ss.str(), formatter); } } /* ************************************************************************* */ template - bool FactorGraph::equals(const FactorGraph& fg, double tol) const { + bool FactorGraph::equals(const This& fg, double tol) const { /** check whether the two factor graphs have the same number of factors_ */ if (factors_.size() != fg.size()) return false; @@ -78,10 +86,61 @@ namespace gtsam { return size_; } + /* ************************************************************************* */ + template + std::pair::sharedConditional, FactorGraph > + FactorGraph::eliminateFrontals(size_t nFrontals, const Eliminate& eliminate) const + { + // Build variable index + VariableIndex variableIndex(*this); + + // Find first variable + Index firstIndex = 0; + while(firstIndex < variableIndex.size() && variableIndex[firstIndex].empty()) + ++ firstIndex; + + // Check that number of variables is in bounds + if(firstIndex + nFrontals > variableIndex.size()) + throw std::invalid_argument("Requested to eliminate more frontal variables than exist in the factor graph."); + + // Get set of involved factors + FastSet involvedFactorIs; + for(Index j = firstIndex; j < firstIndex + nFrontals; ++j) { + BOOST_FOREACH(size_t i, variableIndex[j]) { + involvedFactorIs.insert(i); + } + } + + // Separate factors into involved and remaining + FactorGraph involvedFactors; + FactorGraph remainingFactors; + FastSet::const_iterator involvedFactorIsIt = involvedFactorIs.begin(); + for(size_t i = 0; i < this->size(); ++i) { + if(involvedFactorIsIt != involvedFactorIs.end() && *involvedFactorIsIt == i) { + // If the current factor is involved, add it to involved and increment involved iterator + involvedFactors.push_back((*this)[i]); + ++ involvedFactorIsIt; + } else { + // If not involved, add to remaining + remainingFactors.push_back((*this)[i]); + } + } + + // Do dense elimination on the involved factors + typename FactorGraph::EliminationResult eliminationResult = + eliminate(involvedFactors, nFrontals); + + // Add the remaining factor back into the factor graph + remainingFactors.push_back(eliminationResult.second); + + // Return the eliminated factor and remaining factor graph + return std::make_pair(eliminationResult.first, remainingFactors); + } + /* ************************************************************************* */ template void FactorGraph::replace(size_t index, sharedFactor factor) { - if (index >= factors_.size()) throw invalid_argument(boost::str( + if (index >= factors_.size()) throw std::invalid_argument(boost::str( boost::format("Factor graph does not contain a factor with index %d.") % index)); // Replace the factor @@ -101,30 +160,34 @@ namespace gtsam { } /* ************************************************************************* */ - template - typename DERIVED::shared_ptr Combine(const FactorGraph& factors, - const FastMap >& variableSlots) { - typedef const pair > KeySlotPair; - return typename DERIVED::shared_ptr(new DERIVED( - boost::make_transform_iterator(variableSlots.begin(), boost::bind(&KeySlotPair::first, _1)), - boost::make_transform_iterator(variableSlots.end(), boost::bind(&KeySlotPair::first, _1)))); + template + typename DERIVEDFACTOR::shared_ptr Combine(const FactorGraph& factors, + const FastMap >& variableSlots) { + + typedef const std::pair > KeySlotPair; + // Local functional for getting keys out of key-value pairs + struct Local { static KEY FirstOf(const KeySlotPair& pr) { return pr.first; } }; + + return typename DERIVEDFACTOR::shared_ptr(new DERIVEDFACTOR( + boost::make_transform_iterator(variableSlots.begin(), &Local::FirstOf), + boost::make_transform_iterator(variableSlots.end(), &Local::FirstOf))); } /* ************************************************************************* */ + // Recursive function to add factors in cliques to vector of factors_io template void _FactorGraph_BayesTree_adder( - vector::sharedFactor>& factors, + std::vector >& factors_io, const typename BayesTree::sharedClique& clique) { if(clique) { // Add factor from this clique - factors.push_back((*clique)->toFactor()); + factors_io.push_back((*clique)->toFactor()); // Traverse children typedef typename BayesTree::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& child, clique->children()) { - _FactorGraph_BayesTree_adder(factors, child); - } + BOOST_FOREACH(const sharedClique& child, clique->children()) + _FactorGraph_BayesTree_adder(factors_io, child); } } diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 33cdd02a1..ed3e7d952 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -21,14 +21,13 @@ #pragma once -#include -#include -#include - #include #include #include +#include +#include + namespace gtsam { // Forward declarations @@ -41,30 +40,28 @@ template class BayesTree; */ template class FactorGraph { + public: - typedef FACTOR FactorType; - typedef typename FACTOR::KeyType KeyType; - typedef boost::shared_ptr > shared_ptr; - typedef typename boost::shared_ptr sharedFactor; + + typedef FACTOR FactorType; ///< factor type + typedef typename FACTOR::KeyType KeyType; ///< type of Keys we use to index factors with + typedef boost::shared_ptr sharedFactor; ///< Shared pointer to a factor + typedef boost::shared_ptr sharedConditional; ///< Shared pointer to a conditional + + typedef FactorGraph This; ///< Typedef for this class + typedef boost::shared_ptr shared_ptr; ///< Shared pointer for this class typedef typename std::vector::iterator iterator; typedef typename std::vector::const_iterator const_iterator; - /** typedef for elimination result */ - typedef std::pair< - boost::shared_ptr, - typename FACTOR::shared_ptr> EliminationResult; + /** typedef for elimination result */ + typedef std::pair EliminationResult; - /** typedef for an eliminate subroutine */ - typedef boost::function&, size_t)> Eliminate; - - /** Typedef for the result of factorization */ - typedef std::pair< - boost::shared_ptr, - FactorGraph > FactorizationResult; + /** typedef for an eliminate subroutine */ + typedef boost::function Eliminate; protected: - /** concept check */ + /** concept check, makes sure FACTOR defines print and equals */ GTSAM_CONCEPT_TESTABLE_TYPE(FACTOR) /** Collection of factors */ @@ -82,7 +79,11 @@ template class BayesTree; /// @name Advanced Constructors /// @{ - /** convert from Bayes net */ + /** + * @brief Constructor from a Bayes net + * @param bayesNet the Bayes net to convert, type CONDITIONAL must yield compatible factor + * @return a factor graph with all the conditionals, as factors + */ template FactorGraph(const BayesNet& bayesNet); @@ -113,7 +114,7 @@ template class BayesTree; } /** push back many factors */ - void push_back(const FactorGraph& factors) { + void push_back(const This& factors) { factors_.insert(end(), factors.begin(), factors.end()); } @@ -123,19 +124,25 @@ template class BayesTree; factors_.insert(end(), firstFactor, lastFactor); } - /** push back many factors stored in a vector*/ + /** + * @brief Add a vector of derived factors + * @param factors to add + */ template - void push_back(const std::vector >& factors); + void push_back(const std::vector >& factors) { + factors_.insert(end(), factors.begin(), factors.end()); + } /// @} /// @name Testable /// @{ /** print out graph */ - void print(const std::string& s = "FactorGraph") const; + void print(const std::string& s = "FactorGraph", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /** Check equality */ - bool equals(const FactorGraph& fg, double tol = 1e-9) const; + bool equals(const This& fg, double tol = 1e-9) const; /// @} /// @name Standard Interface @@ -151,8 +158,10 @@ template class BayesTree; operator const std::vector&() const { return factors_; } /** Get a specific factor by index */ - const sharedFactor operator[](size_t i) const { assert(i class BayesTree; /** Get the last factor */ sharedFactor back() const { return factors_.back(); } + /** Eliminate the first \c n frontal variables, returning the resulting + * conditional and remaining factor graph - this is very inefficient for + * eliminating all variables, to do that use EliminationTree or + * JunctionTree. + */ + std::pair > eliminateFrontals(size_t nFrontals, const Eliminate& eliminate) const; + /// @} /// @name Modifying Factor Graphs (imperative, discouraged) /// @{ @@ -192,39 +208,6 @@ template class BayesTree; /** return the number valid factors */ size_t nrFactors() const; - /** dynamic_cast the factor pointers down or up the class hierarchy */ - template - typename RELATED::shared_ptr dynamicCastFactors() const { - typename RELATED::shared_ptr ret(new RELATED); - ret->reserve(this->size()); - BOOST_FOREACH(const sharedFactor& factor, *this) { - typename RELATED::FactorType::shared_ptr castedFactor(boost::dynamic_pointer_cast(factor)); - if(castedFactor) - ret->push_back(castedFactor); - else - throw std::invalid_argument("In FactorGraph::dynamic_factor_cast(), dynamic_cast failed, meaning an invalid cast was requested."); - } - return ret; - } - - /** - * dynamic_cast factor pointers if possible, otherwise convert with a - * constructor of the target type. - */ - template - typename TARGET::shared_ptr convertCastFactors() const { - typename TARGET::shared_ptr ret(new TARGET); - ret->reserve(this->size()); - BOOST_FOREACH(const sharedFactor& factor, *this) { - typename TARGET::FactorType::shared_ptr castedFactor(boost::dynamic_pointer_cast(factor)); - if(castedFactor) - ret->push_back(castedFactor); - else - ret->push_back(typename TARGET::FactorType::shared_ptr(new typename TARGET::FactorType(*factor))); - } - return ret; - } - private: /** Serialization function */ @@ -239,44 +222,19 @@ template class BayesTree; }; // FactorGraph /** Create a combined joint factor (new style for EliminationTree). */ - template - typename DERIVED::shared_ptr Combine(const FactorGraph& factors, + template + typename DERIVEDFACTOR::shared_ptr Combine(const FactorGraph& factors, const FastMap >& variableSlots); /** * static function that combines two factor graphs - * @param const &fg1 Linear factor graph - * @param const &fg2 Linear factor graph + * @param fg1 Linear factor graph + * @param fg2 Linear factor graph * @return a new combined factor graph */ template FACTORGRAPH combine(const FACTORGRAPH& fg1, const FACTORGRAPH& fg2); - /* - * These functions are defined here because they are templated on an - * additional parameter. Putting them in the -inl.h file would mean these - * would have to be explicitly instantiated for any possible derived factor - * type. - */ - - /* ************************************************************************* */ - template - template - FactorGraph::FactorGraph(const BayesNet& bayesNet) { - factors_.reserve(bayesNet.size()); - BOOST_FOREACH(const typename CONDITIONAL::shared_ptr& cond, bayesNet) { - this->push_back(cond->toFactor()); - } - } - - /* ************************************************************************* */ - template - template - void FactorGraph::push_back(const std::vector >& factors) { - BOOST_FOREACH(const boost::shared_ptr& factor, factors) - this->push_back(factor); - } - } // namespace gtsam #include diff --git a/gtsam/inference/GenericMultifrontalSolver-inl.h b/gtsam/inference/GenericMultifrontalSolver-inl.h index 652db02ca..39cda6771 100644 --- a/gtsam/inference/GenericMultifrontalSolver-inl.h +++ b/gtsam/inference/GenericMultifrontalSolver-inl.h @@ -21,8 +21,6 @@ #include #include -using namespace std; - namespace gtsam { /* ************************************************************************* */ @@ -36,28 +34,45 @@ namespace gtsam { /* ************************************************************************* */ template GenericMultifrontalSolver::GenericMultifrontalSolver( - const typename FactorGraph::shared_ptr& graph, + const sharedGraph& graph, const VariableIndex::shared_ptr& variableIndex) : structure_(variableIndex), junctionTree_(new JT(*graph, *structure_)) { } + /* ************************************************************************* */ + template + void GenericMultifrontalSolver::print(const std::string& s) const { + this->structure_->print(s + " structure:\n"); + this->junctionTree_->print(s + " jtree:"); + } + + /* ************************************************************************* */ + template + bool GenericMultifrontalSolver::equals( + const GenericMultifrontalSolver& expected, double tol) const { + if (!this->structure_->equals(*expected.structure_, tol)) return false; + if (!this->junctionTree_->equals(*expected.junctionTree_, tol)) return false; + return true; + } + /* ************************************************************************* */ template - void GenericMultifrontalSolver::replaceFactors( - const typename FactorGraph::shared_ptr& graph) { + void GenericMultifrontalSolver::replaceFactors(const sharedGraph& graph) { junctionTree_.reset(new JT(*graph, *structure_)); } /* ************************************************************************* */ - template - typename BayesTree::shared_ptr GenericMultifrontalSolver::eliminate( - typename FactorGraph::Eliminate function) const { + template + typename BayesTree::shared_ptr + GenericMultifrontalSolver::eliminate(Eliminate function) const { // eliminate junction tree, returns pointer to root - typename BayesTree::sharedClique root = junctionTree_->eliminate(function); + typename BayesTree::sharedClique + root = junctionTree_->eliminate(function); // create an empty Bayes tree and insert root clique - typename BayesTree::shared_ptr bayesTree(new BayesTree); + typename BayesTree::shared_ptr + bayesTree(new BayesTree); bayesTree->insert(root); // return the Bayes tree @@ -69,9 +84,10 @@ namespace gtsam { typename FactorGraph::shared_ptr GenericMultifrontalSolver::jointFactorGraph( const std::vector& js, Eliminate function) const { - // We currently have code written only for computing the + // FIXME: joint for arbitrary sets of variables not present + // TODO: develop and implement theory for shortcuts of more than two variables - if (js.size() != 2) throw domain_error( + if (js.size() != 2) throw std::domain_error( "*MultifrontalSolver::joint(js) currently can only compute joint marginals\n" "for exactly two variables. You can call marginal to compute the\n" "marginal for one variable. *SequentialSolver::joint(js) can compute the\n" @@ -82,7 +98,7 @@ namespace gtsam { /* ************************************************************************* */ template - typename F::shared_ptr GenericMultifrontalSolver::marginalFactor( + typename boost::shared_ptr GenericMultifrontalSolver::marginalFactor( Index j, Eliminate function) const { return eliminate(function)->marginalFactor(j, function); } diff --git a/gtsam/inference/GenericMultifrontalSolver.h b/gtsam/inference/GenericMultifrontalSolver.h index 5d6cc74ef..2d50b2ec1 100644 --- a/gtsam/inference/GenericMultifrontalSolver.h +++ b/gtsam/inference/GenericMultifrontalSolver.h @@ -72,7 +72,17 @@ namespace gtsam { GenericMultifrontalSolver(const sharedGraph& factorGraph, const VariableIndex::shared_ptr& variableIndex); - /// @} + /// @} + /// @name Testable + /// @{ + + /** Print to cout */ + void print(const std::string& name = "GenericMultifrontalSolver: ") const; + + /** Test whether is equal to another */ + bool equals(const GenericMultifrontalSolver& other, double tol = 1e-9) const; + + /// @} /// @name Standard Interface /// @{ @@ -102,7 +112,7 @@ namespace gtsam { * Compute the marginal density over a variable, by integrating out * all of the other variables. This function returns the result as a factor. */ - typename FACTOR::shared_ptr marginalFactor(Index j, + typename boost::shared_ptr marginalFactor(Index j, Eliminate function) const; /// @} diff --git a/gtsam/inference/GenericSequentialSolver-inl.h b/gtsam/inference/GenericSequentialSolver-inl.h index b2629566b..368aae831 100644 --- a/gtsam/inference/GenericSequentialSolver-inl.h +++ b/gtsam/inference/GenericSequentialSolver-inl.h @@ -41,7 +41,7 @@ namespace gtsam { template GenericSequentialSolver::GenericSequentialSolver( const sharedFactorGraph& factorGraph, - const VariableIndex::shared_ptr& variableIndex) : + const boost::shared_ptr& variableIndex) : factors_(factorGraph), structure_(variableIndex), eliminationTree_(EliminationTree::Create(*factors_, *structure_)) { } @@ -88,43 +88,43 @@ namespace gtsam { GenericSequentialSolver::jointFactorGraph( const std::vector& js, Eliminate function) const { - // Compute a COLAMD permutation with the marginal variable constrained to the end. + // Compute a COLAMD permutation with the marginal variables constrained to the end. Permutation::shared_ptr permutation(inference::PermutationCOLAMD(*structure_, js)); Permutation::shared_ptr permutationInverse(permutation->inverse()); // Permute the factors - NOTE that this permutes the original factors, not // copies. Other parts of the code may hold shared_ptr's to these factors so // we must undo the permutation before returning. - BOOST_FOREACH(const typename FACTOR::shared_ptr& factor, *factors_) - if (factor) factor->permuteWithInverse(*permutationInverse); + BOOST_FOREACH(const typename boost::shared_ptr& factor, *factors_) + if (factor) factor->permuteWithInverse(*permutationInverse); // Eliminate all variables typename BayesNet::shared_ptr bayesNet(EliminationTree::Create(*factors_)->eliminate(function)); // Undo the permuation on the original factors and on the structure. - BOOST_FOREACH(const typename FACTOR::shared_ptr& factor, *factors_) - if (factor) factor->permuteWithInverse(*permutation); + BOOST_FOREACH(const typename boost::shared_ptr& factor, *factors_) + if (factor) factor->permuteWithInverse(*permutation); // Take the joint marginal from the Bayes net. sharedFactorGraph joint(new FactorGraph ); joint->reserve(js.size()); typename BayesNet::const_reverse_iterator - conditional = bayesNet->rbegin(); + conditional = bayesNet->rbegin(); for (size_t i = 0; i < js.size(); ++i) joint->push_back((*(conditional++))->toFactor()); // Undo the permutation on the eliminated joint marginal factors - BOOST_FOREACH(const typename FACTOR::shared_ptr& factor, *joint) - factor->permuteWithInverse(*permutation); + BOOST_FOREACH(const typename boost::shared_ptr& factor, *joint) + factor->permuteWithInverse(*permutation); return joint; } /* ************************************************************************* */ template - typename FACTOR::shared_ptr // + typename boost::shared_ptr // GenericSequentialSolver::marginalFactor(Index j, Eliminate function) const { // Create a container for the one variable index std::vector js(1); diff --git a/gtsam/inference/GenericSequentialSolver.h b/gtsam/inference/GenericSequentialSolver.h index 5486b3280..5b4d4b41e 100644 --- a/gtsam/inference/GenericSequentialSolver.h +++ b/gtsam/inference/GenericSequentialSolver.h @@ -130,7 +130,7 @@ namespace gtsam { * Compute the marginal Gaussian density over a variable, by integrating out * all of the other variables. This function returns the result as a factor. */ - typename FACTOR::shared_ptr marginalFactor(Index j, Eliminate function) const; + typename boost::shared_ptr marginalFactor(Index j, Eliminate function) const; /// @} diff --git a/gtsam/inference/ISAM-inl.h b/gtsam/inference/ISAM-inl.h index 5d72f396c..c1252f1b0 100644 --- a/gtsam/inference/ISAM-inl.h +++ b/gtsam/inference/ISAM-inl.h @@ -19,7 +19,6 @@ #include #include // for operator += -using namespace boost::assign; #include #include @@ -27,8 +26,6 @@ using namespace boost::assign; namespace gtsam { - using namespace std; - /* ************************************************************************* */ template ISAM::ISAM() : BayesTree() {} diff --git a/gtsam/inference/IndexFactor.cpp b/gtsam/inference/IndexFactor.cpp index f74aa4ff5..b04338d5b 100644 --- a/gtsam/inference/IndexFactor.cpp +++ b/gtsam/inference/IndexFactor.cpp @@ -58,7 +58,7 @@ namespace gtsam { /* ************************************************************************* */ void IndexFactor::permuteWithInverse(const Permutation& inversePermutation) { BOOST_FOREACH(Index& key, keys()) - key = inversePermutation[key]; + key = inversePermutation[key]; assertInvariants(); } /* ************************************************************************* */ diff --git a/gtsam/inference/IndexFactor.h b/gtsam/inference/IndexFactor.h index 9b2d39727..8ab5a880a 100644 --- a/gtsam/inference/IndexFactor.h +++ b/gtsam/inference/IndexFactor.h @@ -98,6 +98,18 @@ namespace gtsam { assertInvariants(); } + /** Construct 5-way factor */ + IndexFactor(Index j1, Index j2, Index j3, Index j4, Index j5) : + Base(j1, j2, j3, j4, j5) { + assertInvariants(); + } + + /** Construct 6-way factor */ + IndexFactor(Index j1, Index j2, Index j3, Index j4, Index j5, Index j6) : + Base(j1, j2, j3, j4, j5, j6) { + assertInvariants(); + } + /// @} /// @name Advanced Constructors /// @{ diff --git a/gtsam/inference/JunctionTree-inl.h b/gtsam/inference/JunctionTree-inl.h index ad8b389ab..1d647ef88 100644 --- a/gtsam/inference/JunctionTree-inl.h +++ b/gtsam/inference/JunctionTree-inl.h @@ -19,19 +19,15 @@ #pragma once -#include #include #include #include +#include #include -#include -#include namespace gtsam { - using namespace std; - /* ************************************************************************* */ template void JunctionTree::construct(const FG& fg, const VariableIndex& variableIndex) { @@ -72,7 +68,7 @@ namespace gtsam { /* ************************************************************************* */ template typename JunctionTree::sharedClique JunctionTree::distributeFactors( - const FG& fg, const typename SymbolicBayesTree::sharedClique& bayesClique) { + const FG& fg, const SymbolicBayesTree::sharedClique& bayesClique) { // Build "target" index. This is an index for each variable of the factors // that involve this variable as their *lowest-ordered* variable. For each @@ -83,7 +79,7 @@ namespace gtsam { // Two stages - first build an array of the lowest-ordered variable in each // factor and find the last variable to be eliminated. - vector lowestOrdered(fg.size(), numeric_limits::max()); + std::vector lowestOrdered(fg.size(), std::numeric_limits::max()); Index maxVar = 0; for(size_t i=0; i > targets(maxVar+1); + std::vector > targets(maxVar+1); for(size_t i=0; i::max()) + if(lowestOrdered[i] != std::numeric_limits::max()) targets[lowestOrdered[i]].push_back(i); // Now call the recursive distributeFactors @@ -145,7 +141,7 @@ namespace gtsam { /* ************************************************************************* */ template - pair::BTClique::shared_ptr, + std::pair::BTClique::shared_ptr, typename FG::sharedFactor> JunctionTree::eliminateOneClique( typename FG::Eliminate function, const boost::shared_ptr& current) const { @@ -155,9 +151,9 @@ namespace gtsam { fg.push_back(*current); // add the local factors // receive the factors from the child and its clique point - list children; + std::list children; BOOST_FOREACH(const boost::shared_ptr& child, current->children()) { - pair tree_factor( + std::pair tree_factor( eliminateOneClique(function, child)); children.push_back(tree_factor.first); fg.push_back(tree_factor.second); @@ -185,7 +181,7 @@ namespace gtsam { } toc(3, "Update tree"); - return make_pair(new_clique, eliminated.second); + return std::make_pair(new_clique, eliminated.second); } /* ************************************************************************* */ @@ -194,9 +190,9 @@ namespace gtsam { typename FG::Eliminate function) const { if (this->root()) { tic(2, "JT eliminate"); - pair ret = + std::pair ret = this->eliminateOneClique(function, this->root()); - if (ret.second->size() != 0) throw runtime_error( + if (ret.second->size() != 0) throw std::runtime_error( "JuntionTree::eliminate: elimination failed because of factors left over!"); toc(2, "JT eliminate"); return ret.first; diff --git a/gtsam/inference/JunctionTree.h b/gtsam/inference/JunctionTree.h index 33a9aa5e4..4ff55d19b 100644 --- a/gtsam/inference/JunctionTree.h +++ b/gtsam/inference/JunctionTree.h @@ -47,7 +47,7 @@ namespace gtsam { * except that in the JunctionTree, at each node multiple variables are eliminated at a time. * * - * \ingroup Multifrontal + * \addtogroup Multifrontal * \nosubgrouping */ template::Clique> @@ -108,7 +108,7 @@ namespace gtsam { JunctionTree(const FG& factorGraph); /** Construct from a factor graph and pre-computed variable index. - * @param factorGraph The factor graph for which to build the junction tree + * @param fg The factor graph for which to build the junction tree * @param structure The set of factors involving each variable. If this is not * precomputed, you can call the JunctionTree(const FG&) * constructor instead. diff --git a/gtsam/inference/Permutation.h b/gtsam/inference/Permutation.h index dc3aa669a..4e32b1f52 100644 --- a/gtsam/inference/Permutation.h +++ b/gtsam/inference/Permutation.h @@ -26,7 +26,7 @@ namespace gtsam { -/** + /** * A permutation reorders variables, for example to reduce fill-in during * elimination. To save computation, the permutation can be applied to * the necessary data structures only once, then multiple computations @@ -36,10 +36,9 @@ namespace gtsam { * that linearized factor graphs are already correctly ordered and need * not be permuted. * - * For convenience, there is also a helper class "Permuted" that transforms - * arguments supplied through the square-bracket [] operator through the - * permutation. Note that this helper class stores a reference to the original - * container. + * Permutations can be considered to a 1-1 mapping from an original set of indices + * to a different set of indices. Permutations can be composed and inverted + * in order to create new indexing for a structure. * \nosubgrouping */ class Permutation { @@ -82,11 +81,25 @@ public: /// @{ /** - * Permute the given variable, i.e. determine it's new index after the - * permutation. + * Return the new index of the supplied variable after the permutation */ Index operator[](Index variable) const { check(variable); return rangeIndices_[variable]; } + /** + * Return the new index of the supplied variable after the permutation. This version allows modification. + */ + Index& operator[](Index variable) { check(variable); return rangeIndices_[variable]; } + + /** + * Return the new index of the supplied variable after the permutation. Synonym for operator[](Index). + */ + Index at(Index variable) const { return operator[](variable); } + + /** + * Return the new index of the supplied variable after the permutation. This version allows modification. Synonym for operator[](Index). + */ + Index& at(Index variable) { return operator[](variable); } + /** * The number of variables in the range of this permutation, i.e. the output * space. @@ -115,8 +128,8 @@ public: static Permutation PullToFront(const std::vector& toFront, size_t size, bool filterDuplicates = false); /** - * Create a permutation that pulls the given variables to the front while - * pushing the rest to the back. + * Create a permutation that pushes the given variables to the back while + * pulling the rest to the front. */ static Permutation PushToBack(const std::vector& toBack, size_t size, bool filterDuplicates = false); @@ -133,18 +146,25 @@ public: */ Permutation::shared_ptr inverse() const; - const_iterator begin() const { return rangeIndices_.begin(); } /// + void applyToCollection(OUTPUT_COLLECTION& output, const INPUT_COLLECTION& input) const { + for(size_t i = 0; i < output.size(); ++i) output[i] = input[(*this)[i]]; } /// @} /// @name Advanced Interface /// @{ - /** - * TODO: comment - */ - Index& operator[](Index variable) { check(variable); return rangeIndices_[variable]; } /** * A partial permutation, reorders the variables selected by selector through @@ -153,8 +173,8 @@ public: */ Permutation::shared_ptr partialPermutation(const Permutation& selector, const Permutation& partialPermutation) const; - iterator begin() { return rangeIndices_.begin(); } /// permuted(permutation, container); - * permuted[index1]; - * permuted[index2]; - * which is equivalent to: - * container[permutation[index1]]; - * container[permutation[index2]]; - * but more concise. - */ -template -class Permuted { - Permutation permutation_; - CONTAINER& container_; -public: - typedef typename CONTAINER::iterator::value_type value_type; - - /** Construct as a permuted view on the Container. The permutation is copied - * but only a reference to the container is stored. - */ - Permuted(const Permutation& permutation, CONTAINER& container) : permutation_(permutation), container_(container) {} - - /** Construct as a view on the Container with an identity permutation. Only - * a reference to the container is stored. - */ - Permuted(CONTAINER& container) : permutation_(Permutation::Identity(container.size())), container_(container) {} - - /** Print */ - void print(const std::string& str = "") const { - std::cout << str; - permutation_.print(" permutation: "); - container_.print(" container: "); - } - - /** Access the container through the permutation */ - value_type& operator[](size_t index) { return container_[permutation_[index]]; } - - /** Access the container through the permutation (const version) */ - const value_type& operator[](size_t index) const { return container_[permutation_[index]]; } - - /** Assignment operator for cloning in ISAM2 */ - Permuted operator=(const Permuted& other) { - permutation_ = other.permutation_; - container_ = other.container_; - return *this; - } - - /** Permute this view by applying a permutation to the underlying permutation */ - void permute(const Permutation& permutation) { assert(permutation.size() == this->size()); permutation_ = *permutation_.permute(permutation); } - - /** Access the underlying container */ - CONTAINER* operator->() { return &container_; } - - /** Access the underlying container (const version) */ - const CONTAINER* operator->() const { return &container_; } - - /** Size of the underlying container */ - size_t size() const { return container_.size(); } - - /** Access to the underlying container */ - CONTAINER& container() { return container_; } - - /** Access to the underlying container (const version) */ - const CONTAINER& container() const { return container_; } - - /** Access the underlying permutation */ - Permutation& permutation() { return permutation_; } - const Permutation& permutation() const { return permutation_; } -}; - - } diff --git a/gtsam/inference/SymbolicFactorGraph.cpp b/gtsam/inference/SymbolicFactorGraph.cpp index 2d5190f45..ff7a91ca6 100644 --- a/gtsam/inference/SymbolicFactorGraph.cpp +++ b/gtsam/inference/SymbolicFactorGraph.cpp @@ -15,43 +15,43 @@ * @author Frank Dellaert */ -#include - #include #include #include #include +#include + namespace gtsam { using namespace std; /* ************************************************************************* */ - SymbolicFactorGraph::SymbolicFactorGraph(const BayesNet& bayesNet) : + SymbolicFactorGraph::SymbolicFactorGraph(const SymbolicBayesNet& bayesNet) : FactorGraph(bayesNet) {} - /* ************************************************************************* */ + /* ************************************************************************* */ + SymbolicFactorGraph::SymbolicFactorGraph(const SymbolicBayesTree& bayesTree) : + FactorGraph(bayesTree) {} + + /* ************************************************************************* */ void SymbolicFactorGraph::push_factor(Index key) { - boost::shared_ptr factor(new IndexFactor(key)); - push_back(factor); + push_back(boost::make_shared(key)); } /** Push back binary factor */ void SymbolicFactorGraph::push_factor(Index key1, Index key2) { - boost::shared_ptr factor(new IndexFactor(key1,key2)); - push_back(factor); + push_back(boost::make_shared(key1,key2)); } /** Push back ternary factor */ void SymbolicFactorGraph::push_factor(Index key1, Index key2, Index key3) { - boost::shared_ptr factor(new IndexFactor(key1,key2,key3)); - push_back(factor); + push_back(boost::make_shared(key1,key2,key3)); } /** Push back 4-way factor */ void SymbolicFactorGraph::push_factor(Index key1, Index key2, Index key3, Index key4) { - boost::shared_ptr factor(new IndexFactor(key1,key2,key3,key4)); - push_back(factor); + push_back(boost::make_shared(key1,key2,key3,key4)); } /* ************************************************************************* */ @@ -63,12 +63,18 @@ namespace gtsam { return keys; } + /* ************************************************************************* */ + std::pair + SymbolicFactorGraph::eliminateFrontals(size_t nFrontals) const + { + return FactorGraph::eliminateFrontals(nFrontals, EliminateSymbolic); + } + /* ************************************************************************* */ IndexFactor::shared_ptr CombineSymbolic( const FactorGraph& factors, const FastMap >& variableSlots) { - IndexFactor::shared_ptr combined(Combine (factors, - variableSlots)); + vector >& variableSlots) { + IndexFactor::shared_ptr combined(Combine (factors, variableSlots)); // combined->assertInvariants(); return combined; } @@ -85,12 +91,9 @@ namespace gtsam { if (keys.size() < 1) throw invalid_argument( "IndexFactor::CombineAndEliminate called on factors with no variables."); - pair result; - std::vector newKeys(keys.begin(),keys.end()); - result.first.reset(new IndexConditional(newKeys, nrFrontals)); - result.second.reset(new IndexFactor(newKeys.begin()+nrFrontals, newKeys.end())); - - return result; + vector newKeys(keys.begin(), keys.end()); + return make_pair(boost::make_shared(newKeys, nrFrontals), + boost::make_shared(newKeys.begin() + nrFrontals, newKeys.end())); } /* ************************************************************************* */ diff --git a/gtsam/inference/SymbolicFactorGraph.h b/gtsam/inference/SymbolicFactorGraph.h index 4da2baf13..1b20ac239 100644 --- a/gtsam/inference/SymbolicFactorGraph.h +++ b/gtsam/inference/SymbolicFactorGraph.h @@ -23,12 +23,14 @@ namespace gtsam { template class EliminationTree; } namespace gtsam { template class BayesNet; } +namespace gtsam { template class BayesTree; } namespace gtsam { class IndexConditional; } namespace gtsam { + typedef EliminationTree SymbolicEliminationTree; typedef BayesNet SymbolicBayesNet; - typedef EliminationTree SymbolicEliminationTree; + typedef BayesTree SymbolicBayesTree; /** Symbolic IndexFactor Graph * \nosubgrouping @@ -45,13 +47,25 @@ namespace gtsam { } /** Construct from a BayesNet */ - SymbolicFactorGraph(const BayesNet& bayesNet); + SymbolicFactorGraph(const SymbolicBayesNet& bayesNet); + + /** Construct from a BayesTree */ + SymbolicFactorGraph(const SymbolicBayesTree& bayesTree); /** * Construct from a factor graph of any type */ template SymbolicFactorGraph(const FactorGraph& fg); + + /** Eliminate the first \c n frontal variables, returning the resulting + * conditional and remaining factor graph - this is very inefficient for + * eliminating all variables, to do that use EliminationTree or + * JunctionTree. Note that this version simply calls + * FactorGraph::eliminateFrontals with EliminateSymbolic + * as the eliminate function argument. + */ + std::pair eliminateFrontals(size_t nFrontals) const; /// @} /// @name Standard Interface @@ -63,6 +77,8 @@ namespace gtsam { */ FastSet keys() const; + + /// @} /// @name Advanced Interface /// @{ @@ -82,9 +98,8 @@ namespace gtsam { }; /** Create a combined joint factor (new style for EliminationTree). */ - IndexFactor::shared_ptr CombineSymbolic( - const FactorGraph& factors, const FastMap >& variableSlots); + IndexFactor::shared_ptr CombineSymbolic(const FactorGraph& factors, + const FastMap >& variableSlots); /** * CombineAndEliminate provides symbolic elimination. diff --git a/gtsam/inference/SymbolicMultifrontalSolver.h b/gtsam/inference/SymbolicMultifrontalSolver.h index 35b253c31..802b10d72 100644 --- a/gtsam/inference/SymbolicMultifrontalSolver.h +++ b/gtsam/inference/SymbolicMultifrontalSolver.h @@ -22,7 +22,50 @@ namespace gtsam { -// The base class provides all of the needed functionality -typedef GenericMultifrontalSolver > > SymbolicMultifrontalSolver; + class SymbolicMultifrontalSolver : GenericMultifrontalSolver > > { + + protected: + typedef GenericMultifrontalSolver > > Base; + + public: + /** + * Construct the solver for a factor graph. This builds the junction + * tree, which does the symbolic elimination, identifies the cliques, + * and distributes all the factors to the right cliques. + */ + SymbolicMultifrontalSolver(const SymbolicFactorGraph& factorGraph) : Base(factorGraph) {}; + + /** + * Construct the solver with a shared pointer to a factor graph and to a + * VariableIndex. The solver will store these pointers, so this constructor + * is the fastest. + */ + SymbolicMultifrontalSolver(const SymbolicFactorGraph::shared_ptr& factorGraph, + const VariableIndex::shared_ptr& variableIndex) : Base(factorGraph, variableIndex) {}; + + /** Print to cout */ + void print(const std::string& name = "SymbolicMultifrontalSolver: ") const { Base::print(name); }; + + /** Test whether is equal to another */ + bool equals(const SymbolicMultifrontalSolver& other, double tol = 1e-9) const { return Base::equals(other, tol); }; + + /** + * Eliminate the factor graph sequentially. Uses a column elimination tree + * to recursively eliminate. + */ + SymbolicBayesTree::shared_ptr eliminate() const { return Base::eliminate(&EliminateSymbolic); }; + + /** + * Compute the marginal joint over a set of variables, by integrating out + * all of the other variables. Returns the result as a factor graph. + */ + SymbolicFactorGraph::shared_ptr jointFactorGraph(const std::vector& js) const { return Base::jointFactorGraph(js, &EliminateSymbolic); }; + + /** + * Compute the marginal Gaussian density over a variable, by integrating out + * all of the other variables. This function returns the result as a factor. + */ + IndexFactor::shared_ptr marginalFactor(Index j) const { return Base::marginalFactor(j, &EliminateSymbolic); }; + }; } diff --git a/gtsam/inference/SymbolicSequentialSolver.h b/gtsam/inference/SymbolicSequentialSolver.h index d6e21e88e..c114261f0 100644 --- a/gtsam/inference/SymbolicSequentialSolver.h +++ b/gtsam/inference/SymbolicSequentialSolver.h @@ -21,8 +21,51 @@ namespace gtsam { -// The base class provides all of the needed functionality -typedef GenericSequentialSolver SymbolicSequentialSolver; + class SymbolicSequentialSolver : GenericSequentialSolver { + + protected: + typedef GenericSequentialSolver Base; + + public: + /** + * Construct the solver for a factor graph. This builds the junction + * tree, which does the symbolic elimination, identifies the cliques, + * and distributes all the factors to the right cliques. + */ + SymbolicSequentialSolver(const SymbolicFactorGraph& factorGraph) : Base(factorGraph) {}; + + /** + * Construct the solver with a shared pointer to a factor graph and to a + * VariableIndex. The solver will store these pointers, so this constructor + * is the fastest. + */ + SymbolicSequentialSolver(const SymbolicFactorGraph::shared_ptr& factorGraph, + const VariableIndex::shared_ptr& variableIndex) : Base(factorGraph, variableIndex) {}; + + /** Print to cout */ + void print(const std::string& name = "SymbolicSequentialSolver: ") const { Base::print(name); }; + + /** Test whether is equal to another */ + bool equals(const SymbolicSequentialSolver& other, double tol = 1e-9) const { return Base::equals(other, tol); }; + + /** + * Eliminate the factor graph sequentially. Uses a column elimination tree + * to recursively eliminate. + */ + SymbolicBayesNet::shared_ptr eliminate() const { return Base::eliminate(&EliminateSymbolic); }; + + /** + * Compute the marginal joint over a set of variables, by integrating out + * all of the other variables. Returns the result as a factor graph. + */ + SymbolicFactorGraph::shared_ptr jointFactorGraph(const std::vector& js) const { return Base::jointFactorGraph(js, &EliminateSymbolic); }; + + /** + * Compute the marginal Gaussian density over a variable, by integrating out + * all of the other variables. This function returns the result as a factor. + */ + IndexFactor::shared_ptr marginalFactor(Index j) const { return Base::marginalFactor(j, &EliminateSymbolic); }; + }; } diff --git a/gtsam/inference/VariableIndex.cpp b/gtsam/inference/VariableIndex.cpp index c7ef90e9f..b24e2f5fc 100644 --- a/gtsam/inference/VariableIndex.cpp +++ b/gtsam/inference/VariableIndex.cpp @@ -18,37 +18,12 @@ #include #include +#include namespace gtsam { using namespace std; -/* ************************************************************************* */ -VariableIndex::VariableIndex(const VariableIndex& other) : - index_(indexUnpermuted_) { - *this = other; -} - -/* ************************************************************************* */ -VariableIndex& VariableIndex::operator=(const VariableIndex& rhs) { - index_ = rhs.index_; - nFactors_ = rhs.nFactors_; - nEntries_ = rhs.nEntries_; - return *this; -} - -/* ************************************************************************* */ -void VariableIndex::permute(const Permutation& permutation) { -#ifndef NDEBUG - // Assert that the permutation does not leave behind any non-empty variables, - // otherwise the nFactors and nEntries counts would be incorrect. - for(Index j=0; jindex_.size(); ++j) - if(find(permutation.begin(), permutation.end(), j) == permutation.end()) - assert(this->operator[](j).empty()); -#endif - index_.permute(permutation); -} - /* ************************************************************************* */ bool VariableIndex::equals(const VariableIndex& other, double tol) const { if(this->nEntries_ == other.nEntries_ && this->nFactors_ == other.nFactors_) { @@ -66,17 +41,13 @@ bool VariableIndex::equals(const VariableIndex& other, double tol) const { /* ************************************************************************* */ void VariableIndex::print(const string& str) const { - cout << str << "\n"; + cout << str; cout << "nEntries = " << nEntries() << ", nFactors = " << nFactors() << "\n"; - Index var = 0; - BOOST_FOREACH(const Factors& variable, index_.container()) { - Permutation::const_iterator rvar = find(index_.permutation().begin(), index_.permutation().end(), var); - assert(rvar != index_.permutation().end()); - cout << "var " << (rvar-index_.permutation().begin()) << ":"; - BOOST_FOREACH(const size_t factor, variable) + for(Index var = 0; var < size(); ++var) { + cout << "var " << var << ":"; + BOOST_FOREACH(const size_t factor, index_[var]) cout << " " << factor; cout << "\n"; - ++ var; } cout << flush; } @@ -85,7 +56,7 @@ void VariableIndex::print(const string& str) const { void VariableIndex::outputMetisFormat(ostream& os) const { os << size() << " " << nFactors() << "\n"; // run over variables, which will be hyper-edges. - BOOST_FOREACH(const Factors& variable, index_.container()) { + BOOST_FOREACH(const Factors& variable, index_) { // every variable is a hyper-edge covering its factors BOOST_FOREACH(const size_t factor, variable) os << (factor+1) << " "; // base 1 @@ -94,4 +65,26 @@ void VariableIndex::outputMetisFormat(ostream& os) const { os << flush; } +/* ************************************************************************* */ +void VariableIndex::permuteInPlace(const Permutation& permutation) { + // Create new index and move references to data into it in permuted order + deque newIndex(this->size()); + for(Index i = 0; i < newIndex.size(); ++i) + newIndex[i].swap(this->index_[permutation[i]]); + + // Move reference to entire index into the VariableIndex + index_.swap(newIndex); +} + +/* ************************************************************************* */ +void VariableIndex::removeUnusedAtEnd(size_t nToRemove) { +#ifndef NDEBUG + for(size_t i = this->size() - nToRemove; i < this->size(); ++i) + if(!(*this)[i].empty()) + throw std::invalid_argument("Attempting to remove non-empty variables with VariableIndex::removeUnusedAtEnd()"); +#endif + + index_.resize(this->size() - nToRemove); +} + } diff --git a/gtsam/inference/VariableIndex.h b/gtsam/inference/VariableIndex.h index c9efc6b22..d747d1122 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -18,20 +18,23 @@ #pragma once #include +#include #include #include #include -#include +#include namespace gtsam { + class Permutation; + /** * The VariableIndex class computes and stores the block column structure of a * factor graph. The factor graph stores a collection of factors, each of * which involves a set of variables. In contrast, the VariableIndex is built * from a factor graph prior to elimination, and stores the list of factors - * that involve each variable. This information is stored as a vector of + * that involve each variable. This information is stored as a deque of * lists of factor indices. * \nosubgrouping */ @@ -44,8 +47,7 @@ public: typedef Factors::const_iterator Factor_const_iterator; protected: - std::vector indexUnpermuted_; - Permuted > index_; // Permuted view of indexUnpermuted. + std::deque index_; size_t nFactors_; // Number of factors in the original factor graph. size_t nEntries_; // Sum of involved variable counts of each factor. @@ -55,7 +57,7 @@ public: /// @{ /** Default constructor, creates an empty VariableIndex */ - VariableIndex() : index_(indexUnpermuted_), nFactors_(0), nEntries_(0) {} + VariableIndex() : nFactors_(0), nEntries_(0) {} /** * Create a VariableIndex that computes and stores the block column structure @@ -70,16 +72,6 @@ public: */ template VariableIndex(const FactorGraph& factorGraph); - /** - * Copy constructor - */ - VariableIndex(const VariableIndex& other); - - /** - * Assignment operator - */ - VariableIndex& operator=(const VariableIndex& rhs); - /// @} /// @name Standard Interface /// @{ @@ -120,9 +112,6 @@ public: /// @name Advanced Interface /// @{ - /** Access a list of factors by variable */ - Factors& operator[](Index variable) { checkVar(variable); return index_[variable]; } - /** * Augment the variable index with new factors. This can be used when * solving problems incrementally. @@ -131,17 +120,25 @@ public: /** * Remove entries corresponding to the specified factors. + * NOTE: We intentionally do not decrement nFactors_ because the factor + * indices need to remain consistent. Removing factors from a factor graph + * does not shift the indices of other factors. Also, we keep nFactors_ + * one greater than the highest-numbered factor referenced in a VariableIndex. + * * @param indices The indices of the factors to remove, which must match \c factors * @param factors The factors being removed, which must symbolically correspond * exactly to the factors with the specified \c indices that were added. */ template void remove(const CONTAINER& indices, const FactorGraph& factors); - /** - * Apply a variable permutation. Does not rearrange data, just permutes - * future lookups by variable. - */ - void permute(const Permutation& permutation); + /// Permute the variables in the VariableIndex according to the given permutation + void permuteInPlace(const Permutation& permutation); + + /** Remove unused empty variables at the end of the ordering (in debug mode + * verifies they are empty). + * @param nToRemove The number of unused variables at the end to remove + */ + void removeUnusedAtEnd(size_t nToRemove); protected: Factor_iterator factorsBegin(Index variable) { checkVar(variable); return index_[variable].begin(); } /// void fill(const FactorGraph& factorGraph); /// @} @@ -183,7 +180,7 @@ void VariableIndex::fill(const FactorGraph& factorGraph) { /* ************************************************************************* */ template VariableIndex::VariableIndex(const FactorGraph& factorGraph) : - index_(indexUnpermuted_), nFactors_(0), nEntries_(0) { + nFactors_(0), nEntries_(0) { // If the factor graph is empty, return an empty index because inside this // if block we assume at least one factor. @@ -200,8 +197,7 @@ VariableIndex::VariableIndex(const FactorGraph& factorGraph) : } // Allocate array - index_.container().resize(maxVar+1); - index_.permutation() = Permutation::Identity(maxVar+1); + index_.resize(maxVar+1); fill(factorGraph); } @@ -210,7 +206,7 @@ VariableIndex::VariableIndex(const FactorGraph& factorGraph) : /* ************************************************************************* */ template VariableIndex::VariableIndex(const FactorGraph& factorGraph, Index nVariables) : - indexUnpermuted_(nVariables), index_(indexUnpermuted_), nFactors_(0), nEntries_(0) { + index_(nVariables), nFactors_(0), nEntries_(0) { fill(factorGraph); } @@ -232,11 +228,7 @@ void VariableIndex::augment(const FactorGraph& factors) { } // Allocate index - Index originalSize = index_.size(); - index_.container().resize(std::max(index_.size(), maxVar+1)); - index_.permutation().resize(index_.container().size()); - for(Index var=originalSize; var void VariableIndex::remove(const CONTAINER& indices, const FactorGraph& factors) { + // NOTE: We intentionally do not decrement nFactors_ because the factor + // indices need to remain consistent. Removing factors from a factor graph + // does not shift the indices of other factors. Also, we keep nFactors_ + // one greater than the highest-numbered factor referenced in a VariableIndex. for(size_t fi=0; fikeys().size(); ++ji) { diff --git a/gtsam/inference/VariableSlots.h b/gtsam/inference/VariableSlots.h index 551993db4..2533a7411 100644 --- a/gtsam/inference/VariableSlots.h +++ b/gtsam/inference/VariableSlots.h @@ -48,10 +48,6 @@ namespace gtsam { * variable index 3), row-block 2 (also meaning component factor 2), comes from * column-block 0 of component factor 2. * - * Note that in the case of GaussianFactor, the rows of the combined factor are - * further sorted so that the column-block position of the first structural - * non-zero increases monotonically through the rows. This additional process - * is not performed by this class. * \nosubgrouping */ diff --git a/gtsam/inference/graph-inl.h b/gtsam/inference/graph-inl.h index d8395942a..ff65147cc 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 @@ -24,8 +24,6 @@ #include -using namespace std; - #define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL) namespace gtsam { @@ -44,7 +42,7 @@ public: /* ************************************************************************* */ template -list predecessorMap2Keys(const PredecessorMap& p_map) { +std::list predecessorMap2Keys(const PredecessorMap& p_map) { typedef typename SGraph::Vertex SVertex; @@ -66,13 +64,13 @@ SDGraph toBoostGraph(const G& graph) { // convert the factor graph to boost graph SDGraph g; typedef typename boost::graph_traits >::vertex_descriptor BoostVertex; - map key2vertex; + std::map key2vertex; BoostVertex v1, v2; typename G::const_iterator itFactor; for(itFactor=graph.begin(); itFactor!=graph.end(); itFactor++) { if ((*itFactor)->keys().size() > 2) - throw(invalid_argument("toBoostGraph: only support factors with at most two keys")); + throw(std::invalid_argument("toBoostGraph: only support factors with at most two keys")); if ((*itFactor)->keys().size() == 1) continue; @@ -104,24 +102,24 @@ SDGraph toBoostGraph(const G& graph) { /* ************************************************************************* */ template -boost::tuple > +boost::tuple > predecessorMap2Graph(const PredecessorMap& p_map) { G g; - map key2vertex; + std::map key2vertex; V v1, v2, root; KEY child, parent; bool foundRoot = false; FOREACH_PAIR(child, parent, p_map) { if (key2vertex.find(child) == key2vertex.end()) { v1 = add_vertex(child, g); - key2vertex.insert(make_pair(child, v1)); + key2vertex.insert(std::make_pair(child, v1)); } else v1 = key2vertex[child]; if (key2vertex.find(parent) == key2vertex.end()) { v2 = add_vertex(parent, g); - key2vertex.insert(make_pair(parent, v2)); + key2vertex.insert(std::make_pair(parent, v2)); } else v2 = key2vertex[parent]; @@ -133,7 +131,7 @@ predecessorMap2Graph(const PredecessorMap& p_map) { } if (!foundRoot) - throw invalid_argument("predecessorMap2Graph: invalid predecessor map!"); + throw std::invalid_argument("predecessorMap2Graph: invalid predecessor map!"); else return boost::tuple >(g, root, key2vertex); } @@ -173,7 +171,7 @@ boost::shared_ptr composePoses(const G& graph, const PredecessorMap PoseGraph g; PoseVertex root; - map key2vertex; + std::map key2vertex; boost::tie(g, root, key2vertex) = predecessorMap2Graph(tree); @@ -183,7 +181,7 @@ boost::shared_ptr composePoses(const G& graph, const PredecessorMap BOOST_FOREACH(typename G::sharedFactor nl_factor, graph) { if (nl_factor->keys().size() > 2) - throw invalid_argument("composePoses: only support factors with at most two keys"); + throw std::invalid_argument("composePoses: only support factors with at most two keys"); // e.g. in pose2graph, nonlinear factor needs to be converted to pose2factor boost::shared_ptr factor = boost::dynamic_pointer_cast(nl_factor); @@ -196,9 +194,9 @@ boost::shared_ptr composePoses(const G& graph, const PredecessorMap PoseVertex v2 = key2vertex.find(key2)->second; POSE l1Xl2 = factor->measured(); - tie(edge12, found1) = boost::edge(v1, v2, g); - tie(edge21, found2) = boost::edge(v2, v1, g); - if (found1 && found2) throw invalid_argument ("composePoses: invalid spanning tree"); + boost::tie(edge12, found1) = boost::edge(v1, v2, g); + boost::tie(edge21, found2) = boost::edge(v2, v1, g); + if (found1 && found2) throw std::invalid_argument ("composePoses: invalid spanning tree"); if (!found1 && !found2) continue; if (found1) boost::put(boost::edge_weight, g, edge12, l1Xl2); @@ -225,13 +223,13 @@ PredecessorMap findMinimumSpanningTree(const G& fg) { SDGraph g = gtsam::toBoostGraph(fg); // find minimum spanning tree - vector::Vertex> p_map(boost::num_vertices(g)); + std::vector::Vertex> p_map(boost::num_vertices(g)); prim_minimum_spanning_tree(g, &p_map[0]); // convert edge to string pairs PredecessorMap tree; typename SDGraph::vertex_iterator itVertex = boost::vertices(g).first; - typename vector::Vertex>::iterator vi; + typename std::vector::Vertex>::iterator vi; for (vi = p_map.begin(); vi != p_map.end(); itVertex++, vi++) { KEY key = boost::get(boost::vertex_name, g, *itVertex); KEY parent = boost::get(boost::vertex_name, g, *vi); @@ -250,7 +248,7 @@ void split(const G& g, const PredecessorMap& tree, G& Ab1, G& Ab2) { BOOST_FOREACH(const F& factor, g) { if (factor->keys().size() > 2) - throw(invalid_argument("split: only support factors with at most two keys")); + throw(std::invalid_argument("split: only support factors with at most two keys")); if (factor->keys().size() == 1) { Ab1.push_back(factor); diff --git a/gtsam/inference/graph.h b/gtsam/inference/graph.h index 98d41940b..88ab5d0e8 100644 --- a/gtsam/inference/graph.h +++ b/gtsam/inference/graph.h @@ -108,3 +108,5 @@ namespace gtsam { } // namespace gtsam + +#include diff --git a/gtsam/inference/inference-inl.h b/gtsam/inference/inference-inl.h index 02e78e8e9..c17f947d1 100644 --- a/gtsam/inference/inference-inl.h +++ b/gtsam/inference/inference-inl.h @@ -31,7 +31,8 @@ namespace inference { /* ************************************************************************* */ template -Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIndex, const CONSTRAINED& constrainLast) { +Permutation::shared_ptr PermutationCOLAMD( + const VariableIndex& variableIndex, const CONSTRAINED& constrainLast) { std::vector cmember(variableIndex.size(), 0); @@ -47,6 +48,22 @@ Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIndex, co return PermutationCOLAMD_(variableIndex, cmember); } +/* ************************************************************************* */ +template +Permutation::shared_ptr PermutationCOLAMDGrouped( + const VariableIndex& variableIndex, const CONSTRAINED_MAP& constraints) { + std::vector cmember(variableIndex.size(), 0); + + typedef typename CONSTRAINED_MAP::value_type constraint_pair; + BOOST_FOREACH(const constraint_pair& p, constraints) { + assert(p.first < variableIndex.size()); + // FIXME: check that no groups are skipped + cmember[p.first] = p.second; + } + + return PermutationCOLAMD_(variableIndex, cmember); +} + /* ************************************************************************* */ inline Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIndex) { std::vector cmember(variableIndex.size(), 0); @@ -55,10 +72,14 @@ inline Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIn /* ************************************************************************* */ template -typename Graph::FactorizationResult eliminate(const Graph& factorGraph, const std::vector& variables, - const typename Graph::Eliminate& eliminateFcn, boost::optional variableIndex_) { +std::pair eliminate( + const Graph& factorGraph, + const std::vector& variables, + const typename Graph::Eliminate& eliminateFcn, + boost::optional variableIndex_) { - const VariableIndex& variableIndex = variableIndex_ ? *variableIndex_ : VariableIndex(factorGraph); + const VariableIndex& variableIndex = + variableIndex_ ? *variableIndex_ : VariableIndex(factorGraph); // First find the involved factors Graph involvedFactors; @@ -108,13 +129,11 @@ typename Graph::FactorizationResult eliminate(const Graph& factorGraph, const st if(remainingFactor->size() != 0) remainingGraph.push_back(remainingFactor); - return typename Graph::FactorizationResult(conditional, remainingGraph); + return std::make_pair(conditional, remainingGraph); -} - - -} - -} +} // eliminate + +} // namespace inference +} // namespace gtsam diff --git a/gtsam/inference/inference.cpp b/gtsam/inference/inference.cpp index 9b7252030..3cddc4cfc 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 @@ -28,9 +29,9 @@ using namespace std; namespace gtsam { - namespace inference { +/* ************************************************************************* */ Permutation::shared_ptr PermutationCOLAMD_(const VariableIndex& variableIndex, std::vector& cmember) { size_t nEntries = variableIndex.nEntries(), nFactors = variableIndex.nFactors(), nVars = variableIndex.size(); // Convert to compressed column major format colamd wants it in (== MATLAB format!) @@ -92,6 +93,6 @@ Permutation::shared_ptr PermutationCOLAMD_(const VariableIndex& variableIndex, s return permutation; } -} - -} +/* ************************************************************************* */ +} // \namespace inference +} // \namespace gtsam diff --git a/gtsam/inference/inference.h b/gtsam/inference/inference.h index d87720b5a..7ba268789 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 @@ -28,53 +29,85 @@ namespace gtsam { -namespace inference { + namespace inference { -/** - * Compute a permutation (variable ordering) using colamd - */ -Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIndex); + /** + * Compute a permutation (variable ordering) using colamd + */ + Permutation::shared_ptr PermutationCOLAMD( + const VariableIndex& variableIndex); -/** - * Compute a permutation (variable ordering) using constrained colamd - */ -template -Permutation::shared_ptr PermutationCOLAMD(const VariableIndex& variableIndex, const CONSTRAINED& constrainLast); + /** + * Compute a permutation (variable ordering) using constrained colamd to move + * a set of variables to the end of the ordering + * @param variableIndex is the variable index lookup from a graph + * @param constrainlast is a vector of keys that should be constrained + * @tparam constrainLast is a std::vector (or similar structure) + */ + template + Permutation::shared_ptr PermutationCOLAMD( + const VariableIndex& variableIndex, const CONSTRAINED& constrainLast); -/** - * Compute a CCOLAMD permutation using the constraint groups in cmember. - */ -Permutation::shared_ptr PermutationCOLAMD_(const VariableIndex& variableIndex, std::vector& cmember); + /** + * Compute a permutation of variable ordering using constrained colamd to + * move variables to the end in groups (0 = unconstrained, higher numbers at + * the end). + * @param variableIndex is the variable index lookup from a graph + * @param constraintMap is a map from variable index -> group number for constrained variables + * @tparam CONSTRAINED_MAP is an associative structure (like std::map), from size_t->int + */ + template + Permutation::shared_ptr PermutationCOLAMDGrouped( + const VariableIndex& variableIndex, const CONSTRAINED_MAP& constraints); -/** Factor the factor graph into a conditional and a remaining factor graph. - * Given the factor graph \f$ f(X) \f$, and \c variables to factorize out - * \f$ V \f$, this function factorizes into \f$ f(X) = f(V;Y)f(Y) \f$, where - * \f$ Y := X\V \f$ are the remaining variables. If \f$ f(X) = p(X) \f$ is - * a probability density or likelihood, the factorization produces a - * conditional probability density and a marginal \f$ p(X) = p(V|Y)p(Y) \f$. - * - * For efficiency, this function treats the variables to eliminate - * \c variables as fully-connected, so produces a dense (fully-connected) - * conditional on all of the variables in \c variables, instead of a sparse - * BayesNet. If the variables are not fully-connected, it is more efficient - * to sequentially factorize multiple times. - */ -template -typename Graph::FactorizationResult eliminate(const Graph& factorGraph, const std::vector& variables, - const typename Graph::Eliminate& eliminateFcn, boost::optional variableIndex = boost::none); + /** + * Compute a CCOLAMD permutation using the constraint groups in cmember. + * The format for cmember is a part of ccolamd. + * + * @param variableIndex is the variable structure from a graph + * @param cmember is the constraint group list for each variable, where + * 0 is the default, unconstrained group, and higher numbers move further to + * the back of the list + * + * AGC: does cmember change? + */ + Permutation::shared_ptr PermutationCOLAMD_( + const VariableIndex& variableIndex, std::vector& cmember); -/** Eliminate a single variable, by calling - * eliminate(const Graph&, const std::vector&, const typename Graph::Eliminate&, boost::optional) - */ -template -typename Graph::FactorizationResult eliminateOne(const Graph& factorGraph, typename Graph::KeyType variable, - const typename Graph::Eliminate& eliminateFcn, boost::optional variableIndex = boost::none) { - std::vector variables(1, variable); - return eliminate(factorGraph, variables, eliminateFcn, variableIndex); -} + /** Factor the factor graph into a conditional and a remaining factor graph. + * Given the factor graph \f$ f(X) \f$, and \c variables to factorize out + * \f$ V \f$, this function factorizes into \f$ f(X) = f(V;Y)f(Y) \f$, where + * \f$ Y := X\V \f$ are the remaining variables. If \f$ f(X) = p(X) \f$ is + * a probability density or likelihood, the factorization produces a + * conditional probability density and a marginal \f$ p(X) = p(V|Y)p(Y) \f$. + * + * For efficiency, this function treats the variables to eliminate + * \c variables as fully-connected, so produces a dense (fully-connected) + * conditional on all of the variables in \c variables, instead of a sparse + * BayesNet. If the variables are not fully-connected, it is more efficient + * to sequentially factorize multiple times. + */ + template + std::pair eliminate( + const Graph& factorGraph, + const std::vector& variables, + const typename Graph::Eliminate& eliminateFcn, + boost::optional variableIndex = boost::none); -} + /** Eliminate a single variable, by calling + * eliminate(const Graph&, const std::vector&, const typename Graph::Eliminate&, boost::optional) + */ + template + std::pair eliminateOne( + const Graph& factorGraph, typename Graph::KeyType variable, + const typename Graph::Eliminate& eliminateFcn, + boost::optional variableIndex = boost::none) { + std::vector variables(1, variable); + return eliminate(factorGraph, variables, eliminateFcn, variableIndex); + } -} // namespace gtsam + } // \namespace inference + +} // \namespace gtsam #include diff --git a/gtsam/inference/tests/testBayesTree.cpp b/gtsam/inference/tests/testBayesTree.cpp index 71021ef70..b99364092 100644 --- a/gtsam/inference/tests/testBayesTree.cpp +++ b/gtsam/inference/tests/testBayesTree.cpp @@ -30,10 +30,9 @@ using namespace boost::assign; #include #include +using namespace std; using namespace gtsam; -typedef BayesTree SymbolicBayesTree; - ///* ************************************************************************* */ //// SLAM example from RSS sqrtSAM paper static const Index _x3_=0, _x2_=1; @@ -61,7 +60,7 @@ static const Index _x3_=0, _x2_=1; /* ************************************************************************* */ // Conditionals for ASIA example from the tutorial with A and D evidence static const Index _X_=0, _T_=1, _S_=2, _E_=3, _L_=4, _B_=5; -IndexConditional::shared_ptr +static IndexConditional::shared_ptr B(new IndexConditional(_B_)), L(new IndexConditional(_L_, _B_)), E(new IndexConditional(_E_, _L_, _B_)), @@ -70,11 +69,11 @@ IndexConditional::shared_ptr X(new IndexConditional(_X_, _E_)); // Cliques -IndexConditional::shared_ptr +static IndexConditional::shared_ptr ELB(IndexConditional::FromKeys(cref_list_of<3>(_E_)(_L_)(_B_), 3)); // Bayes Tree for Asia example -SymbolicBayesTree createAsiaSymbolicBayesTree() { +static SymbolicBayesTree createAsiaSymbolicBayesTree() { SymbolicBayesTree bayesTree; // Ordering asiaOrdering; asiaOrdering += _X_, _T_, _S_, _E_, _L_, _B_; SymbolicBayesTree::insert(bayesTree, B); @@ -239,6 +238,76 @@ TEST( BayesTree, removePath3 ) CHECK(assert_equal(expectedOrphans, orphans)); } +void getAllCliques(const SymbolicBayesTree::sharedClique& subtree, SymbolicBayesTree::Cliques& cliques) { + // Check if subtree exists + if (subtree) { + cliques.push_back(subtree); + // Recursive call over all child cliques + BOOST_FOREACH(SymbolicBayesTree::sharedClique& childClique, subtree->children()) { + getAllCliques(childClique,cliques); + } + } +} + +/* ************************************************************************* */ +TEST( BayesTree, shortcutCheck ) +{ + const Index _A_=6, _B_=5, _C_=4, _D_=3, _E_=2, _F_=1, _G_=0; + IndexConditional::shared_ptr + A(new IndexConditional(_A_)), + B(new IndexConditional(_B_, _A_)), + C(new IndexConditional(_C_, _A_)), + D(new IndexConditional(_D_, _C_)), + E(new IndexConditional(_E_, _B_)), + F(new IndexConditional(_F_, _E_)), + G(new IndexConditional(_G_, _F_)); + SymbolicBayesTree bayesTree; +// Ordering ord; ord += _A_,_B_,_C_,_D_,_E_,_F_; + SymbolicBayesTree::insert(bayesTree, A); + SymbolicBayesTree::insert(bayesTree, B); + SymbolicBayesTree::insert(bayesTree, C); + SymbolicBayesTree::insert(bayesTree, D); + SymbolicBayesTree::insert(bayesTree, E); + SymbolicBayesTree::insert(bayesTree, F); + SymbolicBayesTree::insert(bayesTree, G); + + //bayesTree.print("BayesTree"); + //bayesTree.saveGraph("BT1.dot"); + + SymbolicBayesTree::sharedClique rootClique= bayesTree.root(); + //rootClique->printTree(); + SymbolicBayesTree::Cliques allCliques; + getAllCliques(rootClique,allCliques); + + BayesNet bn; + BOOST_FOREACH(SymbolicBayesTree::sharedClique& clique, allCliques) { + //clique->print("Clique#"); + bn = clique->shortcut(rootClique, &EliminateSymbolic); + //bn.print("Shortcut:\n"); + //cout << endl; + } + + // Check if all the cached shortcuts are cleared + rootClique->deleteCachedShorcuts(); + BOOST_FOREACH(SymbolicBayesTree::sharedClique& clique, allCliques) { + bool notCleared = clique->cachedShortcut(); + CHECK( notCleared == false); + } + +// BOOST_FOREACH(SymbolicBayesTree::sharedClique& clique, allCliques) { +// clique->print("Clique#"); +// if(clique->cachedShortcut()){ +// bn = clique->cachedShortcut().get(); +// bn.print("Shortcut:\n"); +// } +// else +// cout << "Not Initialized" << endl; +// cout << endl; +// } +} + + + /* ************************************************************************* */ TEST( BayesTree, removeTop ) { diff --git a/gtsam/inference/tests/testEliminationTree.cpp b/gtsam/inference/tests/testEliminationTree.cpp index 0ec8b2266..c1df6e98e 100644 --- a/gtsam/inference/tests/testEliminationTree.cpp +++ b/gtsam/inference/tests/testEliminationTree.cpp @@ -101,8 +101,7 @@ TEST(EliminationTree, eliminate ) fg.push_factor(3, 4); // eliminate - SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate( - &EliminateSymbolic); + SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate(); CHECK(assert_equal(expected,actual)); } diff --git a/gtsam/inference/tests/testFactorGraph.cpp b/gtsam/inference/tests/testFactorGraph.cpp index 8669329bb..bfbe716d4 100644 --- a/gtsam/inference/tests/testFactorGraph.cpp +++ b/gtsam/inference/tests/testFactorGraph.cpp @@ -21,80 +21,43 @@ #include #include #include // for operator += +#include using namespace boost::assign; #include +#include #include using namespace std; using namespace gtsam; -typedef boost::shared_ptr shared; - -///* ************************************************************************* */ -// SL-FIX TEST( FactorGraph, splitMinimumSpanningTree ) -//{ -// SymbolicFactorGraph G; -// G.push_factor("x1", "x2"); -// G.push_factor("x1", "x3"); -// G.push_factor("x1", "x4"); -// G.push_factor("x2", "x3"); -// G.push_factor("x2", "x4"); -// G.push_factor("x3", "x4"); -// -// SymbolicFactorGraph T, C; -// boost::tie(T, C) = G.splitMinimumSpanningTree(); -// -// SymbolicFactorGraph expectedT, expectedC; -// expectedT.push_factor("x1", "x2"); -// expectedT.push_factor("x1", "x3"); -// expectedT.push_factor("x1", "x4"); -// expectedC.push_factor("x2", "x3"); -// expectedC.push_factor("x2", "x4"); -// expectedC.push_factor("x3", "x4"); -// CHECK(assert_equal(expectedT,T)); -// CHECK(assert_equal(expectedC,C)); -//} - -///* ************************************************************************* */ -///** -// * x1 - x2 - x3 - x4 - x5 -// * | | / | -// * l1 l2 l3 -// */ -// SL-FIX TEST( FactorGraph, removeSingletons ) -//{ -// SymbolicFactorGraph G; -// G.push_factor("x1", "x2"); -// G.push_factor("x2", "x3"); -// G.push_factor("x3", "x4"); -// G.push_factor("x4", "x5"); -// G.push_factor("x2", "l1"); -// G.push_factor("x3", "l2"); -// G.push_factor("x4", "l2"); -// G.push_factor("x4", "l3"); -// -// SymbolicFactorGraph singletonGraph; -// set singletons; -// boost::tie(singletonGraph, singletons) = G.removeSingletons(); -// -// set singletons_excepted; singletons_excepted += "x1", "x2", "x5", "l1", "l3"; -// CHECK(singletons_excepted == singletons); -// -// SymbolicFactorGraph singletonGraph_excepted; -// singletonGraph_excepted.push_factor("x2", "l1"); -// singletonGraph_excepted.push_factor("x4", "l3"); -// singletonGraph_excepted.push_factor("x1", "x2"); -// singletonGraph_excepted.push_factor("x4", "x5"); -// singletonGraph_excepted.push_factor("x2", "x3"); -// CHECK(singletonGraph_excepted.equals(singletonGraph)); -//} - /* ************************************************************************* */ -TEST(FactorGraph, dynamic_factor_cast) { - FactorGraph fg; - fg.dynamicCastFactors >(); +TEST(FactorGraph, eliminateFrontals) { + + SymbolicFactorGraph sfgOrig; + sfgOrig.push_factor(0,1); + sfgOrig.push_factor(0,2); + sfgOrig.push_factor(1,3); + sfgOrig.push_factor(1,4); + sfgOrig.push_factor(2,3); + sfgOrig.push_factor(4,5); + + IndexConditional::shared_ptr actualCond; + SymbolicFactorGraph actualSfg; + boost::tie(actualCond, actualSfg) = sfgOrig.eliminateFrontals(2); + + vector condIndices; + condIndices += 0,1,2,3,4; + IndexConditional expectedCond(condIndices, 2); + + SymbolicFactorGraph expectedSfg; + expectedSfg.push_factor(2,3); + expectedSfg.push_factor(4,5); + expectedSfg.push_factor(2,3,4); + + EXPECT(assert_equal(expectedSfg, actualSfg)); + EXPECT(assert_equal(expectedCond, *actualCond)); } /* ************************************************************************* */ diff --git a/gtsam/inference/tests/testISAM.cpp b/gtsam/inference/tests/testISAM.cpp index 8fdc78fc0..18cf66723 100644 --- a/gtsam/inference/tests/testISAM.cpp +++ b/gtsam/inference/tests/testISAM.cpp @@ -34,7 +34,7 @@ typedef ISAM SymbolicISAM; /* ************************************************************************* */ // Some numbers that should be consistent among all smoother tests -double sigmax1 = 0.786153, sigmax2 = 0.687131, sigmax3 = 0.671512, sigmax4 = +static double sigmax1 = 0.786153, sigmax2 = 0.687131, sigmax3 = 0.671512, sigmax4 = 0.669534, sigmax5 = sigmax3, sigmax6 = sigmax2, sigmax7 = sigmax1; /* ************************************************************************* */ diff --git a/gtsam/inference/tests/testInference.cpp b/gtsam/inference/tests/testInference.cpp index 41c33a456..b25703cb6 100644 --- a/gtsam/inference/tests/testInference.cpp +++ b/gtsam/inference/tests/testInference.cpp @@ -11,8 +11,8 @@ /** * @file testInference.cpp - * @brief * @author Richard Roberts + * @author Alex Cunningham * @date Dec 6, 2010 */ @@ -35,8 +35,84 @@ TEST(inference, UnobservedVariables) { VariableIndex variableIndex(sfg); - Permutation::shared_ptr colamd(inference::PermutationCOLAMD(variableIndex)); + // Computes a permutation with known variables first, skipped variables last + // Actual 0 1 3 5 2 4 + Permutation::shared_ptr actual(inference::PermutationCOLAMD(variableIndex)); + Permutation expected(6); + expected[0] = 0; + expected[1] = 1; + expected[2] = 3; + expected[3] = 5; + expected[4] = 2; + expected[5] = 4; + EXPECT(assert_equal(expected, *actual)); +} + +/* ************************************************************************* */ +TEST(inference, constrained_ordering) { + SymbolicFactorGraph sfg; + + // create graph with wanted variable set = 2, 4 + sfg.push_factor(0,1); + sfg.push_factor(1,2); + sfg.push_factor(2,3); + sfg.push_factor(3,4); + sfg.push_factor(4,5); + + VariableIndex variableIndex(sfg); + + // unconstrained version + Permutation::shared_ptr actUnconstrained(inference::PermutationCOLAMD(variableIndex)); + Permutation expUnconstrained = Permutation::Identity(6); + EXPECT(assert_equal(expUnconstrained, *actUnconstrained)); + + // constrained version - push one set to the end + std::vector constrainLast; + constrainLast.push_back(2); + constrainLast.push_back(4); + Permutation::shared_ptr actConstrained(inference::PermutationCOLAMD(variableIndex, constrainLast)); + Permutation expConstrained(6); + expConstrained[0] = 0; + expConstrained[1] = 1; + expConstrained[2] = 5; + expConstrained[3] = 3; + expConstrained[4] = 4; + expConstrained[5] = 2; + EXPECT(assert_equal(expConstrained, *actConstrained)); +} + +/* ************************************************************************* */ +TEST(inference, grouped_constrained_ordering) { + SymbolicFactorGraph sfg; + + // create graph with constrained groups: + // 1: 2, 4 + // 2: 5 + sfg.push_factor(0,1); + sfg.push_factor(1,2); + sfg.push_factor(2,3); + sfg.push_factor(3,4); + sfg.push_factor(4,5); + + VariableIndex variableIndex(sfg); + + // constrained version - push one set to the end + FastMap constraints; + constraints[2] = 1; + constraints[4] = 1; + constraints[5] = 2; + + Permutation::shared_ptr actConstrained(inference::PermutationCOLAMDGrouped(variableIndex, constraints)); + Permutation expConstrained(6); + expConstrained[0] = 0; + expConstrained[1] = 1; + expConstrained[2] = 3; + expConstrained[3] = 2; + expConstrained[4] = 4; + expConstrained[5] = 5; + EXPECT(assert_equal(expConstrained, *actConstrained)); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam/inference/tests/testJunctionTree.cpp b/gtsam/inference/tests/testJunctionTree.cpp index 16309abda..e9694eda3 100644 --- a/gtsam/inference/tests/testJunctionTree.cpp +++ b/gtsam/inference/tests/testJunctionTree.cpp @@ -35,7 +35,6 @@ using namespace gtsam; using namespace std; typedef JunctionTree SymbolicJunctionTree; -typedef BayesTree SymbolicBayesTree; /* ************************************************************************* * * x1 - x2 - x3 - x4 @@ -83,8 +82,7 @@ TEST( JunctionTree, eliminate) SymbolicJunctionTree jt(fg); SymbolicBayesTree::sharedClique actual = jt.eliminate(&EliminateSymbolic); - BayesNet bn(*SymbolicSequentialSolver(fg).eliminate( - &EliminateSymbolic)); + BayesNet bn(*SymbolicSequentialSolver(fg).eliminate()); SymbolicBayesTree expected(bn); // cout << "BT from JT:\n"; diff --git a/gtsam/inference/tests/testSymbolicBayesNet.cpp b/gtsam/inference/tests/testSymbolicBayesNet.cpp index 20abb6a71..06b1bded9 100644 --- a/gtsam/inference/tests/testSymbolicBayesNet.cpp +++ b/gtsam/inference/tests/testSymbolicBayesNet.cpp @@ -35,7 +35,7 @@ static const Index _C_ = 3; static const Index _D_ = 4; static const Index _E_ = 5; -IndexConditional::shared_ptr +static IndexConditional::shared_ptr B(new IndexConditional(_B_)), L(new IndexConditional(_L_, _B_)); diff --git a/gtsam/inference/tests/testVariableIndex.cpp b/gtsam/inference/tests/testVariableIndex.cpp index a990a5a87..412b3fa04 100644 --- a/gtsam/inference/tests/testVariableIndex.cpp +++ b/gtsam/inference/tests/testVariableIndex.cpp @@ -22,6 +22,7 @@ #include #include +using namespace std; using namespace gtsam; /* ************************************************************************* */ @@ -43,7 +44,9 @@ TEST(VariableIndex, augment) { VariableIndex actual(fg1); actual.augment(fg2); - CHECK(assert_equal(expected, actual)); + LONGS_EQUAL(16, actual.nEntries()); + LONGS_EQUAL(8, actual.nFactors()); + EXPECT(assert_equal(expected, actual)); } /* ************************************************************************* */ diff --git a/gtsam/linear/ConjugateGradientSolver.h b/gtsam/linear/ConjugateGradientSolver.h new file mode 100644 index 000000000..a89d7a10c --- /dev/null +++ b/gtsam/linear/ConjugateGradientSolver.h @@ -0,0 +1,76 @@ +/* ---------------------------------------------------------------------------- + + * 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 + +namespace gtsam { + +/** + * parameters for the conjugate gradient method + */ + +class ConjugateGradientParameters : public IterativeOptimizationParameters { +public: + typedef IterativeOptimizationParameters Base; + typedef boost::shared_ptr shared_ptr; + + size_t minIterations_; ///< minimum number of cg iterations + size_t maxIterations_; ///< maximum number of cg iterations + size_t reset_; ///< number of iterations before reset + double epsilon_rel_; ///< threshold for relative error decrease + double epsilon_abs_; ///< threshold for absolute error decrease + + ConjugateGradientParameters() + : minIterations_(1), maxIterations_(500), reset_(501), epsilon_rel_(1e-3), epsilon_abs_(1e-3){} + + ConjugateGradientParameters(size_t minIterations, size_t maxIterations, size_t reset, double epsilon_rel, double epsilon_abs) + : minIterations_(minIterations), maxIterations_(maxIterations), reset_(reset), epsilon_rel_(epsilon_rel), epsilon_abs_(epsilon_abs){} + + ConjugateGradientParameters(const ConjugateGradientParameters &p) + : Base(p), minIterations_(p.minIterations_), maxIterations_(p.maxIterations_), reset_(p.reset_), epsilon_rel_(p.epsilon_rel_), epsilon_abs_(p.epsilon_abs_) {} + + /* general interface */ + inline size_t minIterations() const { return minIterations_; } + inline size_t maxIterations() const { return maxIterations_; } + inline size_t reset() const { return reset_; } + inline double epsilon() const { return epsilon_rel_; } + inline double epsilon_rel() const { return epsilon_rel_; } + inline double epsilon_abs() const { return epsilon_abs_; } + + inline size_t getMinIterations() const { return minIterations_; } + inline size_t getMaxIterations() const { return maxIterations_; } + inline size_t getReset() const { return reset_; } + inline double getEpsilon() const { return epsilon_rel_; } + inline double getEpsilon_rel() const { return epsilon_rel_; } + inline double getEpsilon_abs() const { return epsilon_abs_; } + + inline void setMinIterations(size_t value) { minIterations_ = value; } + inline void setMaxIterations(size_t value) { maxIterations_ = value; } + inline void setReset(size_t value) { reset_ = value; } + inline void setEpsilon(double value) { epsilon_rel_ = value; } + inline void setEpsilon_rel(double value) { epsilon_rel_ = value; } + inline void setEpsilon_abs(double value) { epsilon_abs_ = value; } + + virtual void print(const std::string &s="") const { + Base::print(); + std::cout << "ConjugateGradientParameters: " + << "minIter = " << minIterations_ + << ", maxIter = " << maxIterations_ + << ", resetIter = " << reset_ + << ", eps_rel = " << epsilon_rel_ + << ", eps_abs = " << epsilon_abs_ + << std::endl; + } +}; + +} diff --git a/gtsam/linear/Errors.cpp b/gtsam/linear/Errors.cpp index 71d0cc003..65a52cce1 100644 --- a/gtsam/linear/Errors.cpp +++ b/gtsam/linear/Errors.cpp @@ -17,7 +17,6 @@ * @author Christian Potthast */ -#include #include #include @@ -56,7 +55,6 @@ struct equalsVector : public std::binary_function +#include +#include +#include +#include + #include +#include #include -#include -#include -#include - -#include +#include using namespace std; using namespace gtsam; - // trick from some reading group #define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL) #define REVERSE_FOREACH_PAIR( KEY, VAL, COL) BOOST_REVERSE_FOREACH (boost::tie(KEY,VAL),COL) @@ -99,6 +99,24 @@ void optimizeInPlace(const GaussianBayesNet& bn, VectorValues& x) { } } +/* ************************************************************************* */ +VectorValues backSubstitute(const GaussianBayesNet& bn, const VectorValues& input) { + VectorValues output = input; + BOOST_REVERSE_FOREACH(const boost::shared_ptr cg, bn) { + 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); + } + + BOOST_FOREACH(const boost::shared_ptr cg, bn) { + cg->scaleFrontalsBySigma(output); + } + + return output; +} + + /* ************************************************************************* */ // gy=inv(L)*gx by solving L*gy=gx. // gy=inv(R'*inv(Sigma))*gx @@ -224,12 +242,12 @@ double determinant(const GaussianBayesNet& bayesNet) { /* ************************************************************************* */ VectorValues gradient(const GaussianBayesNet& bayesNet, const VectorValues& x0) { - return gradient(FactorGraph(bayesNet), x0); + return gradient(GaussianFactorGraph(bayesNet), x0); } /* ************************************************************************* */ void gradientAtZero(const GaussianBayesNet& bayesNet, VectorValues& g) { - gradientAtZero(FactorGraph(bayesNet), g); + gradientAtZero(GaussianFactorGraph(bayesNet), g); } /* ************************************************************************* */ diff --git a/gtsam/linear/GaussianBayesNet.h b/gtsam/linear/GaussianBayesNet.h index 8c6e72357..fb179da92 100644 --- a/gtsam/linear/GaussianBayesNet.h +++ b/gtsam/linear/GaussianBayesNet.h @@ -106,6 +106,12 @@ namespace gtsam { * */ void optimizeGradientSearchInPlace(const GaussianBayesNet& bn, VectorValues& grad); + /** + * Backsubstitute + * gy=inv(R*inv(Sigma))*gx + */ + VectorValues backSubstitute(const GaussianBayesNet& bn, const VectorValues& gx); + /** * Transpose Backsubstitute * gy=inv(L)*gx by solving L*gy=gx. 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/GaussianBayesTree.cpp b/gtsam/linear/GaussianBayesTree.cpp index ae76d958e..04cb4a25a 100644 --- a/gtsam/linear/GaussianBayesTree.cpp +++ b/gtsam/linear/GaussianBayesTree.cpp @@ -18,7 +18,7 @@ */ #include -#include +#include namespace gtsam { @@ -35,27 +35,27 @@ void optimizeInPlace(const GaussianBayesTree& bayesTree, VectorValues& result) { } /* ************************************************************************* */ -VectorValues optimizeGradientSearch(const GaussianBayesTree& Rd) { +VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree) { tic(0, "Allocate VectorValues"); - VectorValues grad = *allocateVectorValues(Rd); + VectorValues grad = *allocateVectorValues(bayesTree); toc(0, "Allocate VectorValues"); - optimizeGradientSearchInPlace(Rd, grad); + optimizeGradientSearchInPlace(bayesTree, grad); return grad; } /* ************************************************************************* */ -void optimizeGradientSearchInPlace(const GaussianBayesTree& Rd, VectorValues& grad) { +void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad) { tic(1, "Compute Gradient"); // Compute gradient (call gradientAtZero function, which is defined for various linear systems) - gradientAtZero(Rd, grad); + gradientAtZero(bayesTree, grad); double gradientSqNorm = grad.dot(grad); toc(1, "Compute Gradient"); tic(2, "Compute R*g"); // Compute R * g - FactorGraph Rd_jfg(Rd); + FactorGraph Rd_jfg(bayesTree); Errors Rg = Rd_jfg * grad; toc(2, "Compute R*g"); diff --git a/gtsam/linear/GaussianBayesTree.h b/gtsam/linear/GaussianBayesTree.h index 8b581351c..91480d43a 100644 --- a/gtsam/linear/GaussianBayesTree.h +++ b/gtsam/linear/GaussianBayesTree.h @@ -25,13 +25,14 @@ namespace gtsam { +/// A Bayes Tree representing a Gaussian density typedef BayesTree GaussianBayesTree; /// optimize the BayesTree, starting from the root VectorValues optimize(const GaussianBayesTree& bayesTree); /// recursively optimize this conditional and all subtrees -void optimizeInPlace(const GaussianBayesTree& clique, VectorValues& result); +void optimizeInPlace(const GaussianBayesTree& bayesTree, VectorValues& result); namespace internal { template @@ -63,10 +64,10 @@ void optimizeInPlace(const typename BAYESTREE::sharedClique& clique, VectorValue * * \f[ \delta x = \hat\alpha g = \frac{-g^T g}{(R g)^T(R g)} \f] */ -VectorValues optimizeGradientSearch(const GaussianBayesTree& bn); +VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree); /** In-place version of optimizeGradientSearch requiring pre-allocated VectorValues \c x */ -void optimizeGradientSearchInPlace(const GaussianBayesTree& bn, VectorValues& grad); +void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad); /** * Compute the gradient of the energy function, diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index de459a00f..b35bffd3c 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -17,8 +17,10 @@ #include #include +#include #include +#include #include #include #include @@ -73,7 +75,7 @@ GaussianConditional::GaussianConditional(Index key, const Vector& d, const Matri const Matrix& R, const list >& parents, const Vector& sigmas) : IndexConditional(key, GetKeys(parents.size(), parents.begin(), parents.end())), rsd_(matrix_), sigmas_(sigmas) { assert(R.rows() <= R.cols()); - size_t dims[1+parents.size()+1]; + size_t* dims = (size_t*)alloca(sizeof(size_t)*(1+parents.size()+1)); // FIXME: alloca is bad, just ask Google. dims[0] = R.cols(); size_t j=1; std::list >::const_iterator parent=parents.begin(); @@ -95,7 +97,7 @@ GaussianConditional::GaussianConditional(const std::list Index_Matrix; BOOST_FOREACH(const Index_Matrix& term, terms) { @@ -129,16 +131,16 @@ GaussianConditional& GaussianConditional::operator=(const GaussianConditional& r } /* ************************************************************************* */ -void GaussianConditional::print(const string &s) const +void GaussianConditional::print(const string &s, const IndexFormatter& formatter) const { cout << s << ": density on "; for(const_iterator it = beginFrontals(); it != endFrontals(); ++it) { - cout << (boost::format("[%1%]")%(*it)).str() << " "; + cout << (boost::format("[%1%]")%(formatter(*it))).str() << " "; } cout << endl; gtsam::print(Matrix(get_R()),"R"); for(const_iterator it = beginParents() ; it != endParents() ; ++it ) { - gtsam::print(Matrix(get_S(it)), (boost::format("A[%1%]")%(*it)).str()); + gtsam::print(Matrix(get_S(it)), (boost::format("A[%1%]")%(formatter(*it))).str()); } gtsam::print(Vector(get_d()),"d"); gtsam::print(sigmas_,"sigmas"); @@ -182,41 +184,34 @@ JacobianFactor::shared_ptr GaussianConditional::toFactor() const { return JacobianFactor::shared_ptr(new JacobianFactor(*this)); } -/* ************************************************************************* */ -template -inline static void doSolveInPlace(const GaussianConditional& conditional, VALUES& x) { - - // Helper function to solve-in-place on a VectorValues or Permuted, - // called by GaussianConditional::solveInPlace(VectorValues&) and by - // GaussianConditional::solveInPlace(Permuted&). - - static const bool debug = false; - if(debug) conditional.print("Solving conditional in place"); - Vector xS = internal::extractVectorValuesSlices(x, conditional.beginParents(), conditional.endParents()); - xS = conditional.get_d() - conditional.get_S() * xS; - Vector soln = conditional.get_R().triangularView().solve(xS); - if(debug) { - gtsam::print(Matrix(conditional.get_R()), "Calling backSubstituteUpper on "); - gtsam::print(soln, "full back-substitution solution: "); - } - internal::writeVectorValuesSlices(soln, x, conditional.beginFrontals(), conditional.endFrontals()); -} - /* ************************************************************************* */ void GaussianConditional::solveInPlace(VectorValues& x) const { - doSolveInPlace(*this, x); // Call helper version above -} + static const bool debug = false; + if(debug) this->print("Solving conditional in place"); + Vector xS = internal::extractVectorValuesSlices(x, this->beginParents(), this->endParents()); + xS = this->get_d() - this->get_S() * xS; + Vector soln = this->get_R().triangularView().solve(xS); -/* ************************************************************************* */ -void GaussianConditional::solveInPlace(Permuted& x) const { - doSolveInPlace(*this, x); // Call helper version above + // Check for indeterminant solution + if(soln.unaryExpr(!boost::lambda::bind(ptr_fun(isfinite), boost::lambda::_1)).any()) + throw IndeterminantLinearSystemException(this->keys().front()); + + if(debug) { + gtsam::print(Matrix(this->get_R()), "Calling backSubstituteUpper on "); + gtsam::print(soln, "full back-substitution solution: "); + } + internal::writeVectorValuesSlices(soln, x, this->beginFrontals(), this->endFrontals()); } /* ************************************************************************* */ void GaussianConditional::solveTransposeInPlace(VectorValues& gy) const { Vector frontalVec = internal::extractVectorValuesSlices(gy, beginFrontals(), endFrontals()); - // TODO: verify permutation frontalVec = gtsam::backSubstituteUpper(frontalVec,Matrix(get_R())); + + // Check for indeterminant solution + if(frontalVec.unaryExpr(!boost::lambda::bind(ptr_fun(isfinite), boost::lambda::_1)).any()) + throw IndeterminantLinearSystemException(this->keys().front()); + GaussianConditional::const_iterator it; for (it = beginParents(); it!= endParents(); it++) { const Index i = *it; diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 2f91a6115..cde4f266f 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -80,7 +80,7 @@ public: GaussianConditional(); /** constructor */ - GaussianConditional(Index key); + explicit GaussianConditional(Index key); /** constructor with no parents * |Rx-d| @@ -138,7 +138,8 @@ public: GaussianConditional& operator=(const GaussianConditional& rhs); /** print */ - void print(const std::string& = "GaussianConditional") const; + void print(const std::string& = "GaussianConditional", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /** equals function */ bool equals(const GaussianConditional &cg, double tol = 1e-9) const; @@ -195,23 +196,6 @@ public: */ void solveInPlace(VectorValues& x) const; - /** - * Solves a conditional Gaussian and writes the solution into the entries of - * \c x for each frontal variable of the conditional (version for permuted - * VectorValues). The parents are assumed to have already been solved in - * and their values are read from \c x. This function works for multiple - * frontal variables. - * - * Given the Gaussian conditional with log likelihood \f$ |R x_f - (d - S x_s)|^2, - * where \f$ f \f$ are the frontal variables and \f$ s \f$ are the separator - * variables of this conditional, this solve function computes - * \f$ x_f = R^{-1} (d - S x_s) \f$ using back-substitution. - * - * @param x VectorValues structure with solved parents \f$ x_s \f$, and into which the - * solution \f$ x_f \f$ will be written. - */ - void solveInPlace(Permuted& x) const; - // functions for transpose backsubstitution /** diff --git a/gtsam/linear/GaussianDensity.cpp b/gtsam/linear/GaussianDensity.cpp index 97e42d9ba..c8fc4c21a 100644 --- a/gtsam/linear/GaussianDensity.cpp +++ b/gtsam/linear/GaussianDensity.cpp @@ -23,11 +23,11 @@ using namespace std; namespace gtsam { /* ************************************************************************* */ - void GaussianDensity::print(const string &s) const + void GaussianDensity::print(const string &s, const IndexFormatter& formatter) const { cout << s << ": density on "; for(const_iterator it = beginFrontals(); it != endFrontals(); ++it) - cout << (boost::format("[%1%]")%(*it)).str() << " "; + cout << (boost::format("[%1%]")%(formatter(*it))).str() << " "; cout << endl; gtsam::print(Matrix(get_R()),"R"); gtsam::print(Vector(get_d()),"d"); diff --git a/gtsam/linear/GaussianDensity.h b/gtsam/linear/GaussianDensity.h index 2c13e847c..4d4f673f9 100644 --- a/gtsam/linear/GaussianDensity.h +++ b/gtsam/linear/GaussianDensity.h @@ -54,7 +54,8 @@ namespace gtsam { } /// print - void print(const std::string& = "GaussianDensity") const; + void print(const std::string& = "GaussianDensity", + const IndexFormatter& formatter =DefaultIndexFormatter) const; /// Mean \f$ \mu = R^{-1} d \f$ Vector mean() const; diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h index 3fdad19c6..0d435ce17 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -20,8 +20,11 @@ #pragma once +#include #include +#include + #include #include @@ -80,7 +83,9 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; // Implementing Testable interface - virtual void print(const std::string& s = "") const = 0; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const = 0; + virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const = 0; virtual double error(const VectorValues& c) const = 0; /** 0.5*(A*x-b)'*D*(A*x-b) */ @@ -88,6 +93,16 @@ namespace gtsam { /** Return the dimension of the variable pointed to by the given key iterator */ virtual size_t getDim(const_iterator variable) const = 0; + /** Return the augmented information matrix represented by this GaussianFactor. + * The augmented information matrix contains the information matrix with an + * additional column holding the information vector, and an additional row + * holding the transpose of the information vector. The lower-right entry + * contains the constant error term (when \f$ \delta x = 0 \f$). The + * augmented information matrix is described in more detail in HessianFactor, + * which in fact stores an augmented information matrix. + */ + virtual Matrix computeInformation() const = 0; + /** Clone a factor (make a deep copy) */ virtual GaussianFactor::shared_ptr clone() const = 0; @@ -96,7 +111,16 @@ namespace gtsam { * to already be inverted. This acts just as a change-of-name for each * variable. The order of the variables within the factor is not changed. */ - virtual void permuteWithInverse(const Permutation& inversePermutation) { IndexFactor::permuteWithInverse(inversePermutation); } + virtual void permuteWithInverse(const Permutation& inversePermutation) { + IndexFactor::permuteWithInverse(inversePermutation); + } + + /** + * Construct the corresponding anti-factor to negate information + * stored stored in this factor. + * @return a HessianFactor with negated Hessian matrices + */ + virtual GaussianFactor::shared_ptr negate() const = 0; private: /** Serialization function */ diff --git a/gtsam/linear/GaussianFactorGraph.cpp b/gtsam/linear/GaussianFactorGraph.cpp index 853cf26ba..222f025a0 100644 --- a/gtsam/linear/GaussianFactorGraph.cpp +++ b/gtsam/linear/GaussianFactorGraph.cpp @@ -47,6 +47,13 @@ namespace gtsam { return keys; } + /* ************************************************************************* */ + std::pair + GaussianFactorGraph::eliminateFrontals(size_t nFrontals) const + { + return FactorGraph::eliminateFrontals(nFrontals, EliminateQR); + } + /* ************************************************************************* */ void GaussianFactorGraph::permuteWithInverse( const Permutation& inversePermutation) { @@ -159,16 +166,33 @@ namespace gtsam { } /* ************************************************************************* */ - Matrix GaussianFactorGraph::denseJacobian() const { + Matrix GaussianFactorGraph::augmentedJacobian() const { + // Convert to Jacobians + FactorGraph jfg; + jfg.reserve(this->size()); + BOOST_FOREACH(const sharedFactor& factor, *this) { + if(boost::shared_ptr jf = + boost::dynamic_pointer_cast(factor)) + jfg.push_back(jf); + else + jfg.push_back(boost::make_shared(*factor)); + } // combine all factors - JacobianFactor combined(*CombineJacobians(*convertCastFactors > (), VariableSlots(*this))); + JacobianFactor combined(*CombineJacobians(jfg, VariableSlots(*this))); return combined.matrix_augmented(); } + /* ************************************************************************* */ + std::pair GaussianFactorGraph::jacobian() const { + Matrix augmented = augmentedJacobian(); + return make_pair( + augmented.leftCols(augmented.cols()-1), + augmented.col(augmented.cols()-1)); + } + /* ************************************************************************* */ // Helper functions for Combine - static boost::tuple, size_t, size_t> countDims(const std::vector& factors, const VariableSlots& variableSlots) { + static boost::tuple, size_t, size_t> countDims(const FactorGraph& factors, const VariableSlots& variableSlots) { #ifndef NDEBUG vector varDims(variableSlots.size(), numeric_limits::max()); #else @@ -231,20 +255,6 @@ break; } toc(1, "countDims"); - if (debug) cout << "Sort rows" << endl; - tic(2, "sort rows"); - vector rowSources; - rowSources.reserve(m); - bool anyConstrained = false; - for (size_t sourceFactorI = 0; sourceFactorI < factors.size(); ++sourceFactorI) { - const JacobianFactor& sourceFactor(*factors[sourceFactorI]); - sourceFactor.collectInfo(sourceFactorI, rowSources); - if (sourceFactor.isConstrained()) anyConstrained = true; - } - assert(rowSources.size() == m); - std::sort(rowSources.begin(), rowSources.end()); - toc(2, "sort rows"); - if (debug) cout << "Allocate new factor" << endl; tic(3, "allocate"); JacobianFactor::shared_ptr combined(new JacobianFactor()); @@ -252,36 +262,47 @@ break; Vector sigmas(m); toc(3, "allocate"); - if (debug) cout << "Copy rows" << endl; - tic(4, "copy rows"); + if (debug) cout << "Copy blocks" << endl; + tic(4, "copy blocks"); + // Loop over slots in combined factor Index combinedSlot = 0; BOOST_FOREACH(const VariableSlots::value_type& varslot, variableSlots) { - for (size_t row = 0; row < m; ++row) { - const JacobianFactor::_RowSource& info(rowSources[row]); - const JacobianFactor& source(*factors[info.factorI]); - size_t sourceRow = info.factorRowI; - Index sourceSlot = varslot.second[info.factorI]; - combined->copyRow(source, sourceRow, sourceSlot, row, combinedSlot); + JacobianFactor::ABlock destSlot(combined->getA(combined->begin()+combinedSlot)); + // Loop over source factors + size_t nextRow = 0; + for(size_t factorI = 0; factorI < factors.size(); ++factorI) { + // Slot in source factor + const Index sourceSlot = varslot.second[factorI]; + const size_t sourceRows = factors[factorI]->rows(); + JacobianFactor::ABlock::RowsBlockXpr destBlock(destSlot.middleRows(nextRow, sourceRows)); + // Copy if exists in source factor, otherwise set zero + if(sourceSlot != numeric_limits::max()) + destBlock = factors[factorI]->getA(factors[factorI]->begin()+sourceSlot); + else + destBlock.setZero(); + nextRow += sourceRows; } ++combinedSlot; } - toc(4, "copy rows"); + toc(4, "copy blocks"); - if (debug) cout << "Copy rhs (b), sigma, and firstNonzeroBlocks" << endl; + if (debug) cout << "Copy rhs (b) and sigma" << endl; tic(5, "copy vectors"); - for (size_t row = 0; row < m; ++row) { - const JacobianFactor::_RowSource& info(rowSources[row]); - const JacobianFactor& source(*factors[info.factorI]); - const size_t sourceRow = info.factorRowI; - combined->getb()(row) = source.getb()(sourceRow); - sigmas(row) = source.get_model()->sigmas()(sourceRow); + bool anyConstrained = false; + // Loop over source factors + size_t nextRow = 0; + for(size_t factorI = 0; factorI < factors.size(); ++factorI) { + const size_t sourceRows = factors[factorI]->rows(); + combined->getb().segment(nextRow, sourceRows) = factors[factorI]->getb(); + sigmas.segment(nextRow, sourceRows) = factors[factorI]->get_model()->sigmas(); + if (factors[factorI]->isConstrained()) anyConstrained = true; + nextRow += sourceRows; } - combined->copyFNZ(m, variableSlots.size(),rowSources); toc(5, "copy vectors"); if (debug) cout << "Create noise model from sigmas" << endl; tic(6, "noise model"); - combined->setModel( anyConstrained,sigmas); + combined->setModel(anyConstrained, sigmas); toc(6, "noise model"); if (debug) cout << "Assert Invariants" << endl; @@ -304,9 +325,7 @@ break; } /* ************************************************************************* */ - static - FastMap findScatterAndDims - (const FactorGraph& factors) { + static FastMap findScatterAndDims(const FactorGraph& factors) { const bool debug = ISDEBUG("findScatterAndDims"); @@ -336,7 +355,7 @@ break; } /* ************************************************************************* */ - Matrix GaussianFactorGraph::denseHessian() const { + Matrix GaussianFactorGraph::augmentedHessian() const { Scatter scatter = findScatterAndDims(*this); @@ -354,6 +373,14 @@ break; return result; } + /* ************************************************************************* */ + std::pair GaussianFactorGraph::hessian() const { + Matrix augmented = augmentedHessian(); + return make_pair( + augmented.topLeftCorner(augmented.rows()-1, augmented.rows()-1), + augmented.col(augmented.rows()-1).head(augmented.rows()-1)); + } + /* ************************************************************************* */ GaussianFactorGraph::EliminationResult EliminateCholesky(const FactorGraph< GaussianFactor>& factors, size_t nrFrontals) { @@ -377,22 +404,14 @@ break; // Form Ab' * Ab tic(3, "combine"); - HessianFactor::shared_ptr // - combinedFactor(new HessianFactor(factors, dimensions, scatter)); + HessianFactor::shared_ptr combinedFactor(new HessianFactor(factors, dimensions, scatter)); toc(3, "combine"); // Do Cholesky, note that after this, the lower triangle still contains // some untouched non-zeros that should be zero. We zero them while // extracting submatrices next. tic(4, "partial Cholesky"); - try { - combinedFactor->partialCholesky(nrFrontals); - } catch - (std::exception &ex) { // catch exception from Cholesky - combinedFactor->print("combinedFactor"); - string reason = "EliminateCholesky failed while trying to eliminate the combined factor"; - throw invalid_argument(reason); - } + combinedFactor->partialCholesky(nrFrontals); toc(4, "partial Cholesky"); @@ -494,67 +513,134 @@ break; return EliminateQR(factors, nrFrontals); else { GaussianFactorGraph::EliminationResult ret; -#ifdef NDEBUG - static const bool diag = false; -#else - static const bool diag = !ISDEBUG("NoCholeskyDiagnostics"); -#endif - if (!diag) { - tic(2, "EliminateCholesky"); - ret = EliminateCholesky(factors, nrFrontals); - toc(2, "EliminateCholesky"); - } else { - try { - tic(2, "EliminateCholesky"); - ret = EliminateCholesky(factors, nrFrontals); - toc(2, "EliminateCholesky"); - } catch (const exception& e) { - cout << "Exception in EliminateCholesky: " << e.what() << endl; - SETDEBUG("EliminateCholesky", true); - SETDEBUG("updateATA", true); - SETDEBUG("JacobianFactor::eliminate", true); - SETDEBUG("JacobianFactor::Combine", true); - SETDEBUG("choleskyPartial", true); - factors.print("Combining factors: "); - EliminateCholesky(factors, nrFrontals); - throw; - } - } - - const bool checkCholesky = ISDEBUG("EliminateGaussian Check Cholesky"); - if (checkCholesky) { - GaussianFactorGraph::EliminationResult expected; - FactorGraph jacobians = convertToJacobians(factors); - try { - // Compare with QR - expected = EliminateJacobians(jacobians, nrFrontals); - } catch (...) { - cout << "Exception in QR" << endl; - throw; - } - - H actual_factor(*ret.second); - H expected_factor(*expected.second); - if (!assert_equal(*expected.first, *ret.first, 100.0) - || !assert_equal(expected_factor, actual_factor, 1.0)) { - cout << "Cholesky and QR do not agree" << endl; - - SETDEBUG("EliminateCholesky", true); - SETDEBUG("updateATA", true); - SETDEBUG("JacobianFactor::eliminate", true); - SETDEBUG("JacobianFactor::Combine", true); - jacobians.print("Jacobian Factors: "); - EliminateJacobians(jacobians, nrFrontals); - EliminateCholesky(factors, nrFrontals); - factors.print("Combining factors: "); - - throw runtime_error("Cholesky and QR do not agree"); - } - } - + tic(2, "EliminateCholesky"); + ret = EliminateCholesky(factors, nrFrontals); + toc(2, "EliminateCholesky"); return ret; } } // \EliminatePreferCholesky + + + /* ************************************************************************* */ + static JacobianFactor::shared_ptr convertToJacobianFactorPtr(const GaussianFactor::shared_ptr &gf) { + JacobianFactor::shared_ptr result = boost::dynamic_pointer_cast(gf); + if( !result ) { + result = boost::make_shared(*gf); // Convert any non-Jacobian factors to Jacobians (e.g. Hessian -> Jacobian with Cholesky) + } + return result; + } + + /* ************************************************************************* */ + Errors operator*(const GaussianFactorGraph& fg, const VectorValues& x) { + Errors e; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + e.push_back((*Ai)*x); + } + return e; + } + + /* ************************************************************************* */ + void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, Errors& e) { + multiplyInPlace(fg,x,e.begin()); + } + + /* ************************************************************************* */ + void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, const Errors::iterator& e) { + Errors::iterator ei = e; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + *ei = (*Ai)*x; + ei++; + } + } + + /* ************************************************************************* */ + // x += alpha*A'*e + void transposeMultiplyAdd(const GaussianFactorGraph& fg, double alpha, const Errors& e, VectorValues& x) { + // For each factor add the gradient contribution + Errors::const_iterator ei = e.begin(); + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + Ai->transposeMultiplyAdd(alpha,*(ei++),x); + } + } + + /* ************************************************************************* */ + VectorValues gradient(const GaussianFactorGraph& fg, const VectorValues& x0) { + // It is crucial for performance to make a zero-valued clone of x + VectorValues g = VectorValues::Zero(x0); + Errors e; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + e.push_back(Ai->error_vector(x0)); + } + transposeMultiplyAdd(fg, 1.0, e, g); + return g; + } + + /* ************************************************************************* */ + void gradientAtZero(const GaussianFactorGraph& fg, VectorValues& g) { + // Zero-out the gradient + g.setZero(); + Errors e; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + e.push_back(-Ai->getb()); + } + transposeMultiplyAdd(fg, 1.0, e, g); + } + + /* ************************************************************************* */ + void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r) { + Index i = 0 ; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + r[i] = Ai->getb(); + i++; + } + VectorValues Ax = VectorValues::SameStructure(r); + multiply(fg,x,Ax); + axpy(-1.0,Ax,r); + } + + /* ************************************************************************* */ + void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r) { + r.vector() = Vector::Zero(r.dim()); + Index i = 0; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + SubVector &y = r[i]; + for(JacobianFactor::const_iterator j = Ai->begin(); j != Ai->end(); ++j) { + y += Ai->getA(j) * x[*j]; + } + ++i; + } + } + + /* ************************************************************************* */ + void transposeMultiply(const GaussianFactorGraph& fg, const VectorValues &r, VectorValues &x) { + x.vector() = Vector::Zero(x.dim()); + Index i = 0; + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + for(JacobianFactor::const_iterator j = Ai->begin(); j != Ai->end(); ++j) { + x[*j] += Ai->getA(j).transpose() * r[i]; + } + ++i; + } + } + + /* ************************************************************************* */ + boost::shared_ptr gaussianErrors_(const GaussianFactorGraph& fg, const VectorValues& x) { + boost::shared_ptr e(new Errors); + BOOST_FOREACH(const GaussianFactor::shared_ptr& Ai_G, fg) { + JacobianFactor::shared_ptr Ai = convertToJacobianFactorPtr(Ai_G); + e->push_back(Ai->error_vector(x)); + } + return e; + } + } // namespace gtsam diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index 1f66b5b4c..5e6e792be 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -31,26 +31,6 @@ namespace gtsam { - class SharedDiagonal; - - /** return A*x-b - * \todo Make this a member function - affects SubgraphPreconditioner */ - template - Errors gaussianErrors(const FactorGraph& fg, const VectorValues& x) { - return *gaussianErrors_(fg, x); - } - - /** shared pointer version - * \todo Make this a member function - affects SubgraphPreconditioner */ - template - boost::shared_ptr gaussianErrors_(const FactorGraph& fg, const VectorValues& x) { - boost::shared_ptr e(new Errors); - BOOST_FOREACH(const typename FACTOR::shared_ptr& factor, fg) { - e->push_back(factor->error_vector(x)); - } - return e; - } - /** * A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e. * Factor == GaussianFactor @@ -85,32 +65,32 @@ namespace gtsam { push_back(fg); } - /** Add a Jacobian factor */ - void add(const boost::shared_ptr& factor) { - factors_.push_back(boost::shared_ptr(factor)); + /** Add a factor by value - makes a copy */ + void add(const GaussianFactor& factor) { + factors_.push_back(factor.clone()); } - /** Add a Hessian factor */ - void add(const boost::shared_ptr& factor) { - factors_.push_back(boost::shared_ptr(factor)); + /** Add a factor by pointer - stores pointer without copying the factor */ + void add(const sharedFactor& factor) { + factors_.push_back(factor); } /** Add a null factor */ void add(const Vector& b) { - add(JacobianFactor::shared_ptr(new JacobianFactor(b))); + add(JacobianFactor(b)); } /** Add a unary factor */ void add(Index key1, const Matrix& A1, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,b,model))); + add(JacobianFactor(key1,A1,b,model)); } /** Add a binary factor */ void add(Index key1, const Matrix& A1, Index key2, const Matrix& A2, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,key2,A2,b,model))); + add(JacobianFactor(key1,A1,key2,A2,b,model)); } /** Add a ternary factor */ @@ -118,13 +98,13 @@ namespace gtsam { Index key2, const Matrix& A2, Index key3, const Matrix& A3, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,key2,A2,key3,A3,b,model))); + add(JacobianFactor(key1,A1,key2,A2,key3,A3,b,model)); } /** Add an n-ary factor */ void add(const std::vector > &terms, const Vector &b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(terms,b,model))); + add(JacobianFactor(terms,b,model)); } /** @@ -134,6 +114,16 @@ namespace gtsam { typedef FastSet Keys; Keys keys() const; + + /** Eliminate the first \c n frontal variables, returning the resulting + * conditional and remaining factor graph - this is very inefficient for + * eliminating all variables, to do that use EliminationTree or + * JunctionTree. Note that this version simply calls + * FactorGraph::eliminateFrontals with EliminateQR as the + * eliminate function argument. + */ + std::pair eliminateFrontals(size_t nFrontals) const; + /** Permute the variables in the factors */ void permuteWithInverse(const Permutation& inversePermutation); @@ -151,9 +141,9 @@ namespace gtsam { } /** - * static function that combines two factor graphs - * @param const &lfg1 Linear factor graph - * @param const &lfg2 Linear factor graph + * Static function that combines two factor graphs. + * @param lfg1 Linear factor graph + * @param lfg2 Linear factor graph * @return a new combined factor graph */ static GaussianFactorGraph combine2(const GaussianFactorGraph& lfg1, @@ -180,15 +170,43 @@ namespace gtsam { Matrix sparseJacobian_() const; /** - * Return a dense \f$ m \times n \f$ Jacobian matrix, augmented with b - * with standard deviations are baked into A and b + * Return a dense \f$ [ \;A\;b\; ] \in \mathbb{R}^{m \times n+1} \f$ + * Jacobian matrix, augmented with b with the noise models baked + * into A and b. The negative log-likelihood is + * \f$ \frac{1}{2} \Vert Ax-b \Vert^2 \f$. See also + * GaussianFactorGraph::jacobian and GaussianFactorGraph::sparseJacobian. */ - Matrix denseJacobian() const; + Matrix augmentedJacobian() const; + + /** + * Return the dense Jacobian \f$ A \f$ and right-hand-side \f$ b \f$, + * with the noise models baked into A and b. The negative log-likelihood + * is \f$ \frac{1}{2} \Vert Ax-b \Vert^2 \f$. See also + * GaussianFactorGraph::augmentedJacobian and + * GaussianFactorGraph::sparseJacobian. + */ + std::pair jacobian() const; /** - * Return a dense \f$ n \times n \f$ Hessian matrix, augmented with \f$ A^T b \f$ + * Return a dense \f$ \Lambda \in \mathbb{R}^{n+1 \times n+1} \f$ Hessian + * matrix, augmented with the information vector \f$ \eta \f$. The + * augmented Hessian is + \f[ \left[ \begin{array}{ccc} + \Lambda & \eta \\ + \eta^T & c + \end{array} \right] \f] + and the negative log-likelihood is + \f$ \frac{1}{2} x^T \Lambda x + \eta^T x + c \f$. */ - Matrix denseHessian() const; + Matrix augmentedHessian() const; + + /** + * Return the dense Hessian \f$ \Lambda \f$ and information vector + * \f$ \eta \f$, with the noise models baked in. The negative log-likelihood + * is \frac{1}{2} x^T \Lambda x + \eta^T x + c. See also + * GaussianFactorGraph::augmentedHessian. + */ + std::pair hessian() const; private: /** Serialization function */ @@ -202,7 +220,7 @@ namespace gtsam { /** * Combine and eliminate several factors. - * \ingroup LinearSolving + * \addtogroup LinearSolving */ JacobianFactor::shared_ptr CombineJacobians( const FactorGraph& factors, @@ -223,7 +241,7 @@ namespace gtsam { * @param nrFrontals Number of frontal variables to eliminate. * @return The conditional and remaining factor - * \ingroup LinearSolving + * \addtogroup LinearSolving */ GaussianFactorGraph::EliminationResult EliminateJacobians(const FactorGraph< JacobianFactor>& factors, size_t nrFrontals = 1); @@ -238,7 +256,7 @@ namespace gtsam { * @param nrFrontals Number of frontal variables to eliminate. * @return The conditional and remaining factor - * \ingroup LinearSolving + * \addtogroup LinearSolving */ GaussianFactorGraph::EliminationResult EliminateQR(const FactorGraph< GaussianFactor>& factors, size_t nrFrontals = 1); @@ -260,7 +278,7 @@ namespace gtsam { * @param nrFrontals Number of frontal variables to eliminate. * @return The conditional and remaining factor - * \ingroup LinearSolving + * \addtogroup LinearSolving */ GaussianFactorGraph::EliminationResult EliminatePreferCholesky(const FactorGraph< GaussianFactor>& factors, size_t nrFrontals = 1); @@ -281,9 +299,59 @@ namespace gtsam { * @param nrFrontals Number of frontal variables to eliminate. * @return The conditional and remaining factor - * \ingroup LinearSolving + * \addtogroup LinearSolving */ GaussianFactorGraph::EliminationResult EliminateCholesky(const FactorGraph< GaussianFactor>& factors, size_t nrFrontals = 1); + /****** Linear Algebra Opeations ******/ + + /** return A*x */ + Errors operator*(const GaussianFactorGraph& fg, const VectorValues& x); + + /** In-place version e <- A*x that overwrites e. */ + void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, Errors& e); + + /** In-place version e <- A*x that takes an iterator. */ + void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, const Errors::iterator& e); + + /** x += alpha*A'*e */ + void transposeMultiplyAdd(const GaussianFactorGraph& fg, double alpha, const Errors& e, VectorValues& x); + + /** + * Compute the gradient of the energy function, + * \f$ \nabla_{x=x_0} \left\Vert \Sigma^{-1} A x - b \right\Vert^2 \f$, + * centered around \f$ x = x_0 \f$. + * The gradient is \f$ A^T(Ax-b) \f$. + * @param fg The Jacobian factor graph $(A,b)$ + * @param x0 The center about which to compute the gradient + * @return The gradient as a VectorValues + */ + VectorValues gradient(const GaussianFactorGraph& fg, const VectorValues& x0); + + /** + * Compute the gradient of the energy function, + * \f$ \nabla_{x=0} \left\Vert \Sigma^{-1} A x - b \right\Vert^2 \f$, + * centered around zero. + * The gradient is \f$ A^T(Ax-b) \f$. + * @param fg The Jacobian factor graph $(A,b)$ + * @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues + * @return The gradient as a VectorValues + */ + void gradientAtZero(const GaussianFactorGraph& fg, VectorValues& g); + + /* matrix-vector operations */ + void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r); + void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r); + void transposeMultiply(const GaussianFactorGraph& fg, const VectorValues &r, VectorValues &x); + + /** shared pointer version + * \todo Make this a member function - affects SubgraphPreconditioner */ + boost::shared_ptr gaussianErrors_(const GaussianFactorGraph& fg, const VectorValues& x); + + /** return A*x-b + * \todo Make this a member function - affects SubgraphPreconditioner */ + inline Errors gaussianErrors(const GaussianFactorGraph& fg, const VectorValues& x) { + return *gaussianErrors_(fg, x); } + } // namespace gtsam 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..2f35845b8 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 */ @@ -48,20 +48,8 @@ public: /** Override update_internal to also keep track of variable dimensions. */ template void update_internal(const FACTORGRAPH& newFactors, Cliques& orphans) { - - Super::update_internal(newFactors, orphans, &EliminateQR); - - // update dimensions - BOOST_FOREACH(const typename FACTORGRAPH::sharedFactor& factor, newFactors) { - for(typename FACTORGRAPH::FactorType::const_iterator key = factor->begin(); key != factor->end(); ++key) { - if(*key >= dims_.size()) - dims_.resize(*key + 1); - if(dims_[*key] == 0) - dims_[*key] = factor->getDim(key); - else - assert(dims_[*key] == factor->getDim(key)); - } - } + Super::update_internal(newFactors, orphans, &EliminateQR); // TODO: why does this force QR? + update_dimensions(newFactors); } template @@ -70,11 +58,29 @@ public: this->update_internal(newFactors, orphans); } + template + inline void update_dimensions(const FACTORGRAPH& newFactors) { + BOOST_FOREACH(const typename FACTORGRAPH::sharedFactor& factor, newFactors) { + for(typename FACTORGRAPH::FactorType::const_iterator key = factor->begin(); key != factor->end(); ++key) { + if(*key >= dims_.size()) + dims_.resize(*key + 1); + if(dims_[*key] == 0) + dims_[*key] = factor->getDim(key); + else + assert(dims_[*key] == factor->getDim(key)); + } + } + } + void clear() { Super::clear(); dims_.clear(); } + // access + const Dims& dims() const { return dims_; } ///< Const access to dimensions structure + Dims& dims() { return dims_; } ///< non-const access to dimensions structure (advanced interface) + friend VectorValues optimize(const GaussianISAM&); /** return marginal on any variable as a factor, Bayes net, or mean/cov */ diff --git a/gtsam/linear/GaussianJunctionTree.h b/gtsam/linear/GaussianJunctionTree.h index 3d4227b93..b97998a12 100644 --- a/gtsam/linear/GaussianJunctionTree.h +++ b/gtsam/linear/GaussianJunctionTree.h @@ -35,7 +35,7 @@ namespace gtsam { * create a BayesTree. In both cases, you need to provide a basic * GaussianFactorGraph::Eliminate function that will be used to * - * \ingroup Multifrontal + * \addtogroup Multifrontal */ class GaussianJunctionTree: public JunctionTree { diff --git a/gtsam/linear/GaussianMultifrontalSolver.h b/gtsam/linear/GaussianMultifrontalSolver.h index 6adde1aa5..322aacfc6 100644 --- a/gtsam/linear/GaussianMultifrontalSolver.h +++ b/gtsam/linear/GaussianMultifrontalSolver.h @@ -100,6 +100,8 @@ public: * Compute the marginal joint over a set of variables, by integrating out * all of the other variables. This function returns the result as a factor * graph. + * + * NOTE: This function is limited to computing a joint on 2 variables */ GaussianFactorGraph::shared_ptr jointFactorGraph(const std::vector& js) const; @@ -116,7 +118,7 @@ public: * all of the other variables. This function returns the result as a mean * vector and covariance matrix. Compared to marginalCanonical, which * returns a GaussianConditional, this function back-substitutes the R factor - * to obtain the mean, then computes \Sigma = (R^T * R)^-1. + * to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$. */ Matrix marginalCovariance(Index j) const; 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..8fd8e2dbb 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 @@ -115,7 +115,7 @@ public: * all of the other variables. This function returns the result as a mean * vector and covariance matrix. Compared to marginalCanonical, which * returns a GaussianConditional, this function back-substitutes the R factor - * to obtain the mean, then computes \Sigma = (R^T * R)^-1. + * to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$. */ Matrix marginalCovariance(Index j) const; diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index b1f829005..e152738fb 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -47,13 +48,7 @@ string SlotEntry::toString() const { /* ************************************************************************* */ void HessianFactor::assertInvariants() const { -#ifndef NDEBUG - // Check for non-finite values - for(size_t i=0; i<(size_t) matrix_.rows(); ++i) - for(size_t j=i; j<(size_t) matrix_.cols(); ++j) - if(!isfinite(matrix_(i,j))) - throw invalid_argument("HessianFactor contains non-finite matrix entries."); -#endif + GaussianFactor::assertInvariants(); // The base class checks for unique keys } /* ************************************************************************* */ @@ -188,7 +183,7 @@ HessianFactor::HessianFactor(const std::vector& js, const std::vector& factors, if (debug) cout << "Combining " << factors.size() << " factors" << endl; BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors) { - shared_ptr hessian(boost::dynamic_pointer_cast(factor)); - if (hessian) - updateATA(*hessian, scatter); - else { - JacobianFactor::shared_ptr jacobianFactor(boost::dynamic_pointer_cast(factor)); - if (jacobianFactor) + if(factor) { + if(shared_ptr hessian = boost::dynamic_pointer_cast(factor)) + updateATA(*hessian, scatter); + else if(JacobianFactor::shared_ptr jacobianFactor = boost::dynamic_pointer_cast(factor)) updateATA(*jacobianFactor, scatter); else throw invalid_argument("GaussianFactor is neither Hessian nor Jacobian"); @@ -292,11 +285,11 @@ HessianFactor& HessianFactor::operator=(const HessianFactor& rhs) { } /* ************************************************************************* */ -void HessianFactor::print(const std::string& s) const { +void HessianFactor::print(const std::string& s, const IndexFormatter& formatter) const { cout << s << "\n"; cout << " keys: "; for(const_iterator key=this->begin(); key!=this->end(); ++key) - cout << *key << "(" << this->getDim(key) << ") "; + cout << formatter(*key) << "(" << this->getDim(key) << ") "; cout << "\n"; gtsam::print(Matrix(info_.range(0,info_.nBlocks(), 0,info_.nBlocks()).selfadjointView()), "Ab^T * Ab: "); } @@ -315,13 +308,8 @@ bool HessianFactor::equals(const GaussianFactor& lf, double tol) const { } /* ************************************************************************* */ -double HessianFactor::constantTerm() const { - return info_(this->size(), this->size())(0,0); -} - -/* ************************************************************************* */ -HessianFactor::constColumn HessianFactor::linearTerm() const { - return info_.rangeColumn(0, this->size(), this->size(), 0); +Matrix HessianFactor::computeInformation() const { + return info_.full().selfadjointView(); } /* ************************************************************************* */ @@ -345,7 +333,7 @@ void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatte // First build an array of slots tic(1, "slots"); - size_t slots[update.size()]; + size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google. size_t slot = 0; BOOST_FOREACH(Index j, update) { slots[slot] = scatter.find(j)->second.slot; @@ -360,7 +348,6 @@ void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatte // Apply updates to the upper triangle tic(3, "update"); - assert(this->info_.nBlocks() - 1 == scatter.size()); for(size_t j2=0; j2info_.nBlocks()-1 : slots[j2]; for(size_t j1=0; j1<=j2; ++j1) { @@ -399,7 +386,7 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt // First build an array of slots tic(1, "slots"); - size_t slots[update.size()]; + size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google. size_t slot = 0; BOOST_FOREACH(Index j, update) { slots[slot] = scatter.find(j)->second.slot; @@ -437,7 +424,6 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt // Apply updates to the upper triangle tic(3, "update"); - assert(this->info_.nBlocks() - 1 == scatter.size()); for(size_t j2=0; j2info_.nBlocks()-1 : slots[j2]; for(size_t j1=0; j1<=j2; ++j1) { @@ -468,7 +454,8 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt /* ************************************************************************* */ void HessianFactor::partialCholesky(size_t nrFrontals) { - choleskyPartial(matrix_, info_.offset(nrFrontals)); + if(!choleskyPartial(matrix_, info_.offset(nrFrontals))) + throw IndeterminantLinearSystemException(this->keys().front()); } /* ************************************************************************* */ @@ -506,4 +493,24 @@ GaussianConditional::shared_ptr HessianFactor::splitEliminatedFactor(size_t nrFr return conditional; } +/* ************************************************************************* */ +GaussianFactor::shared_ptr HessianFactor::negate() const { + // Copy Hessian Blocks from Hessian factor and invert + std::vector js; + std::vector Gs; + std::vector gs; + double f; + js.insert(js.end(), begin(), end()); + for(size_t i = 0; i < js.size(); ++i){ + for(size_t j = i; j < js.size(); ++j){ + Gs.push_back( -info(begin()+i, begin()+j) ); + } + gs.push_back( -linearTerm(begin()+i) ); + } + f = -constantTerm(); + + // Create the Anti-Hessian Factor from the negated blocks + return HessianFactor::shared_ptr(new HessianFactor(js, Gs, gs, f)); +} + } // gtsam diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index d6ff23159..9e4ed2074 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -1,309 +1,366 @@ -/* ---------------------------------------------------------------------------- - - * 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 HessianFactor.h - * @brief Contains the HessianFactor class, a general quadratic factor - * @author Richard Roberts - * @date Dec 8, 2010 - */ - -#pragma once - -#include -#include -#include - -// Forward declarations for friend unit tests -class ConversionConstructorHessianFactorTest; -class Constructor1HessianFactorTest; -class Constructor1bHessianFactorTest; -class combineHessianFactorTest; - - -namespace gtsam { - - // Forward declarations - class JacobianFactor; - class SharedDiagonal; - class GaussianConditional; - template class BayesNet; - - // Definition of Scatter, which is an intermediate data structure used when - // building a HessianFactor incrementally, to get the keys in the right - // order. - struct SlotEntry { - size_t slot; - size_t dimension; - SlotEntry(size_t _slot, size_t _dimension) - : slot(_slot), dimension(_dimension) {} - std::string toString() const; - }; - typedef FastMap Scatter; - - /** - * @brief A Gaussian factor using the canonical parameters (information form) - * - * HessianFactor implements a general quadratic factor of the form - * \f[ E(x) = 0.5 x^T G x - x^T g + 0.5 f \f] - * that stores the matrix \f$ G \f$, the vector \f$ g \f$, and the constant term \f$ f \f$. - * - * When \f$ G \f$ is positive semidefinite, this factor represents a Gaussian, - * in which case \f$ G \f$ is the information matrix \f$ \Lambda \f$, - * \f$ g \f$ is the information vector \f$ \eta \f$, and \f$ f \f$ is the residual - * sum-square-error at the mean, when \f$ x = \mu \f$. - * - * Indeed, the negative log-likelihood of a Gaussian is (up to a constant) - * @f$ E(x) = 0.5(x-\mu)^T P^{-1} (x-\mu) @f$ - * with @f$ \mu @f$ the mean and @f$ P @f$ the covariance matrix. Expanding the product we get - * @f[ - * E(x) = 0.5 x^T P^{-1} x - x^T P^{-1} \mu + 0.5 \mu^T P^{-1} \mu - * @f] - * We define the Information matrix (or Hessian) @f$ \Lambda = P^{-1} @f$ - * and the information vector @f$ \eta = P^{-1} \mu = \Lambda \mu @f$ - * to arrive at the canonical form of the Gaussian: - * @f[ - * E(x) = 0.5 x^T \Lambda x - x^T \eta + 0.5 \mu^T \Lambda \mu - * @f] - * - * This factor is one of the factors that can be in a GaussianFactorGraph. - * It may be returned from NonlinearFactor::linearize(), but is also - * used internally to store the Hessian during Cholesky elimination. - * - * This can represent a quadratic factor with characteristics that cannot be - * represented using a JacobianFactor (which has the form - * \f$ E(x) = \Vert Ax - b \Vert^2 \f$ and stores the Jacobian \f$ A \f$ - * and error vector \f$ b \f$, i.e. is a sum-of-squares factor). For example, - * a HessianFactor need not be positive semidefinite, it can be indefinite or - * even negative semidefinite. - * - * If a HessianFactor is indefinite or negative semi-definite, then in order - * for solving the linear system to be possible, - * the Hessian of the full system must be positive definite (i.e. when all - * small Hessians are combined, the result must be positive definite). If - * this is not the case, an error will occur during elimination. - * - * This class stores G, g, and f as an augmented matrix HessianFactor::matrix_. - * The upper-left n x n blocks of HessianFactor::matrix_ store the upper-right - * triangle of G, the upper-right-most column of length n of HessianFactor::matrix_ - * stores g, and the lower-right entry of HessianFactor::matrix_ stores f, i.e. - * \code - HessianFactor::matrix_ = [ G11 G12 G13 ... g1 - 0 G22 G23 ... g2 - 0 0 G33 ... g3 - : : : : - 0 0 0 ... f ] - \endcode - Blocks can be accessed as follows: - \code - G11 = info(begin(), begin()); - G12 = info(begin(), begin()+1); - G23 = info(begin()+1, begin()+2); - g2 = linearTerm(begin()+1); - f = constantTerm(); - ....... - \endcode - */ - class HessianFactor : public GaussianFactor { - protected: - typedef Matrix InfoMatrix; ///< The full augmented Hessian - typedef SymmetricBlockView BlockInfo; ///< A blockwise view of the Hessian - typedef GaussianFactor Base; ///< Typedef to base class - - InfoMatrix matrix_; ///< The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'*H*[x -1] - BlockInfo info_; ///< The block view of the full information matrix. - - /** Update the factor by adding the information from the JacobianFactor - * (used internally during elimination). - * @param update The JacobianFactor containing the new information to add - * @param scatter A mapping from variable index to slot index in this HessianFactor - */ - void updateATA(const JacobianFactor& update, const Scatter& scatter); - - /** Update the factor by adding the information from the HessianFactor - * (used internally during elimination). - * @param update The HessianFactor containing the new information to add - * @param scatter A mapping from variable index to slot index in this HessianFactor - */ - void updateATA(const HessianFactor& update, const Scatter& scatter); - - public: - - typedef boost::shared_ptr shared_ptr; ///< A shared_ptr to this - typedef BlockInfo::Block Block; ///< A block from the Hessian matrix - typedef BlockInfo::constBlock constBlock; ///< A block from the Hessian matrix (const version) - typedef BlockInfo::Column Column; ///< A column containing the linear term h - typedef BlockInfo::constColumn constColumn; ///< A column containing the linear term h (const version) - - /** Copy constructor */ - HessianFactor(const HessianFactor& gf); - - /** default constructor for I/O */ - HessianFactor(); - - /** Construct a unary factor. G is the quadratic term (Hessian matrix), g - * the linear term (a vector), and f the constant term. The quadratic - * error is: - * 0.5*(f - 2*x'*g + x'*G*x) - */ - HessianFactor(Index j, const Matrix& G, const Vector& g, double f); - - /** Construct a unary factor, given a mean and covariance matrix. - * error is 0.5*(x-mu)'*inv(Sigma)*(x-mu) - */ - HessianFactor(Index j, const Vector& mu, const Matrix& Sigma); - - /** Construct a binary factor. Gxx are the upper-triangle blocks of the - * quadratic term (the Hessian matrix), gx the pieces of the linear vector - * term, and f the constant term. - * JacobianFactor error is \f[ 0.5* (Ax-b)' M (Ax-b) = 0.5*x'A'MAx - x'A'Mb + 0.5*b'Mb \f] - * HessianFactor error is \f[ 0.5*(x'Gx - 2x'g + f) = 0.5*x'Gx - x'*g + 0.5*f \f] - * So, with \f$ A = [A1 A2] \f$ and \f$ G=A*'M*A = [A1';A2']*M*[A1 A2] \f$ we have - \code - n1*n1 G11 = A1'*M*A1 - n1*n2 G12 = A1'*M*A2 - n2*n2 G22 = A2'*M*A2 - n1*1 g1 = A1'*M*b - n2*1 g2 = A2'*M*b - 1*1 f = b'*M*b - \endcode - */ - HessianFactor(Index j1, Index j2, - const Matrix& G11, const Matrix& G12, const Vector& g1, - const Matrix& G22, const Vector& g2, double f); - - /** Construct a ternary factor. Gxx are the upper-triangle blocks of the - * quadratic term (the Hessian matrix), gx the pieces of the linear vector - * term, and f the constant term. - */ - HessianFactor(Index j1, Index j2, Index j3, - const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1, - const Matrix& G22, const Matrix& G23, const Vector& g2, - const Matrix& G33, const Vector& g3, double f); - - /** Construct an n-way factor. Gs contains the upper-triangle blocks of the - * quadratic term (the Hessian matrix) provided in row-order, gs the pieces - * of the linear vector term, and f the constant term. - */ - HessianFactor(const std::vector& js, const std::vector& Gs, - const std::vector& gs, double f); - - /** Construct from Conditional Gaussian */ - HessianFactor(const GaussianConditional& cg); - - /** Convert from a JacobianFactor (computes A^T * A) or HessianFactor */ - HessianFactor(const GaussianFactor& factor); - - /** Special constructor used in EliminateCholesky which combines the given factors */ - HessianFactor(const FactorGraph& factors, - const std::vector& dimensions, const Scatter& scatter); - - /** Destructor */ - virtual ~HessianFactor() {} - - /** Aassignment operator */ - HessianFactor& operator=(const HessianFactor& rhs); - - /** Clone this JacobianFactor */ - virtual GaussianFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - shared_ptr(new HessianFactor(*this))); - } - - /** Print the factor for debugging and testing (implementing Testable) */ - virtual void print(const std::string& s = "") const; - - /** Compare to another factor for testing (implementing Testable) */ - virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const; - - /** Evaluate the factor error f(x), see above. */ - virtual double error(const VectorValues& c) const; /** 0.5*[x -1]'*H*[x -1] (also see constructor documentation) */ - - /** Return the dimension of the variable pointed to by the given key iterator - * todo: Remove this in favor of keeping track of dimensions with variables? - * @param variable An iterator pointing to the slot in this factor. You can - * use, for example, begin() + 2 to get the 3rd variable in this factor. - */ - virtual size_t getDim(const_iterator variable) const { return info_(variable-this->begin(), 0).rows(); } - - /** Return the number of columns and rows of the Hessian matrix */ - size_t rows() const { return info_.rows(); } - - /** Return a view of the block at (j1,j2) of the upper-triangular part of the - * information matrix \f$ H \f$, no data is copied. See HessianFactor class documentation - * above to explain that only the upper-triangular part of the information matrix is stored - * and returned by this function. - * @param j1 Which block row to get, as an iterator pointing to the slot in this factor. You can - * use, for example, begin() + 2 to get the 3rd variable in this factor. - * @param j2 Which block column to get, as an iterator pointing to the slot in this factor. You can - * use, for example, begin() + 2 to get the 3rd variable in this factor. - * @return A view of the requested block, not a copy. - */ - constBlock info(const_iterator j1, const_iterator j2) const { return info_(j1-begin(), j2-begin()); } - - /** Return the upper-triangular part of the full *augmented* information matrix, - * as described above. See HessianFactor class documentation above to explain that only the - * upper-triangular part of the information matrix is stored and returned by this function. - */ - constBlock info() const { return info_.full(); } - - /** Return the constant term \f$ f \f$ as described above - * @return The constant term \f$ f \f$ - */ - double constantTerm() const; - - /** Return the part of linear term \f$ g \f$ as described above corresponding to the requested variable. - * @param j Which block row to get, as an iterator pointing to the slot in this factor. You can - * use, for example, begin() + 2 to get the 3rd variable in this factor. - * @return The linear term \f$ g \f$ */ - constColumn linearTerm(const_iterator j) const { return info_.column(j-begin(), size(), 0); } - - /** Return the complete linear term \f$ g \f$ as described above. - * @return The linear term \f$ g \f$ */ - constColumn linearTerm() const; - - // Friend unit test classes - friend class ::ConversionConstructorHessianFactorTest; - friend class ::Constructor1HessianFactorTest; - friend class ::Constructor1bHessianFactorTest; - friend class ::combineHessianFactorTest; - - // Friend JacobianFactor for conversion - friend class JacobianFactor; - - // used in eliminateCholesky: - - /** - * Do Cholesky. Note that after this, the lower triangle still contains - * some untouched non-zeros that should be zero. We zero them while - * extracting submatrices in splitEliminatedFactor. Frank says :-( - */ - void partialCholesky(size_t nrFrontals); - - /** split partially eliminated factor */ - boost::shared_ptr splitEliminatedFactor(size_t nrFrontals); - - /** assert invariants */ - void assertInvariants() const; - - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor); - ar & BOOST_SERIALIZATION_NVP(info_); - ar & BOOST_SERIALIZATION_NVP(matrix_); - } - }; - -} - +/* ---------------------------------------------------------------------------- + + * 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 HessianFactor.h + * @brief Contains the HessianFactor class, a general quadratic factor + * @author Richard Roberts + * @date Dec 8, 2010 + */ + +#pragma once + +#include +#include +#include + +// Forward declarations for friend unit tests +class ConversionConstructorHessianFactorTest; +class Constructor1HessianFactorTest; +class Constructor1bHessianFactorTest; +class combineHessianFactorTest; + + +namespace gtsam { + + // Forward declarations + class JacobianFactor; + class GaussianConditional; + template class BayesNet; + + // Definition of Scatter, which is an intermediate data structure used when + // building a HessianFactor incrementally, to get the keys in the right + // order. + struct SlotEntry { + size_t slot; + size_t dimension; + SlotEntry(size_t _slot, size_t _dimension) + : slot(_slot), dimension(_dimension) {} + std::string toString() const; + }; + typedef FastMap Scatter; + + /** + * @brief A Gaussian factor using the canonical parameters (information form) + * + * HessianFactor implements a general quadratic factor of the form + * \f[ E(x) = 0.5 x^T G x - x^T g + 0.5 f \f] + * that stores the matrix \f$ G \f$, the vector \f$ g \f$, and the constant term \f$ f \f$. + * + * When \f$ G \f$ is positive semidefinite, this factor represents a Gaussian, + * in which case \f$ G \f$ is the information matrix \f$ \Lambda \f$, + * \f$ g \f$ is the information vector \f$ \eta \f$, and \f$ f \f$ is the residual + * sum-square-error at the mean, when \f$ x = \mu \f$. + * + * Indeed, the negative log-likelihood of a Gaussian is (up to a constant) + * @f$ E(x) = 0.5(x-\mu)^T P^{-1} (x-\mu) @f$ + * with @f$ \mu @f$ the mean and @f$ P @f$ the covariance matrix. Expanding the product we get + * @f[ + * E(x) = 0.5 x^T P^{-1} x - x^T P^{-1} \mu + 0.5 \mu^T P^{-1} \mu + * @f] + * We define the Information matrix (or Hessian) @f$ \Lambda = P^{-1} @f$ + * and the information vector @f$ \eta = P^{-1} \mu = \Lambda \mu @f$ + * to arrive at the canonical form of the Gaussian: + * @f[ + * E(x) = 0.5 x^T \Lambda x - x^T \eta + 0.5 \mu^T \Lambda \mu + * @f] + * + * This factor is one of the factors that can be in a GaussianFactorGraph. + * It may be returned from NonlinearFactor::linearize(), but is also + * used internally to store the Hessian during Cholesky elimination. + * + * This can represent a quadratic factor with characteristics that cannot be + * represented using a JacobianFactor (which has the form + * \f$ E(x) = \Vert Ax - b \Vert^2 \f$ and stores the Jacobian \f$ A \f$ + * and error vector \f$ b \f$, i.e. is a sum-of-squares factor). For example, + * a HessianFactor need not be positive semidefinite, it can be indefinite or + * even negative semidefinite. + * + * If a HessianFactor is indefinite or negative semi-definite, then in order + * for solving the linear system to be possible, + * the Hessian of the full system must be positive definite (i.e. when all + * small Hessians are combined, the result must be positive definite). If + * this is not the case, an error will occur during elimination. + * + * This class stores G, g, and f as an augmented matrix HessianFactor::matrix_. + * The upper-left n x n blocks of HessianFactor::matrix_ store the upper-right + * triangle of G, the upper-right-most column of length n of HessianFactor::matrix_ + * stores g, and the lower-right entry of HessianFactor::matrix_ stores f, i.e. + * \code + HessianFactor::matrix_ = [ G11 G12 G13 ... g1 + 0 G22 G23 ... g2 + 0 0 G33 ... g3 + : : : : + 0 0 0 ... f ] + \endcode + Blocks can be accessed as follows: + \code + G11 = info(begin(), begin()); + G12 = info(begin(), begin()+1); + G23 = info(begin()+1, begin()+2); + g2 = linearTerm(begin()+1); + f = constantTerm(); + ....... + \endcode + */ + class HessianFactor : public GaussianFactor { + protected: + typedef Matrix InfoMatrix; ///< The full augmented Hessian + typedef SymmetricBlockView BlockInfo; ///< A blockwise view of the Hessian + typedef GaussianFactor Base; ///< Typedef to base class + + InfoMatrix matrix_; ///< The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'*H*[x -1] + BlockInfo info_; ///< The block view of the full information matrix. + + public: + + typedef boost::shared_ptr shared_ptr; ///< A shared_ptr to this + typedef BlockInfo::Block Block; ///< A block from the Hessian matrix + typedef BlockInfo::constBlock constBlock; ///< A block from the Hessian matrix (const version) + typedef BlockInfo::Column Column; ///< A column containing the linear term h + typedef BlockInfo::constColumn constColumn; ///< A column containing the linear term h (const version) + + /** Copy constructor */ + HessianFactor(const HessianFactor& gf); + + /** default constructor for I/O */ + HessianFactor(); + + /** Construct a unary factor. G is the quadratic term (Hessian matrix), g + * the linear term (a vector), and f the constant term. The quadratic + * error is: + * 0.5*(f - 2*x'*g + x'*G*x) + */ + HessianFactor(Index j, const Matrix& G, const Vector& g, double f); + + /** Construct a unary factor, given a mean and covariance matrix. + * error is 0.5*(x-mu)'*inv(Sigma)*(x-mu) + */ + HessianFactor(Index j, const Vector& mu, const Matrix& Sigma); + + /** Construct a binary factor. Gxx are the upper-triangle blocks of the + * quadratic term (the Hessian matrix), gx the pieces of the linear vector + * term, and f the constant term. + * JacobianFactor error is \f[ 0.5* (Ax-b)' M (Ax-b) = 0.5*x'A'MAx - x'A'Mb + 0.5*b'Mb \f] + * HessianFactor error is \f[ 0.5*(x'Gx - 2x'g + f) = 0.5*x'Gx - x'*g + 0.5*f \f] + * So, with \f$ A = [A1 A2] \f$ and \f$ G=A*'M*A = [A1';A2']*M*[A1 A2] \f$ we have + \code + n1*n1 G11 = A1'*M*A1 + n1*n2 G12 = A1'*M*A2 + n2*n2 G22 = A2'*M*A2 + n1*1 g1 = A1'*M*b + n2*1 g2 = A2'*M*b + 1*1 f = b'*M*b + \endcode + */ + HessianFactor(Index j1, Index j2, + const Matrix& G11, const Matrix& G12, const Vector& g1, + const Matrix& G22, const Vector& g2, double f); + + /** Construct a ternary factor. Gxx are the upper-triangle blocks of the + * quadratic term (the Hessian matrix), gx the pieces of the linear vector + * term, and f the constant term. + */ + HessianFactor(Index j1, Index j2, Index j3, + const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1, + const Matrix& G22, const Matrix& G23, const Vector& g2, + const Matrix& G33, const Vector& g3, double f); + + /** Construct an n-way factor. Gs contains the upper-triangle blocks of the + * quadratic term (the Hessian matrix) provided in row-order, gs the pieces + * of the linear vector term, and f the constant term. + */ + HessianFactor(const std::vector& js, const std::vector& Gs, + const std::vector& gs, double f); + + /** Construct from Conditional Gaussian */ + explicit HessianFactor(const GaussianConditional& cg); + + /** Convert from a JacobianFactor (computes A^T * A) or HessianFactor */ + explicit HessianFactor(const GaussianFactor& factor); + + /** Special constructor used in EliminateCholesky which combines the given factors */ + HessianFactor(const FactorGraph& factors, + const std::vector& dimensions, const Scatter& scatter); + + /** Destructor */ + virtual ~HessianFactor() {} + + /** Aassignment operator */ + HessianFactor& operator=(const HessianFactor& rhs); + + /** Clone this JacobianFactor */ + virtual GaussianFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + shared_ptr(new HessianFactor(*this))); + } + + /** Print the factor for debugging and testing (implementing Testable) */ + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; + + /** Compare to another factor for testing (implementing Testable) */ + virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const; + + /** Evaluate the factor error f(x), see above. */ + virtual double error(const VectorValues& c) const; /** 0.5*[x -1]'*H*[x -1] (also see constructor documentation) */ + + /** Return the dimension of the variable pointed to by the given key iterator + * todo: Remove this in favor of keeping track of dimensions with variables? + * @param variable An iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + */ + virtual size_t getDim(const_iterator variable) const { return info_(variable-this->begin(), 0).rows(); } + + /** Return the number of columns and rows of the Hessian matrix */ + size_t rows() const { return info_.rows(); } + + /** + * Construct the corresponding anti-factor to negate information + * stored stored in this factor. + * @return a HessianFactor with negated Hessian matrices + */ + virtual GaussianFactor::shared_ptr negate() const; + + /** Return a view of the block at (j1,j2) of the upper-triangular part of the + * information matrix \f$ H \f$, no data is copied. See HessianFactor class documentation + * above to explain that only the upper-triangular part of the information matrix is stored + * and returned by this function. + * @param j1 Which block row to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @param j2 Which block column to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @return A view of the requested block, not a copy. + */ + constBlock info(const_iterator j1, const_iterator j2) const { return info_(j1-begin(), j2-begin()); } + + /** Return a view of the block at (j1,j2) of the upper-triangular part of the + * information matrix \f$ H \f$, no data is copied. See HessianFactor class documentation + * above to explain that only the upper-triangular part of the information matrix is stored + * and returned by this function. + * @param j1 Which block row to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @param j2 Which block column to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @return A view of the requested block, not a copy. + */ + Block info(iterator j1, iterator j2) { return info_(j1-begin(), j2-begin()); } + + /** Return the upper-triangular part of the full *augmented* information matrix, + * as described above. See HessianFactor class documentation above to explain that only the + * upper-triangular part of the information matrix is stored and returned by this function. + */ + constBlock info() const { return info_.full(); } + + /** Return the upper-triangular part of the full *augmented* information matrix, + * as described above. See HessianFactor class documentation above to explain that only the + * upper-triangular part of the information matrix is stored and returned by this function. + */ + Block info() { return info_.full(); } + + /** Return the constant term \f$ f \f$ as described above + * @return The constant term \f$ f \f$ + */ + double constantTerm() const { return info_(this->size(), this->size())(0,0); } + + /** Return the constant term \f$ f \f$ as described above + * @return The constant term \f$ f \f$ + */ + double& constantTerm() { return info_(this->size(), this->size())(0,0); } + + /** Return the part of linear term \f$ g \f$ as described above corresponding to the requested variable. + * @param j Which block row to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @return The linear term \f$ g \f$ */ + constColumn linearTerm(const_iterator j) const { return info_.column(j-begin(), size(), 0); } + + /** Return the part of linear term \f$ g \f$ as described above corresponding to the requested variable. + * @param j Which block row to get, as an iterator pointing to the slot in this factor. You can + * use, for example, begin() + 2 to get the 3rd variable in this factor. + * @return The linear term \f$ g \f$ */ + Column linearTerm(iterator j) { return info_.column(j-begin(), size(), 0); } + + /** Return the complete linear term \f$ g \f$ as described above. + * @return The linear term \f$ g \f$ */ + constColumn linearTerm() const { return info_.rangeColumn(0, this->size(), this->size(), 0); } + + /** Return the complete linear term \f$ g \f$ as described above. + * @return The linear term \f$ g \f$ */ + Column linearTerm() { return info_.rangeColumn(0, this->size(), this->size(), 0); } + + /** Return the augmented information matrix represented by this GaussianFactor. + * The augmented information matrix contains the information matrix with an + * additional column holding the information vector, and an additional row + * holding the transpose of the information vector. The lower-right entry + * contains the constant error term (when \f$ \delta x = 0 \f$). The + * augmented information matrix is described in more detail in HessianFactor, + * which in fact stores an augmented information matrix. + * + * For HessianFactor, this is the same as info() except that this function + * returns a complete symmetric matrix whereas info() returns a matrix where + * only the upper triangle is valid, but should be interpreted as symmetric. + * This is because info() returns only a reference to the internal + * representation of the augmented information matrix, which stores only the + * upper triangle. + */ + virtual Matrix computeInformation() const; + + // Friend unit test classes + friend class ::ConversionConstructorHessianFactorTest; + friend class ::Constructor1HessianFactorTest; + friend class ::Constructor1bHessianFactorTest; + friend class ::combineHessianFactorTest; + + // Friend JacobianFactor for conversion + friend class JacobianFactor; + + // used in eliminateCholesky: + + /** + * Do Cholesky. Note that after this, the lower triangle still contains + * some untouched non-zeros that should be zero. We zero them while + * extracting submatrices in splitEliminatedFactor. Frank says :-( + */ + void partialCholesky(size_t nrFrontals); + + /** split partially eliminated factor */ + boost::shared_ptr splitEliminatedFactor(size_t nrFrontals); + + /** Update the factor by adding the information from the JacobianFactor + * (used internally during elimination). + * @param update The JacobianFactor containing the new information to add + * @param scatter A mapping from variable index to slot index in this HessianFactor + */ + void updateATA(const JacobianFactor& update, const Scatter& scatter); + + /** Update the factor by adding the information from the HessianFactor + * (used internally during elimination). + * @param update The HessianFactor containing the new information to add + * @param scatter A mapping from variable index to slot index in this HessianFactor + */ + void updateATA(const HessianFactor& update, const Scatter& scatter); + + /** assert invariants */ + void assertInvariants() const; + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor); + ar & BOOST_SERIALIZATION_NVP(info_); + ar & BOOST_SERIALIZATION_NVP(matrix_); + } + }; + +} + diff --git a/gtsam/linear/IterativeOptimizationParameters.h b/gtsam/linear/IterativeOptimizationParameters.h deleted file mode 100644 index b38f6ab1a..000000000 --- a/gtsam/linear/IterativeOptimizationParameters.h +++ /dev/null @@ -1,232 +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 IterativeOptimizationParameters.h - * @date Oct 22, 2010 - * @author Yong-Dian Jian - */ - -#pragma once - -#include -#include -#include - -namespace gtsam { - -/* parameters for combinatorial preconditioner */ -struct CombinatorialParameters { - - enum Group { /* group of variables */ - BLOCK = 0, /* utilize the inherent block structure */ - SCALAR /* break the block variables into scalars */ - } group_; - - enum Type { /* subgraph specification */ - JACOBI = 0, /* block diagonal */ - SPTREE, /* spanning tree */ - GSP, /* gspn, n = 0: all factors, n = 1: all unary factors, n = 2: spanning tree, etc .. */ - KOUTIS, /* implement Koutis2011Focs */ - } type_; - - enum Weight { /* how to weigh the graph edges */ - EQUAL = 0, /* 0: every block edge has equal weight */ - RHS_2NORM, /* 1: use the 2-norm of the rhs */ - LHS_FNORM, /* 2: use the frobenius norm of the lhs */ - RAW, /* 3: use raw scalar weight for the scalar case */ - } weight_ ; - - int complexity_;/* a parameter for the subgraph complexity */ - int hessian_; /* 0: do nothing, 1: use whole block hessian */ - - CombinatorialParameters(): group_(BLOCK), type_(JACOBI), weight_(EQUAL), complexity_(0), hessian_(1) {} - CombinatorialParameters(Group group, Type type, Weight weight, int complexity, int hessian) - : group_(group), type_(type), weight_(weight), complexity_(complexity), hessian_(hessian) {} - - inline Group group() const { return group_; } - inline Type type() const { return type_; } - inline Weight weight() const { return weight_; } - inline int complexity() const { return complexity_; } - inline int hessian() const { return hessian_; } - - inline bool isScalar() const { return group_ == SCALAR; } - inline bool isBlock() const { return group_ == BLOCK; } - inline bool isStatic() const { return (type_ == JACOBI || weight_ == EQUAL) ? true : false;} - inline bool isDynamic() const { return !isStatic(); } - - inline void print() const { - - const std::string groupStr[2] = {"block", "scalar"}; - const std::string typeStr[4] = {"jacobi", "sptree", "gsp", "koutis"}; - const std::string weightStr[4] = {"equal", "rhs-2norm", "lhs-form", "raw"}; - - std::cout << "CombinatorialParameters: " - << "group = " << groupStr[group_] - << ", type = " << typeStr[type_] - << ", weight = " << weightStr[weight_] - << ", complexity = " << complexity_ - << ", hessian = " << hessian_ << std::endl; - } -}; - -/* parameters for the preconditioner */ -struct PreconditionerParameters { - - typedef boost::shared_ptr shared_ptr; - - enum Kernel { /* Preconditioner Kernel */ - GTSAM = 0, /* Jacobian Factor Graph of GTSAM */ - CHOLMOD /* Cholmod Sparse */ - } kernel_ ; - - enum Type { /* preconditioner type */ - Combinatorial = 0 /* combinatorial preconditioner */ - } type_; - - CombinatorialParameters combinatorial_; - - enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */ - - PreconditionerParameters(): kernel_(CHOLMOD), type_(Combinatorial), verbosity_(SILENT) {} - PreconditionerParameters(Kernel kernel, const CombinatorialParameters &combinatorial, Verbosity verbosity) - : kernel_(kernel), type_(Combinatorial), combinatorial_(combinatorial), verbosity_(verbosity) {} - - /* general interface */ - inline Kernel kernel() const { return kernel_; } - inline Type type() const { return type_; } - inline const CombinatorialParameters & combinatorial() const { return combinatorial_; } - inline Verbosity verbosity() const { return verbosity_; } - - - void print() const { - const std::string kernelStr[2] = {"gtsam", "cholmod"}; - const std::string typeStr[1] = {"combinatorial"}; - - std::cout << "PreconditionerParameters: " - << "kernel = " << kernelStr[kernel_] - << ", type = " << typeStr[type_] << std::endl; - combinatorial_.print(); - } -}; - -/* parameters for the conjugate gradient method */ -struct ConjugateGradientParameters { - - size_t minIterations_; /* minimum number of cg iterations */ - size_t maxIterations_; /* maximum number of cg iterations */ - size_t reset_; /* number of iterations before reset */ - double epsilon_rel_; /* threshold for relative error decrease */ - double epsilon_abs_; /* threshold for absolute error decrease */ - - enum BLASKernel { /* Matrix Operation Kernel */ - GTSAM = 0, /* Jacobian Factor Graph of GTSAM */ - SBM, /* Sparse Block Matrix */ - SBM_MT /* Sparse Block Matrix Multithreaded */ - } blas_kernel_; - - size_t degree_; /* the maximum degree of the vertices to be eliminated before doing cg */ - - enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */ - - ConjugateGradientParameters() - : minIterations_(1), maxIterations_(500), reset_(501), epsilon_rel_(1e-3), epsilon_abs_(1e-3), - blas_kernel_(GTSAM), degree_(0), verbosity_(SILENT) {} - - ConjugateGradientParameters(size_t minIterations, size_t maxIterations, size_t reset, - double epsilon_rel, double epsilon_abs, BLASKernel blas = GTSAM, size_t degree = 0, Verbosity verbosity = SILENT) - : minIterations_(minIterations), maxIterations_(maxIterations), reset_(reset), - epsilon_rel_(epsilon_rel), epsilon_abs_(epsilon_abs), blas_kernel_(blas), degree_(degree), verbosity_(verbosity) {} - - /* general interface */ - inline size_t minIterations() const { return minIterations_; } - inline size_t maxIterations() const { return maxIterations_; } - inline size_t reset() const { return reset_; } - inline double epsilon() const { return epsilon_rel_; } - inline double epsilon_rel() const { return epsilon_rel_; } - inline double epsilon_abs() const { return epsilon_abs_; } - inline BLASKernel blas_kernel() const { return blas_kernel_; } - inline size_t degree() const { return degree_; } - inline Verbosity verbosity() const { return verbosity_; } - - void print() const { - const std::string blasStr[4] = {"gtsam", "sbm", "sbm-mt"}; - std::cout << "ConjugateGradientParameters: " - << "blas = " << blasStr[blas_kernel_] - << ", minIter = " << minIterations_ - << ", maxIter = " << maxIterations_ - << ", resetIter = " << reset_ - << ", eps_rel = " << epsilon_rel_ - << ", eps_abs = " << epsilon_abs_ - << ", degree = " << degree_ - << std::endl; - } -}; - -/* parameters for iterative linear solvers */ -struct IterativeOptimizationParameters { - -public: - - typedef boost::shared_ptr shared_ptr; - - PreconditionerParameters preconditioner_; - ConjugateGradientParameters cg_; - enum Kernel { PCG = 0 /*, PCGPlus*/, LSPCG } kernel_ ; /* Iterative Method Kernel */ - enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */ - -public: - - IterativeOptimizationParameters() - : preconditioner_(), cg_(), kernel_(PCG), verbosity_(SILENT) {} - - IterativeOptimizationParameters(const IterativeOptimizationParameters &p) : - preconditioner_(p.preconditioner_), cg_(p.cg_), kernel_(p.kernel_), verbosity_(p.verbosity_) {} - - IterativeOptimizationParameters( - const PreconditionerParameters &p, const ConjugateGradientParameters &c, Kernel kernel = PCG, Verbosity verbosity = SILENT) - : preconditioner_(p), cg_(c), kernel_(kernel), verbosity_(verbosity) {} - - /* general interface */ - inline Kernel kernel() const { return kernel_; } - inline Verbosity verbosity() const { return verbosity_; } - - /* utility */ - inline const PreconditionerParameters& preconditioner() const { return preconditioner_; } - inline const ConjugateGradientParameters& cg() const { return cg_; } - - /* interface to preconditioner parameters */ - inline PreconditionerParameters::Kernel preconditioner_kernel() const { return preconditioner_.kernel(); } - inline PreconditionerParameters::Type type() const { return preconditioner_.type(); } - - /* interface to cg parameters */ - inline size_t minIterations() const { return cg_.minIterations(); } - inline size_t maxIterations() const { return cg_.maxIterations(); } - inline size_t reset() const { return cg_.reset(); } - inline double epsilon() const { return cg_.epsilon_rel(); } - inline double epsilon_rel() const { return cg_.epsilon_rel(); } - inline double epsilon_abs() const { return cg_.epsilon_abs(); } - inline size_t degree() const { return cg_.degree(); } - inline ConjugateGradientParameters::BLASKernel blas_kernel() const { return cg_.blas_kernel(); } - - void print(const std::string &s="") const { - const std::string kernelStr[2] = {"pcg", "lspcg"}; - std::cout << s << std::endl - << "IterativeOptimizationParameters: " - << "kernel = " << kernelStr[kernel_] << std::endl; - cg_.print(); - preconditioner_.print(); - - } - -}; - -} diff --git a/gtsam/linear/IterativeSolver.cpp b/gtsam/linear/IterativeSolver.cpp new file mode 100644 index 000000000..2bba3e12b --- /dev/null +++ b/gtsam/linear/IterativeSolver.cpp @@ -0,0 +1,50 @@ +/** + * @file IterativeSolver.cpp + * @brief + * @date Sep 3, 2012 + * @author Yong-Dian Jian + */ + +#include +#include +#include + +namespace gtsam { + +std::string IterativeOptimizationParameters::getKernel() const { return kernelTranslator(kernel_); } +std::string IterativeOptimizationParameters::getVerbosity() const { return verbosityTranslator(verbosity_); } +void IterativeOptimizationParameters::setKernel(const std::string &src) { kernel_ = kernelTranslator(src); } +void IterativeOptimizationParameters::setVerbosity(const std::string &src) { verbosity_ = verbosityTranslator(src); } + +IterativeOptimizationParameters::Kernel IterativeOptimizationParameters::kernelTranslator(const std::string &src) { + std::string s = src; boost::algorithm::to_upper(s); + if (s == "CG") return IterativeOptimizationParameters::CG; + /* default is cg */ + else return IterativeOptimizationParameters::CG; +} + +IterativeOptimizationParameters::Verbosity IterativeOptimizationParameters::verbosityTranslator(const std::string &src) { + std::string s = src; boost::algorithm::to_upper(s); + if (s == "SILENT") return IterativeOptimizationParameters::SILENT; + else if (s == "COMPLEXITY") return IterativeOptimizationParameters::COMPLEXITY; + else if (s == "ERROR") return IterativeOptimizationParameters::ERROR; + /* default is default */ + else return IterativeOptimizationParameters::SILENT; +} + +std::string IterativeOptimizationParameters::kernelTranslator(IterativeOptimizationParameters::Kernel k) { + if ( k == CG ) return "CG"; + else return "UNKNOWN"; +} + +std::string IterativeOptimizationParameters::verbosityTranslator(IterativeOptimizationParameters::Verbosity verbosity) { + if (verbosity == SILENT) return "SILENT"; + else if (verbosity == COMPLEXITY) return "COMPLEXITY"; + else if (verbosity == ERROR) return "ERROR"; + else return "UNKNOWN"; +} + + +} + + diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index 7b1c1e630..7946874bb 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -9,44 +9,67 @@ * -------------------------------------------------------------------------- */ -/** - * @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 +#include namespace gtsam { -class IterativeSolver { + /** + * parameters for iterative linear solvers + */ + class IterativeOptimizationParameters { -public: + public: - typedef boost::shared_ptr shared_ptr; - typedef IterativeOptimizationParameters Parameters; + typedef boost::shared_ptr shared_ptr; + enum Kernel { CG = 0 } kernel_ ; ///< Iterative Method Kernel + enum Verbosity { SILENT = 0, COMPLEXITY, ERROR } verbosity_; -protected: + public: - Parameters::shared_ptr parameters_ ; + IterativeOptimizationParameters(const IterativeOptimizationParameters &p) + : kernel_(p.kernel_), verbosity_(p.verbosity_) {} -public: + IterativeOptimizationParameters(const Kernel kernel = CG, const Verbosity verbosity = SILENT) + : kernel_(kernel), verbosity_(verbosity) {} - IterativeSolver(): parameters_(new Parameters()) {} - IterativeSolver(const IterativeSolver &solver) : parameters_(solver.parameters_) {} - IterativeSolver(const Parameters::shared_ptr& parameters) : parameters_(parameters) {} - IterativeSolver(const Parameters ¶meters) : parameters_(new Parameters(parameters)) {} + virtual ~IterativeOptimizationParameters() {} - virtual ~IterativeSolver() {} + /* general interface */ + inline Kernel kernel() const { return kernel_; } + inline Verbosity verbosity() const { return verbosity_; } - virtual VectorValues::shared_ptr optimize () = 0; + /* matlab interface */ + std::string getKernel() const ; + std::string getVerbosity() const; + void setKernel(const std::string &s) ; + void setVerbosity(const std::string &s) ; - Parameters::shared_ptr parameters() { return parameters_ ; } -}; + void print() const { + std::cout << "IterativeOptimizationParameters: " + << "kernel = " << kernelTranslator(kernel_) + << ", verbosity = " << verbosityTranslator(verbosity_) << std::endl; + } + + static Kernel kernelTranslator(const std::string &s); + static Verbosity verbosityTranslator(const std::string &s); + static std::string kernelTranslator(Kernel k); + static std::string verbosityTranslator(Verbosity v); + }; + + class IterativeSolver { + public: + typedef boost::shared_ptr shared_ptr; + IterativeSolver() {} + virtual ~IterativeSolver() {} + + /* interface to the nonlinear optimizer */ + virtual VectorValues optimize () = 0; + /* update interface to the nonlinear optimizer */ + virtual void replaceFactors(const GaussianFactorGraph::shared_ptr &factorGraph, const double lambda) {} + }; } diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index e2facec40..759be4948 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -15,6 +15,7 @@ * @date Dec 8, 2010 */ +#include #include #include #include @@ -29,15 +30,16 @@ #include #include #include -#include -#include +#include +//#include +//#include #include #include #include using namespace std; -using namespace boost::lambda; +//using namespace boost::lambda; namespace gtsam { @@ -46,40 +48,48 @@ namespace gtsam { #ifndef NDEBUG GaussianFactor::assertInvariants(); // The base class checks for unique keys assert((size() == 0 && Ab_.rows() == 0 && Ab_.nBlocks() == 0) || size()+1 == Ab_.nBlocks()); - assert(firstNonzeroBlocks_.size() == Ab_.rows()); - for(size_t i=0; i(&gf)) + *this = JacobianFactor(*rhs); + else if(const HessianFactor* rhs = dynamic_cast(&gf)) + *this = JacobianFactor(*rhs); + else + throw std::invalid_argument("In JacobianFactor(const GaussianFactor& rhs), rhs is neither a JacobianFactor nor a HessianFactor"); + assertInvariants(); + } + /* ************************************************************************* */ JacobianFactor::JacobianFactor() : Ab_(matrix_) { assertInvariants(); } /* ************************************************************************* */ - JacobianFactor::JacobianFactor(const Vector& b_in) : firstNonzeroBlocks_(b_in.size(), 0), Ab_(matrix_) { + JacobianFactor::JacobianFactor(const Vector& b_in) : Ab_(matrix_) { size_t dims[] = { 1 }; Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+1, b_in.size())); getb() = b_in; + model_ = noiseModel::Unit::Create(this->rows()); assertInvariants(); } /* ************************************************************************* */ JacobianFactor::JacobianFactor(Index i1, const Matrix& A1, const Vector& b, const SharedDiagonal& model) : - GaussianFactor(i1), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { + GaussianFactor(i1), model_(model), Ab_(matrix_) { + + if(model->dim() != (size_t) b.size()) + throw InvalidNoiseModel(b.size(), model->dim()); + size_t dims[] = { A1.cols(), 1}; Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+2, b.size())); Ab_(0) = A1; @@ -90,7 +100,11 @@ namespace gtsam { /* ************************************************************************* */ JacobianFactor::JacobianFactor(Index i1, const Matrix& A1, Index i2, const Matrix& A2, const Vector& b, const SharedDiagonal& model) : - GaussianFactor(i1,i2), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { + GaussianFactor(i1,i2), model_(model), Ab_(matrix_) { + + if(model->dim() != (size_t) b.size()) + throw InvalidNoiseModel(b.size(), model->dim()); + size_t dims[] = { A1.cols(), A2.cols(), 1}; Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+3, b.size())); Ab_(0) = A1; @@ -102,7 +116,11 @@ namespace gtsam { /* ************************************************************************* */ JacobianFactor::JacobianFactor(Index i1, const Matrix& A1, Index i2, const Matrix& A2, Index i3, const Matrix& A3, const Vector& b, const SharedDiagonal& model) : - GaussianFactor(i1,i2,i3), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { + GaussianFactor(i1,i2,i3), model_(model), Ab_(matrix_) { + + if(model->dim() != (size_t) b.size()) + throw InvalidNoiseModel(b.size(), model->dim()); + size_t dims[] = { A1.cols(), A2.cols(), A3.cols(), 1}; Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+4, b.size())); Ab_(0) = A1; @@ -116,9 +134,13 @@ namespace gtsam { JacobianFactor::JacobianFactor(const std::vector > &terms, const Vector &b, const SharedDiagonal& model) : GaussianFactor(GetKeys(terms.size(), terms.begin(), terms.end())), - model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) + model_(model), Ab_(matrix_) { - size_t dims[terms.size()+1]; + + if(model->dim() != (size_t) b.size()) + throw InvalidNoiseModel(b.size(), model->dim()); + + size_t* dims = (size_t*)alloca(sizeof(size_t)*(terms.size()+1)); // FIXME: alloca is bad, just ask Google. for(size_t j=0; j > &terms, const Vector &b, const SharedDiagonal& model) : GaussianFactor(GetKeys(terms.size(), terms.begin(), terms.end())), - model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) + model_(model), Ab_(matrix_) { - size_t dims[terms.size()+1]; + + if(model->dim() != (size_t) b.size()) + throw InvalidNoiseModel(b.size(), model->dim()); + + size_t* dims=(size_t*)alloca(sizeof(size_t)*(terms.size()+1)); // FIXME: alloca is bad, just ask Google. size_t j=0; std::list >::const_iterator term=terms.begin(); for(; term!=terms.end(); ++term,++j) @@ -150,9 +176,11 @@ namespace gtsam { } /* ************************************************************************* */ - JacobianFactor::JacobianFactor(const GaussianConditional& cg) : GaussianFactor(cg), model_(noiseModel::Diagonal::Sigmas(cg.get_sigmas(), true)), Ab_(matrix_) { + JacobianFactor::JacobianFactor(const GaussianConditional& cg) : + GaussianFactor(cg), + model_(noiseModel::Diagonal::Sigmas(cg.get_sigmas(), true)), + Ab_(matrix_) { Ab_.assignNoalias(cg.rsd_); - firstNonzeroBlocks_.resize(cg.get_d().size(), 0); // set sigmas from precisions assertInvariants(); } @@ -160,18 +188,16 @@ namespace gtsam { JacobianFactor::JacobianFactor(const HessianFactor& factor) : Ab_(matrix_) { keys_ = factor.keys_; Ab_.assignNoalias(factor.info_); + + // Do Cholesky to get a Jacobian size_t maxrank; - try { - maxrank = choleskyCareful(matrix_).first; - } catch(const CarefulCholeskyNegativeMatrixException& e) { - cout << - "Attempting to convert a HessianFactor to a JacobianFactor, but for this\n" - "HessianFactor it is not possible because either the Hessian is negative or\n" - "indefinite, or the quadratic error function it describes becomes negative for\n" - "some values. Here is the HessianFactor on which this conversion was attempted:\n"; - factor.print(""); - throw; - } + bool success; + boost::tie(maxrank, success) = choleskyCareful(matrix_); + + // Check for indefinite system + if(!success) + throw IndeterminantLinearSystemException(factor.keys().front()); + // Zero out lower triangle matrix_.topRows(maxrank).triangularView() = Matrix::Zero(maxrank, matrix_.cols()); @@ -179,23 +205,6 @@ namespace gtsam { Ab_.rowEnd() = maxrank; model_ = noiseModel::Unit::Create(maxrank); - firstNonzeroBlocks_.resize(this->rows(), 0); - - // Sort keys - set vars; - for(size_t j=0; jBase::operator=(rhs); // Copy keys model_ = rhs.model_; // Copy noise model - firstNonzeroBlocks_ = rhs.firstNonzeroBlocks_; // Copy staircase pattern Ab_.assignNoalias(rhs.Ab_); // Copy matrix and block structure assertInvariants(); return *this; } /* ************************************************************************* */ - void JacobianFactor::print(const string& s) const { + void JacobianFactor::print(const string& s, const IndexFormatter& formatter) const { cout << s << "\n"; if (empty()) { cout << " empty, keys: "; - BOOST_FOREACH(const Index& key, keys()) { cout << key << " "; } + BOOST_FOREACH(const Index& key, keys()) { cout << formatter(key) << " "; } cout << endl; } else { for(const_iterator key=begin(); key!=end(); ++key) - cout << boost::format("A[%1%]=\n")%*key << getA(key) << endl; + cout << boost::format("A[%1%]=\n")%formatter(*key) << getA(key) << endl; cout << "b=" << getb() << endl; model_->print("model"); } @@ -271,6 +279,12 @@ namespace gtsam { return 0.5 * weighted.dot(weighted); } + /* ************************************************************************* */ + Matrix JacobianFactor::computeInformation() const { + Matrix AbWhitened = Ab_.full(); + model_->WhitenInPlace(AbWhitened); + return AbWhitened.transpose() * AbWhitened; + } /* ************************************************************************* */ Vector JacobianFactor::operator*(const VectorValues& x) const { @@ -284,7 +298,6 @@ namespace gtsam { return model_->whiten(Ax); } - /* ************************************************************************* */ void JacobianFactor::transposeMultiplyAdd(double alpha, const Vector& e, VectorValues& x) const { @@ -345,11 +358,68 @@ namespace gtsam { return result; } + /* ************************************************************************* */ + GaussianFactor::shared_ptr JacobianFactor::negate() const { + HessianFactor hessian(*this); + return hessian.negate(); + } + /* ************************************************************************* */ GaussianConditional::shared_ptr JacobianFactor::eliminateFirst() { return this->eliminate(1); } + /* ************************************************************************* */ + GaussianConditional::shared_ptr JacobianFactor::splitConditional(size_t nrFrontals) { + assert(Ab_.rowStart() == 0 && Ab_.rowEnd() == (size_t) matrix_.rows() && Ab_.firstBlock() == 0); + assert(size() >= nrFrontals); + assertInvariants(); + + const bool debug = ISDEBUG("JacobianFactor::splitConditional"); + + if(debug) cout << "Eliminating " << nrFrontals << " frontal variables" << endl; + if(debug) this->print("Splitting JacobianFactor: "); + + size_t frontalDim = Ab_.range(0,nrFrontals).cols(); + + // Check for singular factor + if(model_->dim() < frontalDim) + throw IndeterminantLinearSystemException(this->keys().front()); + + // Extract conditional + tic(3, "cond Rd"); + + // Restrict the matrix to be in the first nrFrontals variables + Ab_.rowEnd() = Ab_.rowStart() + frontalDim; + const Eigen::VectorBlock sigmas = model_->sigmas().segment(Ab_.rowStart(), Ab_.rowEnd()-Ab_.rowStart()); + GaussianConditional::shared_ptr conditional(new GaussianConditional(begin(), end(), nrFrontals, Ab_, sigmas)); + if(debug) conditional->print("Extracted conditional: "); + Ab_.rowStart() += frontalDim; + Ab_.firstBlock() += nrFrontals; + toc(3, "cond Rd"); + + if(debug) conditional->print("Extracted conditional: "); + + tic(4, "remaining factor"); + // Take lower-right block of Ab to get the new factor + Ab_.rowEnd() = model_->dim(); + keys_.erase(begin(), begin() + nrFrontals); + // Set sigmas with the right model + if (model_->isConstrained()) + model_ = noiseModel::Constrained::MixedSigmas(sub(model_->sigmas(), frontalDim, model_->dim())); + else + model_ = noiseModel::Diagonal::Sigmas(sub(model_->sigmas(), frontalDim, model_->dim())); + if(debug) this->print("Eliminated factor: "); + assert(Ab_.rows() <= Ab_.cols()-1); + toc(4, "remaining factor"); + + if(debug) print("Eliminated factor: "); + + assertInvariants(); + + return conditional; + } + /* ************************************************************************* */ GaussianConditional::shared_ptr JacobianFactor::eliminate(size_t nrFrontals) { @@ -361,34 +431,6 @@ namespace gtsam { if(debug) cout << "Eliminating " << nrFrontals << " frontal variables" << endl; if(debug) this->print("Eliminating JacobianFactor: "); - - // NOTE: stairs are not currently used in the Eigen QR implementation - // add this back if DenseQR is ever reimplemented -// tic(1, "stairs"); -// // Translate the left-most nonzero column indices into top-most zero row indices -// vector firstZeroRows(Ab_.cols()); -// { -// size_t lastNonzeroRow = 0; -// vector::iterator firstZeroRowsIt = firstZeroRows.begin(); -// for(size_t var=0; varrows() && firstNonzeroBlocks_[lastNonzeroRow] <= var) -// ++ lastNonzeroRow; -// fill(firstZeroRowsIt, firstZeroRowsIt+Ab_(var).cols(), lastNonzeroRow); -// firstZeroRowsIt += Ab_(var).cols(); -// } -// assert(firstZeroRowsIt+1 == firstZeroRows.end()); -// *firstZeroRowsIt = this->rows(); -// } -// toc(1, "stairs"); - -// #ifndef NDEBUG -// for(size_t col=0; colprint("QR result noise model: "); - // Check for singular factor - if(noiseModel->dim() < frontalDim) { - throw domain_error((boost::format( - "JacobianFactor is singular in variable %1%, discovered while attempting\n" - "to eliminate this variable.") % front()).str()); - } - - // Extract conditionals - tic(3, "cond Rd"); - GaussianConditional::shared_ptr conditionals(new GaussianConditional()); - - // Restrict the matrix to be in the first nrFrontals variables - Ab_.rowEnd() = Ab_.rowStart() + frontalDim; - const Eigen::VectorBlock sigmas = noiseModel->sigmas().segment(Ab_.rowStart(), Ab_.rowEnd()-Ab_.rowStart()); - conditionals = boost::make_shared(begin(), end(), nrFrontals, Ab_, sigmas); - if(debug) conditionals->print("Extracted conditional: "); - Ab_.rowStart() += frontalDim; - Ab_.firstBlock() += nrFrontals; - toc(3, "cond Rd"); - - if(debug) conditionals->print("Extracted conditionals: "); - - tic(4, "remaining factor"); - // Take lower-right block of Ab to get the new factor - Ab_.rowEnd() = noiseModel->dim(); - keys_.erase(begin(), begin() + nrFrontals); - // Set sigmas with the right model - if (noiseModel->isConstrained()) - model_ = noiseModel::Constrained::MixedSigmas(sub(noiseModel->sigmas(), frontalDim, noiseModel->dim())); - else - model_ = noiseModel::Diagonal::Sigmas(sub(noiseModel->sigmas(), frontalDim, noiseModel->dim())); - if(debug) this->print("Eliminated factor: "); - assert(Ab_.rows() <= Ab_.cols()-1); - toc(4, "remaining factor"); - - // todo SL: deal with "dead" pivot columns!!! - tic(5, "rowstarts"); - size_t varpos = 0; - firstNonzeroBlocks_.resize(this->rows()); - for(size_t row=0; row& rowSources) const { - assertInvariants(); - for (size_t row = 0; row < rows(); ++row) { - Index firstNonzeroVar; - if (firstNonzeroBlocks_[row] < size()) { - firstNonzeroVar = keys_[firstNonzeroBlocks_[row]]; - } else if (firstNonzeroBlocks_[row] == size()) { - firstNonzeroVar = back() + 1; - } else { - assert(false); - } - rowSources.push_back(_RowSource(firstNonzeroVar, index, row)); - } - } - /* ************************************************************************* */ void JacobianFactor::allocate(const VariableSlots& variableSlots, vector< size_t>& varDims, size_t m) { keys_.resize(variableSlots.size()); std::transform(variableSlots.begin(), variableSlots.end(), begin(), - bind(&VariableSlots::const_iterator::value_type::first, - boost::lambda::_1)); + boost::bind(&VariableSlots::const_iterator::value_type::first, _1)); varDims.push_back(1); Ab_.copyStructureFrom(BlockAb(matrix_, varDims.begin(), varDims.end(), m)); - firstNonzeroBlocks_.resize(m); - } - - /* ************************************************************************* */ - void JacobianFactor::copyRow(const JacobianFactor& source, Index sourceRow, - size_t sourceSlot, size_t row, Index slot) { - ABlock combinedBlock = Ab_(slot); - if (sourceSlot != numeric_limits::max()) { - if (source.firstNonzeroBlocks_[sourceRow] <= sourceSlot) { - const constABlock sourceBlock(source.Ab_(sourceSlot)); - combinedBlock.row(row).noalias() = sourceBlock.row(sourceRow); - } else { - combinedBlock.row(row).setZero(); - } - } else { - combinedBlock.row(row).setZero(); - } - } - - /* ************************************************************************* */ - void JacobianFactor::copyFNZ(size_t m, size_t n, - vector<_RowSource>& rowSources) { - Index i = 0; - for (size_t row = 0; row < m; ++row) { - while (i < n && rowSources[row].firstNonzeroVar > keys_[i]) - ++i; - firstNonzeroBlocks_[row] = i; - } } /* ************************************************************************* */ void JacobianFactor::setModel(bool anyConstrained, const Vector& sigmas) { + if((size_t) sigmas.size() != this->rows()) + throw InvalidNoiseModel(this->rows(), sigmas.size()); if (anyConstrained) model_ = noiseModel::Constrained::MixedSigmas(sigmas); else @@ -531,97 +479,14 @@ namespace gtsam { } /* ************************************************************************* */ - Errors operator*(const FactorGraph& fg, const VectorValues& x) { - Errors e; - BOOST_FOREACH(const JacobianFactor::shared_ptr& Ai, fg) { - e.push_back((*Ai)*x); - } - return e; - } - - /* ************************************************************************* */ - void multiplyInPlace(const FactorGraph& fg, const VectorValues& x, Errors& e) { - multiplyInPlace(fg,x,e.begin()); - } - - /* ************************************************************************* */ - void multiplyInPlace(const FactorGraph& fg, const VectorValues& x, const Errors::iterator& e) { - Errors::iterator ei = e; - BOOST_FOREACH(const JacobianFactor::shared_ptr& Ai, fg) { - *ei = (*Ai)*x; - ei++; - } - } - - - /* ************************************************************************* */ - // x += alpha*A'*e - void transposeMultiplyAdd(const FactorGraph& fg, double alpha, const Errors& e, VectorValues& x) { - // For each factor add the gradient contribution - Errors::const_iterator ei = e.begin(); - BOOST_FOREACH(const JacobianFactor::shared_ptr& Ai, fg) { - Ai->transposeMultiplyAdd(alpha,*(ei++),x); - } - } - - /* ************************************************************************* */ - VectorValues gradient(const FactorGraph& fg, const VectorValues& x0) { - // It is crucial for performance to make a zero-valued clone of x - VectorValues g = VectorValues::Zero(x0); - Errors e; - BOOST_FOREACH(const JacobianFactor::shared_ptr& factor, fg) { - e.push_back(factor->error_vector(x0)); - } - transposeMultiplyAdd(fg, 1.0, e, g); - return g; - } - - /* ************************************************************************* */ - void gradientAtZero(const FactorGraph& fg, VectorValues& g) { - // Zero-out the gradient - g.setZero(); - Errors e; - BOOST_FOREACH(const JacobianFactor::shared_ptr& factor, fg) { - e.push_back(-factor->getb()); - } - transposeMultiplyAdd(fg, 1.0, e, g); - } - - /* ************************************************************************* */ - void residual(const FactorGraph& fg, const VectorValues &x, VectorValues &r) { - Index i = 0 ; - BOOST_FOREACH(const JacobianFactor::shared_ptr& factor, fg) { - r[i] = factor->getb(); - i++; - } - VectorValues Ax = VectorValues::SameStructure(r); - multiply(fg,x,Ax); - axpy(-1.0,Ax,r); - } - - /* ************************************************************************* */ - void multiply(const FactorGraph& fg, const VectorValues &x, VectorValues &r) { - r.vector() = Vector::Zero(r.dim()); - Index i = 0; - BOOST_FOREACH(const JacobianFactor::shared_ptr& factor, fg) { - SubVector &y = r[i]; - for(JacobianFactor::const_iterator j = factor->begin(); j != factor->end(); ++j) { - y += factor->getA(j) * x[*j]; - } - ++i; - } - } - - /* ************************************************************************* */ - void transposeMultiply(const FactorGraph& fg, const VectorValues &r, VectorValues &x) { - x.vector() = Vector::Zero(x.dim()); - Index i = 0; - BOOST_FOREACH(const JacobianFactor::shared_ptr& factor, fg) { - for(JacobianFactor::const_iterator j = factor->begin(); j != factor->end(); ++j) { - x[*j] += factor->getA(j).transpose() * r[i]; - } - ++i; - } + const char* JacobianFactor::InvalidNoiseModel::what() const throw() { + if(description_.empty()) + description_ = (boost::format( + "A JacobianFactor was attempted to be constructed or modified to use a\n" + "noise model of incompatible dimension. The JacobianFactor has\n" + "dimensionality (i.e. length of error vector) %d but the provided noise\n" + "model has dimensionality %d.") % factorDims % noiseModelDims).str(); + return description_.c_str(); } } diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index b5a2dd500..f2bd9c75d 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include #include #include @@ -78,14 +78,11 @@ namespace gtsam { * \f[ E(x) = \frac{1}{2} (A_1 x_{j1} + A_2 x_{j2} - b)^T \Sigma^{-1} (A_1 x_{j1} + A_2 x_{j2} - b) . \f] */ class JacobianFactor : public GaussianFactor { - public: - typedef Matrix AbMatrix; - typedef VerticalBlockView BlockAb; - protected: + typedef Matrix AbMatrix; + typedef VerticalBlockView BlockAb; - SharedDiagonal model_; // Gaussian noise model with diagonal covariance matrix - std::vector firstNonzeroBlocks_; + noiseModel::Diagonal::shared_ptr model_; // Gaussian noise model with diagonal covariance matrix AbMatrix matrix_; // the full matrix corresponding to the factor BlockAb Ab_; // the block view of the full matrix typedef GaussianFactor Base; // typedef to base @@ -97,11 +94,12 @@ namespace gtsam { typedef BlockAb::Column BVector; typedef BlockAb::constColumn constBVector; - public: - /** Copy constructor */ JacobianFactor(const JacobianFactor& gf); + /** Convert from other GaussianFactor */ + JacobianFactor(const GaussianFactor& gf); + /** default constructor for I/O */ JacobianFactor(); @@ -148,13 +146,31 @@ namespace gtsam { } // Implementing Testable interface - virtual void print(const std::string& s = "") const; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const; Vector unweighted_error(const VectorValues& c) const; /** (A*x-b) */ Vector error_vector(const VectorValues& c) const; /** (A*x-b)/sigma */ virtual double error(const VectorValues& c) const; /** 0.5*(A*x-b)'*D*(A*x-b) */ + /** Return the augmented information matrix represented by this GaussianFactor. + * The augmented information matrix contains the information matrix with an + * additional column holding the information vector, and an additional row + * holding the transpose of the information vector. The lower-right entry + * contains the constant error term (when \f$ \delta x = 0 \f$). The + * augmented information matrix is described in more detail in HessianFactor, + * which in fact stores an augmented information matrix. + */ + virtual Matrix computeInformation() const; + + /** + * Construct the corresponding anti-factor to negate information + * stored stored in this factor. + * @return a HessianFactor with negated Hessian matrices + */ + virtual GaussianFactor::shared_ptr negate() const; + /** Check if the factor contains no information, i.e. zero rows. This does * not necessarily mean that the factor involves no variables (to check for * involving no variables use keys().empty()). @@ -224,7 +240,6 @@ namespace gtsam { /** * Return (dense) matrix associated with factor * The returned system is an augmented matrix: [A b] - * @param ordering of variables needed for matrix column order * @param set weight to use whitening to bake in weights */ Matrix matrix_augmented(bool weight = true) const; @@ -251,41 +266,43 @@ namespace gtsam { /** return a multi-frontal conditional. It's actually a chordal Bayesnet */ boost::shared_ptr eliminate(size_t nrFrontals = 1); - /* Used by ::CombineJacobians for sorting */ - struct _RowSource { - size_t firstNonzeroVar; - size_t factorI; - size_t factorRowI; - _RowSource(size_t _firstNonzeroVar, size_t _factorI, size_t _factorRowI) : - firstNonzeroVar(_firstNonzeroVar), factorI(_factorI), factorRowI(_factorRowI) {} - bool operator<(const _RowSource& o) const { - return firstNonzeroVar < o.firstNonzeroVar; - } - }; + /** + * splits a pre-factorized factor into a conditional, and changes the current + * factor to be the remaining component. Performs same operation as eliminate(), + * but without running QR. + */ + boost::shared_ptr splitConditional(size_t nrFrontals = 1); // following methods all used in CombineJacobians: // Many imperative, perhaps all need to be combined in constructor - /** Collect information on Jacobian rows */ - void collectInfo(size_t index, std::vector<_RowSource>& rowSources) const; - /** allocate space */ void allocate(const VariableSlots& variableSlots, std::vector& varDims, size_t m); - /** copy a slot from source */ - void copyRow(const JacobianFactor& source, - Index sourceRow, size_t sourceSlot, size_t row, Index slot); - - /** copy firstNonzeroBlocks structure */ - void copyFNZ(size_t m, size_t n, std::vector<_RowSource>& rowSources); - /** set noiseModel correctly */ void setModel(bool anyConstrained, const Vector& sigmas); /** Assert invariants after elimination */ void assertInvariants() const; + /** An exception indicating that the noise model dimension passed into the + * JacobianFactor has a different dimensionality than the factor. */ + class InvalidNoiseModel : std::exception { + public: + const size_t factorDims; ///< The dimensionality of the factor + const size_t noiseModelDims; ///< The dimensionality of the noise model + + InvalidNoiseModel(size_t factorDims, size_t noiseModelDims) : + factorDims(factorDims), noiseModelDims(noiseModelDims) {} + virtual ~InvalidNoiseModel() throw() {} + + virtual const char* what() const throw(); + + private: + mutable std::string description_; + }; + private: // Friend HessianFactor to facilitate conversion constructors @@ -301,52 +318,11 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor); - ar & BOOST_SERIALIZATION_NVP(firstNonzeroBlocks_); ar & BOOST_SERIALIZATION_NVP(Ab_); ar & BOOST_SERIALIZATION_NVP(model_); ar & BOOST_SERIALIZATION_NVP(matrix_); } - }; // JacobianFactor - /** return A*x */ - Errors operator*(const FactorGraph& fg, const VectorValues& x); - - /* In-place version e <- A*x that overwrites e. */ - void multiplyInPlace(const FactorGraph& fg, const VectorValues& x, Errors& e); - - /* In-place version e <- A*x that takes an iterator. */ - void multiplyInPlace(const FactorGraph& fg, const VectorValues& x, const Errors::iterator& e); - - /** x += alpha*A'*e */ - void transposeMultiplyAdd(const FactorGraph& fg, double alpha, const Errors& e, VectorValues& x); - - /** - * Compute the gradient of the energy function, - * \f$ \nabla_{x=x_0} \left\Vert \Sigma^{-1} A x - b \right\Vert^2 \f$, - * centered around \f$ x = x_0 \f$. - * The gradient is \f$ A^T(Ax-b) \f$. - * @param fg The Jacobian factor graph $(A,b)$ - * @param x0 The center about which to compute the gradient - * @return The gradient as a VectorValues - */ - VectorValues gradient(const FactorGraph& fg, const VectorValues& x0); - - /** - * Compute the gradient of the energy function, - * \f$ \nabla_{x=0} \left\Vert \Sigma^{-1} A x - b \right\Vert^2 \f$, - * centered around zero. - * The gradient is \f$ A^T(Ax-b) \f$. - * @param fg The Jacobian factor graph $(A,b)$ - * @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues - * @return The gradient as a VectorValues - */ - void gradientAtZero(const FactorGraph& fg, VectorValues& g); - - // matrix-vector operations - void residual(const FactorGraph& fg, const VectorValues &x, VectorValues &r); - void multiply(const FactorGraph& fg, const VectorValues &x, VectorValues &r); - void transposeMultiply(const FactorGraph& fg, const VectorValues &r, VectorValues &x); - } // gtsam diff --git a/gtsam/linear/KalmanFilter.cpp b/gtsam/linear/KalmanFilter.cpp index 0df9d99ce..987191254 100644 --- a/gtsam/linear/KalmanFilter.cpp +++ b/gtsam/linear/KalmanFilter.cpp @@ -23,7 +23,6 @@ #include #include #include -#include #include #include diff --git a/gtsam/linear/KalmanFilter.h b/gtsam/linear/KalmanFilter.h index b74a0db7d..df4cd1d65 100644 --- a/gtsam/linear/KalmanFilter.h +++ b/gtsam/linear/KalmanFilter.h @@ -10,17 +10,17 @@ * -------------------------------------------------------------------------- */ /** - * @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 */ +#pragma once + #include +#include #ifndef KALMANFILTER_DEFAULT_FACTORIZATION #define KALMANFILTER_DEFAULT_FACTORIZATION QR @@ -28,9 +28,6 @@ namespace gtsam { - class SharedDiagonal; - class SharedGaussian; - /** * Kalman Filter class * diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index b6472061f..7479c2141 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -27,9 +27,7 @@ #include #include -#include #include -#include static double inf = std::numeric_limits::infinity(); using namespace std; @@ -125,7 +123,7 @@ SharedDiagonal Gaussian::QR(Matrix& Ab) const { if(debug) gtsam::print(Ab, "Whitened Ab: "); // Eigen QR - much faster than older householder approach - inplace_QR(Ab, false); + inplace_QR(Ab); // hand-coded householder implementation // TODO: necessary to isolate last column? @@ -134,35 +132,6 @@ SharedDiagonal Gaussian::QR(Matrix& Ab) const { return Unit::Create(maxRank); } -/* ************************************************************************* */ -SharedDiagonal Gaussian::Cholesky(Matrix& Ab, size_t nFrontals) const { - // get size(A) and maxRank - // TODO: really no rank problems ? - - // pre-whiten everything (cheaply if possible) - tic("Cholesky: 1 whiten"); - WhitenInPlace(Ab); - toc("Cholesky: 1 whiten"); - - // Form A'*A (todo: this is probably less efficient than possible) - tic("Cholesky: 2 A' * A"); - Ab = Ab.transpose() * Ab; - toc("Cholesky: 2 A' * A"); - - // Use Cholesky to factor Ab - tic("Cholesky: 3 careful"); - size_t maxrank = choleskyCareful(Ab).first; - toc("Cholesky: 3 careful"); - - // Due to numerical error the rank could appear to be more than the number - // of variables. The important part is that it does not includes the - // augmented b column. - if(maxrank == (size_t) Ab.cols()) - -- maxrank; - - return Unit::Create(maxrank); -} - void Gaussian::WhitenSystem(vector& A, Vector& b) const { BOOST_FOREACH(Matrix& Aj, A) { WhitenInPlace(Aj); } whitenInPlace(b); @@ -226,7 +195,7 @@ Diagonal::shared_ptr Diagonal::Sigmas(const Vector& sigmas, bool smart) { /* ************************************************************************* */ void Diagonal::print(const string& name) const { - gtsam::print(sigmas_, name + ": diagonal sigmas"); + gtsam::print(sigmas_, name + "diagonal sigmas"); } /* ************************************************************************* */ @@ -261,18 +230,6 @@ void Diagonal::WhitenInPlace(Matrix& H) const { vector_scale_inplace(invsigmas(), H); } -/* ************************************************************************* */ -Vector Diagonal::sample() const { - Vector result(dim_); - for (size_t i = 0; i < dim_; i++) { - typedef boost::normal_distribution Normal; - Normal dist(0.0, this->sigmas_(i)); - boost::variate_generator norm(generator, dist); - result(i) = norm(); - } - return result; -} - /* ************************************************************************* */ // Constrained /* ************************************************************************* */ @@ -290,8 +247,8 @@ Constrained::shared_ptr Constrained::MixedSigmas(const Vector& mu, const Vector& /* ************************************************************************* */ void Constrained::print(const std::string& name) const { - gtsam::print(sigmas_, name + ": constrained sigmas"); - gtsam::print(mu_, name + ": constrained mu"); + gtsam::print(sigmas_, name + "constrained sigmas"); + gtsam::print(mu_, name + "constrained mu"); } /* ************************************************************************* */ @@ -428,6 +385,12 @@ SharedDiagonal Constrained::QR(Matrix& Ab) const { /* ************************************************************************* */ // Isotropic +/* ************************************************************************* */ +Isotropic::shared_ptr Isotropic::Sigma(size_t dim, double sigma, bool smart) { + if (smart && fabs(sigma-1.0)<1e-9) return Unit::Create(dim); + return shared_ptr(new Isotropic(dim, sigma)); +} + /* ************************************************************************* */ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smart) { if (smart && fabs(variance-1.0)<1e-9) return Unit::Create(dim); @@ -436,7 +399,7 @@ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smar /* ************************************************************************* */ void Isotropic::print(const string& name) const { - cout << name << ": isotropic sigma " << " " << sigma_ << endl; + cout << name << "isotropic sigma " << " " << sigma_ << endl; } /* ************************************************************************* */ @@ -464,23 +427,11 @@ void Isotropic::WhitenInPlace(Matrix& H) const { H *= invsigma_; } -/* ************************************************************************* */ -// faster version -Vector Isotropic::sample() const { - typedef boost::normal_distribution Normal; - Normal dist(0.0, this->sigma_); - boost::variate_generator norm(generator, dist); - Vector result(dim_); - for (size_t i = 0; i < dim_; i++) - result(i) = norm(); - return result; -} - /* ************************************************************************* */ // Unit /* ************************************************************************* */ void Unit::print(const std::string& name) const { - cout << name << ": unit (" << dim_ << ") " << endl; + cout << name << "unit (" << dim_ << ") " << endl; } /* ************************************************************************* */ @@ -583,7 +534,7 @@ void Base::reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const { /* ************************************************************************* */ void Null::print(const std::string &s="") const -{ cout << s << ": null ()" << endl; } +{ cout << s << "null ()" << endl; } Null::shared_ptr Null::Create() { return shared_ptr(new Null()); } @@ -604,7 +555,7 @@ double Fair::weight(const double &error) const { return 1.0 / (1.0 + fabs(error)/c_); } void Fair::print(const std::string &s="") const -{ cout << s << ": fair (" << c_ << ")" << endl; } +{ cout << s << "fair (" << c_ << ")" << endl; } bool Fair::equals(const Base &expected, const double tol) const { const Fair* p = dynamic_cast (&expected); @@ -632,7 +583,7 @@ double Huber::weight(const double &error) const { } void Huber::print(const std::string &s="") const { - cout << s << ": huber (" << k_ << ")" << endl; + cout << s << "huber (" << k_ << ")" << endl; } bool Huber::equals(const Base &expected, const double tol) const { diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index b6cf4deac..8588c738b 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -19,15 +19,17 @@ #pragma once #include +#include +#include #include +#include namespace gtsam { - class SharedDiagonal; // forward declare - /// All noise models live in the noiseModel namespace namespace noiseModel { + // Forward declaration class Gaussian; class Diagonal; class Constrained; @@ -111,6 +113,8 @@ namespace gtsam { * as indeed * |y|^2 = y'*y = x'*R'*R*x * Various derived classes are available that are more efficient. + * The named constructors return a shared_ptr because, when the smart flag is true, + * the underlying object might be a derived class such as Diagonal. */ class Gaussian: public Base { @@ -145,7 +149,6 @@ namespace gtsam { /** * A Gaussian noise model created by specifying a square root information matrix. - * @param smart, check if can be simplified to derived class */ static shared_ptr SqrtInformation(const Matrix& R) { return shared_ptr(new Gaussian(R.rows(),R)); @@ -153,9 +156,10 @@ namespace gtsam { /** * A Gaussian noise model created by specifying a covariance matrix. - * @param smart, check if can be simplified to derived class + * @param covariance The square covariance Matrix + * @param smart check if can be simplified to derived class */ - static shared_ptr Covariance(const Matrix& covariance, bool smart=false); + static shared_ptr Covariance(const Matrix& covariance, bool smart = true); virtual void print(const std::string& name) const; virtual bool equals(const Base& expected, double tol=1e-9) const; @@ -197,13 +201,7 @@ namespace gtsam { * @param Ab is the m*(n+1) augmented system matrix [A b] * @return in-place QR factorization [R d]. Below-diagonal is undefined !!!!! */ - virtual SharedDiagonal QR(Matrix& Ab) const; - - /** - * Cholesky factorization - * FIXME: this is never used anywhere - */ - virtual SharedDiagonal Cholesky(Matrix& Ab, size_t nFrontals) const; + virtual boost::shared_ptr QR(Matrix& Ab) const; /** * Return R itself, but note that Whiten(H) is cheaper than R*H @@ -261,21 +259,22 @@ namespace gtsam { * A diagonal noise model created by specifying a Vector of sigmas, i.e. * standard devations, the diagonal of the square root covariance matrix. */ - static shared_ptr Sigmas(const Vector& sigmas, bool smart=false); + static shared_ptr Sigmas(const Vector& sigmas, bool smart = true); /** * A diagonal noise model created by specifying a Vector of variances, i.e. * i.e. the diagonal of the covariance matrix. - * @param smart, check if can be simplified to derived class + * @param variances A vector containing the variances of this noise model + * @param smart check if can be simplified to derived class */ - static shared_ptr Variances(const Vector& variances, bool smart = false); + static shared_ptr Variances(const Vector& variances, bool smart = true); /** * A diagonal noise model created by specifying a Vector of precisions, i.e. * i.e. the diagonal of the information matrix, i.e., weights */ - static shared_ptr Precisions(const Vector& precisions) { - return Variances(reciprocal(precisions)); + static shared_ptr Precisions(const Vector& precisions, bool smart = true) { + return Variances(reciprocal(precisions), smart); } virtual void print(const std::string& name) const; @@ -296,11 +295,6 @@ namespace gtsam { Vector invsigmas() const; double invsigma(size_t i) const; - /** - * generate random variate - */ - virtual Vector sample() const; - /** * Return R itself, but note that Whiten(H) is cheaper than R*H */ @@ -368,13 +362,13 @@ namespace gtsam { * standard devations, some of which might be zero */ static shared_ptr MixedSigmas(const Vector& mu, const Vector& sigmas, - bool smart = false); + bool smart = true); /** * A diagonal noise model created by specifying a Vector of * standard devations, some of which might be zero */ - static shared_ptr MixedSigmas(const Vector& sigmas, bool smart = false) { + static shared_ptr MixedSigmas(const Vector& sigmas, bool smart = true) { return MixedSigmas(repeat(sigmas.size(), 1000.0), sigmas, smart); } @@ -383,7 +377,7 @@ namespace gtsam { * standard devations, some of which might be zero */ static shared_ptr MixedSigmas(double m, const Vector& sigmas, - bool smart = false) { + bool smart = true) { return MixedSigmas(repeat(sigmas.size(), m), sigmas, smart); } @@ -445,7 +439,7 @@ namespace gtsam { /** * Apply QR factorization to the system [A b], taking into account constraints */ - virtual SharedDiagonal QR(Matrix& Ab) const; + virtual Diagonal::shared_ptr QR(Matrix& Ab) const; /** * Check constrained is always true @@ -496,21 +490,21 @@ namespace gtsam { /** * An isotropic noise model created by specifying a standard devation sigma */ - static shared_ptr Sigma(size_t dim, double sigma) { - return shared_ptr(new Isotropic(dim, sigma)); - } + static shared_ptr Sigma(size_t dim, double sigma, bool smart = true); /** * An isotropic noise model created by specifying a variance = sigma^2. - * @param smart, check if can be simplified to derived class + * @param dim The dimension of this noise model + * @param variance The variance of this noise model + * @param smart check if can be simplified to derived class */ - static shared_ptr Variance(size_t dim, double variance, bool smart = false); + static shared_ptr Variance(size_t dim, double variance, bool smart = true); /** * An isotropic noise model created by specifying a precision */ - static shared_ptr Precision(size_t dim, double precision) { - return Variance(dim, 1.0/precision); + static shared_ptr Precision(size_t dim, double precision, bool smart = true) { + return Variance(dim, 1.0/precision, smart); } virtual void print(const std::string& name) const; @@ -525,11 +519,6 @@ namespace gtsam { */ inline double sigma() const { return sigma_; } - /** - * generate random variate - */ - virtual Vector sample() const; - private: /** Serialization function */ friend class boost::serialization::access; @@ -609,7 +598,7 @@ namespace gtsam { virtual bool equals(const Base& expected, const double tol=1e-8) const = 0; inline double sqrtWeight(const double &error) const - { return sqrt(weight(error)); } + { return std::sqrt(weight(error)); } /** produce a weight vector according to an error vector and the implemented * robust function */ @@ -728,6 +717,13 @@ namespace gtsam { } // namespace noiseModel + /** Note, deliberately not in noiseModel namespace. + * Deprecated. Only for compatibility with previous version. + */ + typedef noiseModel::Base::shared_ptr SharedNoiseModel; + typedef noiseModel::Gaussian::shared_ptr SharedGaussian; + typedef noiseModel::Diagonal::shared_ptr SharedDiagonal; + } // namespace gtsam diff --git a/gtsam/linear/Sampler.cpp b/gtsam/linear/Sampler.cpp index 058533104..6031440bd 100644 --- a/gtsam/linear/Sampler.cpp +++ b/gtsam/linear/Sampler.cpp @@ -18,27 +18,32 @@ #include #include - namespace gtsam { /* ************************************************************************* */ -Sampler::Sampler(const SharedDiagonal& model, int32_t seed) - : sigmas_(model->sigmas()), generator_(static_cast(seed)) +Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed) + : model_(model), generator_(static_cast(seed)) { } /* ************************************************************************* */ Sampler::Sampler(const Vector& sigmas, int32_t seed) - : sigmas_(sigmas), generator_(static_cast(seed)) +: model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(static_cast(seed)) { } /* ************************************************************************* */ -Vector Sampler::sample() { - size_t d = dim(); +Sampler::Sampler(int32_t seed) +: generator_(static_cast(seed)) +{ +} + +/* ************************************************************************* */ +Vector Sampler::sampleDiagonal(const Vector& sigmas) { + size_t d = sigmas.size(); Vector result(d); for (size_t i = 0; i < d; i++) { - double sigma = sigmas_(i); + double sigma = sigmas(i); // handle constrained case separately if (sigma == 0.0) { @@ -53,4 +58,19 @@ Vector Sampler::sample() { return result; } +/* ************************************************************************* */ +Vector Sampler::sample() { + assert(model_.get()); + const Vector& sigmas = model_->sigmas(); + return sampleDiagonal(sigmas); +} + +/* ************************************************************************* */ +Vector Sampler::sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) { + assert(model.get()); + const Vector& sigmas = model->sigmas(); + return sampleDiagonal(sigmas); +} +/* ************************************************************************* */ + } // \namespace gtsam diff --git a/gtsam/linear/Sampler.h b/gtsam/linear/Sampler.h index 53b59a9ea..3f6fee7ca 100644 --- a/gtsam/linear/Sampler.h +++ b/gtsam/linear/Sampler.h @@ -10,15 +10,17 @@ * -------------------------------------------------------------------------- */ /** - * @file Sampler.h * @brief sampling that can be parameterized using a NoiseModel to generate samples from + * @file Sampler.h * the given distribution * @author Alex Cunningham */ #pragma once -#include +#include + +#include namespace gtsam { @@ -31,8 +33,8 @@ namespace gtsam { */ class Sampler { protected: - /** sigmas from the noise model */ - Vector sigmas_; + /** noiseModel created at generation */ + noiseModel::Diagonal::shared_ptr model_; /** generator */ boost::minstd_rand generator_; @@ -46,7 +48,7 @@ public: * * NOTE: do not use zero as a seed, it will break the generator */ - Sampler(const SharedDiagonal& model, int32_t seed = 42u); + Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed = 42u); /** * Create a sampler for a distribution specified by a vector of sigmas directly @@ -55,9 +57,17 @@ public: */ Sampler(const Vector& sigmas, int32_t seed = 42u); + /** + * Create a sampler without a given noisemodel - pass in to sample + * + * NOTE: do not use zero as a seed, it will break the generator + */ + Sampler(int32_t seed = 42u); + /** access functions */ - size_t dim() const { return sigmas_.size(); } - Vector sigmas() const { return sigmas_; } + size_t dim() const { assert(model_.get()); return model_->dim(); } + Vector sigmas() const { assert(model_.get()); return model_->sigmas(); } + const noiseModel::Diagonal::shared_ptr& model() const { return model_; } /** * sample from distribution @@ -65,6 +75,19 @@ public: */ Vector sample(); + /** + * Sample from noisemodel passed in as an argument, + * can be used without having initialized a model for the system. + * + * NOTE: not const due to need to update the underlying generator + */ + Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model); + +protected: + + /** given sigmas for a diagonal model, returns a sample */ + Vector sampleDiagonal(const Vector& sigmas); + }; -} +} // \namespace gtsam diff --git a/gtsam/linear/SharedDiagonal.h b/gtsam/linear/SharedDiagonal.h deleted file mode 100644 index 8a7e101a2..000000000 --- a/gtsam/linear/SharedDiagonal.h +++ /dev/null @@ -1,81 +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 SharedDiagonal.h - * @brief Class that wraps a shared noise model with diagonal covariance - * @author Frank Dellaert - * @date Jan 22, 2010 - */ - -#pragma once - -#include - -namespace gtsam { // note, deliberately not in noiseModel namespace - - // A useful convenience class to refer to a shared Diagonal model - // There are (somewhat dangerous) constructors from Vector and pair - // that call Sigmas and Sigma, respectively. - class SharedDiagonal: public noiseModel::Diagonal::shared_ptr { - public: - SharedDiagonal() { - } - SharedDiagonal(const noiseModel::Diagonal::shared_ptr& p) : - noiseModel::Diagonal::shared_ptr(p) { - } - SharedDiagonal(const noiseModel::Constrained::shared_ptr& p) : - noiseModel::Diagonal::shared_ptr(p) { - } - SharedDiagonal(const noiseModel::Isotropic::shared_ptr& p) : - noiseModel::Diagonal::shared_ptr(p) { - } - SharedDiagonal(const noiseModel::Unit::shared_ptr& p) : - noiseModel::Diagonal::shared_ptr(p) { - } - SharedDiagonal(const Vector& sigmas) : - noiseModel::Diagonal::shared_ptr(noiseModel::Diagonal::Sigmas(sigmas)) { - } - - /// Print - inline void print(const std::string &s) const { (*this)->print(s); } - - /// Generate a sample - inline Vector sample() const { return (*this)->sample(); } - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("SharedDiagonal", - boost::serialization::base_object(*this)); - } - }; - - // TODO: make these the ones really used in unit tests - inline SharedDiagonal sharedSigmas(const Vector& sigmas) { - return noiseModel::Diagonal::Sigmas(sigmas); - } - inline SharedDiagonal sharedSigma(size_t dim, double sigma) { - return noiseModel::Isotropic::Sigma(dim, sigma); - } - inline SharedDiagonal sharedPrecisions(const Vector& precisions) { - return noiseModel::Diagonal::Precisions(precisions); - } - inline SharedDiagonal sharedPrecision(size_t dim, double precision) { - return noiseModel::Isotropic::Precision(dim, precision); - } - inline SharedDiagonal sharedUnit(size_t dim) { - return noiseModel::Unit::Create(dim); - } - -} - diff --git a/gtsam/linear/SharedGaussian.h b/gtsam/linear/SharedGaussian.h deleted file mode 100644 index a3154bac1..000000000 --- a/gtsam/linear/SharedGaussian.h +++ /dev/null @@ -1,70 +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 SharedGaussian.h - * @brief Class that wraps a shared Gaussian noise model - * @author Frank Dellaert - * @date Jan 22, 2010 - */ - -#pragma once - -#include -#include - -namespace gtsam { // note, deliberately not in noiseModel namespace - - /** - * A useful convenience class to refer to a shared Gaussian model - * Also needed to make noise models in matlab - */ - class SharedGaussian: public SharedNoiseModel { - public: - - typedef SharedNoiseModel Base; - - SharedGaussian() {} - SharedGaussian(const noiseModel::Gaussian::shared_ptr& p) : Base(p) {} - SharedGaussian(const noiseModel::Diagonal::shared_ptr& p) : Base(p) {} - SharedGaussian(const noiseModel::Constrained::shared_ptr& p) : Base(p) {} - SharedGaussian(const noiseModel::Isotropic::shared_ptr& p) : Base(p) {} - SharedGaussian(const noiseModel::Unit::shared_ptr& p) : Base(p) {} - - // Define GTSAM_MAGIC_GAUSSIAN to have access to slightly - // dangerous and non-shared (inefficient, wasteful) noise models. - // Intended to be used only in tests (if you must) and the MATLAB wrapper -#ifdef GTSAM_MAGIC_GAUSSIAN - SharedGaussian(const Matrix& covariance) - : Base(noiseModel::Gaussian::Covariance(covariance)) {} - SharedGaussian(const Vector& sigmas) - : Base(noiseModel::Diagonal::Sigmas(sigmas)) {} -#endif - -// Define GTSAM_DANGEROUS_GAUSSIAN to have access to bug-prone fixed dimension Gaussians -// Not intended for human use, only for backwards compatibility of old unit tests -#ifdef GTSAM_DANGEROUS_GAUSSIAN - SharedGaussian(const double& s) : - Base(noiseModel::Isotropic::Sigma(GTSAM_DANGEROUS_GAUSSIAN, s)) {} -#endif - - /// Print - inline void print(const std::string &s) const { (*this)->print(s); } - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("SharedGaussian", - boost::serialization::base_object(*this)); - } - }; -} diff --git a/gtsam/linear/SharedNoiseModel.h b/gtsam/linear/SharedNoiseModel.h deleted file mode 100644 index 1d66e3495..000000000 --- a/gtsam/linear/SharedNoiseModel.h +++ /dev/null @@ -1,89 +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 - - * -------------------------------------------------------------------------- */ - -#pragma once - -#include - -namespace gtsam { // note, deliberately not in noiseModel namespace - - struct SharedNoiseModel: public noiseModel::Base::shared_ptr { - - typedef noiseModel::Base::shared_ptr Base; - - SharedNoiseModel() {} - SharedNoiseModel(const noiseModel::Robust::shared_ptr& p): Base(p) {} - SharedNoiseModel(const noiseModel::Gaussian::shared_ptr& p): Base(p) {} - SharedNoiseModel(const noiseModel::Diagonal::shared_ptr& p): Base(p) {} - SharedNoiseModel(const noiseModel::Constrained::shared_ptr& p): Base(p) {} - SharedNoiseModel(const noiseModel::Isotropic::shared_ptr& p): Base(p) {} - SharedNoiseModel(const noiseModel::Unit::shared_ptr& p): Base(p) {} - - #ifdef GTSAM_MAGIC_GAUSSIAN - SharedNoiseModel(const Matrix& covariance) : - Base(boost::static_pointer_cast( - noiseModel::Gaussian::Covariance(covariance))) {} - - SharedNoiseModel(const Vector& sigmas) : - Base(boost::static_pointer_cast( - noiseModel::Diagonal::Sigmas(sigmas))) {} - #endif - - // Define GTSAM_DANGEROUS_GAUSSIAN to have access to bug-prone fixed dimension Gaussians - // Not intended for human use, only for backwards compatibility of old unit tests - #ifdef GTSAM_DANGEROUS_GAUSSIAN - SharedNoiseModel(const double& s) : - Base(boost::static_pointer_cast( - noiseModel::Isotropic::Sigma(GTSAM_DANGEROUS_GAUSSIAN, s))) {} - #endif - - /// Print - inline void print(const std::string &s) const { (*this)->print(s); } - - // Static syntactic sugar functions to create noisemodels directly - // These should only be used with the Matlab interface - static inline SharedNoiseModel Sigmas(const Vector& sigmas, bool smart=false) { - return noiseModel::Diagonal::Sigmas(sigmas, smart); - } - - static inline SharedNoiseModel Sigma(size_t dim, double sigma) { - return noiseModel::Isotropic::Sigma(dim, sigma); - } - - static inline SharedNoiseModel Precisions(const Vector& precisions) { - return noiseModel::Diagonal::Precisions(precisions); - } - - static inline SharedNoiseModel Precision(size_t dim, double precision) { - return noiseModel::Isotropic::Precision(dim, precision); - } - - static inline SharedNoiseModel Unit(size_t dim) { - return noiseModel::Unit::Create(dim); - } - - static inline SharedNoiseModel SqrtInformation(const Matrix& R) { - return noiseModel::Gaussian::SqrtInformation(R); - } - - static inline SharedNoiseModel Covariance(const Matrix& covariance, bool smart=false) { - return noiseModel::Gaussian::Covariance(covariance, smart); - } - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("SharedNoiseModel", - boost::serialization::base_object(*this)); - } - }; -} diff --git a/gtsam/linear/SubgraphPreconditioner.cpp b/gtsam/linear/SubgraphPreconditioner.cpp new file mode 100644 index 000000000..8b5a3708f --- /dev/null +++ b/gtsam/linear/SubgraphPreconditioner.cpp @@ -0,0 +1,139 @@ +/* ---------------------------------------------------------------------------- + + * 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 SubgraphPreconditioner.cpp + * @date Dec 31, 2009 + * @author: Frank Dellaert + */ + +#include +#include +#include + +using namespace std; + +namespace gtsam { + + /* ************************************************************************* */ + static GaussianFactorGraph::shared_ptr convertToJacobianFactors(const GaussianFactorGraph &gfg) { + GaussianFactorGraph::shared_ptr result(new GaussianFactorGraph()); + BOOST_FOREACH(const GaussianFactor::shared_ptr &gf, gfg) { + JacobianFactor::shared_ptr jf = boost::dynamic_pointer_cast(gf); + if( !jf ) { + jf = boost::make_shared(*gf); // Convert any non-Jacobian factors to Jacobians (e.g. Hessian -> Jacobian with Cholesky) + } + result->push_back(jf); + } + return result; + } + + /* ************************************************************************* */ + SubgraphPreconditioner::SubgraphPreconditioner(const sharedFG& Ab2, + const sharedBayesNet& Rc1, const sharedValues& xbar) : + Ab2_(convertToJacobianFactors(*Ab2)), Rc1_(Rc1), xbar_(xbar), b2bar_(new Errors(-gaussianErrors(*Ab2_,*xbar))) { + } + + /* ************************************************************************* */ + // x = xbar + inv(R1)*y + VectorValues SubgraphPreconditioner::x(const VectorValues& y) const { + return *xbar_ + gtsam::backSubstitute(*Rc1_, y); + } + + /* ************************************************************************* */ + double error(const SubgraphPreconditioner& sp, const VectorValues& y) { + Errors e(y); + VectorValues x = sp.x(y); + Errors e2 = gaussianErrors(*sp.Ab2(),x); + return 0.5 * (dot(e, e) + dot(e2,e2)); + } + + /* ************************************************************************* */ + // gradient is y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar), + VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y) { + VectorValues x = gtsam::backSubstitute(*sp.Rc1(), y); /* inv(R1)*y */ + Errors e = (*sp.Ab2()*x - *sp.b2bar()); /* (A2*inv(R1)*y-b2bar) */ + VectorValues v = VectorValues::Zero(x); + transposeMultiplyAdd(*sp.Ab2(), 1.0, e, v); /* A2'*(A2*inv(R1)*y-b2bar) */ + return y + gtsam::backSubstituteTranspose(*sp.Rc1(), v); + } + + /* ************************************************************************* */ + // Apply operator A, A*y = [I;A2*inv(R1)]*y = [y; A2*inv(R1)*y] + Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y) { + + Errors e(y); + VectorValues x = gtsam::backSubstitute(*sp.Rc1(), y); /* x=inv(R1)*y */ + Errors e2 = *sp.Ab2() * x; /* A2*x */ + e.splice(e.end(), e2); + return e; + } + + /* ************************************************************************* */ + // In-place version that overwrites e + void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e) { + + Errors::iterator ei = e.begin(); + for ( Index i = 0 ; i < y.size() ; ++i, ++ei ) { + *ei = y[i]; + } + + // Add A2 contribution + VectorValues x = gtsam::backSubstitute(*sp.Rc1(), y); // x=inv(R1)*y + gtsam::multiplyInPlace(*sp.Ab2(), x, ei); // use iterator version + } + + /* ************************************************************************* */ + // Apply operator A', A'*e = [I inv(R1')*A2']*e = e1 + inv(R1')*A2'*e2 + VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e) { + + Errors::const_iterator it = e.begin(); + VectorValues y = sp.zero(); + for ( Index i = 0 ; i < y.size() ; ++i, ++it ) + y[i] = *it ; + sp.transposeMultiplyAdd2(1.0,it,e.end(),y); + return y; + } + + /* ************************************************************************* */ + // y += alpha*A'*e + void transposeMultiplyAdd + (const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y) { + + Errors::const_iterator it = e.begin(); + for ( Index i = 0 ; i < y.size() ; ++i, ++it ) { + const Vector& ei = *it; + axpy(alpha, ei, y[i]); + } + sp.transposeMultiplyAdd2(alpha, it, e.end(), y); + } + + /* ************************************************************************* */ + // y += alpha*inv(R1')*A2'*e2 + void SubgraphPreconditioner::transposeMultiplyAdd2 (double alpha, + Errors::const_iterator it, Errors::const_iterator end, VectorValues& y) const { + + // create e2 with what's left of e + // TODO can we avoid creating e2 by passing iterator to transposeMultiplyAdd ? + Errors e2; + while (it != end) e2.push_back(*(it++)); + + VectorValues x = VectorValues::Zero(y); // x = 0 + gtsam::transposeMultiplyAdd(*Ab2_,1.0,e2,x); // x += A2'*e2 + axpy(alpha, gtsam::backSubstituteTranspose(*Rc1_, x), y); // y += alpha*inv(R1')*x + } + + /* ************************************************************************* */ + void SubgraphPreconditioner::print(const std::string& s) const { + cout << s << endl; + Ab2_->print(); + } +} // nsamespace gtsam diff --git a/gtsam/linear/SubgraphPreconditioner.h b/gtsam/linear/SubgraphPreconditioner.h new file mode 100644 index 000000000..f266928d7 --- /dev/null +++ b/gtsam/linear/SubgraphPreconditioner.h @@ -0,0 +1,117 @@ +/* ---------------------------------------------------------------------------- + + * 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 SubgraphPreconditioner.h + * @date Dec 31, 2009 + * @author Frank Dellaert + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + + /** + * Subgraph conditioner class, as explained in the RSS 2010 submission. + * Starting with a graph A*x=b, we split it in two systems A1*x=b1 and A2*x=b2 + * We solve R1*x=c1, and make the substitution y=R1*x-c1. + * To use the class, give the Bayes Net R1*x=c1 and Graph A2*x=b2. + * Then solve for yhat using CG, and solve for xhat = system.x(yhat). + */ + class SubgraphPreconditioner { + + public: + typedef boost::shared_ptr shared_ptr; + typedef boost::shared_ptr sharedBayesNet; + typedef boost::shared_ptr sharedFG; + typedef boost::shared_ptr sharedValues; + typedef boost::shared_ptr sharedErrors; + + private: + sharedFG Ab2_; + sharedBayesNet Rc1_; + sharedValues xbar_; ///< A1 \ b1 + sharedErrors b2bar_; ///< A2*xbar - b2 + + public: + + SubgraphPreconditioner(); + + /** + * Constructor + * @param Ab2: the Graph A2*x=b2 + * @param Rc1: the Bayes Net R1*x=c1 + * @param xbar: the solution to R1*x=c1 + */ + SubgraphPreconditioner(const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar); + + /** Access Ab2 */ + const sharedFG& Ab2() const { return Ab2_; } + + /** Access Rc1 */ + const sharedBayesNet& Rc1() const { return Rc1_; } + + /** Access b2bar */ + const sharedErrors b2bar() const { return b2bar_; } + + /** + * Add zero-mean i.i.d. Gaussian prior terms to each variable + * @param sigma Standard deviation of Gaussian + */ +// SubgraphPreconditioner add_priors(double sigma) const; + + /* x = xbar + inv(R1)*y */ + VectorValues x(const VectorValues& y) const; + + /* A zero VectorValues with the structure of xbar */ + VectorValues zero() const { + VectorValues V(VectorValues::Zero(*xbar_)); + return V ; + } + + /** + * Add constraint part of the error only + * y += alpha*inv(R1')*A2'*e2 + * Takes a range indicating e2 !!!! + */ + void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin, + Errors::const_iterator end, VectorValues& y) const; + + /** print the object */ + void print(const std::string& s = "SubgraphPreconditioner") const; + }; + + /* error, given y */ + double error(const SubgraphPreconditioner& sp, const VectorValues& y); + + /** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */ + VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y); + + /** Apply operator A */ + Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y); + + /** Apply operator A in place: needs e allocated already */ + void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e); + + /** Apply operator A' */ + VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e); + + /** + * Add A'*e to y + * y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2] + */ + void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y); + +} // namespace gtsam diff --git a/gtsam/linear/SubgraphSolver.cpp b/gtsam/linear/SubgraphSolver.cpp new file mode 100644 index 000000000..9986fb76c --- /dev/null +++ b/gtsam/linear/SubgraphSolver.cpp @@ -0,0 +1,137 @@ +/* ---------------------------------------------------------------------------- + + * 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 +#include +#include +#include +#include +#include + +using namespace std; + +namespace gtsam { + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianFactorGraph &gfg, const Parameters ¶meters) + : parameters_(parameters) +{ + initialize(gfg); +} + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianFactorGraph::shared_ptr &jfg, const Parameters ¶meters) + : parameters_(parameters) +{ + initialize(*jfg); +} + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianFactorGraph &Ab1, const GaussianFactorGraph &Ab2, const Parameters ¶meters) + : parameters_(parameters) { + + GaussianBayesNet::shared_ptr Rc1 = EliminationTree::Create(Ab1)->eliminate(&EliminateQR); + initialize(Rc1, boost::make_shared(Ab2)); +} + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianFactorGraph::shared_ptr &Ab1, + const GaussianFactorGraph::shared_ptr &Ab2, const Parameters ¶meters) + : parameters_(parameters) { + + GaussianBayesNet::shared_ptr Rc1 = EliminationTree::Create(*Ab1)->eliminate(&EliminateQR); + initialize(Rc1, Ab2); +} + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianBayesNet::shared_ptr &Rc1, const GaussianFactorGraph &Ab2, + const Parameters ¶meters) : parameters_(parameters) +{ + initialize(Rc1, boost::make_shared(Ab2)); +} + +/**************************************************************************************************/ +SubgraphSolver::SubgraphSolver(const GaussianBayesNet::shared_ptr &Rc1, + const GaussianFactorGraph::shared_ptr &Ab2, const Parameters ¶meters) : parameters_(parameters) +{ + initialize(Rc1, Ab2); +} + +VectorValues SubgraphSolver::optimize() { + VectorValues ybar = conjugateGradients(*pc_, pc_->zero(), parameters_); + return pc_->x(ybar); +} + +void SubgraphSolver::initialize(const GaussianFactorGraph &jfg) +{ + GaussianFactorGraph::shared_ptr Ab1 = boost::make_shared(), + Ab2 = boost::make_shared(); + + boost::tie(Ab1, Ab2) = splitGraph(jfg) ; + if (parameters_.verbosity()) + cout << "Split A into (A1) " << Ab1->size() << " and (A2) " << Ab2->size() << " factors" << endl; + + GaussianBayesNet::shared_ptr Rc1 = EliminationTree::Create(*Ab1)->eliminate(&EliminateQR); + VectorValues::shared_ptr xbar(new VectorValues(gtsam::optimize(*Rc1))); + pc_ = boost::make_shared(Ab2, Rc1, xbar); +} + +void SubgraphSolver::initialize(const GaussianBayesNet::shared_ptr &Rc1, const GaussianFactorGraph::shared_ptr &Ab2) +{ + VectorValues::shared_ptr xbar(new VectorValues(gtsam::optimize(*Rc1))); + pc_ = boost::make_shared(Ab2, Rc1, xbar); +} + +boost::tuple +SubgraphSolver::splitGraph(const GaussianFactorGraph &jfg) { + + const VariableIndex index(jfg); + const size_t n = index.size(); + DSFVector D(n); + + GaussianFactorGraph::shared_ptr At(new GaussianFactorGraph()); + GaussianFactorGraph::shared_ptr Ac( new GaussianFactorGraph()); + + size_t t = 0; + BOOST_FOREACH ( const GaussianFactor::shared_ptr &gf, jfg ) { + + if ( gf->keys().size() > 2 ) { + throw runtime_error("SubgraphSolver::splitGraph the graph is not simple, sanity check failed "); + } + + bool augment = false ; + + /* check whether this factor should be augmented to the "tree" graph */ + if ( gf->keys().size() == 1 ) augment = true; + else { + const Index u = gf->keys()[0], v = gf->keys()[1], + u_root = D.findSet(u), v_root = D.findSet(v); + if ( u_root != v_root ) { + t++; augment = true ; + D.makeUnionInPlace(u_root, v_root); + } + } + if ( augment ) At->push_back(gf); + else Ac->push_back(gf); + } + + return boost::tie(At, Ac); +} + +} // \namespace gtsam diff --git a/gtsam/linear/SubgraphSolver.h b/gtsam/linear/SubgraphSolver.h new file mode 100644 index 000000000..fe968d486 --- /dev/null +++ b/gtsam/linear/SubgraphSolver.h @@ -0,0 +1,87 @@ +/* ---------------------------------------------------------------------------- + + * 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 +#include + +namespace gtsam { + +class SubgraphSolverParameters : public ConjugateGradientParameters { +public: + typedef ConjugateGradientParameters Base; + SubgraphSolverParameters() : Base() {} + virtual void print(const std::string &s="") const { Base::print(s); } +}; + +/** + * This class implements 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. + * + * To use it in nonlinear optimization, please see the following example + * + * LevenbergMarquardtParams parameters; + * parameters.linearSolverType = SuccessiveLinearizationParams::CONJUGATE_GRADIENT; + * parameters.iterativeParams = boost::make_shared(); + * LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); + * Values result = optimizer.optimize(); + * + * \nosubgrouping + */ + +class SubgraphSolver : public IterativeSolver { + +public: + typedef SubgraphSolverParameters Parameters; + +protected: + Parameters parameters_; + SubgraphPreconditioner::shared_ptr pc_; ///< preconditioner object + +public: + /* Given a gaussian factor graph, split it into a spanning tree (A1) + others (A2) for SPCG */ + SubgraphSolver(const GaussianFactorGraph &A, const Parameters ¶meters); + SubgraphSolver(const GaussianFactorGraph::shared_ptr &A, const Parameters ¶meters); + + /* The user specify the subgraph part and the constraint part, may throw exception if A1 is underdetermined */ + SubgraphSolver(const GaussianFactorGraph &Ab1, const GaussianFactorGraph &Ab2, const Parameters ¶meters); + SubgraphSolver(const GaussianFactorGraph::shared_ptr &Ab1, const GaussianFactorGraph::shared_ptr &Ab2, const Parameters ¶meters); + + /* The same as above, but the A1 is solved before */ + SubgraphSolver(const GaussianBayesNet::shared_ptr &Rc1, const GaussianFactorGraph &Ab2, const Parameters ¶meters); + SubgraphSolver(const GaussianBayesNet::shared_ptr &Rc1, const GaussianFactorGraph::shared_ptr &Ab2, const Parameters ¶meters); + + virtual ~SubgraphSolver() {} + virtual VectorValues optimize () ; + +protected: + + void initialize(const GaussianFactorGraph &jfg); + void initialize(const GaussianBayesNet::shared_ptr &Rc1, const GaussianFactorGraph::shared_ptr &Ab2); + + boost::tuple + splitGraph(const GaussianFactorGraph &gfg) ; +}; + +} // namespace gtsam + + diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index a0af31c70..fd7f2757c 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -17,10 +17,12 @@ */ #include +#include #include using namespace std; -using namespace gtsam; + +namespace gtsam { /* ************************************************************************* */ VectorValues::VectorValues(const VectorValues& other) { @@ -43,6 +45,14 @@ VectorValues VectorValues::Zero(const VectorValues& x) { return cloned; } +/* ************************************************************************* */ +vector VectorValues::dims() const { + std::vector result(this->size()); + for(Index j = 0; j < this->size(); ++j) + result[j] = this->dim(j); + return result; +} + /* ************************************************************************* */ void VectorValues::insert(Index j, const Vector& value) { // Make sure j does not already exist @@ -77,10 +87,10 @@ void VectorValues::insert(Index j, const Vector& value) { } /* ************************************************************************* */ -void VectorValues::print(const std::string& str) const { +void VectorValues::print(const std::string& str, const IndexFormatter& formatter) const { std::cout << str << ": " << size() << " elements\n"; for (Index var = 0; var < size(); ++var) - std::cout << " " << var << ": \n" << operator[](var) << "\n"; + std::cout << " " << formatter(var) << ": \n" << operator[](var) << "\n"; std::cout.flush(); } @@ -151,6 +161,14 @@ VectorValues VectorValues::operator+(const VectorValues& c) const { return result; } +/* ************************************************************************* */ +VectorValues VectorValues::operator-(const VectorValues& c) const { + assert(this->hasSameStructure(c)); + VectorValues result(SameStructure(c)); + result.values_ = this->values_ - c.values_; + return result; +} + /* ************************************************************************* */ void VectorValues::operator+=(const VectorValues& c) { assert(this->hasSameStructure(c)); @@ -158,20 +176,30 @@ void VectorValues::operator+=(const VectorValues& c) { } /* ************************************************************************* */ -VectorValues& VectorValues::operator=(const Permuted& rhs) { - if(this->size() != rhs.size()) - throw std::invalid_argument("VectorValues assignment from Permuted requires pre-allocation, see documentation."); - for(size_t j=0; jsize(); ++j) { - if(exists(j)) { - SubVector& l(this->at(j)); - const SubVector& r(rhs[j]); - if(l.rows() != r.rows()) - throw std::invalid_argument("VectorValues assignment from Permuted requires pre-allocation, see documentation."); - l = r; - } else { - if(rhs.container().exists(rhs.permutation()[j])) - throw std::invalid_argument("VectorValues assignment from Permuted requires pre-allocation, see documentation."); - } - } - return *this; +VectorValues VectorValues::permute(const Permutation& permutation) const { + // Create result and allocate space + VectorValues lhs; + lhs.values_.resize(this->dim()); + lhs.maps_.reserve(this->size()); + + // Copy values from this VectorValues to the permuted VectorValues + size_t lhsPos = 0; + for(size_t i = 0; i < this->size(); ++i) { + // Map the next LHS subvector to the next slice of the LHS vector + lhs.maps_.push_back(SubVector(lhs.values_, lhsPos, this->at(permutation[i]).size())); + // Copy the data from the RHS subvector to the LHS subvector + lhs.maps_[i] = this->at(permutation[i]); + // Increment lhs position + lhsPos += lhs.maps_[i].size(); + } + + return lhs; } + +/* ************************************************************************* */ +void VectorValues::swap(VectorValues& other) { + this->values_.swap(other.values_); + this->maps_.swap(other.maps_); +} + +} \ No newline at end of file diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 7939b486d..9fad99223 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -19,14 +19,18 @@ #include #include -#include +#include #include #include #include +#include namespace gtsam { + // Forward declarations + class Permutation; + /** * This class represents a collection of vector-valued variables associated * each with a unique integer index. It is typically used to store the variables @@ -130,6 +134,9 @@ namespace gtsam { /** Return the summed dimensionality of all variables. */ size_t dim() const { return values_.rows(); } + /** Return the dimension of each vector in this container */ + std::vector dims() const; + /** Check whether a variable with index \c j exists. */ bool exists(Index j) const { return j < size() && maps_[j].rows() > 0; } @@ -147,7 +154,7 @@ namespace gtsam { /** Insert a vector \c value with index \c j. * Causes reallocation. Can be used to insert values in any order, but - * throws an invalid_argument exception if the index \j is already used. + * throws an invalid_argument exception if the index \c j is already used. * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ @@ -158,23 +165,24 @@ namespace gtsam { iterator begin() { chk(); return maps_.begin(); } ///< Iterator over variables const_iterator begin() const { chk(); return maps_.begin(); } ///< Iterator over variables - iterator end() { chk(); return maps_.end(); } ///< Iterator over variables + iterator end() { chk(); return maps_.end(); } ///< Iterator over variables const_iterator end() const { chk(); return maps_.end(); } ///< Iterator over variables - reverse_iterator rbegin() { chk(); return maps_.rbegin(); } ///< Reverse iterator over variables + reverse_iterator rbegin() { chk(); return maps_.rbegin(); } ///< Reverse iterator over variables const_reverse_iterator rbegin() const { chk(); return maps_.rbegin(); } ///< Reverse iterator over variables - reverse_iterator rend() { chk(); return maps_.rend(); } ///< Reverse iterator over variables + reverse_iterator rend() { chk(); return maps_.rend(); } ///< Reverse iterator over variables const_reverse_iterator rend() const { chk(); return maps_.rend(); } ///< Reverse iterator over variables /** print required by Testable for unit testing */ - void print(const std::string& str = "VectorValues: ") const; + void print(const std::string& str = "VectorValues: ", + const IndexFormatter& formatter =DefaultIndexFormatter) const; /** equals required by Testable for unit testing */ bool equals(const VectorValues& x, double tol = 1e-9) const; - /// @} + /// @{ /// \anchor AdvancedConstructors /// @name Advanced Constructors - /// @{ + /// @} /** Construct from a container of variable dimensions (in variable order), without initializing any values. */ template @@ -262,22 +270,39 @@ namespace gtsam { return gtsam::dot(this->values_, V.values_); } + /** Vector L2 norm */ + inline double norm() const { + return this->vector().norm(); + } + /** * + operator does element-wise addition. Both VectorValues must have the * same structure (checked when NDEBUG is not defined). */ VectorValues operator+(const VectorValues& c) const; + /** + * + operator does element-wise subtraction. Both VectorValues must have the + * same structure (checked when NDEBUG is not defined). + */ + VectorValues operator-(const VectorValues& c) const; + /** * += operator does element-wise addition. Both VectorValues must have the * same structure (checked when NDEBUG is not defined). */ void operator+=(const VectorValues& c); - /** Assignment operator from Permuted, requires the dimensions - * of the assignee to already be properly pre-allocated. - */ - VectorValues& operator=(const Permuted& rhs); + /** + * Permute the entries of this VectorValues, returns a new VectorValues as + * the result. + */ + VectorValues permute(const Permutation& permutation) const; + + /** + * Swap the data in this VectorValues with another. + */ + void swap(VectorValues& other); /// @} @@ -296,6 +321,16 @@ namespace gtsam { void copyStructureFrom(const VectorValues& other); public: + + /** + * scale a vector by a scalar + */ + friend VectorValues operator*(const double a, const VectorValues &V) { + VectorValues result(VectorValues::SameStructure(V)); + result.values_ = a * V.values_; + return result; + } + /// TODO: linear algebra interface seems to have been added for SPCG. friend size_t dim(const VectorValues& V) { return V.dim(); @@ -384,7 +419,7 @@ namespace gtsam { maps_.reserve(maps_.size() + dimensions.size()); BOOST_FOREACH(size_t dim, dimensions) { maps_.push_back(values_.segment(varStart, dim)); - varStart += dim; // varStart is continued from first for loop + varStart += (int)dim; // varStart is continued from first for loop } } diff --git a/gtsam/linear/iterative-inl.h b/gtsam/linear/iterative-inl.h index 02048d3df..5cc0841b0 100644 --- a/gtsam/linear/iterative-inl.h +++ b/gtsam/linear/iterative-inl.h @@ -18,12 +18,9 @@ #pragma once -#include - -#include #include - -using namespace std; +#include +#include namespace gtsam { @@ -32,13 +29,13 @@ namespace gtsam { template struct CGState { - typedef IterativeOptimizationParameters Parameters; + typedef ConjugateGradientParameters Parameters; const Parameters ¶meters_; - int k; - bool steepest; - V g, d; - double gamma, threshold; + int k; ///< iteration + bool steepest; ///< flag to indicate we are doing steepest descent + V g, d; ///< gradient g and search direction d for CG + double gamma, threshold; ///< gamma (squared L2 norm of g) and convergence threshold E Ad; /* ************************************************************************* */ @@ -53,7 +50,7 @@ namespace gtsam { // init gamma and calculate threshold gamma = dot(g,g) ; - threshold = ::max(parameters_.epsilon_abs(), parameters_.epsilon() * parameters_.epsilon() * gamma); + threshold = std::max(parameters_.epsilon_abs(), parameters_.epsilon() * parameters_.epsilon() * gamma); // Allocate and calculate A*d for first iteration if (gamma > parameters_.epsilon_abs()) Ad = Ab * d; @@ -62,10 +59,10 @@ namespace gtsam { /* ************************************************************************* */ // print void print(const V& x) { - cout << "iteration = " << k << endl; + std::cout << "iteration = " << k << std::endl; gtsam::print(x,"x"); gtsam::print(g, "g"); - cout << "dotg = " << gamma << endl; + std::cout << "dotg = " << gamma << std::endl; gtsam::print(d, "d"); gtsam::print(Ad, "Ad"); } @@ -82,6 +79,7 @@ namespace gtsam { /* ************************************************************************* */ // take a step, return true if converged bool step(const S& Ab, V& x) { + if ((++k) >= ((int)parameters_.maxIterations())) return true; //----------------------------------> @@ -94,9 +92,12 @@ namespace gtsam { // check for convergence double new_gamma = dot(g, g); - if (parameters_.verbosity() != IterativeOptimizationParameters::SILENT) - cout << "iteration " << k << ": alpha = " << alpha - << ", dotg = " << new_gamma << endl; + + if (parameters_.verbosity() != ConjugateGradientParameters::SILENT) + std::cout << "iteration " << k << ": alpha = " << alpha + << ", dotg = " << new_gamma + << std::endl; + if (new_gamma < threshold) return true; // calculate new search direction @@ -121,22 +122,20 @@ namespace gtsam { // conjugate gradient method. // S: linear system, V: step vector, E: errors template - V conjugateGradients( - const S& Ab, - V x, - const IterativeOptimizationParameters ¶meters, - bool steepest = false) { + V conjugateGradients(const S& Ab, V x, const ConjugateGradientParameters ¶meters, bool steepest) { CGState state(Ab, x, parameters, steepest); - if (parameters.verbosity() != IterativeOptimizationParameters::SILENT) - cout << "CG: epsilon = " << parameters.epsilon() - << ", maxIterations = " << parameters.maxIterations() - << ", ||g0||^2 = " << state.gamma - << ", threshold = " << state.threshold << endl; + + if (parameters.verbosity() != ConjugateGradientParameters::SILENT) + std::cout << "CG: epsilon = " << parameters.epsilon() + << ", maxIterations = " << parameters.maxIterations() + << ", ||g0||^2 = " << state.gamma + << ", threshold = " << state.threshold + << std::endl; if ( state.gamma < state.threshold ) { - if (parameters.verbosity() != IterativeOptimizationParameters::SILENT) - cout << "||g0||^2 < threshold, exiting immediately !" << endl; + if (parameters.verbosity() != ConjugateGradientParameters::SILENT) + std::cout << "||g0||^2 < threshold, exiting immediately !" << std::endl; return x; } diff --git a/gtsam/linear/iterative.cpp b/gtsam/linear/iterative.cpp index c431e0c82..07d4de865 100644 --- a/gtsam/linear/iterative.cpp +++ b/gtsam/linear/iterative.cpp @@ -15,55 +15,64 @@ * @author Frank Dellaert * @date Dec 28, 2009 */ -#include +#include #include #include #include -#include -#include +#include + +#include using namespace std; namespace gtsam { - /* ************************************************************************* */ - void System::print (const string& s) const { - cout << s << endl; - gtsam::print(A_, "A"); - gtsam::print(b_, "b"); - } + /* ************************************************************************* */ + void System::print(const string& s) const { + cout << s << endl; + gtsam::print(A_, "A"); + gtsam::print(b_, "b"); + } - /* ************************************************************************* */ + /* ************************************************************************* */ - Vector steepestDescent(const System& Ab, const Vector& x, const IterativeOptimizationParameters & parameters) { - return conjugateGradients (Ab, x, parameters, true); - } + Vector steepestDescent(const System& Ab, const Vector& x, + const ConjugateGradientParameters & parameters) { + return conjugateGradients(Ab, x, parameters, true); + } - Vector conjugateGradientDescent(const System& Ab, const Vector& x, const IterativeOptimizationParameters & parameters) { - return conjugateGradients (Ab, x, parameters); - } + Vector conjugateGradientDescent(const System& Ab, const Vector& x, + const ConjugateGradientParameters & parameters) { + return conjugateGradients(Ab, x, parameters); + } - /* ************************************************************************* */ - Vector steepestDescent(const Matrix& A, const Vector& b, const Vector& x, const IterativeOptimizationParameters & parameters) { - System Ab(A, b); - return conjugateGradients (Ab, x, parameters, true); - } + /* ************************************************************************* */ + Vector steepestDescent(const Matrix& A, const Vector& b, const Vector& x, + const ConjugateGradientParameters & parameters) { + System Ab(A, b); + return conjugateGradients(Ab, x, parameters, true); + } - Vector conjugateGradientDescent(const Matrix& A, const Vector& b, const Vector& x, const IterativeOptimizationParameters & parameters) { - System Ab(A, b); - return conjugateGradients (Ab, x, parameters); - } + Vector conjugateGradientDescent(const Matrix& A, const Vector& b, + const Vector& x, const ConjugateGradientParameters & parameters) { + System Ab(A, b); + return conjugateGradients(Ab, x, parameters); + } - /* ************************************************************************* */ - VectorValues steepestDescent(const FactorGraph& fg, const VectorValues& x, const IterativeOptimizationParameters & parameters) { - return conjugateGradients, VectorValues, Errors> (fg, x, parameters, true); - } + /* ************************************************************************* */ + VectorValues steepestDescent(const GaussianFactorGraph& fg, + const VectorValues& x, const ConjugateGradientParameters & parameters) { + return conjugateGradients( + fg, x, parameters, true); + } - VectorValues conjugateGradientDescent(const FactorGraph& fg, const VectorValues& x, const IterativeOptimizationParameters & parameters) { - return conjugateGradients, VectorValues, Errors> (fg, x, parameters); - } + VectorValues conjugateGradientDescent(const GaussianFactorGraph& fg, + const VectorValues& x, const ConjugateGradientParameters & parameters) { + return conjugateGradients( + fg, x, parameters); + } - /* ************************************************************************* */ +/* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/linear/iterative.h b/gtsam/linear/iterative.h index 2e6f77f10..0eb04bf49 100644 --- a/gtsam/linear/iterative.h +++ b/gtsam/linear/iterative.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * 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) @@ -20,7 +20,7 @@ #include #include -#include +#include namespace gtsam { @@ -31,19 +31,18 @@ namespace gtsam { * "Vector" class E needs dot(v,v) * @param Ab, the "system" that needs to be solved, examples below * @param x is the initial estimate - * @param epsilon determines the convergence criterion: norm(g) - V conjugateGradients(const S& Ab, V x, bool verbose, double epsilon, - size_t maxIterations, bool steepest = false); + template + V conjugateGradients(const S& Ab, V x, + const ConjugateGradientParameters ¶meters, bool steepest = false); /** * Helper class encapsulating the combined system |Ax-b_|^2 * Needed to run Conjugate Gradients on matrices * */ class System { + private: const Matrix& A_; const Vector& b_; @@ -105,7 +104,7 @@ namespace gtsam { Vector conjugateGradientDescent( const System& Ab, const Vector& x, - const IterativeOptimizationParameters & parameters); + const ConjugateGradientParameters & parameters); /** convenience calls using matrices, will create System class internally: */ @@ -116,7 +115,7 @@ namespace gtsam { const Matrix& A, const Vector& b, const Vector& x, - const IterativeOptimizationParameters & parameters); + const ConjugateGradientParameters & parameters); /** * Method of conjugate gradients (CG), Matrix version @@ -125,25 +124,26 @@ namespace gtsam { const Matrix& A, const Vector& b, const Vector& x, - const IterativeOptimizationParameters & parameters); - - class GaussianFactorGraph; + const ConjugateGradientParameters & parameters); /** * Method of steepest gradients, Gaussian Factor Graph version - * */ + */ VectorValues steepestDescent( const GaussianFactorGraph& fg, const VectorValues& x, - const IterativeOptimizationParameters & parameters); + const ConjugateGradientParameters & parameters); /** * Method of conjugate gradients (CG), Gaussian Factor Graph version - * */ + */ VectorValues conjugateGradientDescent( const GaussianFactorGraph& fg, const VectorValues& x, - const IterativeOptimizationParameters & parameters); + const ConjugateGradientParameters & parameters); } // namespace gtsam + +#include + diff --git a/gtsam/linear/linearExceptions.h b/gtsam/linear/linearExceptions.h new file mode 100644 index 000000000..5e90f57b3 --- /dev/null +++ b/gtsam/linear/linearExceptions.h @@ -0,0 +1,180 @@ +/* ---------------------------------------------------------------------------- + + * 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 linearExceptions.h + * @brief Exceptions that may be thrown by linear solver components + * @author Richard Roberts + * @date Aug 17, 2012 + */ +#pragma once + +#include +#include +#include + +namespace gtsam { + + /** + Thrown when a linear system is ill-posed. The most common cause for this + error is having underconstrained variables. Mathematically, the system is + either underdetermined, or its quadratic error function is concave in some + directions. + + Examples of situations causing this error are: + - A landmark observed by two cameras with a very small baseline will have + high uncertainty in its distance from the cameras but low uncertainty + in its bearing, creating a poorly-conditioned system. + - A landmark observed by only a single ProjectionFactor, RangeFactor, or + BearingFactor (the landmark is not completely constrained). + - An overall scale or rigid transformation ambiguity, for example missing + a prior or hard constraint on the first pose, or missing a scale + constraint between the first two cameras (in structure-from-motion). + + Mathematically, the following conditions cause this problem: + - Underdetermined system: This occurs when the variables are not + completely constrained by factors. Even if all variables are involved + in factors, the variables can still be numerically underconstrained, + (for example, if a landmark is observed by only one ProjectionFactor). + Mathematically in this case, the rank of the linear Jacobian or Hessian + is less than the number of scalars in the system. + - Indefinite system: This condition occurs when the system Hessian is + indefinite, i.e. non-positive-semidefinite. Note that this condition + can also indicate an underdetermined system, but when solving with + Cholesky, accumulation of numerical errors can cause the system to + become indefinite (have some negative eigenvalues) even if it is in + reality positive semi-definite (has some near-zero positive + eigenvalues). Alternatively, if the system contains some + HessianFactor's with negative eigenvalues, these can create a truly + indefinite system, whose quadratic error function has negative + curvature in some directions. + - Poorly-conditioned system: A system that is positive-definite (has a + unique solution) but is numerically ill-conditioned can accumulate + numerical errors during solving that cause the system to become + indefinite later during the elimination process. Note that poorly- + conditioned systems will usually have inaccurate solutions, even if + they do not always trigger this error. Systems with almost- + unconstrained variables or vastly different measurement uncertainties + or variable units can be poorly-conditioned. + + Resolving this problem: + - This exception contains the variable at which the problem was + discovered (IndeterminantLinearSystemException::nearbyVariable()). + Note, however, that this is not necessarily the variable where the + problem originates. For example, in the case that a prior on the + first camera was forgotten, it may only be another camera or landmark + where the problem can be detected. Where the problem is detected + depends on the graph structure and variable elimination ordering. + - MATLAB (or similar software) is a useful tool to diagnose this problem. + Use GaussianFactorGraph::sparseJacobian_(), + GaussianFactorGraph::sparseJacobian() + GaussianFactorGraph::denseJacobian(), and + GaussianFactorGraph::denseHessian() to output the linear graph in + matrix format. If using the MATLAB wrapper, the returned matrices can + be immediately inspected and analyzed using standard methods. If not + using the MATLAB wrapper, the output of these functions may be written + to text files and then loaded into MATLAB. + - When outputting linear graphs as Jacobian matrices, rows are ordered in + the same order as factors in the graph, which each factor occupying the + number of rows indicated by its JacobianFactor::rows() function. Each + column appears in elimination ordering, as in the Ordering class. Each + variable occupies the number of columns indicated by the + JacobianFactor::getDim() function. + - When outputting linear graphs as Hessian matrices, rows and columns are + ordered in elimination order and occupy scalars in the same way as + described for Jacobian columns in the previous bullet. + */ + class IndeterminantLinearSystemException : public std::exception { + Index j_; + mutable std::string what_; + public: + IndeterminantLinearSystemException(Index j) throw() : j_(j) {} + virtual ~IndeterminantLinearSystemException() throw() {} + Index nearbyVariable() const { return j_; } + virtual const char* what() const throw() { + if(what_.empty()) + what_ = +"\nIndeterminant linear system detected while working near variable with\n" +"index " + boost::lexical_cast(j_) + " in ordering.\n" +"\n\ +Thrown when a linear system is ill-posed. The most common cause for this\n\ +error is having underconstrained variables. Mathematically, the system is\n\ +either underdetermined, or its quadratic error function is concave in some\n\ +directions.\n\ +\n\ +Examples of situations causing this error are:\n\ +- A landmark observed by two cameras with a very small baseline will have\n\ + high uncertainty in its distance from the cameras but low uncertainty\n\ + in its bearing, creating a poorly-conditioned system.\n\ +- A landmark observed by only a single ProjectionFactor, RangeFactor, or\n\ + BearingFactor (the landmark is not completely constrained).\n\ +- An overall scale or rigid transformation ambiguity, for example missing\n\ + a prior or hard constraint on the first pose, or missing a scale\n\ + constraint between the first two cameras (in structure-from-motion).\n\ +\n\ +Mathematically, the following conditions cause this problem:\n\ +- Underdetermined system: This occurs when the variables are not\n\ + completely constrained by factors. Even if all variables are involved\n\ + in factors, the variables can still be numerically underconstrained,\n\ + (for example, if a landmark is observed by only one ProjectionFactor).\n\ + Mathematically in this case, the rank of the linear Jacobian or Hessian\n\ + is less than the number of scalars in the system.\n\ +- Indefinite system: This condition occurs when the system Hessian is\n\ + indefinite, i.e. non-positive-semidefinite. Note that this condition\n\ + can also indicate an underdetermined system, but when solving with\n\ + Cholesky, accumulation of numerical errors can cause the system to\n\ + become indefinite (have some negative eigenvalues) even if it is in\n\ + reality positive semi-definite (has some near-zero positive\n\ + eigenvalues). Alternatively, if the system contains some\n\ + HessianFactor's with negative eigenvalues, these can create a truly\n\ + indefinite system, whose quadratic error function has negative\n\ + curvature in some directions.\n\ +- Poorly-conditioned system: A system that is positive-definite (has a\n\ + unique solution) but is numerically ill-conditioned can accumulate\n\ + numerical errors during solving that cause the system to become\n\ + indefinite later during the elimination process. Note that poorly-\n\ + conditioned systems will usually have inaccurate solutions, even if\n\ + they do not always trigger this error. Systems with almost-\n\ + unconstrained variables or vastly different measurement uncertainties\n\ + or variable units can be poorly-conditioned.\n\ +\n\ +Resolving this problem:\n\ +- This exception contains the variable at which the problem was\n\ + discovered (IndeterminantLinearSystemException::nearbyVariable()).\n\ + Note, however, that this is not necessarily the variable where the\n\ + problem originates. For example, in the case that a prior on the\n\ + first camera was forgotten, it may only be another camera or landmark\n\ + where the problem can be detected. Where the problem is detected\n\ + depends on the graph structure and variable elimination ordering.\n\ +- MATLAB (or similar software) is a useful tool to diagnose this problem.\n\ + Use GaussianFactorGraph::sparseJacobian_(),\n\ + GaussianFactorGraph::sparseJacobian()\n\ + GaussianFactorGraph::denseJacobian(), and\n\ + GaussianFactorGraph::denseHessian() to output the linear graph in\n\ + matrix format. If using the MATLAB wrapper, the returned matrices can\n\ + be immediately inspected and analyzed using standard methods. If not\n\ + using the MATLAB wrapper, the output of these functions may be written\n\ + to text files and then loaded into MATLAB.\n\ +- When outputting linear graphs as Jacobian matrices, rows are ordered in\n\ + the same order as factors in the graph, which each factor occupying the\n\ + number of rows indicated by its JacobianFactor::rows() function. Each\n\ + column appears in elimination ordering, as in the Ordering class. Each\n\ + variable occupies the number of columns indicated by the\n\ + JacobianFactor::getDim() function.\n\ +- When outputting linear graphs as Hessian matrices, rows and columns are\n\ + ordered in elimination order and occupy scalars in the same way as\n\ + described for Jacobian columns in the previous bullet.\ +"; + return what_.c_str(); + } + }; + +} diff --git a/gtsam/linear/tests/testGaussianConditional.cpp b/gtsam/linear/tests/testGaussianConditional.cpp index 93030b598..8b0c5e239 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -267,55 +267,6 @@ TEST( GaussianConditional, solve_multifrontal ) } -/* ************************************************************************* */ -TEST( GaussianConditional, solve_multifrontal_permuted ) -{ - // create full system, 3 variables, 2 frontals, all 2 dim - Matrix full_matrix = Matrix_(4, 7, - 1.0, 0.0, 2.0, 0.0, 3.0, 0.0, 0.1, - 0.0, 1.0, 0.0, 2.0, 0.0, 3.0, 0.2, - 0.0, 0.0, 3.0, 0.0, 4.0, 0.0, 0.3, - 0.0, 0.0, 0.0, 3.0, 0.0, 4.0, 0.4); - - // 3 variables, all dim=2 - vector dims; dims += 2, 2, 2, 1; - GaussianConditional::rsd_type matrices(full_matrix, dims.begin(), dims.end()); - Vector sigmas = ones(4); - vector cgdims; cgdims += _x_, _x1_, _l1_; - GaussianConditional cg(cgdims.begin(), cgdims.end(), 2, matrices, sigmas); - - EXPECT(assert_equal(Vector_(4, 0.1, 0.2, 0.3, 0.4), cg.get_d())); - - // partial solution - Vector sl1 = Vector_(2, 9.0, 10.0); - - // elimination order; _x_, _x1_, _l1_ - VectorValues actualUnpermuted(vector(3, 2)); - Permutation permutation(3); - permutation[0] = 2; - permutation[1] = 0; - permutation[2] = 1; - Permuted actual(permutation, actualUnpermuted); - actual[_x_] = Vector_(2, 0.1, 0.2); // rhs - actual[_x1_] = Vector_(2, 0.3, 0.4); // rhs - actual[_l1_] = sl1; // parent - - VectorValues expectedUnpermuted(vector(3, 2)); - Permuted expected(permutation, expectedUnpermuted); - expected[_x_] = Vector_(2, -3.1,-3.4); - expected[_x1_] = Vector_(2, -11.9,-13.2); - expected[_l1_] = sl1; - - // verify indices/size - EXPECT_LONGS_EQUAL(3, cg.size()); - EXPECT_LONGS_EQUAL(4, cg.dim()); - - // solve and verify - cg.solveInPlace(actual); - EXPECT(assert_equal(expected.container(), actual.container(), tol)); - -} - /* ************************************************************************* */ TEST( GaussianConditional, solveTranspose ) { static const Index _y_=1; diff --git a/gtsam/linear/tests/testGaussianFactorGraph.cpp b/gtsam/linear/tests/testGaussianFactorGraph.cpp index 34009f856..cb835a76a 100644 --- a/gtsam/linear/tests/testGaussianFactorGraph.cpp +++ b/gtsam/linear/tests/testGaussianFactorGraph.cpp @@ -36,7 +36,7 @@ static const Index _x0_=0, _x1_=1, _x2_=2, _x3_=3, _x4_=4, _x_=5, _y_=6, _l1_=7, #endif static SharedDiagonal - sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2), + sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1), sigma_02 = noiseModel::Isotropic::Sigma(2,0.2), constraintModel = noiseModel::Constrained::All(2); /* ************************************************************************* */ @@ -50,10 +50,8 @@ TEST(GaussianFactorGraph, initialization) { fg.add(0, -5*eye(2), 2, 5*eye(2), Vector_(2, 0.0, 1.0), unit2); fg.add(1, -5*eye(2), 2, 5*eye(2), Vector_(2, -1.0, 1.5), unit2); - FactorGraph graph = *fg.dynamicCastFactors >(); - - EXPECT_LONGS_EQUAL(4, graph.size()); - JacobianFactor factor = *graph[0]; + EXPECT_LONGS_EQUAL(4, fg.size()); + JacobianFactor factor = *boost::dynamic_pointer_cast(fg[0]); // Test sparse, which takes a vector and returns a matrix, used in MATLAB // Note that this the augmented vector and the RHS is in column 7 @@ -155,14 +153,20 @@ TEST(GaussianFactorGraph, Combine2) gfg.add(0, A10, 1, A11, b1, noiseModel::Diagonal::Sigmas(s1, true)); gfg.add(1, A21, b2, noiseModel::Diagonal::Sigmas(s2, true)); - JacobianFactor actual = *CombineJacobians(*gfg.dynamicCastFactors > (), VariableSlots(gfg)); + // Convert to Jacobians, inefficient copy of all factors instead of selectively converting only Hessians + FactorGraph jacobians; + BOOST_FOREACH(const GaussianFactorGraph::sharedFactor& factor, gfg) { + jacobians.push_back(boost::make_shared(*factor)); + } + + // Combine Jacobians into a single dense factor + JacobianFactor actual = *CombineJacobians(jacobians, VariableSlots(gfg)); Matrix zero3x3 = zeros(3,3); - Matrix A0 = gtsam::stack(3, &A10, &zero3x3, &zero3x3); - Matrix A1 = gtsam::stack(3, &A11, &A01, &A21); - Vector b = gtsam::concatVectors(3, &b1, &b0, &b2); - Vector sigmas = gtsam::concatVectors(3, &s1, &s0, &s2); + Matrix A0 = gtsam::stack(3, &zero3x3, &A10, &zero3x3); + Matrix A1 = gtsam::stack(3, &A01, &A11, &A21); + Vector b = gtsam::concatVectors(3, &b0, &b1, &b2); + Vector sigmas = gtsam::concatVectors(3, &s0, &s1, &s2); JacobianFactor expected(0, A0, 1, A1, b, noiseModel::Diagonal::Sigmas(sigmas, true)); @@ -213,8 +217,7 @@ TEST(GaussianFactor, CombineAndEliminate) GaussianConditional::shared_ptr actualBN; GaussianFactor::shared_ptr actualFactor; - boost::tie(actualBN, actualFactor) = // - EliminateQR(*gfg.dynamicCastFactors > (), 1); + boost::tie(actualBN, actualFactor) = EliminateQR(gfg, 1); JacobianFactor::shared_ptr actualJacobian = boost::dynamic_pointer_cast< JacobianFactor>(actualFactor); @@ -231,26 +234,26 @@ TEST( NonlinearFactorGraph, combine2){ A11(1,0) = 0; A11(1,1) = 1; Vector b(2); b(0) = 2; b(1) = -1; - JacobianFactor::shared_ptr f1(new JacobianFactor(_x1_, A11, b*sigma1, sharedSigma(2,sigma1))); + JacobianFactor::shared_ptr f1(new JacobianFactor(_x1_, A11, b*sigma1, noiseModel::Isotropic::Sigma(2,sigma1))); double sigma2 = 0.5; A11(0,0) = 1; A11(0,1) = 0; A11(1,0) = 0; A11(1,1) = -1; b(0) = 4 ; b(1) = -5; - JacobianFactor::shared_ptr f2(new JacobianFactor(_x1_, A11, b*sigma2, sharedSigma(2,sigma2))); + JacobianFactor::shared_ptr f2(new JacobianFactor(_x1_, A11, b*sigma2, noiseModel::Isotropic::Sigma(2,sigma2))); double sigma3 = 0.25; A11(0,0) = 1; A11(0,1) = 0; A11(1,0) = 0; A11(1,1) = -1; b(0) = 3 ; b(1) = -88; - JacobianFactor::shared_ptr f3(new JacobianFactor(_x1_, A11, b*sigma3, sharedSigma(2,sigma3))); + JacobianFactor::shared_ptr f3(new JacobianFactor(_x1_, A11, b*sigma3, noiseModel::Isotropic::Sigma(2,sigma3))); // TODO: find a real sigma value for this example double sigma4 = 0.1; A11(0,0) = 6; A11(0,1) = 0; A11(1,0) = 0; A11(1,1) = 7; b(0) = 5 ; b(1) = -6; - JacobianFactor::shared_ptr f4(new JacobianFactor(_x1_, A11*sigma4, b*sigma4, sharedSigma(2,sigma4))); + JacobianFactor::shared_ptr f4(new JacobianFactor(_x1_, A11*sigma4, b*sigma4, noiseModel::Isotropic::Sigma(2,sigma4))); vector lfg; lfg.push_back(f1); @@ -283,7 +286,7 @@ TEST( NonlinearFactorGraph, combine2){ TEST(GaussianFactor, linearFactorN){ Matrix I = eye(2); vector f; - SharedDiagonal model = sharedSigma(2,1.0); + SharedDiagonal model = noiseModel::Isotropic::Sigma(2,1.0); f.push_back(JacobianFactor::shared_ptr(new JacobianFactor(_x1_, I, Vector_(2, 10.0, 5.0), model))); f.push_back(JacobianFactor::shared_ptr(new JacobianFactor(_x1_, -10 * I, @@ -371,7 +374,7 @@ TEST(GaussianFactor, eliminateFrontals) make_pair( 9, Matrix(Ab.block(0, 6, 4, 2))), make_pair(11, Matrix(Ab.block(0, 8, 4, 2))); Vector b1 = Ab.col(10).segment(0, 4); - JacobianFactor::shared_ptr factor1(new JacobianFactor(terms1, b1, sharedSigma(4, 0.5))); + JacobianFactor::shared_ptr factor1(new JacobianFactor(terms1, b1, noiseModel::Isotropic::Sigma(4, 0.5))); // Create second factor list > terms2; @@ -381,7 +384,7 @@ TEST(GaussianFactor, eliminateFrontals) make_pair(9, Matrix(Ab.block(4, 6, 4, 2))), make_pair(11,Matrix(Ab.block(4, 8, 4, 2))); Vector b2 = Ab.col(10).segment(4, 4); - JacobianFactor::shared_ptr factor2(new JacobianFactor(terms2, b2, sharedSigma(4, 0.5))); + JacobianFactor::shared_ptr factor2(new JacobianFactor(terms2, b2, noiseModel::Isotropic::Sigma(4, 0.5))); // Create third factor list > terms3; @@ -390,14 +393,14 @@ TEST(GaussianFactor, eliminateFrontals) make_pair(9, Matrix(Ab.block(8, 6, 4, 2))), make_pair(11,Matrix(Ab.block(8, 8, 4, 2))); Vector b3 = Ab.col(10).segment(8, 4); - JacobianFactor::shared_ptr factor3(new JacobianFactor(terms3, b3, sharedSigma(4, 0.5))); + JacobianFactor::shared_ptr factor3(new JacobianFactor(terms3, b3, noiseModel::Isotropic::Sigma(4, 0.5))); // Create fourth factor list > terms4; terms4 += make_pair(11, Matrix(Ab.block(12, 8, 2, 2))); Vector b4 = Ab.col(10).segment(12, 2); - JacobianFactor::shared_ptr factor4(new JacobianFactor(terms4, b4, sharedSigma(2, 0.5))); + JacobianFactor::shared_ptr factor4(new JacobianFactor(terms4, b4, noiseModel::Isotropic::Sigma(2, 0.5))); // Create factor graph GaussianFactorGraph factors; @@ -407,12 +410,17 @@ TEST(GaussianFactor, eliminateFrontals) factors.push_back(factor4); // extract the dense matrix for the graph - Matrix actualDense = factors.denseJacobian(); + Matrix actualDense = factors.augmentedJacobian(); EXPECT(assert_equal(2.0 * Ab, actualDense)); + // Convert to Jacobians, inefficient copy of all factors instead of selectively converting only Hessians + FactorGraph jacobians; + BOOST_FOREACH(const GaussianFactorGraph::sharedFactor& factor, factors) { + jacobians.push_back(boost::make_shared(*factor)); + } + // Create combined factor - JacobianFactor combined(*CombineJacobians(*factors.dynamicCastFactors > (), VariableSlots(factors))); + JacobianFactor combined(*CombineJacobians(jacobians, VariableSlots(factors))); // Copies factors as they will be eliminated in place JacobianFactor actualFactor_QR = combined; @@ -546,13 +554,13 @@ TEST(GaussianFactor, permuteWithInverse) inversePermutation[4] = 1; inversePermutation[5] = 0; - JacobianFactor actual(1, A1, 3, A2, 5, A3, b, sharedSigma(2, 1.0)); + JacobianFactor actual(1, A1, 3, A2, 5, A3, b, noiseModel::Isotropic::Sigma(2, 1.0)); GaussianFactorGraph actualFG; actualFG.push_back(JacobianFactor::shared_ptr(new JacobianFactor(actual))); VariableIndex actualIndex(actualFG); actual.permuteWithInverse(inversePermutation); // actualIndex.permute(*inversePermutation.inverse()); - JacobianFactor expected(4, A1, 2, A2, 0, A3, b, sharedSigma(2, 1.0)); + JacobianFactor expected(4, A1, 2, A2, 0, A3, b, noiseModel::Isotropic::Sigma(2, 1.0)); GaussianFactorGraph expectedFG; expectedFG.push_back(JacobianFactor::shared_ptr(new JacobianFactor(expected))); // GaussianVariableIndex expectedIndex(expectedFG); @@ -601,7 +609,7 @@ TEST(GaussianFactorGraph, sparseJacobian) { 4., 6.,32.).transpose(); GaussianFactorGraph gfg; - SharedDiagonal model = sharedSigma(2, 0.5); + SharedDiagonal model = noiseModel::Isotropic::Sigma(2, 0.5); gfg.add(0, Matrix_(2,3, 1., 2., 3., 5., 6., 7.), Vector_(2, 4., 8.), model); gfg.add(0, Matrix_(2,3, 9.,10., 0., 0., 0., 0.), 1, Matrix_(2,2, 11., 12., 14., 15.), Vector_(2, 13.,16.), model); @@ -611,7 +619,7 @@ TEST(GaussianFactorGraph, sparseJacobian) { } /* ************************************************************************* */ -TEST(GaussianFactorGraph, denseHessian) { +TEST(GaussianFactorGraph, matrices) { // Create factor graph: // x1 x2 x3 x4 x5 b // 1 2 3 0 0 4 @@ -620,7 +628,7 @@ TEST(GaussianFactorGraph, denseHessian) { // 0 0 0 14 15 16 GaussianFactorGraph gfg; - SharedDiagonal model = sharedUnit(2); + SharedDiagonal model = noiseModel::Unit::Create(2); gfg.add(0, Matrix_(2,3, 1., 2., 3., 5., 6., 7.), Vector_(2, 4., 8.), model); gfg.add(0, Matrix_(2,3, 9.,10., 0., 0., 0., 0.), 1, Matrix_(2,2, 11., 12., 14., 15.), Vector_(2, 13.,16.), model); @@ -631,9 +639,24 @@ TEST(GaussianFactorGraph, denseHessian) { 9,10, 0,11,12,13, 0, 0, 0,14,15,16; + Matrix expectedJacobian = jacobian; Matrix expectedHessian = jacobian.transpose() * jacobian; - Matrix actualHessian = gfg.denseHessian(); + Matrix expectedA = jacobian.leftCols(jacobian.cols()-1); + Vector expectedb = jacobian.col(jacobian.cols()-1); + Matrix expectedL = expectedA.transpose() * expectedA; + Vector expectedeta = expectedA.transpose() * expectedb; + + Matrix actualJacobian = gfg.augmentedJacobian(); + Matrix actualHessian = gfg.augmentedHessian(); + Matrix actualA; Vector actualb; boost::tie(actualA,actualb) = gfg.jacobian(); + Matrix actualL; Vector actualeta; boost::tie(actualL,actualeta) = gfg.hessian(); + + EXPECT(assert_equal(expectedJacobian, actualJacobian)); EXPECT(assert_equal(expectedHessian, actualHessian)); + EXPECT(assert_equal(expectedA, actualA)); + EXPECT(assert_equal(expectedb, actualb)); + EXPECT(assert_equal(expectedL, actualL)); + EXPECT(assert_equal(expectedeta, actualeta)); } /* ************************************************************************* */ diff --git a/gtsam/linear/tests/testGaussianJunctionTree.cpp b/gtsam/linear/tests/testGaussianJunctionTree.cpp index a10f80a4d..c4ddc360b 100644 --- a/gtsam/linear/tests/testGaussianJunctionTree.cpp +++ b/gtsam/linear/tests/testGaussianJunctionTree.cpp @@ -35,10 +35,10 @@ using namespace gtsam; static const Index x2=0, x1=1, x3=2, x4=3; -GaussianFactorGraph createChain() { +static GaussianFactorGraph createChain() { typedef GaussianFactorGraph::sharedFactor Factor; - SharedDiagonal model(Vector_(1, 0.5)); + SharedDiagonal model = noiseModel::Isotropic::Sigma(1, 0.5); Factor factor1(new JacobianFactor(x2, Matrix_(1,1,1.), x1, Matrix_(1,1,1.), Vector_(1,1.), model)); Factor factor2(new JacobianFactor(x2, Matrix_(1,1,1.), x3, Matrix_(1,1,1.), Vector_(1,1.), model)); Factor factor3(new JacobianFactor(x3, Matrix_(1,1,1.), x4, Matrix_(1,1,1.), Vector_(1,1.), model)); diff --git a/gtsam/linear/tests/testHessianFactor.cpp b/gtsam/linear/tests/testHessianFactor.cpp index 59873862a..9c2adcffa 100644 --- a/gtsam/linear/tests/testHessianFactor.cpp +++ b/gtsam/linear/tests/testHessianFactor.cpp @@ -93,7 +93,7 @@ TEST(HessianFactor, ConversionConstructor) { vector > meas; meas.push_back(make_pair(0, Ax2)); meas.push_back(make_pair(1, Al1x1)); - JacobianFactor combined(meas, b2, sigmas); + JacobianFactor combined(meas, b2, noiseModel::Diagonal::Sigmas(sigmas)); HessianFactor actual(combined); @@ -414,10 +414,20 @@ TEST_UNSAFE(HessianFactor, CombineAndEliminate) // create expected Hessian after elimination HessianFactor expectedCholeskyFactor(expectedFactor); - GaussianFactorGraph::EliminationResult actualCholesky = EliminateCholesky( - *gfg.convertCastFactors > (), 1); - HessianFactor::shared_ptr actualFactor = boost::dynamic_pointer_cast< - HessianFactor>(actualCholesky.second); + // Convert all factors to hessians + FactorGraph hessians; + BOOST_FOREACH(const GaussianFactorGraph::sharedFactor& factor, gfg) { + if(boost::shared_ptr hf = boost::dynamic_pointer_cast(factor)) + hessians.push_back(hf); + else if(boost::shared_ptr jf = boost::dynamic_pointer_cast(factor)) + hessians.push_back(boost::make_shared(*jf)); + else + CHECK(false); + } + + // Eliminate + GaussianFactorGraph::EliminationResult actualCholesky = EliminateCholesky(gfg, 1); + HessianFactor::shared_ptr actualFactor = boost::dynamic_pointer_cast(actualCholesky.second); EXPECT(assert_equal(*expectedBN, *actualCholesky.first, 1e-6)); EXPECT(assert_equal(expectedCholeskyFactor, *actualFactor, 1e-6)); @@ -458,7 +468,7 @@ TEST(HessianFactor, eliminate2 ) vector > meas; meas.push_back(make_pair(0, Ax2)); meas.push_back(make_pair(1, Al1x1)); - JacobianFactor combined(meas, b2, sigmas); + JacobianFactor combined(meas, b2, noiseModel::Diagonal::Sigmas(sigmas)); // eliminate the combined factor HessianFactor::shared_ptr combinedLF_Chol(new HessianFactor(combined)); @@ -492,7 +502,7 @@ TEST(HessianFactor, eliminate2 ) 0.00, 1.00, +0.00, -1.00 )/sigma; Vector b1 = Vector_(2,0.0,0.894427); - JacobianFactor expectedLF(1, Bl1x1, b1, repeat(2,1.0)); + JacobianFactor expectedLF(1, Bl1x1, b1, noiseModel::Isotropic::Sigma(2,1.0)); EXPECT(assert_equal(HessianFactor(expectedLF), *actualFactor, 1.5e-3)); } diff --git a/gtsam/linear/tests/testJacobianFactor.cpp b/gtsam/linear/tests/testJacobianFactor.cpp index 0d46807b6..9b6071935 100644 --- a/gtsam/linear/tests/testJacobianFactor.cpp +++ b/gtsam/linear/tests/testJacobianFactor.cpp @@ -26,11 +26,9 @@ using namespace std; using namespace gtsam; -static const Index _x0_=0, _x1_=1, _x2_=2, _x3_=3, _x4_=4, _x_=5, _y_=6, _l1_=7, _l11_=8; +static const Index _x0_=0, _x1_=1, _x2_=2, _x_=5, _y_=6, _l11_=8; -static SharedDiagonal - sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2), - constraintModel = noiseModel::Constrained::All(2); +static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); /* ************************************************************************* */ TEST(JacobianFactor, constructor) @@ -76,7 +74,7 @@ TEST(JacobianFactor, constructor2) JacobianFactor construct() { Matrix A = Matrix_(2,2, 1.,2.,3.,4.); Vector b = Vector_(2, 1.0, 2.0); - SharedDiagonal s = sharedSigmas(Vector_(2, 3.0, 4.0)); + SharedDiagonal s = noiseModel::Diagonal::Sigmas(Vector_(2, 3.0, 4.0)); JacobianFactor::shared_ptr shared( new JacobianFactor(0, A, b, s)); return *shared; @@ -86,7 +84,7 @@ TEST(JacobianFactor, return_value) { Matrix A = Matrix_(2,2, 1.,2.,3.,4.); Vector b = Vector_(2, 1.0, 2.0); - SharedDiagonal s = sharedSigmas(Vector_(2, 3.0, 4.0)); + SharedDiagonal s = noiseModel::Diagonal::Sigmas(Vector_(2, 3.0, 4.0)); JacobianFactor copied = construct(); EXPECT(assert_equal(b, copied.getb())); EXPECT(assert_equal(*s, *copied.get_model())); @@ -107,7 +105,7 @@ TEST(JabobianFactor, Hessian_conversion) { 1.2530, 2.1508, -0.8779, -1.8755, 0, 2.5858, 0.4789, -2.3943).finished(), (Vector(2) << -6.2929, -5.7941).finished(), - sharedUnit(2)); + noiseModel::Unit::Create(2)); JacobianFactor actual(hessian); @@ -140,6 +138,8 @@ TEST(JacobianFactor, error) { #ifdef BROKEN TEST(JacobianFactor, operators ) { + SharedDiagonal sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); + Matrix I = eye(2); Vector b = Vector_(2,0.2,-0.1); JacobianFactor lf(_x1_, -I, _x2_, I, b, sigma0_1); @@ -202,7 +202,7 @@ TEST(JacobianFactor, eliminate2 ) vector > meas; meas.push_back(make_pair(_x2_, Ax2)); meas.push_back(make_pair(_l11_, Al1x1)); - JacobianFactor combined(meas, b2, sigmas); + JacobianFactor combined(meas, b2, noiseModel::Diagonal::Sigmas(sigmas)); // eliminate the combined factor GaussianConditional::shared_ptr actualCG_QR; @@ -236,7 +236,7 @@ TEST(JacobianFactor, eliminate2 ) 0.00, 1.00, +0.00, -1.00 )/sigma; Vector b1 = Vector_(2,0.0,0.894427); - JacobianFactor expectedLF(_l11_, Bl1x1, b1, repeat(2,1.0)); + JacobianFactor expectedLF(_l11_, Bl1x1, b1, noiseModel::Isotropic::Sigma(2,1.0)); EXPECT(assert_equal(expectedLF,*actualLF_QR,1e-3)); } @@ -304,7 +304,7 @@ TEST(JacobianFactor, CONSTRUCTOR_GaussianConditional ) // Call the constructor we are testing ! JacobianFactor actualLF(*CG); - JacobianFactor expectedLF(_x2_,R11,_l11_,S12,d, sigmas); + JacobianFactor expectedLF(_x2_,R11,_l11_,S12,d, noiseModel::Diagonal::Sigmas(sigmas)); EXPECT(assert_equal(expectedLF,actualLF,1e-5)); } diff --git a/gtsam/linear/tests/testJacobianFactorGraph.cpp b/gtsam/linear/tests/testJacobianFactorGraph.cpp new file mode 100644 index 000000000..07dda4652 --- /dev/null +++ b/gtsam/linear/tests/testJacobianFactorGraph.cpp @@ -0,0 +1,92 @@ +/* ---------------------------------------------------------------------------- + + * 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 testJacobianFactorGraph.cpp + * @brief Unit tests for GaussianFactorGraph + * @author Yong Dian Jian + **/ + +#include +#include + + +///* ************************************************************************* */ +//TEST( GaussianFactorGraph, gradient ) +//{ +// GaussianFactorGraph fg = createGaussianFactorGraph(); +// +// // Construct expected gradient +// VectorValues expected; +// +// // 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(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(); +// VectorValues actual = fg.gradient(zero); +// EXPECT(assert_equal(expected,actual)); +// +// // Check it numerically for good measure +// Vector numerical_g = numericalGradient(error,zero,0.001); +// EXPECT(assert_equal(Vector_(6,5.0,-12.5,30.0,5.0,-25.0,17.5),numerical_g)); +// +// // Check the gradient at the solution (should be zero) +// Ordering ord; +// ord += X(2),L(1),X(1); +// GaussianFactorGraph fg2 = createGaussianFactorGraph(); +// VectorValues solution = fg2.optimize(ord); // destructive +// VectorValues actual2 = fg.gradient(solution); +// EXPECT(assert_equal(zero,actual2)); +//} + +///* ************************************************************************* */ +//TEST( GaussianFactorGraph, transposeMultiplication ) +//{ +// // create an ordering +// Ordering ord; ord += X(2),L(1),X(1); +// +// GaussianFactorGraph A = createGaussianFactorGraph(ord); +// Errors e; +// e += Vector_(2, 0.0, 0.0); +// e += Vector_(2,15.0, 0.0); +// e += Vector_(2, 0.0,-5.0); +// e += Vector_(2,-7.5,-5.0); +// +// VectorValues expected = createZeroDelta(ord), actual = A ^ e; +// 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)); +//} + +///* ************************************************************************* */ +//TEST( GaussianFactorGraph, rhs ) +//{ +// // create an ordering +// Ordering ord; ord += X(2),L(1),X(1); +// +// GaussianFactorGraph Ab = createGaussianFactorGraph(ord); +// Errors expected = createZeroDelta(ord), actual = Ab.rhs(); +// expected.push_back(Vector_(2,-1.0,-1.0)); +// expected.push_back(Vector_(2, 2.0,-1.0)); +// expected.push_back(Vector_(2, 0.0, 1.0)); +// expected.push_back(Vector_(2,-1.0, 1.5)); +// EXPECT(assert_equal(expected,actual)); +//} + + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr);} +/* ************************************************************************* */ diff --git a/gtsam/linear/tests/testKalmanFilter.cpp b/gtsam/linear/tests/testKalmanFilter.cpp index ca50c12e9..b45ac6a7b 100644 --- a/gtsam/linear/tests/testKalmanFilter.cpp +++ b/gtsam/linear/tests/testKalmanFilter.cpp @@ -18,8 +18,7 @@ */ #include -#include -#include +#include #include #include diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index 6ca0ccd81..224395051 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -25,8 +25,6 @@ using namespace boost::assign; #include #include #include -#include -#include using namespace std; using namespace gtsam; @@ -131,15 +129,6 @@ TEST(NoiseModel, equals) EXPECT(assert_inequal(*i1,*i2)); } -/* ************************************************************************* */ -TEST(NoiseModel, sample) -{ - Vector s = Vector_(3,1.0,2.0,3.0); - SharedDiagonal model = sharedSigmas(s); - Vector v = model->sample(); - // no check as no way yet to set random seed -} - // TODO enable test once a mechanism for smart constraints exists ///* ************************************************************************* */ //TEST(NoiseModel, ConstrainedSmart ) @@ -258,18 +247,6 @@ TEST( NoiseModel, QR ) EXPECT(linear_dependent(expectedRd2,Ab2,1e-6)); // Ab was modified in place !!! } -/* ************************************************************************* */ -TEST(NoiseModel, Cholesky) -{ - SharedDiagonal expected = noiseModel::Unit::Create(4); - Matrix Ab = exampleQR::Ab; // otherwise overwritten ! - SharedDiagonal actual = exampleQR::diagonal->Cholesky(Ab, 4); - EXPECT(assert_equal(*expected,*actual)); - // Ab was modified in place !!! - Matrix actualRd = Ab.block(0, 0, actual->dim(), Ab.cols()).triangularView(); - EXPECT(linear_dependent(exampleQR::Rd,actualRd,1e-4)); -} - /* ************************************************************************* */ TEST(NoiseModel, QRNan ) { @@ -288,8 +265,8 @@ TEST(NoiseModel, QRNan ) TEST(NoiseModel, SmartCovariance ) { bool smart = true; - SharedGaussian expected = Unit::Create(3); - SharedGaussian actual = Gaussian::Covariance(eye(3), smart); + gtsam::SharedGaussian expected = Unit::Create(3); + gtsam::SharedGaussian actual = Gaussian::Covariance(eye(3), smart); EXPECT(assert_equal(*expected,*actual)); } @@ -306,7 +283,7 @@ TEST(NoiseModel, ScalarOrVector ) TEST(NoiseModel, WhitenInPlace) { Vector sigmas = Vector_(3, 0.1, 0.1, 0.1); - SharedDiagonal model(sigmas); + SharedDiagonal model = Diagonal::Sigmas(sigmas); Matrix A = eye(3); model->WhitenInPlace(A); Matrix expected = eye(3) * 10; @@ -346,8 +323,5 @@ TEST(NoiseModel, robustNoise) } /* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/linear/tests/testSampler.cpp b/gtsam/linear/tests/testSampler.cpp index e01788b65..ffb546e40 100644 --- a/gtsam/linear/tests/testSampler.cpp +++ b/gtsam/linear/tests/testSampler.cpp @@ -25,7 +25,7 @@ const double tol = 1e-5; /* ************************************************************************* */ TEST(testSampler, basic) { Vector sigmas = Vector_(3, 1.0, 0.1, 0.0); - SharedDiagonal model = noiseModel::Diagonal::Sigmas(sigmas); + noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(sigmas); char seed = 'A'; Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1); EXPECT(assert_equal(sigmas, sampler1.sigmas())); diff --git a/gtsam/linear/tests/testSerializationLinear.cpp b/gtsam/linear/tests/testSerializationLinear.cpp index 8082d3626..e8a53c504 100644 --- a/gtsam/linear/tests/testSerializationLinear.cpp +++ b/gtsam/linear/tests/testSerializationLinear.cpp @@ -22,9 +22,6 @@ #include #include #include -#include -#include -#include #include #include @@ -50,11 +47,11 @@ BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); /* ************************************************************************* */ // example noise models -noiseModel::Diagonal::shared_ptr diag3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3)); -noiseModel::Gaussian::shared_ptr gaussian3 = noiseModel::Gaussian::SqrtInformation(2.0 * eye(3,3)); -noiseModel::Isotropic::shared_ptr iso3 = noiseModel::Isotropic::Sigma(3, 0.2); -noiseModel::Constrained::shared_ptr constrained3 = noiseModel::Constrained::MixedSigmas(Vector_(3, 0.0, 0.0, 0.1)); -noiseModel::Unit::shared_ptr unit3 = noiseModel::Unit::Create(3); +static noiseModel::Diagonal::shared_ptr diag3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3)); +static noiseModel::Gaussian::shared_ptr gaussian3 = noiseModel::Gaussian::SqrtInformation(2.0 * eye(3,3)); +static noiseModel::Isotropic::shared_ptr iso3 = noiseModel::Isotropic::Sigma(3, 0.2); +static noiseModel::Constrained::shared_ptr constrained3 = noiseModel::Constrained::MixedSigmas(Vector_(3, 0.0, 0.0, 0.1)); +static noiseModel::Unit::shared_ptr unit3 = noiseModel::Unit::Create(3); /* ************************************************************************* */ TEST (Serialization, noiseModels) { diff --git a/gtsam/linear/tests/testVectorValues.cpp b/gtsam/linear/tests/testVectorValues.cpp index a92b81ddc..17230854a 100644 --- a/gtsam/linear/tests/testVectorValues.cpp +++ b/gtsam/linear/tests/testVectorValues.cpp @@ -421,52 +421,31 @@ TEST(VectorValues, hasSameStructure) { EXPECT(!v1.hasSameStructure(VectorValues())); } + /* ************************************************************************* */ -TEST(VectorValues, permuted_combined) { - Vector v1 = Vector_(3, 1.0,2.0,3.0); - Vector v2 = Vector_(2, 4.0,5.0); - Vector v3 = Vector_(4, 6.0,7.0,8.0,9.0); +TEST(VectorValues, permute) { - vector dims(3); dims[0]=3; dims[1]=2; dims[2]=4; - VectorValues combined(dims); - combined[0] = v1; - combined[1] = v2; - combined[2] = v3; + VectorValues original; + original.insert(0, Vector_(1, 1.0)); + original.insert(1, Vector_(2, 2.0, 3.0)); + original.insert(2, Vector_(2, 4.0, 5.0)); + original.insert(3, Vector_(2, 6.0, 7.0)); - Permutation perm1(3); - perm1[0] = 1; - perm1[1] = 2; - perm1[2] = 0; + VectorValues expected; + expected.insert(0, Vector_(2, 4.0, 5.0)); // from 2 + expected.insert(1, Vector_(1, 1.0)); // from 0 + expected.insert(2, Vector_(2, 6.0, 7.0)); // from 3 + expected.insert(3, Vector_(2, 2.0, 3.0)); // from 1 - Permutation perm2(3); - perm2[0] = 1; - perm2[1] = 2; - perm2[2] = 0; + Permutation permutation(4); + permutation[0] = 2; + permutation[1] = 0; + permutation[2] = 3; + permutation[3] = 1; - Permuted permuted1(combined); - CHECK(assert_equal(v1, permuted1[0])) - CHECK(assert_equal(v2, permuted1[1])) - CHECK(assert_equal(v3, permuted1[2])) + VectorValues actual = original.permute(permutation); - permuted1.permute(perm1); - CHECK(assert_equal(v1, permuted1[2])) - CHECK(assert_equal(v2, permuted1[0])) - CHECK(assert_equal(v3, permuted1[1])) - - permuted1.permute(perm2); - CHECK(assert_equal(v1, permuted1[1])) - CHECK(assert_equal(v2, permuted1[2])) - CHECK(assert_equal(v3, permuted1[0])) - - Permuted permuted2(perm1, combined); - CHECK(assert_equal(v1, permuted2[2])) - CHECK(assert_equal(v2, permuted2[0])) - CHECK(assert_equal(v3, permuted2[1])) - - permuted2.permute(perm2); - CHECK(assert_equal(v1, permuted2[1])) - CHECK(assert_equal(v2, permuted2[2])) - CHECK(assert_equal(v3, permuted2[0])) + EXPECT(assert_equal(expected, actual)); } /* ************************************************************************* */ diff --git a/gtsam/linear/tests/timeFactorOverhead.cpp b/gtsam/linear/tests/timeFactorOverhead.cpp index a843efd84..5ca4ceb59 100644 --- a/gtsam/linear/tests/timeFactorOverhead.cpp +++ b/gtsam/linear/tests/timeFactorOverhead.cpp @@ -60,7 +60,7 @@ int main(int argc, char *argv[]) { blockGfgs.reserve(nTrials); for(size_t trial=0; trial combGfgs; for(size_t trial=0; trial > terms; terms.reserve(varsPerBlock); diff --git a/gtsam/mainpage.dox b/gtsam/mainpage.dox index e81fc1f65..db42b1277 100644 --- a/gtsam/mainpage.dox +++ b/gtsam/mainpage.dox @@ -9,9 +9,9 @@ namespace gtsam { \section new_factor_variable_types Creating new factor and variable types GTSAM comes with a set of variable and factor types typically used in SFM and -SLAM. Geometry variables such as points and poses are in the \ref geometry +SLAM. Geometry variables such as points and poses are in the geometry subdirectory and module. Factors such as BetweenFactor and BearingFactor are in -the \ref gtsam/slam directory. +the gtsam/slam directory. To use GTSAM to solve your own problems, you will often have to create new factor types, which derive either from NonlinearFactor or NoiseModelFactor, or one of their derived types. Here is an outline of the options: diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 84090d666..e3f4e4dcd 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -13,7 +13,7 @@ * @file DoglegOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #include @@ -22,10 +22,33 @@ #include #include +#include + using namespace std; namespace gtsam { +/* ************************************************************************* */ +DoglegParams::VerbosityDL DoglegParams::verbosityDLTranslator(const std::string &verbosityDL) const { + std::string s = verbosityDL; boost::algorithm::to_upper(s); + if (s == "SILENT") return DoglegParams::SILENT; + if (s == "VERBOSE") return DoglegParams::VERBOSE; + + /* default is silent */ + return DoglegParams::SILENT; +} + +/* ************************************************************************* */ +std::string DoglegParams::verbosityDLTranslator(VerbosityDL verbosityDL) const { + std::string s; + switch (verbosityDL) { + case DoglegParams::SILENT: s = "SILENT"; break; + case DoglegParams::VERBOSE: s = "VERBOSE"; break; + default: s = "UNDEFINED"; break; + } + return s; +} + /* ************************************************************************* */ void DoglegOptimizer::iterate(void) { @@ -33,25 +56,25 @@ void DoglegOptimizer::iterate(void) { const Ordering& ordering = *params_.ordering; GaussianFactorGraph::shared_ptr linear = graph_.linearize(state_.values, ordering); - // Get elimination method - GaussianFactorGraph::Eliminate eliminationMethod = params_.getEliminationFunction(); - // Pull out parameters we'll use const bool dlVerbose = (params_.verbosityDL > DoglegParams::SILENT); // Do Dogleg iteration with either Multifrontal or Sequential elimination DoglegOptimizerImpl::IterationResult result; - if(params_.elimination == DoglegParams::MULTIFRONTAL) { + if ( params_.isMultifrontal() ) { GaussianBayesTree bt; - bt.insert(GaussianJunctionTree(*linear).eliminate(eliminationMethod)); + bt.insert(GaussianJunctionTree(*linear).eliminate(params_.getEliminationFunction())); result = DoglegOptimizerImpl::Iterate(state_.Delta, DoglegOptimizerImpl::ONE_STEP_PER_ITERATION, bt, graph_, state_.values, ordering, state_.error, dlVerbose); - - } else if(params_.elimination == DoglegParams::SEQUENTIAL) { - GaussianBayesNet::shared_ptr bn = EliminationTree::Create(*linear)->eliminate(eliminationMethod); + } + else if ( params_.isSequential() ) { + GaussianBayesNet::shared_ptr bn = EliminationTree::Create(*linear)->eliminate(params_.getEliminationFunction()); result = DoglegOptimizerImpl::Iterate(state_.Delta, DoglegOptimizerImpl::ONE_STEP_PER_ITERATION, *bn, graph_, state_.values, ordering, state_.error, dlVerbose); - - } else { + } + else if ( params_.isCG() ) { + throw runtime_error("todo: "); + } + else { throw runtime_error("Optimization parameter is invalid: DoglegParams::elimination"); } diff --git a/gtsam/nonlinear/DoglegOptimizer.h b/gtsam/nonlinear/DoglegOptimizer.h index 7edb43ca9..71551dce1 100644 --- a/gtsam/nonlinear/DoglegOptimizer.h +++ b/gtsam/nonlinear/DoglegOptimizer.h @@ -13,7 +13,7 @@ * @file DoglegOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once @@ -50,6 +50,16 @@ public: std::cout << " deltaInitial: " << deltaInitial << "\n"; std::cout.flush(); } + + double getDeltaInitial() const { return deltaInitial; } + std::string getVerbosityDL() const { return verbosityDLTranslator(verbosityDL); } + + void setDeltaInitial(double deltaInitial) { this->deltaInitial = deltaInitial; } + void setVerbosityDL(const std::string& verbosityDL) { this->verbosityDL = verbosityDLTranslator(verbosityDL); } + +private: + VerbosityDL verbosityDLTranslator(const std::string& verbosityDL) const; + std::string verbosityDLTranslator(VerbosityDL verbosityDL) const; }; /** @@ -57,7 +67,6 @@ public: */ class DoglegState : public NonlinearOptimizerState { public: - double Delta; DoglegState() {} @@ -76,8 +85,11 @@ protected: */ class DoglegOptimizer : public NonlinearOptimizer { -public: +protected: + DoglegParams params_; + DoglegState state_; +public: typedef boost::shared_ptr shared_ptr; /// @name Standard interface @@ -101,7 +113,6 @@ public: * copies the objects. * @param graph The nonlinear factor graph to optimize * @param initialValues The initial variable assignments - * @param params The optimization parameters */ DoglegOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues, const Ordering& ordering) : NonlinearOptimizer(graph) { @@ -129,14 +140,11 @@ public: const DoglegState& state() const { return state_; } /** Access the current trust region radius Delta */ - double Delta() const { return state_.Delta; } + double getDelta() const { return state_.Delta; } /// @} protected: - DoglegParams params_; - DoglegState state_; - /** Access the parameters (base class version) */ virtual const NonlinearOptimizerParams& _params() const { return params_; } diff --git a/gtsam/nonlinear/DoglegOptimizerImpl.cpp b/gtsam/nonlinear/DoglegOptimizerImpl.cpp index 480d76f6a..b46fc6a3f 100644 --- a/gtsam/nonlinear/DoglegOptimizerImpl.cpp +++ b/gtsam/nonlinear/DoglegOptimizerImpl.cpp @@ -15,8 +15,11 @@ * @author Richard Roberts */ +#include #include +using namespace std; + namespace gtsam { /* ************************************************************************* */ VectorValues DoglegOptimizerImpl::ComputeDoglegPoint( @@ -27,12 +30,12 @@ VectorValues DoglegOptimizerImpl::ComputeDoglegPoint( double DeltaSq = Delta*Delta; double x_u_norm_sq = dx_u.vector().squaredNorm(); double x_n_norm_sq = dx_n.vector().squaredNorm(); - if(verbose) cout << "Steepest descent magnitude " << sqrt(x_u_norm_sq) << ", Newton's method magnitude " << sqrt(x_n_norm_sq) << endl; + if(verbose) cout << "Steepest descent magnitude " << std::sqrt(x_u_norm_sq) << ", Newton's method magnitude " << std::sqrt(x_n_norm_sq) << endl; if(DeltaSq < x_u_norm_sq) { // Trust region is smaller than steepest descent update VectorValues x_d = VectorValues::SameStructure(dx_u); - x_d.vector() = dx_u.vector() * sqrt(DeltaSq / x_u_norm_sq); - if(verbose) cout << "In steepest descent region with fraction " << sqrt(DeltaSq / x_u_norm_sq) << " of steepest descent magnitude" << endl; + x_d.vector() = dx_u.vector() * std::sqrt(DeltaSq / x_u_norm_sq); + if(verbose) cout << "In steepest descent region with fraction " << std::sqrt(DeltaSq / x_u_norm_sq) << " of steepest descent magnitude" << endl; return x_d; } else if(DeltaSq < x_n_norm_sq) { // Trust region boundary is between steepest descent point and Newton's method point @@ -59,7 +62,7 @@ VectorValues DoglegOptimizerImpl::ComputeBlend(double Delta, const VectorValues& const double a = uu - 2.*un + nn; const double b = 2. * (un - uu); const double c = uu - Delta*Delta; - double sqrt_b_m4ac = sqrt(b*b - 4*a*c); + double sqrt_b_m4ac = std::sqrt(b*b - 4*a*c); // Compute blending parameter double tau1 = (-b + sqrt_b_m4ac) / (2.*a); diff --git a/gtsam/nonlinear/DoglegOptimizerImpl.h b/gtsam/nonlinear/DoglegOptimizerImpl.h index 03951babf..fa2179afa 100644 --- a/gtsam/nonlinear/DoglegOptimizerImpl.h +++ b/gtsam/nonlinear/DoglegOptimizerImpl.h @@ -61,6 +61,7 @@ struct DoglegOptimizerImpl { */ enum TrustRegionAdaptationMode { SEARCH_EACH_ITERATION, + SEARCH_REDUCE_ONLY, ONE_STEP_PER_ITERATION }; @@ -72,7 +73,7 @@ struct DoglegOptimizerImpl { * * The update is computed using a quadratic approximation \f$ M(\delta x) \f$ * of an original nonlinear error function (a NonlinearFactorGraph) \f$ f(x) \f$. - * The quadratic approximation is represented as a GaussianBayesNet \bayesNet, which is + * The quadratic approximation is represented as a GaussianBayesNet \f$ \bayesNet \f$, which is * obtained by eliminating a GaussianFactorGraph resulting from linearizing * the nonlinear factor graph \f$ f(x) \f$. Thus, \f$ M(\delta x) \f$ is * \f[ @@ -93,8 +94,8 @@ struct DoglegOptimizerImpl { * @param Rd The Bayes' net or tree as described above. * @param f The original nonlinear factor graph with which to evaluate the * accuracy of \f$ M(\delta x) \f$ to adjust \f$ \Delta \f$. - * @param x0 The linearization point about which \bayesNet was created - * @param ordering The variable ordering used to create \bayesNet + * @param x0 The linearization point about which \f$ \bayesNet \f$ was created + * @param ordering The variable ordering used to create\f$ \bayesNet \f$ * @param f_error The result of f.error(x0). * @return A DoglegIterationResult containing the new \c Delta, the linear * update \c dx_d, and the resulting nonlinear error \c f_error. @@ -111,7 +112,7 @@ struct DoglegOptimizerImpl { * * The update is computed using a quadratic approximation \f$ M(\delta x) \f$ * of an original nonlinear error function (a NonlinearFactorGraph) \f$ f(x) \f$. - * The quadratic approximation is represented as a GaussianBayesNet \bayesNet, which is + * The quadratic approximation is represented as a GaussianBayesNet \f$ \bayesNet \f$, which is * obtained by eliminating a GaussianFactorGraph resulting from linearizing * the nonlinear factor graph \f$ f(x) \f$. Thus, \f$ M(\delta x) \f$ is * \f[ @@ -134,8 +135,8 @@ struct DoglegOptimizerImpl { * \f$ \| (1-\tau)\delta x_u + \tau\delta x_n \| = \Delta \f$, where \f$ \Delta \f$ * is the trust region radius. * @param Delta Trust region radius - * @param xu Steepest descent minimizer - * @param xn Newton's method minimizer + * @param x_u Steepest descent minimizer + * @param x_n Newton's method minimizer */ static VectorValues ComputeBlend(double Delta, const VectorValues& x_u, const VectorValues& x_n, const bool verbose=false); }; @@ -176,7 +177,7 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate( result.dx_d = ComputeDoglegPoint(Delta, dx_u, dx_n, verbose); toc(3, "Dog leg point"); - if(verbose) cout << "Delta = " << Delta << ", dx_d_norm = " << result.dx_d.vector().norm() << endl; + if(verbose) std::cout << "Delta = " << Delta << ", dx_d_norm = " << result.dx_d.vector().norm() << std::endl; tic(4, "retract"); // Compute expmapped solution @@ -193,8 +194,8 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate( const double new_M_error = jfg.error(result.dx_d); toc(6, "decrease in M"); - if(verbose) cout << setprecision(15) << "f error: " << f_error << " -> " << result.f_error << endl; - if(verbose) cout << setprecision(15) << "M error: " << M_error << " -> " << new_M_error << endl; + if(verbose) std::cout << std::setprecision(15) << "f error: " << f_error << " -> " << result.f_error << std::endl; + if(verbose) std::cout << std::setprecision(15) << "M error: " << M_error << " -> " << new_M_error << std::endl; tic(7, "adjust Delta"); // Compute gain ratio. Here we take advantage of the invariant that the @@ -203,14 +204,14 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate( 0.5 : (f_error - result.f_error) / (M_error - new_M_error); - if(verbose) cout << setprecision(15) << "rho = " << rho << endl; + if(verbose) std::cout << std::setprecision(15) << "rho = " << rho << std::endl; if(rho >= 0.75) { // M agrees very well with f, so try to increase lambda const double dx_d_norm = result.dx_d.vector().norm(); const double newDelta = std::max(Delta, 3.0 * dx_d_norm); // Compute new Delta - if(mode == ONE_STEP_PER_ITERATION) + if(mode == ONE_STEP_PER_ITERATION || mode == SEARCH_REDUCE_ONLY) stay = false; // If not searching, just return with the new Delta else if(mode == SEARCH_EACH_ITERATION) { if(newDelta == Delta || lastAction == DECREASED_DELTA) @@ -231,13 +232,17 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate( } else if(0.25 > rho && rho >= 0.0) { // M does not agree well with f, decrease Delta until it does double newDelta; - if(Delta > 1e-5) + bool hitMinimumDelta; + if(Delta > 1e-5) { newDelta = 0.5 * Delta; - else + hitMinimumDelta = false; + } else { newDelta = Delta; - if(mode == ONE_STEP_PER_ITERATION || lastAction == INCREASED_DELTA || newDelta == Delta) + hitMinimumDelta = true; + } + if(mode == ONE_STEP_PER_ITERATION || /* mode == SEARCH_EACH_ITERATION && */ lastAction == INCREASED_DELTA || hitMinimumDelta) stay = false; // If not searching, just return with the new smaller delta - else if(mode == SEARCH_EACH_ITERATION) { + else if(mode == SEARCH_EACH_ITERATION || mode == SEARCH_REDUCE_ONLY) { stay = true; lastAction = DECREASED_DELTA; } else { @@ -246,14 +251,18 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate( Delta = newDelta; // Update Delta from new Delta } else { - // f actually increased, so keep decreasing Delta until f does not decrease + // f actually increased, so keep decreasing Delta until f does not decrease. + // NOTE: NaN and Inf solutions also will fall into this case, so that we + // decrease Delta if the solution becomes undetermined. assert(0.0 > rho); if(Delta > 1e-5) { Delta *= 0.5; stay = true; lastAction = DECREASED_DELTA; } else { - if(verbose) cout << "Warning: Dog leg stopping because cannot decrease error with minimum Delta" << endl; + if(verbose) std::cout << "Warning: Dog leg stopping because cannot decrease error with minimum Delta" << std::endl; + result.dx_d.setZero(); // Set delta to zero - don't allow error to increase + result.f_error = f_error; stay = false; } } diff --git a/gtsam/nonlinear/ExtendedKalmanFilter.h b/gtsam/nonlinear/ExtendedKalmanFilter.h index 353439d98..ebca4899c 100644 --- a/gtsam/nonlinear/ExtendedKalmanFilter.h +++ b/gtsam/nonlinear/ExtendedKalmanFilter.h @@ -90,3 +90,5 @@ namespace gtsam { }; } // namespace + +#include diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.cpp b/gtsam/nonlinear/GaussNewtonOptimizer.cpp index 8e2b20859..05ba56a21 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.cpp +++ b/gtsam/nonlinear/GaussNewtonOptimizer.cpp @@ -13,11 +13,9 @@ * @file GaussNewtonOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ -#include -#include #include using namespace std; @@ -32,17 +30,8 @@ void GaussNewtonOptimizer::iterate() { // Linearize graph GaussianFactorGraph::shared_ptr linear = graph_.linearize(current.values, *params_.ordering); - // Optimize - VectorValues delta; - { - GaussianFactorGraph::Eliminate eliminationMethod = params_.getEliminationFunction(); - if(params_.elimination == GaussNewtonParams::MULTIFRONTAL) - delta = GaussianJunctionTree(*linear).optimize(eliminationMethod); - else if(params_.elimination == GaussNewtonParams::SEQUENTIAL) - delta = gtsam::optimize(*EliminationTree::Create(*linear)->eliminate(eliminationMethod)); - else - throw runtime_error("Optimization parameter is invalid: GaussNewtonParams::elimination"); - } + // Solve Factor Graph + const VectorValues delta = solveGaussianFactorGraph(*linear, params_); // Maybe show output if(params_.verbosity >= NonlinearOptimizerParams::DELTA) delta.print("delta"); diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.h b/gtsam/nonlinear/GaussNewtonOptimizer.h index 39b64b667..b68ac4fc5 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.h +++ b/gtsam/nonlinear/GaussNewtonOptimizer.h @@ -13,7 +13,7 @@ * @file GaussNewtonOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once @@ -43,8 +43,11 @@ protected: */ class GaussNewtonOptimizer : public NonlinearOptimizer { -public: +protected: + GaussNewtonParams params_; + GaussNewtonState state_; +public: /// @name Standard interface /// @{ @@ -66,7 +69,6 @@ public: * copies the objects. * @param graph The nonlinear factor graph to optimize * @param initialValues The initial variable assignments - * @param params The optimization parameters */ GaussNewtonOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues, const Ordering& ordering) : NonlinearOptimizer(graph), state_(graph, initialValues) { @@ -95,10 +97,6 @@ public: /// @} protected: - - GaussNewtonParams params_; - GaussNewtonState state_; - /** Access the parameters (base class version) */ virtual const NonlinearOptimizerParams& _params() const { return params_; } diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index 8fe117e34..f3b27b138 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -12,21 +12,26 @@ /** * @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 + +using namespace std; namespace gtsam { /* ************************************************************************* */ void ISAM2::Impl::AddVariables( - const Values& newTheta, Values& theta, Permuted& delta, - Permuted& deltaNewton, Permuted& deltaGradSearch, vector& replacedKeys, - Ordering& ordering, Base::Nodes& nodes, const KeyFormatter& keyFormatter) { + const Values& newTheta, Values& theta, VectorValues& delta, + VectorValues& deltaNewton, VectorValues& deltaGradSearch, vector& replacedKeys, + Ordering& ordering, const KeyFormatter& keyFormatter) { const bool debug = ISDEBUG("ISAM2 AddVariables"); theta.insert(newTheta); @@ -35,34 +40,91 @@ void ISAM2::Impl::AddVariables( std::vector dims(newTheta.dims(*newTheta.orderingArbitrary())); if(debug) cout << "New variables have total dimensionality " << accumulate(dims.begin(), dims.end(), 0) << endl; const size_t newDim = accumulate(dims.begin(), dims.end(), 0); - const size_t originalDim = delta->dim(); - const size_t originalnVars = delta->size(); - delta.container().append(dims); - delta.container().vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); - delta.permutation().resize(originalnVars + newTheta.size()); - deltaNewton.container().append(dims); - deltaNewton.container().vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); - deltaNewton.permutation().resize(originalnVars + newTheta.size()); - deltaGradSearch.container().append(dims); - deltaGradSearch.container().vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); - deltaGradSearch.permutation().resize(originalnVars + newTheta.size()); + const size_t originalDim = delta.dim(); + const size_t originalnVars = delta.size(); + delta.append(dims); + delta.vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); + deltaNewton.append(dims); + deltaNewton.vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); + deltaGradSearch.append(dims); + deltaGradSearch.vector().segment(originalDim, newDim).operator=(Vector::Zero(newDim)); { Index nextVar = originalnVars; BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, newTheta) { - delta.permutation()[nextVar] = nextVar; - deltaNewton.permutation()[nextVar] = nextVar; - deltaGradSearch.permutation()[nextVar] = nextVar; ordering.insert(key_value.key, nextVar); if(debug) cout << "Adding variable " << keyFormatter(key_value.key) << " with order " << nextVar << endl; ++ nextVar; } - assert(delta.permutation().size() == delta.container().size()); assert(ordering.nVars() == delta.size()); assert(ordering.size() == delta.size()); } - assert(ordering.nVars() >= nodes.size()); replacedKeys.resize(ordering.nVars(), false); - nodes.resize(ordering.nVars()); +} + +/* ************************************************************************* */ +void ISAM2::Impl::RemoveVariables(const FastSet& unusedKeys, const ISAM2Clique::shared_ptr& root, + Values& theta, VariableIndex& variableIndex, + VectorValues& delta, VectorValues& deltaNewton, VectorValues& deltaGradSearch, + std::vector& replacedKeys, Ordering& ordering, Base::Nodes& nodes, + GaussianFactorGraph& linearFactors) { + + // Get indices of unused keys + vector unusedIndices; unusedIndices.reserve(unusedKeys.size()); + BOOST_FOREACH(Key key, unusedKeys) { unusedIndices.push_back(ordering[key]); } + + // Create a permutation that shifts the unused variables to the end + Permutation unusedToEnd = Permutation::PushToBack(unusedIndices, delta.size()); + Permutation unusedToEndInverse = *unusedToEnd.inverse(); + + // Use the permutation to remove unused variables while shifting all the others to take up the space + variableIndex.permuteInPlace(unusedToEnd); + variableIndex.removeUnusedAtEnd(unusedIndices.size()); + { + // Create a vector of variable dimensions with the unused ones removed + // by applying the unusedToEnd permutation to the original vector of + // variable dimensions. We only allocate space in the shifted dims + // vector for the used variables, so that the unused ones are dropped + // when the permutation is applied. + vector originalDims = delta.dims(); + vector dims(delta.size() - unusedIndices.size()); + unusedToEnd.applyToCollection(dims, originalDims); + + // Copy from the old data structures to new ones, only iterating up to + // the number of used variables, and applying the unusedToEnd permutation + // in order to remove the unused variables. + VectorValues newDelta(dims); + VectorValues newDeltaNewton(dims); + VectorValues newDeltaGradSearch(dims); + std::vector newReplacedKeys(replacedKeys.size() - unusedIndices.size()); + Base::Nodes newNodes(replacedKeys.size() - unusedIndices.size()); + + for(size_t j = 0; j < dims.size(); ++j) { + newDelta[j] = delta[unusedToEnd[j]]; + newDeltaNewton[j] = deltaNewton[unusedToEnd[j]]; + newDeltaGradSearch[j] = deltaGradSearch[unusedToEnd[j]]; + newReplacedKeys[j] = replacedKeys[unusedToEnd[j]]; + newNodes[j] = nodes[unusedToEnd[j]]; + } + + // Swap the new data structures with the outputs of this function + delta.swap(newDelta); + deltaNewton.swap(newDeltaNewton); + deltaGradSearch.swap(newDeltaGradSearch); + replacedKeys.swap(newReplacedKeys); + nodes.swap(newNodes); + } + + // Reorder and remove from ordering and solution + ordering.permuteWithInverse(unusedToEndInverse); + BOOST_REVERSE_FOREACH(Key key, unusedKeys) { + ordering.pop_back(key); + theta.erase(key); + } + + // Finally, permute references to variables + if(root) + root->permuteWithInverse(unusedToEndInverse); + linearFactors.permuteWithInverse(unusedToEndInverse); } /* ************************************************************************* */ @@ -77,7 +139,7 @@ FastSet ISAM2::Impl::IndicesFromFactors(const Ordering& ordering, const N } /* ************************************************************************* */ -FastSet ISAM2::Impl::CheckRelinearization(const Permuted& delta, const Ordering& ordering, +FastSet ISAM2::Impl::CheckRelinearizationFull(const VectorValues& delta, const Ordering& ordering, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter) { FastSet relinKeys; @@ -104,6 +166,77 @@ FastSet ISAM2::Impl::CheckRelinearization(const Permuted& d return relinKeys; } +/* ************************************************************************* */ +void CheckRelinearizationRecursiveDouble(FastSet& relinKeys, double threshold, const VectorValues& delta, const ISAM2Clique::shared_ptr& clique) { + + // Check the current clique for relinearization + bool relinearize = false; + BOOST_FOREACH(Index var, clique->conditional()->keys()) { + double maxDelta = delta[var].lpNorm(); + if(maxDelta >= threshold) { + relinKeys.insert(var); + relinearize = true; + } + } + + // If this node was relinearized, also check its children + if(relinearize) { + BOOST_FOREACH(const ISAM2Clique::shared_ptr& child, clique->children()) { + CheckRelinearizationRecursiveDouble(relinKeys, threshold, delta, child); + } + } +} + +/* ************************************************************************* */ +void CheckRelinearizationRecursiveMap(FastSet& relinKeys, const FastMap& thresholds, const VectorValues& delta, const Ordering::InvertedMap& decoder, const ISAM2Clique::shared_ptr& clique) { + + // Check the current clique for relinearization + bool relinearize = false; + BOOST_FOREACH(Index var, clique->conditional()->keys()) { + + // Lookup the key associated with this index + Key key = decoder.at(var); + + // Find the threshold for this variable type + const Vector& threshold = thresholds.find(Symbol(key).chr())->second; + + // Verify the threshold vector matches the actual variable size + if(threshold.rows() != delta[var].rows()) + throw std::invalid_argument("Relinearization threshold vector dimensionality passed into iSAM2 parameters does not match actual variable dimensionality"); + + // Check for relinearization + if((delta[var].array().abs() > threshold.array()).any()) { + relinKeys.insert(var); + relinearize = true; + } + } + + // If this node was relinearized, also check its children + if(relinearize) { + BOOST_FOREACH(const ISAM2Clique::shared_ptr& child, clique->children()) { + CheckRelinearizationRecursiveMap(relinKeys, thresholds, delta, decoder, child); + } + } +} + +/* ************************************************************************* */ +FastSet ISAM2::Impl::CheckRelinearizationPartial(const ISAM2Clique::shared_ptr& root, const VectorValues& delta, const Ordering& ordering, + const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter) { + + FastSet relinKeys; + + if(root) { + if(relinearizeThreshold.type() == typeid(double)) { + CheckRelinearizationRecursiveDouble(relinKeys, boost::get(relinearizeThreshold), delta, root); + } else if(relinearizeThreshold.type() == typeid(FastMap)) { + Ordering::InvertedMap decoder = ordering.invert(); + CheckRelinearizationRecursiveMap(relinKeys, boost::get >(relinearizeThreshold), delta, decoder, root); + } + } + + return relinKeys; +} + /* ************************************************************************* */ void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, const vector& markedMask) { static const bool debug = false; @@ -125,13 +258,13 @@ void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, } /* ************************************************************************* */ -void ISAM2::Impl::ExpmapMasked(Values& values, const Permuted& delta, const Ordering& ordering, - const vector& mask, boost::optional&> invalidateIfDebug, const KeyFormatter& keyFormatter) { +void ISAM2::Impl::ExpmapMasked(Values& values, const VectorValues& delta, const Ordering& ordering, + const vector& mask, boost::optional invalidateIfDebug, const KeyFormatter& keyFormatter) { // If debugging, invalidate if requested, otherwise do not invalidate. // Invalidating means setting expmapped entries to Inf, to trigger assertions // if we try to re-use them. #ifdef NDEBUG - invalidateIfDebug = boost::optional&>(); + invalidateIfDebug = boost::none; #endif assert(values.size() == ordering.nVars()); @@ -149,7 +282,7 @@ void ISAM2::Impl::ExpmapMasked(Values& values, const Permuted& del cout << " " << keyFormatter(key_value->key) << " (j = " << var << "), delta = " << delta[var].transpose() << endl; } assert(delta[var].size() == (int)key_value->value.dim()); - assert(delta[var].unaryExpr(&isfinite).all()); + assert(delta[var].unaryExpr(ptr_fun(isfinite)).all()); if(mask[var]) { Value* retracted = key_value->value.retract_(delta[var]); key_value->value = *retracted; @@ -228,7 +361,7 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors, toc(4,"ccolamd permutations"); tic(5,"permute affected variable index"); - affectedFactorsIndex.permute(*affectedColamd); + affectedFactorsIndex.permuteInPlace(*affectedColamd); toc(5,"permute affected variable index"); tic(6,"permute affected factors"); @@ -278,25 +411,13 @@ inline static void optimizeInPlace(const boost::shared_ptr& clique, } /* ************************************************************************* */ -size_t ISAM2::Impl::UpdateDelta(const boost::shared_ptr& root, std::vector& replacedKeys, Permuted& delta, double wildfireThreshold) { +size_t ISAM2::Impl::UpdateDelta(const boost::shared_ptr& root, std::vector& replacedKeys, VectorValues& delta, double wildfireThreshold) { size_t lastBacksubVariableCount; if (wildfireThreshold <= 0.0) { // Threshold is zero or less, so do a full recalculation - // Collect dimensions and allocate new VectorValues - vector dims(delta.size()); - for(size_t j=0; jdim(j); - VectorValues newDelta(dims); - - // Optimize full solution delta - internal::optimizeInPlace(root, newDelta); - - // Copy solution into delta - delta.permutation() = Permutation::Identity(delta.size()); - delta.container() = newDelta; - + internal::optimizeInPlace(root, delta); lastBacksubVariableCount = delta.size(); } else { @@ -304,8 +425,8 @@ size_t ISAM2::Impl::UpdateDelta(const boost::shared_ptr& root, std: lastBacksubVariableCount = optimizeWildfire(root, wildfireThreshold, replacedKeys, delta); // modifies delta_ #ifndef NDEBUG - for(size_t j=0; j).all()); + for(size_t j=0; j)).all()); #endif } @@ -318,7 +439,7 @@ size_t ISAM2::Impl::UpdateDelta(const boost::shared_ptr& root, std: /* ************************************************************************* */ namespace internal { void updateDoglegDeltas(const boost::shared_ptr& clique, std::vector& replacedKeys, - const VectorValues& grad, Permuted& deltaNewton, Permuted& RgProd, size_t& varsUpdated) { + const VectorValues& grad, VectorValues& deltaNewton, VectorValues& RgProd, size_t& varsUpdated) { // Check if any frontal or separator keys were recalculated, if so, we need // update deltas and recurse to children, but if not, we do not need to @@ -357,7 +478,7 @@ void updateDoglegDeltas(const boost::shared_ptr& clique, std::vecto /* ************************************************************************* */ size_t ISAM2::Impl::UpdateDoglegDeltas(const ISAM2& isam, double wildfireThreshold, std::vector& replacedKeys, - Permuted& deltaNewton, Permuted& RgProd) { + VectorValues& deltaNewton, VectorValues& RgProd) { // Get gradient VectorValues grad = *allocateVectorValues(isam); diff --git a/gtsam/nonlinear/ISAM2-impl.h b/gtsam/nonlinear/ISAM2-impl.h index 34573f0c5..b873c87bf 100644 --- a/gtsam/nonlinear/ISAM2-impl.h +++ b/gtsam/nonlinear/ISAM2-impl.h @@ -22,8 +22,6 @@ namespace gtsam { -using namespace std; - struct ISAM2::Impl { struct PartialSolveResult { @@ -48,9 +46,17 @@ struct ISAM2::Impl { * @param nodes Current BayesTree::Nodes index to be augmented with slots for new variables * @param keyFormatter Formatter for printing nonlinear keys during debugging */ - static void AddVariables(const Values& newTheta, Values& theta, Permuted& delta, - Permuted& deltaNewton, Permuted& deltaGradSearch, vector& replacedKeys, - Ordering& ordering, Base::Nodes& nodes, const KeyFormatter& keyFormatter = DefaultKeyFormatter); + static void AddVariables(const Values& newTheta, Values& theta, VectorValues& delta, + VectorValues& deltaNewton, VectorValues& deltaGradSearch, std::vector& replacedKeys, + Ordering& ordering, const KeyFormatter& keyFormatter = DefaultKeyFormatter); + + /** + * Remove variables from the ISAM2 system. + */ + static void RemoveVariables(const FastSet& unusedKeys, const ISAM2Clique::shared_ptr& root, + Values& theta, VariableIndex& variableIndex, VectorValues& delta, VectorValues& deltaNewton, + VectorValues& deltaGradSearch, std::vector& replacedKeys, Ordering& ordering, Base::Nodes& nodes, + GaussianFactorGraph& linearFactors); /** * Extract the set of variable indices from a NonlinearFactorGraph. For each Symbol @@ -70,7 +76,21 @@ struct ISAM2::Impl { * @return The set of variable indices in delta whose magnitude is greater than or * equal to relinearizeThreshold */ - static FastSet CheckRelinearization(const Permuted& delta, const Ordering& ordering, + static FastSet CheckRelinearizationFull(const VectorValues& delta, const Ordering& ordering, + const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter = DefaultKeyFormatter); + + /** + * Find the set of variables to be relinearized according to relinearizeThreshold. + * This check is performed recursively, starting at the top of the tree. Once a + * variable in the tree does not need to be relinearized, no further checks in + * that branch are performed. This is an approximation of the Full version, designed + * to save time at the expense of accuracy. + * @param delta The linear delta to check against the threshold + * @param keyFormatter Formatter for printing nonlinear keys during debugging + * @return The set of variable indices in delta whose magnitude is greater than or + * equal to relinearizeThreshold + */ + static FastSet CheckRelinearizationPartial(const ISAM2Clique::shared_ptr& root, const VectorValues& delta, const Ordering& ordering, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter = DefaultKeyFormatter); /** @@ -88,12 +108,12 @@ struct ISAM2::Impl { * * Alternatively could we trace up towards the root for each variable here? */ - static void FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, const vector& markedMask); + static void FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, const std::vector& markedMask); /** * Apply expmap to the given values, but only for indices appearing in * \c markedRelinMask. Values are expmapped in-place. - * \param [in][out] values The value to expmap in-place + * \param [in, out] values The value to expmap in-place * \param delta The linear delta with which to expmap * \param ordering The ordering * \param mask Mask on linear indices, only \c true entries are expmapped @@ -103,9 +123,9 @@ struct ISAM2::Impl { * recalculate its delta. * @param keyFormatter Formatter for printing nonlinear keys during debugging */ - static void ExpmapMasked(Values& values, const Permuted& delta, + static void ExpmapMasked(Values& values, const VectorValues& delta, const Ordering& ordering, const std::vector& mask, - boost::optional&> invalidateIfDebug = boost::optional&>(), + boost::optional invalidateIfDebug = boost::none, const KeyFormatter& keyFormatter = DefaultKeyFormatter); /** @@ -125,10 +145,10 @@ struct ISAM2::Impl { static PartialSolveResult PartialSolve(GaussianFactorGraph& factors, const FastSet& keys, const ReorderingMode& reorderingMode, bool useQR); - static size_t UpdateDelta(const boost::shared_ptr& root, std::vector& replacedKeys, Permuted& delta, double wildfireThreshold); + static size_t UpdateDelta(const boost::shared_ptr& root, std::vector& replacedKeys, VectorValues& delta, double wildfireThreshold); static size_t UpdateDoglegDeltas(const ISAM2& isam, double wildfireThreshold, std::vector& replacedKeys, - Permuted& deltaNewton, Permuted& RgProd); + VectorValues& deltaNewton, VectorValues& RgProd); }; diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h index 04395069c..ba0071b51 100644 --- a/gtsam/nonlinear/ISAM2-inl.h +++ b/gtsam/nonlinear/ISAM2-inl.h @@ -23,12 +23,8 @@ #include #include -#include - namespace gtsam { -using namespace std; - /* ************************************************************************* */ template VALUE ISAM2::calculateEstimate(Key key) const { @@ -41,7 +37,7 @@ VALUE ISAM2::calculateEstimate(Key key) const { namespace internal { template void optimizeWildfire(const boost::shared_ptr& clique, double threshold, - vector& changed, const vector& replaced, Permuted& delta, int& count) { + std::vector& changed, const std::vector& replaced, VectorValues& delta, int& count) { // if none of the variables in this clique (frontal and separator!) changed // significantly, then by the running intersection property, none of the // cliques in the children need to be processed @@ -70,7 +66,7 @@ void optimizeWildfire(const boost::shared_ptr& clique, double threshold, if(recalculate) { // Temporary copy of the original values, to check how much they change - vector originalValues((*clique)->nrFrontals()); + std::vector originalValues((*clique)->nrFrontals()); GaussianConditional::const_iterator it; for(it = (*clique)->beginFrontals(); it!=(*clique)->endFrontals(); it++) { originalValues[it - (*clique)->beginFrontals()] = delta[*it]; @@ -118,8 +114,8 @@ void optimizeWildfire(const boost::shared_ptr& clique, double threshold, /* ************************************************************************* */ template -int optimizeWildfire(const boost::shared_ptr& root, double threshold, const vector& keys, Permuted& delta) { - vector changed(keys.size(), false); +int optimizeWildfire(const boost::shared_ptr& root, double threshold, const std::vector& keys, VectorValues& delta) { + std::vector changed(keys.size(), false); int count = 0; // starting from the root, call optimize on each conditional if(root) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index bae2252d6..081910e8c 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -20,12 +20,14 @@ using namespace boost::assign; #include #include +#include #include #include #include #include #include +#include #include #include @@ -38,9 +40,50 @@ using namespace std; static const bool disableReordering = false; static const double batchThreshold = 0.65; +/* ************************************************************************* */ +std::string ISAM2DoglegParams::adaptationModeTranslator(const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) const { + std::string s; + switch (adaptationMode) { + case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: s = "SEARCH_EACH_ITERATION"; break; + case DoglegOptimizerImpl::ONE_STEP_PER_ITERATION: s = "ONE_STEP_PER_ITERATION"; break; + default: s = "UNDEFINED"; break; + } + return s; +} + +/* ************************************************************************* */ +DoglegOptimizerImpl::TrustRegionAdaptationMode ISAM2DoglegParams::adaptationModeTranslator(const std::string& adaptationMode) const { + std::string s = adaptationMode; boost::algorithm::to_upper(s); + if (s == "SEARCH_EACH_ITERATION") return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; + if (s == "ONE_STEP_PER_ITERATION") return DoglegOptimizerImpl::ONE_STEP_PER_ITERATION; + + /* default is SEARCH_EACH_ITERATION */ + return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; +} + +/* ************************************************************************* */ +ISAM2Params::Factorization ISAM2Params::factorizationTranslator(const std::string& str) const { + std::string s = str; boost::algorithm::to_upper(s); + if (s == "QR") return ISAM2Params::QR; + if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; + + /* default is CHOLESKY */ + return ISAM2Params::CHOLESKY; +} + +/* ************************************************************************* */ +std::string ISAM2Params::factorizationTranslator(const ISAM2Params::Factorization& value) const { + std::string s; + switch (value) { + case ISAM2Params::QR: s = "QR"; break; + case ISAM2Params::CHOLESKY: s = "CHOLESKY"; break; + default: s = "UNDEFINED"; break; + } + return s; +} + /* ************************************************************************* */ ISAM2::ISAM2(const ISAM2Params& params): - delta_(deltaUnpermuted_), deltaNewton_(deltaNewtonUnpermuted_), RgProd_(RgProdUnpermuted_), deltaDoglegUptodate_(true), deltaUptodate_(true), params_(params) { if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) doglegDelta_ = boost::get(params_.optimizationParams).initialDelta; @@ -48,15 +91,13 @@ ISAM2::ISAM2(const ISAM2Params& params): /* ************************************************************************* */ ISAM2::ISAM2(): - delta_(deltaUnpermuted_), deltaNewton_(deltaNewtonUnpermuted_), RgProd_(RgProdUnpermuted_), deltaDoglegUptodate_(true), deltaUptodate_(true) { if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) doglegDelta_ = boost::get(params_.optimizationParams).initialDelta; } /* ************************************************************************* */ -ISAM2::ISAM2(const ISAM2& other): - delta_(deltaUnpermuted_), deltaNewton_(deltaNewtonUnpermuted_), RgProd_(RgProdUnpermuted_) { +ISAM2::ISAM2(const ISAM2& other) { *this = other; } @@ -88,9 +129,6 @@ ISAM2& ISAM2::operator=(const ISAM2& rhs) { params_ = rhs.params_; doglegDelta_ = rhs.doglegDelta_; -#ifndef NDEBUG - lastRelinVariables_ = rhs.lastRelinVariables_; -#endif lastAffectedVariableCount = rhs.lastAffectedVariableCount; lastAffectedFactorCount = rhs.lastAffectedFactorCount; lastAffectedCliqueCount = rhs.lastAffectedCliqueCount; @@ -205,8 +243,8 @@ GaussianFactorGraph ISAM2::getCachedBoundaryFactors(Cliques& orphans) { return cachedBoundary; } -boost::shared_ptr > ISAM2::recalculate( - const FastSet& markedKeys, const FastSet& relinKeys, const FastVector& observedKeys, +boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKeys, + const FastSet& relinKeys, const FastVector& observedKeys, const FastSet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result) { // TODO: new factors are linearized twice, the newFactors passed in are not used. @@ -307,12 +345,12 @@ boost::shared_ptr > ISAM2::recalculate( // Reorder tic(2,"permute global variable index"); - variableIndex_.permute(*colamd); + variableIndex_.permuteInPlace(*colamd); toc(2,"permute global variable index"); tic(3,"permute delta"); - delta_.permute(*colamd); - deltaNewton_.permute(*colamd); - RgProd_.permute(*colamd); + delta_ = delta_.permute(*colamd); + deltaNewton_ = deltaNewton_.permute(*colamd); + RgProd_ = RgProd_.permute(*colamd); toc(3,"permute delta"); tic(4,"permute ordering"); ordering_.permuteWithInverse(*colamdInverse); @@ -320,11 +358,13 @@ boost::shared_ptr > ISAM2::recalculate( toc(1,"reorder"); tic(2,"linearize"); - linearFactors_ = *nonlinearFactors_.linearize(theta_, ordering_); + GaussianFactorGraph linearized = *nonlinearFactors_.linearize(theta_, ordering_); + if(params_.cacheLinearizedFactors) + linearFactors_ = linearized; toc(2,"linearize"); tic(5,"eliminate"); - JunctionTree jt(linearFactors_, variableIndex_); + JunctionTree jt(linearized, variableIndex_); sharedClique newRoot; if(params_.factorization == ISAM2Params::CHOLESKY) newRoot = jt.eliminate(EliminatePreferCholesky); @@ -343,12 +383,12 @@ boost::shared_ptr > ISAM2::recalculate( lastAffectedMarkedCount = markedKeys.size(); lastAffectedVariableCount = affectedKeysSet->size(); - lastAffectedFactorCount = linearFactors_.size(); + lastAffectedFactorCount = linearized.size(); // Reeliminated keys for detailed results if(params_.enableDetailedResults) { BOOST_FOREACH(Key key, theta_.keys()) { - result.detail->variableStatus[key].isReeliminated = true; + result.detail->variableStatus[key].isReeliminated = true; } } @@ -372,7 +412,7 @@ boost::shared_ptr > ISAM2::recalculate( // Reeliminated keys for detailed results if(params_.enableDetailedResults) { BOOST_FOREACH(Index index, affectedAndNewKeys) { - result.detail->variableStatus[inverseOrdering_->at(index)].isReeliminated = true; + result.detail->variableStatus[inverseOrdering_->at(index)].isReeliminated = true; } } @@ -419,8 +459,12 @@ boost::shared_ptr > ISAM2::recalculate( reorderingMode.constrainedKeys = FastMap(); BOOST_FOREACH(Index var, observedKeys) { reorderingMode.constrainedKeys->insert(make_pair(var, 1)); } } + FastSet affectedUsedKeys = *affectedKeysSet; // Remove unused keys from the set we pass to PartialSolve + BOOST_FOREACH(Index unused, unusedIndices) { + affectedUsedKeys.erase(unused); + } Impl::PartialSolveResult partialSolveResult = - Impl::PartialSolve(factors, *affectedKeysSet, reorderingMode, (params_.factorization == ISAM2Params::QR)); + Impl::PartialSolve(factors, affectedUsedKeys, reorderingMode, (params_.factorization == ISAM2Params::QR)); toc(2,"PartialSolve"); // We now need to permute everything according this partial reordering: the @@ -428,12 +472,12 @@ boost::shared_ptr > ISAM2::recalculate( // re-eliminate. The reordered variables are also mentioned in the // orphans and the leftover cached factors. tic(3,"permute global variable index"); - variableIndex_.permute(partialSolveResult.fullReordering); + variableIndex_.permuteInPlace(partialSolveResult.fullReordering); toc(3,"permute global variable index"); tic(4,"permute delta"); - delta_.permute(partialSolveResult.fullReordering); - deltaNewton_.permute(partialSolveResult.fullReordering); - RgProd_.permute(partialSolveResult.fullReordering); + delta_ = delta_.permute(partialSolveResult.fullReordering); + deltaNewton_ = deltaNewton_.permute(partialSolveResult.fullReordering); + RgProd_ = RgProd_.permute(partialSolveResult.fullReordering); toc(4,"permute delta"); tic(5,"permute ordering"); ordering_.permuteWithInverse(partialSolveResult.fullReorderingInverse); @@ -485,7 +529,7 @@ boost::shared_ptr > ISAM2::recalculate( // Root clique variables for detailed results if(params_.enableDetailedResults) { BOOST_FOREACH(Index index, this->root()->conditional()->frontals()) { - result.detail->variableStatus[inverseOrdering_->at(index)].inRootClique = true; + result.detail->variableStatus[inverseOrdering_->at(index)].inRootClique = true; } } @@ -541,15 +585,38 @@ ISAM2Result ISAM2::update( BOOST_FOREACH(size_t index, removeFactorIndices) { removeFactors.push_back(nonlinearFactors_[index]); nonlinearFactors_.remove(index); + if(params_.cacheLinearizedFactors) + linearFactors_.remove(index); } // Remove removed factors from the variable index so we do not attempt to relinearize them variableIndex_.remove(removeFactorIndices, *removeFactors.symbolic(ordering_)); + + // Compute unused keys and indices + FastSet unusedKeys; + FastSet unusedIndices; + { + // Get keys from removed factors and new factors, and compute unused keys, + // i.e., keys that are empty now and do not appear in the new factors. + FastSet removedAndEmpty; + BOOST_FOREACH(Key key, removeFactors.keys()) { + if(variableIndex_[ordering_[key]].empty()) + removedAndEmpty.insert(removedAndEmpty.end(), key); + } + FastSet newFactorSymbKeys = newFactors.keys(); + std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(), + newFactorSymbKeys.begin(), newFactorSymbKeys.end(), std::inserter(unusedKeys, unusedKeys.end())); + + // Get indices for unused keys + BOOST_FOREACH(Key key, unusedKeys) { + unusedIndices.insert(unusedIndices.end(), ordering_[key]); + } + } toc(1,"push_back factors"); tic(2,"add new variables"); // 2. Initialize any new variables \Theta_{new} and add \Theta:=\Theta\cup\Theta_{new}. - Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_, deltaReplacedMask_, ordering_, Base::nodes_); + Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_, deltaReplacedMask_, ordering_); // New keys for detailed results if(params_.enableDetailedResults) { inverseOrdering_ = ordering_.invert(); @@ -569,16 +636,21 @@ ISAM2Result ISAM2::update( FastSet markedRemoveKeys = Impl::IndicesFromFactors(ordering_, removeFactors); // Get keys involved in removed factors markedKeys.insert(markedRemoveKeys.begin(), markedRemoveKeys.end()); // Add to the overall set of marked keys } - // Observed keys for detailed results + + // Observed keys for detailed results if(params_.enableDetailedResults) { BOOST_FOREACH(Index index, markedKeys) { - result.detail->variableStatus[inverseOrdering_->at(index)].isObserved = true; + result.detail->variableStatus[inverseOrdering_->at(index)].isObserved = true; } } // NOTE: we use assign instead of the iterator constructor here because this // is a vector of size_t, so the constructor unintentionally resolves to // vector(size_t count, Index value) instead of the iterator constructor. - FastVector observedKeys; observedKeys.assign(markedKeys.begin(), markedKeys.end()); // Make a copy of these, as we'll soon add to them + FastVector observedKeys; observedKeys.reserve(markedKeys.size()); + BOOST_FOREACH(Index index, markedKeys) { + if(unusedIndices.find(index) == unusedIndices.end()) // Only add if not unused + observedKeys.push_back(index); // Make a copy of these, as we'll soon add to them + } toc(4,"gather involved keys"); // Check relinearization if we're at the nth step, or we are using a looser loop relin threshold @@ -587,8 +659,11 @@ ISAM2Result ISAM2::update( tic(5,"gather relinearize keys"); vector markedRelinMask(ordering_.nVars(), false); // 4. Mark keys in \Delta above threshold \beta: J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}. - relinKeys = Impl::CheckRelinearization(delta_, ordering_, params_.relinearizeThreshold); - if(disableReordering) relinKeys = Impl::CheckRelinearization(delta_, ordering_, 0.0); // This is used for debugging + if(params_.enablePartialRelinearizationCheck) + relinKeys = Impl::CheckRelinearizationPartial(root_, delta_, ordering_, params_.relinearizeThreshold); + else + relinKeys = Impl::CheckRelinearizationFull(delta_, ordering_, params_.relinearizeThreshold); + if(disableReordering) relinKeys = Impl::CheckRelinearizationFull(delta_, ordering_, 0.0); // This is used for debugging // Above relin threshold keys for detailed results if(params_.enableDetailedResults) { @@ -626,15 +701,8 @@ ISAM2Result ISAM2::update( toc(7,"expmap"); result.variablesRelinearized = markedKeys.size(); - -#ifndef NDEBUG - lastRelinVariables_ = markedRelinMask; -#endif } else { result.variablesRelinearized = 0; -#ifndef NDEBUG - lastRelinVariables_ = vector(ordering_.nVars(), false); -#endif } tic(8,"linearize new"); @@ -668,7 +736,7 @@ ISAM2Result ISAM2::update( } boost::shared_ptr > replacedKeys; if(!markedKeys.empty() || !observedKeys.empty()) - replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, constrainedIndices, result); + replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, unusedIndices, constrainedIndices, result); // Update replaced keys mask (accumulates until back-substitution takes place) if(replacedKeys) { @@ -676,19 +744,23 @@ ISAM2Result ISAM2::update( deltaReplacedMask_[var] = true; } } toc(9,"recalculate"); - //tic(9,"solve"); - // 9. Solve - if(debug) delta_.print("delta_: "); - //toc(9,"solve"); - + // After the top of the tree has been redone and may have index gaps from + // unused keys, condense the indices to remove gaps by rearranging indices + // in all data structures. + if(!unusedKeys.empty()) { + tic(10,"remove variables"); + Impl::RemoveVariables(unusedKeys, root_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, + deltaReplacedMask_, ordering_, Base::nodes_, linearFactors_); + toc(10,"remove variables"); + } result.cliques = this->nodes().size(); deltaDoglegUptodate_ = false; deltaUptodate_ = false; - tic(10,"evaluate error after"); + tic(11,"evaluate error after"); if(params_.evaluateNonlinearError) result.errorAfter.reset(nonlinearFactors_.error(calculateEstimate())); - toc(10,"evaluate error after"); + toc(11,"evaluate error after"); return result; } @@ -719,8 +791,7 @@ void ISAM2::updateDelta(bool forceFullSolve) const { tic(2, "Copy dx_d"); // Update Delta and linear step doglegDelta_ = doglegResult.Delta; - delta_.permutation() = Permutation::Identity(delta_.size()); // Dogleg solves for the full delta so there is no permutation - delta_.container() = doglegResult.dx_d; // Copy the VectorValues containing with the linear solution + delta_ = doglegResult.dx_d; // Copy the VectorValues containing with the linear solution toc(2, "Copy dx_d"); } @@ -732,10 +803,10 @@ Values ISAM2::calculateEstimate() const { // We use ExpmapMasked here instead of regular expmap because the former // handles Permuted tic(1, "Copy Values"); - Values ret(theta_); - toc(1, "Copy Values"); - tic(2, "getDelta"); - const Permuted& delta(getDelta()); + Values ret(theta_); + toc(1, "Copy Values"); + tic(2, "getDelta"); + const VectorValues& delta(getDelta()); toc(2, "getDelta"); tic(3, "Expmap"); vector mask(ordering_.nVars(), true); @@ -752,7 +823,7 @@ Values ISAM2::calculateBestEstimate() const { } /* ************************************************************************* */ -const Permuted& ISAM2::getDelta() const { +const VectorValues& ISAM2::getDelta() const { if(!deltaUptodate_) updateDelta(); return delta_; @@ -825,7 +896,7 @@ void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad) { tic(3, "Compute minimizing step size"); // Compute minimizing step size - double RgNormSq = isam.RgProd_.container().vector().squaredNorm(); + double RgNormSq = isam.RgProd_.vector().squaredNorm(); double step = -gradientSqNorm / RgNormSq; toc(3, "Compute minimizing step size"); diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 30f0b14d2..1cea78837 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -28,11 +28,7 @@ namespace gtsam { /** - * @defgroup ISAM2 - */ - -/** - * @ingroup ISAM2 + * @addtogroup ISAM2 * Parameters for ISAM2 using Gauss-Newton optimization. Either this class or * ISAM2DoglegParams should be specified as the optimizationParams in * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). @@ -44,10 +40,19 @@ struct ISAM2GaussNewtonParams { ISAM2GaussNewtonParams( double _wildfireThreshold = 0.001 ///< see ISAM2GaussNewtonParams public variables, ISAM2GaussNewtonParams::wildfireThreshold ) : wildfireThreshold(_wildfireThreshold) {} + + void print(const std::string str = "") const { + std::cout << str << "type: ISAM2GaussNewtonParams\n"; + std::cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + std::cout.flush(); + } + + double getWildfireThreshold() const { return wildfireThreshold; } + void setWildfireThreshold(double wildfireThreshold) { this->wildfireThreshold = wildfireThreshold; } }; /** - * @ingroup ISAM2 + * @addtogroup ISAM2 * Parameters for ISAM2 using Dogleg optimization. Either this class or * ISAM2GaussNewtonParams should be specified as the optimizationParams in * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). @@ -66,12 +71,35 @@ struct ISAM2DoglegParams { bool _verbose = false ///< see ISAM2DoglegParams::verbose ) : initialDelta(_initialDelta), wildfireThreshold(_wildfireThreshold), adaptationMode(_adaptationMode), verbose(_verbose) {} + + void print(const std::string str = "") const { + std::cout << str << "type: ISAM2DoglegParams\n"; + std::cout << str << "initialDelta: " << initialDelta << "\n"; + std::cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + std::cout << str << "adaptationMode: " << adaptationModeTranslator(adaptationMode) << "\n"; + std::cout.flush(); + } + + double getInitialDelta() const { return initialDelta; } + double getWildfireThreshold() const { return wildfireThreshold; } + std::string getAdaptationMode() const { return adaptationModeTranslator(adaptationMode); }; + bool isVerbose() const { return verbose; }; + + void setInitialDelta(double initialDelta) { this->initialDelta = initialDelta; } + void setWildfireThreshold(double wildfireThreshold) { this->wildfireThreshold = wildfireThreshold; } + void setAdaptationMode(const std::string& adaptationMode) { this->adaptationMode = adaptationModeTranslator(adaptationMode); } + void setVerbose(bool verbose) { this->verbose = verbose; }; + + std::string adaptationModeTranslator(const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) const; + DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator(const std::string& adaptationMode) const; }; /** - * @ingroup ISAM2 + * @addtogroup ISAM2 * Parameters for the ISAM2 algorithm. Default parameter values are listed below. */ +typedef FastMap ISAM2ThresholdMap; +typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue; struct ISAM2Params { typedef boost::variant OptimizationParams; ///< Either ISAM2GaussNewtonParams or ISAM2DoglegParams typedef boost::variant > RelinearizationThreshold; ///< Either a constant relinearization threshold or a per-variable-type set of thresholds @@ -94,8 +122,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 */ @@ -112,7 +140,7 @@ struct ISAM2Params { * Cholesky is faster but potentially numerically unstable for poorly-conditioned problems, which can occur when * uncertainty is very low in some variables (or dimensions of variables) and very high in others. QR is * slower but more numerically stable in poorly-conditioned problems. We suggest using the default of Cholesky - * unless gtsam sometimes throws NegativeMatrixException when your problem's Hessian is actually positive + * unless gtsam sometimes throws IndefiniteLinearSystemException when your problem's Hessian is actually positive * definite. For positive definite problems, numerical error accumulation can cause the problem to become * numerically negative or indefinite as solving proceeds, especially when using Cholesky. */ @@ -129,6 +157,13 @@ struct ISAM2Params { bool enableDetailedResults; ///< Whether to compute and return ISAM2Result::detailedResults, this can increase running time (default: false) + /** Check variables for relinearization in tree-order, stopping the check once a variable does not need to be relinearized (default: false). + * This can improve speed by only checking a small part of the top of the tree. However, variables below the check cut-off can accumulate + * significant deltas without triggering relinearization. This is particularly useful in exploration scenarios where real-time performance + * is desired over correctness. Use with caution. + */ + bool enablePartialRelinearizationCheck; + /** Specify parameters as constructor arguments */ ISAM2Params( OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), ///< see ISAM2Params::optimizationParams @@ -143,11 +178,65 @@ struct ISAM2Params { relinearizeSkip(_relinearizeSkip), enableRelinearization(_enableRelinearization), evaluateNonlinearError(_evaluateNonlinearError), factorization(_factorization), cacheLinearizedFactors(_cacheLinearizedFactors), keyFormatter(_keyFormatter), - enableDetailedResults(false) {} + enableDetailedResults(false), enablePartialRelinearizationCheck(false) {} + + void print(const std::string& str = "") const { + std::cout << str << "\n"; + if(optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) + boost::get(optimizationParams).print("optimizationParams: "); + else if(optimizationParams.type() == typeid(ISAM2DoglegParams)) + boost::get(optimizationParams).print("optimizationParams: "); + else + std::cout << "optimizationParams: " << "{unknown type}" << "\n"; + if(relinearizeThreshold.type() == typeid(double)) + std::cout << "relinearizeThreshold: " << boost::get(relinearizeThreshold) << "\n"; + else + { + std::cout << "relinearizeThreshold: " << "{mapped}" << "\n"; + BOOST_FOREACH(const ISAM2ThresholdMapValue& value, boost::get(relinearizeThreshold)) { + std::cout << " '" << value.first << "' -> [" << value.second.transpose() << " ]\n"; + } + } + std::cout << "relinearizeSkip: " << relinearizeSkip << "\n"; + std::cout << "enableRelinearization: " << enableRelinearization << "\n"; + std::cout << "evaluateNonlinearError: " << evaluateNonlinearError << "\n"; + std::cout << "factorization: " << factorizationTranslator(factorization) << "\n"; + std::cout << "cacheLinearizedFactors: " << cacheLinearizedFactors << "\n"; + std::cout << "enableDetailedResults: " << enableDetailedResults << "\n"; + std::cout << "enablePartialRelinearizationCheck: " << enablePartialRelinearizationCheck << "\n"; + std::cout.flush(); + } + + /** Getters and Setters for all properties */ + OptimizationParams getOptimizationParams() const { return this->optimizationParams; } + RelinearizationThreshold getRelinearizeThreshold() const { return relinearizeThreshold; } + int getRelinearizeSkip() const { return relinearizeSkip; } + bool isEnableRelinearization() const { return enableRelinearization; } + bool isEvaluateNonlinearError() const { return evaluateNonlinearError; } + std::string getFactorization() const { return factorizationTranslator(factorization); } + bool isCacheLinearizedFactors() const { return cacheLinearizedFactors; } + KeyFormatter getKeyFormatter() const { return keyFormatter; } + bool isEnableDetailedResults() const { return enableDetailedResults; } + bool isEnablePartialRelinearizationCheck() const { return enablePartialRelinearizationCheck; } + + void setOptimizationParams(OptimizationParams optimizationParams) { this->optimizationParams = optimizationParams; } + void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) { this->relinearizeThreshold = relinearizeThreshold; } + void setRelinearizeSkip(int relinearizeSkip) { this->relinearizeSkip = relinearizeSkip; } + void setEnableRelinearization(bool enableRelinearization) { this->enableRelinearization = enableRelinearization; } + void setEvaluateNonlinearError(bool evaluateNonlinearError) { this->evaluateNonlinearError = evaluateNonlinearError; } + void setFactorization(const std::string& factorization) { this->factorization = factorizationTranslator(factorization); } + void setCacheLinearizedFactors(bool cacheLinearizedFactors) { this->cacheLinearizedFactors = cacheLinearizedFactors; } + void setKeyFormatter(KeyFormatter keyFormatter) { this->keyFormatter = keyFormatter; } + void setEnableDetailedResults(bool enableDetailedResults) { this->enableDetailedResults = enableDetailedResults; } + void setEnablePartialRelinearizationCheck(bool enablePartialRelinearizationCheck) { this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; } + + Factorization factorizationTranslator(const std::string& str) const; + std::string factorizationTranslator(const Factorization& value) const; }; + /** - * @ingroup ISAM2 + * @addtogroup ISAM2 * This struct is returned from ISAM2::update() and contains information about * the update that is useful for determining whether the solution is * converging, and about how much work was required for the update. See member @@ -203,7 +292,7 @@ struct ISAM2Result { * factors passed as \c newFactors to ISAM2::update(). These indices may be * used later to refer to the factors in order to remove them. */ - FastVector newFactorsIndices; + std::vector newFactorsIndices; /** A struct holding detailed results, which must be enabled with * ISAM2Params::enableDetailedResults. @@ -234,10 +323,24 @@ struct ISAM2Result { /** Detailed results, if enabled by ISAM2Params::enableDetailedResults. See * Detail for information about the results data stored here. */ boost::optional detail; + + + void print(const std::string str = "") const { + std::cout << str << " Reelimintated: " << variablesReeliminated << " Relinearized: " << variablesRelinearized << " Cliques: " << cliques << std::endl; + } + + /** Getters and Setters */ + size_t getVariablesRelinearized() const { return variablesRelinearized; }; + size_t getVariablesReeliminated() const { return variablesReeliminated; }; + size_t getCliques() const { return cliques; }; }; -struct ISAM2Clique : public BayesTreeCliqueBase { - +/** + * Specialized Clique structure for ISAM2, incorporating caching and gradient contribution + * TODO: more documentation + */ +class ISAM2Clique : public BayesTreeCliqueBase { +public: typedef ISAM2Clique This; typedef BayesTreeCliqueBase Base; typedef boost::shared_ptr shared_ptr; @@ -250,11 +353,12 @@ struct ISAM2Clique : public BayesTreeCliqueBase >& result) : - Base(result.first), cachedFactor_(result.second), gradientContribution_(result.first->get_R().cols() + result.first->get_S().cols()) { + Base(result.first), cachedFactor_(result.second), + gradientContribution_(result.first->get_R().cols() + result.first->get_S().cols()) { // Compute gradient contribution const ConditionalType& conditional(*result.first); // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed reasons @@ -264,7 +368,7 @@ struct ISAM2Clique : public BayesTreeCliqueBaseclone() : Base::FactorType::shared_ptr()))); copy->gradientContribution_ = gradientContribution_; @@ -272,22 +376,26 @@ struct ISAM2Clique : public BayesTreeCliqueBaseequals(*other.cachedFactor_, tol))); + return Base::equals(other) && + ((!cachedFactor_ && !other.cachedFactor_) + || (cachedFactor_ && other.cachedFactor_ + && cachedFactor_->equals(*other.cachedFactor_, tol))); } /** print this node */ - void print(const std::string& s = "") const { - Base::print(s); + void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const { + Base::print(s,formatter); if(cachedFactor_) - cachedFactor_->print(s + "Cached: "); + cachedFactor_->print(s + "Cached: ", formatter); else - cout << s << "Cached empty" << endl; + std::cout << s << "Cached empty" << std::endl; if(gradientContribution_.rows() != 0) gtsam::print(gradientContribution_, "Gradient contribution: "); } @@ -304,6 +412,7 @@ struct ISAM2Clique : public BayesTreeCliqueBase @@ -312,10 +421,10 @@ private: ar & BOOST_SERIALIZATION_NVP(cachedFactor_); ar & BOOST_SERIALIZATION_NVP(gradientContribution_); } -}; +}; // \struct ISAM2Clique /** - * @ingroup ISAM2 + * @addtogroup ISAM2 * Implementation of the full ISAM2 algorithm for incremental nonlinear optimization. * * The typical cycle of using this class to create an instance by providing ISAM2Params @@ -334,26 +443,16 @@ protected: /** VariableIndex lets us look up factors by involved variable and keeps track of dimensions */ VariableIndex variableIndex_; - /** The linear delta from the last linear solution, an update to the estimate in theta */ - VectorValues deltaUnpermuted_; + /** The linear delta from the last linear solution, an update to the estimate in theta + * + * This is \c mutable because it is a "cached" variable - it is not updated + * until either requested with getDelta() or calculateEstimate(), or needed + * during update() to evaluate whether to relinearize variables. + */ + mutable VectorValues delta_; - /** The permutation through which the deltaUnpermuted_ is - * referenced. - * - * Permuting Vector entries would be slow, so for performance we - * instead maintain this permutation through which we access the linear delta - * indirectly - * - * This is \c mutable because it is a "cached" variable - it is not updated - * until either requested with getDelta() or calculateEstimate(), or needed - * during update() to evaluate whether to relinearize variables. - */ - mutable Permuted delta_; - - VectorValues deltaNewtonUnpermuted_; - mutable Permuted deltaNewton_; - VectorValues RgProdUnpermuted_; - mutable Permuted RgProd_; + mutable VectorValues deltaNewton_; + mutable VectorValues RgProd_; mutable bool deltaDoglegUptodate_; /** Indicates whether the current delta is up-to-date, only used @@ -400,11 +499,6 @@ protected: /** The inverse ordering, only used for creating ISAM2Result::DetailedResults */ boost::optional inverseOrdering_; -private: -#ifndef NDEBUG - std::vector lastRelinVariables_; -#endif - public: typedef ISAM2 This; ///< This class @@ -446,6 +540,8 @@ public: * @param force_relinearize Relinearize any variables whose delta magnitude is sufficiently * large (Params::relinearizeThreshold), regardless of the relinearization interval * (Params::relinearizeSkip). + * @param constrainedKeys is an optional map of keys to group labels, such that a variable can + * be constrained to a particular grouping in the BayesTree * @return An ISAM2Result struct containing information about the update */ ISAM2Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), @@ -454,7 +550,7 @@ public: bool force_relinearize = false); /** Access the current linearization point */ - const Values& getLinearizationPoint() const {return theta_;} + const Values& getLinearizationPoint() const { return theta_; } /** Compute an estimate from the incomplete linear delta computed during the last update. * This delta is incomplete because it was not updated below wildfire_threshold. If only @@ -482,7 +578,7 @@ public: Values calculateBestEstimate() const; /** Access the current delta, computed during the last call to update */ - const Permuted& getDelta() const; + const VectorValues& getDelta() const; /** Access the set of nonlinear factors */ const NonlinearFactorGraph& getFactorsUnsafe() const { return nonlinearFactors_; } @@ -490,6 +586,9 @@ public: /** Access the current ordering */ const Ordering& getOrdering() const { return ordering_; } + /** Access the nonlinear variable index */ + const VariableIndex& getVariableIndex() const { return variableIndex_; } + size_t lastAffectedVariableCount; size_t lastAffectedFactorCount; size_t lastAffectedCliqueCount; @@ -497,7 +596,10 @@ public: mutable size_t lastBacksubVariableCount; size_t lastNnzTop; - ISAM2Params params() const { return params_; } + const ISAM2Params& params() const { return params_; } + + /** prints out clique statistics */ + void printStats() const { getCliqueData().getStats().print(); } //@} @@ -508,8 +610,7 @@ private: GaussianFactorGraph getCachedBoundaryFactors(Cliques& orphans); boost::shared_ptr > recalculate(const FastSet& markedKeys, const FastSet& relinKeys, - const FastVector& observedKeys, - const boost::optional >& constrainKeys, ISAM2Result& result); + const FastVector& observedKeys, const FastSet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result); // void linear_update(const GaussianFactorGraph& newFactors); void updateDelta(bool forceFullSolve = false) const; @@ -537,7 +638,7 @@ void optimizeInPlace(const ISAM2& isam, VectorValues& delta); /// @return The number of variables that were solved for template int optimizeWildfire(const boost::shared_ptr& root, - double threshold, const std::vector& replaced, Permuted& delta); + double threshold, const std::vector& replaced, VectorValues& delta); /** * Optimize along the gradient direction, with a closed-form computation to diff --git a/gtsam/nonlinear/Key.h b/gtsam/nonlinear/Key.h index 65a65c6d4..ab63fda6d 100644 --- a/gtsam/nonlinear/Key.h +++ b/gtsam/nonlinear/Key.h @@ -20,6 +20,10 @@ #include #include +#include +#include +#include + namespace gtsam { /// Integer nonlinear key type @@ -36,5 +40,10 @@ namespace gtsam { /// and Symbol keys. static const KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter; + /// Useful typedefs for operations with Values - allow for matlab interfaces + typedef FastList KeyList; + typedef FastVector KeyVector; + typedef FastSet KeySet; + } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 1b19cfe75..a77cac35a 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -13,28 +13,67 @@ * @file LevenbergMarquardtOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ -#include +#include -#include // For NegativeMatrixException -#include -#include +#include +#include +#include + +#include +#include using namespace std; namespace gtsam { +/* ************************************************************************* */ +LevenbergMarquardtParams::VerbosityLM LevenbergMarquardtParams::verbosityLMTranslator(const std::string &src) const { + std::string s = src; boost::algorithm::to_upper(s); + if (s == "SILENT") return LevenbergMarquardtParams::SILENT; + if (s == "LAMBDA") return LevenbergMarquardtParams::LAMBDA; + if (s == "TRYLAMBDA") return LevenbergMarquardtParams::TRYLAMBDA; + if (s == "TRYCONFIG") return LevenbergMarquardtParams::TRYCONFIG; + if (s == "TRYDELTA") return LevenbergMarquardtParams::TRYDELTA; + if (s == "DAMPED") return LevenbergMarquardtParams::DAMPED; + + /* default is silent */ + return LevenbergMarquardtParams::SILENT; +} + +/* ************************************************************************* */ +std::string LevenbergMarquardtParams::verbosityLMTranslator(VerbosityLM value) const { + std::string s; + switch (value) { + case LevenbergMarquardtParams::SILENT: s = "SILENT" ; break; + case LevenbergMarquardtParams::LAMBDA: s = "LAMBDA" ; break; + case LevenbergMarquardtParams::TRYLAMBDA: s = "TRYLAMBDA" ; break; + case LevenbergMarquardtParams::TRYCONFIG: s = "TRYCONFIG" ; break; + case LevenbergMarquardtParams::TRYDELTA: s = "TRYDELTA" ; break; + case LevenbergMarquardtParams::DAMPED: s = "DAMPED" ; break; + default: s = "UNDEFINED" ; break; + } + return s; +} + +/* ************************************************************************* */ +void LevenbergMarquardtParams::print(const std::string& str) const { + SuccessiveLinearizationParams::print(str); + std::cout << " lambdaInitial: " << lambdaInitial << "\n"; + std::cout << " lambdaFactor: " << lambdaFactor << "\n"; + std::cout << " lambdaUpperBound: " << lambdaUpperBound << "\n"; + std::cout << " verbosityLM: " << verbosityLMTranslator(verbosityLM) << "\n"; + std::cout.flush(); +} + /* ************************************************************************* */ void LevenbergMarquardtOptimizer::iterate() { // Linearize graph GaussianFactorGraph::shared_ptr linear = graph_.linearize(state_.values, *params_.ordering); - // Get elimination method - GaussianFactorGraph::Eliminate eliminationMethod = params_.getEliminationFunction(); - // Pull out parameters we'll use const NonlinearOptimizerParams::Verbosity nloVerbosity = params_.verbosity; const LevenbergMarquardtParams::VerbosityLM lmVerbosity = params_.verbosityLM; @@ -48,7 +87,7 @@ void LevenbergMarquardtOptimizer::iterate() { // TODO: replace this dampening with a backsubstitution approach GaussianFactorGraph dampedSystem(*linear); { - double sigma = 1.0 / sqrt(state_.lambda); + double sigma = 1.0 / std::sqrt(state_.lambda); dampedSystem.reserve(dampedSystem.size() + dimensions_.size()); // for each of the variables, add a prior for(Index j=0; j::Create(dampedSystem)->eliminate(eliminationMethod)); - else - throw runtime_error("Optimization parameter is invalid: LevenbergMarquardtParams::elimination"); + // Solve Damped Gaussian Factor Graph + const VectorValues delta = solveGaussianFactorGraph(dampedSystem, params_); if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "linear delta norm = " << delta.vector().norm() << endl; if (lmVerbosity >= LevenbergMarquardtParams::TRYDELTA) delta.print("delta"); @@ -102,7 +134,7 @@ void LevenbergMarquardtOptimizer::iterate() { state_.lambda *= params_.lambdaFactor; } } - } catch(const NegativeMatrixException& e) { + } catch(const IndeterminantLinearSystemException& e) { if(lmVerbosity >= LevenbergMarquardtParams::LAMBDA) cout << "Negative matrix, increasing lambda" << endl; // Either we're not cautious, or the same lambda was worse than the current error. diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index c1fe55c26..62d05839d 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -13,7 +13,7 @@ * @file LevenbergMarquardtOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once @@ -30,10 +30,11 @@ class LevenbergMarquardtOptimizer; * all of those parameters. */ class LevenbergMarquardtParams : public SuccessiveLinearizationParams { + public: /** See LevenbergMarquardtParams::lmVerbosity */ enum VerbosityLM { - SILENT, + SILENT = 0, LAMBDA, TRYLAMBDA, TRYCONFIG, @@ -46,26 +47,32 @@ public: double lambdaUpperBound; ///< The maximum lambda to try before assuming the optimization has failed (default: 1e5) VerbosityLM verbosityLM; ///< The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::verbosity - LevenbergMarquardtParams() : - lambdaInitial(1e-5), lambdaFactor(10.0), lambdaUpperBound(1e5), verbosityLM(SILENT) {} - + LevenbergMarquardtParams() : lambdaInitial(1e-5), lambdaFactor(10.0), lambdaUpperBound(1e5), verbosityLM(SILENT) {} virtual ~LevenbergMarquardtParams() {} - virtual void print(const std::string& str = "") const { - SuccessiveLinearizationParams::print(str); - std::cout << " lambdaInitial: " << lambdaInitial << "\n"; - std::cout << " lambdaFactor: " << lambdaFactor << "\n"; - std::cout << " lambdaUpperBound: " << lambdaUpperBound << "\n"; - std::cout.flush(); - } + virtual void print(const std::string& str = "") const; + + inline double getlambdaInitial() const { return lambdaInitial; } + inline double getlambdaFactor() const { return lambdaFactor; } + inline double getlambdaUpperBound() const { return lambdaUpperBound; } + inline std::string getVerbosityLM() const { return verbosityLMTranslator(verbosityLM); } + + inline void setlambdaInitial(double value) { lambdaInitial = value; } + inline void setlambdaFactor(double value) { lambdaFactor = value; } + inline void setlambdaUpperBound(double value) { lambdaUpperBound = value; } + inline void setVerbosityLM(const std::string &s) { verbosityLM = verbosityLMTranslator(s); } + +private: + VerbosityLM verbosityLMTranslator(const std::string &s) const; + std::string verbosityLMTranslator(VerbosityLM value) const; }; /** * State for LevenbergMarquardtOptimizer */ class LevenbergMarquardtState : public NonlinearOptimizerState { -public: +public: double lambda; LevenbergMarquardtState() {} @@ -73,10 +80,10 @@ public: virtual ~LevenbergMarquardtState() {} protected: - LevenbergMarquardtState(const NonlinearFactorGraph& graph, const Values& initialValues, const LevenbergMarquardtParams& params, unsigned int iterations = 0) : - NonlinearOptimizerState(graph, initialValues, iterations), lambda(params.lambdaInitial) {} + LevenbergMarquardtState(const NonlinearFactorGraph& graph, const Values& initialValues, const LevenbergMarquardtParams& params, unsigned int iterations = 0) : + NonlinearOptimizerState(graph, initialValues, iterations), lambda(params.lambdaInitial) {} - friend class LevenbergMarquardtOptimizer; + friend class LevenbergMarquardtOptimizer; }; /** @@ -84,8 +91,12 @@ protected: */ class LevenbergMarquardtOptimizer : public NonlinearOptimizer { -public: +protected: + LevenbergMarquardtParams params_; ///< LM parameters + LevenbergMarquardtState state_; ///< optimization state + std::vector dimensions_; ///< undocumented +public: typedef boost::shared_ptr shared_ptr; /// @name Standard interface @@ -110,16 +121,21 @@ public: * copies the objects. * @param graph The nonlinear factor graph to optimize * @param initialValues The initial variable assignments - * @param params The optimization parameters */ LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues, const Ordering& ordering) : NonlinearOptimizer(graph), dimensions_(initialValues.dims(ordering)) { params_.ordering = ordering; state_ = LevenbergMarquardtState(graph, initialValues, params_); } - /** Access the current damping value */ + /// Access the current damping value double lambda() const { return state_.lambda; } + /// print + virtual void print(const std::string& str = "") const { + std::cout << str << "LevenbergMarquardtOptimizer" << std::endl; + this->params_.print(" parameters:\n"); + } + /// @} /// @name Advanced interface @@ -143,23 +159,18 @@ public: /// @} protected: + /** Access the parameters (base class version) */ + virtual const NonlinearOptimizerParams& _params() const { return params_; } - LevenbergMarquardtParams params_; - LevenbergMarquardtState state_; - std::vector dimensions_; + /** Access the state (base class version) */ + virtual const NonlinearOptimizerState& _state() const { return state_; } - /** Access the parameters (base class version) */ - virtual const NonlinearOptimizerParams& _params() const { return params_; } - - /** Access the state (base class version) */ - virtual const NonlinearOptimizerState& _state() const { return state_; } - - /** Internal function for computing a COLAMD ordering if no ordering is specified */ - LevenbergMarquardtParams ensureHasOrdering(LevenbergMarquardtParams params, const NonlinearFactorGraph& graph, const Values& values) const { - if(!params.ordering) - params.ordering = *graph.orderingCOLAMD(values); - return params; - } + /** Internal function for computing a COLAMD ordering if no ordering is specified */ + LevenbergMarquardtParams ensureHasOrdering(LevenbergMarquardtParams params, const NonlinearFactorGraph& graph, const Values& values) const { + if(!params.ordering) + params.ordering = *graph.orderingCOLAMD(values); + return params; + } }; } diff --git a/gtsam/nonlinear/Marginals.cpp b/gtsam/nonlinear/Marginals.cpp index 34d620bc2..c3078ea76 100644 --- a/gtsam/nonlinear/Marginals.cpp +++ b/gtsam/nonlinear/Marginals.cpp @@ -21,6 +21,8 @@ #include #include +using namespace std; + namespace gtsam { /* ************************************************************************* */ @@ -43,6 +45,14 @@ Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution, bayesTree_ = *GaussianMultifrontalSolver(graph_, true).eliminate(); } +/* ************************************************************************* */ +void Marginals::print(const std::string& str, const KeyFormatter& keyFormatter) const { + ordering_.print(str+"Ordering: ", keyFormatter); + graph_.print(str+"Graph: "); + values_.print(str+"Solution: ", keyFormatter); + bayesTree_.print(str+"Bayes Tree: "); +} + /* ************************************************************************* */ Matrix Marginals::marginalCovariance(Key variable) const { return marginalInformation(variable).inverse(); @@ -61,16 +71,22 @@ Matrix Marginals::marginalInformation(Key variable) const { marginalFactor = bayesTree_.marginalFactor(index, EliminateQR); // Get information matrix (only store upper-right triangle) - if(typeid(*marginalFactor) == typeid(JacobianFactor)) { - JacobianFactor::constABlock A = static_cast(*marginalFactor).getA(); - return A.transpose() * A; // Compute A'A - } else if(typeid(*marginalFactor) == typeid(HessianFactor)) { - const HessianFactor& hessian = static_cast(*marginalFactor); - const size_t dim = hessian.getDim(hessian.begin()); - return hessian.info().topLeftCorner(dim,dim).selfadjointView(); // Take the non-augmented part of the information matrix - } else { - throw runtime_error("Internal error: Marginals::marginalInformation expected either a JacobianFactor or HessianFactor"); - } + Matrix info = marginalFactor->computeInformation(); + const int dim = info.rows() - 1; + return info.topLeftCorner(dim,dim); // Take the non-augmented part of the information matrix +} + +/* ************************************************************************* */ +JointMarginal::JointMarginal(const JointMarginal& other) : + blockView_(fullMatrix_) { + *this = other; +} + +/* ************************************************************************* */ +JointMarginal& JointMarginal::operator=(const JointMarginal& rhs) { + indices_ = rhs.indices_; + blockView_.assignNoalias(rhs.blockView_); + return *this; } /* ************************************************************************* */ @@ -94,11 +110,11 @@ JointMarginal Marginals::jointMarginalInformation(const std::vector& variab return JointMarginal(info, dims, indices); } else { - // Convert keys to linear indices + // Obtain requested variables as ordered indices vector indices(variables.size()); for(size_t i=0; i& variab jointFG = *GaussianSequentialSolver(graph_, true).jointFactorGraph(indices); } - // Conversion from variable keys to position in factor graph variables, + // Build map from variable keys to position in factor graph variables, // which are sorted in index order. Ordering variableConversion; { + // First build map from index to key FastMap usedIndices; for(size_t i=0; i Index_Key; BOOST_FOREACH(const Index_Key& index_key, usedIndices) { @@ -129,15 +147,30 @@ JointMarginal Marginals::jointMarginalInformation(const std::vector& variab // Get dimensions from factor graph std::vector dims(indices.size(), 0); - for(size_t i = 0; i < variables.size(); ++i) - dims[i] = values_.at(variables[i]).dim(); + BOOST_FOREACH(Key key, variables) { + dims[variableConversion[key]] = values_.at(key).dim(); + } // Get information matrix - Matrix augmentedInfo = jointFG.denseHessian(); + Matrix augmentedInfo = jointFG.augmentedHessian(); Matrix info = augmentedInfo.topLeftCorner(augmentedInfo.rows()-1, augmentedInfo.cols()-1); return JointMarginal(info, dims, variableConversion); } } +/* ************************************************************************* */ +void JointMarginal::print(const std::string& s, const KeyFormatter& formatter) const { + cout << s << "Joint marginal on keys "; + bool first = true; + BOOST_FOREACH(const Ordering::value_type& key_index, indices_) { + if(!first) + cout << ", "; + else + first = false; + cout << formatter(key_index.first); + } + cout << ". Use 'at' or 'operator()' to query matrix blocks." << endl; +} + } /* namespace gtsam */ diff --git a/gtsam/nonlinear/Marginals.h b/gtsam/nonlinear/Marginals.h index 77bccdfd2..302c686e8 100644 --- a/gtsam/nonlinear/Marginals.h +++ b/gtsam/nonlinear/Marginals.h @@ -40,6 +40,16 @@ public: QR }; +protected: + + GaussianFactorGraph graph_; + Ordering ordering_; + Values values_; + Factorization factorization_; + GaussianBayesTree bayesTree_; + +public: + /** Construct a marginals class. * @param graph The factor graph defining the full joint density on all variables. * @param solution The linearization point about which to compute Gaussian marginals (usually the MLE as obtained from a NonlinearOptimizer). @@ -47,6 +57,9 @@ public: */ Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization = CHOLESKY); + /** print */ + void print(const std::string& str = "Marginals: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + /** Compute the marginal covariance of a single variable */ Matrix marginalCovariance(Key variable) const; @@ -60,14 +73,6 @@ public: /** Compute the joint marginal information of several variables */ JointMarginal jointMarginalInformation(const std::vector& variables) const; - -protected: - - GaussianFactorGraph graph_; - Values values_; - Ordering ordering_; - Factorization factorization_; - GaussianBayesTree bayesTree_; }; /** @@ -76,7 +81,12 @@ protected: class JointMarginal { protected: - typedef SymmetricBlockView BlockView; + + typedef SymmetricBlockView BlockView; + + Matrix fullMatrix_; + BlockView blockView_; + Ordering indices_; public: /** A block view of the joint marginal - this stores a reference to the @@ -102,15 +112,32 @@ public: Block operator()(Key iVariable, Key jVariable) const { return blockView_(indices_[iVariable], indices_[jVariable]); } + /** Synonym for operator() */ + Block at(Key iVariable, Key jVariable) const { + return (*this)(iVariable, jVariable); } + + /** The full, dense covariance/information matrix of the joint marginal. This returns + * a reference to the JointMarginal object, so the JointMarginal object must be kept + * in scope while this view is needed. Otherwise assign this block object to a Matrix + * to store it. + */ + const Matrix& fullMatrix() const { return fullMatrix_; } + + /** Copy constructor */ + JointMarginal(const JointMarginal& other); + + /** Assignment operator */ + JointMarginal& operator=(const JointMarginal& rhs); + + /** Print */ + void print(const std::string& s = "", const KeyFormatter& formatter = DefaultKeyFormatter) const; + protected: - Matrix fullMatrix_; - BlockView blockView_; - Ordering indices_; + JointMarginal(const Matrix& fullMatrix, const std::vector& dims, const Ordering& indices) : + fullMatrix_(fullMatrix), blockView_(fullMatrix_, dims.begin(), dims.end()), indices_(indices) {} - JointMarginal(const Matrix& fullMatrix, const std::vector& dims, const Ordering& indices) : - fullMatrix_(fullMatrix), blockView_(fullMatrix_, dims.begin(), dims.end()), indices_(indices) {} + friend class Marginals; - friend class Marginals; }; } /* namespace gtsam */ diff --git a/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.cpp b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.cpp new file mode 100644 index 000000000..da14d8982 --- /dev/null +++ b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.cpp @@ -0,0 +1,64 @@ +/** + * @file GradientDescentOptimizer.cpp + * @brief + * @author ydjian + * @date Jun 11, 2012 + */ + +#include +#include +#include +#include +#include + +#include + +using namespace std; + +namespace gtsam { + +/* Return the gradient vector of a nonlinear factor given a linearization point and a variable ordering + * Can be moved to NonlinearFactorGraph.h if desired */ +void gradientInPlace(const NonlinearFactorGraph &nfg, const Values &values, const Ordering &ordering, VectorValues &g) { + // Linearize graph + GaussianFactorGraph::shared_ptr linear = nfg.linearize(values, ordering); + FactorGraph jfg; jfg.reserve(linear->size()); + BOOST_FOREACH(const GaussianFactorGraph::sharedFactor& factor, *linear) { + if(boost::shared_ptr jf = boost::dynamic_pointer_cast(factor)) + jfg.push_back((jf)); + else + jfg.push_back(boost::make_shared(*factor)); + } + // compute the gradient direction + gradientAtZero(jfg, g); +} + +double NonlinearConjugateGradientOptimizer::System::error(const State &state) const { + return graph_.error(state); +} + +NonlinearConjugateGradientOptimizer::System::Gradient NonlinearConjugateGradientOptimizer::System::gradient(const State &state) const { + Gradient result = state.zeroVectors(ordering_); + gradientInPlace(graph_, state, ordering_, result); + return result; +} +NonlinearConjugateGradientOptimizer::System::State NonlinearConjugateGradientOptimizer::System::advance(const State ¤t, const double alpha, const Gradient &g) const { + Gradient step = g; + step.vector() *= alpha; + return current.retract(step, ordering_); +} + +void NonlinearConjugateGradientOptimizer::iterate() { + size_t dummy ; + boost::tie(state_.values, dummy) = nonlinearConjugateGradient(System(graph_, *ordering_), state_.values, params_, true /* single iterations */); + ++state_.iterations; + state_.error = graph_.error(state_.values); +} + +const Values& NonlinearConjugateGradientOptimizer::optimize() { + boost::tie(state_.values, state_.iterations) = nonlinearConjugateGradient(System(graph_, *ordering_), state_.values, params_, false /* up to convergent */); + state_.error = graph_.error(state_.values); + return state_.values; +} + +} /* namespace gtsam */ diff --git a/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h new file mode 100644 index 000000000..5bac11f5e --- /dev/null +++ b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h @@ -0,0 +1,193 @@ +/** + * @file GradientDescentOptimizer.cpp + * @brief + * @author Yong-Dian Jian + * @date Jun 11, 2012 + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** An implementation of the nonlinear cg method using the template below */ +class NonlinearConjugateGradientState : public NonlinearOptimizerState { +public: + typedef NonlinearOptimizerState Base; + NonlinearConjugateGradientState(const NonlinearFactorGraph& graph, const Values& values) + : Base(graph, values) {} +}; + +class NonlinearConjugateGradientOptimizer : public NonlinearOptimizer { + /* a class for the nonlinearConjugateGradient template */ + class System { + public: + typedef Values State; + typedef VectorValues Gradient; + typedef NonlinearOptimizerParams Parameters; + + protected: + const NonlinearFactorGraph &graph_; + const Ordering &ordering_; + + public: + System(const NonlinearFactorGraph &graph, const Ordering &ordering): graph_(graph), ordering_(ordering) {} + double error(const State &state) const ; + Gradient gradient(const State &state) const ; + State advance(const State ¤t, const double alpha, const Gradient &g) const ; + }; + +public: + typedef NonlinearOptimizer Base; + typedef NonlinearConjugateGradientState States; + typedef NonlinearOptimizerParams Parameters; + typedef boost::shared_ptr shared_ptr; + +protected: + States state_; + Parameters params_; + Ordering::shared_ptr ordering_; + VectorValues::shared_ptr gradient_; + +public: + + NonlinearConjugateGradientOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues, + const Parameters& params = Parameters()) + : Base(graph), state_(graph, initialValues), params_(params), ordering_(initialValues.orderingArbitrary()), + gradient_(new VectorValues(initialValues.zeroVectors(*ordering_))){} + + virtual ~NonlinearConjugateGradientOptimizer() {} + virtual void iterate(); + virtual const Values& optimize (); + virtual const NonlinearOptimizerState& _state() const { return state_; } + virtual const NonlinearOptimizerParams& _params() const { return params_; } +}; + +/** Implement the golden-section line search algorithm */ +template +double lineSearch(const S &system, const V currentValues, const W &gradient) { + + /* normalize it such that it becomes a unit vector */ + const double g = gradient.norm(); + + // perform the golden section search algorithm to decide the the optimal step size + // detail refer to http://en.wikipedia.org/wiki/Golden_section_search + const double phi = 0.5*(1.0+std::sqrt(5.0)), resphi = 2.0 - phi, tau = 1e-5; + double minStep = -1.0/g, maxStep = 0, + newStep = minStep + (maxStep-minStep) / (phi+1.0) ; + + V newValues = system.advance(currentValues, newStep, gradient); + double newError = system.error(newValues); + + while (true) { + const bool flag = (maxStep - newStep > newStep - minStep) ? true : false ; + const double testStep = flag ? + newStep + resphi * (maxStep - newStep) : newStep - resphi * (newStep - minStep); + + if ( (maxStep- minStep) < tau * (std::fabs(testStep) + std::fabs(newStep)) ) { + return 0.5*(minStep+maxStep); + } + + const V testValues = system.advance(currentValues, testStep, gradient); + const double testError = system.error(testValues); + + // update the working range + if ( testError >= newError ) { + if ( flag ) maxStep = testStep; + else minStep = testStep; + } + else { + if ( flag ) { + minStep = newStep; + newStep = testStep; + newError = testError; + } + else { + maxStep = newStep; + newStep = testStep; + newError = testError; + } + } + } + return 0.0; +} + +/** + * Implement the nonlinear conjugate gradient method using the Polak-Ribieve formula suggested in + * http://en.wikipedia.org/wiki/Nonlinear_conjugate_gradient_method. + * + * The S (system) class requires three member functions: error(state), gradient(state) and + * advance(state, step-size, direction). The V class denotes the state or the solution. + * + * The last parameter is a switch between gradient-descent and conjugate gradient + */ +template +boost::tuple nonlinearConjugateGradient(const S &system, const V &initial, const NonlinearOptimizerParams ¶ms, const bool singleIteration, const bool gradientDescent = false) { + + // GTSAM_CONCEPT_MANIFOLD_TYPE(V); + + Index iteration = 0; + + // check if we're already close enough + double currentError = system.error(initial); + if(currentError <= params.errorTol) { + if (params.verbosity >= NonlinearOptimizerParams::ERROR){ + std::cout << "Exiting, as error = " << currentError << " < " << params.errorTol << std::endl; + } + return boost::tie(initial, iteration); + } + + V currentValues = initial; + typename S::Gradient currentGradient = system.gradient(currentValues), prevGradient, + direction = currentGradient; + + /* do one step of gradient descent */ + V prevValues = currentValues; double prevError = currentError; + double alpha = lineSearch(system, currentValues, direction); + currentValues = system.advance(prevValues, alpha, direction); + currentError = system.error(currentValues); + + // Maybe show output + if (params.verbosity >= NonlinearOptimizerParams::ERROR) std::cout << "Initial error: " << currentError << std::endl; + + // Iterative loop + do { + if ( gradientDescent == true) { + direction = system.gradient(currentValues); + } + else { + prevGradient = currentGradient; + currentGradient = system.gradient(currentValues); + const double beta = std::max(0.0, currentGradient.dot(currentGradient-prevGradient)/currentGradient.dot(currentGradient)); + direction = currentGradient + (beta*direction); + } + + alpha = lineSearch(system, currentValues, direction); + + prevValues = currentValues; prevError = currentError; + + currentValues = system.advance(prevValues, alpha, direction); + currentError = system.error(currentValues); + + // Maybe show output + if(params.verbosity >= NonlinearOptimizerParams::ERROR) std::cout << "currentError: " << currentError << std::endl; + } while( ++iteration < params.maxIterations && + !singleIteration && + !checkConvergence(params.relativeErrorTol, params.absoluteErrorTol, params.errorTol, prevError, currentError, params.verbosity)); + + // Printing if verbose + if (params.verbosity >= NonlinearOptimizerParams::ERROR && iteration >= params.maxIterations) + std::cout << "nonlinearConjugateGradient: Terminating because reached maximum iterations" << std::endl; + + return boost::tie(currentValues, iteration); +} + + + + + + +} diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index a1c685668..e4a628b85 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -109,8 +109,8 @@ namespace gtsam { /// @{ virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << "Constraint: " << s << " on [" << keyFormatter(this->key()) << "]\n"; - gtsam::print(feasible_,"Feasible Point"); + std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n"; + gtsam::print(feasible_,"Feasible Point:\n"); std::cout << "Variable Dimension: " << feasible_.dim() << std::endl; } @@ -161,6 +161,11 @@ namespace gtsam { return GaussianFactor::shared_ptr(new JacobianFactor(ordering[this->key()], A, b, model)); } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /// @} private: @@ -190,6 +195,7 @@ namespace gtsam { protected: typedef NoiseModelFactor1 Base; + typedef NonlinearEquality1 This; /** default constructor to allow for serialization */ NonlinearEquality1() {} @@ -209,6 +215,11 @@ namespace gtsam { virtual ~NonlinearEquality1() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** g(x) with optional derivative */ Vector evaluateError(const X& x1, boost::optional H = boost::none) const { if (H) (*H) = eye(x1.dim()); @@ -248,6 +259,7 @@ namespace gtsam { protected: typedef NoiseModelFactor2 Base; + typedef NonlinearEquality2 This; GTSAM_CONCEPT_MANIFOLD_TYPE(X); @@ -263,6 +275,11 @@ namespace gtsam { : Base(noiseModel::Constrained::All(X::Dim(), fabs(mu)), key1, key2) {} virtual ~NonlinearEquality2() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** g(x) with optional derivative2 */ Vector evaluateError(const X& x1, const X& x2, boost::optional H1 = boost::none, diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index bf19555bf..ad10b3ee0 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 */ @@ -28,12 +28,20 @@ #include #include -#include +#include #include #include #include -#include + +/** + * Macro to add a standard clone function to a derived factor + * @deprecated: will go away shortly - just add the clone function directly + */ +#define ADD_CLONE_NONLINEAR_FACTOR(Derived) \ + virtual gtsam::NonlinearFactor::shared_ptr clone() const { \ + return boost::static_pointer_cast( \ + gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); } namespace gtsam { @@ -91,9 +99,9 @@ public: /** print */ virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "keys = { "; + std::cout << s << " keys = { "; BOOST_FOREACH(Key key, this->keys()) { std::cout << keyFormatter(key) << " "; } - std::cout << "}" << endl; + std::cout << "}" << std::endl; } /** Check if two factors are equal */ @@ -111,7 +119,7 @@ public: /** * Calculate the error of the factor - * This is typically equal to log-likelihood, e.g. 0.5(h(x)-z)^2/sigma^2 in case of Gaussian. + * This is typically equal to log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/sigma^2 \f$ in case of Gaussian. * You can override this for systems with unusual noise models. */ virtual double error(const Values& c) const = 0; @@ -146,6 +154,45 @@ public: return IndexFactor::shared_ptr(new IndexFactor(indices)); } + /** + * Creates a shared_ptr clone of the factor - needs to be specialized to allow + * for subclasses + * + * By default, throws exception if subclass does not implement the function. + */ + virtual shared_ptr clone() const { + // TODO: choose better exception to throw here + throw std::runtime_error("NonlinearFactor::clone(): Attempting to clone factor with no clone() implemented!"); + return shared_ptr(); + } + + /** + * Creates a shared_ptr clone of the factor with different keys using + * a map from old->new keys + */ + shared_ptr rekey(const std::map& rekey_mapping) const { + shared_ptr new_factor = clone(); + for (size_t i=0; isize(); ++i) { + Key& cur_key = new_factor->keys()[i]; + std::map::const_iterator mapping = rekey_mapping.find(cur_key); + if (mapping != rekey_mapping.end()) + cur_key = mapping->second; + } + return new_factor; + } + + /** + * Clones a factor and fully replaces its keys + * @param new_keys is the full replacement set of keys + */ + shared_ptr rekey(const std::vector& new_keys) const { + assert(new_keys.size() == this->keys().size()); + shared_ptr new_factor = clone(); + new_factor->keys() = new_keys; + return new_factor; + } + + }; // \class NonlinearFactor /* ************************************************************************* */ @@ -182,7 +229,6 @@ public: /** * Constructor - * @param keys The variables involved in this factor */ template NoiseModelFactor(const SharedNoiseModel& noiseModel, ITERATOR beginKeys, ITERATOR endKeys) @@ -333,14 +379,14 @@ public: /** * Constructor - * @param z measurement - * @param key by which to look up X value in Values + * @param key1 by which to look up X value in Values */ NoiseModelFactor1(const SharedNoiseModel& noiseModel, Key key1) : Base(noiseModel, key1) {} /** Calls the 1-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ + * so must be implemented in the derived class. + */ virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { if(this->active(x)) { const X& x1 = x.at(keys_[0]); diff --git a/gtsam/nonlinear/NonlinearFactorGraph.cpp b/gtsam/nonlinear/NonlinearFactorGraph.cpp index 2400ea996..969e40677 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.cpp +++ b/gtsam/nonlinear/NonlinearFactorGraph.cpp @@ -27,112 +27,161 @@ using namespace std; namespace gtsam { - /* ************************************************************************* */ - double NonlinearFactorGraph::probPrime(const Values& c) const { - return exp(-0.5 * error(c)); +/* ************************************************************************* */ +double NonlinearFactorGraph::probPrime(const Values& c) const { + return exp(-0.5 * error(c)); +} + +/* ************************************************************************* */ +void NonlinearFactorGraph::print(const std::string& str, const KeyFormatter& keyFormatter) const { + cout << str << "size: " << size() << endl; + for (size_t i = 0; i < factors_.size(); i++) { + stringstream ss; + ss << "factor " << i << ": "; + if (factors_[i] != NULL) factors_[i]->print(ss.str(), keyFormatter); } +} - /* ************************************************************************* */ - void NonlinearFactorGraph::print(const std::string& str, const KeyFormatter& keyFormatter) const { - cout << str << "size: " << size() << endl; - for (size_t i = 0; i < factors_.size(); i++) { - stringstream ss; - ss << "factor " << i << ": "; - if (factors_[i] != NULL) factors_[i]->print(ss.str(), keyFormatter); - } +/* ************************************************************************* */ +double NonlinearFactorGraph::error(const Values& c) const { + double total_error = 0.; + // iterate over all the factors_ to accumulate the log probabilities + BOOST_FOREACH(const sharedFactor& factor, this->factors_) { + if(factor) + total_error += factor->error(c); } + return total_error; +} - /* ************************************************************************* */ - double NonlinearFactorGraph::error(const Values& c) const { - double total_error = 0.; - // iterate over all the factors_ to accumulate the log probabilities - BOOST_FOREACH(const sharedFactor& factor, this->factors_) { - if(factor) - total_error += factor->error(c); - } - return total_error; +/* ************************************************************************* */ +FastSet NonlinearFactorGraph::keys() const { + FastSet keys; + BOOST_FOREACH(const sharedFactor& factor, this->factors_) { + if(factor) + keys.insert(factor->begin(), factor->end()); } + return keys; +} - /* ************************************************************************* */ - std::set NonlinearFactorGraph::keys() const { - std::set keys; - BOOST_FOREACH(const sharedFactor& factor, this->factors_) { - if(factor) - keys.insert(factor->begin(), factor->end()); - } - return keys; - } - - /* ************************************************************************* */ - Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMD( - const Values& config) const { - - // Create symbolic graph and initial (iterator) ordering - SymbolicFactorGraph::shared_ptr symbolic; - Ordering::shared_ptr ordering; - boost::tie(symbolic, ordering) = this->symbolic(config); - - // Compute the VariableIndex (column-wise index) - VariableIndex variableIndex(*symbolic, ordering->size()); - if (config.size() != variableIndex.size()) throw std::runtime_error( - "orderingCOLAMD: some variables in the graph are not constrained!"); - - // Compute a fill-reducing ordering with COLAMD - Permutation::shared_ptr colamdPerm(inference::PermutationCOLAMD( - variableIndex)); - - // Permute the Ordering with the COLAMD ordering - ordering->permuteWithInverse(*colamdPerm->inverse()); - - // Return the Ordering and VariableIndex to be re-used during linearization - // and elimination - return ordering; - } - - /* ************************************************************************* */ - SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic(const Ordering& ordering) const { - // Generate the symbolic factor graph - SymbolicFactorGraph::shared_ptr symbolicfg(new SymbolicFactorGraph); - symbolicfg->reserve(this->size()); - - BOOST_FOREACH(const sharedFactor& factor, this->factors_) { - if(factor) - symbolicfg->push_back(factor->symbolic(ordering)); - else - symbolicfg->push_back(SymbolicFactorGraph::sharedFactor()); - } - - return symbolicfg; - } - - /* ************************************************************************* */ - pair NonlinearFactorGraph::symbolic( +/* ************************************************************************* */ +Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMD( const Values& config) const { - // Generate an initial key ordering in iterator order - Ordering::shared_ptr ordering(config.orderingArbitrary()); - return make_pair(symbolic(*ordering), ordering); + + // Create symbolic graph and initial (iterator) ordering + SymbolicFactorGraph::shared_ptr symbolic; + Ordering::shared_ptr ordering; + boost::tie(symbolic, ordering) = this->symbolic(config); + + // Compute the VariableIndex (column-wise index) + VariableIndex variableIndex(*symbolic, ordering->size()); + if (config.size() != variableIndex.size()) throw std::runtime_error( + "orderingCOLAMD: some variables in the graph are not constrained!"); + + // Compute a fill-reducing ordering with COLAMD + Permutation::shared_ptr colamdPerm(inference::PermutationCOLAMD( + variableIndex)); + + // Permute the Ordering with the COLAMD ordering + ordering->permuteWithInverse(*colamdPerm->inverse()); + return ordering; +} + +/* ************************************************************************* */ +Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMDConstrained(const Values& config, + const std::map& constraints) const { + // Create symbolic graph and initial (iterator) ordering + SymbolicFactorGraph::shared_ptr symbolic; + Ordering::shared_ptr ordering; + boost::tie(symbolic, ordering) = this->symbolic(config); + + // Compute the VariableIndex (column-wise index) + VariableIndex variableIndex(*symbolic, ordering->size()); + if (config.size() != variableIndex.size()) throw std::runtime_error( + "orderingCOLAMD: some variables in the graph are not constrained!"); + + // Create a constraint list with correct indices + typedef std::map::value_type constraint_type; + std::map index_constraints; + BOOST_FOREACH(const constraint_type& p, constraints) + index_constraints[ordering->at(p.first)] = p.second; + + // Compute a constrained fill-reducing ordering with COLAMD + Permutation::shared_ptr colamdPerm(inference::PermutationCOLAMDGrouped( + variableIndex, index_constraints)); + + // Permute the Ordering with the COLAMD ordering + ordering->permuteWithInverse(*colamdPerm->inverse()); + return ordering; +} + +/* ************************************************************************* */ +SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic(const Ordering& ordering) const { + // Generate the symbolic factor graph + SymbolicFactorGraph::shared_ptr symbolicfg(new SymbolicFactorGraph); + symbolicfg->reserve(this->size()); + + BOOST_FOREACH(const sharedFactor& factor, this->factors_) { + if(factor) + symbolicfg->push_back(factor->symbolic(ordering)); + else + symbolicfg->push_back(SymbolicFactorGraph::sharedFactor()); } - /* ************************************************************************* */ - GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize( - const Values& config, const Ordering& ordering) const { + return symbolicfg; +} - // create an empty linear FG - GaussianFactorGraph::shared_ptr linearFG(new GaussianFactorGraph); - linearFG->reserve(this->size()); +/* ************************************************************************* */ +pair NonlinearFactorGraph::symbolic( + const Values& config) const { + // Generate an initial key ordering in iterator order + Ordering::shared_ptr ordering(config.orderingArbitrary()); + return make_pair(symbolic(*ordering), ordering); +} - // linearize all factors - BOOST_FOREACH(const sharedFactor& factor, this->factors_) { - if(factor) { - GaussianFactor::shared_ptr lf = factor->linearize(config, ordering); - if (lf) linearFG->push_back(lf); - } else - linearFG->push_back(GaussianFactor::shared_ptr()); - } +/* ************************************************************************* */ +GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize( + const Values& config, const Ordering& ordering) const { - return linearFG; + // create an empty linear FG + GaussianFactorGraph::shared_ptr linearFG(new GaussianFactorGraph); + linearFG->reserve(this->size()); + + // linearize all factors + BOOST_FOREACH(const sharedFactor& factor, this->factors_) { + if(factor) { + GaussianFactor::shared_ptr lf = factor->linearize(config, ordering); + if (lf) linearFG->push_back(lf); + } else + linearFG->push_back(GaussianFactor::shared_ptr()); } + return linearFG; +} + +/* ************************************************************************* */ +NonlinearFactorGraph NonlinearFactorGraph::clone() const { + NonlinearFactorGraph result; + BOOST_FOREACH(const sharedFactor& f, *this) { + if (f) + result.push_back(f->clone()); + else + result.push_back(sharedFactor()); // Passes on null factors so indices remain valid + } + return result; +} + +/* ************************************************************************* */ +NonlinearFactorGraph NonlinearFactorGraph::rekey(const std::map& rekey_mapping) const { + NonlinearFactorGraph result; + BOOST_FOREACH(const sharedFactor& f, *this) { + if (f) + result.push_back(f->rekey(rekey_mapping)); + else + result.push_back(sharedFactor()); + } + return result; +} + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 3caeec680..f7ebb42bc 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -46,18 +46,23 @@ namespace gtsam { /** print just calls base class */ void print(const std::string& str = "NonlinearFactorGraph: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - /** return keys in some random order */ - std::set keys() const; + /** return keys as an ordered set - ordering is by key value */ + FastSet keys() const; - /** unnormalized error */ + /** unnormalized error, \f$ 0.5 \sum_i (h_i(X_i)-z)^2/\sigma^2 \f$ in the most common case */ double error(const Values& c) const; /** Unnormalized probability. O(n) */ double probPrime(const Values& c) const; - template - void add(const F& factor) { - this->push_back(boost::shared_ptr(new F(factor))); + /// Add a factor by value - copies the factor object + void add(const NonlinearFactor& factor) { + this->push_back(factor.clone()); + } + + /// Add a factor by pointer - stores pointer without copying factor object + void add(const sharedFactor& factor) { + this->push_back(factor); } /** @@ -75,18 +80,43 @@ namespace gtsam { symbolic(const Values& config) const; /** - * Compute a fill-reducing ordering using COLAMD. This returns the - * ordering and a VariableIndex, which can later be re-used to save - * computation. + * Compute a fill-reducing ordering using COLAMD. */ Ordering::shared_ptr orderingCOLAMD(const Values& config) const; + /** + * Compute a fill-reducing ordering with constraints using CCOLAMD + * + * @param constraints is a map of Key->group, where 0 is unconstrained, and higher + * group numbers are further back in the ordering. Only keys with nonzero group + * indices need to appear in the constraints, unconstrained is assumed for all + * other variables + */ + Ordering::shared_ptr orderingCOLAMDConstrained(const Values& config, + const std::map& constraints) const; + /** * linearize a nonlinear factor graph */ boost::shared_ptr linearize(const Values& config, const Ordering& ordering) const; + /** + * Clone() performs a deep-copy of the graph, including all of the factors + */ + NonlinearFactorGraph clone() const; + + /** + * Rekey() performs a deep-copy of all of the factors, and changes + * keys according to a mapping. + * + * Keys not specified in the mapping will remain unchanged. + * + * @param rekey_mapping is a map of old->new keys + * @result a cloned graph with updated keys + */ + NonlinearFactorGraph rekey(const std::map& rekey_mapping) const; + private: /** Serialization function */ diff --git a/gtsam/nonlinear/NonlinearISAM-inl.h b/gtsam/nonlinear/NonlinearISAM.cpp similarity index 59% rename from gtsam/nonlinear/NonlinearISAM-inl.h rename to gtsam/nonlinear/NonlinearISAM.cpp index e054ecacb..b2135fedd 100644 --- a/gtsam/nonlinear/NonlinearISAM-inl.h +++ b/gtsam/nonlinear/NonlinearISAM.cpp @@ -15,22 +15,28 @@ * @author Viorela Ila and Richard Roberts */ -#pragma once - -#include - -#include +#include #include #include #include +#include + +#include + using namespace std; -using namespace gtsam; + +namespace gtsam { + /* ************************************************************************* */ -template -void NonlinearISAM::update(const Factors& newFactors, +void NonlinearISAM::saveGraph(const string& s, const KeyFormatter& keyFormatter) const { + isam_.saveGraph(s, OrderingIndexFormatter(ordering_, keyFormatter)); +} + +/* ************************************************************************* */ +void NonlinearISAM::update(const NonlinearFactorGraph& newFactors, const Values& initialValues) { if(newFactors.size() > 0) { @@ -48,13 +54,13 @@ void NonlinearISAM::update(const Factors& newFactors, linPoint_.insert(initialValues); // Augment ordering + // TODO: allow for ordering constraints within the new variables // FIXME: should just loop over new values - BOOST_FOREACH(const typename Factors::sharedFactor& factor, newFactors) + BOOST_FOREACH(const NonlinearFactorGraph::sharedFactor& factor, newFactors) BOOST_FOREACH(Key key, factor->keys()) ordering_.tryInsert(key, ordering_.nVars()); // will do nothing if already present - boost::shared_ptr linearizedNewFactors( - newFactors.linearize(linPoint_, ordering_)->template dynamicCastFactors()); + boost::shared_ptr linearizedNewFactors = newFactors.linearize(linPoint_, ordering_); // Update ISAM isam_.update(*linearizedNewFactors); @@ -62,8 +68,7 @@ void NonlinearISAM::update(const Factors& newFactors, } /* ************************************************************************* */ -template -void NonlinearISAM::reorder_relinearize() { +void NonlinearISAM::reorder_relinearize() { // cout << "Reordering, relinearizing..." << endl; @@ -74,11 +79,12 @@ void NonlinearISAM::reorder_relinearize() { isam_.clear(); // Compute an ordering + // TODO: allow for constrained ordering here ordering_ = *factors_.orderingCOLAMD(newLinPoint); // Create a linear factor graph at the new linearization point - boost::shared_ptr gfg( - factors_.linearize(newLinPoint, ordering_)->template dynamicCastFactors()); + // TODO: decouple relinearization and reordering to avoid + boost::shared_ptr gfg = factors_.linearize(newLinPoint, ordering_); // Just recreate the whole BayesTree isam_.update(*gfg); @@ -89,8 +95,7 @@ void NonlinearISAM::reorder_relinearize() { } /* ************************************************************************* */ -template -Values NonlinearISAM::estimate() const { +Values NonlinearISAM::estimate() const { if(isam_.size() > 0) return linPoint_.retract(optimize(isam_), ordering_); else @@ -98,18 +103,24 @@ Values NonlinearISAM::estimate() const { } /* ************************************************************************* */ -template -Matrix NonlinearISAM::marginalCovariance(Key key) const { +Matrix NonlinearISAM::marginalCovariance(Key key) const { return isam_.marginalCovariance(ordering_[key]); } /* ************************************************************************* */ -template -void NonlinearISAM::print(const std::string& s) const { - cout << "ISAM - " << s << ":" << endl; - cout << " ReorderInterval: " << reorderInterval_ << " Current Count: " << reorderCounter_ << endl; - isam_.print("GaussianISAM"); - linPoint_.print("Linearization Point"); - ordering_.print("System Ordering"); - factors_.print("Nonlinear Graph"); +void NonlinearISAM::print(const string& s, const KeyFormatter& keyFormatter) const { + cout << s << "ReorderInterval: " << reorderInterval_ << " Current Count: " << reorderCounter_ << endl; + isam_.print("GaussianISAM:\n"); + linPoint_.print("Linearization Point:\n", keyFormatter); + ordering_.print("System Ordering:\n", keyFormatter); + factors_.print("Nonlinear Graph:\n", keyFormatter); } + +/* ************************************************************************* */ +void NonlinearISAM::printStats() const { + isam_.getCliqueData().getStats().print(); +} + +/* ************************************************************************* */ + +}///\ namespace gtsam diff --git a/gtsam/nonlinear/NonlinearISAM.h b/gtsam/nonlinear/NonlinearISAM.h index 16547770b..fc2f69f55 100644 --- a/gtsam/nonlinear/NonlinearISAM.h +++ b/gtsam/nonlinear/NonlinearISAM.h @@ -24,12 +24,7 @@ namespace gtsam { /** * Wrapper class to manage ISAM in a nonlinear context */ -template class NonlinearISAM { -public: - - typedef GRAPH Factors; - protected: /** The internal iSAM object */ @@ -42,7 +37,7 @@ protected: gtsam::Ordering ordering_; /** The original factors, used when relinearizing */ - Factors factors_; + NonlinearFactorGraph factors_; /** The reordering interval and counter */ int reorderInterval_; @@ -84,21 +79,27 @@ public: const gtsam::Ordering& getOrdering() const { return ordering_; } /** get underlying nonlinear graph */ - const Factors& getFactorsUnsafe() const { return factors_; } + const NonlinearFactorGraph& getFactorsUnsafe() const { return factors_; } /** get counters */ int reorderInterval() const { return reorderInterval_; } /// diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index 76d1fe573..2312a9f88 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -19,11 +19,49 @@ #include #include #include - +#include using namespace std; namespace gtsam { +/* ************************************************************************* */ +NonlinearOptimizerParams::Verbosity NonlinearOptimizerParams::verbosityTranslator(const std::string &src) const { + std::string s = src; boost::algorithm::to_upper(s); + if (s == "SILENT") return NonlinearOptimizerParams::SILENT; + if (s == "ERROR") return NonlinearOptimizerParams::ERROR; + if (s == "VALUES") return NonlinearOptimizerParams::VALUES; + if (s == "DELTA") return NonlinearOptimizerParams::DELTA; + if (s == "LINEAR") return NonlinearOptimizerParams::LINEAR; + + /* default is silent */ + return NonlinearOptimizerParams::SILENT; +} + +/* ************************************************************************* */ +std::string NonlinearOptimizerParams::verbosityTranslator(Verbosity value) const { + std::string s; + switch (value) { + case NonlinearOptimizerParams::SILENT: s = "SILENT"; break; + case NonlinearOptimizerParams::ERROR: s = "ERROR"; break; + case NonlinearOptimizerParams::VALUES: s = "VALUES"; break; + case NonlinearOptimizerParams::DELTA: s = "DELTA"; break; + case NonlinearOptimizerParams::LINEAR: s = "LINEAR"; break; + default: s = "UNDEFINED"; break; + } + return s; +} + +/* ************************************************************************* */ +void NonlinearOptimizerParams::print(const std::string& str) const { + std::cout << str << "\n"; + std::cout << "relative decrease threshold: " << relativeErrorTol << "\n"; + std::cout << "absolute decrease threshold: " << absoluteErrorTol << "\n"; + std::cout << " total error threshold: " << errorTol << "\n"; + std::cout << " maximum iterations: " << maxIterations << "\n"; + std::cout << " verbosity: " << verbosityTranslator(verbosity) << "\n"; + std::cout.flush(); +} + /* ************************************************************************* */ void NonlinearOptimizer::defaultOptimize() { @@ -64,12 +102,24 @@ void NonlinearOptimizer::defaultOptimize() { cout << "Terminating because reached maximum iterations" << endl; } +/* ************************************************************************* */ +const Values& NonlinearOptimizer::optimizeSafely() { + static const Values empty; + try { + defaultOptimize(); + return values(); + } catch (...) { + // uncaught exception, returning empty result + return empty; + } +} + /* ************************************************************************* */ bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity) { - if ( verbosity >= 2 ) { + if ( verbosity >= NonlinearOptimizerParams::ERROR ) { if ( newError <= errorThreshold ) cout << "errorThreshold: " << newError << " < " << errorThreshold << endl; else @@ -80,7 +130,7 @@ bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold // check if diverges double absoluteDecrease = currentError - newError; - if (verbosity >= 2) { + if (verbosity >= NonlinearOptimizerParams::ERROR) { if (absoluteDecrease <= absoluteErrorTreshold) cout << "absoluteDecrease: " << setprecision(12) << absoluteDecrease << " < " << absoluteErrorTreshold << endl; else @@ -89,7 +139,7 @@ bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold // calculate relative error decrease and update currentError double relativeDecrease = absoluteDecrease / currentError; - if (verbosity >= 2) { + if (verbosity >= NonlinearOptimizerParams::ERROR) { if (relativeDecrease <= relativeErrorTreshold) cout << "relativeDecrease: " << setprecision(12) << relativeDecrease << " < " << relativeErrorTreshold << endl; else @@ -97,7 +147,7 @@ bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold } bool converged = (relativeErrorTreshold && (relativeDecrease <= relativeErrorTreshold)) || (absoluteDecrease <= absoluteErrorTreshold); - if (verbosity >= 1 && converged) { + if (verbosity >= NonlinearOptimizerParams::ERROR && converged) { if(absoluteDecrease >= 0.0) cout << "converged" << endl; else @@ -105,6 +155,7 @@ bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold } return converged; } +/* ************************************************************************* */ } diff --git a/gtsam/nonlinear/NonlinearOptimizer.h b/gtsam/nonlinear/NonlinearOptimizer.h index 388058ac0..488d3d832 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.h +++ b/gtsam/nonlinear/NonlinearOptimizer.h @@ -45,21 +45,28 @@ public: Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) NonlinearOptimizerParams() : - maxIterations(100.0), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), + maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol(0.0), verbosity(SILENT) {} - virtual void print(const std::string& str = "") const { - std::cout << str << "\n"; - std::cout << "relative decrease threshold: " << relativeErrorTol << "\n"; - std::cout << "absolute decrease threshold: " << absoluteErrorTol << "\n"; - std::cout << " total error threshold: " << errorTol << "\n"; - std::cout << " maximum iterations: " << maxIterations << "\n"; - std::cout << " verbosity level: " << verbosity << std::endl; - } - virtual ~NonlinearOptimizerParams() {} -}; + virtual void print(const std::string& str = "") const ; + size_t getMaxIterations() const { return maxIterations; } + double getRelativeErrorTol() const { return relativeErrorTol; } + double getAbsoluteErrorTol() const { return absoluteErrorTol; } + double getErrorTol() const { return errorTol; } + std::string getVerbosity() const { return verbosityTranslator(verbosity); } + + void setMaxIterations(size_t value) { maxIterations = value; } + void setRelativeErrorTol(double value) { relativeErrorTol = value; } + void setAbsoluteErrorTol(double value) { absoluteErrorTol = value; } + void setErrorTol(double value) { errorTol = value ; } + void setVerbosity(const std::string &src) { verbosity = verbosityTranslator(src); } + +private: + Verbosity verbosityTranslator(const std::string &s) const; + std::string verbosityTranslator(Verbosity value) const; +}; /** * Base class for a nonlinear optimization state, including the current estimate @@ -169,8 +176,10 @@ Values::const_shared_ptr result = DoglegOptimizer(graph, initialValues, params). */ class NonlinearOptimizer { -public: +protected: + NonlinearFactorGraph graph_; +public: /** A shared pointer to this class */ typedef boost::shared_ptr shared_ptr; @@ -188,10 +197,21 @@ public: */ virtual const Values& optimize() { defaultOptimize(); return values(); } + /** + * Optimize, but return empty result if any uncaught exception is thrown + * Intended for MATLAB. In C++, use above and catch exceptions. + * No message is printed: it is up to the caller to check the result + * @param optimizer a non-linear optimizer + */ + const Values& optimizeSafely(); + + /// return error double error() const { return _state().error; } + /// return number of iterations unsigned int iterations() const { return _state().iterations; } + /// return values const Values& values() const { return _state().values; } /// @} @@ -210,10 +230,7 @@ public: /// @} -protected: - - NonlinearFactorGraph graph_; - +protected: /** A default implementation of the optimization loop, which calls iterate() * until checkConvergence returns true. */ @@ -229,7 +246,7 @@ protected: }; /** Check whether the relative error decrease is less than relativeErrorTreshold, - * the absolute error decrease is less than absoluteErrorTreshold, or + * the absolute error decrease is less than absoluteErrorTreshold, or * the error itself is less than errorThreshold. */ bool checkConvergence(double relativeErrorTreshold, diff --git a/gtsam/nonlinear/Ordering.cpp b/gtsam/nonlinear/Ordering.cpp index 14be537d3..b445af506 100644 --- a/gtsam/nonlinear/Ordering.cpp +++ b/gtsam/nonlinear/Ordering.cpp @@ -41,13 +41,27 @@ void Ordering::permuteWithInverse(const Permutation& inversePermutation) { /* ************************************************************************* */ void Ordering::print(const string& str, const KeyFormatter& keyFormatter) const { - cout << str << " "; - BOOST_FOREACH(const Ordering::value_type& key_order, *this) { - if(key_order != *begin()) - cout << ", "; - cout << keyFormatter(key_order.first) << ":" << key_order.second; - } - cout << endl; + cout << str; + // Print ordering in index order + Ordering::InvertedMap inverted = this->invert(); + // Print the ordering with varsPerLine ordering entries printed on each line, + // for compactness. + static const size_t varsPerLine = 10; + bool endedOnNewline = false; + BOOST_FOREACH(const Ordering::InvertedMap::value_type& index_key, inverted) { + if(index_key.first % varsPerLine != 0) + cout << ", "; + cout << index_key.first << ":" << keyFormatter(index_key.second); + if(index_key.first % varsPerLine == varsPerLine - 1) { + cout << "\n"; + endedOnNewline = true; + } else { + endedOnNewline = false; + } + } + if(!endedOnNewline) + cout << "\n"; + cout.flush(); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/Ordering.h b/gtsam/nonlinear/Ordering.h index e2837a1ca..c6881fbde 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 { @@ -93,7 +93,8 @@ public: /// behavior of std::map) Index& operator[](Key key) { iterator i=order_.find(key); - if(i == order_.end()) throw std::out_of_range(std::string("Attempting to access a key from an ordering that does not contain that key")); + if(i == order_.end()) throw std::out_of_range( + std::string("Attempting to access a key from an ordering that does not contain that key:") + DefaultKeyFormatter(key)); else return i->second; } /// Access the index for the requested key, throws std::out_of_range if the @@ -101,7 +102,8 @@ public: /// behavior of std::map) Index operator[](Key key) const { const_iterator i=order_.find(key); - if(i == order_.end()) throw std::out_of_range(std::string("Attempting to access a key from an ordering that does not contain that key")); + if(i == order_.end()) throw std::out_of_range( + std::string("Attempting to access a key from an ordering that does not contain that key:") + DefaultKeyFormatter(key)); else return i->second; } /** Returns an iterator pointing to the symbol/index pair with the requested, @@ -153,7 +155,7 @@ public: iterator end() { return order_.end(); } /// Test if the key exists in the ordering. - bool exists(Key key) const { return order_.count(key); } + bool exists(Key key) const { return order_.count(key) > 0; } ///TODO: comment std::pair tryInsert(Key key, Index order) { return tryInsert(std::make_pair(key,order)); } @@ -215,7 +217,7 @@ public: /// @{ /** print (from Testable) for testing and debugging */ - void print(const std::string& str = "Ordering:", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& str = "Ordering:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /** equals (from Testable) for testing and debugging */ bool equals(const Ordering& rhs, double tol = 0.0) const; @@ -231,7 +233,10 @@ private: ar & BOOST_SERIALIZATION_NVP(order_); ar & BOOST_SERIALIZATION_NVP(nVars_); } -}; +}; // \class Ordering + +// typedef for use with matlab +typedef Ordering::InvertedMap InvertedOrdering; /** * @class Unordered @@ -256,5 +261,17 @@ public: bool equals(const Unordered &t, double tol=0) const; }; -} +// Create an index formatter that looks up the Key in an inverse ordering, then +// formats the key using the provided key formatter, used in saveGraph. +struct OrderingIndexFormatter { + Ordering::InvertedMap inverseOrdering; + const KeyFormatter& keyFormatter; + OrderingIndexFormatter(const Ordering& ordering, const KeyFormatter& keyFormatter) : + inverseOrdering(ordering.invert()), keyFormatter(keyFormatter) {} + std::string operator()(Index index) { + return keyFormatter(inverseOrdering.at(index)); + } +}; + +} // \namespace gtsam diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.cpp b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.cpp new file mode 100644 index 000000000..fec460b08 --- /dev/null +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.cpp @@ -0,0 +1,80 @@ +/** + * @file SuccessiveLinearizationOptimizer.cpp + * @brief + * @date Jul 24, 2012 + * @author Yong-Dian Jian + */ + +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +void SuccessiveLinearizationParams::setIterativeParams(const SubgraphSolverParameters ¶ms) { + iterativeParams = boost::make_shared(params); +} + +void SuccessiveLinearizationParams::print(const std::string& str) const { + NonlinearOptimizerParams::print(str); + switch ( linearSolverType ) { + case MULTIFRONTAL_CHOLESKY: + std::cout << " linear solver type: MULTIFRONTAL CHOLESKY\n"; + break; + case MULTIFRONTAL_QR: + std::cout << " linear solver type: MULTIFRONTAL QR\n"; + break; + case SEQUENTIAL_CHOLESKY: + std::cout << " linear solver type: SEQUENTIAL CHOLESKY\n"; + break; + case SEQUENTIAL_QR: + std::cout << " linear solver type: SEQUENTIAL QR\n"; + break; + case CHOLMOD: + std::cout << " linear solver type: CHOLMOD\n"; + break; + case CONJUGATE_GRADIENT: + std::cout << " linear solver type: CONJUGATE GRADIENT\n"; + break; + default: + std::cout << " linear solver type: (invalid)\n"; + break; + } + + if(ordering) + std::cout << " ordering: custom\n"; + else + std::cout << " ordering: COLAMD\n"; + + std::cout.flush(); +} + +VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams ¶ms) { + VectorValues delta; + if ( params.isMultifrontal() ) { + delta = GaussianJunctionTree(gfg).optimize(params.getEliminationFunction()); + } + else if ( params.isSequential() ) { + delta = gtsam::optimize(*EliminationTree::Create(gfg)->eliminate(params.getEliminationFunction())); + } + else if ( params.isCG() ) { + if ( !params.iterativeParams ) throw std::runtime_error("solveGaussianFactorGraph: cg parameter has to be assigned ..."); + if ( boost::dynamic_pointer_cast(params.iterativeParams) ) { + SubgraphSolver solver (gfg, *boost::dynamic_pointer_cast(params.iterativeParams)); + delta = solver.optimize(); + } + else { + throw std::runtime_error("solveGaussianFactorGraph: special cg parameter type is not handled in LM solver ..."); + } + } + else { + throw std::runtime_error("solveGaussianFactorGraph: Optimization parameter is invalid"); + } + return delta; +} + +} diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h index f17e01d49..d422c09a9 100644 --- a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h @@ -19,64 +19,88 @@ #pragma once #include +#include namespace gtsam { class SuccessiveLinearizationParams : public NonlinearOptimizerParams { public: - /** See SuccessiveLinearizationParams::elimination */ - enum Elimination { - MULTIFRONTAL, - SEQUENTIAL + /** See SuccessiveLinearizationParams::linearSolverType */ + enum LinearSolverType { + MULTIFRONTAL_CHOLESKY, + MULTIFRONTAL_QR, + SEQUENTIAL_CHOLESKY, + SEQUENTIAL_QR, + CONJUGATE_GRADIENT, /* Experimental Flag */ + CHOLMOD, /* Experimental Flag */ }; - /** See SuccessiveLinearizationParams::factorization */ - enum Factorization { - CHOLESKY, - QR, - }; - - Elimination elimination; ///< The elimination algorithm to use (default: MULTIFRONTAL) - Factorization factorization; ///< The numerical factorization (default: Cholesky) + LinearSolverType linearSolverType; ///< The type of linear solver to use in the nonlinear optimizer boost::optional ordering; ///< The variable elimination ordering, or empty to use COLAMD (default: empty) + IterativeOptimizationParameters::shared_ptr iterativeParams; ///< The container for iterativeOptimization parameters. used in CG Solvers. - SuccessiveLinearizationParams() : - elimination(MULTIFRONTAL), factorization(CHOLESKY) {} - + SuccessiveLinearizationParams() : linearSolverType(MULTIFRONTAL_CHOLESKY) {} virtual ~SuccessiveLinearizationParams() {} - virtual void print(const std::string& str = "") const { - NonlinearOptimizerParams::print(str); - if(elimination == MULTIFRONTAL) - std::cout << " elimination method: MULTIFRONTAL\n"; - else if(elimination == SEQUENTIAL) - std::cout << " elimination method: SEQUENTIAL\n"; - else - std::cout << " elimination method: (invalid)\n"; + inline bool isMultifrontal() const { + return (linearSolverType == MULTIFRONTAL_CHOLESKY) || (linearSolverType == MULTIFRONTAL_QR); } - if(factorization == CHOLESKY) - std::cout << " factorization method: CHOLESKY\n"; - else if(factorization == QR) - std::cout << " factorization method: QR\n"; - else - std::cout << " factorization method: (invalid)\n"; + inline bool isSequential() const { + return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR); } - if(ordering) - std::cout << " ordering: custom\n"; - else - std::cout << " ordering: COLAMD\n"; + inline bool isCholmod() const { return (linearSolverType == CHOLMOD); } - std::cout.flush(); - } + inline bool isCG() const { return (linearSolverType == CONJUGATE_GRADIENT); } + + virtual void print(const std::string& str) const; GaussianFactorGraph::Eliminate getEliminationFunction() const { - if(factorization == SuccessiveLinearizationParams::CHOLESKY) + switch (linearSolverType) { + case MULTIFRONTAL_CHOLESKY: + case SEQUENTIAL_CHOLESKY: return EliminatePreferCholesky; - else if(factorization == SuccessiveLinearizationParams::QR) + + case MULTIFRONTAL_QR: + case SEQUENTIAL_QR: return EliminateQR; - else - throw runtime_error("Nonlinear optimization parameter \"factorization\" is invalid"); + + default: + throw std::runtime_error("Nonlinear optimization parameter \"factorization\" is invalid"); + return EliminateQR; + break; + } } + + std::string getLinearSolverType() const { return linearSolverTranslator(linearSolverType); } + + void setLinearSolverType(const std::string& solver) { linearSolverType = linearSolverTranslator(solver); } + void setIterativeParams(const SubgraphSolverParameters ¶ms); + void setOrdering(const Ordering& ordering) { this->ordering = ordering; } + +private: + std::string linearSolverTranslator(LinearSolverType linearSolverType) const { + switch(linearSolverType) { + case MULTIFRONTAL_CHOLESKY: return "MULTIFRONTAL_CHOLESKY"; + case MULTIFRONTAL_QR: return "MULTIFRONTAL_QR"; + case SEQUENTIAL_CHOLESKY: return "SEQUENTIAL_CHOLESKY"; + case SEQUENTIAL_QR: return "SEQUENTIAL_QR"; + case CONJUGATE_GRADIENT: return "CONJUGATE_GRADIENT"; + case CHOLMOD: return "CHOLMOD"; + default: throw std::invalid_argument("Unknown linear solver type in SuccessiveLinearizationOptimizer"); + } + } + LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const { + if(linearSolverType == "MULTIFRONTAL_CHOLESKY") return MULTIFRONTAL_CHOLESKY; + if(linearSolverType == "MULTIFRONTAL_QR") return MULTIFRONTAL_QR; + if(linearSolverType == "SEQUENTIAL_CHOLESKY") return SEQUENTIAL_CHOLESKY; + if(linearSolverType == "SEQUENTIAL_QR") return SEQUENTIAL_QR; + if(linearSolverType == "CONJUGATE_GRADIENT") return CONJUGATE_GRADIENT; + if(linearSolverType == "CHOLMOD") return CHOLMOD; + throw std::invalid_argument("Unknown linear solver type in SuccessiveLinearizationOptimizer"); + } }; +/* a wrapper for solving a GaussianFactorGraph according to the parameters */ +VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams ¶ms) ; + } /* namespace gtsam */ diff --git a/gtsam/nonlinear/Symbol.cpp b/gtsam/nonlinear/Symbol.cpp new file mode 100644 index 000000000..19cf78eb5 --- /dev/null +++ b/gtsam/nonlinear/Symbol.cpp @@ -0,0 +1,74 @@ +/* ---------------------------------------------------------------------------- + + * 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 Symbol.cpp + * @date June 9, 2012 + * @author: Frank Dellaert + * @author: Richard Roberts + */ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace gtsam { + +static const size_t keyBits = sizeof(Key) * 8; +static const size_t chrBits = sizeof(unsigned char) * 8; +static const size_t indexBits = keyBits - chrBits; +static const Key chrMask = Key(UCHAR_MAX) << indexBits; // For some reason, std::numeric_limits::max() fails +static const Key indexMask = ~chrMask; + +Symbol::Symbol(Key key) { + c_ = (unsigned char) ((key & chrMask) >> indexBits); + j_ = key & indexMask; +} + +Key Symbol::key() const { + if (j_ > indexMask) { + boost::format msg("Symbol index is too large, j=%d, indexMask=%d"); + msg % j_ % indexMask; + throw std::invalid_argument(msg.str()); + } + Key key = (Key(c_) << indexBits) | j_; + return key; +} + +void Symbol::print(const std::string& s) const { + std::cout << s << (std::string) (*this) << std::endl; +} + +bool Symbol::equals(const Symbol& expected, double tol) const { + return (*this) == expected; +} + +Symbol::operator std::string() const { + return str(boost::format("%c%d") % c_ % j_); +} + +boost::function Symbol::ChrTest(unsigned char c) { + namespace bl = boost::lambda; + return bl::bind(&Symbol::chr, bl::bind(bl::constructor(), bl::_1)) + == c; +} + +} // namespace gtsam + diff --git a/gtsam/nonlinear/Symbol.h b/gtsam/nonlinear/Symbol.h index f671a4b30..c128b1105 100644 --- a/gtsam/nonlinear/Symbol.h +++ b/gtsam/nonlinear/Symbol.h @@ -18,17 +18,8 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include - #include +#include namespace gtsam { @@ -44,6 +35,7 @@ protected: size_t j_; public: + /** Default constructor */ Symbol() : c_(0), j_(0) { @@ -60,36 +52,19 @@ public: } /** Constructor that decodes an integer Key */ - Symbol(Key key) { - const size_t keyBits = sizeof(Key) * 8; - const size_t chrBits = sizeof(unsigned char) * 8; - const size_t indexBits = keyBits - chrBits; - const Key chrMask = Key(std::numeric_limits::max()) << indexBits; - const Key indexMask = ~chrMask; - c_ = (unsigned char)((key & chrMask) >> indexBits); - j_ = key & indexMask; - } + Symbol(Key key); + + /** return Key (integer) representation */ + Key key() const; /** Cast to integer */ - operator Key() const { - const size_t keyBits = sizeof(Key) * 8; - const size_t chrBits = sizeof(unsigned char) * 8; - const size_t indexBits = keyBits - chrBits; - const Key chrMask = Key(std::numeric_limits::max()) << indexBits; - const Key indexMask = ~chrMask; - if(j_ > indexMask) - throw std::invalid_argument("Symbol index is too large"); - Key key = (Key(c_) << indexBits) | j_; - return key; - } + operator Key() const { return key(); } - // Testable Requirements - void print(const std::string& s = "") const { - std::cout << s << ": " << (std::string) (*this) << std::endl; - } - bool equals(const Symbol& expected, double tol = 0.0) const { - return (*this) == expected; - } + /// Print + void print(const std::string& s = "") const; + + /// Check equality + bool equals(const Symbol& expected, double tol = 0.0) const; /** Retrieve key character */ unsigned char chr() const { @@ -102,23 +77,29 @@ public: } /** Create a string from the key */ - operator std::string() const { - return str(boost::format("%c%d") % c_ % j_); - } + operator std::string() const; /** Comparison for use in maps */ bool operator<(const Symbol& comp) const { return c_ < comp.c_ || (comp.c_ == c_ && j_ < comp.j_); } + + /** Comparison for use in maps */ bool operator==(const Symbol& comp) const { return comp.c_ == c_ && comp.j_ == j_; } + + /** Comparison for use in maps */ bool operator==(Key comp) const { return comp == (Key)(*this); } + + /** Comparison for use in maps */ bool operator!=(const Symbol& comp) const { return comp.c_ != c_ || comp.j_ != j_; } + + /** Comparison for use in maps */ bool operator!=(Key comp) const { return comp != (Key)(*this); } @@ -128,10 +109,7 @@ public: * Values::filter() function to retrieve all key-value pairs with the * requested character. */ - static boost::function ChrTest(unsigned char c) { - namespace bl = boost::lambda; - return bl::bind(&Symbol::chr, bl::bind(bl::constructor(), bl::_1)) == c; - } + static boost::function ChrTest(unsigned char c); private: @@ -144,6 +122,15 @@ private: } }; +/** Create a symbol key from a character and index, i.e. x5. */ +inline Key symbol(unsigned char c, size_t j) { return (Key)Symbol(c,j); } + +/** Return the character portion of a symbol key. */ +inline unsigned char symbolChr(Key key) { return Symbol(key).chr(); } + +/** Return the index portion of a symbol key. */ +inline size_t symbolIndex(Key key) { return Symbol(key).index(); } + namespace symbol_shorthand { inline Key A(size_t j) { return Symbol('a', j); } inline Key B(size_t j) { return Symbol('b', j); } diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index 40e95188e..3aec3e7b2 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -40,6 +40,187 @@ namespace gtsam { ValueCloneAllocator() {} }; + /* ************************************************************************* */ + template + struct _ValuesKeyValuePair { + const Key key; ///< The key + ValueType& value; ///< The value + + _ValuesKeyValuePair(Key _key, ValueType& _value) : key(_key), value(_value) {} + }; + + /* ************************************************************************* */ + template + struct _ValuesConstKeyValuePair { + const Key key; ///< The key + const ValueType& value; ///< The value + + _ValuesConstKeyValuePair(Key _key, const ValueType& _value) : key(_key), value(_value) {} + _ValuesConstKeyValuePair(const _ValuesKeyValuePair& rhs) : key(rhs.key), value(rhs.value) {} + }; + + /* ************************************************************************* */ + template + class Values::Filtered { + public: + /** A key-value pair, with the value a specific derived Value type. */ + typedef _ValuesKeyValuePair KeyValuePair; + typedef _ValuesConstKeyValuePair ConstKeyValuePair; + typedef KeyValuePair value_type; + + typedef + boost::transform_iterator< + KeyValuePair(*)(Values::KeyValuePair), + boost::filter_iterator< + boost::function, + Values::iterator> > + iterator; + + typedef iterator const_iterator; + + typedef + boost::transform_iterator< + ConstKeyValuePair(*)(Values::ConstKeyValuePair), + boost::filter_iterator< + boost::function, + Values::const_iterator> > + const_const_iterator; + + iterator begin() { return begin_; } + iterator end() { return end_; } + const_iterator begin() const { return begin_; } + const_iterator end() const { return end_; } + const_const_iterator beginConst() const { return constBegin_; } + const_const_iterator endConst() const { return constEnd_; } + + /** Returns the number of values in this view */ + size_t size() const { + size_t i = 0; + for (const_const_iterator it = beginConst(); it != endConst(); ++it) + ++i; + return i; + } + + private: + Filtered(const boost::function& filter, Values& values) : + begin_(boost::make_transform_iterator( + boost::make_filter_iterator( + filter, values.begin(), values.end()), + &castHelper)), + end_(boost::make_transform_iterator( + boost::make_filter_iterator( + filter, values.end(), values.end()), + &castHelper)), + constBegin_(boost::make_transform_iterator( + boost::make_filter_iterator( + filter, ((const Values&)values).begin(), ((const Values&)values).end()), + &castHelper)), + constEnd_(boost::make_transform_iterator( + boost::make_filter_iterator( + filter, ((const Values&)values).end(), ((const Values&)values).end()), + &castHelper)) {} + + friend class Values; + iterator begin_; + iterator end_; + const_const_iterator constBegin_; + const_const_iterator constEnd_; + }; + + /* ************************************************************************* */ + template + class Values::ConstFiltered { + public: + /** A const key-value pair, with the value a specific derived Value type. */ + typedef _ValuesConstKeyValuePair KeyValuePair; + typedef KeyValuePair value_type; + + typedef typename Filtered::const_const_iterator iterator; + typedef typename Filtered::const_const_iterator const_iterator; + + /** Conversion from Filtered to ConstFiltered */ + ConstFiltered(const Filtered& rhs) : + begin_(rhs.beginConst()), + end_(rhs.endConst()) {} + + iterator begin() { return begin_; } + iterator end() { return end_; } + const_iterator begin() const { return begin_; } + const_iterator end() const { return end_; } + + /** Returns the number of values in this view */ + size_t size() const { + size_t i = 0; + for (const_iterator it = begin(); it != end(); ++it) + ++i; + return i; + } + + FastList keys() const { + FastList result; + for(const_iterator it = begin(); it != end(); ++it) + result.push_back(it->key); + return result; + } + + private: + friend class Values; + const_iterator begin_; + const_iterator end_; + ConstFiltered(const boost::function& filter, const Values& values) { + // We remove the const from values to create a non-const Filtered + // view, then pull the const_iterators out of it. + const Filtered filtered(filter, const_cast(values)); + begin_ = filtered.beginConst(); + end_ = filtered.endConst(); + } + }; + + /* ************************************************************************* */ + /** Constructor from a Filtered view copies out all values */ + template + Values::Values(const Values::Filtered& view) { + BOOST_FOREACH(const typename Filtered::KeyValuePair& key_value, view) { + Key key = key_value.key; + insert(key, key_value.value); + } + } + + /* ************************************************************************* */ + template + Values::Values(const Values::ConstFiltered& view) { + BOOST_FOREACH(const typename ConstFiltered::KeyValuePair& key_value, view) { + Key key = key_value.key; + insert(key, key_value.value); + } + } + + /* ************************************************************************* */ + Values::Filtered + inline Values::filter(const boost::function& filterFcn) { + return filter(filterFcn); + } + + /* ************************************************************************* */ + template + Values::Filtered + Values::filter(const boost::function& filterFcn) { + return Filtered(boost::bind(&filterHelper, filterFcn, _1), *this); + } + + /* ************************************************************************* */ + Values::ConstFiltered + inline Values::filter(const boost::function& filterFcn) const { + return filter(filterFcn); + } + + /* ************************************************************************* */ + template + Values::ConstFiltered + Values::filter(const boost::function& filterFcn) const { + return ConstFiltered(boost::bind(&filterHelper, filterFcn, _1), *this); + } + /* ************************************************************************* */ template const ValueType& Values::at(Key j) const { diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index c3d3bd8df..eab37ff17 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -41,9 +41,9 @@ namespace gtsam { /* ************************************************************************* */ void Values::print(const string& str, const KeyFormatter& keyFormatter) const { - cout << str << "Values with " << size() << " values:\n" << endl; + cout << str << "Values with " << size() << " values:" << endl; for(const_iterator key_value = begin(); key_value != end(); ++key_value) { - cout << " " << keyFormatter(key_value->key) << ": "; + cout << "Value " << keyFormatter(key_value->key) << ": "; key_value->value.print(""); } } @@ -90,7 +90,15 @@ namespace gtsam { /* ************************************************************************* */ VectorValues Values::localCoordinates(const Values& cp, const Ordering& ordering) const { VectorValues result(this->dims(ordering)); - localCoordinates(cp, ordering, result); + if(this->size() != cp.size()) + throw DynamicValuesMismatched(); + for(const_iterator it1=this->begin(), it2=cp.begin(); it1!=this->end(); ++it1, ++it2) { + if(it1->key != it2->key) + throw DynamicValuesMismatched(); // If keys do not match + // Will throw a dynamic_cast exception if types do not match + // NOTE: this is separate from localCoordinates(cp, ordering, result) due to at() vs. insert + result.at(ordering[it1->key]) = it1->value.localCoordinates_(it2->value); + } return result; } @@ -120,7 +128,7 @@ namespace gtsam { /* ************************************************************************* */ void Values::insert(Key j, const Value& val) { Key key = j; // Non-const duplicate to deal with non-const insert argument - std::pair insertResult = values_.insert(key, val.clone_()); + std::pair insertResult = values_.insert(key, val.clone_()); if(!insertResult.second) throw ValuesKeyAlreadyExists(j); } @@ -165,10 +173,8 @@ namespace gtsam { /* ************************************************************************* */ FastList Values::keys() const { FastList result; - for(const_iterator key_value = begin(); key_value != end(); ++key_value) { + for(const_iterator key_value = begin(); key_value != end(); ++key_value) result.push_back(key_value->key); - cout << result.back() << endl; - } return result; } diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 4af8e5a3e..25bd3dc2e 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -24,8 +24,11 @@ #pragma once -#include -#include +#include +#include +#include +#include +#include #include #include @@ -35,20 +38,18 @@ #include #include #include -#include -#include -#include -#include -#include +#include +#include namespace gtsam { - // Forward declarations + // Forward declarations / utilities class ValueCloneAllocator; class ValueAutomaticCasting; + template static bool _truePredicate(const T&) { return true; } -/** + /** * A non-templated config holding any types of Manifold-group elements. A * values structure is a map from keys to values. It is used to specify the * value of a bunch of variables in a factor graph. A Values is a values @@ -122,133 +123,13 @@ namespace gtsam { typedef KeyValuePair value_type; - private: - template - struct _KeyValuePair { - const Key key; ///< The key - ValueType& value; ///< The value - - _KeyValuePair(Key _key, ValueType& _value) : key(_key), value(_value) {} - }; - - template - struct _ConstKeyValuePair { - const Key key; ///< The key - const ValueType& value; ///< The value - - _ConstKeyValuePair(Key _key, const ValueType& _value) : key(_key), value(_value) {} - _ConstKeyValuePair(const _KeyValuePair& rhs) : key(rhs.key), value(rhs.value) {} - }; - - public: - + /** A filtered view of a Values, returned from Values::filter. */ template - class Filtered { - public: - /** A key-value pair, with the value a specific derived Value type. */ - typedef _KeyValuePair KeyValuePair; - typedef _ConstKeyValuePair ConstKeyValuePair; - typedef KeyValuePair value_type; - - typedef - boost::transform_iterator< - KeyValuePair(*)(Values::KeyValuePair), - boost::filter_iterator< - boost::function, - Values::iterator> > - iterator; - - typedef iterator const_iterator; - - typedef - boost::transform_iterator< - ConstKeyValuePair(*)(Values::ConstKeyValuePair), - boost::filter_iterator< - boost::function, - Values::const_iterator> > - const_const_iterator; - - iterator begin() { return begin_; } - iterator end() { return end_; } - const_iterator begin() const { return begin_; } - const_iterator end() const { return end_; } - const_const_iterator beginConst() const { return constBegin_; } - const_const_iterator endConst() const { return constEnd_; } - - /** Returns the number of values in this view */ - size_t size() const { - size_t i = 0; - for (const_const_iterator it = beginConst(); it != endConst(); ++it) - ++i; - return i; - } - - private: - Filtered(const boost::function& filter, Values& values) : - begin_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, values.begin(), values.end()), - &castHelper)), - end_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, values.end(), values.end()), - &castHelper)), - constBegin_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, ((const Values&)values).begin(), ((const Values&)values).end()), - &castHelper)), - constEnd_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, ((const Values&)values).end(), ((const Values&)values).end()), - &castHelper)) {} - - friend class Values; - iterator begin_; - iterator end_; - const_const_iterator constBegin_; - const_const_iterator constEnd_; - }; + class Filtered; + /** A filtered view of a const Values, returned from Values::filter. */ template - class ConstFiltered { - public: - /** A const key-value pair, with the value a specific derived Value type. */ - typedef _ConstKeyValuePair KeyValuePair; - typedef KeyValuePair value_type; - - typedef typename Filtered::const_const_iterator iterator; - typedef typename Filtered::const_const_iterator const_iterator; - - /** Conversion from Filtered to ConstFiltered */ - ConstFiltered(const Filtered& rhs) : - begin_(rhs.beginConst()), - end_(rhs.endConst()) {} - - iterator begin() { return begin_; } - iterator end() { return end_; } - const_iterator begin() const { return begin_; } - const_iterator end() const { return end_; } - - /** Returns the number of values in this view */ - size_t size() const { - size_t i = 0; - for (const_iterator it = begin(); it != end(); ++it) - ++i; - return i; - } - - private: - friend class Values; - const_iterator begin_; - const_iterator end_; - ConstFiltered(const boost::function& filter, const Values& values) { - // We remove the const from values to create a non-const Filtered - // view, then pull the const_iterators out of it. - const Filtered filtered(filter, const_cast(values)); - begin_ = filtered.beginConst(); - end_ = filtered.endConst(); - } - }; + class ConstFiltered; /** Default constructor creates an empty Values class */ Values() {} @@ -258,21 +139,11 @@ namespace gtsam { /** Constructor from a Filtered view copies out all values */ template - Values(const Filtered& view) { - BOOST_FOREACH(const typename Filtered::KeyValuePair& key_value, view) { - Key key = key_value.key; - insert(key, key_value.value); - } - } + Values(const Filtered& view); - /** Constructor from Const Filtered view */ + /** Constructor from a Filtered or ConstFiltered view */ template - Values(const ConstFiltered& view) { - BOOST_FOREACH(const typename ConstFiltered::KeyValuePair& key_value, view) { - Key key = key_value.key; - insert(key, key_value.value); - } - } + Values(const ConstFiltered& view); /// @name Testable /// @{ @@ -323,13 +194,6 @@ namespace gtsam { /** Get a zero VectorValues of the correct structure */ VectorValues zeroVectors(const Ordering& ordering) const; - private: - static ConstKeyValuePair make_const_deref_pair(const KeyValueMap::const_iterator::value_type& key_value) { - return ConstKeyValuePair(key_value.first, *key_value.second); } - static KeyValuePair make_deref_pair(const KeyValueMap::iterator::value_type& key_value) { - return KeyValuePair(key_value.first, *key_value.second); } - - public: const_iterator begin() const { return boost::make_transform_iterator(values_.begin(), &make_const_deref_pair); } const_iterator end() const { return boost::make_transform_iterator(values_.end(), &make_const_deref_pair); } iterator begin() { return boost::make_transform_iterator(values_.begin(), &make_deref_pair); } @@ -348,7 +212,7 @@ namespace gtsam { /** Get a delta config about a linearization point c0 (*this) */ VectorValues localCoordinates(const Values& cp, const Ordering& ordering) const; - /** Get a delta config about a linearization point c0 (*this) */ + /** Get a delta config about a linearization point c0 (*this) - assumes uninitialized delta */ void localCoordinates(const Values& cp, const Ordering& ordering, VectorValues& delta) const; ///@} @@ -372,7 +236,7 @@ namespace gtsam { * Returns a set of keys in the config * Note: by construction, the list is ordered */ - FastList keys() const; + KeyList keys() const; /** Replace all keys and variables */ Values& operator=(const Values& rhs); @@ -402,7 +266,7 @@ namespace gtsam { * When iterating over the filtered view, only the key-value pairs * with a key causing \c filterFcn to return \c true are visited. Because * the object Filtered returned from filter() is only a - * view the original Values object must not be deallocated or + * view the original Values object must not be deallocated or * go out of scope as long as the view is needed. * @param filterFcn The function that determines which key-value pairs are * included in the filtered view, for which this function returns \c true @@ -411,9 +275,7 @@ namespace gtsam { * the original Values class. */ Filtered - filter(const boost::function& filterFcn) { - return filter(filterFcn); - } + filter(const boost::function& filterFcn); /** * Return a filtered view of this Values class, without copying any data. @@ -421,7 +283,7 @@ namespace gtsam { * template argument \c ValueType and whose key causes the function argument * \c filterFcn to return true are visited when iterating over the filtered * view. Because the object Filtered returned from filter() is only - * a view the original Values object must not be deallocated or + * a view the original Values object must not be deallocated or * go out of scope as long as the view is needed. * @tparam ValueType The type that the value in a key-value pair must match * to be included in the filtered view. Currently, base classes are not @@ -436,16 +298,14 @@ namespace gtsam { */ template Filtered - filter(const boost::function& filterFcn = (boost::lambda::_1, true)) { - return Filtered(boost::bind(&filterHelper, filterFcn, _1), *this); - } + filter(const boost::function& filterFcn = &_truePredicate); /** * Return a filtered view of this Values class, without copying any data. * When iterating over the filtered view, only the key-value pairs * with a key causing \c filterFcn to return \c true are visited. Because * the object Filtered returned from filter() is only a - * view the original Values object must not be deallocated or + * view the original Values object must not be deallocated or * go out of scope as long as the view is needed. * @param filterFcn The function that determines which key-value pairs are * included in the filtered view, for which this function returns \c true @@ -454,9 +314,7 @@ namespace gtsam { * the original Values class. */ ConstFiltered - filter(const boost::function& filterFcn) const { - return filter(filterFcn); - } + filter(const boost::function& filterFcn) const; /** * Return a filtered view of this Values class, without copying any data. @@ -464,7 +322,7 @@ namespace gtsam { * template argument \c ValueType and whose key causes the function argument * \c filterFcn to return true are visited when iterating over the filtered * view. Because the object Filtered returned from filter() is only - * a view the original Values object must not be deallocated or + * a view the original Values object must not be deallocated or * go out of scope as long as the view is needed. * @tparam ValueType The type that the value in a key-value pair must match * to be included in the filtered view. Currently, base classes are not @@ -478,9 +336,7 @@ namespace gtsam { */ template ConstFiltered - filter(const boost::function& filterFcn = (boost::lambda::_1, true)) const { - return ConstFiltered(boost::bind(&filterHelper, filterFcn, _1), *this); - } + filter(const boost::function& filterFcn = &_truePredicate) const; private: // Filters based on ValueType (if not Value) and also based on the user- @@ -505,6 +361,12 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(values_); } + static ConstKeyValuePair make_const_deref_pair(const KeyValueMap::const_iterator::value_type& key_value) { + return ConstKeyValuePair(key_value.first, *key_value.second); } + + static KeyValuePair make_deref_pair(const KeyValueMap::iterator::value_type& key_value) { + return KeyValuePair(key_value.first, *key_value.second); } + }; /* ************************************************************************* */ @@ -516,13 +378,13 @@ namespace gtsam { mutable std::string message_; public: - /// Construct with the key-value pair attemped to be added + /// Construct with the key-value pair attempted to be added ValuesKeyAlreadyExists(Key key) throw() : key_(key) {} virtual ~ValuesKeyAlreadyExists() throw() {} - /// The duplicate key that was attemped to be added + /// The duplicate key that was attempted to be added Key key() const throw() { return key_; } /// The message to be displayed to the user diff --git a/gtsam/nonlinear/WhiteNoiseFactor.h b/gtsam/nonlinear/WhiteNoiseFactor.h index f5fb7fae1..163633115 100644 --- a/gtsam/nonlinear/WhiteNoiseFactor.h +++ b/gtsam/nonlinear/WhiteNoiseFactor.h @@ -51,7 +51,7 @@ namespace gtsam { public: - /** @brief negative log likelihood as a function of mean \mu and precision \tau + /** @brief negative log likelihood as a function of mean \f$ \mu \f$ and precision \f$ \tau \f$ * @f[ * f(z, \tau, \mu) * = -\log \left( \frac{\sqrt{\tau}}{\sqrt{2\pi}} \exp(-0.5\tau(z-\mu)^2) \right) @@ -163,6 +163,11 @@ namespace gtsam { return linearize(z_, u, p, j1, j2); } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /// @} }; diff --git a/gtsam/nonlinear/tests/testKey.cpp b/gtsam/nonlinear/tests/testKey.cpp index 54a2e504a..ee9734af5 100644 --- a/gtsam/nonlinear/tests/testKey.cpp +++ b/gtsam/nonlinear/tests/testKey.cpp @@ -21,17 +21,19 @@ using namespace boost::assign; #include #include #include - + using namespace std; using namespace gtsam; +Key aKey = gtsam::symbol_shorthand::X(4); + /* ************************************************************************* */ TEST(Key, KeySymbolConversion) { - Symbol expected('j', 4); - Key key(expected); + Symbol original('j', 4); + Key key(original); + EXPECT(assert_equal(key, original.key())) Symbol actual(key); - - EXPECT(assert_equal(expected, actual)) + EXPECT(assert_equal(original, actual)) } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/tests/testOrdering.cpp b/gtsam/nonlinear/tests/testOrdering.cpp index f57e3281a..d89c04d3c 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; @@ -43,8 +44,11 @@ TEST( testOrdering, simple_modifications ) { CHECK_EXCEPTION(ordering.pop_back(x1), std::invalid_argument); // reassemble back make the ordering 1, 2, 4, 3 - ordering.push_back(x4); - ordering.push_back(x3); + EXPECT_LONGS_EQUAL(2, ordering.push_back(x4)); + EXPECT_LONGS_EQUAL(3, ordering.push_back(x3)); + + EXPECT_LONGS_EQUAL(2, ordering[x4]); + EXPECT_LONGS_EQUAL(3, ordering[x3]); // verify Ordering expectedFinal; diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 120a9fa94..57e2c0a34 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 @@ -46,13 +47,13 @@ typedef PinholeCamera PinholeCal3DS2; typedef PinholeCamera PinholeCal3Bundler; /* ************************************************************************* */ -Point3 pt3(1.0, 2.0, 3.0); -Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); -Pose3 pose3(rt3, pt3); +static Point3 pt3(1.0, 2.0, 3.0); +static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); +static Pose3 pose3(rt3, pt3); -Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); -Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0); -Cal3Bundler cal3(1.0, 2.0, 3.0); +static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); +static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0); +static Cal3Bundler cal3(1.0, 2.0, 3.0); TEST (Serialization, TemplatedValues) { Values values; diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 6ccd3b083..ffef740a6 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -10,28 +10,54 @@ * -------------------------------------------------------------------------- */ /** - * @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); + + +class TestValueData { +public: + static int ConstructorCount; + static int DestructorCount; + TestValueData(const TestValueData& other) { cout << "Copy constructor" << endl; ++ ConstructorCount; } + TestValueData() { cout << "Default constructor" << endl; ++ ConstructorCount; } + ~TestValueData() { cout << "Destructor" << endl; ++ DestructorCount; } +}; +int TestValueData::ConstructorCount = 0; +int TestValueData::DestructorCount = 0; +class TestValue : public DerivedValue { + TestValueData data_; +public: + virtual void print(const std::string& str = "") const {} + bool equals(const TestValue& other, double tol = 1e-9) const { return true; } + virtual size_t dim() const { return 0; } + TestValue retract(const Vector&) const { return TestValue(); } + Vector localCoordinates(const TestValue&) const { return Vector(); } +}; /* ************************************************************************* */ TEST( Values, equals1 ) @@ -208,6 +234,24 @@ TEST(Values, expmap_d) CHECK(config0.equals(config0)); } +/* ************************************************************************* */ +TEST(Values, localCoordinates) +{ + Values valuesA; + valuesA.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); + valuesA.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); + + Ordering ordering = *valuesA.orderingArbitrary(); + + VectorValues expDelta = valuesA.zeroVectors(ordering); +// expDelta.at(ordering[key1]) = Vector_(3, 0.1, 0.2, 0.3); +// expDelta.at(ordering[key2]) = Vector_(3, 0.4, 0.5, 0.6); + + Values valuesB = valuesA.retract(expDelta, ordering); + + EXPECT(assert_equal(expDelta, valuesA.localCoordinates(valuesB, ordering))); +} + /* ************************************************************************* */ TEST(Values, extract_keys) { @@ -332,9 +376,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; @@ -353,6 +397,26 @@ TEST(Values, Symbol_filter) { LONGS_EQUAL(2, i); } +/* ************************************************************************* */ +TEST(Values, Destructors) { + // Check that Value destructors are called when Values container is deleted + { + Values values; + { + TestValue value1; + TestValue value2; + LONGS_EQUAL(2, TestValueData::ConstructorCount); + LONGS_EQUAL(0, TestValueData::DestructorCount); + values.insert(0, value1); + values.insert(1, value2); + } + LONGS_EQUAL(4, TestValueData::ConstructorCount); + LONGS_EQUAL(2, TestValueData::DestructorCount); + } + LONGS_EQUAL(4, TestValueData::ConstructorCount); + LONGS_EQUAL(4, TestValueData::DestructorCount); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index 633360fed..b5e77b578 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -26,6 +26,7 @@ namespace gtsam { * A class for downdating an existing factor from a graph. The AntiFactor returns the same * linearized Hessian matrices of the original factor, but with the opposite sign. This effectively * cancels out any affects of the original factor during optimization." + * @addtogroup SLAM */ class AntiFactor: public NonlinearFactor { @@ -50,6 +51,11 @@ namespace gtsam { virtual ~AntiFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** implement functions needed for Testable */ /** print */ @@ -94,30 +100,8 @@ namespace gtsam { // Generate the linearized factor from the contained nonlinear factor GaussianFactor::shared_ptr gaussianFactor = factor_->linearize(c, ordering); - // Cast the GaussianFactor to a Hessian - HessianFactor::shared_ptr hessianFactor = boost::dynamic_pointer_cast(gaussianFactor); - - // If the cast fails, convert it to a Hessian - if(!hessianFactor){ - hessianFactor = HessianFactor::shared_ptr(new HessianFactor(*gaussianFactor)); - } - - // Copy Hessian Blocks from Hessian factor and invert - std::vector js; - std::vector Gs; - std::vector gs; - double f; - js.insert(js.end(), hessianFactor->begin(), hessianFactor->end()); - for(size_t i = 0; i < js.size(); ++i){ - for(size_t j = i; j < js.size(); ++j){ - Gs.push_back( -hessianFactor->info(hessianFactor->begin()+i, hessianFactor->begin()+j) ); - } - gs.push_back( -hessianFactor->linearTerm(hessianFactor->begin()+i) ); - } - f = -hessianFactor->constantTerm(); - - // Create the Anti-Hessian Factor from the negated blocks - return HessianFactor::shared_ptr(new HessianFactor(js, Gs, gs, f)); + // return the negated version of the factor + return gaussianFactor->negate(); } diff --git a/gtsam/slam/BearingFactor.h b/gtsam/slam/BearingFactor.h index 7c208436a..86a6e159c 100644 --- a/gtsam/slam/BearingFactor.h +++ b/gtsam/slam/BearingFactor.h @@ -24,13 +24,14 @@ namespace gtsam { /** * Binary factor for a bearing measurement + * @addtogroup SLAM */ - template + template class BearingFactor: public NoiseModelFactor2 { private: typedef POSE Pose; - typedef typename Pose::Rotation Rot; + typedef ROTATION Rot; typedef POINT Point; typedef BearingFactor This; @@ -55,6 +56,11 @@ namespace gtsam { virtual ~BearingFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** h(x)-z -> between(z,h(x)) for Rot2 manifold */ Vector evaluateError(const Pose& pose, const Point& point, boost::optional H1, boost::optional H2) const { @@ -73,6 +79,13 @@ namespace gtsam { return e != NULL && Base::equals(*e, tol) && this->measured_.equals(e->measured_, tol); } + /** print contents */ + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BearingFactor, bearing = "; + measured_.print(); + Base::print("", keyFormatter); + } + private: /** Serialization function */ diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 4c170c811..d701054f9 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -26,13 +26,14 @@ namespace gtsam { /** * Binary factor for a bearing measurement + * @addtogroup SLAM */ - template + template class BearingRangeFactor: public NoiseModelFactor2 { private: typedef POSE Pose; - typedef typename POSE::Rotation Rot; + typedef ROTATION Rot; typedef POINT Point; typedef BearingRangeFactor This; @@ -57,14 +58,19 @@ namespace gtsam { virtual ~BearingRangeFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** Print */ virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << ": BearingRangeFactor(" + std::cout << s << "BearingRangeFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; - measuredBearing_.print(" measured bearing"); - std::cout << " measured range: " << measuredRange_ << std::endl; - this->noiseModel_->print(" noise model"); + measuredBearing_.print("measured bearing: "); + std::cout << "measured range: " << measuredRange_ << std::endl; + this->noiseModel_->print("noise model:\n"); } /** equals */ diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 2df0b98de..14314ceb7 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -27,6 +27,7 @@ namespace gtsam { /** * A class for a measurement predicted by "between(config[key1],config[key2])" * @tparam VALUE the Value type + * @addtogroup SLAM */ template class BetweenFactor: public NoiseModelFactor2 { @@ -62,6 +63,11 @@ namespace gtsam { virtual ~BetweenFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** implement functions needed for Testable */ /** print */ @@ -69,8 +75,8 @@ namespace gtsam { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; - measured_.print(" measured"); - this->noiseModel_->print(" noise model"); + measured_.print(" measured: "); + this->noiseModel_->print(" noise model: "); } /** equals */ diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 0032d9a05..43d3802c0 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -27,6 +27,7 @@ namespace gtsam { * greater/less than a fixed threshold. The function * will need to have its value function implemented to return * a scalar for comparison. + * @addtogroup SLAM */ template struct BoundingConstraint1: public NoiseModelFactor1 { diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 4f1f48958..3f3ae5a52 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -20,18 +20,21 @@ #pragma once -#include #include - +#include +#include +#include +#include namespace gtsam { /** - * Non-linear factor for a constraint derived from a 2D measurement. The calibration is unknown here compared to GenericProjectionFactor + * Non-linear factor for a constraint derived from a 2D measurement. + * The calibration is unknown here compared to GenericProjectionFactor + * @addtogroup SLAM */ template - class GeneralSFMFactor: - public NoiseModelFactor2 { + class GeneralSFMFactor: public NoiseModelFactor2 { protected: Point2 measured_; ///< the 2D measurement @@ -47,10 +50,10 @@ namespace gtsam { /** * Constructor - * @param z is the 2 dimensional location of point in image (the measurement) + * @param measured is the 2 dimensional location of point in image (the measurement) * @param model is the standard deviation of the measurements - * @param i is basically the frame number - * @param j is the index of the landmark + * @param cameraKey is the index of the camera + * @param landmarkKey is the index of the landmark */ GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model, Key cameraKey, Key landmarkKey) : Base(model, cameraKey, landmarkKey), measured_(measured) {} @@ -61,9 +64,15 @@ namespace gtsam { virtual ~GeneralSFMFactor() {} ///< destructor + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** * print * @param s optional string naming the factor + * @param keyFormatter optional formatter for printing out Symbols */ void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { Base::print(s, keyFormatter); @@ -91,8 +100,8 @@ namespace gtsam { if (H2) *H2 = zeros(2, point.dim()); // cout << e.what() << ": Landmark "<< this->key2_.index() // << " behind Camera " << this->key1_.index() << endl; - return zero(2); } + return zero(2); } /** return the measured */ @@ -105,8 +114,103 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } }; + /** + * Non-linear factor for a constraint derived from a 2D measurement. + * Compared to GeneralSFMFactor, it is a ternary-factor because the calibration is isolated from camera.. + */ + template + class GeneralSFMFactor2: public NoiseModelFactor3 { + protected: + Point2 measured_; ///< the 2D measurement + + public: + + typedef GeneralSFMFactor2 This; + typedef PinholeCamera Camera; ///< typedef for camera type + typedef NoiseModelFactor3 Base; ///< typedef for the base class + typedef Point2 Measurement; ///< typedef for the measurement + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** + * Constructor + * @param measured is the 2 dimensional location of point in image (the measurement) + * @param model is the standard deviation of the measurements + * @param poseKey is the index of the camera + * @param landmarkKey is the index of the landmark + * @param calibKey is the index of the calibration + */ + GeneralSFMFactor2(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, Key calibKey) : + Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {} + GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor + + virtual ~GeneralSFMFactor2() {} ///< destructor + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + measured_.print(s + ".z"); + } + + /** + * equals + */ + bool equals(const NonlinearFactor &p, double tol = 1e-9) const { + const This* e = dynamic_cast(&p); + return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol) ; + } + + /** h(x)-z */ + Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib, + boost::optional H1=boost::none, + boost::optional H2=boost::none, + boost::optional H3=boost::none) const + { + try { + Camera camera(pose3,calib); + Point2 reprojError(camera.project(point, H1, H2, H3) - measured_); + return reprojError.vector(); + } + catch( CheiralityException& e) { + if (H1) *H1 = zeros(2, pose3.dim()); + if (H2) *H2 = zeros(2, point.dim()); + if (H3) *H3 = zeros(2, calib.dim()); + } + return zero(2); + } + + /** return the measured */ + inline const Point2 measured() const { + return measured_; + } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor3", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + }; + + + } //namespace diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 2ab011bf5..5bd0ee76f 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -22,6 +22,7 @@ namespace gtsam { /** * A class for a soft prior on any Value type + * @addtogroup SLAM */ template class PriorFactor: public NoiseModelFactor1 { @@ -56,13 +57,18 @@ namespace gtsam { Base(model, key), prior_(prior) { } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** implement functions needed for Testable */ /** print */ 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"); + std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n"; + prior_.print(" prior mean: "); + this->noiseModel_->print(" noise model: "); } /** equals */ diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index d5e9048e5..79796e6c3 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -28,14 +28,15 @@ namespace gtsam { /** * Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here. * i.e. the main building block for visual SLAM. + * @addtogroup SLAM */ - template + template class GenericProjectionFactor: public NoiseModelFactor2 { protected: // Keep a copy of measurement and calibration for I/O - Point2 measured_; ///< 2D measurement - boost::shared_ptr K_; ///< shared pointer to calibration object + Point2 measured_; ///< 2D measurement + boost::shared_ptr K_; ///< shared pointer to calibration object public: @@ -43,40 +44,46 @@ namespace gtsam { typedef NoiseModelFactor2 Base; /// shorthand for this class - typedef GenericProjectionFactor This; + typedef GenericProjectionFactor This; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; /// Default constructor - GenericProjectionFactor() : - K_(new Cal3_S2(444, 555, 666, 777, 888)) { + GenericProjectionFactor() { } /** * Constructor * TODO: Mark argument order standard (keys, measurement, parameters) - * @param z is the 2 dimensional location of point in image (the measurement) + * @param measured is the 2 dimensional location of point in image (the measurement) * @param model is the standard deviation - * @param j_pose is basically the frame number - * @param j_landmark is the index of the landmark + * @param poseKey is the index of the camera + * @param pointKey is the index of the landmark * @param K shared pointer to the constant calibration */ GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model, - const Key poseKey, Key pointKey, const shared_ptrK& K) : + Key poseKey, Key pointKey, const boost::shared_ptr& K) : Base(model, poseKey, pointKey), measured_(measured), K_(K) { } /** Virtual destructor */ virtual ~GenericProjectionFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** * print * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "ProjectionFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - Base::print(s, keyFormatter); - measured_.print(s + ".z"); + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "GenericProjectionFactor, z = "; + measured_.print(); + Base::print("", keyFormatter); } /// equals @@ -89,16 +96,16 @@ namespace gtsam { Vector evaluateError(const Pose3& pose, const Point3& point, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { try { - SimpleCamera camera(*K_, pose); + PinholeCamera camera(pose, *K_); Point2 reprojectionError(camera.project(point, H1, H2) - measured_); return reprojectionError.vector(); } catch( CheiralityException& e) { if (H1) *H1 = zeros(2,6); if (H2) *H2 = zeros(2,3); - cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) << - " moved behind camera " << DefaultKeyFormatter(this->key1()) << endl; - return ones(2) * 2.0 * K_->fx(); + std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) << + " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl; } + return ones(2) * 2.0 * K_->fx(); } /** return the measurement */ @@ -107,7 +114,7 @@ namespace gtsam { } /** return the calibration object */ - inline const Cal3_S2::shared_ptr calibration() const { + inline const boost::shared_ptr calibration() const { return K_; } diff --git a/gtsam/slam/RangeFactor.h b/gtsam/slam/RangeFactor.h index 489f751db..fa4ddb7f2 100644 --- a/gtsam/slam/RangeFactor.h +++ b/gtsam/slam/RangeFactor.h @@ -24,6 +24,7 @@ namespace gtsam { /** * Binary factor for a range measurement + * @addtogroup SLAM */ template class RangeFactor: public NoiseModelFactor2 { @@ -51,6 +52,11 @@ namespace gtsam { virtual ~RangeFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** h(x)-z */ Vector evaluateError(const Pose& pose, const Point& point, boost::optional H1, boost::optional H2) const { double hx = pose.range(point, H1, H2); @@ -70,7 +76,8 @@ namespace gtsam { /** print contents */ void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - Base::print(s + std::string(" range: ") + boost::lexical_cast(measured_), keyFormatter); + std::cout << s << "RangeFactor, range = " << measured_ << std::endl; + Base::print("", keyFormatter); } private: diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index ae2deeae3..87cb95d25 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -18,10 +18,15 @@ #pragma once +#include #include namespace gtsam { +/** + * A Generic Stereo Factor + * @addtogroup SLAM + */ template class GenericStereoFactor: public NoiseModelFactor2 { private: @@ -34,6 +39,7 @@ public: // shorthand for base class type typedef NoiseModelFactor2 Base; ///< typedef for base class + typedef GenericStereoFactor This; ///< typedef for this class (with templates) typedef boost::shared_ptr shared_ptr; ///< typedef for shared pointer to this object typedef POSE CamPose; ///< typedef for Pose Lie Value type @@ -56,9 +62,15 @@ public: virtual ~GenericStereoFactor() {} ///< Virtual destructor + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** * print * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { Base::print(s, keyFormatter); @@ -68,7 +80,7 @@ public: /** * equals */ - virtual bool equals(const NonlinearFactor& f, double tol) const { + virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { const GenericStereoFactor* p = dynamic_cast (&f); return p && Base::equals(f) && measured_.equals(p->measured_, tol); } @@ -96,6 +108,8 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index f45f560a7..4550b418d 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -16,72 +16,74 @@ * @brief utility functions for loading datasets */ - #include #include #include +#include + +#include +#include #include +#include +#include using namespace std; -using namespace gtsam; +namespace fs = boost::filesystem; #define LINESIZE 81920 -typedef boost::shared_ptr sharedPose2Graph; -typedef pose2SLAM::Odometry Pose2Factor; ///< Typedef for Constraint class for backwards compatibility - namespace gtsam { +#ifndef MATLAB_MEX_FILE /* ************************************************************************* */ -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))); +string findExampleDataFile(const string& name) { + // Search source tree and installed location + vector rootsToSearch; + rootsToSearch.push_back(SOURCE_TREE_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt + rootsToSearch.push_back(INSTALLED_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt - if (path.empty()) path = string(getenv("HOME")) + "/data"; - if (set.empty()) set = string(getenv("DATASET")); + // Search for filename as given, and with .graph and .txt extensions + vector namesToSearch; + namesToSearch.push_back(name); + namesToSearch.push_back(name + ".graph"); + namesToSearch.push_back(name + ".txt"); - 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); + // Find first name that exists + BOOST_FOREACH(const fs::path& root, rootsToSearch) { + BOOST_FOREACH(const fs::path& name, namesToSearch) { + if(fs::is_regular_file(root / name)) + return (root / name).string(); + } + } - return make_pair("unknown", null_model); + // If we did not return already, then we did not find the file + throw std::invalid_argument( + "gtsam::findExampleDataFile could not find a matching file in\n" + SOURCE_TREE_DATASET_DIR " or\n" + INSTALLED_DATASET_DIR " named\n" + + name + ", " + name + ".graph, or " + name + ".txt"); } +#endif /* ************************************************************************* */ - -pair load2D( - pair > dataset, +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) { +/* ************************************************************************* */ +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); - } + if (!is) + throw std::invalid_argument("load2D: can not find the file!"); - Values::shared_ptr poses(new Values); - sharedPose2Graph graph(new pose2SLAM::Graph); + Values::shared_ptr initial(new Values); + NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); string tag; @@ -94,83 +96,120 @@ pair load2D(const string& filename, 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)); + if (maxID && id >= maxID) + continue; + initial->insert(id, Pose2(x, y, yaw)); } is.ignore(LINESIZE, '\n'); } is.clear(); /* clears the end-of-file and error flags */ is.seekg(0, ios::beg); + // Create a sampler with random number generator + Sampler sampler(42u); + // load the factors while (is) { is >> tag; - if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "ODOMETRY")) { - int id1, id2; - double x, y, yaw; + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "ODOMETRY")) { + int id1, id2; + double x, y, yaw; - 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); + 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); - // optional filter - if (maxID && (id1 >= maxID || id2 >= maxID)) continue; + // optional filter + if (maxID && (id1 >= maxID || id2 >= maxID)) + continue; - Pose2 l1Xl2(x, y, yaw); + 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); - } + // 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 (addNoise) - l1Xl2 = l1Xl2.retract((*model)->sample()); + if (addNoise) + l1Xl2 = l1Xl2.retract(sampler.sampleNewModel(*model)); - // 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); + // Insert vertices if pure odometry file + if (!initial->exists(id1)) + initial->insert(id1, Pose2()); + if (!initial->exists(id2)) + initial->insert(id2, initial->at(id1) * l1Xl2); - pose2SLAM::Graph::sharedFactor factor(new Pose2Factor(pose2SLAM::PoseKey(id1), pose2SLAM::PoseKey(id2), l1Xl2, *model)); - graph->push_back(factor); - } + NonlinearFactor::shared_ptr factor( + new BetweenFactor(id1, id2, l1Xl2, *model)); + graph->push_back(factor); + } + if (tag == "BR") { + int id1, id2; + double bearing, range, bearing_std, range_std; + + is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std; + + // optional filter + if (maxID && (id1 >= maxID || id2 >= maxID)) + continue; + + noiseModel::Diagonal::shared_ptr measurementNoise = + noiseModel::Diagonal::Sigmas(Vector_(2, bearing_std, range_std)); + graph->add(BearingRangeFactor(id1, id2, bearing, range, measurementNoise)); + + // Insert poses or points if they do not exist yet + if (!initial->exists(id1)) + initial->insert(id1, Pose2()); + if (!initial->exists(id2)) { + Pose2 pose = initial->at(id1); + Point2 local(cos(bearing)*range,sin(bearing)*range); + Point2 global = pose.transform_from(local); + initial->insert(id2, global); + } + } is.ignore(LINESIZE, '\n'); } - cout << "load2D read a graph file with " << poses->size() << " vertices and " - << graph->nrFactors() << " factors" << endl; + cout << "load2D read a graph file with " << initial->size() + << " vertices and " << graph->nrFactors() << " factors" << endl; - return make_pair(graph, poses); + return make_pair(graph, initial); } /* ************************************************************************* */ -void save2D(const pose2SLAM::Graph& graph, const Values& config, const SharedDiagonal model, - const string& filename) { +void save2D(const NonlinearFactorGraph& graph, const Values& config, + const noiseModel::Diagonal::shared_ptr model, const string& filename) { 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; + 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; + 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 << "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(); @@ -179,7 +218,8 @@ void save2D(const pose2SLAM::Graph& graph, const Values& config, const SharedDia /* ************************************************************************* */ bool load3D(const string& filename) { ifstream is(filename.c_str()); - if (!is) return false; + if (!is) + return false; while (is) { char buf[LINESIZE]; @@ -216,4 +256,6 @@ bool load3D(const string& filename) { } return true; } -} +/* ************************************************************************* */ + +} // \namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 5e06e583d..8da3d6ef9 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -18,43 +18,60 @@ #pragma once +#include +#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 > - dataset(const std::string& dataset = "", const std::string& path = ""); +namespace gtsam { -/** - * 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); +#ifndef MATLAB_MEX_FILE + /** + * Find the full path to an example dataset distributed with gtsam. The name + * may be specified with or without a file extension - if no extension is + * give, this function first looks for the .graph extension, then .txt. We + * first check the gtsam source tree for the file, followed by the installed + * example dataset location. Both the source tree and installed locations + * are obtained from CMake during compilation. + * @return The full path and filename to the requested dataset. + * @throw std::invalid_argument if no matching file could be found using the + * search process described above. + */ + std::string findExampleDataFile(const std::string& name); +#endif -/** 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 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); -/** - * Load TORO 3D Graph - */ -bool load3D(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< + noiseModel::Diagonal::shared_ptr>(), int maxID = 0, bool addNoise = false, + bool smart = true); + + /** save 2d graph */ + void save2D(const NonlinearFactorGraph& graph, const Values& config, + const noiseModel::Diagonal::shared_ptr 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 deleted file mode 100644 index b5f7b18ef..000000000 --- a/gtsam/slam/planarSLAM.cpp +++ /dev/null @@ -1,68 +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 planarSLAM.cpp - * @brief: bearing/range measurements in 2D plane - * @author Frank Dellaert - **/ - -#include -#include - -// Use planarSLAM namespace for specific SLAM instance -namespace planarSLAM { - - /* ************************************************************************* */ - Graph::Graph(const NonlinearFactorGraph& graph) : - NonlinearFactorGraph(graph) {} - - /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose2& p, const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(i), p, model)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addPoseConstraint(Index i, const Pose2& p) { - sharedFactor factor(new Constraint(PoseKey(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)); - 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)); - 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)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addBearingRange(Index i, Index j, const Rot2& z1, - double z2, const SharedNoiseModel& model) { - sharedFactor factor(new BearingRange(PoseKey(i), PointKey(j), z1, z2, model)); - push_back(factor); - } - - /* ************************************************************************* */ - -} // planarSLAM - diff --git a/gtsam/slam/planarSLAM.h b/gtsam/slam/planarSLAM.h deleted file mode 100644 index 07e6896e5..000000000 --- a/gtsam/slam/planarSLAM.h +++ /dev/null @@ -1,118 +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 planarSLAM.h - * @brief: bearing/range measurements in 2D plane - * @author Frank Dellaert - */ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// 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 - typedef NonlinearEquality Constraint; - /// A prior factor to bias the value of a PoseKey - typedef PriorFactor Prior; - /// A factor between two PoseKeys set with a Pose2 - typedef BetweenFactor Odometry; - /// A factor between a PoseKey and a PointKey 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) - typedef RangeFactor Range; - /// A factor between a PoseKey and a PointKey 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 - */ - struct Values: public gtsam::Values { - - /// Default constructor - Values() {} - - /// Copy constructor - Values(const gtsam::Values& values) : - gtsam::Values(values) { - } - - /// get a pose - Pose2 pose(Index key) const { return at(PoseKey(key)); } - - /// get a point - Point2 point(Index key) const { return at(PointKey(key)); } - - /// insert a pose - void insertPose(Index key, const Pose2& pose) { insert(PoseKey(key), pose); } - - /// insert a point - void insertPoint(Index key, const Point2& point) { insert(PointKey(key), point); } - }; - - /// Creates a NonlinearFactorGraph with the Values type - struct Graph: public NonlinearFactorGraph { - - /// Default constructor for a NonlinearFactorGraph - Graph(){} - - /// 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); - - /// Creates a hard constraint to enforce Pose2 p for PoseKey poseKey's value - void addPoseConstraint(Index poseKey, 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 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 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 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); - - /// Optimize - Values optimize(const Values& initialEstimate) { - return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); - } - }; - -} // planarSLAM - - diff --git a/gtsam/slam/pose2SLAM.cpp b/gtsam/slam/pose2SLAM.cpp deleted file mode 100644 index e8cbcd7fe..000000000 --- a/gtsam/slam/pose2SLAM.cpp +++ /dev/null @@ -1,55 +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 pose2SLAM.cpp - * @brief: Odometry measurements in 2D plane - * @author Frank Dellaert - **/ - -#include - -// Use pose2SLAM namespace for specific SLAM instance - -namespace pose2SLAM { - - /* ************************************************************************* */ - 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 + theta)); - return x; - } - - /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose2& p, - const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(i), p, model)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addPoseConstraint(Index i, const Pose2& p) { - sharedFactor factor(new HardConstraint(PoseKey(i), p)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addOdometry(Index i, Index j, const Pose2& z, - const SharedNoiseModel& model) { - sharedFactor factor(new Odometry(PoseKey(i), PoseKey(j), z, model)); - push_back(factor); - } - - /* ************************************************************************* */ - -} // pose2SLAM diff --git a/gtsam/slam/pose2SLAM.h b/gtsam/slam/pose2SLAM.h deleted file mode 100644 index 6dc682f9b..000000000 --- a/gtsam/slam/pose2SLAM.h +++ /dev/null @@ -1,105 +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 pose2SLAM.h - * @brief: 2D Pose SLAM - * @author Frank Dellaert - **/ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -// Use pose2SLAM namespace for specific SLAM instance -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 - struct Values: public gtsam::Values { - - /// Default constructor - Values() {} - - /// Copy constructor - Values(const gtsam::Values& values) : - 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)); } - - /// insert a pose - void insertPose(Index key, const Pose2& pose) { insert(PoseKey(key), 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); - - /** - * List of typedefs for factors - */ - - /// A hard constraint to enforce a specific value for a pose - typedef NonlinearEquality HardConstraint; - /// A prior factor on a pose with Pose2 data type. - typedef PriorFactor Prior; - /// A factor to add an odometry measurement between two poses. - typedef BetweenFactor Odometry; - - /// Graph - struct Graph: public NonlinearFactorGraph { - - /// 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); - - /// Creates a hard constraint for key i with the given Pose2 p. - void addPoseConstraint(Index 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); - - /// Optimize - Values optimize(const Values& initialEstimate) const { - return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); - } - }; - -} // pose2SLAM - - - diff --git a/gtsam/slam/pose3SLAM.cpp b/gtsam/slam/pose3SLAM.cpp deleted file mode 100644 index 0ab962f1e..000000000 --- a/gtsam/slam/pose3SLAM.cpp +++ /dev/null @@ -1,64 +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 pose3SLAM.cpp - * @brief: bearing/range measurements in 2D plane - * @author Frank Dellaert - **/ - -#include -#include - -// Use pose3SLAM namespace for specific SLAM instance -namespace pose3SLAM { - - /* ************************************************************************* */ - 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 - // First pose will be at (R,0,0) - // ^y ^ X - // | | - // z-->xZ--> Y (z pointing towards viewer, Z pointing away from viewer) - // Vehicle at p0 is looking towards y axis (X-axis points towards world y) - Rot3 gR0(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); - for (size_t i = 0; i < n; i++, theta += dtheta) { - 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); - } - return x; - } - - /* ************************************************************************* */ - void Graph::addPrior(Index i, const Pose3& p, const SharedNoiseModel& model) { - sharedFactor factor(new Prior(PoseKey(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)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addHardConstraint(Index i, const Pose3& p) { - sharedFactor factor(new HardConstraint(PoseKey(i), p)); - push_back(factor); - } - - /* ************************************************************************* */ - -} // pose3SLAM diff --git a/gtsam/slam/pose3SLAM.h b/gtsam/slam/pose3SLAM.h deleted file mode 100644 index 6b4efbe6c..000000000 --- a/gtsam/slam/pose3SLAM.h +++ /dev/null @@ -1,79 +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 pose3SLAM.h - * @brief: 3D Pose SLAM - * @author Frank Dellaert - **/ - -#pragma once - -#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 circle(size_t n, double R); - - /// A prior factor on Key with Pose3 data type. - typedef PriorFactor Prior; - /// A factor to put constraints between two factors. - typedef BetweenFactor Constraint; - /// A hard constraint would enforce that the given key would have the input value in the results. - typedef NonlinearEquality HardConstraint; - - /// Graph - struct Graph: public NonlinearFactorGraph { - - /// Adds a factor between keys of the same type - void addPrior(Index 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); - - /// Creates a hard constraint for key i with the given Pose3 p. - void addHardConstraint(Index i, const Pose3& p); - - /// Optimize - Values optimize(const Values& initialEstimate) { - return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); - } - - }; - -} // pose3SLAM - -/** - * Backwards compatibility - */ -namespace gtsam { - typedef pose3SLAM::Prior Pose3Prior; ///< Typedef for Prior class for backwards compatibility - typedef pose3SLAM::Constraint Pose3Factor; ///< Typedef for Constraint class for backwards compatibility - typedef pose3SLAM::Graph Pose3Graph; ///< Typedef for Graph class for backwards compatibility -} diff --git a/gtsam/slam/tests/testAntiFactor.cpp b/gtsam/slam/tests/testAntiFactor.cpp index 183b0c600..0dd576aed 100644 --- a/gtsam/slam/tests/testAntiFactor.cpp +++ b/gtsam/slam/tests/testAntiFactor.cpp @@ -17,18 +17,18 @@ #include -#include #include -#include +#include +#include #include +#include +#include #include #include using namespace std; using namespace gtsam; -using pose3SLAM::PoseKey; - /* ************************************************************************* */ TEST( AntiFactor, NegativeHessian) { @@ -42,17 +42,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); @@ -97,14 +97,14 @@ TEST( AntiFactor, EquivalentBayesNet) Pose3 z(Rot3(), Point3(1, 1, 1)); SharedNoiseModel sigma(noiseModel::Unit::Create(Pose3::Dim())); - boost::shared_ptr graph(new pose3SLAM::Graph()); - graph->addPrior(1, pose1, sigma); - graph->addConstraint(1, 2, pose1.between(pose2), sigma); + NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph()); + graph->add(PriorFactor(1, pose1, sigma)); + graph->add(BetweenFactor(1, 2, pose1.between(pose2), sigma)); // 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::shared_ptr values(new Values()); + values->insert(1, pose1); + values->insert(2, pose2); // Define an elimination ordering Ordering::shared_ptr ordering = graph->orderingCOLAMD(*values); @@ -117,7 +117,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)); + BetweenFactor::shared_ptr f1(new BetweenFactor(1, 2, z, sigma)); graph->push_back(f1); // Add the corresponding AntiFactor between Pose1 and Pose2 diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp new file mode 100644 index 000000000..aae3fc5da --- /dev/null +++ b/gtsam/slam/tests/testDataset.cpp @@ -0,0 +1,38 @@ +/* ---------------------------------------------------------------------------- + + * 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 testDataset.cpp + * @brief Unit test for dataset.cpp + * @author Richard Roberts + */ + +#include + +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +TEST(dataSet, findExampleDataFile) { + const string expected_end = "examples/Data/example.graph"; + const string actual = findExampleDataFile("example"); + string actual_end = actual.substr(actual.size() - expected_end.size(), expected_end.size()); + boost::replace_all(actual_end, "\\", "/"); // Convert directory separators to forward-slash + EXPECT(assert_equal(expected_end, actual_end)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 5b8a217bc..58f06c8d4 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,22 +50,22 @@ 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); } }; -double getGaussian() +static double getGaussian() { double S,V1,V2; // Use Box-Muller method to create gauss noise from uniform noise @@ -75,7 +80,7 @@ double getGaussian() return sqrt(-2.0f * (double)log(S) / S) * V1; } -const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); +static const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); /* ************************************************************************* */ TEST( GeneralSFMFactor, equals ) @@ -97,46 +102,46 @@ 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))); } static const double baseline = 5.0 ; /* ************************************************************************* */ -vector genPoint3() { +static 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() { +static 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 genCameraVariableCalibration() { +static vector genCameraVariableCalibration() { const Cal3_S2 K(640,480,0.01,320,240); vector X ; X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); @@ -144,10 +149,10 @@ vector genCameraVariableCalibration() { return X ; } -shared_ptr getOrdering(const vector& X, const vector& L) { - 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)) ; +static boost::shared_ptr getOrdering(const vector& cameras, const vector& landmarks) { + boost::shared_ptr ordering(new Ordering); + 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 @@ shared_ptr getOrdering(const vector& X, const 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, noiseModel::Isotropic::Sigma(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, noiseModel::Isotropic::Sigma(1, 1.0))); + graph.add(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), noiseModel::Isotropic::Sigma(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(), noiseModel::Isotropic::Sigma(6, 1.0))); + graph.add(RangeFactor(X(0), X(1), 2.0, noiseModel::Isotropic::Sigma(1, 1.0))); + graph.add(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), noiseModel::Isotropic::Sigma(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 76cf7d180..21f5f2008 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,22 +51,22 @@ 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); } }; -double getGaussian() +static double getGaussian() { double S,V1,V2; // Use Box-Muller method to create gauss noise from uniform noise @@ -75,10 +81,10 @@ double getGaussian() return sqrt(-2.0f * (double)log(S) / S) * V1; } -const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); +static const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); /* ************************************************************************* */ -TEST( GeneralSFMFactor, equals ) +TEST( GeneralSFMFactor_Cal3Bundler, equals ) { // Create two identical factors and make sure they're equal Vector z = Vector_(2,323.,240.); @@ -94,18 +100,18 @@ TEST( GeneralSFMFactor, equals ) } /* ************************************************************************* */ -TEST( GeneralSFMFactor, error ) { +TEST( GeneralSFMFactor_Cal3Bundler, 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))); } @@ -113,193 +119,193 @@ TEST( GeneralSFMFactor, error ) { static const double baseline = 5.0 ; /* ************************************************************************* */ -vector genPoint3() { +static 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 ; +static vector genCameraDefaultCalibration() { + 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() { +static 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 ; } -shared_ptr getOrdering(const vector& X, const vector& L) { - 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)) ; +static boost::shared_ptr getOrdering(const std::vector& cameras, const std::vector& landmarks) { + boost::shared_ptr ordering(new Ordering); + 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 ) { +TEST( GeneralSFMFactor_Cal3Bundler, 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); } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_SingleMeasurementError ) { + 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); } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { +TEST( GeneralSFMFactor_Cal3Bundler, 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); } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { +TEST( GeneralSFMFactor_Cal3Bundler, 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,66 +314,66 @@ 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); } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_BA ) { - vector L = genPoint3(); - vector X = genCameraVariableCalibration(); +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_BA ) { + 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, noiseModel::Isotropic::Sigma(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 deleted file mode 100644 index b32bf9a9c..000000000 --- a/gtsam/slam/tests/testPlanarSLAM.cpp +++ /dev/null @@ -1,189 +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 testPlanarSLAM.cpp - * @author Frank Dellaert - **/ - -#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); -static Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3); - -SharedNoiseModel - sigma(noiseModel::Isotropic::Sigma(1,0.1)), - sigma2(noiseModel::Isotropic::Sigma(2,0.1)), - I3(noiseModel::Unit::Create(3)); - -/* ************************************************************************* */ -TEST( planarSLAM, PriorFactor_equals ) -{ - planarSLAM::Prior factor1(PoseKey(2), x1, I3), factor2(PoseKey(2), x2, I3); - EXPECT(assert_equal(factor1, factor1, 1e-5)); - EXPECT(assert_equal(factor2, factor2, 1e-5)); - EXPECT(assert_inequal(factor1, factor2, 1e-5)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, BearingFactor ) -{ - // Create factor - Rot2 z = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 - planarSLAM::Bearing factor(PoseKey(2), PointKey(3), z, sigma); - - // create config - planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); - - // Check error - Vector actual = factor.unwhitenedError(c); - EXPECT(assert_equal(Vector_(1,-0.1),actual)); -} - -/* ************************************************************************* */ -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); - EXPECT(assert_equal(factor1, factor1, 1e-5)); - EXPECT(assert_equal(factor2, factor2, 1e-5)); - EXPECT(assert_inequal(factor1, factor2, 1e-5)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, RangeFactor ) -{ - // Create factor - double z(sqrt(2) - 0.22); // h(x) - z = 0.22 - planarSLAM::Range factor(PoseKey(2), PointKey(3), z, sigma); - - // create config - planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); - - // Check error - Vector actual = factor.unwhitenedError(c); - EXPECT(assert_equal(Vector_(1,0.22),actual)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, RangeFactor_equals ) -{ - planarSLAM::Range factor1(PoseKey(2), PointKey(3), 1.2, sigma), factor2(PoseKey(2), PointKey(3), 7.2, sigma); - EXPECT(assert_equal(factor1, factor1, 1e-5)); - EXPECT(assert_equal(factor2, factor2, 1e-5)); - EXPECT(assert_inequal(factor1, factor2, 1e-5)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, BearingRangeFactor ) -{ - // Create factor - Rot2 r = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 - double b(sqrt(2) - 0.22); // h(x) - z = 0.22 - planarSLAM::BearingRange factor(PoseKey(2), PointKey(3), r, b, sigma2); - - // create config - planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PointKey(3), l3); - - // Check error - Vector actual = factor.unwhitenedError(c); - EXPECT(assert_equal(Vector_(2,-0.1, 0.22),actual)); -} - -/* ************************************************************************* */ -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); - EXPECT(assert_equal(factor1, factor1, 1e-5)); - EXPECT(assert_equal(factor2, factor2, 1e-5)); - EXPECT(assert_inequal(factor1, factor2, 1e-5)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, BearingRangeFactor_poses ) -{ - typedef BearingRangeFactor PoseBearingRange; - PoseBearingRange actual(PoseKey(2), PoseKey(3), Rot2::fromDegrees(60.0), 12.3, sigma2); -} - -/* ************************************************************************* */ -TEST( planarSLAM, PoseConstraint_equals ) -{ - planarSLAM::Constraint factor1(PoseKey(2), x2), factor2(PoseKey(2), x3); - EXPECT(assert_equal(factor1, factor1, 1e-5)); - EXPECT(assert_equal(factor2, factor2, 1e-5)); - EXPECT(assert_inequal(factor1, factor2, 1e-5)); -} - -/* ************************************************************************* */ -TEST( planarSLAM, constructor ) -{ - // create config - planarSLAM::Values c; - c.insert(PoseKey(2), x2); - c.insert(PoseKey(3), x3); - c.insert(PointKey(3), l3); - - // create graph - planarSLAM::Graph G; - - // Add pose constraint - G.addPoseConstraint(2, x2); // make it feasible :-) - - // Add odometry - G.addOdometry(2, 3, Pose2(0, 0, M_PI_4), I3); - - // Create bearing factor - Rot2 z1 = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1 - G.addBearing(2, 3, z1, sigma); - - // Create range factor - double z2(sqrt(2) - 0.22); // h(x) - z = 0.22 - G.addRange(2, 3, z2, sigma); - - Vector expected0 = Vector_(3, 0.0, 0.0, 0.0); - Vector expected1 = Vector_(3, 0.0, 0.0, 0.0); - Vector expected2 = Vector_(1, -0.1); - Vector expected3 = Vector_(1, 0.22); - // Get NoiseModelFactors - FactorGraph GNM = - *G.dynamicCastFactors >(); - EXPECT(assert_equal(expected0, GNM[0]->unwhitenedError(c))); - EXPECT(assert_equal(expected1, GNM[1]->unwhitenedError(c))); - EXPECT(assert_equal(expected2, GNM[2]->unwhitenedError(c))); - EXPECT(assert_equal(expected3, GNM[3]->unwhitenedError(c))); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testPose2SLAM.cpp b/gtsam/slam/tests/testPose2SLAM.cpp deleted file mode 100644 index 22c02ab52..000000000 --- a/gtsam/slam/tests/testPose2SLAM.cpp +++ /dev/null @@ -1,561 +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 testPose2SLAM.cpp - * @author Frank Dellaert, Viorela Ila - **/ - -#include -#include -#include -#include -using namespace gtsam; - -#include - -#include -#include -using namespace boost; -using namespace boost::assign; - -#include -using namespace std; - -typedef pose2SLAM::Odometry Pose2Factor; -using pose2SLAM::PoseKey; - -// common measurement covariance -static double sx=0.5, sy=0.5,st=0.1; -static noiseModel::Gaussian::shared_ptr covariance( - noiseModel::Gaussian::Covariance(Matrix_(3, 3, - sx*sx, 0.0, 0.0, - 0.0, sy*sy, 0.0, - 0.0, 0.0, st*st - ))); -//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 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); - return constraint.evaluateError(pose1, pose2); -} - -TEST( 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); - Matrix H1, H2; - Vector actual = constraint.evaluateError(pose1, pose2, H1, H2); - - Matrix numericalH1 = numericalDerivative21(&f1 , pose1, pose2); - EXPECT(assert_equal(numericalH1,H1,5e-3)); - - Matrix numericalH2 = numericalDerivative22(&f1 , pose1, pose2); - EXPECT(assert_equal(numericalH2,H2)); -} - -/* ************************************************************************* */ -// Test constraint, large displacement -Vector f2(const Pose2& pose1, const Pose2& pose2) { - Pose2 z(2,2,M_PI_2); - Pose2Factor constraint(PoseKey(1), PoseKey(2), z, covariance); - return constraint.evaluateError(pose1, pose2); -} - -TEST( Pose2SLAM, constraint2 ) -{ - // create a factor between unknown poses p1 and p2 - Pose2 pose1, pose2(2,2,M_PI_2); - Pose2Factor constraint(PoseKey(1), PoseKey(2), pose2, covariance); - Matrix H1, H2; - Vector actual = constraint.evaluateError(pose1, pose2, H1, H2); - - Matrix numericalH1 = numericalDerivative21(&f2 , pose1, pose2); - EXPECT(assert_equal(numericalH1,H1,5e-3)); - - Matrix numericalH2 = numericalDerivative22(&f2 , pose1, pose2); - EXPECT(assert_equal(numericalH2,H2)); -} - -/* ************************************************************************* */ -TEST( Pose2SLAM, constructor ) -{ - // create a factor between unknown poses p1 and p2 - Pose2 measured(2,2,M_PI_2); - pose2SLAM::Graph graph; - graph.addOdometry(1,2,measured, covariance); - // get the size of the graph - size_t actual = graph.size(); - // verify - size_t expected = 1; - CHECK(actual == expected); -} - -/* ************************************************************************* */ -TEST( Pose2SLAM, linearization ) -{ - // create a factor between unknown poses p1 and p2 - Pose2 measured(2,2,M_PI_2); - Pose2Factor constraint(PoseKey(1), PoseKey(2), measured, covariance); - pose2SLAM::Graph graph; - graph.addOdometry(1,2,measured, covariance); - - // Choose a linearization point - 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); - // Linearize - Ordering ordering(*config.orderingArbitrary()); - boost::shared_ptr > lfg_linearized = graph.linearize(config, ordering); - //lfg_linearized->print("lfg_actual"); - - // the expected linear factor - FactorGraph lfg_expected; - Matrix A1 = Matrix_(3,3, - 0.0,-2.0, -4.2, - 2.0, 0.0, -4.2, - 0.0, 0.0,-10.0); - - Matrix A2 = Matrix_(3,3, - 2.0, 0.0, 0.0, - 0.0, 2.0, 0.0, - 0.0, 0.0, 10.0); - - 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))); - - CHECK(assert_equal(lfg_expected, *lfg_linearized)); -} - -/* ************************************************************************* */ -TEST(Pose2Graph, 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), covariance); - - // Create initial config - Values initial; - initial.insert(pose2SLAM::PoseKey(0), Pose2(0,0,0)); - initial.insert(pose2SLAM::PoseKey(1), Pose2(0,0,0)); - - // Choose an ordering and optimize - Ordering ordering; - ordering += kx0, kx1; - - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-15; - params.ordering = ordering; - Values actual = LevenbergMarquardtOptimizer(fg, initial, params).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)); - CHECK(assert_equal(expected, actual)); -} - -/* ************************************************************************* */ -// test optimization with 3 poses -TEST(Pose2Graph, optimizeThreePoses) { - - // Create a hexagon of poses - pose2SLAM::Values hexagon = pose2SLAM::circle(3,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(1, 2, delta, covariance); - fg.addOdometry(2, 0, delta, covariance); - - // Create initial config - pose2SLAM::Values initial; - initial.insertPose(0, p0); - initial.insertPose(1, hexagon.pose(1).retract(Vector_(3,-0.1, 0.1,-0.1))); - initial.insertPose(2, hexagon.pose(2).retract(Vector_(3, 0.1,-0.1, 0.1))); - - // Choose an ordering - Ordering ordering; - ordering += kx0,kx1,kx2; - - // optimize - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-15; - params.ordering = ordering; - Values actual = LevenbergMarquardtOptimizer(fg, initial, params).optimize(); - - // Check with ground truth - CHECK(assert_equal((const Values&)hexagon, actual)); -} - -/* ************************************************************************* */ -// test optimization with 6 poses arranged in a hexagon and a loop closure -TEST_UNSAFE(Pose2SLAM, optimizeCircle) { - - // Create a hexagon of poses - pose2SLAM::Values hexagon = pose2SLAM::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(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 - pose2SLAM::Values initial; - initial.insertPose(0, p0); - initial.insertPose(1, hexagon.pose(1).retract(Vector_(3,-0.1, 0.1,-0.1))); - initial.insertPose(2, hexagon.pose(2).retract(Vector_(3, 0.1,-0.1, 0.1))); - initial.insertPose(3, hexagon.pose(3).retract(Vector_(3,-0.1, 0.1,-0.1))); - initial.insertPose(4, hexagon.pose(4).retract(Vector_(3, 0.1,-0.1, 0.1))); - initial.insertPose(5, hexagon.pose(5).retract(Vector_(3,-0.1, 0.1,-0.1))); - - // Choose an ordering - Ordering ordering; - ordering += kx0,kx1,kx2,kx3,kx4,kx5; - - // optimize - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-15; - params.ordering = ordering; - Values actual = LevenbergMarquardtOptimizer(fg, initial, params).optimize(); - - // Check with ground truth - CHECK(assert_equal((const Values&)hexagon, actual)); - - // Check loop closure - CHECK(assert_equal(delta, actual.at(PoseKey(5)).between(actual.at(PoseKey(0))))); - -// Pose2SLAMOptimizer myOptimizer("3"); - -// Matrix A1 = myOptimizer.a1(); -// LONGS_EQUAL(3, A1.rows()); -// LONGS_EQUAL(17, A1.cols()); // 7 + 7 + 3 -// -// Matrix A2 = myOptimizer.a2(); -// LONGS_EQUAL(3, A1.rows()); -// LONGS_EQUAL(7, A2.cols()); // 7 -// -// Vector b1 = myOptimizer.b1(); -// LONGS_EQUAL(9, b1.size()); // 3 + 3 + 3 -// -// Vector b2 = myOptimizer.b2(); -// LONGS_EQUAL(3, b2.size()); // 3 -// -// // Here, call matlab to -// // A=[A1;A2], b=[b1;b2] -// // R=qr(A1) -// // call pcg on A,b, with preconditioner R -> get x -// -// Vector x = myOptimizer.optimize(); -// LONGS_EQUAL(9, x.size()); // 3 + 3 + 3 -// -// myOptimizer.update(x); -// -// Values expected; -// expected.insert(0, Pose2(0.,0.,0.)); -// expected.insert(1, Pose2(1.,0.,0.)); -// expected.insert(2, Pose2(2.,0.,0.)); -// -// // Check with ground truth -// CHECK(assert_equal(expected, *myOptimizer.theta())); -} - -/* ************************************************************************* */ -TEST(Pose2Graph, optimize2) { -// Pose2SLAMOptimizer myOptimizer("100"); -// Matrix A1 = myOptimizer.a1(); -// Matrix A2 = myOptimizer.a2(); -// cout << "A1: " << A1.rows() << " " << A1.cols() << endl; -// cout << "A2: " << A2.rows() << " " << A2.cols() << endl; -// -// //cout << "error: " << myOptimizer.error() << endl; -// for(int i = 0; i<10; i++) { -// myOptimizer.linearize(); -// Vector x = myOptimizer.optimize(); -// myOptimizer.update(x); -// } -// //cout << "error: " << myOptimizer.error() << endl; -// CHECK(myOptimizer.error() < 1.); -} - -///* ************************************************************************* */ -// SL-NEEDED? TEST(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); -// G.addConstraint(2, 3, Pose2(0.,0.,0.), I3); -// -// PredecessorMap tree = -// G.findMinimumSpanningTree(); -// CHECK(tree[1] == 1); -// CHECK(tree[2] == 1); -// CHECK(tree[3] == 1); -//} -// -///* ************************************************************************* */ -// SL-NEEDED? TEST(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); -// G.addConstraint(2, 3, Pose2(0.,0.,0.), I3); -// -// PredecessorMap tree; -// tree.insert(1,2); -// tree.insert(2,2); -// tree.insert(3,2); -// -// G.split(tree, T, C); -// LONGS_EQUAL(2, T.size()); -// LONGS_EQUAL(1, C.size()); -//} - -using namespace pose2SLAM; - -/* ************************************************************************* */ -TEST(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)); - expected.insert(pose2SLAM::PoseKey(1), Pose2( 0, 1, - M_PI )); - expected.insert(pose2SLAM::PoseKey(2), Pose2(-1, 0, - M_PI_2)); - expected.insert(pose2SLAM::PoseKey(3), Pose2( 0, -1, 0 )); - - pose2SLAM::Values actual = pose2SLAM::circle(4,1.0); - CHECK(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -TEST(Pose2SLAM, expmap ) -{ - // expected is circle shifted to right - pose2SLAM::Values expected; - expected.insert(pose2SLAM::PoseKey(0), Pose2( 1.1, 0, M_PI_2)); - expected.insert(pose2SLAM::PoseKey(1), Pose2( 0.1, 1, - M_PI )); - expected.insert(pose2SLAM::PoseKey(2), Pose2(-0.9, 0, - M_PI_2)); - expected.insert(pose2SLAM::PoseKey(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)); - 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); - pose2SLAM::Values actual = circle.retract(delta, ordering); - CHECK(assert_equal(expected,actual)); -} - -// Common measurement covariance -static SharedNoiseModel sigmas = sharedSigmas(Vector_(3,sx,sy,st)); - -/* ************************************************************************* */ -// Very simple test establishing Ax-b \approx z-h(x) -TEST( Pose2Prior, error ) -{ - // Choose a linearization point - Pose2 p1(1, 0, 0); // robot at (1,0) - pose2SLAM::Values x0; - x0.insert(PoseKey(1), p1); - - // Create factor - pose2SLAM::Prior factor(PoseKey(1), p1, sigmas); - - // Actual linearization - Ordering ordering(*x0.orderingArbitrary()); - boost::shared_ptr linear = - boost::dynamic_pointer_cast(factor.linearize(x0, ordering)); - - // Check error at x0, i.e. delta = zero ! - VectorValues delta(VectorValues::Zero(x0.dims(ordering))); - delta[ordering[kx1]] = 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); - 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 ! - CHECK(assert_equal(error_at_plus,factor.whitenedError(x1))); - CHECK(assert_equal(error_at_plus,linear->error_vector(plus))); -} - -/* ************************************************************************* */ -// common Pose2Prior for tests below -static gtsam::Pose2 priorVal(2,2,M_PI_2); -static pose2SLAM::Prior priorFactor(PoseKey(1), priorVal, sigmas); - -/* ************************************************************************* */ -// The error |A*dx-b| approximates (h(x0+dx)-z) = -error_vector -// Hence i.e., b = approximates z-h(x0) = error_vector(x0) -LieVector hprior(const Pose2& p1) { - return LieVector(sigmas->whiten(priorFactor.evaluateError(p1))); -} - -/* ************************************************************************* */ -TEST( Pose2Prior, linearize ) -{ - // Choose a linearization point at ground truth - pose2SLAM::Values x0; - x0.insertPose(1, priorVal); - - // Actual linearization - Ordering ordering(*x0.orderingArbitrary()); - boost::shared_ptr actual = - boost::dynamic_pointer_cast(priorFactor.linearize(x0, ordering)); - - // Test with numerical derivative - Matrix numericalH = numericalDerivative11(hprior, priorVal); - CHECK(assert_equal(numericalH,actual->getA(actual->find(ordering[kx1])))); -} - -/* ************************************************************************* */ -// Very simple test establishing Ax-b \approx z-h(x) -TEST( Pose2Factor, error ) -{ - // Choose a linearization point - Pose2 p1; // robot at origin - Pose2 p2(1, 0, 0); // robot at (1,0) - pose2SLAM::Values x0; - x0.insertPose(1, p1); - x0.insertPose(2, p2); - - // Create factor - Pose2 z = p1.between(p2); - Pose2Factor factor(PoseKey(1), PoseKey(2), z, covariance); - - // Actual linearization - Ordering ordering(*x0.orderingArbitrary()); - boost::shared_ptr linear = - boost::dynamic_pointer_cast(factor.linearize(x0, ordering)); - - // Check error at x0, i.e. delta = zero ! - VectorValues delta(x0.dims(ordering)); - delta[ordering[kx1]] = zero(3); - delta[ordering[kx2]] = 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); - 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))); - CHECK(assert_equal(error_at_plus,linear->error_vector(plus))); -} - -/* ************************************************************************* */ -// common Pose2Factor for tests below -static Pose2 measured(2,2,M_PI_2); -static Pose2Factor factor(PoseKey(1),PoseKey(2),measured, covariance); - -/* ************************************************************************* */ -TEST( Pose2Factor, rhs ) -{ - // Choose a linearization point - 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); - - // Actual linearization - Ordering ordering(*x0.orderingArbitrary()); - boost::shared_ptr linear = - boost::dynamic_pointer_cast(factor.linearize(x0, ordering)); - - // Check RHS - Pose2 hx0 = p1.between(p2); - 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())); -} - -/* ************************************************************************* */ -// The error |A*dx-b| approximates (h(x0+dx)-z) = -error_vector -// Hence i.e., b = approximates z-h(x0) = error_vector(x0) -LieVector h(const Pose2& p1,const Pose2& p2) { - return LieVector(covariance->whiten(factor.evaluateError(p1,p2))); -} - -/* ************************************************************************* */ -TEST( Pose2Factor, linearize ) -{ - // Choose a linearization point at ground truth - 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); - - // expected linearization - Matrix expectedH1 = covariance->Whiten(Matrix_(3,3, - 0.0,-1.0,-2.0, - 1.0, 0.0,-2.0, - 0.0, 0.0,-1.0 - )); - Matrix expectedH2 = covariance->Whiten(Matrix_(3,3, - 1.0, 0.0, 0.0, - 0.0, 1.0, 0.0, - 0.0, 0.0, 1.0 - )); - Vector expected_b = Vector_(3, 0.0, 0.0, 0.0); - - // expected linear factor - Ordering ordering(*x0.orderingArbitrary()); - SharedDiagonal probModel1 = noiseModel::Unit::Create(3); - JacobianFactor expected(ordering[kx1], expectedH1, ordering[kx2], expectedH2, expected_b, probModel1); - - // Actual linearization - boost::shared_ptr actual = - boost::dynamic_pointer_cast(factor.linearize(x0, ordering)); - CHECK(assert_equal(expected,*actual)); - - // Numerical do not work out because BetweenFactor is approximate ? - Matrix numericalH1 = numericalDerivative21(h, p1, p2); - CHECK(assert_equal(expectedH1,numericalH1)); - Matrix numericalH2 = numericalDerivative22(h, p1, p2); - CHECK(assert_equal(expectedH2,numericalH2)); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testPose3SLAM.cpp b/gtsam/slam/tests/testPose3SLAM.cpp deleted file mode 100644 index d4ab3afdb..000000000 --- a/gtsam/slam/tests/testPose3SLAM.cpp +++ /dev/null @@ -1,219 +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 testPose3Graph.cpp - * @author Frank Dellaert, Viorela Ila - **/ - -#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 - -using namespace std; -using namespace gtsam; -using namespace pose3SLAM; - -// common measurement covariance -static Matrix covariance = eye(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)); - - // create a Pose graph with one equality constraint and one measurement - pose3SLAM::Graph fg; - fg.addHardConstraint(0, gT0); - Pose3 _0T1 = gT0.between(gT1); // inv(gT0)*gT1 - double theta = M_PI/3.0; - CHECK(assert_equal(Pose3(Rot3::yaw(-theta),Point3(radius*sin(theta),-radius*cos(theta),0)),_0T1)); - fg.addConstraint(0,1, _0T1, covariance); - fg.addConstraint(1,2, _0T1, covariance); - fg.addConstraint(2,3, _0T1, covariance); - fg.addConstraint(3,4, _0T1, covariance); - fg.addConstraint(4,5, _0T1, covariance); - fg.addConstraint(5,0, _0T1, covariance); - - // 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))); - - // Choose an ordering and optimize - Ordering ordering; - ordering += kx0,kx1,kx2,kx3,kx4,kx5; - - Values actual = LevenbergMarquardtOptimizer(fg, initial, ordering).optimize(); - - // Check with ground truth - 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)); -} - -/* ************************************************************************* */ -TEST(Pose3Graph, partial_prior_height) { - typedef PartialPriorFactor Partial; - - // 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); - 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); - EXPECT(assert_equal(expA, actA)); - - pose3SLAM::Graph graph; - graph.add(height); - - Values values; - values.insert(key, 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_DOUBLES_EQUAL(0.0, graph.error(actual), tol); -} - -/* ************************************************************************* */ -TEST( Pose3Factor, error ) -{ - // Create example - Pose3 t1; // origin - Pose3 t2(Rot3::rodriguez(0.1,0.2,0.3),Point3(0,1,0)); - Pose3 z(Rot3::rodriguez(0.2,0.2,0.3),Point3(0,1.1,0));; - - // Create factor - SharedNoiseModel I6(noiseModel::Unit::Create(6)); - pose3SLAM::Constraint factor(PoseKey(1), PoseKey(2), z, I6); - - // Create config - Values x; - x.insert(PoseKey(1),t1); - x.insert(PoseKey(2),t2); - - // Get error h(x)-z -> localCoordinates(z,h(x)) = localCoordinates(z,between(t1,t2)) - Vector actual = factor.unwhitenedError(x); - Vector expected = z.localCoordinates(t1.between(t2)); - CHECK(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -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); - Matrix actA; - EXPECT(assert_equal(Vector_(2,-2.0,-6.0), priorXY.evaluateError(init, actA), tol)); - Matrix expA = Matrix_(2, 6, - 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 1.0, 0.0); - EXPECT(assert_equal(expA, actA)); - - pose3SLAM::Graph graph; - graph.add(priorXY); - - Values values; - values.insert(key, init); - - Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); - EXPECT(assert_equal(expected, actual.at(key), tol)); - EXPECT_DOUBLES_EQUAL(0.0, graph.error(actual), tol); -} - -// The world coordinate system has z pointing up, y north, x east -// The vehicle has X forward, Y right, Z down -Rot3 R1(Point3( 0, 1, 0), Point3( 1, 0, 0), Point3(0, 0, -1)); -Rot3 R2(Point3(-1, 0, 0), Point3( 0, 1, 0), Point3(0, 0, -1)); -Rot3 R3(Point3( 0,-1, 0), Point3(-1, 0, 0), Point3(0, 0, -1)); -Rot3 R4(Point3( 1, 0, 0), Point3( 0,-1, 0), Point3(0, 0, -1)); - -/* ************************************************************************* */ -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))); - - Values actual = pose3SLAM::circle(4,1.0); - CHECK(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -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))); - - Ordering ordering(*expected.orderingArbitrary()); - VectorValues delta(expected.dims(ordering)); - delta.vector() = Vector_(24, - 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, - 0.0,0.0,0.0, 0.1, 0.0, 0.0); - Values actual = pose3SLAM::circle(4,1.0).retract(delta, ordering); - CHECK(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testProjectionFactor.cpp b/gtsam/slam/tests/testProjectionFactor.cpp index 8b4ecbf21..1bda97951 100644 --- a/gtsam/slam/tests/testProjectionFactor.cpp +++ b/gtsam/slam/tests/testProjectionFactor.cpp @@ -16,13 +16,17 @@ * @date Nov 2009 */ +#include +#include +#include +#include +#include +#include +#include #include -#include - using namespace std; using namespace gtsam; -using namespace visualSLAM; // make cube static Point3 @@ -37,23 +41,31 @@ 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); +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; -// make cameras +typedef GenericProjectionFactor MyProjectionFactor; + +/* ************************************************************************* */ +TEST( ProjectionFactor, nonStandard ) +{ + GenericProjectionFactor f; +} /* ************************************************************************* */ 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; - boost::shared_ptr - factor(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + int i=1, j=1; + boost::shared_ptr + factor(new MyProjectionFactor(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,18 +73,18 @@ 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)); // linearize graph - visualSLAM::Graph graph; + NonlinearFactorGraph graph; graph.push_back(factor); FactorGraph expected_lfg; expected_lfg.push_back(actual); @@ -81,11 +93,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 +107,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; - boost::shared_ptr - factor1(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + int i=1, j=1; + boost::shared_ptr + factor1(new MyProjectionFactor(z, sigma, X(i), L(j), sK)); - boost::shared_ptr - factor2(new visualSLAM::ProjectionFactor(z, sigma, PoseKey(cameraFrameNumber), PointKey(landmarkNumber), sK)); + boost::shared_ptr + factor2(new MyProjectionFactor(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 deleted file mode 100644 index 9cfb8bb72..000000000 --- a/gtsam/slam/tests/testSerializationSLAM.cpp +++ /dev/null @@ -1,207 +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 testSerializationSLAM.cpp - * @brief - * @author Richard Roberts - * @date Feb 7, 2012 - */ - -#include -#include -#include -#include -#include - -#include -#include - -using namespace std; -using namespace gtsam; -using namespace gtsam::serializationTestHelpers; - -/* Create GUIDs for factors */ -/* ************************************************************************* */ -BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); -BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor"); - -/* ************************************************************************* */ -// Export Noisemodels -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); - -BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); -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); - GaussianFactorGraph fg = createGaussianFactorGraph(ordering); - EXPECT(equalsObj(ordering)); - EXPECT(equalsXML(ordering)); - - EXPECT(equalsObj(fg)); - EXPECT(equalsXML(fg)); - - GaussianBayesNet cbn = createSmallGaussianBayesNet(); - EXPECT(equalsObj(cbn)); - EXPECT(equalsXML(cbn)); -} - -/* ************************************************************************* */ -TEST (Serialization, gaussianISAM) { - using namespace example; - Ordering ordering; - GaussianFactorGraph smoother; - boost::tie(smoother, ordering) = createSmoother(7); - BayesTree bayesTree = *GaussianMultifrontalSolver(smoother).eliminate(); - GaussianISAM isam(bayesTree); - - EXPECT(equalsObj(isam)); - EXPECT(equalsXML(isam)); -} - -/* ************************************************************************* */ -/* Create GUIDs for factors in simulated2D */ -BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" ) -BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" ) -BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement") -BOOST_CLASS_EXPORT(gtsam::Point2) - -/* ************************************************************************* */ -TEST (Serialization, smallExample) { - using namespace example; - Graph nfg = createNonlinearFactorGraph(); - Values c1 = createValues(); - EXPECT(equalsObj(nfg)); - EXPECT(equalsXML(nfg)); - - EXPECT(equalsObj(c1)); - EXPECT(equalsXML(c1)); -} - -/* ************************************************************************* */ -/* Create GUIDs for factors */ -BOOST_CLASS_EXPORT_GUID(planarSLAM::Prior, "gtsam::planarSLAM::Prior"); -BOOST_CLASS_EXPORT_GUID(planarSLAM::Bearing, "gtsam::planarSLAM::Bearing"); -BOOST_CLASS_EXPORT_GUID(planarSLAM::Range, "gtsam::planarSLAM::Range"); -BOOST_CLASS_EXPORT_GUID(planarSLAM::BearingRange,"gtsam::planarSLAM::BearingRange"); -BOOST_CLASS_EXPORT_GUID(planarSLAM::Odometry, "gtsam::planarSLAM::Odometry"); -BOOST_CLASS_EXPORT_GUID(planarSLAM::Constraint, "gtsam::planarSLAM::Constraint"); - -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)); - - 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)); - - Graph graph; - graph.add(prior); - graph.add(bearing); - graph.add(range); - graph.add(bearingRange); - graph.add(odometry); - graph.add(constraint); - - // text - EXPECT(equalsObj(PoseKey(2))); - EXPECT(equalsObj(PointKey(3))); - EXPECT(equalsObj(values)); - EXPECT(equalsObj(prior)); - EXPECT(equalsObj(bearing)); - EXPECT(equalsObj(bearingRange)); - EXPECT(equalsObj(range)); - EXPECT(equalsObj(odometry)); - EXPECT(equalsObj(constraint)); - EXPECT(equalsObj(graph)); - - // xml - EXPECT(equalsXML(PoseKey(2))); - EXPECT(equalsXML(PointKey(3))); - EXPECT(equalsXML(values)); - EXPECT(equalsXML(prior)); - EXPECT(equalsXML(bearing)); - EXPECT(equalsXML(bearingRange)); - EXPECT(equalsXML(range)); - EXPECT(equalsXML(odometry)); - EXPECT(equalsXML(constraint)); - EXPECT(equalsXML(graph)); -} - -/* ************************************************************************* */ -/* Create GUIDs for factors */ -BOOST_CLASS_EXPORT_GUID(visualSLAM::PoseConstraint, "gtsam::visualSLAM::PoseConstraint"); -BOOST_CLASS_EXPORT_GUID(visualSLAM::PointConstraint, "gtsam::visualSLAM::PointConstraint"); -BOOST_CLASS_EXPORT_GUID(visualSLAM::PosePrior, "gtsam::visualSLAM::PosePrior"); -BOOST_CLASS_EXPORT_GUID(visualSLAM::PointPrior, "gtsam::visualSLAM::PointPrior"); -BOOST_CLASS_EXPORT_GUID(visualSLAM::ProjectionFactor,"gtsam::visualSLAM::ProjectionFactor"); -BOOST_CLASS_EXPORT_GUID(visualSLAM::StereoFactor, "gtsam::visualSLAM::StereoFactor"); - -BOOST_CLASS_EXPORT(gtsam::Pose3) -BOOST_CLASS_EXPORT(gtsam::Point3) - -Point3 pt3(1.0, 2.0, 3.0); -Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); -Pose3 pose3(rt3, pt3); -Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5); - -/* ************************************************************************* */ -TEST (Serialization, visual_system) { - using namespace visualSLAM; - Values values; - Symbol x1('x',1), x2('x',2); - Symbol l1('l',1), l2('l',2); - Pose3 pose1 = pose3, pose2 = pose3.inverse(); - Point3 pt1(1.0, 2.0, 3.0), pt2(4.0, 5.0, 6.0); - values.insert(x1, pose1); - values.insert(l1, pt1); - SharedNoiseModel model2 = noiseModel::Isotropic::Sigma(2, 0.3); - SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.3); - SharedNoiseModel model6 = noiseModel::Isotropic::Sigma(6, 0.3); - 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); - - EXPECT(equalsObj(values)); - EXPECT(equalsObj(graph)); - - EXPECT(equalsXML(values)); - EXPECT(equalsXML(graph)); -} - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testStereoFactor.cpp b/gtsam/slam/tests/testStereoFactor.cpp index 25cd6e16f..f6a861354 100644 --- a/gtsam/slam/tests/testStereoFactor.cpp +++ b/gtsam/slam/tests/testStereoFactor.cpp @@ -12,58 +12,59 @@ /** * @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 +#include +#include -#include +#include using namespace std; using namespace gtsam; -using namespace boost; -using namespace visualSLAM; -Pose3 camera1(Matrix_(3,3, +static Pose3 camera1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,6.25)); -Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1500, 1500, 0, 320, 240, 0.5)); -StereoCamera stereoCam(Pose3(), K); +static boost::shared_ptr K(new Cal3_S2Stereo(625, 625, 0, 320, 240, 0.5)); // point X Y Z in meters -Point3 p(0, 0, 5); +static 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) { - //Cal3_S2 K(625, 625, 0, 320, 240, 0.5); - 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(NonlinearEquality(X(1), camera1)); - StereoPoint2 z14(320,320.0-50, 240); + 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(GenericStereoFactor(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/testVSLAM.cpp deleted file mode 100644 index bb7623954..000000000 --- a/gtsam/slam/tests/testVSLAM.cpp +++ /dev/null @@ -1,214 +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 testGraph.cpp - * @brief Unit test for two cameras and four landmarks - * single camera - * @author Chris Beall - * @author Frank Dellaert - * @author Viorela Ila - */ - -#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); - -Pose3 camera1(Matrix_(3,3, - 1., 0., 0., - 0.,-1., 0., - 0., 0.,-1. - ), - Point3(0,0,6.25)); - -Pose3 camera2(Matrix_(3,3, - 1., 0., 0., - 0.,-1., 0., - 0., 0.,-1. - ), - Point3(0,0,5.00)); - -/* ************************************************************************* */ -visualSLAM::Graph testGraph() { - Point2 z11(-100, 100); - Point2 z12(-100,-100); - Point2 z13( 100,-100); - Point2 z14( 100, 100); - Point2 z21(-125, 125); - Point2 z22(-125,-125); - Point2 z23( 125,-125); - Point2 z24( 125, 125); - - 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); - return g; -} - -/* ************************************************************************* */ -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); - - // 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); - - // Create an ordering of the variables - Ordering ordering; - ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2); - - // Create an optimizer and check its error - // We expect the initial to be zero because config is the ground truth - LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, ordering); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // Iterate once, and the config should not have changed because we started - // with the ground truth - optimizer.iterate(); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // check if correct - CHECK(assert_equal(initialEstimate, optimizer.values())); -} - - -/* ************************************************************************* */ -TEST( Graph, optimizeLM2) -{ - // build a graph - visualSLAM::Graph graph(testGraph()); - // add 2 camera constraints - graph.addPoseConstraint(1, camera1); - graph.addPoseConstraint(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); - - // Create an ordering of the variables - Ordering ordering; - ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2); - - // Create an optimizer and check its error - // We expect the initial to be zero because config is the ground truth - LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, ordering); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // Iterate once, and the config should not have changed because we started - // with the ground truth - optimizer.iterate(); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // check if correct - CHECK(assert_equal(initialEstimate, optimizer.values())); -} - - -/* ************************************************************************* */ -TEST( Graph, CHECK_ORDERING) -{ - // build a graph - visualSLAM::Graph graph = testGraph(); - // add 2 camera constraints - graph.addPoseConstraint(1, camera1); - graph.addPoseConstraint(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); - - // Create an optimizer and check its error - // We expect the initial to be zero because config is the ground truth - LevenbergMarquardtOptimizer optimizer(graph, initialEstimate); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // Iterate once, and the config should not have changed because we started - // with the ground truth - optimizer.iterate(); - DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9); - - // check if correct - CHECK(assert_equal(initialEstimate, optimizer.values())); -} - -/* ************************************************************************* */ -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)); - - 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)); - - Ordering largeOrdering; - Values largeValues = init; - largeValues.insert(PoseKey(2), Pose3()); - largeOrdering += PoseKey(1),PointKey(1),PoseKey(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); - Values actual = init.retract(delta, largeOrdering); - - CHECK(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ diff --git a/gtsam/slam/visualSLAM.cpp b/gtsam/slam/visualSLAM.cpp deleted file mode 100644 index bc2ee199b..000000000 --- a/gtsam/slam/visualSLAM.cpp +++ /dev/null @@ -1,61 +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 visualSLAM.cpp - * @date Jan 14, 2010 - * @author richard - */ - -#include -#include - -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)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addPoseConstraint(Index poseKey, const Pose3& p) { - boost::shared_ptr factor(new PoseConstraint(PoseKey(poseKey), p)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addPointConstraint(Index pointKey, const Point3& p) { - boost::shared_ptr factor(new PointConstraint(PointKey(pointKey), 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)); - push_back(factor); - } - - /* ************************************************************************* */ - void Graph::addPointPrior(Index pointKey, const Point3& p, const SharedNoiseModel& model) { - boost::shared_ptr factor(new PointPrior(PointKey(pointKey), 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))); - } - - /* ************************************************************************* */ - -} diff --git a/gtsam/slam/visualSLAM.h b/gtsam/slam/visualSLAM.h deleted file mode 100644 index 38d3312a7..000000000 --- a/gtsam/slam/visualSLAM.h +++ /dev/null @@ -1,142 +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 visualSLAM.h - * @brief Basic typedefs for general VisualSLAM problems. Useful for monocular and stereo systems. - * @date Jan 14, 2010 - * @author Richard Roberts - * @author Chris Beall - */ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -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. - */ - typedef NonlinearEquality PoseConstraint; ///< put a hard constraint on a pose - typedef NonlinearEquality PointConstraint; ///< put a hard constraint on a point - typedef PriorFactor PosePrior; ///< put a soft prior on a Pose - typedef PriorFactor PointPrior; ///< put a soft prior on a point - typedef RangeFactor RangeFactor; ///< put a factor on the range from a pose to a point - - /// monocular and stereo camera typedefs for general use - typedef GenericProjectionFactor ProjectionFactor; - typedef GenericStereoFactor StereoFactor; - - /** - * Non-linear factor graph for vanilla visual SLAM - */ - class Graph: public NonlinearFactorGraph { - - public: - /// shared pointer to this type of graph - typedef boost::shared_ptr shared_graph; - - /// default constructor is empty graph - Graph() { - } - - /// print out graph - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - NonlinearFactorGraph::print(s, keyFormatter); - } - - /// check if two graphs are equal - bool equals(const Graph& p, double tol = 1e-9) const { - return NonlinearFactorGraph::equals(p, tol); - } - - /** - * Add a projection factor measurement (monocular) - * @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 calibration object - */ - void addMeasurement(const Point2& measured, const SharedNoiseModel& model, - Index poseKey, Index pointKey, const shared_ptrK& 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()); - - /** - * 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()); - - /** - * Add a prior on a pose - * @param key variable key of the camera pose - * @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)); - - /** - * Add a prior on a landmark - * @param key variable key of the landmark - * @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)); - - /** - * Add a range prior to a landmark - * @param poseKey variable key of the camera pose - * @param pointKey variable key of the landmark - * @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)); - - /** - * Optimize the graph - * @param initialEstimate initial estimate of all variables in the graph - * @param pointKey variable key of the landmark - * @param range approximate range to landmark - * @param model uncertainty model of this prior - */ - Values optimize(const Values& initialEstimate) { - return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); - } - - }; // Graph - -} // namespaces diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index f7563f8ff..c38015db9 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -2,19 +2,26 @@ # and also build tests set (gtsam_unstable_subdirs base - discrete + geometry + discrete +# linear dynamics - slam + nonlinear + slam ) +add_custom_target(check.unstable COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) + # assemble core libaries foreach(subdir ${gtsam_unstable_subdirs}) # Build convenience libraries file(GLOB subdir_srcs "${subdir}/*.cpp") - set(${subdir}_srcs ${subdir_srcs}) - if (GTSAM_BUILD_CONVENIENCE_LIBRARIES) + file(GLOB subdir_headers "${subdir}/*.h") + set(${subdir}_srcs ${subdir_srcs} ${subdir_headers}) + gtsam_assign_source_folders("${${subdir}_srcs}") # Create MSVC structure + if (subdir_srcs AND GTSAM_BUILD_CONVENIENCE_LIBRARIES) message(STATUS "Building Convenience Library: ${subdir}_unstable") - add_library("${subdir}_unstable" STATIC ${subdir_srcs}) + add_library("${subdir}_unstable" STATIC ${${subdir}_srcs}) endif() # Build local library and tests @@ -25,12 +32,17 @@ endforeach(subdir) # assemble gtsam_unstable components set(gtsam_unstable_srcs ${base_srcs} + ${geometry_srcs} ${discrete_srcs} ${dynamics_srcs} - ${slam_srcs} + #${linear_srcs} + ${nonlinear_srcs} + ${slam_srcs} ) -option (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam_unstable" ON) +if(NOT MSVC) + option (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam_unstable" ON) +endif() # Versions - same as core gtsam library set(gtsam_unstable_version ${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}) @@ -47,7 +59,10 @@ set_target_properties(gtsam_unstable-static PROPERTIES VERSION ${gtsam_unstable_version} SOVERSION ${gtsam_unstable_soversion}) target_link_libraries(gtsam_unstable-static gtsam-static) -install(TARGETS gtsam_unstable-static ARCHIVE DESTINATION lib) +set(gtsam_unstable-lib "gtsam_unstable-static") +install(TARGETS gtsam_unstable-static EXPORT GTSAM-exports ARCHIVE DESTINATION lib) +list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable-static) +set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) if (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY) message(STATUS "Building GTSAM_UNSTABLE - shared") @@ -58,39 +73,27 @@ if (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY) VERSION ${gtsam_unstable_version} SOVERSION ${gtsam_unstable_soversion}) target_link_libraries(gtsam_unstable-shared gtsam-shared) - install(TARGETS gtsam_unstable-shared LIBRARY DESTINATION lib ) + install(TARGETS gtsam_unstable-shared EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) + list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable-shared) + set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) endif(GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY) # Wrap version for gtsam_unstable -if (GTSAM_BUILD_WRAP) +if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Set up codegen include(GtsamMatlabWrap) - # Wrap codegen - #usage: wrap mexExtension interfacePath moduleName toolboxPath - # mexExtension : OS/CPU-dependent extension for MEX binaries - # interfacePath : *absolute* path to directory of module interface file - # moduleName : the name of the module, interface file must be called moduleName.h - # toolboxPath : the directory in which to generate the wrappers - # [mexFlags] : extra flags for the mex command - # TODO: generate these includes programmatically - set(mexFlags "-I${Boost_INCLUDE_DIR} -I${CMAKE_INSTALL_PREFIX}/include -I${CMAKE_INSTALL_PREFIX}/include/gtsam_unstable -I${CMAKE_INSTALL_PREFIX}/include/gtsam_unstable/dynamics -I${CMAKE_INSTALL_PREFIX}/include/gtsam_unstable/discrete -L${CMAKE_INSTALL_PREFIX}/lib -lgtsam -lgtsam_unstable") - set(toolbox_path ${CMAKE_BINARY_DIR}/wrap/gtsam_unstable) - set(moduleName gtsam_unstable) + # Choose include flags depending on build process + set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR}) + set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR}) + set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) + set(GTSAM_UNSTABLE_LIB_DIR ${MEX_LIB_ROOT}/gtsam_unstable) - find_mexextension() + # Generate, build and install toolbox + set(mexFlags -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT}) - # Code generation command - add_custom_target(wrap_gtsam_unstable ALL COMMAND - ${CMAKE_BINARY_DIR}/wrap/wrap ${GTSAM_MEX_BIN_EXTENSION} ${CMAKE_CURRENT_SOURCE_DIR} ${moduleName} ${toolbox_path} "${mexFlags}" - DEPENDS wrap) - - if (GTSAM_INSTALL_MATLAB_TOOLBOX) - # Primary toolbox files - message(STATUS "Installing Matlab Toolbox to ${GTSAM_TOOLBOX_INSTALL_PATH}") - install(DIRECTORY DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}) # make an empty folder - # exploit need for trailing slash to specify a full folder, rather than just its contents to copy - install(DIRECTORY ${toolbox_path} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}) - endif (GTSAM_INSTALL_MATLAB_TOOLBOX) -endif(GTSAM_BUILD_WRAP) + # Macro to handle details of setting up targets + wrap_library(gtsam_unstable "${mexFlags}" "./" gtsam) + +endif(GTSAM_INSTALL_MATLAB_TOOLBOX) diff --git a/gtsam_unstable/base/BTree.h b/gtsam_unstable/base/BTree.h index 2a40465a3..379725a7a 100644 --- a/gtsam_unstable/base/BTree.h +++ b/gtsam_unstable/base/BTree.h @@ -26,7 +26,7 @@ namespace gtsam { /** * @brief Binary tree - * @ingroup base + * @addtogroup base */ template class BTree { diff --git a/gtsam_unstable/base/CMakeLists.txt b/gtsam_unstable/base/CMakeLists.txt index 7e455e9bf..0545cd4c9 100644 --- a/gtsam_unstable/base/CMakeLists.txt +++ b/gtsam_unstable/base/CMakeLists.txt @@ -16,4 +16,4 @@ set (base_excluded_tests "") # Add all tests gtsam_add_subdir_tests(base_unstable "${base_local_libs}" "${base_full_libs}" "${base_excluded_tests}") - +add_dependencies(check.unstable check.base_unstable) diff --git a/gtsam_unstable/base/DSF.h b/gtsam_unstable/base/DSF.h index 5276779b0..0c7cc7399 100644 --- a/gtsam_unstable/base/DSF.h +++ b/gtsam_unstable/base/DSF.h @@ -34,7 +34,7 @@ namespace gtsam { * S = {S_1,S_2,...} of disjoint dynamic sets. Each set is identified by * a representative, which is some member of the set. * - * @ingroup base + * @addtogroup base */ template class DSF : protected BTree { diff --git a/gtsam_unstable/base/Dummy.cpp b/gtsam_unstable/base/Dummy.cpp new file mode 100644 index 000000000..90d71d27e --- /dev/null +++ b/gtsam_unstable/base/Dummy.cpp @@ -0,0 +1,43 @@ +/* ---------------------------------------------------------------------------- + + * 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 Dummy.h + * @brief Dummy class for testing MATLAB memory allocation + * @author Andrew Melim + * @author Frank Dellaert + * @date June 14, 2012 + */ + +#include +#include + +namespace gtsam { + +static size_t gDummyCount = 0; + +Dummy::Dummy():id(++gDummyCount) { + std::cout << "Dummy constructor " << id << std::endl; +} + +Dummy::~Dummy() { + std::cout << "Dummy destructor " << id << std::endl; +} + +void Dummy::print(const std::string& s) const { + std::cout << s << "Dummy " << id << std::endl; +} + +unsigned char Dummy::dummyTwoVar(unsigned char a) const { + return a; +} + +} diff --git a/gtsam_unstable/base/Dummy.h b/gtsam_unstable/base/Dummy.h new file mode 100644 index 000000000..0ab344f74 --- /dev/null +++ b/gtsam_unstable/base/Dummy.h @@ -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 + + * -------------------------------------------------------------------------- */ + +/** + * @file Dummy.h + * @brief Dummy class for testing MATLAB memory allocation + * @author Andrew Melim + * @author Frank Dellaert + * @date June 14, 2012 + */ + +#include + +namespace gtsam { + + struct Dummy { + size_t id; + Dummy(); + ~Dummy(); + void print(const std::string& s="") const ; + unsigned char dummyTwoVar(unsigned char a) const ; + }; + +} // namespace gtsam + diff --git a/gtsam_unstable/discrete/AllDiff.cpp b/gtsam_unstable/discrete/AllDiff.cpp index 46efd4499..ac412fa7f 100644 --- a/gtsam_unstable/discrete/AllDiff.cpp +++ b/gtsam_unstable/discrete/AllDiff.cpp @@ -20,10 +20,11 @@ namespace gtsam { } /* ************************************************************************* */ - void AllDiff::print(const std::string& s) const { - std::cout << s << ": AllDiff on "; + void AllDiff::print(const std::string& s, + const IndexFormatter& formatter) const { + std::cout << s << "AllDiff on "; BOOST_FOREACH (Index dkey, keys_) - std::cout << dkey << " "; + std::cout << formatter(dkey) << " "; std::cout << std::endl; } @@ -39,14 +40,14 @@ namespace gtsam { } /* ************************************************************************* */ - AllDiff::operator DecisionTreeFactor() const { + DecisionTreeFactor AllDiff::toDecisionTreeFactor() const { // We will do this by converting the allDif into many BinaryAllDiff constraints DecisionTreeFactor converted; size_t nrKeys = keys_.size(); for (size_t i1 = 0; i1 < nrKeys; i1++) for (size_t i2 = i1 + 1; i2 < nrKeys; i2++) { BinaryAllDiff binary12(discreteKey(i1),discreteKey(i2)); - converted = converted * binary12; + converted = converted * binary12.toDecisionTreeFactor(); } return converted; } @@ -54,7 +55,7 @@ namespace gtsam { /* ************************************************************************* */ DecisionTreeFactor AllDiff::operator*(const DecisionTreeFactor& f) const { // TODO: can we do this more efficiently? - return DecisionTreeFactor(*this) * f; + return toDecisionTreeFactor() * f; } /* ************************************************************************* */ diff --git a/gtsam_unstable/discrete/AllDiff.h b/gtsam_unstable/discrete/AllDiff.h index 4f4e10511..1a560ace2 100644 --- a/gtsam_unstable/discrete/AllDiff.h +++ b/gtsam_unstable/discrete/AllDiff.h @@ -34,13 +34,14 @@ namespace gtsam { AllDiff(const DiscreteKeys& dkeys); // print - virtual void print(const std::string& s = "") const; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /// Calculate value = expensive ! virtual double operator()(const Values& values) const; /// Convert into a decisiontree, can be *very* expensive ! - virtual operator DecisionTreeFactor() const; + virtual DecisionTreeFactor toDecisionTreeFactor() const; /// Multiply into a decisiontree virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; diff --git a/gtsam_unstable/discrete/BinaryAllDiff.h b/gtsam_unstable/discrete/BinaryAllDiff.h index 04eeba953..9ed2f79f1 100644 --- a/gtsam_unstable/discrete/BinaryAllDiff.h +++ b/gtsam_unstable/discrete/BinaryAllDiff.h @@ -33,9 +33,10 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "") const { - std::cout << s << ": BinaryAllDiff on " << keys_[0] << " and " << keys_[1] - << std::endl; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const { + std::cout << s << "BinaryAllDiff on " << formatter(keys_[0]) << " and " + << formatter(keys_[1]) << std::endl; } /// Calculate value @@ -44,7 +45,7 @@ namespace gtsam { } /// Convert into a decisiontree - virtual operator DecisionTreeFactor() const { + virtual DecisionTreeFactor toDecisionTreeFactor() const { DiscreteKeys keys; keys.push_back(DiscreteKey(keys_[0],cardinality0_)); keys.push_back(DiscreteKey(keys_[1],cardinality1_)); @@ -59,7 +60,7 @@ namespace gtsam { /// Multiply into a decisiontree virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const { // TODO: can we do this more efficiently? - return DecisionTreeFactor(*this) * f; + return toDecisionTreeFactor() * f; } /* diff --git a/gtsam_unstable/discrete/CMakeLists.txt b/gtsam_unstable/discrete/CMakeLists.txt index b049562a5..ae84426a8 100644 --- a/gtsam_unstable/discrete/CMakeLists.txt +++ b/gtsam_unstable/discrete/CMakeLists.txt @@ -16,16 +16,36 @@ set (discrete_full_libs gtsam_unstable-static) # Exclude tests that don't work -set (discrete_excluded_tests "${CMAKE_CURRENT_SOURCE_DIR}/tests/testScheduler.cpp") +#set (discrete_excluded_tests +#"${CMAKE_CURRENT_SOURCE_DIR}/tests/testScheduler.cpp" +#) + # Add all tests gtsam_add_subdir_tests(discrete_unstable "${discrete_local_libs}" "${discrete_full_libs}" "${discrete_excluded_tests}") +add_dependencies(check.unstable check.discrete_unstable) -# add examples -foreach(example schedulingExample schedulingQuals12) - add_executable(${example} "examples/${example}.cpp") - add_dependencies(${example} gtsam-static gtsam_unstable-static) - target_link_libraries(${example} gtsam-static gtsam_unstable-static) - add_custom_target(${example}.run ${EXECUTABLE_OUTPUT_PATH}${example} ${ARGN}) -endforeach(example) +# List examples to build - comment out here to exclude from compilation +set(discrete_unstable_examples +schedulingExample +schedulingQuals12 +) +if (GTSAM_BUILD_EXAMPLES) + foreach(example ${discrete_unstable_examples}) + add_executable(${example} "examples/${example}.cpp") + + # Disable building during make all/install + if (GTSAM_ENABLE_INSTALL_EXAMPLE_FIX) + set_target_properties(${example} PROPERTIES EXCLUDE_FROM_ALL ON) + endif() + + if(NOT MSVC) + add_dependencies(examples ${example}) + add_custom_target(${example}.run ${EXECUTABLE_OUTPUT_PATH}${example} ${ARGN}) + endif() + + add_dependencies(${example} gtsam-static gtsam_unstable-static) + target_link_libraries(${example} gtsam-static gtsam_unstable-static) + endforeach(example) +endif (GTSAM_BUILD_EXAMPLES) diff --git a/gtsam_unstable/discrete/CSP.cpp b/gtsam_unstable/discrete/CSP.cpp index 4da2f440a..20c0e7617 100644 --- a/gtsam_unstable/discrete/CSP.cpp +++ b/gtsam_unstable/discrete/CSP.cpp @@ -11,6 +11,8 @@ #include #include +using namespace std; + namespace gtsam { /// Find the best total assignment - can be expensive @@ -49,8 +51,9 @@ namespace gtsam { // if not already a singleton if (!domains[v].isSingleton()) { // get the constraint and call its ensureArcConsistency method - Constraint::shared_ptr factor = (*this)[f]; - changed[v] = factor->ensureArcConsistency(v,domains) || changed[v]; + Constraint::shared_ptr constraint = boost::dynamic_pointer_cast((*this)[f]); + if (!constraint) throw runtime_error("CSP:runArcConsistency: non-constraint factor"); + changed[v] = constraint->ensureArcConsistency(v,domains) || changed[v]; } } // f if (changed[v]) anyChange = true; @@ -59,8 +62,8 @@ namespace gtsam { // TODO: Sudoku specific hack if (print) { if (cardinality == 9 && n == 81) { - for (size_t i = 0, v = 0; i < sqrt(n); i++) { - for (size_t j = 0; j < sqrt(n); j++, v++) { + for (size_t i = 0, v = 0; i < (size_t)std::sqrt((double)n); i++) { + for (size_t j = 0; j < (size_t)std::sqrt((double)n); j++, v++) { if (changed[v]) cout << "*"; domains[v].print(); cout << "\t"; @@ -84,8 +87,10 @@ namespace gtsam { // TODO: create a new ordering as we go, to ensure a connected graph // KeyOrdering ordering; // vector dkeys; - BOOST_FOREACH(const Constraint::shared_ptr& factor, factors_) { - Constraint::shared_ptr reduced = factor->partiallyApply(domains); + BOOST_FOREACH(const DiscreteFactor::shared_ptr& f, factors_) { + Constraint::shared_ptr constraint = boost::dynamic_pointer_cast(f); + if (!constraint) throw runtime_error("CSP:runArcConsistency: non-constraint factor"); + Constraint::shared_ptr reduced = constraint->partiallyApply(domains); if (print) reduced->print(); } #endif diff --git a/gtsam_unstable/discrete/CSP.h b/gtsam_unstable/discrete/CSP.h index e2e2a2251..ef4bbc17a 100644 --- a/gtsam_unstable/discrete/CSP.h +++ b/gtsam_unstable/discrete/CSP.h @@ -18,7 +18,7 @@ namespace gtsam { * A specialization of a DiscreteFactorGraph. * It knows about CSP-specific constraints and algorithms */ - class CSP: public FactorGraph { + class CSP: public DiscreteFactorGraph { public: /** A map from keys to values */ @@ -27,30 +27,10 @@ namespace gtsam { typedef boost::shared_ptr sharedValues; public: - /// Constructor - CSP() { - } - template - void add(const DiscreteKey& j, SOURCE table) { - DiscreteKeys keys; - keys.push_back(j); - push_back(boost::make_shared(keys, table)); - } - - template - void add(const DiscreteKey& j1, const DiscreteKey& j2, SOURCE table) { - DiscreteKeys keys; - keys.push_back(j1); - keys.push_back(j2); - push_back(boost::make_shared(keys, table)); - } - - /** add shared discreteFactor immediately from arguments */ - template - void add(const DiscreteKeys& keys, SOURCE table) { - push_back(boost::make_shared(keys, table)); - } +// /// Constructor +// CSP() { +// } /// Add a unary constraint, allowing only a single value void addSingleValue(const DiscreteKey& dkey, size_t value) { @@ -71,19 +51,28 @@ namespace gtsam { push_back(factor); } +// /** return product of all factors as a single factor */ +// DecisionTreeFactor product() const { +// DecisionTreeFactor result; +// BOOST_FOREACH(const sharedFactor& factor, *this) +// if (factor) result = (*factor) * result; +// return result; +// } + /// Find the best total assignment - can be expensive sharedValues optimalAssignment() const; - /* - * Perform loopy belief propagation - * True belief propagation would check for each value in domain - * whether any satisfying separator assignment can be found. - * This corresponds to hyper-arc consistency in CSP speak. - * This can be done by creating a mini-factor graph and search. - * For a nine-by-nine Sudoku, the search tree will be 8+6+6=20 levels deep. - * It will be very expensive to exclude values that way. - */ - // void applyBeliefPropagation(size_t nrIterations = 10) const; +// /* +// * Perform loopy belief propagation +// * True belief propagation would check for each value in domain +// * whether any satisfying separator assignment can be found. +// * This corresponds to hyper-arc consistency in CSP speak. +// * This can be done by creating a mini-factor graph and search. +// * For a nine-by-nine Sudoku, the search tree will be 8+6+6=20 levels deep. +// * It will be very expensive to exclude values that way. +// */ +// void applyBeliefPropagation(size_t nrIterations = 10) const; + /* * Apply arc-consistency ~ Approximate loopy belief propagation * We need to give the domains to a constraint, and it returns @@ -92,7 +81,7 @@ namespace gtsam { */ void runArcConsistency(size_t cardinality, size_t nrIterations = 10, bool print = false) const; - }; + }; // CSP } // gtsam diff --git a/gtsam_unstable/discrete/Domain.cpp b/gtsam_unstable/discrete/Domain.cpp index fd2631cec..dbc05e3f6 100644 --- a/gtsam_unstable/discrete/Domain.cpp +++ b/gtsam_unstable/discrete/Domain.cpp @@ -15,9 +15,10 @@ namespace gtsam { using namespace std; /* ************************************************************************* */ - void Domain::print(const string& s) const { -// cout << s << ": Domain on " << keys_[0] << " (j=" << keys_[0] -// << ") with values"; + void Domain::print(const string& s, + const IndexFormatter& formatter) const { +// cout << s << ": Domain on " << formatter(keys_[0]) << " (j=" << +// formatter(keys_[0]) << ") with values"; // BOOST_FOREACH (size_t v,values_) cout << " " << v; // cout << endl; BOOST_FOREACH (size_t v,values_) cout << v; @@ -29,7 +30,7 @@ namespace gtsam { } /* ************************************************************************* */ - Domain::operator DecisionTreeFactor() const { + DecisionTreeFactor Domain::toDecisionTreeFactor() const { DiscreteKeys keys; keys += DiscreteKey(keys_[0],cardinality_); vector table; @@ -42,7 +43,7 @@ namespace gtsam { /* ************************************************************************* */ DecisionTreeFactor Domain::operator*(const DecisionTreeFactor& f) const { // TODO: can we do this more efficiently? - return DecisionTreeFactor(*this) * f; + return toDecisionTreeFactor() * f; } /* ************************************************************************* */ diff --git a/gtsam_unstable/discrete/Domain.h b/gtsam_unstable/discrete/Domain.h index 50c534f8a..85b35fe8c 100644 --- a/gtsam_unstable/discrete/Domain.h +++ b/gtsam_unstable/discrete/Domain.h @@ -66,7 +66,8 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "") const; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; bool contains(size_t value) const { return values_.count(value)>0; @@ -76,7 +77,7 @@ namespace gtsam { virtual double operator()(const Values& values) const; /// Convert into a decisiontree - virtual operator DecisionTreeFactor() const; + virtual DecisionTreeFactor toDecisionTreeFactor() const; /// Multiply into a decisiontree virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; diff --git a/gtsam_unstable/discrete/Scheduler.cpp b/gtsam_unstable/discrete/Scheduler.cpp index 678ba1580..d551b1f0b 100644 --- a/gtsam_unstable/discrete/Scheduler.cpp +++ b/gtsam_unstable/discrete/Scheduler.cpp @@ -105,7 +105,6 @@ namespace gtsam { /** Add student-specific constraints to the graph */ void Scheduler::addStudentSpecificConstraints(size_t i, boost::optional slot) { -#ifdef BROKEN bool debug = ISDEBUG("Scheduler::buildGraph"); assert(i table; @@ -40,7 +41,7 @@ namespace gtsam { /* ************************************************************************* */ DecisionTreeFactor SingleValue::operator*(const DecisionTreeFactor& f) const { // TODO: can we do this more efficiently? - return DecisionTreeFactor(*this) * f; + return toDecisionTreeFactor() * f; } /* ************************************************************************* */ diff --git a/gtsam_unstable/discrete/SingleValue.h b/gtsam_unstable/discrete/SingleValue.h index 3f7f3011d..1f6e362aa 100644 --- a/gtsam_unstable/discrete/SingleValue.h +++ b/gtsam_unstable/discrete/SingleValue.h @@ -42,13 +42,14 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "") const; + virtual void print(const std::string& s = "", + const IndexFormatter& formatter = DefaultIndexFormatter) const; /// Calculate value virtual double operator()(const Values& values) const; /// Convert into a decisiontree - virtual operator DecisionTreeFactor() const; + virtual DecisionTreeFactor toDecisionTreeFactor() const; /// Multiply into a decisiontree virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; diff --git a/gtsam_unstable/discrete/examples/schedulingExample.cpp b/gtsam_unstable/discrete/examples/schedulingExample.cpp index 485f0ea1c..0f9854007 100644 --- a/gtsam_unstable/discrete/examples/schedulingExample.cpp +++ b/gtsam_unstable/discrete/examples/schedulingExample.cpp @@ -151,9 +151,9 @@ void solveStaged(size_t addMutex = 2) { scheduler.buildGraph(addMutex); // Do EXACT INFERENCE - tic_("eliminate"); + tic_(3,"eliminate"); DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate(); - toc_("eliminate"); + toc_(3,"eliminate"); // find root node DiscreteConditional::shared_ptr root = *(chordal->rbegin()); diff --git a/gtsam_unstable/discrete/examples/schedulingQuals12.cpp b/gtsam_unstable/discrete/examples/schedulingQuals12.cpp index d0fa041c9..4221eb755 100644 --- a/gtsam_unstable/discrete/examples/schedulingQuals12.cpp +++ b/gtsam_unstable/discrete/examples/schedulingQuals12.cpp @@ -178,9 +178,9 @@ void solveStaged(size_t addMutex = 2) { scheduler.buildGraph(addMutex); // Do EXACT INFERENCE - tic_("eliminate"); + tic_(3,"eliminate"); DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate(); - toc_("eliminate"); + toc_(3,"eliminate"); // find root node DiscreteConditional::shared_ptr root = *(chordal->rbegin()); diff --git a/gtsam_unstable/discrete/tests/testCSP.cpp b/gtsam_unstable/discrete/tests/testCSP.cpp index 46bf61240..f446932e2 100644 --- a/gtsam_unstable/discrete/tests/testCSP.cpp +++ b/gtsam_unstable/discrete/tests/testCSP.cpp @@ -7,6 +7,8 @@ #include #include +#include +using boost::assign::insert; #include #include #include @@ -25,12 +27,12 @@ TEST_UNSAFE( BinaryAllDif, allInOne) // Check construction and conversion BinaryAllDiff c1(ID, UT); DecisionTreeFactor f1(ID & UT, "0 1 1 0"); - EXPECT(assert_equal(f1,(DecisionTreeFactor)c1)); + EXPECT(assert_equal(f1,c1.toDecisionTreeFactor())); // Check construction and conversion BinaryAllDiff c2(UT, AZ); DecisionTreeFactor f2(UT & AZ, "0 1 1 0"); - EXPECT(assert_equal(f2,(DecisionTreeFactor)c2)); + EXPECT(assert_equal(f2,c2.toDecisionTreeFactor())); DecisionTreeFactor f3 = f1*f2; EXPECT(assert_equal(f3,c1*f2)); @@ -146,16 +148,16 @@ TEST_UNSAFE( CSP, AllDiff) dkeys += ID,UT,AZ; csp.addAllDiff(dkeys); csp.addSingleValue(AZ,2); - //GTSAM_PRINT(csp); +// GTSAM_PRINT(csp); // Check construction and conversion SingleValue s(AZ,2); DecisionTreeFactor f1(AZ,"0 0 1"); - EXPECT(assert_equal(f1,(DecisionTreeFactor)s)); + EXPECT(assert_equal(f1,s.toDecisionTreeFactor())); // Check construction and conversion AllDiff alldiff(dkeys); - DecisionTreeFactor actual = (DecisionTreeFactor)alldiff; + DecisionTreeFactor actual = alldiff.toDecisionTreeFactor(); // GTSAM_PRINT(actual); // actual.dot("actual"); DecisionTreeFactor f2(ID & AZ & UT, @@ -200,16 +202,16 @@ TEST_UNSAFE( CSP, AllDiff) known[AZ.first] = 2; DiscreteFactor::shared_ptr reduced1 = alldiff.partiallyApply(known); DecisionTreeFactor f3(ID & UT, "0 1 1 1 0 1 1 1 0"); - EXPECT(assert_equal(f3,reduced1->operator DecisionTreeFactor())); + EXPECT(assert_equal(f3,reduced1->toDecisionTreeFactor())); DiscreteFactor::shared_ptr reduced2 = singleValue.partiallyApply(known); DecisionTreeFactor f4(AZ, "0 0 1"); - EXPECT(assert_equal(f4,reduced2->operator DecisionTreeFactor())); + EXPECT(assert_equal(f4,reduced2->toDecisionTreeFactor())); // Parial application, version 2 DiscreteFactor::shared_ptr reduced3 = alldiff.partiallyApply(domains); - EXPECT(assert_equal(f3,reduced3->operator DecisionTreeFactor())); + EXPECT(assert_equal(f3,reduced3->toDecisionTreeFactor())); DiscreteFactor::shared_ptr reduced4 = singleValue.partiallyApply(domains); - EXPECT(assert_equal(f4,reduced4->operator DecisionTreeFactor())); + EXPECT(assert_equal(f4,reduced4->toDecisionTreeFactor())); // full arc-consistency test csp.runArcConsistency(nrColors); 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/discrete/tests/testScheduler.cpp b/gtsam_unstable/discrete/tests/testScheduler.cpp index bf9273ad6..6559754d5 100644 --- a/gtsam_unstable/discrete/tests/testScheduler.cpp +++ b/gtsam_unstable/discrete/tests/testScheduler.cpp @@ -149,7 +149,7 @@ TEST( schedulingExample, test) /* ************************************************************************* */ TEST( schedulingExample, smallFromFile) { - string path("../../../gtsam_unstable/discrete/examples/"); + string path(TOPSRCDIR "/gtsam_unstable/discrete/examples/"); Scheduler s(2, path + "small.csv"); // add areas diff --git a/gtsam_unstable/discrete/tests/testSudoku.cpp b/gtsam_unstable/discrete/tests/testSudoku.cpp index 1bbac4777..1e4026e7f 100644 --- a/gtsam_unstable/discrete/tests/testSudoku.cpp +++ b/gtsam_unstable/discrete/tests/testSudoku.cpp @@ -7,6 +7,8 @@ #include #include +#include +using boost::assign::insert; #include #include #include @@ -14,6 +16,8 @@ using namespace std; using namespace gtsam; +#define PRINT false + class Sudoku: public CSP { /// sudoku size @@ -73,7 +77,7 @@ public: } // add box constraints - size_t N = sqrt(n), i0 = 0; + size_t N = (size_t)sqrt(double(n)), i0 = 0; for (size_t I = 0; I < N; I++) { size_t j0 = 0; for (size_t J = 0; J < N; J++) { @@ -119,7 +123,7 @@ TEST_UNSAFE( Sudoku, small) 0,1, 0,0); // Do BP - csp.runArcConsistency(4); + csp.runArcConsistency(4,10,PRINT); // optimize and check CSP::sharedValues solution = csp.optimalAssignment(); @@ -150,7 +154,7 @@ TEST_UNSAFE( Sudoku, easy) 5,0,0, 0,3,0, 7,0,0); // Do BP - sudoku.runArcConsistency(4); + sudoku.runArcConsistency(4,10,PRINT); // sudoku.printSolution(); // don't do it } @@ -172,7 +176,7 @@ TEST_UNSAFE( Sudoku, extreme) 0,0,0, 2,7,5, 9,0,0); // Do BP - sudoku.runArcConsistency(9,10,false); + sudoku.runArcConsistency(9,10,PRINT); #ifdef METIS VariableIndex index(sudoku); @@ -201,7 +205,7 @@ TEST_UNSAFE( Sudoku, AJC_3star_Feb8_2012) 0,0,0, 1,0,0, 0,3,7); // Do BP - sudoku.runArcConsistency(9,10,true); + sudoku.runArcConsistency(9,10,PRINT); //sudoku.printSolution(); // don't do it } diff --git a/gtsam_unstable/dynamics/CMakeLists.txt b/gtsam_unstable/dynamics/CMakeLists.txt index 66d0b9ac1..d0d45e0e4 100644 --- a/gtsam_unstable/dynamics/CMakeLists.txt +++ b/gtsam_unstable/dynamics/CMakeLists.txt @@ -23,4 +23,4 @@ set (dynamics_excluded_tests "") # Add all tests gtsam_add_subdir_tests(dynamics_unstable "${dynamics_local_libs}" "${dynamics_full_libs}" "${dynamics_excluded_tests}") - +add_dependencies(check.unstable check.dynamics_unstable) diff --git a/gtsam_unstable/dynamics/DynamicsPriors.h b/gtsam_unstable/dynamics/DynamicsPriors.h index 2d0f9e6a6..ccf7063dc 100644 --- a/gtsam_unstable/dynamics/DynamicsPriors.h +++ b/gtsam_unstable/dynamics/DynamicsPriors.h @@ -9,7 +9,7 @@ #pragma once -#include +#include #include diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 29b77c661..f42ecc352 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -51,9 +51,14 @@ public: virtual ~FullIMUFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** Check if two factors are equal */ virtual bool equals(const NonlinearFactor& e, double tol = 1e-9) const { - const This* const f = dynamic_cast(&e); + const This* const f = dynamic_cast(&e); return f && Base::equals(e) && equal_with_abs_tol(accel_, f->accel_, tol) && equal_with_abs_tol(gyro_, f->gyro_, tol) && @@ -72,8 +77,6 @@ public: const Vector& gyro() const { return gyro_; } const Vector& accel() const { return accel_; } Vector z() const { return concatVectors(2, &accel_, &gyro_); } - const Key& key1() const { return this->key1_; } - const Key& key2() const { return this->key2_; } /** * Error evaluation with optional derivatives - calculates diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 7ded5ef82..9e5651cc9 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -44,9 +44,14 @@ public: virtual ~IMUFactor() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** Check if two factors are equal */ virtual bool equals(const NonlinearFactor& e, double tol = 1e-9) const { - const This* const f = dynamic_cast(&e); + const This* const f = dynamic_cast(&e); return f && Base::equals(e) && equal_with_abs_tol(accel_, f->accel_, tol) && equal_with_abs_tol(gyro_, f->gyro_, tol) && @@ -65,8 +70,6 @@ public: const Vector& gyro() const { return gyro_; } const Vector& accel() const { return accel_; } Vector z() const { return concatVectors(2, &accel_, &gyro_); } - const Key& key1() const { return this->key1_; } - const Key& key2() const { return this->key2_; } /** * Error evaluation with optional derivatives - calculates diff --git a/gtsam_unstable/dynamics/PoseRTV.cpp b/gtsam_unstable/dynamics/PoseRTV.cpp index 4ab4bcf1d..c10885fc0 100644 --- a/gtsam_unstable/dynamics/PoseRTV.cpp +++ b/gtsam_unstable/dynamics/PoseRTV.cpp @@ -10,7 +10,6 @@ #include #include -#include #include namespace gtsam { @@ -201,7 +200,7 @@ Vector PoseRTV::imuPrediction(const PoseRTV& x2, double dt) const { // rotation rates // just using euler angles based on matlab code // FIXME: this is silly - we shouldn't use differences in Euler angles - Matrix Enb = dynamics::RRTMnb(r1); + Matrix Enb = RRTMnb(r1); Vector euler1 = r1.xyz(), euler2 = r2.xyz(); Vector dR = euler2 - euler1; @@ -258,7 +257,7 @@ PoseRTV PoseRTV::transformed_from(const Pose3& trans, } if (Dtrans) { - *Dtrans = numericalDerivative22(transformed_from_, *this, trans, 1e-6); + *Dtrans = numericalDerivative22(transformed_from_, *this, trans, 1e-8); // // *Dtrans = zeros(9,6); // // directly affecting the pose @@ -276,4 +275,39 @@ PoseRTV PoseRTV::transformed_from(const Pose3& trans, return PoseRTV(newpose, newvel); } +/* ************************************************************************* */ +Matrix PoseRTV::RRTMbn(const Vector& euler) { + assert(euler.size() == 3); + const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); + const double t2 = tan(euler(2-1)), c2 = cos(euler(2-1)); + Matrix Ebn(3,3); + Ebn << 1.0, s1 * t2, c1 * t2, + 0.0, c1, -s1, + 0.0, s1 / c2, c1 / c2; + return Ebn; +} + +/* ************************************************************************* */ +Matrix PoseRTV::RRTMbn(const Rot3& att) { + return PoseRTV::RRTMbn(att.rpy()); +} + +/* ************************************************************************* */ +Matrix PoseRTV::RRTMnb(const Vector& euler) { + assert(euler.size() == 3); + Matrix Enb(3,3); + const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); + const double s2 = sin(euler(2-1)), c2 = cos(euler(2-1)); + Enb << 1.0, 0.0, -s2, + 0.0, c1, s1*c2, + 0.0, -s1, c1*c2; + return Enb; +} + +/* ************************************************************************* */ +Matrix PoseRTV::RRTMnb(const Rot3& att) { + return PoseRTV::RRTMnb(att.rpy()); +} + +/* ************************************************************************* */ } // \namespace gtsam diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index b2e325f53..077756f56 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -153,6 +153,20 @@ public: boost::optional Dglobal=boost::none, boost::optional Dtrans=boost::none) const; + // Utility functions + + /// RRTMbn - Function computes the rotation rate transformation matrix from + /// body axis rates to euler angle (global) rates + static Matrix RRTMbn(const Vector& euler); + + static Matrix RRTMbn(const Rot3& att); + + /// RRTMnb - Function computes the rotation rate transformation matrix from + /// euler angle rates to body axis rates + static Matrix RRTMnb(const Vector& euler); + + static Matrix RRTMnb(const Rot3& att); + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index a35f09bb7..801bf12cd 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -72,6 +72,11 @@ public: virtual ~VelocityConstraint() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new VelocityConstraint(*this))); } + /** * Calculates the error for trapezoidal model given */ diff --git a/gtsam_unstable/dynamics/imuSystem.cpp b/gtsam_unstable/dynamics/imuSystem.cpp deleted file mode 100644 index 209615bcc..000000000 --- a/gtsam_unstable/dynamics/imuSystem.cpp +++ /dev/null @@ -1,63 +0,0 @@ -/** - * @file ilm3DSystem.cpp - * @brief Implementations of ilm 3D domain - * @author Alex Cunningham - */ - -#include -#include - -namespace imu { - -using namespace gtsam; - -/* ************************************************************************* */ -void Graph::addPrior(Key key, const PoseRTV& pose, const SharedNoiseModel& noiseModel) { - add(Prior(PoseKey(key), pose, noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addConstraint(Key key, const PoseRTV& pose) { - add(Constraint(PoseKey(key), pose)); -} - -/* ************************************************************************* */ -void Graph::addHeightPrior(Key key, double z, const SharedNoiseModel& noiseModel) { - add(DHeightPrior(PoseKey(key), z, noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addFullIMUMeasurement(Key key1, Key key2, - const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel) { - add(FullIMUMeasurement(accel, gyro, dt, PoseKey(key1), PoseKey(key2), noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addIMUMeasurement(Key key1, Key key2, - const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel) { - add(IMUMeasurement(accel, gyro, dt, PoseKey(key1), PoseKey(key2), noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addVelocityConstraint(Key key1, Key key2, double dt, const SharedNoiseModel& noiseModel) { - add(VelocityConstraint(PoseKey(key1), PoseKey(key2), dt, noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addBetween(Key key1, Key key2, const PoseRTV& z, const SharedNoiseModel& noiseModel) { - add(Between(PoseKey(key1), PoseKey(key2), z, noiseModel)); -} - -/* ************************************************************************* */ -void Graph::addRange(Key key1, Key key2, double z, const SharedNoiseModel& noiseModel) { - add(Range(PoseKey(key1), PoseKey(key2), z, noiseModel)); -} - -/* ************************************************************************* */ -Values Graph::optimize(const Values& init) const { - return LevenbergMarquardtOptimizer(*this, init).optimize(); -} -/* ************************************************************************* */ - -} // \namespace imu - diff --git a/gtsam_unstable/dynamics/imuSystem.h b/gtsam_unstable/dynamics/imuSystem.h deleted file mode 100644 index b0bee8873..000000000 --- a/gtsam_unstable/dynamics/imuSystem.h +++ /dev/null @@ -1,88 +0,0 @@ -/** - * @file imuSystem.h - * @brief A 3D Dynamic system domain as a demonstration of IMU factors - * @author Alex Cunningham - */ - -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -/** - * This domain focuses on a single class of variables: PoseRTV, which - * models a dynamic pose operating with IMU measurements and assorted priors. - * - * There are also partial priors that constraint certain components of the - * poses, as well as between and range factors to model other between-pose - * information. - */ -namespace imu { - -using namespace gtsam; - -// Values: just poses -inline Symbol PoseKey(Index j) { return Symbol('x', j); } - -struct Values : public gtsam::Values { - typedef gtsam::Values Base; - - Values() {} - Values(const Values& values) : Base(values) {} - Values(const Base& values) : Base(values) {} - - void insertPose(Index key, const PoseRTV& pose) { insert(PoseKey(key), pose); } - PoseRTV pose(Index key) const { return at(PoseKey(key)); } -}; - -// factors -typedef IMUFactor IMUMeasurement; // IMU between measurements -typedef FullIMUFactor FullIMUMeasurement; // Full-state IMU between measurements -typedef BetweenFactor Between; // full odometry (including velocity) -typedef NonlinearEquality Constraint; -typedef PriorFactor Prior; -typedef RangeFactor Range; - -// graph components -struct Graph : public NonlinearFactorGraph { - typedef NonlinearFactorGraph Base; - - Graph() {} - Graph(const Base& graph) : Base(graph) {} - Graph(const Graph& graph) : Base(graph) {} - - // prior factors - void addPrior(size_t key, const PoseRTV& pose, const SharedNoiseModel& noiseModel); - void addConstraint(size_t key, const PoseRTV& pose); - void addHeightPrior(size_t key, double z, const SharedNoiseModel& noiseModel); - - // inertial factors - void addFullIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel); - void addIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel); - void addVelocityConstraint(size_t key1, size_t key2, double dt, const SharedNoiseModel& noiseModel); - - // other measurements - void addBetween(size_t key1, size_t key2, const PoseRTV& z, const SharedNoiseModel& noiseModel); - void addRange(size_t key1, size_t key2, double z, const SharedNoiseModel& noiseModel); - - // optimization - Values optimize(const Values& init) const; -}; - -} // \namespace imu - diff --git a/gtsam_unstable/dynamics/imu_examples.h b/gtsam_unstable/dynamics/imu_examples.h deleted file mode 100644 index 90bbc9d8b..000000000 --- a/gtsam_unstable/dynamics/imu_examples.h +++ /dev/null @@ -1,273 +0,0 @@ -/** - * @file imu_examples.h - * @brief Example measurements from ACFR matlab simulation - * @author Alex Cunningham - */ - -#pragma once - -#include -#include - -namespace gtsam { -namespace examples { - -// examples pulled from simulated dataset - -// case pulled from dataset (frame 5000, no noise, flying robot) -namespace frame5000 { -double dt=0.010000; - -// previous frame -gtsam::Point3 posInit( - -34.959663877411039, - -36.312388041359441, - -9.929634578582256); -gtsam::Vector velInit = gtsam::Vector_(3, - -2.325950469365050, - -5.545469040035986, - 0.026939998635121); -gtsam::Vector attInit = gtsam::Vector_(3, - -0.005702574137157, - -0.029956547314287, - 1.625011216344428); - -// IMU measurement (accel (0-2), gyro (3-5)) - from current frame -gtsam::Vector accel = gtsam::Vector_(3, - 1.188806676070333, - -0.183885870345845, - -9.870747316422888); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0, - 0.026142019158168, - -2.617993877991494); - -// resulting frame -gtsam::Point3 posFinal( - -34.982904302954310, - -36.367693859767584, - -9.929367164045985); -gtsam::Vector velFinal = gtsam::Vector_(3, - -2.324042554327658, - -5.530581840815272, - 0.026741453627181); -gtsam::Vector attFinal = gtsam::Vector_(3, - -0.004918046965288, - -0.029844423605949, - 1.598818460739227); - -PoseRTV init (posInit, gtsam::Rot3::RzRyRx(attInit), velInit); -PoseRTV final(posFinal, gtsam::Rot3::RzRyRx(attFinal), velFinal); -} - -// case pulled from dataset (frame 10000, no noise, flying robot) -namespace frame10000 { -double dt=0.010000; - -// previous frame -gtsam::Point3 posInit( - -30.320731549352189, - -1.988742283760434, - -9.946212692656349); -gtsam::Vector velInit = gtsam::Vector_(3, - -0.094887047280235, - -5.200243574047883, - -0.006106911050672); -gtsam::Vector attInit = gtsam::Vector_(3, - -0.049884854704728, - -0.004630595995732, - -1.952691683647753); - -// IMU measurement (accel (0-2), gyro (3-5)) - from current frame -gtsam::Vector accel = gtsam::Vector_(3, - 0.127512027192321, - 0.508566822495083, - -9.987963604829643); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0, - 0.004040957322961, - 2.617993877991494); - -// resulting frame -gtsam::Point3 posFinal( - -30.321685191305157, - -2.040760054006146, - -9.946292804391417); -gtsam::Vector velFinal = gtsam::Vector_(3, - -0.095364195297074, - -5.201777024575911, - -0.008011173506779); -gtsam::Vector attFinal = gtsam::Vector_(3, - -0.050005924151669, - -0.003284795837998, - -1.926546047162884); - -PoseRTV init (posInit, gtsam::Rot3::RzRyRx(attInit), velInit); -PoseRTV final(posFinal, gtsam::Rot3::RzRyRx(attFinal), velFinal); -} - -// case pulled from dataset (frame at time 4.00, no noise, flying robot, poses from 3.99 to 4.0) -namespace flying400 { -double dt=0.010000; - -// start pose -// time 3.9900000e+00 -// pos (x,y,z) 1.8226188e+01 -6.7168156e+01 -9.8236334e+00 -// vel (dx,dy,dz) -5.2887267e+00 1.6117880e-01 -2.2665072e-02 -// att (r, p, y) 1.0928413e-02 -2.0811771e-02 2.7206011e+00 - -// previous frame -gtsam::Point3 posInit( - 1.8226188e+01, -6.7168156e+01, -9.8236334e+00); -gtsam::Vector velInit = gtsam::Vector_(3,-5.2887267e+00, 1.6117880e-01, -2.2665072e-02); -gtsam::Vector attInit = gtsam::Vector_(3, 1.0928413e-02, -2.0811771e-02, 2.7206011e+00); - -// time 4.0000000e+00 -// accel 3.4021509e-01 -3.4413998e-01 -9.8822495e+00 -// gyro 0.0000000e+00 1.8161697e-02 -2.6179939e+00 - -// IMU measurement (accel (0-2), gyro (3-5)) - ax, ay, az, r, p, y -gtsam::Vector accel = gtsam::Vector_(3, - 3.4021509e-01, -3.4413998e-01, -9.8822495e+00); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0000000e+00, 1.8161697e-02, -2.6179939e+00); // original version (possibly r, p, y) - -// final pose -// time 4.0000000e+00 -// pos (x,y,z) 1.8173262e+01 -6.7166500e+01 -9.8238667e+00 -// vel (vx,vy,vz) -5.2926092e+00 1.6559974e-01 -2.3330881e-02 -// att (r, p, y) 1.1473269e-02 -2.0344066e-02 2.6944191e+00 - -// resulting frame -gtsam::Point3 posFinal(1.8173262e+01, -6.7166500e+01, -9.8238667e+00); -gtsam::Vector velFinal = gtsam::Vector_(3,-5.2926092e+00, 1.6559974e-01, -2.3330881e-02); -gtsam::Vector attFinal = gtsam::Vector_(3, 1.1473269e-02, -2.0344066e-02, 2.6944191e+00); - -// full states -PoseRTV init (posInit, gtsam::Rot3::ypr( attInit(2), attInit(1), attInit(0)), velInit); -PoseRTV final(posFinal, gtsam::Rot3::ypr(attFinal(2), attFinal(1), attFinal(0)), velFinal); - -} // \namespace flying400 - -namespace flying650 { -double dt=0.010000; - -// from time 6.49 to 6.50 in robot F2 - - -// frame (6.49) -// 6.4900000e+00 -3.8065039e+01 -6.4788024e+01 -9.8947445e+00 -5.0099274e+00 1.5999675e-01 -1.7762191e-02 -5.7708025e-03 -1.0109000e-02 -3.0465662e+00 -gtsam::Point3 posInit( - -3.8065039e+01, -6.4788024e+01, -9.8947445e+00); -gtsam::Vector velInit = gtsam::Vector_(3,-5.0099274e+00, 1.5999675e-01, -1.7762191e-02); -gtsam::Vector attInit = gtsam::Vector_(3,-5.7708025e-03, -1.0109000e-02, -3.0465662e+00); - -// IMU measurement (accel (0-2), gyro (3-5)) - ax, ay, az, r, p, y -// 6.5000000e+00 -9.2017256e-02 8.6770069e-02 -9.8213017e+00 0.0000000e+00 1.0728860e-02 -2.6179939e+00 -gtsam::Vector accel = gtsam::Vector_(3, - -9.2017256e-02, 8.6770069e-02, -9.8213017e+00); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0000000e+00, 1.0728860e-02, -2.6179939e+00); // in r,p,y - -// resulting frame (6.50) -// 6.5000000e+00 -3.8115139e+01 -6.4786428e+01 -9.8949233e+00 -5.0099817e+00 1.5966531e-01 -1.7882777e-02 -5.5061386e-03 -1.0152792e-02 -3.0727477e+00 -gtsam::Point3 posFinal(-3.8115139e+01, -6.4786428e+01, -9.8949233e+00); -gtsam::Vector velFinal = gtsam::Vector_(3,-5.0099817e+00, 1.5966531e-01, -1.7882777e-02); -gtsam::Vector attFinal = gtsam::Vector_(3,-5.5061386e-03, -1.0152792e-02, -3.0727477e+00); - -// full states -PoseRTV init (posInit, gtsam::Rot3::ypr( attInit(2), attInit(1), attInit(0)), velInit); -PoseRTV final(posFinal, gtsam::Rot3::ypr(attFinal(2), attFinal(1), attFinal(0)), velFinal); - -} // \namespace flying650 - - -namespace flying39 { -double dt=0.010000; - -// from time 0.38 to 0.39 in robot F1 - -// frame (0.38) -// 3.8000000e-01 3.4204706e+01 -6.7413834e+01 -9.9996055e+00 -2.2484370e-02 -1.3603911e-03 1.5267496e-02 7.9033358e-04 -1.4946656e-02 -3.1174147e+00 -gtsam::Point3 posInit( 3.4204706e+01, -6.7413834e+01, -9.9996055e+00); -gtsam::Vector velInit = gtsam::Vector_(3,-2.2484370e-02, -1.3603911e-03, 1.5267496e-02); -gtsam::Vector attInit = gtsam::Vector_(3, 7.9033358e-04, -1.4946656e-02, -3.1174147e+00); - -// IMU measurement (accel (0-2), gyro (3-5)) - ax, ay, az, r, p, y -// 3.9000000e-01 7.2229967e-01 -9.5790214e-03 -9.3943087e+00 0.0000000e+00 -2.9157400e-01 -2.6179939e+00 -gtsam::Vector accel = gtsam::Vector_(3, 7.2229967e-01, -9.5790214e-03, -9.3943087e+00); -gtsam::Vector gyro = gtsam::Vector_(3, 0.0000000e+00, -2.9157400e-01, -2.6179939e+00); // in r,p,y - -// resulting frame (0.39) -// 3.9000000e-01 3.4204392e+01 -6.7413848e+01 -9.9994098e+00 -3.1382246e-02 -1.3577532e-03 1.9568177e-02 1.1816996e-03 -1.7841704e-02 3.1395854e+00 -gtsam::Point3 posFinal(3.4204392e+01, -6.7413848e+01, -9.9994098e+00); -gtsam::Vector velFinal = gtsam::Vector_(3,-3.1382246e-02, -1.3577532e-03, 1.9568177e-02); -gtsam::Vector attFinal = gtsam::Vector_(3, 1.1816996e-03, -1.7841704e-02, 3.1395854e+00); - -// full states -PoseRTV init (posInit, gtsam::Rot3::ypr( attInit(2), attInit(1), attInit(0)), velInit); -PoseRTV final(posFinal, gtsam::Rot3::ypr(attFinal(2), attFinal(1), attFinal(0)), velFinal); - -} // \namespace flying39 - -namespace ground200 { -double dt=0.010000; - -// from time 2.00 to 2.01 in robot G1 - -// frame (2.00) -// 2.0000000e+00 3.6863524e+01 -8.4874053e+01 0.0000000e+00 -7.9650687e-01 1.8345508e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 1.9804083e+00 -gtsam::Point3 posInit(3.6863524e+01, -8.4874053e+01, 0.0000000e+00); -gtsam::Vector velInit = gtsam::Vector_(3,-7.9650687e-01, 1.8345508e+00, 0.0000000e+00); -gtsam::Vector attInit = gtsam::Vector_(3, 0.0000000e+00, 0.0000000e+00, 1.9804083e+00); - -// IMU measurement (accel (0-2), gyro (3-5)) - ax, ay, az, r, p, y -// 2.0100000e+00 1.0000000e+00 8.2156504e-15 -9.8100000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 -gtsam::Vector accel = gtsam::Vector_(3, - 1.0000000e+00, 8.2156504e-15, -9.8100000e+00); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0000000e+00, 0.0000000e+00, 0.0000000e+00); // in r,p,y - -// resulting frame (2.01) -// 2.0100000e+00 3.6855519e+01 -8.4855615e+01 0.0000000e+00 -8.0048940e-01 1.8437236e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 1.9804083e+00 -gtsam::Point3 posFinal(3.6855519e+01, -8.4855615e+01, 0.0000000e+00); -gtsam::Vector velFinal = gtsam::Vector_(3,-8.0048940e-01, 1.8437236e+00, 0.0000000e+00); -gtsam::Vector attFinal = gtsam::Vector_(3, 0.0000000e+00, 0.0000000e+00, 1.9804083e+00); - -// full states -PoseRTV init (posInit, gtsam::Rot3::ypr( attInit(2), attInit(1), attInit(0)), velInit); -PoseRTV final(posFinal, gtsam::Rot3::ypr(attFinal(2), attFinal(1), attFinal(0)), velFinal); - -} // \namespace ground200 - -namespace ground600 { -double dt=0.010000; - -// from time 6.00 to 6.01 in robot G1 - -// frame (6.00) -// 6.0000000e+00 3.0320057e+01 -7.0883904e+01 0.0000000e+00 -4.0020377e+00 2.9972811e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 2.4987711e+00 -gtsam::Point3 posInit(3.0320057e+01, -7.0883904e+01, 0.0000000e+00); -gtsam::Vector velInit = gtsam::Vector_(3,-4.0020377e+00, 2.9972811e+00, 0.0000000e+00); -gtsam::Vector attInit = gtsam::Vector_(3, 0.0000000e+00, 0.0000000e+00, 2.4987711e+00); - -// IMU measurement (accel (0-2), gyro (3-5)) - ax, ay, az, r, p, y -// 6.0100000e+00 6.1683759e-02 7.8536587e+00 -9.8100000e+00 0.0000000e+00 0.0000000e+00 1.5707963e+00 -gtsam::Vector accel = gtsam::Vector_(3, - 6.1683759e-02, 7.8536587e+00, -9.8100000e+00); -gtsam::Vector gyro = gtsam::Vector_(3, - 0.0000000e+00, 0.0000000e+00, 1.5707963e+00); // in r,p,y - -// resulting frame (6.01) -// 6.0100000e+00 3.0279571e+01 -7.0854564e+01 0.0000000e+00 -4.0486232e+00 2.9340501e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 2.5144791e+00 -gtsam::Point3 posFinal(3.0279571e+01, -7.0854564e+01, 0.0000000e+00); -gtsam::Vector velFinal = gtsam::Vector_(3,-4.0486232e+00, 2.9340501e+00, 0.0000000e+00); -gtsam::Vector attFinal = gtsam::Vector_(3, 0.0000000e+00, 0.0000000e+00, 2.5144791e+00); - -// full states -PoseRTV init (posInit, gtsam::Rot3::ypr( attInit(2), attInit(1), attInit(0)), velInit); -PoseRTV final(posFinal, gtsam::Rot3::ypr(attFinal(2), attFinal(1), attFinal(0)), velFinal); - -} // \namespace ground600 - -} // \namespace examples -} // \namespace gtsam diff --git a/gtsam_unstable/dynamics/inertialUtils.cpp b/gtsam_unstable/dynamics/inertialUtils.cpp deleted file mode 100644 index 94d99f690..000000000 --- a/gtsam_unstable/dynamics/inertialUtils.cpp +++ /dev/null @@ -1,51 +0,0 @@ -/** - * @file inertialUtils.cpp - * - * @date Nov 28, 2011 - * @author Alex Cunningham - */ - -#include - -namespace gtsam { -namespace dynamics { - -/* ************************************************************************* */ -Matrix RRTMbn(const Vector& euler) { - assert(euler.size() == 3); - const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); - const double t2 = tan(euler(2-1)), c2 = cos(euler(2-1)); - Matrix Ebn(3,3); - Ebn << 1.0, s1 * t2, c1 * t2, - 0.0, c1, -s1, - 0.0, s1 / c2, c1 / c2; - return Ebn; -} - -/* ************************************************************************* */ -Matrix RRTMbn(const Rot3& att) { - return RRTMbn(att.rpy()); -} - -/* ************************************************************************* */ -Matrix RRTMnb(const Vector& euler) { - assert(euler.size() == 3); - Matrix Enb(3,3); - const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); - const double s2 = sin(euler(2-1)), c2 = cos(euler(2-1)); - Enb << 1.0, 0.0, -s2, - 0.0, c1, s1*c2, - 0.0, -s1, c1*c2; - return Enb; -} - -/* ************************************************************************* */ -Matrix RRTMnb(const Rot3& att) { - return RRTMnb(att.rpy()); -} - -} // \namespace dynamics -} // \namespace gtsam - - - diff --git a/gtsam_unstable/dynamics/inertialUtils.h b/gtsam_unstable/dynamics/inertialUtils.h deleted file mode 100644 index 250ed3abe..000000000 --- a/gtsam_unstable/dynamics/inertialUtils.h +++ /dev/null @@ -1,32 +0,0 @@ -/** - * @file inertialUtils.h - * - * @brief Utility functions for working with dynamic systems - derived from Mitch's matlab code - * This is mostly just syntactic sugar for working with dynamic systems that use - * Euler angles to specify the orientation of a robot. - * - * @date Nov 28, 2011 - * @author Alex Cunningham - */ - -#pragma once - -#include - -namespace gtsam { -namespace dynamics { - -/// RRTMbn - Function computes the rotation rate transformation matrix from -/// body axis rates to euler angle (global) rates -Matrix RRTMbn(const Vector& euler); - -Matrix RRTMbn(const Rot3& att); - -/// RRTMnb - Function computes the rotation rate transformation matrix from -/// euler angle rates to body axis rates -Matrix RRTMnb(const Vector& euler); - -Matrix RRTMnb(const Rot3& att); - -} // \namespace dynamics -} // \namespace gtsam diff --git a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp index ad66b2b60..01c7925b3 100644 --- a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp +++ b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp @@ -3,26 +3,35 @@ * @author Alex Cunningham */ +#include + #include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; using namespace gtsam; -using namespace imu; const double tol=1e-5; +static const Key x0 = 0, x1 = 1, x2 = 2, x3 = 3, x4 = 4; static const Vector g = delta(3, 2, -9.81); -Key x1 = PoseKey(1), x2 = PoseKey(2), x3 = PoseKey(3), x4 = PoseKey(4); - /* ************************************************************************* */ TEST(testIMUSystem, instantiations) { // just checking for compilation PoseRTV x1_v; - imu::Values local_values; - Graph graph; gtsam::SharedNoiseModel model1 = gtsam::noiseModel::Unit::Create(1); gtsam::SharedNoiseModel model3 = gtsam::noiseModel::Unit::Create(3); @@ -31,13 +40,13 @@ TEST(testIMUSystem, instantiations) { Vector accel = ones(3), gyro = ones(3); - IMUMeasurement imu(accel, gyro, 0.01, x1, x2, model6); - FullIMUMeasurement full_imu(accel, gyro, 0.01, x1, x2, model9); - Constraint poseHardPrior(x1, x1_v); - Between odom(x1, x2, x1_v, model9); - Range range(x1, x2, 1.0, model1); + IMUFactor imu(accel, gyro, 0.01, x1, x2, model6); + FullIMUFactor full_imu(accel, gyro, 0.01, x1, x2, model9); + NonlinearEquality poseHardPrior(x1, x1_v); + BetweenFactor odom(x1, x2, x1_v, model9); + RangeFactor range(x1, x2, 1.0, model1); VelocityConstraint constraint(x1, x2, 0.1, 10000); - Prior posePrior(x1, x1_v, model9); + PriorFactor posePrior(x1, x1_v, model9); DHeightPrior heightPrior(x1, 0.1, model1); VelocityPrior velPrior(x1, ones(3), model3); } @@ -59,17 +68,17 @@ TEST( testIMUSystem, optimize_chain ) { imu34 = pose3.imuPrediction(pose4, dt); // assemble simple graph with IMU measurements and velocity constraints - Graph graph; - graph.add(Constraint(x1, pose1)); - graph.add(IMUMeasurement(imu12, dt, x1, x2, model)); - graph.add(IMUMeasurement(imu23, dt, x2, x3, model)); - graph.add(IMUMeasurement(imu34, dt, x3, x4, model)); + NonlinearFactorGraph graph; + graph.add(NonlinearEquality(x1, pose1)); + graph.add(IMUFactor(imu12, dt, x1, x2, model)); + graph.add(IMUFactor(imu23, dt, x2, x3, model)); + graph.add(IMUFactor(imu34, dt, x3, x4, model)); graph.add(VelocityConstraint(x1, x2, dt)); graph.add(VelocityConstraint(x2, x3, dt)); graph.add(VelocityConstraint(x3, x4, dt)); // ground truth values - imu::Values true_values; + Values true_values; true_values.insert(x1, pose1); true_values.insert(x2, pose2); true_values.insert(x3, pose3); @@ -79,13 +88,13 @@ TEST( testIMUSystem, optimize_chain ) { EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5); // initialize with zero values and optimize - imu::Values values; + Values values; values.insert(x1, PoseRTV()); values.insert(x2, PoseRTV()); values.insert(x3, PoseRTV()); values.insert(x4, PoseRTV()); - imu::Values actual = graph.optimize(values); + Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); EXPECT(assert_equal(true_values, actual, tol)); } @@ -106,14 +115,14 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) { imu34 = pose3.imuPrediction(pose4, dt); // assemble simple graph with IMU measurements and velocity constraints - Graph graph; - graph.add(Constraint(x1, pose1)); - graph.add(FullIMUMeasurement(imu12, dt, x1, x2, model)); - graph.add(FullIMUMeasurement(imu23, dt, x2, x3, model)); - graph.add(FullIMUMeasurement(imu34, dt, x3, x4, model)); + NonlinearFactorGraph graph; + graph.add(NonlinearEquality(x1, pose1)); + graph.add(FullIMUFactor(imu12, dt, x1, x2, model)); + graph.add(FullIMUFactor(imu23, dt, x2, x3, model)); + graph.add(FullIMUFactor(imu34, dt, x3, x4, model)); // ground truth values - imu::Values true_values; + Values true_values; true_values.insert(x1, pose1); true_values.insert(x2, pose2); true_values.insert(x3, pose3); @@ -123,7 +132,7 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) { EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5); // initialize with zero values and optimize - imu::Values values; + Values values; values.insert(x1, PoseRTV()); values.insert(x2, PoseRTV()); values.insert(x3, PoseRTV()); @@ -131,42 +140,10 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) { cout << "Initial Error: " << graph.error(values) << endl; // Initial error is 0.5 - need better prediction model - imu::Values actual = graph.optimize(values); + Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); // EXPECT(assert_equal(true_values, actual, tol)); // FAIL } -///* ************************************************************************* */ -//TEST( testIMUSystem, imu_factor_basics ) { -// using namespace examples; -// PoseKey x1(1), x2(2); -// SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(6, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6)); -// IMUMeasurement factor(frame5000::accel, frame5000::gyro, frame5000::dt, x1, x2, model); -// -// EXPECT(assert_equal(x1, factor.key1())); -// EXPECT(assert_equal(x2, factor.key2())); -// EXPECT(assert_equal(frame5000::accel, factor.accel(), tol)); -// EXPECT(assert_equal(frame5000::gyro, factor.gyro(), tol)); -// Vector full_meas = concatVectors(2, &frame5000::accel, &frame5000::gyro); -// EXPECT(assert_equal(full_meas, factor.z(), tol)); -//} -// -///* ************************************************************************* */ -//TEST( testIMUSystem, imu_factor_predict_function ) { -// using namespace examples; -// PoseKey x1(1), x2(2); -// SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(6, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6)); -// IMUMeasurement factor(frame5000::accel, frame5000::gyro, frame5000::dt, x1, x2, model); -// -// // verify zero error -// Vector actZeroError = factor.evaluateError(frame5000::init, frame5000::final); -// EXPECT(assert_equal(zero(6), actZeroError, tol)); -// -// // verify nonzero error - z-h(x) -// Vector actError = factor.evaluateError(frame10000::init, frame10000::final); -// Vector meas10k = concatVectors(2, &frame10000::accel, &frame10000::gyro); -// EXPECT(assert_equal(factor.z() - meas10k, actError, tol)); -//} - /* ************************************************************************* */ TEST( testIMUSystem, linear_trajectory) { // create a linear trajectory of poses @@ -178,24 +155,23 @@ TEST( testIMUSystem, linear_trajectory) { Vector gyro = delta(3, 0, 0.1); // constant rotation SharedDiagonal model = noiseModel::Unit::Create(9); - imu::Values true_traj, init_traj; - Graph graph; + Values true_traj, init_traj; + NonlinearFactorGraph graph; - graph.add(Constraint(PoseKey(0), start)); - true_traj.insert(PoseKey(0), start); - init_traj.insert(PoseKey(0), start); + graph.add(NonlinearEquality(x0, start)); + true_traj.insert(x0, start); + init_traj.insert(x0, start); size_t nrPoses = 10; PoseRTV cur_pose = start; for (size_t i=1; i(accel - g, gyro, dt, xA, xB, model)); true_traj.insert(xB, cur_pose); init_traj.insert(xB, PoseRTV()); } // EXPECT_DOUBLES_EQUAL(0, graph.error(true_traj), 1e-5); // FAIL - } /* ************************************************************************* */ diff --git a/gtsam_unstable/dynamics/tests/testInertialUtils.cpp b/gtsam_unstable/dynamics/tests/testInertialUtils.cpp deleted file mode 100644 index 5360aaae8..000000000 --- a/gtsam_unstable/dynamics/tests/testInertialUtils.cpp +++ /dev/null @@ -1,34 +0,0 @@ -/** - * @file testInertialUtils.cpp - * - * @brief Conversions for the utility functions from the matlab implementation - * - * @date Nov 28, 2011 - * @author Alex Cunningham - */ - -#include - -#include - -using namespace gtsam; - -static const double tol = 1e-5; - -/* ************************************************************************* */ -TEST(testInertialUtils, RRTMbn) { - EXPECT(assert_equal(Matrix::Identity(3,3), dynamics::RRTMbn(zero(3)), tol)); - EXPECT(assert_equal(Matrix::Identity(3,3), dynamics::RRTMbn(Rot3()), tol)); - EXPECT(assert_equal(dynamics::RRTMbn(Vector_(3, 0.3, 0.2, 0.1)), dynamics::RRTMbn(Rot3::ypr(0.1, 0.2, 0.3)), tol)); -} - -/* ************************************************************************* */ -TEST(testInertialUtils, RRTMnb) { - EXPECT(assert_equal(Matrix::Identity(3,3), dynamics::RRTMnb(zero(3)), tol)); - EXPECT(assert_equal(Matrix::Identity(3,3), dynamics::RRTMnb(Rot3()), tol)); - EXPECT(assert_equal(dynamics::RRTMnb(Vector_(3, 0.3, 0.2, 0.1)), dynamics::RRTMnb(Rot3::ypr(0.1, 0.2, 0.3)), tol)); -} - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ diff --git a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp index 381971502..1444f69fc 100644 --- a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp +++ b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp @@ -9,7 +9,6 @@ #include #include -#include using namespace gtsam; @@ -119,85 +118,6 @@ TEST( testPoseRTV, dynamics_identities ) { // EXPECT(assert_equal(x4.translation(), x3.imuPrediction(x4, dt).second, tol)); } -///* ************************************************************************* */ -//TEST( testPoseRTV, constant_velocity ) { -// double dt = 1.0; -// PoseRTV init(Rot3(), Point3(1.0, 2.0, 3.0), Vector_(3, 0.5, 0.0, 0.0)); -// PoseRTV final(Rot3(), Point3(1.5, 2.0, 3.0), Vector_(3, 0.5, 0.0, 0.0)); -// -// // constant velocity, so gyro is zero, but accel includes gravity -// Vector accel = delta(3, 2, -9.81), gyro = zero(3); -// -// // perform integration -// PoseRTV actFinal = init.integrate(accel, gyro, dt); -// EXPECT(assert_equal(final, actFinal, tol)); -// -// // perform prediction -// Vector actAccel, actGyro; -// boost::tie(actAccel, actGyro) = init.predict(final, dt); -// EXPECT(assert_equal(accel, actAccel, tol)); -// EXPECT(assert_equal(gyro, actGyro, tol)); -//} -// -///* ************************************************************************* */ -//TEST( testPoseRTV, frame10000_imu ) { -// using namespace examples; -// -// // perform integration -// PoseRTV actFinal = frame10000::init.integrate(frame10000::accel, frame10000::gyro, frame10000::dt); -// EXPECT(assert_equal(frame10000::final, actFinal, tol)); -// -// // perform prediction -// Vector actAccel, actGyro; -// boost::tie(actAccel, actGyro) = frame10000::init.predict(frame10000::final, frame10000::dt); -// EXPECT(assert_equal(frame10000::accel, actAccel, tol)); -// EXPECT(assert_equal(frame10000::gyro, actGyro, tol)); -//} -// -///* ************************************************************************* */ -//TEST( testPoseRTV, frame5000_imu ) { -// using namespace examples; -// -// // perform integration -// PoseRTV actFinal = frame5000::init.integrate(frame5000::accel, frame5000::gyro, frame5000::dt); -// EXPECT(assert_equal(frame5000::final, actFinal, tol)); -// -// // perform prediction -// Vector actAccel, actGyro; -// boost::tie(actAccel, actGyro) = frame5000::init.predict(frame5000::final, frame5000::dt); -// EXPECT(assert_equal(frame5000::accel, actAccel, tol)); -// EXPECT(assert_equal(frame5000::gyro, actGyro, tol)); -//} -// -///* ************************************************************************* */ -//TEST( testPoseRTV, time4_imu ) { -// using namespace examples::flying400; -// -// // perform integration -// PoseRTV actFinal = init.integrate(accel, gyro, dt); -// EXPECT(assert_equal(final, actFinal, tol)); -// -// // perform prediction -// Vector actAccel, actGyro; -// boost::tie(actAccel, actGyro) = init.predict(final, dt); -// EXPECT(assert_equal(accel, actAccel, tol)); -// EXPECT(assert_equal(gyro, actGyro, tol)); -//} -// -///* ************************************************************************* */ -//TEST( testPoseRTV, time65_imu ) { -// using namespace examples::flying650; -// -// // perform integration -// PoseRTV actFinal = init.integrate(accel, gyro, dt); -// EXPECT(assert_equal(final, actFinal, tol)); -// -// // perform prediction -// Vector actAccel, actGyro; -// boost::tie(actAccel, actGyro) = init.predict(final, dt); -// EXPECT(assert_equal(accel, actAccel, tol)); -// EXPECT(assert_equal(gyro, actGyro, tol)); -//} /* ************************************************************************* */ double range_proxy(const PoseRTV& A, const PoseRTV& B) { return A.range(B); } @@ -232,8 +152,8 @@ TEST( testPoseRTV, transformed_from_1 ) { PoseRTV expected(transform.compose(start.pose()), transform.rotation().rotate(V)); EXPECT(assert_equal(expected, actual, tol)); - Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-8); - Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); + Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails + Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size EXPECT(assert_equal(numDGlobal, actDGlobal, tol)); EXPECT(assert_equal(numDTrans, actDTrans, tol)); // FIXME: still needs analytic derivative } @@ -251,138 +171,25 @@ TEST( testPoseRTV, transformed_from_2 ) { PoseRTV expected(transform.compose(start.pose()), transform.rotation().rotate(V)); EXPECT(assert_equal(expected, actual, tol)); - Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-8); - Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); + Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails + Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size EXPECT(assert_equal(numDGlobal, actDGlobal, tol)); EXPECT(assert_equal(numDTrans, actDTrans, tol)); // FIXME: still needs analytic derivative } /* ************************************************************************* */ -// ground robot maximums -//const static double ground_max_accel = 1.0; // m/s^2 -//const static double ground_mag_vel = 5.0; // m/s - fixed in simulator +TEST(testPoseRTV, RRTMbn) { + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(zero(3)), tol)); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(Rot3()), tol)); + EXPECT(assert_equal(PoseRTV::RRTMbn(Vector_(3, 0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::ypr(0.1, 0.2, 0.3)), tol)); +} -///* ************************************************************************* */ -//TEST(testPoseRTV, flying_integration650) { -// using namespace examples; -// const PoseRTV &x1 = flying650::init, &x2 = flying650::final; -// Vector accel = flying650::accel, gyro = flying650::gyro; -// double dt = flying650::dt; -// -// // control inputs -// double pitch_rate = gyro(1), -// heading_rate = gyro(2), -// lift_control = 0.0; /// FIXME: need to find this value -// -// PoseRTV actual_x2; -// actual_x2 = x1.flyingDynamics(pitch_rate, heading_rate, lift_control, dt); -// -// // FIXME: enable remaining components when there the lift control value is known -// EXPECT(assert_equal(x2.R(), actual_x2.R(), tol)); -//// EXPECT(assert_equal(x2.t(), actual_x2.t(), tol)); -//// EXPECT(assert_equal(x2.v(), actual_x2.v(), tol)); -//} - -///* ************************************************************************* */ -//TEST(testPoseRTV, imu_prediction650) { -// using namespace examples; -// const PoseRTV &x1 = flying650::init, &x2 = flying650::final; -// Vector accel = flying650::accel, gyro = flying650::gyro; -// double dt = flying650::dt; -// -// // given states, predict the imu measurement and t2 (velocity constraint) -// Vector actual_imu; -// Point3 actual_t2; -// boost::tie(actual_imu, actual_t2) = x1.imuPrediction(x2, dt); -// -// EXPECT(assert_equal(x2.t(), actual_t2, tol)); -// EXPECT(assert_equal(accel, actual_imu.head(3), tol)); -// EXPECT(assert_equal(gyro, actual_imu.tail(3), tol)); -//} -// -///* ************************************************************************* */ -//TEST(testPoseRTV, imu_prediction39) { -// // This case was a known failure case for gyro prediction, returning [9.39091; 0.204952; 625.63] using -// // the general approach for reverse-engineering the gyro updates -// using namespace examples; -// const PoseRTV &x1 = flying39::init, &x2 = flying39::final; -// Vector accel = flying39::accel, gyro = flying39::gyro; -// double dt = flying39::dt; -// -// // given states, predict the imu measurement and t2 (velocity constraint) -// Vector actual_imu; -// Point3 actual_t2; -// boost::tie(actual_imu, actual_t2) = x1.imuPrediction(x2, dt); -// -// EXPECT(assert_equal(x2.t(), actual_t2, tol)); -// EXPECT(assert_equal(accel, actual_imu.head(3), tol)); -// EXPECT(assert_equal(gyro, actual_imu.tail(3), tol)); -//} -// -///* ************************************************************************* */ -//TEST(testPoseRTV, ground_integration200) { -// using namespace examples; -// const PoseRTV &x1 = ground200::init, &x2 = ground200::final; -// Vector accel = ground200::accel, gyro = ground200::gyro; -// double dt = ground200::dt; -// -// // integrates from one pose to the next with known measurements -// // No heading change in this example -// // Hits maximum accel bound in this example -// -// PoseRTV actual_x2; -// actual_x2 = x1.planarDynamics(ground_mag_vel, gyro(2), ground_max_accel, dt); -// -// EXPECT(assert_equal(x2, actual_x2, tol)); -//} -// -///* ************************************************************************* */ -//TEST(testPoseRTV, ground_prediction200) { -// using namespace examples; -// const PoseRTV &x1 = ground200::init, &x2 = ground200::final; -// Vector accel = ground200::accel, gyro = ground200::gyro; -// double dt = ground200::dt; -// -// // given states, predict the imu measurement and t2 (velocity constraint) -// Vector actual_imu; -// Point3 actual_t2; -// boost::tie(actual_imu, actual_t2) = x1.imuPrediction(x2, dt); -// -// EXPECT(assert_equal(x2.t(), actual_t2, tol)); -// EXPECT(assert_equal(accel, actual_imu.head(3), tol)); -// EXPECT(assert_equal(gyro, actual_imu.tail(3), tol)); -//} -// -///* ************************************************************************* */ -//TEST(testPoseRTV, ground_integration600) { -// using namespace examples; -// const PoseRTV &x1 = ground600::init, &x2 = ground600::final; -// Vector accel = ground600::accel, gyro = ground600::gyro; -// double dt = ground600::dt; -// -// // integrates from one pose to the next with known measurements -// PoseRTV actual_x2; -// actual_x2 = x1.planarDynamics(ground_mag_vel, gyro(2), ground_max_accel, dt); -// -// EXPECT(assert_equal(x2, actual_x2, tol)); -//} -// -///* ************************************************************************* */ -//TEST(testPoseRTV, ground_prediction600) { -// using namespace examples; -// const PoseRTV &x1 = ground600::init, &x2 = ground600::final; -// Vector accel = ground600::accel, gyro = ground600::gyro; -// double dt = ground600::dt; -// -// // given states, predict the imu measurement and t2 (velocity constraint) -// Vector actual_imu; -// Point3 actual_t2; -// boost::tie(actual_imu, actual_t2) = x1.imuPrediction(x2, dt); -// -// EXPECT(assert_equal(x2.t(), actual_t2, tol)); -// EXPECT(assert_equal(accel, actual_imu.head(3), tol)); -// EXPECT(assert_equal(gyro, actual_imu.tail(3), tol)); -//} +/* ************************************************************************* */ +TEST(testPoseRTV, RRTMnb) { + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(zero(3)), tol)); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(Rot3()), tol)); + EXPECT(assert_equal(PoseRTV::RRTMnb(Vector_(3, 0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::ypr(0.1, 0.2, 0.3)), tol)); +} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } diff --git a/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp b/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp index eb5950fe7..ea4a3493d 100644 --- a/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp +++ b/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp @@ -4,14 +4,14 @@ */ #include -#include + +#include using namespace gtsam; -using namespace imu; const double tol=1e-5; -Key x1 = PoseKey(1), x2 = PoseKey(2); +const Key x1 = 1, x2 = 2; const double dt = 1.0; PoseRTV origin, diff --git a/gtsam_unstable/geometry/CMakeLists.txt b/gtsam_unstable/geometry/CMakeLists.txt new file mode 100644 index 000000000..d6b6a706d --- /dev/null +++ b/gtsam_unstable/geometry/CMakeLists.txt @@ -0,0 +1,22 @@ +# Install headers +file(GLOB geometry_headers "*.h") +install(FILES ${geometry_headers} DESTINATION include/gtsam_unstable/geometry) + +# Components to link tests in this subfolder against +set(geometry_local_libs + #geometry_unstable # No sources currently, so no convenience lib + geometry + base + ccolamd +) + +set (geometry_full_libs + gtsam-static + gtsam_unstable-static) + +# Exclude tests that don't work +set (geometry_excluded_tests "") + +# Add all tests +gtsam_add_subdir_tests(geometry_unstable "${geometry_local_libs}" "${geometry_full_libs}" "${geometry_excluded_tests}") +add_dependencies(check.unstable check.geometry_unstable) diff --git a/gtsam_unstable/geometry/InvDepthCamera3.h b/gtsam_unstable/geometry/InvDepthCamera3.h new file mode 100644 index 000000000..d0b9ccd88 --- /dev/null +++ b/gtsam_unstable/geometry/InvDepthCamera3.h @@ -0,0 +1,179 @@ + +/** + * @file InvDepthCamera3.h + * @brief + * @author Chris Beall + * @date Apr 14, 2012 + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +/** + * A pinhole camera class that has a Pose3 and a Calibration. + * @ingroup geometry + * \nosubgrouping + */ +template +class InvDepthCamera3 { +private: + Pose3 pose_; + boost::shared_ptr k_; + +public: + + /// @name Standard Constructors + /// @{ + + /** default constructor */ + InvDepthCamera3() {} + + /** constructor with pose and calibration */ + InvDepthCamera3(const Pose3& pose, const boost::shared_ptr& k) : + pose_(pose),k_(k) {} + + /// @} + /// @name Standard Interface + /// @{ + + virtual ~InvDepthCamera3() {} + + /// return pose + inline Pose3& pose() { return pose_; } + + /// return calibration + inline const boost::shared_ptr& calibration() const { return k_; } + + /// print + void print(const std::string& s = "") const { + pose_.print("pose3"); + k_.print("calibration"); + } + + static gtsam::Point3 invDepthTo3D(const gtsam::LieVector& pw, const gtsam::LieScalar& inv) { + gtsam::Point3 ray_base(pw.vector().segment(0,3)); + double theta = pw(3), phi = pw(4); + double rho = inv.value(); // inverse depth + gtsam::Point3 m(cos(theta)*cos(phi),sin(theta)*cos(phi),sin(phi)); + return ray_base + m/rho; + } + + /** project a point from world InvDepth parameterization to the image + * @param pw is a point in the world coordinate + * @param H1 is the jacobian w.r.t. [pose3 calibration] + * @param H2 is the jacobian w.r.t. inv_depth_landmark + */ + inline gtsam::Point2 project(const gtsam::LieVector& pw, + const gtsam::LieScalar& inv_depth, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none, + boost::optional H3 = boost::none) const { + + gtsam::Point3 ray_base(pw.vector().segment(0,3)); + double theta = pw(3), phi = pw(4); + double rho = inv_depth.value(); // inverse depth + gtsam::Point3 m(cos(theta)*cos(phi),sin(theta)*cos(phi),sin(phi)); + const gtsam::Point3 landmark = ray_base + m/rho; + + gtsam::PinholeCamera camera(pose_, *k_); + + if (!H1 && !H2 && !H3) { + gtsam::Point2 uv= camera.project(landmark); + return uv; + } + else { + gtsam::Matrix J2; + gtsam::Point2 uv= camera.project(landmark,H1, J2); + if (H1) { + *H1 = (*H1) * gtsam::eye(6); + } + + double cos_theta = cos(theta); + double sin_theta = sin(theta); + double cos_phi = cos(phi); + double sin_phi = sin(phi); + double rho2 = rho * rho; + + if (H2) { + double H11 = 1; + double H12 = 0; + double H13 = 0; + double H14 = -cos_phi*sin_theta/rho; + double H15 = -cos_theta*sin_phi/rho; + + double H21 = 0; + double H22 = 1; + double H23 = 0; + double H24 = cos_phi*cos_theta/rho; + double H25 = -sin_phi*sin_theta/rho; + + double H31 = 0; + double H32 = 0; + double H33 = 1; + double H34 = 0; + double H35 = cos_phi/rho; + + *H2 = J2 * gtsam::Matrix_(3,5, + H11, H12, H13, H14, H15, + H21, H22, H23, H24, H25, + H31, H32, H33, H34, H35); + } + if(H3) { + double H16 = -cos_phi*cos_theta/rho2; + double H26 = -cos_phi*sin_theta/rho2; + double H36 = -sin_phi/rho2; + *H3 = J2 * gtsam::Matrix_(3,1, + H16, + H26, + H36); + } + return uv; + } + } + + /** + * backproject a 2-dimensional point to an Inverse Depth landmark + * useful for point initialization + */ + + inline std::pair backproject(const gtsam::Point2& pi, const double depth) const { + const gtsam::Point2 pn = k_->calibrate(pi); + gtsam::Point3 pc(pn.x(), pn.y(), 1.0); + pc = pc/pc.norm(); + gtsam::Point3 pw = pose_.transform_from(pc); + const gtsam::Point3& pt = pose_.translation(); + gtsam::Point3 ray = pw - pt; + double theta = atan2(ray.y(), ray.x()); // longitude + double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y())); + return std::make_pair(gtsam::LieVector(5, pt.x(),pt.y(),pt.z(), theta, phi), + gtsam::LieScalar(1./depth)); + } + +private: + + /// @} + /// @name Advanced Interface + /// @{ + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_NVP(pose_); + ar & BOOST_SERIALIZATION_NVP(k_); + } + /// @} +}; // \class InvDepthCamera +} // \namesapce gtsam diff --git a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp new file mode 100644 index 000000000..a69410e34 --- /dev/null +++ b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp @@ -0,0 +1,157 @@ +/* + * testInvDepthFactor.cpp + * + * Created on: Apr 13, 2012 + * Author: cbeall3 + */ + +#include + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); +Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +SimpleCamera level_camera(level_pose, *K); + +/* ************************************************************************* */ +TEST( InvDepthFactor, Project1) { + + // landmark 5 meters infront of camera + Point3 landmark(5, 0, 1); + + Point2 expected_uv = level_camera.project(landmark); + + InvDepthCamera3 inv_camera(level_pose, K); + LieVector inv_landmark(5, 1., 0., 1., 0., 0.); + LieScalar inv_depth(1./4); + Point2 actual_uv = inv_camera.project(inv_landmark, inv_depth); + EXPECT(assert_equal(expected_uv, actual_uv)); + EXPECT(assert_equal(Point2(640,480), actual_uv)); +} + +/* ************************************************************************* */ +TEST( InvDepthFactor, Project2) { + + // landmark 1m to the left and 1m up from camera + // inv landmark xyz is same as camera xyz, so depth actually doesn't matter + Point3 landmark(1, 1, 2); + Point2 expected = level_camera.project(landmark); + + InvDepthCamera3 inv_camera(level_pose, K); + LieVector diag_landmark(5, 0., 0., 1., M_PI/4., atan(1.0/sqrt(2.0))); + LieScalar inv_depth(1/sqrt(3.0)); + Point2 actual = inv_camera.project(diag_landmark, inv_depth); + EXPECT(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST( InvDepthFactor, Project3) { + + // landmark 1m to the left and 1m up from camera + // inv depth landmark xyz at origion + Point3 landmark(1, 1, 2); + Point2 expected = level_camera.project(landmark); + + InvDepthCamera3 inv_camera(level_pose, K); + LieVector diag_landmark(5, 0., 0., 0., M_PI/4., atan(2./sqrt(2.0))); + LieScalar inv_depth( 1./sqrt(1.0+1+4)); + Point2 actual = inv_camera.project(diag_landmark, inv_depth); + EXPECT(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST( InvDepthFactor, Project4) { + + // landmark 4m to the left and 1m up from camera + // inv depth landmark xyz at origion + Point3 landmark(1, 4, 2); + Point2 expected = level_camera.project(landmark); + + InvDepthCamera3 inv_camera(level_pose, K); + LieVector diag_landmark(5, 0., 0., 0., atan(4.0/1), atan(2./sqrt(1.+16.))); + LieScalar inv_depth(1./sqrt(1.+16.+4.)); + Point2 actual = inv_camera.project(diag_landmark, inv_depth); + EXPECT(assert_equal(expected, actual)); +} + + +/* ************************************************************************* */ +Point2 project_(const Pose3& pose, const LieVector& landmark, const LieScalar& inv_depth) { + return InvDepthCamera3(pose,K).project(landmark, inv_depth); } + +TEST( InvDepthFactor, Dproject_pose) +{ + LieVector landmark(6,0.1,0.2,0.3, 0.1,0.2); + LieScalar inv_depth(1./4); + Matrix expected = numericalDerivative31(project_,level_pose, landmark, inv_depth); + InvDepthCamera3 inv_camera(level_pose,K); + Matrix actual; + Point2 uv = inv_camera.project(landmark, inv_depth, actual, boost::none, boost::none); + EXPECT(assert_equal(expected,actual,1e-6)); +} + +/* ************************************************************************* */ +TEST( InvDepthFactor, Dproject_landmark) +{ + LieVector landmark(5,0.1,0.2,0.3, 0.1,0.2); + LieScalar inv_depth(1./4); + Matrix expected = numericalDerivative32(project_,level_pose, landmark, inv_depth); + InvDepthCamera3 inv_camera(level_pose,K); + Matrix actual; + Point2 uv = inv_camera.project(landmark, inv_depth, boost::none, actual, boost::none); + EXPECT(assert_equal(expected,actual,1e-7)); +} + +/* ************************************************************************* */ +TEST( InvDepthFactor, Dproject_inv_depth) +{ + LieVector landmark(5,0.1,0.2,0.3, 0.1,0.2); + LieScalar inv_depth(1./4); + Matrix expected = numericalDerivative33(project_,level_pose, landmark, inv_depth); + InvDepthCamera3 inv_camera(level_pose,K); + Matrix actual; + Point2 uv = inv_camera.project(landmark, inv_depth, boost::none, boost::none, actual); + EXPECT(assert_equal(expected,actual,1e-7)); +} + +/* ************************************************************************* */ +TEST(InvDepthFactor, backproject) +{ + LieVector expected(5,0.,0.,1., 0.1,0.2); + LieScalar inv_depth(1./4); + InvDepthCamera3 inv_camera(level_pose,K); + Point2 z = inv_camera.project(expected, inv_depth); + + LieVector actual_vec; + LieScalar actual_inv; + boost::tie(actual_vec, actual_inv) = inv_camera.backproject(z, 4); + EXPECT(assert_equal(expected,actual_vec,1e-7)); + EXPECT(assert_equal(inv_depth,actual_inv,1e-7)); +} + +/* ************************************************************************* */ +TEST(InvDepthFactor, backproject2) +{ + // backwards facing camera + LieVector expected(5,-5.,-5.,2., 3., -0.1); + LieScalar inv_depth(1./10); + InvDepthCamera3 inv_camera(Pose3(Rot3::ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); + Point2 z = inv_camera.project(expected, inv_depth); + + LieVector actual_vec; + LieScalar actual_inv; + boost::tie(actual_vec, actual_inv) = inv_camera.backproject(z, 10); + EXPECT(assert_equal(expected,actual_vec,1e-7)); + EXPECT(assert_equal(inv_depth,actual_inv,1e-7)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr);} +/* ************************************************************************* */ diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 376706e7f..a459925fd 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -2,17 +2,26 @@ * Matlab toolbox interface definition for gtsam_unstable */ -// Most things are in the gtsam namespace -using namespace gtsam; - // specify the classes from gtsam we are using -class gtsam::Point3; -class gtsam::Rot3; -class gtsam::Pose3; -class gtsam::SharedNoiseModel; +virtual class gtsam::Value; +virtual class gtsam::Point3; +virtual class gtsam::Rot3; +virtual class gtsam::Pose2; +virtual class gtsam::Pose3; +virtual class gtsam::noiseModel::Base; +virtual class gtsam::NonlinearFactor; + +namespace gtsam { + +#include +class Dummy { + Dummy(); + void print(string s) const; + unsigned char dummyTwoVar(unsigned char a) const; +}; #include -class PoseRTV { +virtual class PoseRTV : gtsam::Value { PoseRTV(); PoseRTV(Vector rtv); PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const gtsam::Point3& vel); @@ -22,7 +31,7 @@ class PoseRTV { PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz); // testable - bool equals(const PoseRTV& other, double tol) const; + bool equals(const gtsam::PoseRTV& other, double tol) const; void print(string s) const; // access @@ -39,58 +48,155 @@ class PoseRTV { // manifold/Lie static size_t Dim(); size_t dim() const; - PoseRTV retract(Vector v) const; - Vector localCoordinates(const PoseRTV& p) const; - static PoseRTV Expmap(Vector v); - static Vector Logmap(const PoseRTV& p); - PoseRTV inverse() const; - PoseRTV compose(const PoseRTV& p) const; - PoseRTV between(const PoseRTV& p) const; + gtsam::PoseRTV retract(Vector v) const; + Vector localCoordinates(const gtsam::PoseRTV& p) const; + static gtsam::PoseRTV Expmap(Vector v); + static Vector Logmap(const gtsam::PoseRTV& p); + gtsam::PoseRTV inverse() const; + gtsam::PoseRTV compose(const gtsam::PoseRTV& p) const; + gtsam::PoseRTV between(const gtsam::PoseRTV& p) const; // measurement - double range(const PoseRTV& other) const; - PoseRTV transformed_from(const gtsam::Pose3& trans) const; + double range(const gtsam::PoseRTV& other) const; + gtsam::PoseRTV transformed_from(const gtsam::Pose3& trans) const; // IMU/dynamics - PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const; - PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const; - PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const; - Vector imuPrediction(const PoseRTV& x2, double dt) const; - gtsam::Point3 translationIntegration(const PoseRTV& x2, double dt) const; - Vector translationIntegrationVec(const PoseRTV& x2, double dt) const; + gtsam::PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const; + gtsam::PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const; + gtsam::PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const; + Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const; + gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const; + Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; }; -#include -namespace imu { -class Values { - Values(); +// Nonlinear factors from gtsam, for our Value types +#include +template +virtual class PriorFactor : gtsam::NonlinearFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); +}; + + +#include +template +virtual class BetweenFactor : gtsam::NonlinearFactor { + BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); +}; + + +#include +template +virtual class RangeFactor : gtsam::NonlinearFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactorRTV; + + +#include +template +virtual class NonlinearEquality : gtsam::NonlinearFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); +}; + +#include +template +virtual class IMUFactor : gtsam::NonlinearFactor { + /** Standard constructor */ + IMUFactor(Vector accel, Vector gyro, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + /** Full IMU vector specification */ + IMUFactor(Vector imu_vector, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + Vector gyro() const; + Vector accel() const; + Vector z() const; + size_t key1() const; + size_t key2() const; +}; + +#include +template +virtual class FullIMUFactor : gtsam::NonlinearFactor { + /** Standard constructor */ + FullIMUFactor(Vector accel, Vector gyro, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + /** Single IMU vector - imu = [accel, gyro] */ + FullIMUFactor(Vector imu, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + Vector gyro() const; + Vector accel() const; + Vector z() const; + size_t key1() const; + size_t key2() const; +}; + + +#include +virtual class DHeightPrior : gtsam::NonlinearFactor { + DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model); +}; + + +virtual class DRollPrior : gtsam::NonlinearFactor { + /** allows for explicit roll parameterization - uses canonical coordinate */ + DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model); + /** Forces roll to zero */ + DRollPrior(size_t key, const gtsam::noiseModel::Base* model); +}; + + +virtual class VelocityPrior : gtsam::NonlinearFactor { + VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model); +}; + + +virtual class DGroundConstraint : gtsam::NonlinearFactor { + // Primary constructor allows for variable height of the "floor" + DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model); + // Fully specify vector - use only for debugging + DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); +}; + +//************************************************************************* +// General nonlinear factor types +//************************************************************************* +#include + +#include +template +virtual class PoseTranslationPrior : gtsam::NonlinearFactor { + PoseTranslationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseTranslationPrior PoseTranslationPrior2D; +typedef gtsam::PoseTranslationPrior PoseTranslationPrior3D; + +#include +template +virtual class PoseRotationPrior : gtsam::NonlinearFactor { + PoseRotationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseRotationPrior PoseRotationPrior2D; +typedef gtsam::PoseRotationPrior PoseRotationPrior3D; + +#include +virtual class RelativeElevationFactor: gtsam::NonlinearFactor { + RelativeElevationFactor(); + RelativeElevationFactor(size_t poseKey, size_t pointKey, double measured, + const gtsam::noiseModel::Base* model); + + double measured() const; void print(string s) const; - - void insertPose(size_t key, const PoseRTV& pose); - PoseRTV pose(size_t key) const; }; -class Graph { - Graph(); - void print(string s) const; - - // prior factors - void addPrior(size_t key, const PoseRTV& pose, const gtsam::SharedNoiseModel& noiseModel); - void addConstraint(size_t key, const PoseRTV& pose); - void addHeightPrior(size_t key, double z, const gtsam::SharedNoiseModel& noiseModel); - - // inertial factors - void addFullIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel); - void addIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel); - void addVelocityConstraint(size_t key1, size_t key2, double dt, const gtsam::SharedNoiseModel& noiseModel); - - // other measurements - void addBetween(size_t key1, size_t key2, const PoseRTV& z, const gtsam::SharedNoiseModel& noiseModel); - void addRange(size_t key1, size_t key2, double z, const gtsam::SharedNoiseModel& noiseModel); - - // optimization - imu::Values optimize(const imu::Values& init) const; -}; - -}///\namespace imu +} //\namespace gtsam 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_unstable/nonlinear/CMakeLists.txt b/gtsam_unstable/nonlinear/CMakeLists.txt new file mode 100644 index 000000000..a815e956d --- /dev/null +++ b/gtsam_unstable/nonlinear/CMakeLists.txt @@ -0,0 +1,25 @@ +# Install headers +file(GLOB nonlinear_headers "*.h") +install(FILES ${nonlinear_headers} DESTINATION include/gtsam_unstable/nonlinear) + +# Components to link tests in this subfolder against +set(nonlinear_local_libs + nonlinear_unstable + nonlinear + linear + inference + geometry + base + ccolamd +) + +set (nonlinear_full_libs + gtsam-static + gtsam_unstable-static) + +# Exclude tests that don't work +set (nonlinear_excluded_tests "") + +# Add all tests +gtsam_add_subdir_tests(nonlinear_unstable "${nonlinear_local_libs}" "${nonlinear_full_libs}" "${nonlinear_excluded_tests}") +add_dependencies(check.unstable check.nonlinear_unstable) diff --git a/gtsam_unstable/nonlinear/LinearContainerFactor.cpp b/gtsam_unstable/nonlinear/LinearContainerFactor.cpp new file mode 100644 index 000000000..b5701fb13 --- /dev/null +++ b/gtsam_unstable/nonlinear/LinearContainerFactor.cpp @@ -0,0 +1,240 @@ +/** + * @file LinearContainerFactor.cpp + * + * @date Jul 6, 2012 + * @author Alex Cunningham + */ + +#include + +#include + +namespace gtsam { + +/* ************************************************************************* */ +void LinearContainerFactor::rekeyFactor(const Ordering& ordering) { + Ordering::InvertedMap invOrdering = ordering.invert(); // TODO: inefficient - make more selective ordering invert + rekeyFactor(invOrdering); +} + +/* ************************************************************************* */ +void LinearContainerFactor::rekeyFactor(const Ordering::InvertedMap& invOrdering) { + BOOST_FOREACH(Index& idx, factor_->keys()) { + Key fullKey = invOrdering.find(idx)->second; + idx = fullKey; + keys_.push_back(fullKey); + } +} + +/* ************************************************************************* */ +void LinearContainerFactor::initializeLinearizationPoint(const Values& linearizationPoint) { + if (!linearizationPoint.empty()) { + linearizationPoint_ = Values(); + BOOST_FOREACH(const gtsam::Key& key, this->keys()) { + linearizationPoint_->insert(key, linearizationPoint.at(key)); + } + } else { + linearizationPoint_ = boost::none; + } +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor(const GaussianFactor::shared_ptr& factor, + const boost::optional& linearizationPoint) +: factor_(factor), linearizationPoint_(linearizationPoint) { + // Extract keys stashed in linear factor + BOOST_FOREACH(const Index& idx, factor_->keys()) + keys_.push_back(idx); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const JacobianFactor& factor, const Ordering& ordering, + const Values& linearizationPoint) +: factor_(factor.clone()) { + rekeyFactor(ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const HessianFactor& factor, const Ordering& ordering, + const Values& linearizationPoint) +: factor_(factor.clone()) { + rekeyFactor(ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor, const Ordering& ordering, + const Values& linearizationPoint) +: factor_(factor->clone()) { + rekeyFactor(ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor, + const Values& linearizationPoint) +: factor_(factor->clone()) +{ + // Extract keys stashed in linear factor + BOOST_FOREACH(const Index& idx, factor_->keys()) + keys_.push_back(idx); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor(const JacobianFactor& factor, + const Ordering::InvertedMap& inverted_ordering, + const Values& linearizationPoint) +: factor_(factor.clone()) { + rekeyFactor(inverted_ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor(const HessianFactor& factor, + const Ordering::InvertedMap& inverted_ordering, + const Values& linearizationPoint) +: factor_(factor.clone()) { + rekeyFactor(inverted_ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor, + const Ordering::InvertedMap& ordering, + const Values& linearizationPoint) +: factor_(factor->clone()) { + rekeyFactor(ordering); + initializeLinearizationPoint(linearizationPoint); +} + +/* ************************************************************************* */ +void LinearContainerFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const { + Base::print(s+"LinearContainerFactor", keyFormatter); + if (factor_) + factor_->print(" Stored Factor", keyFormatter); + if (linearizationPoint_) + linearizationPoint_->print(" LinearizationPoint", keyFormatter); +} + +/* ************************************************************************* */ +bool LinearContainerFactor::equals(const NonlinearFactor& f, double tol) const { + const LinearContainerFactor* jcf = dynamic_cast(&f); + if (!jcf || !factor_->equals(*jcf->factor_, tol) || !NonlinearFactor::equals(f)) + return false; + if (!linearizationPoint_ && !jcf->linearizationPoint_) + return true; + if (linearizationPoint_ && jcf->linearizationPoint_) + return linearizationPoint_->equals(*jcf->linearizationPoint_, tol); + return false; +} + +/* ************************************************************************* */ +double LinearContainerFactor::error(const Values& c) const { + if (!linearizationPoint_) + return 0; + + // Extract subset of values for comparision + Values csub; + BOOST_FOREACH(const gtsam::Key& key, keys()) + csub.insert(key, c.at(key)); + + // create dummy ordering for evaluation + Ordering ordering = *csub.orderingArbitrary(); + VectorValues delta = linearizationPoint_->localCoordinates(csub, ordering); + + // Change keys on stored factor + BOOST_FOREACH(gtsam::Index& index, factor_->keys()) + index = ordering[index]; + + // compute error + double error = factor_->error(delta); + + // change keys back + factor_->keys() = keys(); + + return error; +} + +/* ************************************************************************* */ +size_t LinearContainerFactor::dim() const { + if (isJacobian()) + return toJacobian()->get_model()->dim(); + else + return 1; // Hessians don't have true dimension +} + +/* ************************************************************************* */ +GaussianFactor::shared_ptr LinearContainerFactor::order(const Ordering& ordering) const { + // clone factor + boost::shared_ptr result = factor_->clone(); + + // rekey + BOOST_FOREACH(Index& key, result->keys()) + key = ordering[key]; + + return result; +} + +/* ************************************************************************* */ +GaussianFactor::shared_ptr LinearContainerFactor::linearize( + const Values& c, const Ordering& ordering) const { + return order(ordering); +} + +/* ************************************************************************* */ +bool LinearContainerFactor::isJacobian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +JacobianFactor::shared_ptr LinearContainerFactor::toJacobian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +HessianFactor::shared_ptr LinearContainerFactor::toHessian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +GaussianFactor::shared_ptr LinearContainerFactor::negate(const Ordering& ordering) const { + GaussianFactor::shared_ptr result = factor_->negate(); + BOOST_FOREACH(Key& key, result->keys()) + key = ordering[key]; + return result; +} + +/* ************************************************************************* */ +NonlinearFactor::shared_ptr LinearContainerFactor::negate() const { + GaussianFactor::shared_ptr antifactor = factor_->negate(); // already has keys in place + return NonlinearFactor::shared_ptr(new LinearContainerFactor(antifactor,linearizationPoint_)); +} + +/* ************************************************************************* */ +NonlinearFactorGraph LinearContainerFactor::convertLinearGraph( + const GaussianFactorGraph& linear_graph, const Ordering& ordering) { + return convertLinearGraph(linear_graph, ordering.invert()); +} + +/* ************************************************************************* */ +NonlinearFactorGraph LinearContainerFactor::convertLinearGraph( + const GaussianFactorGraph& linear_graph, const InvertedOrdering& invOrdering) { + NonlinearFactorGraph result; + BOOST_FOREACH(const GaussianFactor::shared_ptr& f, linear_graph) + if (f) + result.push_back(NonlinearFactorGraph::sharedFactor(new LinearContainerFactor(f, invOrdering))); + return result; +} + +/* ************************************************************************* */ +} // \namespace gtsam + + + diff --git a/gtsam_unstable/nonlinear/LinearContainerFactor.h b/gtsam_unstable/nonlinear/LinearContainerFactor.h new file mode 100644 index 000000000..324556622 --- /dev/null +++ b/gtsam_unstable/nonlinear/LinearContainerFactor.h @@ -0,0 +1,149 @@ +/** + * @file LinearContainerFactor.h + * + * @brief Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph + * + * @date Jul 6, 2012 + * @author Alex Cunningham + */ + +#pragma once + +#include +#include + +namespace gtsam { + +/** + * Dummy version of a generic linear factor to be injected into a nonlinear factor graph + */ +class LinearContainerFactor : public NonlinearFactor { +protected: + + GaussianFactor::shared_ptr factor_; + boost::optional linearizationPoint_; + + /** direct copy constructor */ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, + const boost::optional& linearizationPoint); + +public: + + /** Primary constructor: store a linear factor and decode the ordering */ + LinearContainerFactor(const JacobianFactor& factor, const Ordering& ordering, + const Values& linearizationPoint = Values()); + + /** Primary constructor: store a linear factor and decode the ordering */ + LinearContainerFactor(const HessianFactor& factor, const Ordering& ordering, + const Values& linearizationPoint = Values()); + + /** Constructor from shared_ptr */ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Ordering& ordering, + const Values& linearizationPoint = Values()); + + /** Constructor from re-keyed factor: all indices assumed replaced with Key */ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, + const Values& linearizationPoint = Values()); + + /** Alternate constructor: store a linear factor and decode keys with inverted ordering*/ + LinearContainerFactor(const JacobianFactor& factor, + const Ordering::InvertedMap& inverted_ordering, + const Values& linearizationPoint = Values()); + + /** Alternate constructor: store a linear factor and decode keys with inverted ordering*/ + LinearContainerFactor(const HessianFactor& factor, + const Ordering::InvertedMap& inverted_ordering, + const Values& linearizationPoint = Values()); + + /** Constructor from shared_ptr with inverted ordering*/ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, + const Ordering::InvertedMap& ordering, + const Values& linearizationPoint = Values()); + + // Access + + const GaussianFactor::shared_ptr& factor() const { return factor_; } + + // Testable + + /** print */ + void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; + + /** Check if two factors are equal */ + bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + + // NonlinearFactor + + /** + * Calculate the error of the factor: uses the underlying linear factor to compute ordering + */ + double error(const Values& c) const; + + /** get the dimension of the factor: rows of linear factor */ + size_t dim() const; + + /** Extract the linearization point used in recalculating error */ + const boost::optional& linearizationPoint() const { return linearizationPoint_; } + + /** Apply the ordering to a graph - same as linearize(), but without needing a linearization point */ + GaussianFactor::shared_ptr order(const Ordering& ordering) const; + + /** linearize to a GaussianFactor: values has no effect, just clones/rekeys underlying factor */ + GaussianFactor::shared_ptr linearize(const Values& c, const Ordering& ordering) const; + + /** + * Creates an anti-factor directly and performs rekeying due to ordering + */ + GaussianFactor::shared_ptr negate(const Ordering& ordering) const; + + /** + * Creates the equivalent anti-factor as another LinearContainerFactor, + * so it remains independent of ordering. + */ + NonlinearFactor::shared_ptr negate() const; + + /** + * Creates a shared_ptr clone of the factor - needs to be specialized to allow + * for subclasses + * + * Clones the underlying linear factor + */ + NonlinearFactor::shared_ptr clone() const { + return NonlinearFactor::shared_ptr(new LinearContainerFactor(factor_,linearizationPoint_)); + } + + // casting syntactic sugar + + /** + * Simple check whether this is a Jacobian or Hessian factor + */ + bool isJacobian() const; + + /** Casts to JacobianFactor */ + JacobianFactor::shared_ptr toJacobian() const; + + /** Casts to HessianFactor */ + HessianFactor::shared_ptr toHessian() const; + + /** + * Utility function for converting linear graphs to nonlinear graphs + * consisting of LinearContainerFactors. Two versions are available, using + * either the ordering the linear graph was linearized around, or the inverse ordering. + * If the inverse ordering is present, it will be faster. + */ + static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph, + const Ordering& ordering); + + static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph, + const InvertedOrdering& invOrdering); + +protected: + void rekeyFactor(const Ordering& ordering); + void rekeyFactor(const Ordering::InvertedMap& invOrdering); + void initializeLinearizationPoint(const Values& linearizationPoint); + +}; // \class LinearContainerFactor + +} // \namespace gtsam + + diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.cpp b/gtsam_unstable/nonlinear/LinearizedFactor.cpp new file mode 100644 index 000000000..3b989be6c --- /dev/null +++ b/gtsam_unstable/nonlinear/LinearizedFactor.cpp @@ -0,0 +1,148 @@ +/* ---------------------------------------------------------------------------- + + * 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 LinearizedFactor.cpp + * @brief A dummy factor that allows a linear factor to act as a nonlinear factor + * @author Alex Cunningham + */ + +#include +#include + +#include + +namespace gtsam { + +using namespace std; + +/* ************************************************************************* */ +LinearizedFactor::LinearizedFactor(JacobianFactor::shared_ptr lin_factor, + const KeyLookup& decoder, const Values& lin_points) +: Base(lin_factor->get_model()), b_(lin_factor->getb()), model_(lin_factor->get_model()) { + BOOST_FOREACH(const Index& idx, *lin_factor) { + // find full symbol + KeyLookup::const_iterator decode_it = decoder.find(idx); + if (decode_it == decoder.end()) + throw runtime_error("LinearizedFactor: could not find index in decoder!"); + Key key(decode_it->second); + + // extract linearization point + assert(lin_points.exists(key)); + this->lin_points_.insert(key, lin_points.at(key)); // NOTE: will not overwrite + + // extract Jacobian + Matrix A = lin_factor->getA(lin_factor->find(idx)); + this->matrices_.insert(std::make_pair(key, A)); + + // store keys + this->keys_.push_back(key); + } +} + +/* ************************************************************************* */ +LinearizedFactor::LinearizedFactor(JacobianFactor::shared_ptr lin_factor, + const Ordering& ordering, const Values& lin_points) +: Base(lin_factor->get_model()), b_(lin_factor->getb()), model_(lin_factor->get_model()) { + const KeyLookup decoder = ordering.invert(); + BOOST_FOREACH(const Index& idx, *lin_factor) { + // find full symbol + KeyLookup::const_iterator decode_it = decoder.find(idx); + if (decode_it == decoder.end()) + throw runtime_error("LinearizedFactor: could not find index in decoder!"); + Key key(decode_it->second); + + // extract linearization point + assert(lin_points.exists(key)); + this->lin_points_.insert(key, lin_points.at(key)); // NOTE: will not overwrite + + // extract Jacobian + Matrix A = lin_factor->getA(lin_factor->find(idx)); + this->matrices_.insert(std::make_pair(key, A)); + + // store keys + this->keys_.push_back(key); + } +} + +/* ************************************************************************* */ +Vector LinearizedFactor::unwhitenedError(const Values& c, + boost::optional&> H) const { + // extract the points in the new values + Vector ret = - b_; + + if (H) H->resize(this->size()); + size_t i=0; + BOOST_FOREACH(Key key, this->keys()) { + const Value& newPt = c.at(key); + const Value& linPt = lin_points_.at(key); + Vector d = linPt.localCoordinates_(newPt); + const Matrix& A = matrices_.at(key); + ret += A * d; + if (H) (*H)[i++] = A; + } + + return ret; +} + +/* ************************************************************************* */ +boost::shared_ptr +LinearizedFactor::linearize(const Values& c, const Ordering& ordering) const { + + // sort by varid - only known at linearization time + typedef std::map VarMatrixMap; + VarMatrixMap sorting_terms; + BOOST_FOREACH(const KeyMatrixMap::value_type& p, matrices_) + sorting_terms.insert(std::make_pair(ordering[p.first], p.second)); + + // move into terms + std::vector > terms; + BOOST_FOREACH(const VarMatrixMap::value_type& p, sorting_terms) + terms.push_back(p); + + // compute rhs: adjust current by whitened update + Vector b = unwhitenedError(c) + b_; // remove original b + this->noiseModel_->whitenInPlace(b); + + return boost::shared_ptr(new JacobianFactor(terms, b - b_, model_)); +} + +/* ************************************************************************* */ +void LinearizedFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const { + this->noiseModel_->print(s + std::string(" model")); + BOOST_FOREACH(const KeyMatrixMap::value_type& p, matrices_) { + gtsam::print(p.second, keyFormatter(p.first)); + } + gtsam::print(b_, std::string("b")); + std::cout << " nonlinear keys: "; + BOOST_FOREACH(const Key& key, this->keys()) + cout << keyFormatter(key) << " "; + lin_points_.print("Linearization Point"); +} + +/* ************************************************************************* */ +bool LinearizedFactor::equals(const NonlinearFactor& other, double tol) const { + const LinearizedFactor* e = dynamic_cast(&other); + if (!e || !Base::equals(other, tol) + || !lin_points_.equals(e->lin_points_, tol) + || !equal_with_abs_tol(b_, e->b_, tol) + || !model_->equals(*e->model_, tol) + || matrices_.size() != e->matrices_.size()) + return false; + + KeyMatrixMap::const_iterator map1 = matrices_.begin(), map2 = e->matrices_.begin(); + for (; map1 != matrices_.end() && map2 != e->matrices_.end(); ++map1, ++map2) + if ((map1->first != map2->first) || !equal_with_abs_tol(map1->second, map2->second, tol)) + return false; + return true; +} + +} // \namespace gtsam diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h new file mode 100644 index 000000000..28102d8fd --- /dev/null +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -0,0 +1,125 @@ +/* ---------------------------------------------------------------------------- + + * 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 LinearizedFactor.h + * @brief A dummy factor that allows a linear factor to act as a nonlinear factor + * @author Alex Cunningham + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * A dummy factor that takes a linearized factor and inserts it into + * a nonlinear graph. + */ +class LinearizedFactor : public gtsam::NoiseModelFactor { + +public: + /** base type */ + typedef gtsam::NoiseModelFactor Base; + typedef LinearizedFactor This; + + /** shared pointer for convenience */ + typedef boost::shared_ptr shared_ptr; + + + /** decoder for keys - avoids the use of a full ordering */ + typedef gtsam::Ordering::InvertedMap KeyLookup; + +protected: + /** hold onto the factor itself */ + // store components of a jacobian factor + typedef std::map KeyMatrixMap; + KeyMatrixMap matrices_; + gtsam::Vector b_; + gtsam::SharedDiagonal model_; /// separate from the noisemodel in NonlinearFactor due to Diagonal/Gaussian + + /** linearization points for error calculation */ + gtsam::Values lin_points_; + + /** default constructor for serialization */ + LinearizedFactor() {} + +public: + + virtual ~LinearizedFactor() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + + /** + * Use this constructor with pre-constructed decoders + * @param lin_factor is a gaussian factor with linear keys (no labels baked in) + * @param decoder is a structure to look up the correct keys + * @param values is assumed to have the correct key structure with labels + */ + LinearizedFactor(gtsam::JacobianFactor::shared_ptr lin_factor, + const KeyLookup& decoder, const gtsam::Values& lin_points); + + /** + * Use this constructor with the ordering used to linearize the graph + * @param lin_factor is a gaussian factor with linear keys (no labels baked in) + * @param ordering is the full ordering used to linearize the graph + * @param values is assumed to have the correct key structure with labels + */ + LinearizedFactor(gtsam::JacobianFactor::shared_ptr lin_factor, + const gtsam::Ordering& ordering, const gtsam::Values& lin_points); + + /** Vector of errors, unwhitened, with optional derivatives (ordered by key) */ + virtual gtsam::Vector unwhitenedError(const gtsam::Values& c, + boost::optional&> H = boost::none) const; + + /** + * linearize to a GaussianFactor + * Reimplemented from NoiseModelFactor to directly copy out the + * matrices and only update the RHS b with an updated residual + */ + virtual boost::shared_ptr linearize( + const gtsam::Values& c, const gtsam::Ordering& ordering) const; + + // Testable + + /** print function */ + virtual void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + + /** equals function with optional tolerance */ + virtual bool equals(const NonlinearFactor& other, double tol = 1e-9) const; + + // access functions + + const gtsam::Vector& b() const { return b_; } + inline const gtsam::Values& linearizationPoint() const { return lin_points_; } + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NonlinearFactor", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(matrices_); + ar & BOOST_SERIALIZATION_NVP(b_); + ar & BOOST_SERIALIZATION_NVP(model_); + ar & BOOST_SERIALIZATION_NVP(lin_points_); + } +}; + +} // \namespace gtsam + diff --git a/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp b/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp new file mode 100644 index 000000000..51f2f73a2 --- /dev/null +++ b/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp @@ -0,0 +1,162 @@ +/** + * @file testLinearContainerFactor.cpp + * + * @date Jul 6, 2012 + * @author Alex Cunningham + */ + +#include + +#include + +#include +#include + +using namespace gtsam; + +const gtsam::noiseModel::Diagonal::shared_ptr diag_model2 = noiseModel::Diagonal::Sigmas(Vector_(2, 1.0, 1.0)); +const double tol = 1e-5; + +gtsam::Key l1 = 101, l2 = 102, x1 = 1, x2 = 2; + +Point2 landmark1(5.0, 1.5), landmark2(7.0, 1.5); +Pose2 poseA1(0.0, 0.0, 0.0), poseA2(2.0, 0.0, 0.0); + +/* ************************************************************************* */ +TEST( testLinearContainerFactor, generic_jacobian_factor ) { + + Ordering initOrdering; initOrdering += x1, x2, l1, l2; + + JacobianFactor expLinFactor1( + initOrdering[l1], + Matrix_(2,2, + 2.74222, -0.0067457, + 0.0, 2.63624), + initOrdering[l2], + Matrix_(2,2, + -0.0455167, -0.0443573, + -0.0222154, -0.102489), + Vector_(2, 0.0277052, + -0.0533393), + diag_model2); + + LinearContainerFactor actFactor1(expLinFactor1, initOrdering); + Values values; + values.insert(l1, landmark1); + values.insert(l2, landmark2); + values.insert(x1, poseA1); + values.insert(x2, poseA2); + + // Check reconstruction from same ordering + GaussianFactor::shared_ptr actLinearizationA = actFactor1.linearize(values, initOrdering); + EXPECT(assert_equal(*expLinFactor1.clone(), *actLinearizationA, tol)); + + // Check reconstruction from new ordering + Ordering newOrdering; newOrdering += x1, l1, x2, l2; + GaussianFactor::shared_ptr actLinearizationB = actFactor1.linearize(values, newOrdering); + + JacobianFactor expLinFactor2( + newOrdering[l1], + Matrix_(2,2, + 2.74222, -0.0067457, + 0.0, 2.63624), + newOrdering[l2], + Matrix_(2,2, + -0.0455167, -0.0443573, + -0.0222154, -0.102489), + Vector_(2, 0.0277052, + -0.0533393), + diag_model2); + + EXPECT(assert_equal(*expLinFactor2.clone(), *actLinearizationB, tol)); +} + +/* ************************************************************************* */ +TEST( testLinearContainerFactor, jacobian_factor_withlinpoints ) { + + Ordering ordering; ordering += x1, x2, l1, l2; + + JacobianFactor expLinFactor( + ordering[l1], + Matrix_(2,2, + 2.74222, -0.0067457, + 0.0, 2.63624), + ordering[l2], + Matrix_(2,2, + -0.0455167, -0.0443573, + -0.0222154, -0.102489), + Vector_(2, 0.0277052, + -0.0533393), + diag_model2); + + Values values; + values.insert(l1, landmark1); + values.insert(l2, landmark2); + values.insert(x1, poseA1); + values.insert(x2, poseA2); + + LinearContainerFactor actFactor(expLinFactor, ordering, values); + LinearContainerFactor actFactorNolin(expLinFactor, ordering); + + EXPECT(assert_equal(actFactor, actFactor, tol)); + EXPECT(assert_inequal(actFactor, actFactorNolin, tol)); + EXPECT(assert_inequal(actFactorNolin, actFactor, tol)); + + // Check contents + Values expLinPoint; + expLinPoint.insert(l1, landmark1); + expLinPoint.insert(l2, landmark2); + CHECK(actFactor.linearizationPoint()); + EXPECT(assert_equal(expLinPoint, *actFactor.linearizationPoint())); + + // Check error evaluation + VectorValues delta = values.zeroVectors(ordering); + delta.at(ordering[l1]) = Vector_(2, 1.0, 2.0); + delta.at(ordering[l2]) = Vector_(2, 3.0, 4.0); + Values noisyValues = values.retract(delta, ordering); + double expError = expLinFactor.error(delta); + EXPECT_DOUBLES_EQUAL(expError, actFactor.error(noisyValues), tol); + EXPECT_DOUBLES_EQUAL(expLinFactor.error(values.zeroVectors(ordering)), actFactor.error(values), tol); +} + +/* ************************************************************************* */ +TEST( testLinearContainerFactor, generic_hessian_factor ) { + Matrix G11 = Matrix_(1,1, 1.0); + Matrix G12 = Matrix_(1,2, 2.0, 4.0); + Matrix G13 = Matrix_(1,3, 3.0, 6.0, 9.0); + + Matrix G22 = Matrix_(2,2, 3.0, 5.0, 0.0, 6.0); + Matrix G23 = Matrix_(2,3, 4.0, 6.0, 8.0, 1.0, 2.0, 4.0); + + Matrix G33 = Matrix_(3,3, 1.0, 2.0, 3.0, 0.0, 5.0, 6.0, 0.0, 0.0, 9.0); + + Vector g1 = Vector_(1, -7.0); + Vector g2 = Vector_(2, -8.0, -9.0); + Vector g3 = Vector_(3, 1.0, 2.0, 3.0); + + double f = 10.0; + + Ordering initOrdering; initOrdering += x1, x2, l1, l2; + HessianFactor initFactor(initOrdering[x1], initOrdering[x2], initOrdering[l1], + G11, G12, G13, g1, G22, G23, g2, G33, g3, f); + + Values values; + values.insert(l1, landmark1); + values.insert(l2, landmark2); + values.insert(x1, poseA1); + values.insert(x2, poseA2); + + LinearContainerFactor actFactor(initFactor, initOrdering); + GaussianFactor::shared_ptr actLinearization1 = actFactor.linearize(values, initOrdering); + EXPECT(assert_equal(*initFactor.clone(), *actLinearization1, tol)); + + Ordering newOrdering; newOrdering += l1, x1, x2, l2; + HessianFactor expLinFactor(newOrdering[x1], newOrdering[x2], newOrdering[l1], + G11, G12, G13, g1, G22, G23, g2, G33, g3, f); + GaussianFactor::shared_ptr actLinearization2 = actFactor.linearize(values, newOrdering); + EXPECT(assert_equal(*expLinFactor.clone(), *actLinearization2, tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam_unstable/nonlinear/tests/testLinearizedFactor.cpp b/gtsam_unstable/nonlinear/tests/testLinearizedFactor.cpp new file mode 100644 index 000000000..9c0438e49 --- /dev/null +++ b/gtsam_unstable/nonlinear/tests/testLinearizedFactor.cpp @@ -0,0 +1,69 @@ +/** + * @file testLinearizedFactor + * @author Alex Cunningham + */ + +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace boost::assign; +using namespace gtsam; + +static const double tol = 1e-5; + +/* ************************************************************************* */ +TEST( testLinearizedFactor, creation ) { + // Create a set of local keys (No robot label) + Key l1 = 11, l2 = 12, + l3 = 13, l4 = 14, + l5 = 15, l6 = 16, + l7 = 17, l8 = 18; + + // creating an ordering to decode the linearized factor + Ordering ordering; + ordering += l1,l2,l3,l4,l5,l6,l7,l8; + + // create a decoder for only the relevant variables + LinearizedFactor::KeyLookup decoder; + decoder[2] = l3; + decoder[4] = l5; + + // create a linear factor + SharedDiagonal model = noiseModel::Unit::Create(2); + JacobianFactor::shared_ptr linear_factor(new JacobianFactor( + ordering[l3], eye(2,2), ordering[l5], 2.0 * eye(2,2), zero(2), model)); + + // create a set of values - build with full set of values + gtsam::Values full_values, exp_values; + full_values.insert(l3, Point2(1.0, 2.0)); + full_values.insert(l5, Point2(4.0, 3.0)); + exp_values = full_values; + full_values.insert(l1, Point2(3.0, 7.0)); + + // create the test LinearizedFactor + // This is called in the constructor of DDFSlot for each linear factor + LinearizedFactor actual1(linear_factor, decoder, full_values); + LinearizedFactor actual2(linear_factor, ordering, full_values); + + EXPECT(assert_equal(actual1, actual2, tol)); + + // Verify the keys + vector expKeys; + expKeys += l3, l5; + EXPECT(assert_container_equality(expKeys, actual1.keys())); + EXPECT(assert_container_equality(expKeys, actual2.keys())); + + // Verify subset of linearization points + EXPECT(assert_equal(exp_values, actual1.linearizationPoint(), tol)); + EXPECT(assert_equal(exp_values, actual2.linearizationPoint(), tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam_unstable/slam/CMakeLists.txt b/gtsam_unstable/slam/CMakeLists.txt index b0442044f..33cb45df9 100644 --- a/gtsam_unstable/slam/CMakeLists.txt +++ b/gtsam_unstable/slam/CMakeLists.txt @@ -4,7 +4,7 @@ install(FILES ${slam_headers} DESTINATION include/gtsam_unstable/slam) # Components to link tests in this subfolder against set(slam_local_libs - slam_unstable + slam_unstable slam nonlinear linear @@ -23,4 +23,4 @@ set (slam_excluded_tests "") # Add all tests gtsam_add_subdir_tests(slam_unstable "${slam_local_libs}" "${slam_full_libs}" "${slam_excluded_tests}") - +add_dependencies(check.unstable check.slam_unstable) diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h new file mode 100644 index 000000000..f5856f6c8 --- /dev/null +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -0,0 +1,116 @@ + +/** + * @file InvDepthFactor3.h + * @brief Inverse Depth Factor + * @author Chris Beall + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * Ternary factor representing a visual measurement that includes inverse depth + */ +template +class InvDepthFactor3: public gtsam::NoiseModelFactor3 { +protected: + + // Keep a copy of measurement and calibration for I/O + gtsam::Point2 measured_; ///< 2D measurement + boost::shared_ptr K_; ///< shared pointer to calibration object + +public: + + /// shorthand for base class type + typedef gtsam::NoiseModelFactor3 Base; + + /// shorthand for this class + typedef InvDepthFactor3 This; + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /// Default constructor + InvDepthFactor3() : K_(new gtsam::Cal3_S2(444, 555, 666, 777, 888)) {} + + /** + * Constructor + * TODO: Mark argument order standard (keys, measurement, parameters) + * @param measured is the 2 dimensional location of point in image (the measurement) + * @param model is the standard deviation + * @param poseKey is the index of the camera pose + * @param pointKey is the index of the landmark + * @param invDepthKey is the index of inverse depth + * @param K shared pointer to the constant calibration + */ + InvDepthFactor3(const gtsam::Point2& measured, const gtsam::SharedNoiseModel& model, + const gtsam::Key poseKey, gtsam::Key pointKey, gtsam::Key invDepthKey, const gtsam::shared_ptrK& K) : + Base(model, poseKey, pointKey, invDepthKey), measured_(measured), K_(K) {} + + /** Virtual destructor */ + virtual ~InvDepthFactor3() {} + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "InvDepthFactor3", + const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + measured_.print(s + ".z"); + } + + /// equals + virtual bool equals(const gtsam::NonlinearFactor& p, double tol = 1e-9) const { + const This *e = dynamic_cast(&p); + return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol) && this->K_->equals(*e->K_, tol); + } + + /// Evaluate error h(x)-z and optionally derivatives + gtsam::Vector evaluateError(const POSE& pose, const gtsam::LieVector& point, const INVDEPTH& invDepth, + boost::optional H1=boost::none, + boost::optional H2=boost::none, + boost::optional H3=boost::none) const { + try { + InvDepthCamera3 camera(pose, K_); + gtsam::Point2 reprojectionError(camera.project(point, invDepth, H1, H2, H3) - measured_); + return reprojectionError.vector(); + } catch( CheiralityException& e) { + if (H1) *H1 = gtsam::zeros(2,6); + if (H2) *H2 = gtsam::zeros(2,5); + if (H3) *H2 = gtsam::zeros(2,1); + std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) << + " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl; + return gtsam::ones(2) * 2.0 * K_->fx(); + } + return gtsam::Vector_(1, 0.0); + } + + /** return the measurement */ + const gtsam::Point2& imagePoint() const { + return measured_; + } + + /** return the calibration object */ + inline const gtsam::Cal3_S2::shared_ptr calibration() const { + return K_; + } + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(measured_); + ar & BOOST_SERIALIZATION_NVP(K_); + } +}; +} // \ namespace gtsam diff --git a/gtsam/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h similarity index 85% rename from gtsam/slam/PartialPriorFactor.h rename to gtsam_unstable/slam/PartialPriorFactor.h index 4c7069174..f096ed9bc 100644 --- a/gtsam/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -18,6 +18,7 @@ #pragma once #include +#include namespace gtsam { @@ -28,15 +29,12 @@ namespace gtsam { * * The prior vector used in this factor is stored in compressed form, such that * it only contains values for measurements that are to be compared, and they are in - * the same order as T::Logmap(). The mask will determine which components to extract + * the same order as VALUE::Logmap(). The mask will determine which components to extract * in the error function. * - * It takes two template parameters: - * Key (typically TypedSymbol) is used to look up T's in a Values - * Values where the T's are stored, typically Values or a TupleValues<...> - * * For practical use, it would be good to subclass this factor and have the class type * construct the mask. + * @tparam VALUE is the type of variable the prior effects */ template class PartialPriorFactor: public NoiseModelFactor1 { @@ -46,12 +44,15 @@ namespace gtsam { protected: + // Concept checks on the variable type - currently requires Lie + GTSAM_CONCEPT_LIE_TYPE(VALUE) + typedef NoiseModelFactor1 Base; typedef PartialPriorFactor This; - Vector prior_; ///< measurement on logmap parameters, in compressed form + Vector prior_; ///< measurement on tangent space parameters, in compressed form std::vector mask_; ///< indices of values to constrain in compressed prior vector - Matrix H_; ///< Constant jacobian - computed at creation + Matrix H_; ///< Constant Jacobian - computed at creation /** default constructor - only use for serialization */ PartialPriorFactor() {} @@ -65,9 +66,6 @@ namespace gtsam { public: - // shorthand for a smart pointer to a factor - typedef typename boost::shared_ptr shared_ptr; - virtual ~PartialPriorFactor() {} /** Single Element Constructor: acts on a single parameter specified by idx */ @@ -86,6 +84,11 @@ namespace gtsam { this->fillH(); } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** implement functions needed for Testable */ /** print */ @@ -109,6 +112,7 @@ namespace gtsam { if (H) (*H) = H_; // FIXME: this was originally the generic retraction - may not produce same results Vector full_logmap = T::Logmap(p); +// Vector full_logmap = T::identity().localCoordinates(p); // Alternate implementation Vector masked_logmap = zero(this->dim()); for (size_t i=0; i + +namespace gtsam { + +template +class PoseRotationPrior : public NoiseModelFactor1 { +public: + + typedef PoseRotationPrior This; + typedef NoiseModelFactor1 Base; + typedef POSE Pose; + typedef typename POSE::Translation Translation; + typedef typename POSE::Rotation Rotation; + + GTSAM_CONCEPT_POSE_TYPE(Pose) + GTSAM_CONCEPT_GROUP_TYPE(Pose) + GTSAM_CONCEPT_LIE_TYPE(Rotation) + +protected: + + Rotation measured_; + +public: + + /** standard constructor */ + PoseRotationPrior(Key key, const Rotation& rot_z, const SharedNoiseModel& model) + : Base(model, key), measured_(rot_z) {} + + /** Constructor that pulls the translation from an incoming POSE */ + PoseRotationPrior(Key key, const POSE& pose_z, const SharedNoiseModel& model) + : Base(model, key), measured_(pose_z.rotation()) {} + + virtual ~PoseRotationPrior() {} + + // access + const Rotation& measured() const { return measured_; } + + // testable + + /** equals specialized to this factor */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol) && measured_.equals(e->measured_, tol); + } + + /** print contents */ + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(s + "PoseRotationPrior", keyFormatter); + measured_.print("Measured Rotation"); + } + + /** h(x)-z */ + Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const { + const Rotation& newR = pose.rotation(); + const size_t rDim = newR.dim(), xDim = pose.dim(); + if (H) { + *H = gtsam::zeros(rDim, xDim); + if (pose_traits::isRotFirst()) + (*H).leftCols(rDim).setIdentity(rDim, rDim); + else + (*H).rightCols(rDim).setIdentity(rDim, rDim); + } + + return Rotation::Logmap(newR) - Rotation::Logmap(measured_); + } + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor1", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } +}; + +} // \namespace gtsam + + + + diff --git a/gtsam_unstable/slam/PoseTranslationPrior.h b/gtsam_unstable/slam/PoseTranslationPrior.h new file mode 100644 index 000000000..9fc2bb423 --- /dev/null +++ b/gtsam_unstable/slam/PoseTranslationPrior.h @@ -0,0 +1,119 @@ +/** + * @file PoseTranslationPrior.h + * + * @brief Implements a prior on the translation component of a pose + * + * @date Jun 14, 2012 + * @author Alex Cunningham + */ + +#pragma once + +#include +#include + +namespace gtsam { + +/** simple pose traits for building factors */ +namespace pose_traits { + +/** checks whether parameterization of rotation is before or after translation in Lie algebra */ +template +bool isRotFirst() { + throw std::invalid_argument("PoseTrait: no implementation for this pose type"); + return false; +} + +// Instantiate for common poses +template<> inline bool isRotFirst() { return true; } +template<> inline bool isRotFirst() { return false; } + +} // \namespace pose_traits + +/** + * A prior on the translation part of a pose + */ +template +class PoseTranslationPrior : public NoiseModelFactor1 { +public: + typedef PoseTranslationPrior This; + typedef NoiseModelFactor1 Base; + typedef POSE Pose; + typedef typename POSE::Translation Translation; + typedef typename POSE::Rotation Rotation; + + GTSAM_CONCEPT_POSE_TYPE(Pose) + GTSAM_CONCEPT_GROUP_TYPE(Pose) + GTSAM_CONCEPT_LIE_TYPE(Translation) + +protected: + + Translation measured_; + +public: + + /** standard constructor */ + PoseTranslationPrior(Key key, const Translation& measured, const noiseModel::Base::shared_ptr& model) + : Base(model, key), measured_(measured) { + } + + /** Constructor that pulls the translation from an incoming POSE */ + PoseTranslationPrior(Key key, const POSE& pose_z, const noiseModel::Base::shared_ptr& model) + : Base(model, key), measured_(pose_z.translation()) { + } + + virtual ~PoseTranslationPrior() {} + + const Translation& measured() const { return measured_; } + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + + /** h(x)-z */ + Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const { + const Translation& newTrans = pose.translation(); + const Rotation& R = pose.rotation(); + const size_t tDim = newTrans.dim(), xDim = pose.dim(); + if (H) { + *H = gtsam::zeros(tDim, xDim); + if (pose_traits::isRotFirst()) + (*H).rightCols(tDim) = R.matrix(); + else + (*H).leftCols(tDim) = R.matrix(); + } + + return newTrans.vector() - measured_.vector(); + } + + /** equals specialized to this factor */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol) && measured_.equals(e->measured_, tol); + } + + /** print contents */ + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(s + "PoseTranslationPrior", keyFormatter); + measured_.print("Measured Translation"); + } + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor1", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + +}; + +} // \namespace gtsam + + + + diff --git a/gtsam_unstable/slam/RelativeElevationFactor.cpp b/gtsam_unstable/slam/RelativeElevationFactor.cpp new file mode 100644 index 000000000..2d0ca7548 --- /dev/null +++ b/gtsam_unstable/slam/RelativeElevationFactor.cpp @@ -0,0 +1,53 @@ +/** + * @file RelativeElevationFactor.cpp + * + * @date Aug 17, 2012 + * @author Alex Cunningham + */ + +#include + +namespace gtsam { + +/* ************************************************************************* */ +RelativeElevationFactor::RelativeElevationFactor(Key poseKey, Key pointKey, double measured, + const SharedNoiseModel& model) +: Base(model, poseKey, pointKey), measured_(measured) +{ +} + +/* ************************************************************************* */ +Vector RelativeElevationFactor::evaluateError(const Pose3& pose, const Point3& point, + boost::optional H1, boost::optional H2) const { + double hx = pose.z() - point.z(); + if (H1) { + *H1 = zeros(1, 6); + // Use bottom row of rotation matrix for derivative of translation + (*H1)(0, 3) = pose.rotation().r1().z(); + (*H1)(0, 4) = pose.rotation().r2().z(); + (*H1)(0, 5) = pose.rotation().r3().z(); + } + + if (H2) { + *H2 = zeros(1, 3); + (*H2)(0, 2) = -1.0; + } + return Vector_(1, hx - measured_); +} + +/* ************************************************************************* */ +bool RelativeElevationFactor::equals(const NonlinearFactor& expected, double tol) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol) && fabs(this->measured_ - e->measured_) < tol; +} + +/* ************************************************************************* */ +void RelativeElevationFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const { + std::cout << s << "RelativeElevationFactor, relative elevation = " << measured_ << std::endl; + Base::print("", keyFormatter); +} +/* ************************************************************************* */ + +} // \namespace gtsam + + diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h new file mode 100644 index 000000000..a0186a9f2 --- /dev/null +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -0,0 +1,77 @@ +/** + * @file RelativeElevationFactor.h + * + * @brief Factor representing a known relative altitude in global frame + * + * @date Aug 17, 2012 + * @author Alex Cunningham + */ + +#pragma once + +#include +#include + +namespace gtsam { + +/** + * Binary factor for a relative elevation. Note that this + * factor takes into account only elevation, and corrects for orientation. + * Unlike a range factor, the relative elevation is signed, and only affects + * the Z coordinate. Measurement function h(pose, pt) = h.z() - pt.z() + * + * Dimension: 1 + * + * TODO: enable use of a Pose3 for the target as well + */ +class RelativeElevationFactor: public NoiseModelFactor2 { +private: + + double measured_; /** measurement */ + + typedef RelativeElevationFactor This; + typedef NoiseModelFactor2 Base; + +public: + + RelativeElevationFactor() : measured_(0.0) {} /* Default constructor */ + + RelativeElevationFactor(Key poseKey, Key pointKey, double measured, + const SharedNoiseModel& model); + + virtual ~RelativeElevationFactor() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + + /** h(x)-z */ + Vector evaluateError(const Pose3& pose, const Point3& point, + boost::optional H1 = boost::none, boost::optional H2 = boost::none) const; + + /** return the measured */ + inline double measured() const { return measured_; } + + /** equals specialized to this factor */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const; + + /** print contents */ + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } +}; // RelativeElevationFactor + + +} // \namespace gtsam + + diff --git a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp new file mode 100644 index 000000000..5567bc9ce --- /dev/null +++ b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp @@ -0,0 +1,92 @@ +/* + * testInvDepthFactor.cpp + * + * Created on: Apr 13, 2012 + * Author: cbeall3 + */ + +#include + +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); +static SharedNoiseModel sigma(noiseModel::Unit::Create(2)); + +Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +SimpleCamera level_camera(level_pose, *K); + +typedef InvDepthFactor3 InverseDepthFactor; +typedef NonlinearEquality PoseConstraint; + +/* ************************************************************************* */ +TEST( InvDepthFactor, optimize) { + + // landmark 5 meters infront of camera + Point3 landmark(5, 0, 1); + + Point2 expected_uv = level_camera.project(landmark); + + InvDepthCamera3 inv_camera(level_pose, K); + LieVector inv_landmark(5, 1., 0., 1., 0., 0.); + LieScalar inv_depth(1./4); + + gtsam::NonlinearFactorGraph graph; + Values initial; + + InverseDepthFactor::shared_ptr factor(new InverseDepthFactor(expected_uv, sigma, + Symbol('x',1), Symbol('l',1), Symbol('d',1), K)); + graph.push_back(factor); + graph.add(PoseConstraint(Symbol('x',1),level_pose)); + initial.insert(Symbol('x',1), level_pose); + initial.insert(Symbol('l',1), inv_landmark); + initial.insert(Symbol('d',1), inv_depth); + + LevenbergMarquardtParams lmParams; + Values result = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize(); + EXPECT(assert_equal(initial, result, 1e-9)); + + /// Add a second camera + + // add a camera 1 meter to the right + Pose3 right_pose = level_pose * Pose3(Rot3(), Point3(2,0,0)); + SimpleCamera right_camera(right_pose, *K); + + InvDepthCamera3 right_inv_camera(right_pose, K); + + Point3 landmark1(6,0,1); + Point2 right_uv = right_camera.project(landmark1); + + + InverseDepthFactor::shared_ptr factor1(new InverseDepthFactor(right_uv, sigma, + Symbol('x',2), Symbol('l',1),Symbol('d',1),K)); + graph.push_back(factor1); + + graph.add(PoseConstraint(Symbol('x',2),right_pose)); + + initial.insert(Symbol('x',2), right_pose); + + // TODO: need to add priors to make this work with +// Values result2 = optimize(graph, initial, +// NonlinearOptimizationParameters(),MULTIFRONTAL, GN); + + Values result2 = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize(); + Point3 l1_result2 = InvDepthCamera3::invDepthTo3D( + result2.at(Symbol('l',1)), + result2.at(Symbol('d',1))); + + EXPECT(assert_equal(landmark1, l1_result2, 1e-9)); +} + + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr);} +/* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testPoseRotationPrior.cpp b/gtsam_unstable/slam/tests/testPoseRotationPrior.cpp new file mode 100644 index 000000000..2f60e114a --- /dev/null +++ b/gtsam_unstable/slam/tests/testPoseRotationPrior.cpp @@ -0,0 +1,95 @@ +/** + * @file testPoseRotationPrior.cpp + * + * @brief Tests rotation priors on poses + * + * @date Jun 14, 2012 + * @author Alex Cunningham + */ + +#include + +#include + +#include +#include + +#include + +using namespace gtsam; + +const SharedNoiseModel model1 = noiseModel::Diagonal::Sigmas(Vector_(1, 0.1)); +const SharedNoiseModel model3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3)); + +typedef PoseRotationPrior Pose2RotationPrior; +typedef PoseRotationPrior Pose3RotationPrior; + +const double tol = 1e-5; + +const gtsam::Key poseKey = 1; + +// Pose3 examples +const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); +const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::Expmap(Vector_(3, 0.1, 0.2, 0.3)); + +// Pose2 examples +const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); +const Rot2 rot2A, rot2B = Rot2::fromAngle(M_PI_2); + +/* ************************************************************************* */ +LieVector evalFactorError3(const Pose3RotationPrior& factor, const Pose3& x) { + return LieVector(factor.evaluateError(x)); +} + +/* ************************************************************************* */ +LieVector evalFactorError2(const Pose2RotationPrior& factor, const Pose2& x) { + return LieVector(factor.evaluateError(x)); +} + +/* ************************************************************************* */ +TEST( testPoseRotationFactor, level3_zero_error ) { + Pose3 pose1(rot3A, point3A); + Pose3RotationPrior factor(poseKey, rot3A, model3); + Matrix actH1; + EXPECT(assert_equal(zero(3), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseRotationFactor, level3_error ) { + Pose3 pose1(rot3A, point3A); + Pose3RotationPrior factor(poseKey, rot3C, model3); + Matrix actH1; + EXPECT(assert_equal(Vector_(3,-0.1,-0.2,-0.3), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseRotationFactor, level2_zero_error ) { + Pose2 pose1(rot2A, point2A); + Pose2RotationPrior factor(poseKey, rot2A, model1); + Matrix actH1; + EXPECT(assert_equal(zero(1), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError2, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseRotationFactor, level2_error ) { + Pose2 pose1(rot2A, point2A); + Pose2RotationPrior factor(poseKey, rot2B, model1); + Matrix actH1; + EXPECT(assert_equal(Vector_(1,-M_PI_2), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError2, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testPoseTranslationPrior.cpp b/gtsam_unstable/slam/tests/testPoseTranslationPrior.cpp new file mode 100644 index 000000000..9e11555ee --- /dev/null +++ b/gtsam_unstable/slam/tests/testPoseTranslationPrior.cpp @@ -0,0 +1,136 @@ +/** + * @file testPoseTranslationPrior.cpp + * + * @date Aug 19, 2012 + * @author Alex Cunningham + */ + +#include + +#include +#include +#include + +#include + +using namespace gtsam; + +const SharedNoiseModel model2 = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); +const SharedNoiseModel model3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3)); + +typedef PoseTranslationPrior Pose2TranslationPrior; +typedef PoseTranslationPrior Pose3TranslationPrior; + +const double tol = 1e-5; + +const gtsam::Key poseKey = 1; + +// Pose3 examples +const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); +const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::RzRyRx(0.1, 0.2, 0.3); + +// Pose2 examples +const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); +const Rot2 rot2A, rot2B = Rot2::fromAngle(M_PI_2); + +/* ************************************************************************* */ +LieVector evalFactorError3(const Pose3TranslationPrior& factor, const Pose3& x) { + return LieVector(factor.evaluateError(x)); +} + +/* ************************************************************************* */ +LieVector evalFactorError2(const Pose2TranslationPrior& factor, const Pose2& x) { + return LieVector(factor.evaluateError(x)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, level3_zero_error ) { + Pose3 pose1(rot3A, point3A); + Pose3TranslationPrior factor(poseKey, point3A, model3); + Matrix actH1; + EXPECT(assert_equal(zero(3), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, level3_error ) { + Pose3 pose1(rot3A, point3A); + Pose3TranslationPrior factor(poseKey, point3B, model3); + Matrix actH1; + EXPECT(assert_equal(Vector_(3,-3.0,-4.0,-5.0), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, pitched3_zero_error ) { + Pose3 pose1(rot3B, point3A); + Pose3TranslationPrior factor(poseKey, point3A, model3); + Matrix actH1; + EXPECT(assert_equal(zero(3), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, pitched3_error ) { + Pose3 pose1(rot3B, point3A); + Pose3TranslationPrior factor(poseKey, point3B, model3); + Matrix actH1; + EXPECT(assert_equal(Vector_(3,-3.0,-4.0,-5.0), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, smallrot3_zero_error ) { + Pose3 pose1(rot3C, point3A); + Pose3TranslationPrior factor(poseKey, point3A, model3); + Matrix actH1; + EXPECT(assert_equal(zero(3), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, smallrot3_error ) { + Pose3 pose1(rot3C, point3A); + Pose3TranslationPrior factor(poseKey, point3B, model3); + Matrix actH1; + EXPECT(assert_equal(Vector_(3,-3.0,-4.0,-5.0), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, level2_zero_error ) { + Pose2 pose1(rot2A, point2A); + Pose2TranslationPrior factor(poseKey, point2A, model2); + Matrix actH1; + EXPECT(assert_equal(zero(2), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError2, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +TEST( testPoseTranslationFactor, level2_error ) { + Pose2 pose1(rot2A, point2A); + Pose2TranslationPrior factor(poseKey, point2B, model2); + Matrix actH1; + EXPECT(assert_equal(Vector_(2,-3.0,-4.0), factor.evaluateError(pose1, actH1))); + Matrix expH1 = numericalDerivative11( + boost::bind(evalFactorError2, factor, _1), pose1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp new file mode 100644 index 000000000..321464c48 --- /dev/null +++ b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp @@ -0,0 +1,138 @@ +/** + * @file testRelativeElevationFactor.cpp + * + * @date Aug 17, 2012 + * @author Alex Cunningham + */ + +#include + +#include + +#include + +using namespace gtsam; + +SharedNoiseModel model1 = noiseModel::Unit::Create(1); + +const double tol = 1e-5; + +const Pose3 pose1(Rot3(), Point3(2.0, 3.0, 4.0)); +const Pose3 pose2(Rot3::pitch(-M_PI_2), Point3(2.0, 3.0, 4.0)); +const Pose3 pose3(Rot3::RzRyRx(0.1, 0.2, 0.3), Point3(2.0, 3.0, 4.0)); +const Point3 point1(3.0, 4.0, 2.0); +const gtsam::Key poseKey = 1, pointKey = 2; + +/* ************************************************************************* */ +LieVector evalFactorError(const RelativeElevationFactor& factor, const Pose3& x, const Point3& p) { + return LieVector(factor.evaluateError(x, p)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, level_zero_error ) { + // Zero error + double measured = 2.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(zero(1), factor.evaluateError(pose1, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, level_positive ) { + // Positive meas + double measured = 0.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(Vector_(1, 2.0), factor.evaluateError(pose1, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, level_negative ) { + // Negative meas + double measured = -1.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(Vector_(1, 3.0), factor.evaluateError(pose1, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, rotated_zero_error ) { + // Zero error + double measured = 2.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(zero(1), factor.evaluateError(pose2, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, rotated_positive ) { + // Positive meas + double measured = 0.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(Vector_(1, 2.0), factor.evaluateError(pose2, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, rotated_negative1 ) { + // Negative meas + double measured = -1.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(Vector_(1, 3.0), factor.evaluateError(pose2, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +TEST( testRelativeElevationFactor, rotated_negative2 ) { + // Negative meas + double measured = -1.0; + RelativeElevationFactor factor(poseKey, pointKey, measured, model1); + Matrix actH1, actH2; + EXPECT(assert_equal(Vector_(1, 3.0), factor.evaluateError(pose3, point1, actH1, actH2))); + Matrix expH1 = numericalDerivative21( + boost::bind(evalFactorError, factor, _1, _2), pose3, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + boost::bind(evalFactorError, factor, _1, _2), pose3, point1, 1e-5); + EXPECT(assert_equal(expH1, actH1, tol)); + EXPECT(assert_equal(expH2, actH2, tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/makedoc.sh b/makedoc.sh deleted file mode 100755 index 5acbd3d87..000000000 --- a/makedoc.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/sh - -# Add to PATH the default install path for doxygen on Mac OS X - -PATH=$PATH:/Applications/Doxygen.app/Contents/Resources - - -# Run doxygen from the gtsam directory even if this script is run from another -# directory, so that the output 'doc' goes in the gtsam directory. - -GTSAM_DIR=$(dirname "$0") -cd $GTSAM_DIR -doxygen \ No newline at end of file diff --git a/makestats.sh b/makestats.sh new file mode 100644 index 000000000..f1201ddd0 --- /dev/null +++ b/makestats.sh @@ -0,0 +1 @@ +java -jar ~/src/statsvn-0.7.0/statsvn.jar -output-dir stats -exclude "examples/Data/**/*;gtsam/3rdparty/**/*" logfile.log . diff --git a/matlab.h b/matlab.h new file mode 100644 index 000000000..dfc0117e7 --- /dev/null +++ b/matlab.h @@ -0,0 +1,142 @@ +/* ---------------------------------------------------------------------------- + + * 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 matlab.h + * @brief Contains *generic* global functions designed particularly for the matlab interface + * @author Stephen Williams + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace gtsam { + + namespace utilities { + + /// Extract all Point2 values into a single matrix [x y] + Matrix extractPoint2(const Values& values) { + size_t j=0; + Values::ConstFiltered points = values.filter(); + Matrix result(points.size(),2); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, points) + result.row(j++) = key_value.value.vector(); + return result; + } + + /// Extract all Point3 values into a single matrix [x y z] + Matrix extractPoint3(const Values& values) { + size_t j=0; + Values::ConstFiltered points = values.filter(); + Matrix result(points.size(),3); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, points) + result.row(j++) = key_value.value.vector(); + return result; + } + + /// Extract all Pose2 values into a single matrix [x y theta] + Matrix extractPose2(const Values& values) { + size_t j=0; + Values::ConstFiltered poses = values.filter(); + Matrix result(poses.size(),3); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, poses) + result.row(j++) << key_value.value.x(), key_value.value.y(), key_value.value.theta(); + return result; + } + + /// Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z] + Matrix extractPose3(const Values& values) { + size_t j=0; + Values::ConstFiltered poses = values.filter(); + Matrix result(poses.size(),12); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, poses) { + result.row(j).segment(0, 3) << key_value.value.rotation().matrix().row(0); + result.row(j).segment(3, 3) << key_value.value.rotation().matrix().row(1); + result.row(j).segment(6, 3) << key_value.value.rotation().matrix().row(2); + result.row(j).tail(3) = key_value.value.translation().vector(); + j++; + } + return result; + } + + + /// perturb all Point2 using normally distributed noise + void perturbPoint2(Values& values, double sigma, int32_t seed = 42u) { + noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,sigma); + Sampler sampler(model, seed); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, values.filter()) { + values.update(key_value.key, key_value.value.retract(sampler.sample())); + } + } + + /// perturb all Point3 using normally distributed noise + void perturbPoint3(Values& values, double sigma, int32_t seed = 42u) { + noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,sigma); + Sampler sampler(model, seed); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, values.filter()) { + values.update(key_value.key, key_value.value.retract(sampler.sample())); + } + } + + /// insert a number of initial point values by backprojecting + void insertBackprojections(Values& values, const SimpleCamera& camera, const Vector& J, const Matrix& Z, double depth) { + if (Z.rows() != 2) throw std::invalid_argument("insertBackProjections: Z must be 2*K"); + if (Z.cols() != J.size()) throw std::invalid_argument("insertBackProjections: J and Z must have same number of entries"); + for(int k=0;k > + (Point2(Z(0, k), Z(1, k)), model, i, Key(J(k)), K)); + } + } + + /// calculate the errors of all projection factors in a graph + Matrix reprojectionErrors(const NonlinearFactorGraph& graph, const Values& values) { + // first count + size_t K = 0, k=0; + BOOST_FOREACH(const NonlinearFactor::shared_ptr& f, graph) + if (boost::dynamic_pointer_cast >(f)) ++K; + // now fill + Matrix errors(2,K); + BOOST_FOREACH(const NonlinearFactor::shared_ptr& f, graph) { + boost::shared_ptr > p = boost::dynamic_pointer_cast >(f); + if (p) errors.col(k++) = p->unwhitenedError(values); + } + return errors; + } + + } + +} + diff --git a/tests/matlab/CHECK.m b/matlab/+gtsam/CHECK.m similarity index 100% rename from tests/matlab/CHECK.m rename to matlab/+gtsam/CHECK.m diff --git a/matlab/+gtsam/Contents.m b/matlab/+gtsam/Contents.m new file mode 100644 index 000000000..0af19e1c8 --- /dev/null +++ b/matlab/+gtsam/Contents.m @@ -0,0 +1,161 @@ +% GTSAM MATLAB toolbox interface to the Georgia Tech Smoothing and Mapping C++ library +% Version 2.1 08-Sep-2012 +% +%% Basic Utilities +% linear_independent - check whether the rows of two matrices are linear independent +% Permutation - class Permutation, see Doxygen page for details +% +%% General Inference Classes +% IndexConditional - class IndexConditional, see Doxygen page for details +% IndexFactor - class IndexFactor, see Doxygen page for details +% SymbolicBayesNet - class SymbolicBayesNet, see Doxygen page for details +% SymbolicBayesTree - class SymbolicBayesTree, see Doxygen page for details +% SymbolicFactorGraph - class SymbolicFactorGraph, see Doxygen page for details +% SymbolicMultifrontalSolver - class SymbolicMultifrontalSolver, see Doxygen page for details +% SymbolicSequentialSolver - class SymbolicSequentialSolver, see Doxygen page for details +% VariableIndex - class VariableIndex, see Doxygen page for details +% +%% Linear-Gaussian Factor Graphs +% Errors - class Errors, see Doxygen page for details +% GaussianBayesNet - class GaussianBayesNet, see Doxygen page for details +% GaussianConditional - class GaussianConditional, see Doxygen page for details +% GaussianDensity - class GaussianDensity, see Doxygen page for details +% GaussianFactor - class GaussianFactor, see Doxygen page for details +% GaussianFactorGraph - class GaussianFactorGraph, see Doxygen page for details +% GaussianISAM - class GaussianISAM, see Doxygen page for details +% HessianFactor - class HessianFactor, see Doxygen page for details +% JacobianFactor - class JacobianFactor, see Doxygen page for details +% VectorValues - class VectorValues, see Doxygen page for details +% +%% Linear Inference +% GaussianSequentialSolver - class GaussianSequentialSolver, see Doxygen page for details +% IterativeOptimizationParameters - class IterativeOptimizationParameters, see Doxygen page for details +% KalmanFilter - class KalmanFilter, see Doxygen page for details +% SubgraphSolver - class SubgraphSolver, see Doxygen page for details +% SubgraphSolverParameters - class SubgraphSolverParameters, see Doxygen page for details +% SuccessiveLinearizationParams - class SuccessiveLinearizationParams, see Doxygen page for details +% Sampler - class Sampler, see Doxygen page for details +% +%% Nonlinear Factor Graphs +% NonlinearFactor - class NonlinearFactor, see Doxygen page for details +% NonlinearFactorGraph - class NonlinearFactorGraph, see Doxygen page for details +% Ordering - class Ordering, see Doxygen page for details +% Value - class Value, see Doxygen page for details +% Values - class Values, see Doxygen page for details +% +%% Nonlinear Optimization +% ConjugateGradientParameters - class ConjugateGradientParameters, see Doxygen page for details +% DoglegOptimizer - class DoglegOptimizer, see Doxygen page for details +% DoglegParams - class DoglegParams, see Doxygen page for details +% GaussNewtonOptimizer - class GaussNewtonOptimizer, see Doxygen page for details +% GaussNewtonParams - class GaussNewtonParams, see Doxygen page for details +% ISAM2 - class ISAM2, see Doxygen page for details +% ISAM2DoglegParams - class ISAM2DoglegParams, see Doxygen page for details +% ISAM2GaussNewtonParams - class ISAM2GaussNewtonParams, see Doxygen page for details +% ISAM2Params - class ISAM2Params, see Doxygen page for details +% ISAM2Result - class ISAM2Result, see Doxygen page for details +% ISAM2ThresholdMap - class ISAM2ThresholdMap, see Doxygen page for details +% ISAM2ThresholdMapValue - class ISAM2ThresholdMapValue, see Doxygen page for details +% InvertedOrdering - class InvertedOrdering, see Doxygen page for details +% JointMarginal - class JointMarginal, see Doxygen page for details +% KeyList - class KeyList, see Doxygen page for details +% KeySet - class KeySet, see Doxygen page for details +% KeyVector - class KeyVector, see Doxygen page for details +% LevenbergMarquardtOptimizer - class LevenbergMarquardtOptimizer, see Doxygen page for details +% LevenbergMarquardtParams - class LevenbergMarquardtParams, see Doxygen page for details +% Marginals - class Marginals, see Doxygen page for details +% NonlinearISAM - class NonlinearISAM, see Doxygen page for details +% NonlinearOptimizer - class NonlinearOptimizer, see Doxygen page for details +% NonlinearOptimizerParams - class NonlinearOptimizerParams, see Doxygen page for details +% +%% Geometry +% Cal3_S2 - class Cal3_S2, see Doxygen page for details +% Cal3_S2Stereo - class Cal3_S2Stereo, see Doxygen page for details +% Cal3DS2 - class Cal3DS2, see Doxygen page for details +% CalibratedCamera - class CalibratedCamera, see Doxygen page for details +% Point2 - class Point2, see Doxygen page for details +% Point3 - class Point3, see Doxygen page for details +% Pose2 - class Pose2, see Doxygen page for details +% Pose3 - class Pose3, see Doxygen page for details +% Rot2 - class Rot2, see Doxygen page for details +% Rot3 - class Rot3, see Doxygen page for details +% SimpleCamera - class SimpleCamera, see Doxygen page for details +% StereoPoint2 - class StereoPoint2, see Doxygen page for details +% +%% SLAM and SFM +% BearingFactor2D - class BearingFactor2D, see Doxygen page for details +% BearingRangeFactor2D - class BearingRangeFactor2D, see Doxygen page for details +% BetweenFactorLieMatrix - class BetweenFactorLieMatrix, see Doxygen page for details +% BetweenFactorLieScalar - class BetweenFactorLieScalar, see Doxygen page for details +% BetweenFactorLieVector - class BetweenFactorLieVector, see Doxygen page for details +% BetweenFactorPoint2 - class BetweenFactorPoint2, see Doxygen page for details +% BetweenFactorPoint3 - class BetweenFactorPoint3, see Doxygen page for details +% BetweenFactorPose2 - class BetweenFactorPose2, see Doxygen page for details +% BetweenFactorPose3 - class BetweenFactorPose3, see Doxygen page for details +% BetweenFactorRot2 - class BetweenFactorRot2, see Doxygen page for details +% BetweenFactorRot3 - class BetweenFactorRot3, see Doxygen page for details +% GeneralSFMFactor2Cal3_S2 - class GeneralSFMFactor2Cal3_S2, see Doxygen page for details +% GeneralSFMFactorCal3_S2 - class GeneralSFMFactorCal3_S2, see Doxygen page for details +% GenericProjectionFactorCal3_S2 - class GenericProjectionFactorCal3_S2, see Doxygen page for details +% GenericStereoFactor3D - class GenericStereoFactor3D, see Doxygen page for details +% NonlinearEqualityCal3_S2 - class NonlinearEqualityCal3_S2, see Doxygen page for details +% NonlinearEqualityCalibratedCamera - class NonlinearEqualityCalibratedCamera, see Doxygen page for details +% NonlinearEqualityLieMatrix - class NonlinearEqualityLieMatrix, see Doxygen page for details +% NonlinearEqualityLieScalar - class NonlinearEqualityLieScalar, see Doxygen page for details +% NonlinearEqualityLieVector - class NonlinearEqualityLieVector, see Doxygen page for details +% NonlinearEqualityPoint2 - class NonlinearEqualityPoint2, see Doxygen page for details +% NonlinearEqualityPoint3 - class NonlinearEqualityPoint3, see Doxygen page for details +% NonlinearEqualityPose2 - class NonlinearEqualityPose2, see Doxygen page for details +% NonlinearEqualityPose3 - class NonlinearEqualityPose3, see Doxygen page for details +% NonlinearEqualityRot2 - class NonlinearEqualityRot2, see Doxygen page for details +% NonlinearEqualityRot3 - class NonlinearEqualityRot3, see Doxygen page for details +% NonlinearEqualitySimpleCamera - class NonlinearEqualitySimpleCamera, see Doxygen page for details +% NonlinearEqualityStereoPoint2 - class NonlinearEqualityStereoPoint2, see Doxygen page for details +% PriorFactorCal3_S2 - class PriorFactorCal3_S2, see Doxygen page for details +% PriorFactorCalibratedCamera - class PriorFactorCalibratedCamera, see Doxygen page for details +% PriorFactorLieMatrix - class PriorFactorLieMatrix, see Doxygen page for details +% PriorFactorLieScalar - class PriorFactorLieScalar, see Doxygen page for details +% PriorFactorLieVector - class PriorFactorLieVector, see Doxygen page for details +% PriorFactorPoint2 - class PriorFactorPoint2, see Doxygen page for details +% PriorFactorPoint3 - class PriorFactorPoint3, see Doxygen page for details +% PriorFactorPose2 - class PriorFactorPose2, see Doxygen page for details +% PriorFactorPose3 - class PriorFactorPose3, see Doxygen page for details +% PriorFactorRot2 - class PriorFactorRot2, see Doxygen page for details +% PriorFactorRot3 - class PriorFactorRot3, see Doxygen page for details +% PriorFactorSimpleCamera - class PriorFactorSimpleCamera, see Doxygen page for details +% PriorFactorStereoPoint2 - class PriorFactorStereoPoint2, see Doxygen page for details +% RangeFactorCalibratedCamera - class RangeFactorCalibratedCamera, see Doxygen page for details +% RangeFactorCalibratedCameraPoint - class RangeFactorCalibratedCameraPoint, see Doxygen page for details +% RangeFactorPose2 - class RangeFactorPose2, see Doxygen page for details +% RangeFactorPose3 - class RangeFactorPose3, see Doxygen page for details +% RangeFactorPosePoint2 - class RangeFactorPosePoint2, see Doxygen page for details +% RangeFactorPosePoint3 - class RangeFactorPosePoint3, see Doxygen page for details +% RangeFactorSimpleCamera - class RangeFactorSimpleCamera, see Doxygen page for details +% RangeFactorSimpleCameraPoint - class RangeFactorSimpleCameraPoint, see Doxygen page for details +% VisualISAMGenerateData - VisualISAMGenerateData creates data for viusalSLAM::iSAM examples +% VisualISAMInitialize - VisualISAMInitialize initializes visualSLAM::iSAM object and noise parameters +% VisualISAMPlot - VisualISAMPlot plots current state of ISAM2 object +% VisualISAMStep - VisualISAMStep executes one update step of visualSLAM::iSAM object +% +%% MATLAB-only Utilities +% CHECK - throw an error if an assertion fails +% circlePose2 - circlePose2 generates a set of poses in a circle. This function +% circlePose3 - circlePose3 generates a set of poses in a circle. This function +% covarianceEllipse - covarianceEllipse plots a Gaussian as an uncertainty ellipse +% covarianceEllipse3D - covarianceEllipse3D plots a Gaussian as an uncertainty ellipse +% EQUALITY - test equality of two vectors/matrices up to tolerance +% findExampleDataFile - Find a dataset in the examples folder +% load2D - load2D reads a TORO-style 2D pose graph +% load3D - load3D reads a TORO-style 3D pose graph +% plot2DPoints - Plots the Point2's in a values, with optional covariances +% plot2DTrajectory - Plots the Pose2's in a values, with optional covariances +% plot3DPoints - Plots the Point3's in a values, with optional covariances +% plot3DTrajectory - plot3DTrajectory plots a 3D trajectory +% plotCamera - +% plotPoint2 - plotPoint2 shows a Point2, possibly with covariance matrix +% plotPoint3 - Plot a Point3 with an optional covariance matrix +% plotPose2 - plotPose2 shows a Pose2, possibly with covariance matrix +% plotPose3 - plotPose3 shows a Pose, possibly with covariance matrix +% symbol - create a Symbol key +% symbolChr - get character from a symbol key +% symbolIndex - get index from a symbol key diff --git a/matlab/+gtsam/EQUALITY.m b/matlab/+gtsam/EQUALITY.m new file mode 100644 index 000000000..a387e1154 --- /dev/null +++ b/matlab/+gtsam/EQUALITY.m @@ -0,0 +1,19 @@ +function EQUALITY(name,expected,actual,tol) +% test equality of two vectors/matrices up to tolerance + +if nargin<4,tol=1e-9;end + +sameSize = size(expected)==size(actual); +if all(sameSize) + equal = abs(expected-actual)xZ--> Y (z pointing towards viewer, Z pointing away from viewer) +% Vehicle at p0 is looking towards y axis (X-axis points towards world y) + +if nargin<3,symbolChar=0;end +if nargin<2,radius=1.0;end +if nargin<1,numPoses=8;end + +% Force symbolChar to be a single character +symbolChar = char(symbolChar); +symbolChar = symbolChar(1); + +values = gtsam.Values; +theta = 0.0; +dtheta = 2*pi()/numPoses; +for i = 1:numPoses + key = gtsam.symbol(symbolChar, i-1); + pose = gtsam.Pose2(radius*cos(theta), radius*sin(theta), pi()/2 + theta); + values.insert(key, pose); + theta = theta + dtheta; +end diff --git a/matlab/+gtsam/circlePose3.m b/matlab/+gtsam/circlePose3.m new file mode 100644 index 000000000..686bce7cf --- /dev/null +++ b/matlab/+gtsam/circlePose3.m @@ -0,0 +1,33 @@ +function values = circlePose3(numPoses, radius, symbolChar) +% circlePose3 generates a set of poses in a circle. This function +% returns those poses inside a gtsam.Values object, with sequential +% keys starting from 0. An optional character may be provided, which +% will be stored in the msb of each key (i.e. gtsam.Symbol). +% +% We use aerospace/navlab convention, X forward, Y right, Z down +% First pose will be at (R,0,0) +% ^y ^ X +% | | +% z-->xZ--> Y (z pointing towards viewer, Z pointing away from viewer) +% Vehicle at p0 is looking towards y axis (X-axis points towards world y) + +if nargin<3,symbolChar=0;end +if nargin<2,radius=1.0;end +if nargin<1,numPoses=8;end + +% Force symbolChar to be a single character +symbolChar = char(symbolChar); +symbolChar = symbolChar(1); + +values = gtsam.Values; +theta = 0.0; +dtheta = 2*pi()/numPoses; +gRo = gtsam.Rot3([0, 1, 0 ; 1, 0, 0 ; 0, 0, -1]); +for i = 1:numPoses + key = gtsam.symbol(symbolChar, i-1); + gti = gtsam.Point3(radius*cos(theta), radius*sin(theta), 0); + oRi = gtsam.Rot3.Yaw(-theta); % negative yaw goes counterclockwise, with Z down ! + gTi = gtsam.Pose3(gRo.compose(oRi), gti); + values.insert(key, gTi); + theta = theta + dtheta; +end diff --git a/matlab/+gtsam/covarianceEllipse.m b/matlab/+gtsam/covarianceEllipse.m new file mode 100644 index 000000000..7728fc866 --- /dev/null +++ b/matlab/+gtsam/covarianceEllipse.m @@ -0,0 +1,34 @@ +function covarianceEllipse(x,P,color) +% covarianceEllipse plots a Gaussian as an uncertainty ellipse +% Based on Maybeck Vol 1, page 366 +% k=2.296 corresponds to 1 std, 68.26% of all probability +% k=11.82 corresponds to 3 std, 99.74% of all probability +% +% covarianceEllipse(x,P,color) +% it is assumed x and y are the first two components of state x + +[e,s] = eig(P(1:2,1:2)); +s1 = s(1,1); +s2 = s(2,2); +k = 2.296; +[ex,ey] = ellipse( sqrt(s1*k)*e(:,1), sqrt(s2*k)*e(:,2), x(1:2) ); +line(ex,ey,'color',color); + + function [x,y] = ellipse(a,b,c); + % ellipse: return the x and y coordinates for an ellipse + % [x,y] = ellipse(a,b,c); + % a, and b are the axes. c is the center + + global ellipse_x ellipse_y + if ~exist('elipse_x') + q =0:2*pi/25:2*pi; + ellipse_x = cos(q); + ellipse_y = sin(q); + end + + points = a*ellipse_x + b*ellipse_y; + x = c(1) + points(1,:); + y = c(2) + points(2,:); + end + +end \ No newline at end of file diff --git a/matlab/+gtsam/covarianceEllipse3D.m b/matlab/+gtsam/covarianceEllipse3D.m new file mode 100644 index 000000000..9682a9fc1 --- /dev/null +++ b/matlab/+gtsam/covarianceEllipse3D.m @@ -0,0 +1,27 @@ +function covarianceEllipse3D(c,P) +% covarianceEllipse3D plots a Gaussian as an uncertainty ellipse +% Based on Maybeck Vol 1, page 366 +% k=2.296 corresponds to 1 std, 68.26% of all probability +% k=11.82 corresponds to 3 std, 99.74% of all probability +% +% Modified from http://www.mathworks.com/matlabcentral/newsreader/view_thread/42966 + +[e,s] = svd(P); +k = 11.82; +radii = k*sqrt(diag(s)); + +% generate data for "unrotated" ellipsoid +[xc,yc,zc] = ellipsoid(0,0,0,radii(1),radii(2),radii(3),8); + +% rotate data with orientation matrix U and center M +data = kron(e(:,1),xc) + kron(e(:,2),yc) + kron(e(:,3),zc); +n = size(data,2); +x = data(1:n,:)+c(1); +y = data(n+1:2*n,:)+c(2); +z = data(2*n+1:end,:)+c(3); + +% now plot the rotated ellipse +sc = surf(x,y,z,abs(xc)); +shading interp +alpha(0.5) +axis equal \ No newline at end of file diff --git a/matlab/+gtsam/findExampleDataFile.m b/matlab/+gtsam/findExampleDataFile.m new file mode 100644 index 000000000..9c40960b9 --- /dev/null +++ b/matlab/+gtsam/findExampleDataFile.m @@ -0,0 +1,19 @@ +function datafile = findExampleDataFile(datasetName) +%FINDEXAMPLEDATAFILE Find a dataset in the examples folder + +[ myPath, ~, ~ ] = fileparts(mfilename('fullpath')); +searchPath = { ... + fullfile(myPath, [ '../../examples/Data/' datasetName ]) ... + fullfile(myPath, [ '../gtsam_examples/Data/' datasetName ]) }; +datafile = []; +for path = searchPath + if exist(path{:}, 'file') + datafile = path{:}; + end +end +if isempty(datafile) + error([ 'Could not find example data file ' datasetName ]); +end + +end + diff --git a/matlab/+gtsam/load3D.m b/matlab/+gtsam/load3D.m new file mode 100644 index 000000000..94202e0c8 --- /dev/null +++ b/matlab/+gtsam/load3D.m @@ -0,0 +1,58 @@ +function [graph,initial] = load3D(filename,model,successive,N) +% load3D reads a TORO-style 3D pose graph +% cannot read noise model from file yet, uses specified model +% if [successive] is tru, constructs initial estimate from odometry + +import gtsam.* + +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 = NonlinearFactorGraph; +initial = Values; +origin=gtsam.Pose3; +initial.insert(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); + i1=v{2}; + if (~successive && i1i1 + initial.insert(i2,initial.at(i1).compose(dpose)); + else + initial.insert(i1,initial.at(i2).compose(dpose.inverse)); + end + end + end + end + end +end + diff --git a/matlab/+gtsam/plot2DPoints.m b/matlab/+gtsam/plot2DPoints.m new file mode 100644 index 000000000..d4703a5d7 --- /dev/null +++ b/matlab/+gtsam/plot2DPoints.m @@ -0,0 +1,37 @@ +function plot2DPoints(values, linespec, marginals) +%PLOT2DPOINTS Plots the Point2's in a values, with optional covariances +% Finds all the Point2 objects in the given Values object and plots them. +% If a Marginals object is given, this function will also plot marginal +% covariance ellipses for each point. + +import gtsam.* + +if ~exist('linespec', 'var') || isempty(linespec) + linespec = 'g'; +end +haveMarginals = exist('marginals', 'var'); +keys = KeyVector(values.keys); + +holdstate = ishold; +hold on + +% Plot points and covariance matrices +for i = 0:keys.size-1 + key = keys.at(i); + p = values.at(key); + if isa(p, 'gtsam.Point2') + if haveMarginals + P = marginals.marginalCovariance(key); + gtsam.plotPoint2(p, linespec, P); + else + gtsam.plotPoint2(p, linespec); + end + end +end + +if ~holdstate + hold off +end + +end + diff --git a/matlab/+gtsam/plot2DTrajectory.m b/matlab/+gtsam/plot2DTrajectory.m new file mode 100644 index 000000000..329026398 --- /dev/null +++ b/matlab/+gtsam/plot2DTrajectory.m @@ -0,0 +1,54 @@ +function plot2DTrajectory(values, linespec, marginals) +%PLOT2DTRAJECTORY Plots the Pose2's in a values, with optional covariances +% Finds all the Pose2 objects in the given Values object and plots them +% in increasing key order, connecting consecutive poses with a line. If +% a Marginals object is given, this function will also plot marginal +% covariance ellipses for each pose. + +import gtsam.* + +if ~exist('linespec', 'var') || isempty(linespec) + linespec = 'k*-'; +end + +haveMarginals = exist('marginals', 'var'); +keys = KeyVector(values.keys); + +holdstate = ishold; +hold on + +% Plot poses and covariance matrices +lastIndex = []; +for i = 0:keys.size-1 + key = keys.at(i); + x = values.at(key); + if isa(x, 'gtsam.Pose2') + if ~isempty(lastIndex) + % Draw line from last pose then covariance ellipse on top of + % last pose. + lastKey = keys.at(lastIndex); + lastPose = values.at(lastKey); + plot([ x.x; lastPose.x ], [ x.y; lastPose.y ], linespec); + if haveMarginals + P = marginals.marginalCovariance(lastKey); + gtsam.plotPose2(lastPose, 'g', P); + end + end + lastIndex = i; + end +end + +% Draw final covariance ellipse +if ~isempty(lastIndex) && haveMarginals + lastKey = keys.at(lastIndex); + lastPose = values.at(lastKey); + P = marginals.marginalCovariance(lastKey); + gtsam.plotPose2(lastPose, 'g', P); +end + +if ~holdstate + hold off +end + +end + diff --git a/matlab/+gtsam/plot3DPoints.m b/matlab/+gtsam/plot3DPoints.m new file mode 100644 index 000000000..8feab1744 --- /dev/null +++ b/matlab/+gtsam/plot3DPoints.m @@ -0,0 +1,36 @@ +function plot3DPoints(values, linespec, marginals) +%PLOT3DPOINTS Plots the Point3's in a values, with optional covariances +% Finds all the Point3 objects in the given Values object and plots them. +% If a Marginals object is given, this function will also plot marginal +% covariance ellipses for each point. + +import gtsam.* + +if ~exist('linespec', 'var') || isempty(linespec) + linespec = 'g'; +end +haveMarginals = exist('marginals', 'var'); +keys = KeyVector(values.keys); + +holdstate = ishold; +hold on + +% Plot points and covariance matrices +for i = 0:keys.size-1 + key = keys.at(i); + p = values.at(key); + if isa(p, 'gtsam.Point3') + if haveMarginals + P = marginals.marginalCovariance(key); + gtsam.plotPoint3(p, linespec, P); + else + gtsam.plotPoint3(p, linespec); + end + end +end + +if ~holdstate + hold off +end + +end diff --git a/matlab/+gtsam/plot3DTrajectory.m b/matlab/+gtsam/plot3DTrajectory.m new file mode 100644 index 000000000..d24e21297 --- /dev/null +++ b/matlab/+gtsam/plot3DTrajectory.m @@ -0,0 +1,55 @@ +function plot3DTrajectory(values,linespec,frames,scale,marginals) +% plot3DTrajectory plots a 3D trajectory +% plot3DTrajectory(values,linespec,frames,scale,marginals) + +if ~exist('scale','var') || isempty(scale), scale=1; end +if ~exist('frames','var'), scale=[]; end + +import gtsam.* + +haveMarginals = exist('marginals', 'var'); +keys = KeyVector(values.keys); + +holdstate = ishold; +hold on + +% Plot poses and covariance matrices +lastIndex = []; +for i = 0:keys.size-1 + key = keys.at(i); + x = values.at(key); + if isa(x, 'gtsam.Pose3') + if ~isempty(lastIndex) + % Draw line from last pose then covariance ellipse on top of + % last pose. + lastKey = keys.at(lastIndex); + lastPose = values.at(lastKey); + plot3([ x.x; lastPose.x ], [ x.y; lastPose.y ], [ x.z; lastPose.z ], linespec); + if haveMarginals + P = marginals.marginalCovariance(lastKey); + else + P = []; + end + gtsam.plotPose3(lastPose, P, scale); + end + lastIndex = i; + end +end + +% Draw final pose +if ~isempty(lastIndex) + lastKey = keys.at(lastIndex); + lastPose = values.at(lastKey); + if haveMarginals + P = marginals.marginalCovariance(lastKey); + else + P = []; + end + gtsam.plotPose3(lastPose, P, scale); +end + +if ~holdstate + hold off +end + +end \ No newline at end of file diff --git a/matlab/+gtsam/plotCamera.m b/matlab/+gtsam/plotCamera.m new file mode 100644 index 000000000..ba352b757 --- /dev/null +++ b/matlab/+gtsam/plotCamera.m @@ -0,0 +1,18 @@ +function plotCamera(pose, axisLength) + C = pose.translation().vector(); + R = pose.rotation().matrix(); + + xAxis = C+R(:,1)*axisLength; + L = [C xAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','r'); + + yAxis = C+R(:,2)*axisLength; + L = [C yAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','g'); + + zAxis = C+R(:,3)*axisLength; + L = [C zAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','b'); + + axis equal +end \ No newline at end of file diff --git a/matlab/+gtsam/plotPoint2.m b/matlab/+gtsam/plotPoint2.m new file mode 100644 index 000000000..55e476118 --- /dev/null +++ b/matlab/+gtsam/plotPoint2.m @@ -0,0 +1,10 @@ +function plotPoint2(p,color,P) +% plotPoint2 shows a Point2, possibly with covariance matrix +if size(color,2)==1 + plot(p.x,p.y,[color '*']); +else + plot(p.x,p.y,color); +end +if exist('P', 'var') + gtsam.covarianceEllipse([p.x;p.y],P,color(1)); +end \ No newline at end of file diff --git a/matlab/+gtsam/plotPoint3.m b/matlab/+gtsam/plotPoint3.m new file mode 100644 index 000000000..390b44939 --- /dev/null +++ b/matlab/+gtsam/plotPoint3.m @@ -0,0 +1,13 @@ +function plotPoint3(p, color, P) +%PLOTPOINT3 Plot a Point3 with an optional covariance matrix +if size(color,2)==1 + plot3(p.x,p.y,p.z,[color '*']); +else + plot3(p.x,p.y,p.z,color); +end +if exist('P', 'var') + gtsam.covarianceEllipse3D([p.x;p.y;p.z],P); +end + +end + diff --git a/matlab/+gtsam/plotPose2.m b/matlab/+gtsam/plotPose2.m new file mode 100644 index 000000000..799bad48e --- /dev/null +++ b/matlab/+gtsam/plotPose2.m @@ -0,0 +1,13 @@ +function plotPose2(pose,color,P,axisLength) +% plotPose2 shows a Pose2, possibly with covariance matrix +if nargin<4,axisLength=0.1;end + +plot(pose.x,pose.y,[color '*']); +c = cos(pose.theta); +s = sin(pose.theta); +quiver(pose.x,pose.y,c,s,axisLength,color); +if nargin>2 + pPp = P(1:2,1:2); % covariance matrix in pose coordinate frame + gRp = [c -s;s c]; % rotation from pose to global + gtsam.covarianceEllipse([pose.x;pose.y],gRp*pPp*gRp',color); +end \ No newline at end of file diff --git a/matlab/+gtsam/plotPose3.m b/matlab/+gtsam/plotPose3.m new file mode 100644 index 000000000..8c3c7dd76 --- /dev/null +++ b/matlab/+gtsam/plotPose3.m @@ -0,0 +1,31 @@ +function plotPose3(pose, P, axisLength) +% plotPose3 shows a Pose, possibly with covariance matrix +if nargin<3,axisLength=0.1;end + +% get rotation and translation (center) +gRp = pose.rotation().matrix(); % rotation from pose to global +C = pose.translation().vector(); + +if ~isempty(axisLength) + % draw the camera axes + xAxis = C+gRp(:,1)*axisLength; + L = [C xAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','r'); + + yAxis = C+gRp(:,2)*axisLength; + L = [C yAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','g'); + + zAxis = C+gRp(:,3)*axisLength; + L = [C zAxis]'; + line(L(:,1),L(:,2),L(:,3),'Color','b'); +end + +% plot the covariance +if (nargin>2) && (~isempty(P)) + pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + gtsam.covarianceEllipse3D(C,gPp); +end + +end diff --git a/matlab/CMakeLists.txt b/matlab/CMakeLists.txt new file mode 100644 index 000000000..16cfb501a --- /dev/null +++ b/matlab/CMakeLists.txt @@ -0,0 +1,22 @@ +# Install matlab components + +# Tests +message(STATUS "Installing Matlab Toolbox Tests") +install(DIRECTORY "${GTSAM_SOURCE_ROOT_DIR}/matlab/gtsam_tests" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}" FILES_MATCHING PATTERN "*.m" PATTERN ".svn" EXCLUDE) + +# Examples +message(STATUS "Installing Matlab Toolbox Examples") +# Matlab files: *.m and *.fig +install(DIRECTORY "${GTSAM_SOURCE_ROOT_DIR}/matlab/gtsam_examples" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}" FILES_MATCHING PATTERN "*.m" PATTERN "*.fig" PATTERN ".svn" EXCLUDE) + +# Utilities +message(STATUS "Installing Matlab Toolbox Utilities") +install(DIRECTORY "${GTSAM_SOURCE_ROOT_DIR}/matlab/+gtsam" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}" FILES_MATCHING PATTERN "*.m" PATTERN ".svn" EXCLUDE) +install(FILES "${GTSAM_SOURCE_ROOT_DIR}/matlab/README-gtsam-toolbox.txt" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}") + +message(STATUS "Installing Matlab Toolbox Examples (Data)") +# Data files: *.graph and *.txt +file(GLOB matlab_examples_data_graph "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.graph") +file(GLOB matlab_examples_data_txt "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.txt") +set(matlab_examples_data ${matlab_examples_data_graph} ${matlab_examples_data_txt}) +install(FILES ${matlab_examples_data} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam_examples/Data) diff --git a/matlab/README-gtsam-toolbox.txt b/matlab/README-gtsam-toolbox.txt new file mode 100644 index 000000000..6f74f9806 --- /dev/null +++ b/matlab/README-gtsam-toolbox.txt @@ -0,0 +1,76 @@ +================================================================================ +GTSAM - Georgia Tech Smoothing and Mapping Library + +MATLAB wrapper + +http://borg.cc.gatech.edu/projects/gtsam +================================================================================ + +This is the GTSAM MATLAB toolbox, a MATLAB wrapper around the GTSAM C++ +library. + + +---------------------------------------- +Note about newer Ubuntu versions unsupported by MATLAB (later than 10.04) +---------------------------------------- + +If you have a newer Ubuntu system, you must make a small modification to your +MATLAB installation, due to MATLAB being distributed with an old version of +the C++ standard library. Delete or rename all files starting with +'libstdc++' in your MATLAB installation directory, in paths: + + /usr/local/MATLAB/[version]/sys/os/[system]/ + /usr/local/MATLAB/[version]/bin/[system]/ + + +---------------------------------------- +Adding the toolbox to your MATLAB path +---------------------------------------- + +To get started, first add the 'toolbox' folder to your MATLAB path - in the +MATLAB file browser, right-click on the folder and click 'Add to path -> This +folder' (do not add the subfolders to your path). + + +---------------------------------------- +Trying out the examples +---------------------------------------- + +The examples are located in the 'gtsam_examples' subfolder. You may either +run them individually at the MATLAB command line, or open the GTSAM example +GUI by running 'gtsamExamples'. Example: + +>> cd /Users/yourname/toolbox % Change to wherever you installed the toolbox +>> cd gtsam_examples % Change to the examples directory +>> gtsamExamples % Run the GTSAM examples GUI + + +---------------------------------------- +Running the unit tests +---------------------------------------- + +The GTSAM MATLAB toolbox also has a small set of unit tests located in the +gtsam_tests directory. Example: + +>> cd /Users/yourname/toolbox % Change to wherever you installed the toolbox +>> cd gtsam_tests % Change to the examples directory +>> test_gtsam % Run the unit tests +Starting: testJacobianFactor +Starting: testKalmanFilter +Starting: testLocalizationExample +Starting: testOdometryExample +Starting: testPlanarSLAMExample +Starting: testPose2SLAMExample +Starting: testPose3SLAMExample +Starting: testSFMExample +Starting: testStereoVOExample +Starting: testVisualISAMExample +Tests complete! + + +---------------------------------------- +Writing your own code +---------------------------------------- + +Coding for the GTSAM MATLAB toolbox is straightforward and very fast once you +understand a few basic concepts! Please see the manual to get started. diff --git a/matlab/gtsam_examples/LocalizationExample.m b/matlab/gtsam_examples/LocalizationExample.m new file mode 100644 index 000000000..2dcb5341b --- /dev/null +++ b/matlab/gtsam_examples/LocalizationExample.m @@ -0,0 +1,59 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 Example of a simple 2D localization example +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - Robot poses are facing along the X axis (horizontal, to the right in 2D) +% - The robot moves 2 meters each step +% - The robot is on a grid, moving 2 meters each step + +%% Create the graph (defined in pose2SLAM.h, derived from NonlinearFactorGraph) +graph = NonlinearFactorGraph; + +%% Add two odometry factors +odometry = Pose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta +graph.add(BetweenFactorPose2(1, 2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(2, 3, odometry, odometryNoise)); + +%% Add three "GPS" measurements +% We use Pose2 Priors here with high variance on theta +priorNoise = noiseModel.Diagonal.Sigmas([0.1; 0.1; 10]); +graph.add(PriorFactorPose2(1, Pose2(0.0, 0.0, 0.0), priorNoise)); +graph.add(PriorFactorPose2(2, Pose2(2.0, 0.0, 0.0), priorNoise)); +graph.add(PriorFactorPose2(3, Pose2(4.0, 0.0, 0.0), priorNoise)); + +%% print +graph.print(sprintf('\nFactor graph:\n')); + +%% Initialize to noisy points +initialEstimate = Values; +initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); +initialEstimate.insert(2, Pose2(2.3, 0.1,-0.2)); +initialEstimate.insert(3, Pose2(4.1, 0.1, 0.1)); +initialEstimate.print(sprintf('\nInitial estimate:\n ')); + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimizeSafely(); +result.print(sprintf('\nFinal result:\n ')); + +%% Plot trajectory and covariance ellipses +cla; +hold on; + +plot2DTrajectory(result, [], Marginals(graph, result)); + +axis([-0.6 4.8 -1 1]) +axis equal +view(2) diff --git a/matlab/gtsam_examples/OdometryExample.m b/matlab/gtsam_examples/OdometryExample.m new file mode 100644 index 000000000..81d2db676 --- /dev/null +++ b/matlab/gtsam_examples/OdometryExample.m @@ -0,0 +1,57 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 Example of a simple 2D localization example +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - Robot poses are facing along the X axis (horizontal, to the right in 2D) +% - The robot moves 2 meters each step +% - The robot is on a grid, moving 2 meters each step + +%% Create the graph (defined in pose2SLAM.h, derived from NonlinearFactorGraph) +graph = NonlinearFactorGraph; + +%% Add a Gaussian prior on pose x_1 +priorMean = Pose2(0.0, 0.0, 0.0); % prior mean is at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta +graph.add(PriorFactorPose2(1, priorMean, priorNoise)); % add directly to graph + +%% Add two odometry factors +odometry = Pose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta +graph.add(BetweenFactorPose2(1, 2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(2, 3, odometry, odometryNoise)); + +%% print +graph.print(sprintf('\nFactor graph:\n')); + +%% Initialize to noisy points +initialEstimate = Values; +initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); +initialEstimate.insert(2, Pose2(2.3, 0.1,-0.2)); +initialEstimate.insert(3, Pose2(4.1, 0.1, 0.1)); +initialEstimate.print(sprintf('\nInitial estimate:\n ')); + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimizeSafely(); +result.print(sprintf('\nFinal result:\n ')); + +%% Plot trajectory and covariance ellipses +cla; +hold on; + +plot2DTrajectory(result, [], Marginals(graph, result)); + +axis([-0.6 4.8 -1 1]) +axis equal +view(2) diff --git a/matlab/gtsam_examples/PlanarSLAMExample.m b/matlab/gtsam_examples/PlanarSLAMExample.m new file mode 100644 index 000000000..ef1516017 --- /dev/null +++ b/matlab/gtsam_examples/PlanarSLAMExample.m @@ -0,0 +1,80 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +% @author Alex Cunningham +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - All values are axis aligned +% - Robot poses are facing along the X axis (horizontal, to the right in images) +% - We have bearing and range information for measurements +% - We have full odometry for measurements +% - The robot and landmarks are on a grid, moving 2 meters each step +% - Landmarks are 2 meters away from the robot trajectory + +%% Create keys for variables +i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); +j1 = symbol('l',1); j2 = symbol('l',2); + +%% Create graph container and add factors to it +graph = NonlinearFactorGraph; + +%% Add prior +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); + +%% Add odometry +odometry = Pose2(2.0, 0.0, 0.0); +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); + +%% Add bearing/range measurement factors +degrees = pi/180; +brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), brNoise)); +graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); + +% print +graph.print(sprintf('\nFull graph:\n')); + +%% Initialize to noisy points +initialEstimate = Values; +initialEstimate.insert(i1, Pose2(0.5, 0.0, 0.2)); +initialEstimate.insert(i2, Pose2(2.3, 0.1,-0.2)); +initialEstimate.insert(i3, Pose2(4.1, 0.1, 0.1)); +initialEstimate.insert(j1, Point2(1.8, 2.1)); +initialEstimate.insert(j2, Point2(4.1, 1.8)); + +initialEstimate.print(sprintf('\nInitial estimate:\n')); + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimizeSafely(); +result.print(sprintf('\nFinal result:\n')); + +%% Plot Covariance Ellipses +cla;hold on + +marginals = Marginals(graph, result); +plot2DTrajectory(result, [], marginals); +plot2DPoints(result, 'b', marginals); + +plot([result.at(i1).x; result.at(j1).x],[result.at(i1).y; result.at(j1).y], 'c-'); +plot([result.at(i2).x; result.at(j1).x],[result.at(i2).y; result.at(j1).y], 'c-'); +plot([result.at(i3).x; result.at(j2).x],[result.at(i3).y; result.at(j2).y], 'c-'); +axis([-0.6 4.8 -1 1]) +axis equal +view(2) + diff --git a/matlab/gtsam_examples/PlanarSLAMExample_graph.m b/matlab/gtsam_examples/PlanarSLAMExample_graph.m new file mode 100644 index 000000000..9ca88e49a --- /dev/null +++ b/matlab/gtsam_examples/PlanarSLAMExample_graph.m @@ -0,0 +1,47 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +clear + +import gtsam.* + +%% Find data file +datafile = findExampleDataFile('example.graph'); + +%% Initialize graph, initial estimate, and odometry noise +model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 2*pi/180]); +[graph,initial] = load2D(datafile, model); + +%% Add a Gaussian prior on a pose in the middle +priorMean = initial.at(40); +priorNoise = noiseModel.Diagonal.Sigmas([0.1; 0.1; 2*pi/180]); +graph.add(PriorFactorPose2(40, priorMean, priorNoise)); % add directly to graph + +%% Plot Initial Estimate +cla +plot2DTrajectory(initial, 'r-'); axis equal + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initial); +tic +result = optimizer.optimizeSafely; +toc + +%% Plot Covariance Ellipses +cla;hold on +marginals = Marginals(graph, result); +plot2DTrajectory(result, 'g', marginals); +plot2DPoints(result, 'b', marginals); +axis tight +axis equal +view(2) + diff --git a/matlab/gtsam_examples/PlanarSLAMExample_sampling.m b/matlab/gtsam_examples/PlanarSLAMExample_sampling.m new file mode 100644 index 000000000..327c64d4d --- /dev/null +++ b/matlab/gtsam_examples/PlanarSLAMExample_sampling.m @@ -0,0 +1,74 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +% @author Alex Cunningham +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Create the same factor graph as in PlanarSLAMExample +i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); +graph = NonlinearFactorGraph; +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph +odometry = Pose2(2.0, 0.0, 0.0); +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); + +%% Except, for measurements we offer a choice +j1 = symbol('l',1); j2 = symbol('l',2); +degrees = pi/180; +brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +if 1 + graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); + graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +else + bearingModel = noiseModel.Diagonal.Sigmas(0.1); + graph.add(BearingFactor2D(i1, j1, Rot2(45*degrees), bearingModel)); + graph.add(BearingFactor2D(i2, j1, Rot2(90*degrees), bearingModel)); +end +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); + +%% Initialize MCMC sampler with ground truth +sample = Values; +sample.insert(i1, Pose2(0,0,0)); +sample.insert(i2, Pose2(2,0,0)); +sample.insert(i3, Pose2(4,0,0)); +sample.insert(j1, Point2(2,2)); +sample.insert(j2, Point2(4,2)); + +%% Calculate and plot Covariance Ellipses +cla;hold on +marginals = Marginals(graph, sample); + +plot2DTrajectory(sample, [], marginals); +plot2DPoints(sample, [], marginals); + +for j=1:2 + key = symbol('l',j); + point{j} = sample.at(key); + Q{j}=marginals.marginalCovariance(key); + S{j}=chol(Q{j}); % for sampling +end + +plot([sample.at(i1).x; sample.at(j1).x],[sample.at(i1).y; sample.at(j1).y], 'c-'); +plot([sample.at(i2).x; sample.at(j1).x],[sample.at(i2).y; sample.at(j1).y], 'c-'); +plot([sample.at(i3).x; sample.at(j2).x],[sample.at(i3).y; sample.at(j2).y], 'c-'); +view(2); axis auto; axis equal + +%% Do Sampling on point 2 +N=1000; +for s=1:N + delta = S{2}*randn(2,1); + proposedPoint = Point2(point{2}.x+delta(1),point{2}.y+delta(2)); + plotPoint2(proposedPoint,'k.') +end \ No newline at end of file diff --git a/matlab/gtsam_examples/Pose2SLAMExample.m b/matlab/gtsam_examples/Pose2SLAMExample.m new file mode 100644 index 000000000..65ce28dbb --- /dev/null +++ b/matlab/gtsam_examples/Pose2SLAMExample.m @@ -0,0 +1,67 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +% @author Alex Cunningham +% @author Frank Dellaert +% @author Chris Beall +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - All values are axis aligned +% - Robot poses are facing along the X axis (horizontal, to the right in images) +% - We have full odometry for measurements +% - The robot is on a grid, moving 2 meters each step + +%% Create graph container and add factors to it +graph = NonlinearFactorGraph; + +%% Add prior +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(1, Pose2(0, 0, 0), priorNoise)); % add directly to graph + +%% Add odometry +model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(1, 2, Pose2(2, 0, 0 ), model)); +graph.add(BetweenFactorPose2(2, 3, Pose2(2, 0, pi/2), model)); +graph.add(BetweenFactorPose2(3, 4, Pose2(2, 0, pi/2), model)); +graph.add(BetweenFactorPose2(4, 5, Pose2(2, 0, pi/2), model)); + +%% Add pose constraint +graph.add(BetweenFactorPose2(5, 2, Pose2(2, 0, pi/2), model)); + +% print +graph.print(sprintf('\nFactor graph:\n')); + +%% Initialize to noisy points +initialEstimate = Values; +initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 )); +initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2 )); +initialEstimate.insert(3, Pose2(4.1, 0.1, pi/2)); +initialEstimate.insert(4, Pose2(4.0, 2.0, pi )); +initialEstimate.insert(5, Pose2(2.1, 2.1, -pi/2)); +initialEstimate.print(sprintf('\nInitial estimate:\n')); + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimizeSafely(); +result.print(sprintf('\nFinal result:\n')); + +%% Plot Covariance Ellipses +cla; +hold on +plot([result.at(5).x;result.at(2).x],[result.at(5).y;result.at(2).y],'r-'); +marginals = Marginals(graph, result); + +plot2DTrajectory(result, [], marginals); +for i=1:5,marginals.marginalCovariance(i),end +axis equal +axis tight +view(2) diff --git a/examples/matlab/Pose2SLAMExample_advanced.m b/matlab/gtsam_examples/Pose2SLAMExample_advanced.m similarity index 54% rename from examples/matlab/Pose2SLAMExample_advanced.m rename to matlab/gtsam_examples/Pose2SLAMExample_advanced.m index 2199def5b..343dee05b 100644 --- a/examples/matlab/Pose2SLAMExample_advanced.m +++ b/matlab/gtsam_examples/Pose2SLAMExample_advanced.m @@ -14,59 +14,55 @@ % @author Can Erdogan %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +import gtsam.* + %% Assumptions % - All values are axis aligned % - Robot poses are facing along the X axis (horizontal, to the right in images) % - 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; +graph = NonlinearFactorGraph; %% 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 = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +graph.add(PriorFactorPose2(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 = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +odometry = Pose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) +graph.add(BetweenFactorPose2(1, 2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(2, 3, odometry, odometryNoise)); %% Add measurements % general noisemodel for measurements -meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]); +measurementNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); % print 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 = Values; +initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); +initialEstimate.insert(2, Pose2(2.3, 0.1,-0.2)); +initialEstimate.insert(3, Pose2(4.1, 0.1, 0.1)); initialEstimate.print('initial estimate'); %% set up solver, choose ordering and optimize -%params = gtsamNonlinearOptimizationParameters_newDecreaseThresholds(1e-15, 1e-15); -% -%ord = graph.orderingCOLAMD(initialEstimate); -% -%result = pose2SLAMOptimizer(graph,initialEstimate,ord,params); -%result.print('final result'); +params = DoglegParams; +params.setAbsoluteErrorTol(1e-15); +params.setRelativeErrorTol(1e-15); +params.setVerbosity('ERROR'); +params.setVerbosityDL('VERBOSE'); +params.setOrdering(graph.orderingCOLAMD(initialEstimate)); +optimizer = DoglegOptimizer(graph, initialEstimate, params); -% % -% % disp('\\\'); -% % -% % %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd -result = graph.optimize(initialEstimate); +result = optimizer.optimizeSafely(); result.print('final result'); %% Get the corresponding dense matrix @@ -79,4 +75,6 @@ IJS = gfg.sparseJacobian_(); Ab=sparse(IJS(1,:),IJS(2,:),IJS(3,:)); A = Ab(:,1:end-1); b = full(Ab(:,end)); +clf spy(A); +title('Non-zero entries in measurement Jacobian'); diff --git a/matlab/gtsam_examples/Pose2SLAMExample_circle.m b/matlab/gtsam_examples/Pose2SLAMExample_circle.m new file mode 100644 index 000000000..3d2265d76 --- /dev/null +++ b/matlab/gtsam_examples/Pose2SLAMExample_circle.m @@ -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 +% +% @brief Read graph from file and perform GraphSLAM +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Create a hexagon of poses +hexagon = circlePose2(6,1.0); +p0 = hexagon.at(0); +p1 = hexagon.at(1); + +%% create a Pose graph with one equality constraint and one measurement +fg = NonlinearFactorGraph; +fg.add(NonlinearEqualityPose2(0, p0)); +delta = p0.between(p1); +covariance = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]); +fg.add(BetweenFactorPose2(0,1, delta, covariance)); +fg.add(BetweenFactorPose2(1,2, delta, covariance)); +fg.add(BetweenFactorPose2(2,3, delta, covariance)); +fg.add(BetweenFactorPose2(3,4, delta, covariance)); +fg.add(BetweenFactorPose2(4,5, delta, covariance)); +fg.add(BetweenFactorPose2(5,0, delta, covariance)); + +%% Create initial config +initial = Values; +initial.insert(0, p0); +initial.insert(1, hexagon.at(1).retract([-0.1, 0.1,-0.1]')); +initial.insert(2, hexagon.at(2).retract([ 0.1,-0.1, 0.1]')); +initial.insert(3, hexagon.at(3).retract([-0.1, 0.1,-0.1]')); +initial.insert(4, hexagon.at(4).retract([ 0.1,-0.1, 0.1]')); +initial.insert(5, hexagon.at(5).retract([-0.1, 0.1,-0.1]')); + +%% Plot Initial Estimate +cla +plot2DTrajectory(initial, 'g*-'); axis equal + +%% optimize +optimizer = DoglegOptimizer(fg, initial); +result = optimizer.optimizeSafely; + +%% Show Result +hold on; plot2DTrajectory(result, 'b*-'); +view(2); +axis([-1.5 1.5 -1.5 1.5]); +result.print(sprintf('\nFinal result:\n')); diff --git a/matlab/gtsam_examples/Pose2SLAMExample_graph.m b/matlab/gtsam_examples/Pose2SLAMExample_graph.m new file mode 100644 index 000000000..eb1b03950 --- /dev/null +++ b/matlab/gtsam_examples/Pose2SLAMExample_graph.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 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Find data file +datafile = findExampleDataFile('w100-odom.graph'); + +%% Initialize graph, initial estimate, and odometry noise +model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]); +[graph,initial] = load2D(datafile, model); + +%% Add a Gaussian prior on pose x_1 +priorMean = Pose2(0, 0, 0); % prior mean is at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.01; 0.01; 0.01]); +graph.add(PriorFactorPose2(0, priorMean, priorNoise)); % add directly to graph + +%% Plot Initial Estimate +cla +plot2DTrajectory(initial, 'g-*'); axis equal + +%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd +optimizer = LevenbergMarquardtOptimizer(graph, initial); +tic +result = optimizer.optimizeSafely; +toc +hold on; plot2DTrajectory(result, 'b-*'); + +%% Plot Covariance Ellipses +marginals = Marginals(graph, result); +P={}; +for i=1:result.size()-1 + pose_i = result.at(i); + P{i}=marginals.marginalCovariance(i); + plotPose2(pose_i,'b',P{i}) +end +view(2) +axis tight; axis equal; +% fprintf(1,'%.5f %.5f %.5f\n',P{99}) \ No newline at end of file diff --git a/matlab/gtsam_examples/Pose2SLAMwSPCG.m b/matlab/gtsam_examples/Pose2SLAMwSPCG.m new file mode 100644 index 000000000..67f22fe1d --- /dev/null +++ b/matlab/gtsam_examples/Pose2SLAMwSPCG.m @@ -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 +% +% @brief Simple 2D robotics example using the SimpleSPCGSolver +% @author Yong-Dian Jian +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - All values are axis aligned +% - Robot poses are facing along the X axis (horizontal, to the right in images) +% - We have full odometry for measurements +% - The robot is on a grid, moving 2 meters each step + +%% Create graph container and add factors to it +graph = NonlinearFactorGraph; + +%% Add prior +% gaussian for prior +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(1, priorMean, priorNoise)); % add directly to graph + +%% Add odometry +% general noisemodel for odometry +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise)); +graph.add(BetweenFactorPose2(2, 3, Pose2(2.0, 0.0, pi/2), odometryNoise)); +graph.add(BetweenFactorPose2(3, 4, Pose2(2.0, 0.0, pi/2), odometryNoise)); +graph.add(BetweenFactorPose2(4, 5, Pose2(2.0, 0.0, pi/2), odometryNoise)); + +%% Add pose constraint +model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(5, 2, Pose2(2.0, 0.0, pi/2), model)); + +% print +graph.print(sprintf('\nFactor graph:\n')); + +%% Initialize to noisy points +initialEstimate = Values; +initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 )); +initialEstimate.insert(2, Pose2(2.3, 0.1,-0.2 )); +initialEstimate.insert(3, Pose2(4.1, 0.1, pi/2)); +initialEstimate.insert(4, Pose2(4.0, 2.0, pi )); +initialEstimate.insert(5, Pose2(2.1, 2.1,-pi/2)); +initialEstimate.print(sprintf('\nInitial estimate:\n')); + +%% Optimize using Levenberg-Marquardt optimization with SubgraphSolver +params = gtsam.LevenbergMarquardtParams; +subgraphParams = gtsam.SubgraphSolverParameters; +params.setLinearSolverType('CONJUGATE_GRADIENT'); +params.setIterativeParams(subgraphParams); +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimize(); +result.print(sprintf('\nFinal result:\n')); + + + diff --git a/matlab/gtsam_examples/Pose3SLAMExample.m b/matlab/gtsam_examples/Pose3SLAMExample.m new file mode 100644 index 000000000..0d2bd237f --- /dev/null +++ b/matlab/gtsam_examples/Pose3SLAMExample.m @@ -0,0 +1,56 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Create a hexagon of poses +hexagon = circlePose3(6,1.0); +p0 = hexagon.at(0); +p1 = hexagon.at(1); + +%% create a Pose graph with one equality constraint and one measurement +fg = NonlinearFactorGraph; +fg.add(NonlinearEqualityPose3(0, p0)); +delta = p0.between(p1); +covariance = noiseModel.Diagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +fg.add(BetweenFactorPose3(0,1, delta, covariance)); +fg.add(BetweenFactorPose3(1,2, delta, covariance)); +fg.add(BetweenFactorPose3(2,3, delta, covariance)); +fg.add(BetweenFactorPose3(3,4, delta, covariance)); +fg.add(BetweenFactorPose3(4,5, delta, covariance)); +fg.add(BetweenFactorPose3(5,0, delta, covariance)); + +%% Create initial config +initial = Values; +s = 0.10; +initial.insert(0, p0); +initial.insert(1, hexagon.at(1).retract(s*randn(6,1))); +initial.insert(2, hexagon.at(2).retract(s*randn(6,1))); +initial.insert(3, hexagon.at(3).retract(s*randn(6,1))); +initial.insert(4, hexagon.at(4).retract(s*randn(6,1))); +initial.insert(5, hexagon.at(5).retract(s*randn(6,1))); + +%% Plot Initial Estimate +cla +plot3DTrajectory(initial, 'g-*'); + +%% optimize +optimizer = DoglegOptimizer(fg, initial); +result = optimizer.optimizeSafely(); + +%% Show Result +hold on; plot3DTrajectory(result, 'b-*', true, 0.3); +axis([-2 2 -2 2 -1 1]); +axis equal +view(-37,40) +colormap hot +result.print(sprintf('\nFinal result:\n')); diff --git a/matlab/gtsam_examples/Pose3SLAMExample_graph.m b/matlab/gtsam_examples/Pose3SLAMExample_graph.m new file mode 100644 index 000000000..f4eb8dd3a --- /dev/null +++ b/matlab/gtsam_examples/Pose3SLAMExample_graph.m @@ -0,0 +1,41 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Find data file +N = 2500; +% dataset = 'sphere_smallnoise.graph'; +% dataset = 'sphere2500_groundtruth.txt'; +dataset = 'sphere2500.txt'; + +datafile = findExampleDataFile(dataset); + +%% Initialize graph, initial estimate, and odometry noise +model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +[graph,initial]=load3D(datafile,model,true,N); + +%% Plot Initial Estimate +cla +first = initial.at(0); +plot3(first.x(),first.y(),first.z(),'r*'); hold on +plot3DTrajectory(initial,'g-',false); +drawnow; + +%% Read again, now with all constraints, and optimize +graph = load3D(datafile, model, false, N); +graph.add(NonlinearEqualityPose3(0, first)); +optimizer = LevenbergMarquardtOptimizer(graph, initial); +result = optimizer.optimizeSafely(); +plot3DTrajectory(result, 'r-', false); axis equal; + +view(3); axis equal; \ No newline at end of file diff --git a/matlab/gtsam_examples/SBAExample.m b/matlab/gtsam_examples/SBAExample.m new file mode 100644 index 000000000..b0f754044 --- /dev/null +++ b/matlab/gtsam_examples/SBAExample.m @@ -0,0 +1,84 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 An SFM example (adapted from SFMExample.m) optimizing calibration +% @author Yong-Dian Jian +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - Landmarks as 8 vertices of a cube: (10,10,10) (-10,10,10) etc... +% - Cameras are on a circle around the cube, pointing at the world origin +% - Each camera sees all landmarks. +% - Visual measurements as 2D points are given, corrupted by Gaussian noise. + +% Data Options +options.triangle = false; +options.nrCameras = 10; +options.showImages = false; + +%% Generate data +[data,truth] = VisualISAMGenerateData(options); + +measurementNoiseSigma = 1.0; +pointNoiseSigma = 0.1; +cameraNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1 ... + 0.001*ones(1,5)]'; + +%% Create the graph (defined in visualSLAM.h, derived from NonlinearFactorGraph) +graph = NonlinearFactorGraph; + + +%% Add factors for all measurements +measurementNoise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma); +for i=1:length(data.Z) + for k=1:length(data.Z{i}) + j = data.J{i}{k}; + graph.add(GeneralSFMFactorCal3_S2(data.Z{i}{k}, measurementNoise, symbol('c',i), symbol('p',j))); + end +end + +%% Add Gaussian priors for a pose and a landmark to constrain the system +cameraPriorNoise = noiseModel.Diagonal.Sigmas(cameraNoiseSigmas); +firstCamera = SimpleCamera(truth.cameras{1}.pose, truth.K); +graph.add(PriorFactorSimpleCamera(symbol('c',1), firstCamera, cameraPriorNoise)); + +pointPriorNoise = noiseModel.Isotropic.Sigma(3,pointNoiseSigma); +graph.add(PriorFactorPoint3(symbol('p',1), truth.points{1}, pointPriorNoise)); + +%% Print the graph +graph.print(sprintf('\nFactor graph:\n')); + + +%% Initialize cameras and points close to ground truth in this example +initialEstimate = Values; +for i=1:size(truth.cameras,2) + pose_i = truth.cameras{i}.pose.retract(0.1*randn(6,1)); + camera_i = SimpleCamera(pose_i, truth.K); + initialEstimate.insert(symbol('c',i), camera_i); +end +for j=1:size(truth.points,2) + point_j = truth.points{j}.retract(0.1*randn(3,1)); + initialEstimate.insert(symbol('p',j), point_j); +end +initialEstimate.print(sprintf('\nInitial estimate:\n ')); + +%% Fine grain optimization, allowing user to iterate step by step +parameters = LevenbergMarquardtParams; +parameters.setlambdaInitial(1.0); +parameters.setVerbosityLM('trylambda'); + +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, parameters); + +for i=1:5 + optimizer.iterate(); +end + +result = optimizer.values(); +result.print(sprintf('\nFinal result:\n ')); diff --git a/matlab/gtsam_examples/SFMExample.m b/matlab/gtsam_examples/SFMExample.m new file mode 100644 index 000000000..4115fa6e3 --- /dev/null +++ b/matlab/gtsam_examples/SFMExample.m @@ -0,0 +1,89 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 A structure from motion example +% @author Duy-Nguyen Ta +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - Landmarks as 8 vertices of a cube: (10,10,10) (-10,10,10) etc... +% - Cameras are on a circle around the cube, pointing at the world origin +% - Each camera sees all landmarks. +% - Visual measurements as 2D points are given, corrupted by Gaussian noise. + +% Data Options +options.triangle = false; +options.nrCameras = 10; +options.showImages = false; + +%% Generate data +[data,truth] = VisualISAMGenerateData(options); + +measurementNoiseSigma = 1.0; +pointNoiseSigma = 0.1; +poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]'; + +%% Create the graph (defined in visualSLAM.h, derived from NonlinearFactorGraph) +graph = NonlinearFactorGraph; + +%% Add factors for all measurements +measurementNoise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma); +for i=1:length(data.Z) + for k=1:length(data.Z{i}) + j = data.J{i}{k}; + graph.add(GenericProjectionFactorCal3_S2(data.Z{i}{k}, measurementNoise, symbol('x',i), symbol('p',j), data.K)); + end +end + +%% Add Gaussian priors for a pose and a landmark to constrain the system +posePriorNoise = noiseModel.Diagonal.Sigmas(poseNoiseSigmas); +graph.add(PriorFactorPose3(symbol('x',1), truth.cameras{1}.pose, posePriorNoise)); +pointPriorNoise = noiseModel.Isotropic.Sigma(3,pointNoiseSigma); +graph.add(PriorFactorPoint3(symbol('p',1), truth.points{1}, pointPriorNoise)); + +%% Print the graph +graph.print(sprintf('\nFactor graph:\n')); + +%% Initialize cameras and points close to ground truth in this example +initialEstimate = Values; +for i=1:size(truth.cameras,2) + pose_i = truth.cameras{i}.pose.retract(0.1*randn(6,1)); + initialEstimate.insert(symbol('x',i), pose_i); +end +for j=1:size(truth.points,2) + point_j = truth.points{j}.retract(0.1*randn(3,1)); + initialEstimate.insert(symbol('p',j), point_j); +end +initialEstimate.print(sprintf('\nInitial estimate:\n ')); + +%% Fine grain optimization, allowing user to iterate step by step +parameters = LevenbergMarquardtParams; +parameters.setlambdaInitial(1.0); +parameters.setVerbosityLM('trylambda'); + +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, parameters); + +for i=1:5 + optimizer.iterate(); +end +result = optimizer.values(); +result.print(sprintf('\nFinal result:\n ')); + +%% Plot results with covariance ellipses +marginals = Marginals(graph, result); +cla +hold on; + +plot3DPoints(result, [], marginals); +plot3DTrajectory(result, '*', 1, 8, marginals); + +axis([-40 40 -40 40 -10 20]);axis equal +view(3) +colormap('hot') diff --git a/matlab/gtsam_examples/StereoVOExample.m b/matlab/gtsam_examples/StereoVOExample.m new file mode 100644 index 000000000..8dbaa1a76 --- /dev/null +++ b/matlab/gtsam_examples/StereoVOExample.m @@ -0,0 +1,75 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 Basic VO Example with 3 landmarks and two cameras +% @author Chris Beall +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Assumptions +% - For simplicity this example is in the camera's coordinate frame +% - X: right, Y: down, Z: forward +% - Pose x1 is at the origin, Pose 2 is 1 meter forward (along Z-axis) +% - x1 is fixed with a constraint, x2 is initialized with noisy values +% - No noise on measurements + +%% Create keys for variables +x1 = symbol('x',1); x2 = symbol('x',2); +l1 = symbol('l',1); l2 = symbol('l',2); l3 = symbol('l',3); + +%% Create graph container and add factors to it +graph = NonlinearFactorGraph; + +%% add a constraint on the starting pose +first_pose = Pose3(); +graph.add(NonlinearEqualityPose3(x1, first_pose)); + +%% Create realistic calibration and measurement noise model +% format: fx fy skew cx cy baseline +K = Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2); +stereo_model = noiseModel.Diagonal.Sigmas([1.0; 1.0; 1.0]); + +%% Add measurements +% pose 1 +graph.add(GenericStereoFactor3D(StereoPoint2(520, 480, 440), stereo_model, x1, l1, K)); +graph.add(GenericStereoFactor3D(StereoPoint2(120, 80, 440), stereo_model, x1, l2, K)); +graph.add(GenericStereoFactor3D(StereoPoint2(320, 280, 140), stereo_model, x1, l3, K)); + +%pose 2 +graph.add(GenericStereoFactor3D(StereoPoint2(570, 520, 490), stereo_model, x2, l1, K)); +graph.add(GenericStereoFactor3D(StereoPoint2( 70, 20, 490), stereo_model, x2, l2, K)); +graph.add(GenericStereoFactor3D(StereoPoint2(320, 270, 115), stereo_model, x2, l3, K)); + + +%% Create initial estimate for camera poses and landmarks +initialEstimate = Values; +initialEstimate.insert(x1, first_pose); +% noisy estimate for pose 2 +initialEstimate.insert(x2, Pose3(Rot3(), Point3(0.1,-.1,1.1))); +initialEstimate.insert(l1, Point3( 1, 1, 5)); +initialEstimate.insert(l2, Point3(-1, 1, 5)); +initialEstimate.insert(l3, Point3( 0,-.5, 5)); + +%% optimize +fprintf(1,'Optimizing\n'); tic +optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); +result = optimizer.optimizeSafely(); +toc + +%% visualize initial trajectory, final trajectory, and final points +cla; hold on; +axis normal +axis([-1.5 1.5 -2 2 -1 6]); +axis equal +view(-38,12) +camup([0;1;0]); + +plot3DTrajectory(initialEstimate, 'r', 1, 0.3); +plot3DTrajectory(result, 'g', 1, 0.3); +plot3DPoints(result); diff --git a/matlab/gtsam_examples/StereoVOExample_large.m b/matlab/gtsam_examples/StereoVOExample_large.m new file mode 100644 index 000000000..b77733abd --- /dev/null +++ b/matlab/gtsam_examples/StereoVOExample_large.m @@ -0,0 +1,76 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 Stereo Visual Odometry from file and optimize +% @author Chris Beall +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Load calibration +% format: fx fy skew cx cy baseline +calib = dlmread(findExampleDataFile('VO_calibration.txt')); +K = Cal3_S2Stereo(calib(1), calib(2), calib(3), calib(4), calib(5), calib(6)); +stereo_model = noiseModel.Diagonal.Sigmas([1.0; 1.0; 1.0]); + +%% create empty graph and values +graph = NonlinearFactorGraph; +initial = Values; + + +%% load the initial poses from VO +% row format: camera_id 4x4 pose (row, major) +fprintf(1,'Reading data\n'); +cameras = dlmread(findExampleDataFile('VO_camera_poses_large.txt')); +for i=1:size(cameras,1) + pose = Pose3(reshape(cameras(i,2:17),4,4)'); + initial.insert(symbol('x',cameras(i,1)),pose); +end + +%% load stereo measurements and initialize landmarks +% camera_id landmark_id uL uR v X Y Z +measurements = dlmread(findExampleDataFile('VO_stereo_factors_large.txt')); + +fprintf(1,'Creating Graph\n'); tic +for i=1:size(measurements,1) + sf = measurements(i,:); + graph.add(GenericStereoFactor3D(StereoPoint2(sf(3),sf(4),sf(5)), stereo_model, ... + symbol('x', sf(1)), symbol('l', sf(2)), K)); + + if ~initial.exists(symbol('l',sf(2))) + % 3D landmarks are stored in camera coordinates: transform + % to world coordinates using the respective initial pose + pose = initial.at(symbol('x', sf(1))); + world_point = pose.transform_from(Point3(sf(6),sf(7),sf(8))); + initial.insert(symbol('l',sf(2)), world_point); + end +end +toc + +%% add a constraint on the starting pose +key = symbol('x',1); +first_pose = initial.at(key); +graph.add(NonlinearEqualityPose3(key, first_pose)); + +%% optimize +fprintf(1,'Optimizing\n'); tic +optimizer = LevenbergMarquardtOptimizer(graph, initial); +result = optimizer.optimizeSafely(); +toc + +%% visualize initial trajectory, final trajectory, and final points +cla; hold on; + +plot3DTrajectory(initial, 'r', 1, 0.5); +plot3DTrajectory(result, 'g', 1, 0.5); +plot3DPoints(result); + +axis([-5 20 -20 20 0 100]); +axis equal +view(3) +camup([0;1;0]); diff --git a/matlab/gtsam_examples/VisualISAMDemo.m b/matlab/gtsam_examples/VisualISAMDemo.m new file mode 100644 index 000000000..813d6d2e1 --- /dev/null +++ b/matlab/gtsam_examples/VisualISAMDemo.m @@ -0,0 +1,9 @@ +% VisualISAMDemo: runs VisualSLAM iSAM demo in a GUI +% Authors: Duy Nguyen Ta + +% Make sure global variables are visible on command prompt +% so you can examine how they change as you step through +global options truth data noiseModels isam result frame_i + +% Start GUI +VisualISAM_gui \ No newline at end of file diff --git a/matlab/gtsam_examples/VisualISAMExample.m b/matlab/gtsam_examples/VisualISAMExample.m new file mode 100644 index 000000000..751373b69 --- /dev/null +++ b/matlab/gtsam_examples/VisualISAMExample.m @@ -0,0 +1,50 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 A simple visual SLAM example for structure from motion +% @author Duy-Nguyen Ta +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +% Data Options +options.triangle = false; +options.nrCameras = 20; +options.showImages = false; + +% iSAM Options +options.hardConstraint = false; +options.pointPriors = false; +options.batchInitialization = true; +options.reorderInterval = 10; +options.alwaysRelinearize = false; + +% Display Options +options.saveDotFile = false; +options.printStats = false; +options.drawInterval = 5; +options.cameraInterval = 1; +options.drawTruePoses = false; +options.saveFigures = false; +options.saveDotFiles = false; + +%% Generate data +[data,truth] = VisualISAMGenerateData(options); + +%% Initialize iSAM with the first pose and points +[noiseModels,isam,result,nextPose] = VisualISAMInitialize(data,truth,options); +cla; +VisualISAMPlot(truth, data, isam, result, options) + +%% Main loop for iSAM: stepping through all poses +for frame_i=3:options.nrCameras + [isam,result,nextPose] = VisualISAMStep(data,noiseModels,isam,result,truth,nextPose); + if mod(frame_i,options.drawInterval)==0 + VisualISAMPlot(truth, data, isam, result, options) + end +end diff --git a/matlab/gtsam_examples/VisualISAM_gui.fig b/matlab/gtsam_examples/VisualISAM_gui.fig new file mode 100644 index 000000000..d4d65f565 Binary files /dev/null and b/matlab/gtsam_examples/VisualISAM_gui.fig differ diff --git a/matlab/gtsam_examples/VisualISAM_gui.m b/matlab/gtsam_examples/VisualISAM_gui.m new file mode 100644 index 000000000..4ccde5e53 --- /dev/null +++ b/matlab/gtsam_examples/VisualISAM_gui.m @@ -0,0 +1,268 @@ +function varargout = VisualISAM_gui(varargin) +% VisualISAM_gui: runs VisualSLAM iSAM demo in GUI +% Interface is defined by VisualISAM_gui.fig +% You can run this file directly, but won't have access to globals +% By running ViusalISAMDemo, you see all variables in command prompt +% Authors: Duy Nguyen Ta + +% Last Modified by GUIDE v2.5 13-Jun-2012 23:15:43 + +% Begin initialization code - DO NOT EDIT +gui_Singleton = 1; +gui_State = struct('gui_Name', mfilename, ... + 'gui_Singleton', gui_Singleton, ... + 'gui_OpeningFcn', @VisualISAM_gui_OpeningFcn, ... + 'gui_OutputFcn', @VisualISAM_gui_OutputFcn, ... + 'gui_LayoutFcn', [] , ... + 'gui_Callback', []); +if nargin && ischar(varargin{1}) + gui_State.gui_Callback = str2func(varargin{1}); +end + +if nargout + [varargout{1:nargout}] = gui_mainfcn(gui_State, varargin{:}); +else + gui_mainfcn(gui_State, varargin{:}); +end +% End initialization code - DO NOT EDIT + + +% --- Executes just before VisualISAM_gui is made visible. +function VisualISAM_gui_OpeningFcn(hObject, ~, handles, varargin) +% This function has no output args, see OutputFcn. +% varargin command line arguments to VisualISAM_gui (see VARARGIN) + +% Choose default command line output for VisualISAM_gui +handles.output = hObject; + +% Update handles structure +guidata(hObject, handles); + +% --- Outputs from this function are returned to the command line. +function varargout = VisualISAM_gui_OutputFcn(hObject, ~, handles) +% varargout cell array for returning output args (see VARARGOUT); +% Get default command line output from handles structure +varargout{1} = handles.output; + + +%---------------------------------------------------------- +% Convenient functions +%---------------------------------------------------------- +function showFramei(hObject, handles) +global frame_i +set(handles.frameStatus, 'String', sprintf('Frame: %d',frame_i)); +drawnow +guidata(hObject, handles); + +function showWaiting(handles, status) +set(handles.waitingStatus,'String', status); +drawnow +guidata(handles.waitingStatus, handles); + +function triangle = chooseDataset(handles) +str = cellstr(get(handles.dataset,'String')); +sel = get(handles.dataset,'Value'); +switch str{sel} + case 'triangle' + triangle = true; + case 'cube' + triangle = false; +end + +function initOptions(handles) + +global options + +% Data options +options.triangle = chooseDataset(handles); +options.nrCameras = str2num(get(handles.numCamEdit,'String')); +options.showImages = get(handles.showImagesCB,'Value'); + +% iSAM Options +options.hardConstraint = get(handles.hardConstraintCB,'Value'); +options.pointPriors = get(handles.pointPriorsCB,'Value'); +options.batchInitialization = get(handles.batchInitCB,'Value'); +%options.reorderInterval = str2num(get(handles.reorderIntervalEdit,'String')); +options.alwaysRelinearize = get(handles.alwaysRelinearizeCB,'Value'); + +% Display Options +options.saveDotFile = get(handles.saveGraphCB,'Value'); +options.printStats = get(handles.printStatsCB,'Value'); +options.drawInterval = str2num(get(handles.drawInterval,'String')); +options.cameraInterval = str2num(get(handles.cameraIntervalEdit,'String')); +options.drawTruePoses = get(handles.drawTruePosesCB,'Value'); +options.saveFigures = get(handles.saveFiguresCB,'Value'); +options.saveDotFiles = get(handles.saveGraphsCB,'Value'); + +%---------------------------------------------------------- +% Callback functions for GUI elements +%---------------------------------------------------------- + +% --- Executes during object creation, after setting all properties. +function dataset_CreateFcn(hObject, ~, handles) +% handles empty - handles not created until after all CreateFcns called +% Hint: popupmenu controls usually have a white background on Windows. +% See ISPC and COMPUTER. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + +% --- Executes on selection change in dataset. +function dataset_Callback(hObject, ~, handles) +% Hints: contents = cellstr(get(hObject,'String')) returns dataset contents as cell array +% contents{get(hObject,'Value')} returns selected item from dataset + + +% --- Executes during object creation, after setting all properties. +function numCamEdit_CreateFcn(hObject, ~, handles) +% Hint: edit controls usually have a white background on Windows. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + +function numCamEdit_Callback(hObject, ~, handles) +% Hints: get(hObject,'String') returns contents of numCamEdit as text +% str2double(get(hObject,'String')) returns contents of numCamEdit as a double + + +% --- Executes on button press in showImagesCB. +function showImagesCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of showImagesCB + + +% --- Executes on button press in hardConstraintCB. +function hardConstraintCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of hardConstraintCB + + +% --- Executes on button press in pointPriorsCB. +function pointPriorsCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of pointPriorsCB + + +% --- Executes during object creation, after setting all properties. +function batchInitCB_CreateFcn(hObject, eventdata, handles) +set(hObject,'Value',1); + +% --- Executes on button press in batchInitCB. +function batchInitCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of batchInitCB + + +% --- Executes on button press in alwaysRelinearizeCB. +function alwaysRelinearizeCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of alwaysRelinearizeCB + + +% --- Executes during object creation, after setting all properties. +function reorderIntervalText_CreateFcn(hObject, ~, handles) +% Hint: edit controls usually have a white background on Windows. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + + +% --- Executes during object creation, after setting all properties. +function reorderIntervalEdit_CreateFcn(hObject, ~, handles) +% Hint: edit controls usually have a white background on Windows. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + + +% --- Executes during object creation, after setting all properties. +function drawInterval_CreateFcn(hObject, ~, handles) +% Hint: edit controls usually have a white background on Windows. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + + +function drawInterval_Callback(hObject, ~, handles) +% Hints: get(hObject,'String') returns contents of drawInterval as text +% str2double(get(hObject,'String')) returns contents of drawInterval as a double + + +function cameraIntervalEdit_Callback(hObject, ~, handles) +% Hints: get(hObject,'String') returns contents of cameraIntervalEdit as text +% str2double(get(hObject,'String')) returns contents of cameraIntervalEdit as a double + + +% --- Executes during object creation, after setting all properties. +function cameraIntervalEdit_CreateFcn(hObject, ~, handles) +% Hint: edit controls usually have a white background on Windows. +% See ISPC and COMPUTER. +if ispc && isequal(get(hObject,'BackgroundColor'), get(0,'defaultUicontrolBackgroundColor')) + set(hObject,'BackgroundColor','white'); +end + + +% --- Executes on button press in saveGraphCB. +function saveGraphCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of saveGraphCB + + +% --- Executes on button press in printStatsCB. +function printStatsCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of printStatsCB + + +% --- Executes on button press in drawTruePosesCB. +function drawTruePosesCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of drawTruePosesCB + + +% --- Executes on button press in saveFiguresCB. +function saveFiguresCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of saveFiguresCB + + +% --- Executes on button press in saveGraphsCB. +function saveGraphsCB_Callback(hObject, ~, handles) +% Hint: get(hObject,'Value') returns toggle state of saveGraphsCB + +% --- Executes on button press in intializeButton. +function intializeButton_Callback(hObject, ~, handles) + +global frame_i truth data noiseModels isam result nextPoseIndex options + +% initialize global options +initOptions(handles) + +% Generate Data +[data,truth] = gtsam.VisualISAMGenerateData(options); + +% Initialize and plot +[noiseModels,isam,result,nextPoseIndex] = gtsam.VisualISAMInitialize(data,truth,options); +cla +gtsam.VisualISAMPlot(truth, data, isam, result, options) +frame_i = 2; +showFramei(hObject, handles) + + +% --- Executes on button press in runButton. +function runButton_Callback(hObject, ~, handles) +global frame_i truth data noiseModels isam result nextPoseIndex options +while (frame_i +#include namespace simulated2D { diff --git a/gtsam/slam/simulated2D.h b/tests/simulated2D.h similarity index 81% rename from gtsam/slam/simulated2D.h rename to tests/simulated2D.h index ca9c0cf15..c5a62bba9 100644 --- a/gtsam/slam/simulated2D.h +++ b/tests/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); } }; @@ -123,6 +117,7 @@ namespace simulated2D { class GenericPrior: public NoiseModelFactor1 { public: typedef NoiseModelFactor1 Base; ///< base class + typedef GenericPrior This; typedef boost::shared_ptr > shared_ptr; typedef VALUE Pose; ///< shortcut to Pose type @@ -138,11 +133,17 @@ namespace simulated2D { return (prior(x, H) - measured_).vector(); } + virtual ~GenericPrior() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + private: /// Default constructor - GenericPrior() { - } + GenericPrior() { } /// Serialization function friend class boost::serialization::access; @@ -160,14 +161,15 @@ namespace simulated2D { class GenericOdometry: public NoiseModelFactor2 { public: typedef NoiseModelFactor2 Base; ///< base class + typedef GenericOdometry This; typedef boost::shared_ptr > shared_ptr; typedef VALUE Pose; ///< shortcut to Pose type 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 @@ -177,11 +179,17 @@ namespace simulated2D { return (odo(x1, x2, H1, H2) - measured_).vector(); } + virtual ~GenericOdometry() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + private: /// Default constructor - GenericOdometry() { - } + GenericOdometry() { } /// Serialization function friend class boost::serialization::access; @@ -199,6 +207,7 @@ namespace simulated2D { class GenericMeasurement: public NoiseModelFactor2 { public: typedef NoiseModelFactor2 Base; ///< base class + typedef GenericMeasurement This; typedef boost::shared_ptr > shared_ptr; typedef POSE Pose; ///< shortcut to Pose type typedef LANDMARK Landmark; ///< shortcut to Landmark type @@ -206,8 +215,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 @@ -217,11 +226,17 @@ namespace simulated2D { return (mea(x1, x2, H1, H2) - measured_).vector(); } + virtual ~GenericMeasurement() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + private: /// Default constructor - GenericMeasurement() { - } + GenericMeasurement() { } /// Serialization function friend class boost::serialization::access; diff --git a/gtsam/slam/simulated2DConstraints.h b/tests/simulated2DConstraints.h similarity index 83% rename from gtsam/slam/simulated2DConstraints.h rename to tests/simulated2DConstraints.h index b44062933..b9f2edcb5 100644 --- a/gtsam/slam/simulated2DConstraints.h +++ b/tests/simulated2DConstraints.h @@ -24,7 +24,7 @@ #include #include #include -#include +#include // \namespace @@ -53,11 +53,17 @@ namespace simulated2D { template struct ScalarCoordConstraint1: public BoundingConstraint1 { typedef BoundingConstraint1 Base; ///< Base class convenience typedef + typedef ScalarCoordConstraint1 This; ///< This class convenience typedef typedef boost::shared_ptr > shared_ptr; ///< boost::shared_ptr convenience typedef typedef VALUE Point; ///< Constrained variable type virtual ~ScalarCoordConstraint1() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** * Constructor for constraint * @param key is the label for the constrained variable @@ -66,8 +72,8 @@ namespace simulated2D { * @param mu is the penalty function gain */ ScalarCoordConstraint1(Key key, double c, - bool isGreaterThan, double mu = 1000.0) : - Base(key, c, isGreaterThan, mu) { + bool isGreaterThan, double mu = 1000.0) : + Base(key, c, isGreaterThan, mu) { } /** @@ -116,10 +122,16 @@ namespace simulated2D { template struct MaxDistanceConstraint : public BoundingConstraint2 { typedef BoundingConstraint2 Base; ///< Base class for factor + typedef MaxDistanceConstraint This; ///< This class for factor typedef VALUE Point; ///< Type of variable constrained virtual ~MaxDistanceConstraint() {} + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + /** * Primary constructor for factor * @param key1 is the first variable key @@ -157,15 +169,21 @@ namespace simulated2D { */ template struct MinDistanceConstraint : public BoundingConstraint2 { - typedef BoundingConstraint2 Base; ///< Base class for factor - typedef POSE Pose; ///< Type of pose variable constrained - typedef POINT Point; ///< Type of point variable constrained + typedef BoundingConstraint2 Base; ///< Base class for factor + typedef MinDistanceConstraint This; ///< This class for factor + typedef POSE Pose; ///< Type of pose variable constrained + typedef POINT Point; ///< Type of point variable constrained - virtual ~MinDistanceConstraint() {} + virtual ~MinDistanceConstraint() {} - /** - * Primary constructor for factor - * @param key1 is the first variable key + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + + /** + * Primary constructor for factor + * @param key1 is the first variable key * @param key2 is the second variable key * @param range_bound is the minimum range allowed between the variables * @param mu is the gain for the penalty function diff --git a/gtsam/slam/simulated2DOriented.cpp b/tests/simulated2DOriented.cpp similarity index 96% rename from gtsam/slam/simulated2DOriented.cpp rename to tests/simulated2DOriented.cpp index 947aaddc5..c7d1d8469 100644 --- a/gtsam/slam/simulated2DOriented.cpp +++ b/tests/simulated2DOriented.cpp @@ -15,7 +15,7 @@ * @author Frank Dellaert */ -#include +#include namespace simulated2DOriented { diff --git a/gtsam/slam/simulated2DOriented.h b/tests/simulated2DOriented.h similarity index 80% rename from gtsam/slam/simulated2DOriented.h rename to tests/simulated2DOriented.h index 242aab94b..ef8378fc5 100644 --- a/gtsam/slam/simulated2DOriented.h +++ b/tests/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 @@ -102,6 +99,8 @@ namespace simulated2DOriented { struct GenericOdometry: public NoiseModelFactor2 { Pose2 measured_; ///< Between measurement for odometry factor + typedef GenericOdometry This; + /** * Creates an odometry factor between two poses */ @@ -110,6 +109,8 @@ namespace simulated2DOriented { NoiseModelFactor2(model, i1, i2), measured_(measured) { } + virtual ~GenericOdometry() {} + /// Evaluate error and optionally derivative Vector evaluateError(const VALUE& x1, const VALUE& x2, boost::optional H1 = boost::none, @@ -117,6 +118,11 @@ namespace simulated2DOriented { return measured_.localCoordinates(odo(x1, x2, H1, H2)); } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + }; typedef GenericOdometry Odometry; diff --git a/gtsam_unstable/slam/simulated3D.cpp b/tests/simulated3D.cpp similarity index 95% rename from gtsam_unstable/slam/simulated3D.cpp rename to tests/simulated3D.cpp index 933d1f194..980b6cabd 100644 --- a/gtsam_unstable/slam/simulated3D.cpp +++ b/tests/simulated3D.cpp @@ -15,7 +15,7 @@ * @author Alex Cunningham **/ -#include +#include namespace gtsam { diff --git a/gtsam_unstable/slam/simulated3D.h b/tests/simulated3D.h similarity index 89% rename from gtsam_unstable/slam/simulated3D.h rename to tests/simulated3D.h index 7b4dfce37..ef79991b8 100644 --- a/gtsam_unstable/slam/simulated3D.h +++ b/tests/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/slam/smallExample.cpp b/tests/smallExample.cpp similarity index 81% rename from gtsam/slam/smallExample.cpp rename to tests/smallExample.cpp index 170f3ef03..71c8269e9 100644 --- a/gtsam/slam/smallExample.cpp +++ b/tests/smallExample.cpp @@ -17,27 +17,27 @@ * @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; + using namespace gtsam::noiseModel; typedef boost::shared_ptr shared; @@ -49,8 +49,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 +61,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 +90,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 +108,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,41 +122,41 @@ 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; } /* ************************************************************************* */ - FactorGraph createGaussianFactorGraph(const Ordering& ordering) { + GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { // Create empty graph - GaussianFactorGraph fg; + GaussianFactorGraph fg; 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.push_back(boost::make_shared(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.push_back(boost::make_shared(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.push_back(boost::make_shared(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.push_back(boost::make_shared(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2)); - return *fg.dynamicCastFactors >(); + return fg; } /* ************************************************************************* */ @@ -221,7 +222,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; } @@ -239,23 +240,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); @@ -272,7 +273,7 @@ namespace example { } /* ************************************************************************* */ - FactorGraph createSimpleConstraintGraph() { + GaussianFactorGraph createSimpleConstraintGraph() { // create unary factor // prior on _x_, mean = [1,-1], sigma=0.1 Matrix Ax = eye(2); @@ -292,7 +293,7 @@ namespace example { constraintModel)); // construct the graph - FactorGraph fg; + GaussianFactorGraph fg; fg.push_back(f1); fg.push_back(f2); @@ -309,7 +310,7 @@ namespace example { } /* ************************************************************************* */ - FactorGraph createSingleConstraintGraph() { + GaussianFactorGraph createSingleConstraintGraph() { // create unary factor // prior on _x_, mean = [1,-1], sigma=0.1 Matrix Ax = eye(2); @@ -334,7 +335,7 @@ namespace example { constraintModel)); // construct the graph - FactorGraph fg; + GaussianFactorGraph fg; fg.push_back(f1); fg.push_back(f2); @@ -350,7 +351,7 @@ namespace example { } /* ************************************************************************* */ - FactorGraph createMultiConstraintGraph() { + GaussianFactorGraph createMultiConstraintGraph() { // unary factor 1 Matrix A = eye(2); Vector b = Vector_(2, -2.0, 2.0); @@ -395,7 +396,7 @@ namespace example { constraintModel)); // construct the graph - FactorGraph fg; + GaussianFactorGraph fg; fg.push_back(lf1); fg.push_back(lc1); fg.push_back(lc2); @@ -416,24 +417,24 @@ namespace example { /* ************************************************************************* */ // Create key for simulated planar graph Symbol key(int x, int y) { - return PoseKey(1000*x+y); + return X(1000*x+y); } /* ************************************************************************* */ - boost::tuple, Ordering, VectorValues> planarGraph(size_t N) { + boost::tuple planarGraph(size_t N) { // create empty graph NonlinearFactorGraph nlfg; // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal - shared constraint(new simulated2D::Prior(Point2(1.0, 1.0), sharedSigma(2,1e-3), key(1,1))); + shared constraint(new simulated2D::Prior(Point2(1.0, 1.0), Isotropic::Sigma(2,1e-3), key(1,1))); nlfg.push_back(constraint); // Create horizontal constraints, 1...N*(N-1) Point2 z1(1.0, 0.0); // move right for (size_t x = 1; x < N; x++) for (size_t y = 1; y <= N; y++) { - shared f(new simulated2D::Odometry(z1, sharedSigma(2,0.01), key(x, y), key(x + 1, y))); + shared f(new simulated2D::Odometry(z1, Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); nlfg.push_back(f); } @@ -441,7 +442,7 @@ namespace example { Point2 z2(0.0, 1.0); // move up for (size_t x = 1; x <= N; x++) for (size_t y = 1; y < N; y++) { - shared f(new simulated2D::Odometry(z2, sharedSigma(2,0.01), key(x, y), key(x, y + 1))); + shared f(new simulated2D::Odometry(z2, Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); nlfg.push_back(f); } @@ -457,7 +458,8 @@ namespace example { xtrue[ordering[key(x, y)]] = Point2(x,y).vector(); // linearize around zero - return boost::make_tuple(*nlfg.linearize(zeros, ordering), ordering, xtrue); + boost::shared_ptr gfg = nlfg.linearize(zeros, ordering); + return boost::make_tuple(*gfg, xtrue); } /* ************************************************************************* */ @@ -470,9 +472,9 @@ namespace example { } /* ************************************************************************* */ - pair, FactorGraph > splitOffPlanarTree(size_t N, - const FactorGraph& original) { - FactorGraph T, C; + pair splitOffPlanarTree(size_t N, + const GaussianFactorGraph& original) { + GaussianFactorGraph T, C; // Add the x11 constraint to the tree T.push_back(original[0]); diff --git a/gtsam/slam/smallExample.h b/tests/smallExample.h similarity index 87% rename from gtsam/slam/smallExample.h rename to tests/smallExample.h index 96dcbaf09..f87847f24 100644 --- a/gtsam/slam/smallExample.h +++ b/tests/smallExample.h @@ -21,9 +21,9 @@ #pragma once -#include +#include #include -#include +#include namespace gtsam { namespace example { @@ -65,7 +65,7 @@ namespace gtsam { * create a linear factor graph * The non-linear graph above evaluated at NoisyValues */ - FactorGraph createGaussianFactorGraph(const Ordering& ordering); + GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering); /** * create small Chordal Bayes Net x <- y @@ -99,21 +99,21 @@ namespace gtsam { * Creates a simple constrained graph with one linear factor and * one binary equality constraint that sets x = y */ - FactorGraph createSimpleConstraintGraph(); + GaussianFactorGraph createSimpleConstraintGraph(); VectorValues createSimpleConstraintValues(); /** * Creates a simple constrained graph with one linear factor and * one binary constraint. */ - FactorGraph createSingleConstraintGraph(); + GaussianFactorGraph createSingleConstraintGraph(); VectorValues createSingleConstraintValues(); /** * Creates a constrained graph with a linear factor and two * binary constraints that share a node */ - FactorGraph createMultiConstraintGraph(); + GaussianFactorGraph createMultiConstraintGraph(); VectorValues createMultiConstraintValues(); /* ******************************************************* */ @@ -129,7 +129,7 @@ namespace gtsam { * -x11-x21-x31 * with x11 clamped at (1,1), and others related by 2D odometry. */ - boost::tuple, Ordering, VectorValues> planarGraph(size_t N); + boost::tuple planarGraph(size_t N); /* * Create canonical ordering for planar graph that also works for tree @@ -146,8 +146,8 @@ namespace gtsam { * | * -x11-x21-x31 */ - std::pair, FactorGraph > splitOffPlanarTree( - size_t N, const FactorGraph& original); + std::pair splitOffPlanarTree( + size_t N, const GaussianFactorGraph& original); } // example } // gtsam diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index e1b685fc8..128251a23 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -15,12 +15,13 @@ * @author Alex Cunningham */ -#include - -#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)); +gtsam::Key key = 1; double mu = 10.0; // greater than iq2D::PoseXInequality constraint1(key, 1.0, true, mu); @@ -168,23 +169,22 @@ TEST( testBoundingConstraint, unary_simple_optimization2) { Point2 start_pt(2.0, 3.0); NonlinearFactorGraph graph; - Symbol x1('x',1); - graph.add(iq2D::PoseXInequality(x1, 1.0, false)); - graph.add(iq2D::PoseYInequality(x1, 2.0, false)); - graph.add(simulated2D::Prior(start_pt, soft_model2, x1)); + graph.add(iq2D::PoseXInequality(key, 1.0, false)); + graph.add(iq2D::PoseYInequality(key, 2.0, false)); + graph.add(simulated2D::Prior(start_pt, soft_model2, key)); Values initValues; - initValues.insert(x1, start_pt); + initValues.insert(key, start_pt); Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize(); Values expected; - expected.insert(x1, goal_pt); + expected.insert(key, goal_pt); CHECK(assert_equal(expected, actual, tol)); } /* ************************************************************************* */ TEST( testBoundingConstraint, MaxDistance_basics) { - Symbol key1('x',1), key2('x',2); + gtsam::Key key1 = 1, key2 = 2; Point2 pt1, pt2(1.0, 0.0), pt3(2.0, 0.0), pt4(3.0, 0.0); iq2D::PoseMaxDistConstraint rangeBound(key1, key2, 2.0, mu); EXPECT_DOUBLES_EQUAL(2.0, rangeBound.threshold(), tol); diff --git a/tests/testDoglegOptimizer.cpp b/tests/testDoglegOptimizer.cpp index b16ac0cdc..6b03b572b 100644 --- a/tests/testDoglegOptimizer.cpp +++ b/tests/testDoglegOptimizer.cpp @@ -15,15 +15,16 @@ * @author Richard Roberts */ -#include -#include -#include +#include +#include +#include #include #include #include -#include -#include -#include +#include +#include + +#include #include #include // for 'list_of()' @@ -31,7 +32,10 @@ using namespace std; using namespace gtsam; -using boost::shared_ptr; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; /* ************************************************************************* */ double computeError(const GaussianBayesNet& gbn, const LieVector& values) { @@ -92,7 +96,7 @@ TEST(DoglegOptimizer, ComputeSteepestDescentPoint) { gradientValues.vector() = gradient; // Compute the gradient using dense matrices - Matrix augmentedHessian = GaussianFactorGraph(gbn).denseHessian(); + Matrix augmentedHessian = GaussianFactorGraph(gbn).augmentedHessian(); LONGS_EQUAL(11, augmentedHessian.cols()); VectorValues denseMatrixGradient = *allocateVectorValues(gbn); denseMatrixGradient.vector() = -augmentedHessian.col(10).segment(0,10); @@ -196,7 +200,7 @@ TEST(DoglegOptimizer, BT_BN_equivalency) { GaussianFactorGraph expected(gbn); GaussianFactorGraph actual(bt); - EXPECT(assert_equal(expected.denseJacobian(), actual.denseJacobian())); + EXPECT(assert_equal(expected.augmentedHessian(), actual.augmentedHessian())); } /* ************************************************************************* */ @@ -272,7 +276,7 @@ TEST(DoglegOptimizer, ComputeSteepestDescentPointBT) { gradientValues.vector() = gradient; // Compute the gradient using dense matrices - Matrix augmentedHessian = GaussianFactorGraph(bt).denseHessian(); + Matrix augmentedHessian = GaussianFactorGraph(bt).augmentedHessian(); LONGS_EQUAL(11, augmentedHessian.cols()); VectorValues denseMatrixGradient = *allocateVectorValues(bt); denseMatrixGradient.vector() = -augmentedHessian.col(10).segment(0,10); @@ -381,17 +385,17 @@ TEST(DoglegOptimizer, ComputeDoglegPoint) { /* ************************************************************************* */ TEST(DoglegOptimizer, Iterate) { // really non-linear factor graph - shared_ptr fg(new example::Graph( + boost::shared_ptr fg(new example::Graph( example::createReallyNonlinearFactorGraph())); // 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 - shared_ptr ord(new Ordering()); - ord->push_back(simulated2D::PoseKey(1)); + boost::shared_ptr ord(new Ordering()); + 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 d9e5643a4..c19bcd4c9 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 ) { @@ -409,11 +414,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/testGaussianBayesNet.cpp b/tests/testGaussianBayesNet.cpp index 8444dacc3..60af529ec 100644 --- a/tests/testGaussianBayesNet.cpp +++ b/tests/testGaussianBayesNet.cpp @@ -29,7 +29,7 @@ using namespace boost::assign; #include #include #include -#include +#include using namespace std; using namespace gtsam; diff --git a/tests/testGaussianFactor.cpp b/tests/testGaussianFactor.cpp index 2cfb7a076..f5419b7ff 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,28 +31,25 @@ #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), + sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1), sigma_02 = noiseModel::Isotropic::Sigma(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); // FIXME: throws exception /* ************************************************************************* */ TEST( GaussianFactor, linearFactor ) { + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); Ordering ordering; ordering += kx1,kx2,kl1; Matrix I = eye(2); @@ -53,48 +57,23 @@ 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); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph - JacobianFactor::shared_ptr lf = fg[1]; + JacobianFactor::shared_ptr lf = + boost::dynamic_pointer_cast(fg[1]); // check if the two factors are the same EXPECT(assert_equal(expected,*lf)); } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, keys ) -//{ -// // get the factor kf2 from the small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// GaussianFactor::shared_ptr lf = fg[1]; -// list expected; -// expected.push_back(kx1); -// expected.push_back(kx2); -// EXPECT(lf->keys() == expected); -//} - -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, dimensions ) -//{ -// // get the factor kf2 from the small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// // Check a single factor -// Dimensions expected; -// insert(expected)(kx1, 2)(kx2, 2); -// Dimensions actual = fg[1]->dimensions(); -// EXPECT(expected==actual); -//} - /* ************************************************************************* */ TEST( GaussianFactor, getDim ) { + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); // 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 @@ -105,74 +84,19 @@ TEST( GaussianFactor, getDim ) EXPECT_LONGS_EQUAL(expected, actual); } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, combine ) -//{ -// // create a small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// // get two factors from it and insert the factors into a vector -// vector lfg; -// lfg.push_back(fg[4 - 1]); -// lfg.push_back(fg[2 - 1]); -// -// // combine in a factor -// GaussianFactor combined(lfg); -// -// // sigmas -// double sigma2 = 0.1; -// double sigma4 = 0.2; -// Vector sigmas = Vector_(4, sigma4, sigma4, sigma2, sigma2); -// -// // the expected combined linear factor -// Matrix Ax2 = Matrix_(4, 2, // x2 -// -5., 0., -// +0., -5., -// 10., 0., -// +0., 10.); -// -// Matrix Al1 = Matrix_(4, 2, // l1 -// 5., 0., -// 0., 5., -// 0., 0., -// 0., 0.); -// -// Matrix Ax1 = Matrix_(4, 2, // x1 -// 0.00, 0., // f4 -// 0.00, 0., // f4 -// -10., 0., // f2 -// 0.00, -10. // f2 -// ); -// -// // the RHS -// Vector b2(4); -// b2(0) = -1.0; -// b2(1) = 1.5; -// b2(2) = 2.0; -// b2(3) = -1.0; -// -// // use general constructor for making arbitrary factors -// vector > meas; -// meas.push_back(make_pair(kx2, Ax2)); -// meas.push_back(make_pair(kl1, Al1)); -// meas.push_back(make_pair(kx1, Ax1)); -// GaussianFactor expected(meas, b2, noiseModel::Diagonal::Sigmas(ones(4))); -// EXPECT(assert_equal(expected,combined)); -//} - /* ************************************************************************* */ TEST( GaussianFactor, error ) { + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); // 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 @@ -180,53 +104,13 @@ TEST( GaussianFactor, error ) DOUBLES_EQUAL( 1.0, actual, 0.00000001 ); } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, eliminate ) -//{ -// // create a small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// // get two factors from it and insert the factors into a vector -// vector lfg; -// lfg.push_back(fg[4 - 1]); -// lfg.push_back(fg[2 - 1]); -// -// // combine in a factor -// GaussianFactor combined(lfg); -// -// // eliminate the combined factor -// GaussianConditional::shared_ptr actualCG; -// GaussianFactor::shared_ptr actualLF; -// boost::tie(actualCG,actualLF) = combined.eliminate(kx2); -// -// // create expected Conditional Gaussian -// Matrix I = eye(2)*sqrt(125.0); -// Matrix R11 = I, S12 = -0.2*I, S13 = -0.8*I; -// Vector d = I*Vector_(2,0.2,-0.14); -// -// // Check the conditional Gaussian -// GaussianConditional -// expectedCG(kx2, d, R11, kl1, S12, kx1, S13, repeat(2, 1.0)); -// -// // the expected linear factor -// I = eye(2)/0.2236; -// Matrix Bl1 = I, Bx1 = -I; -// Vector b1 = I*Vector_(2,0.0,0.2); -// -// GaussianFactor expectedLF(kl1, Bl1, kx1, Bx1, b1, repeat(2,1.0)); -// -// // check if the result matches -// EXPECT(assert_equal(expectedCG,*actualCG,1e-3)); -// EXPECT(assert_equal(expectedLF,*actualLF,1e-3)); -//} - /* ************************************************************************* */ TEST( GaussianFactor, matrix ) { + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); // create a small linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - FactorGraph fg = createGaussianFactorGraph(ordering); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph //GaussianFactor::shared_ptr lf = fg[1]; // NOTE: using the older version @@ -263,7 +147,7 @@ TEST( GaussianFactor, matrix ) EQUALITY(b_act2,b2); // Ensure that whitening is consistent - shared_ptr model = lf->get_model(); + boost::shared_ptr model = lf->get_model(); model->WhitenSystem(A_act2, b_act2); EQUALITY(A_act1, A_act2); EQUALITY(b_act1, b_act2); @@ -272,9 +156,10 @@ TEST( GaussianFactor, matrix ) /* ************************************************************************* */ TEST( GaussianFactor, matrix_aug ) { + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); // create a small linear factor graph Ordering ordering; ordering += kx1,kx2,kl1; - FactorGraph fg = createGaussianFactorGraph(ordering); + GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering); // get the factor kf2 from the factor graph //GaussianFactor::shared_ptr lf = fg[1]; @@ -307,7 +192,7 @@ TEST( GaussianFactor, matrix_aug ) EQUALITY(Ab_act2,Ab2); // Ensure that whitening is consistent - shared_ptr model = lf->get_model(); + boost::shared_ptr model = lf->get_model(); model->WhitenInPlace(Ab_act1); EQUALITY(Ab_act1, Ab_act2); } @@ -320,72 +205,13 @@ void print(const list& i) { cout << endl; } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, sparse ) -//{ -// // create a small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// // get the factor kf2 from the factor graph -// GaussianFactor::shared_ptr lf = fg[1]; -// -// // render with a given ordering -// Ordering ord; -// ord += kx1,kx2; -// -// list i,j; -// list s; -// boost::tie(i,j,s) = lf->sparse(fg.columnIndices(ord)); -// -// list i1,j1; -// i1 += 1,2,1,2; -// j1 += 1,2,3,4; -// -// list s1; -// s1 += -10,-10,10,10; -// -// EXPECT(i==i1); -// EXPECT(j==j1); -// EXPECT(s==s1); -//} - -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactor, sparse2 ) -//{ -// // create a small linear factor graph -// Ordering ordering; ordering += kx1,kx2,kl1; -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// // get the factor kf2 from the factor graph -// GaussianFactor::shared_ptr lf = fg[1]; -// -// // render with a given ordering -// Ordering ord; -// ord += kx2,kl1,kx1; -// -// list i,j; -// list s; -// boost::tie(i,j,s) = lf->sparse(fg.columnIndices(ord)); -// -// list i1,j1; -// i1 += 1,2,1,2; -// j1 += 5,6,1,2; -// -// list s1; -// s1 += -10,-10,10,10; -// -// EXPECT(i==i1); -// EXPECT(j==j1); -// EXPECT(s==s1); -//} - /* ************************************************************************* */ TEST( GaussianFactor, size ) { // create a linear factor graph + const Key kx1 = X(1), kx2 = X(2), kl1 = L(1); 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 2e68200f5..306c64fb7 100644 --- a/tests/testGaussianFactorGraphB.cpp +++ b/tests/testGaussianFactorGraphB.cpp @@ -15,9 +15,17 @@ * @author Christian Potthast **/ -#include -#include -using namespace std; +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include @@ -26,192 +34,62 @@ 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)); } /* ************************************************************************* */ -//TEST( GaussianFactorGraph, error ) { -// Ordering ordering; ordering += kx(1),kx(2),kl(1); -// FactorGraph fg = createGaussianFactorGraph(ordering); -// VectorValues cfg = createZeroDelta(ordering); -// -// // note the error is the same as in testNonlinearFactorGraph as a -// // zero delta config in the linear graph is equivalent to noisy in -// // non-linear, which is really linear under the hood -// double actual = fg.error(cfg); -// DOUBLES_EQUAL( 5.625, actual, 1e-9 ); -//} +TEST( GaussianFactorGraph, error ) { + Ordering ordering; ordering += X(1),X(2),L(1); + GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + VectorValues cfg = createZeroDelta(ordering); -/* ************************************************************************* */ -/* unit test for find seperator */ -/* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, find_separator ) -//{ -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// set separator = fg.find_separator(kx(2)); -// set expected; -// expected.insert(kx(1)); -// expected.insert(kl(1)); -// -// EXPECT(separator.size()==expected.size()); -// set::iterator it1 = separator.begin(), it2 = expected.begin(); -// for(; it1!=separator.end(); it1++, it2++) -// EXPECT(*it1 == *it2); -//} - -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, combine_factors_x1 ) -//{ -// // create a small example for a linear factor graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// // combine all factors -// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(1)); -// -// // the expected linear factor -// Matrix Al1 = Matrix_(6,2, -// 0., 0., -// 0., 0., -// 0., 0., -// 0., 0., -// 5., 0., -// 0., 5. -// ); -// -// Matrix Ax1 = Matrix_(6,2, -// 10., 0., -// 0., 10., -// -10., 0., -// 0.,-10., -// -5., 0., -// 0.,-5. -// ); -// -// Matrix Ax2 = Matrix_(6,2, -// 0., 0., -// 0., 0., -// 10., 0., -// 0., 10., -// 0., 0., -// 0., 0. -// ); -// -// // the expected RHS vector -// Vector b(6); -// b(0) = -1; -// b(1) = -1; -// b(2) = 2; -// b(3) = -1; -// b(4) = 0; -// 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)); -// GaussianFactor expected(meas, b, ones(6)); -// //GaussianFactor expected(kl(1), Al1, kx(1), Ax1, kx(2), Ax2, b); -// -// // check if the two factors are the same -// EXPECT(assert_equal(expected,*actual)); -//} -// -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, combine_factors_x2 ) -//{ -// // create a small example for a linear factor graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// // combine all factors -// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(2)); -// -// // the expected linear factor -// Matrix Al1 = Matrix_(4,2, -// // l1 -// 0., 0., -// 0., 0., -// 5., 0., -// 0., 5. -// ); -// -// Matrix Ax1 = Matrix_(4,2, -// // x1 -// -10., 0., // f2 -// 0.,-10., // f2 -// 0., 0., // f4 -// 0., 0. // f4 -// ); -// -// Matrix Ax2 = Matrix_(4,2, -// // x2 -// 10., 0., -// 0., 10., -// -5., 0., -// 0.,-5. -// ); -// -// // the expected RHS vector -// Vector b(4); -// b(0) = 2; -// b(1) = -1; -// b(2) = -1; -// 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)); -// GaussianFactor expected(meas, b, ones(4)); -// -// // check if the two factors are the same -// EXPECT(assert_equal(expected,*actual)); -//} + // note the error is the same as in testNonlinearFactorGraph as a + // zero delta config in the linear graph is equivalent to noisy in + // non-linear, which is really linear under the hood + double actual = fg.error(cfg); + DOUBLES_EQUAL( 5.625, actual, 1e-9 ); +} /* ************************************************************************* */ 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); + GaussianConditional::shared_ptr conditional; + GaussianFactorGraph remaining; + boost::tie(conditional,remaining) = inference::eliminateOne(fg, 0, EliminateQR); // 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)); + EXPECT(assert_equal(expected,*conditional,tol)); } /* ************************************************************************* */ 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 +97,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,15 +105,15 @@ 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; // create expected Conditional Gaussian - double sig = sqrt(2)/10.; + 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 +121,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); - GaussianConditional::shared_ptr conditional = result.first; - GaussianFactorGraph remaining = result.second; + GaussianConditional::shared_ptr conditional; + GaussianFactorGraph remaining; + boost::tie(conditional,remaining) = inference::eliminateOne(fg, ordering[X(1)], EliminateQR); // 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, @@ -265,7 +143,7 @@ TEST( GaussianFactorGraph, eliminateOne_x1_fast ) 0., -2.357022603955159, 7.071067811865475, 0., 0., 7.071067811865475), - Vector_(4, -0.707106781186547, 0.942809041582063, 0.707106781186547, -1.414213562373094), sharedUnit(4)); + Vector_(4, -0.707106781186547, 0.942809041582063, 0.707106781186547, -1.414213562373094), noiseModel::Unit::Create(4)); EXPECT(assert_equal(expected,*conditional,tol)); EXPECT(assert_equal((const GaussianFactor&)expectedFactor,*remaining.back(),tol)); @@ -274,15 +152,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 +168,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)/10.; + 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 +188,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); @@ -332,52 +210,11 @@ TEST( GaussianFactorGraph, eliminateAll ) EXPECT(assert_equal(expected,actualQR,tol)); } -///* ************************************************************************* */ -//TEST( GaussianFactorGraph, eliminateAll_fast ) -//{ -// // create expected Chordal bayes Net -// Matrix I = eye(2); -// -// Vector d1 = Vector_(2, -0.1,-0.1); -// GaussianBayesNet expected = simpleGaussian(kx(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); -// -// 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); -// -// // Check one ordering -// GaussianFactorGraph fg1 = createGaussianFactorGraph(); -// Ordering ordering; -// ordering += kx(2),kl(1),kx(1); -// GaussianBayesNet actual = fg1.eliminate(ordering, false); -// EXPECT(assert_equal(expected,actual,tol)); -//} - -///* ************************************************************************* */ -//TEST( GaussianFactorGraph, add_priors ) -//{ -// Ordering ordering; ordering += kl(1),kx(1),kx(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))); -// EXPECT(assert_equal(expected,actual)); -//} - /* ************************************************************************* */ 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 ! @@ -393,51 +230,11 @@ TEST( GaussianFactorGraph, copying ) EXPECT(assert_equal(expected,actual)); } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, matrix ) -//{ -// // render with a given ordering -// Ordering ord; -// ord += kx(2),kl(1),kx(1); -// -// // Create a graph -// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); -// -// Matrix A; Vector b; -// boost::tie(A,b) = fg.matrix(); -// -// Matrix A1 = Matrix_(2*4,3*2, -// +0., 0., 0., 0., 10., 0., // unary factor on x1 (prior) -// +0., 0., 0., 0., 0., 10., -// 10., 0., 0., 0.,-10., 0., // binary factor on x2,x1 (odometry) -// +0., 10., 0., 0., 0.,-10., -// +0., 0., 5., 0., -5., 0., // binary factor on l1,x1 (z1) -// +0., 0., 0., 5., 0., -5., -// -5., 0., 5., 0., 0., 0., // binary factor on x2,l1 (z2) -// +0., -5., 0., 5., 0., 0. -// ); -// Vector b1 = Vector_(8,-1., -1., 2., -1., 0., 1., -1., 1.5); -// -// EQUALITY(A,A1); -// EXPECT(b==b1); -//} - -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, sizeOfA ) -//{ -// // create a small linear factor graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// pair mn = fg.sizeOfA(); -// EXPECT(8 == mn.first); -// EXPECT(6 == mn.second); -//} - /* ************************************************************************* */ 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 @@ -447,39 +244,24 @@ TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet ) GaussianFactorGraph fg2(CBN); GaussianBayesNet CBN2 = *GaussianSequentialSolver(fg2).eliminate(); EXPECT(assert_equal(CBN,CBN2)); - - // Base FactorGraph only -// FactorGraph fg3(CBN); -// GaussianBayesNet CBN3 = gtsam::eliminate(fg3,ord); -// EXPECT(assert_equal(CBN,CBN3)); } /* ************************************************************************* */ 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); -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// set interested; interested += kl(1),kx(1); -// Ordering actual = fg.getOrdering(interested); -// EXPECT(assert_equal(expected,actual)); -//} - /* ************************************************************************* */ 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 +279,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); @@ -511,29 +293,11 @@ TEST( GaussianFactorGraph, optimize_QR ) EXPECT(assert_equal(expected,actual)); } -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, optimizeMultiFrontlas ) -//{ -// // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); -// -// // create a graph -// GaussianFactorGraph fg = createGaussianFactorGraph(ord); -// -// // optimize the graph -// VectorValues actual = fg.optimizeMultiFrontals(ord); -// -// // verify -// VectorValues expected = createCorrectDelta(); -// -// EXPECT(assert_equal(expected,actual)); -//} - /* ************************************************************************* */ 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 +319,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); @@ -581,48 +345,6 @@ void print(vector v) { cout << endl; } -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, factor_lookup) -//{ -// // create a test graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// // ask for all factor indices connected to x1 -// list x1_factors = fg.factors(kx(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)); -// size_t x2_indices[] = { 1, 3 }; -// list x2_expected(x2_indices, x2_indices + 2); -// EXPECT(x2_factors==x2_expected); -//} - -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, findAndRemoveFactors ) -//{ -// // create the graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// // We expect to remove these three factors: 0, 1, 2 -// GaussianFactor::shared_ptr f0 = fg[0]; -// GaussianFactor::shared_ptr f1 = fg[1]; -// GaussianFactor::shared_ptr f2 = fg[2]; -// -// // call the function -// vector factors = fg.findAndRemoveFactors(kx(1)); -// -// // Check the factors -// EXPECT(f0==factors[0]); -// EXPECT(f1==factors[1]); -// EXPECT(f2==factors[2]); -// -// // EXPECT if the factors are deleted from the factor graph -// LONGS_EQUAL(1,fg.nrFactors()); -//} - /* ************************************************************************* */ TEST(GaussianFactorGraph, createSmoother) { @@ -632,83 +354,22 @@ TEST(GaussianFactorGraph, createSmoother) LONGS_EQUAL(5,fg2.size()); } -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, variables ) -//{ -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// Dimensions expected; -// insert(expected)(kl(1), 2)(kx(1), 2)(kx(2), 2); -// Dimensions actual = fg.dimensions(); -// EXPECT(expected==actual); -//} - -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, keys ) -//{ -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// Ordering expected; -// expected += kl(1),kx(1),kx(2); -// EXPECT(assert_equal(expected,fg.keys())); -//} - -///* ************************************************************************* */ -// 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))); -//} - /* ************************************************************************* */ 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); } -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, gradient ) -//{ -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// -// // 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 -// // 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)); -// -// // Check the gradient at delta=0 -// VectorValues zero = createZeroDelta(); -// VectorValues actual = fg.gradient(zero); -// EXPECT(assert_equal(expected,actual)); -// -// // Check it numerically for good measure -// Vector numerical_g = numericalGradient(error,zero,0.001); -// EXPECT(assert_equal(Vector_(6,5.0,-12.5,30.0,5.0,-25.0,17.5),numerical_g)); -// -// // Check the gradient at the solution (should be zero) -// Ordering ord; -// ord += kx(2),kl(1),kx(1); -// GaussianFactorGraph fg2 = createGaussianFactorGraph(); -// VectorValues solution = fg2.optimize(ord); // destructive -// VectorValues actual2 = fg.gradient(solution); -// EXPECT(assert_equal(zero,actual2)); -//} - /* ************************************************************************* */ 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); + GaussianFactorGraph A = createGaussianFactorGraph(ord); VectorValues x = createCorrectDelta(ord); Errors actual = A * x; Errors expected; @@ -719,61 +380,26 @@ TEST( GaussianFactorGraph, multiplication ) EXPECT(assert_equal(expected,actual)); } -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, transposeMultiplication ) -//{ -// // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); -// -// GaussianFactorGraph A = createGaussianFactorGraph(ord); -// Errors e; -// e += Vector_(2, 0.0, 0.0); -// e += Vector_(2,15.0, 0.0); -// e += Vector_(2, 0.0,-5.0); -// 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); -// EXPECT(assert_equal(expected,actual)); -//} - -///* ************************************************************************* */ -// SL-NEEDED? TEST( GaussianFactorGraph, rhs ) -//{ -// // create an ordering -// Ordering ord; ord += kx(2),kl(1),kx(1); -// -// GaussianFactorGraph Ab = createGaussianFactorGraph(ord); -// Errors expected = createZeroDelta(ord), actual = Ab.rhs(); -// expected.push_back(Vector_(2,-1.0,-1.0)); -// expected.push_back(Vector_(2, 2.0,-1.0)); -// expected.push_back(Vector_(2, 0.0, 1.0)); -// expected.push_back(Vector_(2,-1.0, 1.5)); -// EXPECT(assert_equal(expected,actual)); -//} - /* ************************************************************************* */ // Extra test on elimination prompted by Michael's email to Frank 1/4/2010 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); + SharedDiagonal sigma = noiseModel::Isotropic::Sigma(1,2.0); + 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; @@ -820,22 +446,6 @@ TEST( GaussianFactorGraph, constrained_single ) EXPECT(assert_equal(expected, actual)); } -///* ************************************************************************* */ -//SL-FIX TEST( GaussianFactorGraph, constrained_single2 ) -//{ -// // get a graph with a constraint in it -// GaussianFactorGraph fg = createSingleConstraintGraph(); -// -// // eliminate and solve -// Ordering ord; -// ord += "yk, x"; -// VectorValues actual = fg.optimize(ord); -// -// // verify -// VectorValues expected = createSingleConstraintValues(); -// EXPECT(assert_equal(expected, actual)); -//} - /* ************************************************************************* */ TEST( GaussianFactorGraph, constrained_multi1 ) { @@ -851,171 +461,39 @@ TEST( GaussianFactorGraph, constrained_multi1 ) EXPECT(assert_equal(expected, actual)); } -///* ************************************************************************* */ -//SL-FIX TEST( GaussianFactorGraph, constrained_multi2 ) -//{ -// // get a graph with a constraint in it -// GaussianFactorGraph fg = createMultiConstraintGraph(); -// -// // eliminate and solve -// Ordering ord; -// ord += "zk, xk, y"; -// VectorValues actual = fg.optimize(ord); -// -// // verify -// VectorValues expected = createMultiConstraintValues(); -// EXPECT(assert_equal(expected, actual)); -//} - /* ************************************************************************* */ -SharedDiagonal model = sharedSigma(2,1); - -// SL-FIX TEST( GaussianFactorGraph, findMinimumSpanningTree ) -//{ -// 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); -// -// 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); -//} - -///* ************************************************************************* */ -// SL-FIX TEST( GaussianFactorGraph, split ) -//{ -// 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); -// -// PredecessorMap tree; -// tree[kx(1)] = kx(1); -// tree[kx(2)] = kx(1); -// tree[kx(3)] = kx(1); -// tree[kx(4)] = kx(1); -// -// GaussianFactorGraph Ab1, Ab2; -// g.split(tree, Ab1, Ab2); -// LONGS_EQUAL(3, Ab1.size()); -// LONGS_EQUAL(2, Ab2.size()); -//} +static SharedDiagonal model = noiseModel::Isotropic::Sigma(2,1); /* ************************************************************************* */ TEST(GaussianFactorGraph, replace) { - Ordering ord; ord += kx(1),kx(2),kx(3),kx(4),kx(5),kx(6); - SharedDiagonal noise(sharedSigma(3, 1.0)); + Ordering ord; ord += X(1),X(2),X(3),X(4),X(5),X(6); + SharedDiagonal noise(noiseModel::Isotropic::Sigma(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); -// actual.checkGraphConsistency(); actual.push_back(f2); -// actual.checkGraphConsistency(); actual.push_back(f3); -// actual.checkGraphConsistency(); actual.replace(0, f4); -// actual.checkGraphConsistency(); GaussianFactorGraph expected; expected.push_back(f4); -// actual.checkGraphConsistency(); expected.push_back(f2); -// actual.checkGraphConsistency(); expected.push_back(f3); -// actual.checkGraphConsistency(); EXPECT(assert_equal(expected, actual)); } -///* ************************************************************************* */ -//TEST ( GaussianFactorGraph, combine_matrix ) { -// // create a small linear factor graph -// GaussianFactorGraph fg = createGaussianFactorGraph(); -// Dimensions dimensions = fg.dimensions(); -// -// // get two factors from it and insert the factors into a vector -// vector lfg; -// lfg.push_back(fg[4 - 1]); -// lfg.push_back(fg[2 - 1]); -// -// // combine in a factor -// Matrix Ab; SharedDiagonal noise; -// Ordering order; order += kx(2), kl(1), kx(1); -// boost::tie(Ab, noise) = combineFactorsAndCreateMatrix(lfg, order, dimensions); -// -// // the expected augmented matrix -// Matrix expAb = Matrix_(4, 7, -// -5., 0., 5., 0., 0., 0.,-1.0, -// +0., -5., 0., 5., 0., 0., 1.5, -// 10., 0., 0., 0.,-10., 0., 2.0, -// +0., 10., 0., 0., 0.,-10.,-1.0); -// -// // expected noise model -// SharedDiagonal expModel = noiseModel::Unit::Create(4); -// -// EXPECT(assert_equal(expAb, Ab)); -// EXPECT(assert_equal(*expModel, *noise)); -//} - -/* ************************************************************************* */ -/* - * x2 x1 x3 b - * 1 1 1 1 1 0 1 - * 1 1 1 -> 1 1 1 - * 1 1 1 1 - */ -// SL-NEEDED? TEST ( GaussianFactorGraph, eliminateFrontals ) { -// 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)); -// fg.push_back(factor1); -// fg.push_back(factor2); -// fg.push_back(factor3); -// -// Ordering frontals; frontals += kx(2), kx(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.))); -// 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 fg_expected; -// fg_expected.push_back(factor_expected); -// EXPECT(assert_equal(fg_expected, fg)); -//} - /* ************************************************************************* */ TEST(GaussianFactorGraph, createSmoother2) { @@ -1026,8 +504,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,8 +522,8 @@ TEST(GaussianFactorGraph, hasConstraints) FactorGraph fgc2 = createSimpleConstraintGraph() ; EXPECT(hasConstraints(fgc2)); - Ordering ordering; ordering += kx(1), kx(2), kl(1); - FactorGraph fg = createGaussianFactorGraph(ordering); + Ordering ordering; ordering += X(1), X(2), L(1); + GaussianFactorGraph fg = createGaussianFactorGraph(ordering); EXPECT(!hasConstraints(fg)); } diff --git a/tests/testGaussianISAM.cpp b/tests/testGaussianISAM.cpp index 4c798aa8d..74417b57a 100644 --- a/tests/testGaussianISAM.cpp +++ b/tests/testGaussianISAM.cpp @@ -15,41 +15,42 @@ * @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 -double sigmax1 = 0.786153, sigmax2 = 1.0/1.47292, sigmax3 = 0.671512, sigmax4 = - 0.669534, sigmax5 = sigmax3, sigmax6 = sigmax2, sigmax7 = sigmax1; +static double sigmax1 = 0.786153, sigmax2 = 1.0/1.47292, sigmax3 = 0.671512, sigmax4 = + 0.669534 /*, sigmax5 = sigmax3, sigmax6 = sigmax2*/, sigmax7 = sigmax1; -const double tol = 1e-4; +static const double tol = 1e-4; /* ************************************************************************* */ -TEST_UNSAFE( ISAM, iSAM_smoother ) +TEST( 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; @@ -75,31 +76,6 @@ TEST_UNSAFE( ISAM, iSAM_smoother ) EXPECT(assert_equal(e, optimized)); } -/* ************************************************************************* */ -// SL-FIX TEST( ISAM, iSAM_smoother2 ) -//{ -// // Create smoother with 7 nodes -// 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); -// GaussianFactorGraph factors1; -// for (int i=0;i<7;i++) factors1.push_back(smoother[i]); -// GaussianISAM actual(*inference::Eliminate(factors1)); -// -// // run iSAM with remaining factors -// GaussianFactorGraph factors2; -// for (int i=7;i<13;i++) factors2.push_back(smoother[i]); -// actual.update(factors2); -// -// // Create expected Bayes Tree by solving smoother with "natural" ordering -// Ordering ordering; -// for (int t = 1; t <= 7; t++) ordering += symbol('x', t); -// GaussianISAM expected(smoother.eliminate(ordering)); -// -// EXPECT(assert_equal(expected, actual)); -//} - /* ************************************************************************* * Bayes tree for smoother with "natural" ordering: C1 x6 x7 @@ -129,7 +105,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 +113,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 +122,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 +151,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 +168,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 +219,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 +233,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 +255,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 +264,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 +284,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 +303,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)); } @@ -372,9 +348,9 @@ TEST_UNSAFE(BayesTree, simpleMarginal) Matrix A12 = Rot2::fromDegrees(45.0).matrix(); - gfg.add(0, eye(2), zero(2), sharedSigma(2, 1.0)); - gfg.add(0, -eye(2), 1, eye(2), ones(2), sharedSigma(2, 1.0)); - gfg.add(1, -eye(2), 2, A12, ones(2), sharedSigma(2, 1.0)); + gfg.add(0, eye(2), zero(2), noiseModel::Isotropic::Sigma(2, 1.0)); + gfg.add(0, -eye(2), 1, eye(2), ones(2), noiseModel::Isotropic::Sigma(2, 1.0)); + gfg.add(1, -eye(2), 2, A12, ones(2), noiseModel::Isotropic::Sigma(2, 1.0)); Matrix expected(GaussianSequentialSolver(gfg).marginalCovariance(2)); Matrix actual(GaussianMultifrontalSolver(gfg).marginalCovariance(2)); diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 40e1ca4e1..c4b90d882 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -4,93 +4,99 @@ * @author Michael Kaess */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + #include #include // for operator += #include using namespace boost::assign; -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - 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 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); +SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas(Vector_(2, M_PI/100.0, 0.1)); + ISAM2 createSlamlikeISAM2( boost::optional init_values = boost::none, - boost::optional full_graph = 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)); Values fullinit; - planarSLAM::Graph fullgraph; + NonlinearFactorGraph fullgraph; // i keeps track of the time step size_t i = 0; // Add a prior at time 0 and update isam { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(PriorFactor(0, Pose2(0.0, 0.0, 0.0), odoNoise)); 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); } // Add odometry from time 0 to time 5 for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); 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); } // Add odometry from time 5 to 6 and landmark measurement at time 5 { - 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); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise)); + newfactors.add(BearingRangeFactor(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; @@ -98,28 +104,28 @@ ISAM2 createSlamlikeISAM2( // Add odometry from time 6 to time 10 for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); 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); } // Add odometry from time 10 to 11 and landmark measurement at time 10 { - 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); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); + newfactors.add(BearingRangeFactor(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; @@ -135,119 +141,161 @@ ISAM2 createSlamlikeISAM2( } /* ************************************************************************* */ -TEST_UNSAFE(ISAM2, AddVariables) { +TEST_UNSAFE(ISAM2, ImplAddVariables) { // 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)); - deltaUnpermuted.insert(1, Vector_(2, .4, .5)); + VectorValues delta; + delta.insert(0, Vector_(3, .1, .2, .3)); + delta.insert(1, Vector_(2, .4, .5)); - Permutation permutation(2); - permutation[0] = 1; - permutation[1] = 0; + VectorValues deltaNewton; + deltaNewton.insert(0, Vector_(3, .1, .2, .3)); + deltaNewton.insert(1, Vector_(2, .4, .5)); - Permuted delta(permutation, deltaUnpermuted); - - VectorValues deltaNewtonUnpermuted; - deltaNewtonUnpermuted.insert(0, Vector_(3, .1, .2, .3)); - deltaNewtonUnpermuted.insert(1, Vector_(2, .4, .5)); - - Permutation permutationNewton(2); - permutationNewton[0] = 1; - permutationNewton[1] = 0; - - Permuted deltaNewton(permutationNewton, deltaNewtonUnpermuted); - - VectorValues deltaRgUnpermuted; - deltaRgUnpermuted.insert(0, Vector_(3, .1, .2, .3)); - deltaRgUnpermuted.insert(1, Vector_(2, .4, .5)); - - Permutation permutationRg(2); - permutationRg[0] = 1; - permutationRg[1] = 0; - - Permuted deltaRg(permutationRg, deltaRgUnpermuted); + VectorValues deltaRg; + deltaRg.insert(0, Vector_(3, .1, .2, .3)); + deltaRg.insert(1, Vector_(2, .4, .5)); vector replacedKeys(2, false); - Ordering ordering; ordering += planarSLAM::PointKey(0), planarSLAM::PoseKey(0); - - ISAM2::Nodes nodes(2); + Ordering ordering; ordering += 100, 0; // 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(delta[0], delta[ordering[100]])); + EXPECT(assert_equal(delta[1], 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)); - deltaUnpermutedExpected.insert(1, Vector_(2, .4, .5)); - deltaUnpermutedExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); + VectorValues deltaExpected; + deltaExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaExpected.insert(1, Vector_(2, .4, .5)); + deltaExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); - Permutation permutationExpected(3); - permutationExpected[0] = 1; - permutationExpected[1] = 0; - permutationExpected[2] = 2; + VectorValues deltaNewtonExpected; + deltaNewtonExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaNewtonExpected.insert(1, Vector_(2, .4, .5)); + deltaNewtonExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); - Permuted deltaExpected(permutationExpected, deltaUnpermutedExpected); - - VectorValues deltaNewtonUnpermutedExpected; - deltaNewtonUnpermutedExpected.insert(0, Vector_(3, .1, .2, .3)); - deltaNewtonUnpermutedExpected.insert(1, Vector_(2, .4, .5)); - deltaNewtonUnpermutedExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); - - Permutation permutationNewtonExpected(3); - permutationNewtonExpected[0] = 1; - permutationNewtonExpected[1] = 0; - permutationNewtonExpected[2] = 2; - - Permuted deltaNewtonExpected(permutationNewtonExpected, deltaNewtonUnpermutedExpected); - - VectorValues deltaRgUnpermutedExpected; - deltaRgUnpermutedExpected.insert(0, Vector_(3, .1, .2, .3)); - deltaRgUnpermutedExpected.insert(1, Vector_(2, .4, .5)); - deltaRgUnpermutedExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); - - Permutation permutationRgExpected(3); - permutationRgExpected[0] = 1; - permutationRgExpected[1] = 0; - permutationRgExpected[2] = 2; - - Permuted deltaRgExpected(permutationRgExpected, deltaRgUnpermutedExpected); + VectorValues deltaRgExpected; + deltaRgExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaRgExpected.insert(1, Vector_(2, .4, .5)); + deltaRgExpected.insert(2, Vector_(3, 0.0, 0.0, 0.0)); vector replacedKeysExpected(3, false); - Ordering orderingExpected; orderingExpected += planarSLAM::PointKey(0), planarSLAM::PoseKey(0), planarSLAM::PoseKey(1); - - ISAM2::Nodes nodesExpected( - 3, ISAM2::sharedClique()); + Ordering orderingExpected; orderingExpected += 100, 0, 1; // Expand initial state - ISAM2::Impl::AddVariables(newTheta, theta, delta, deltaNewton, deltaRg, replacedKeys, ordering, nodes); + ISAM2::Impl::AddVariables(newTheta, theta, delta, deltaNewton, deltaRg, replacedKeys, ordering); EXPECT(assert_equal(thetaExpected, theta)); - EXPECT(assert_equal(deltaUnpermutedExpected, deltaUnpermuted)); - EXPECT(assert_equal(deltaExpected.permutation(), delta.permutation())); - EXPECT(assert_equal(deltaNewtonUnpermutedExpected, deltaNewtonUnpermuted)); - EXPECT(assert_equal(deltaNewtonExpected.permutation(), deltaNewton.permutation())); - EXPECT(assert_equal(deltaRgUnpermutedExpected, deltaRgUnpermuted)); - EXPECT(assert_equal(deltaRgExpected.permutation(), deltaRg.permutation())); + EXPECT(assert_equal(deltaExpected, delta)); + EXPECT(assert_equal(deltaNewtonExpected, deltaNewton)); + EXPECT(assert_equal(deltaRgExpected, deltaRg)); EXPECT(assert_container_equality(replacedKeysExpected, replacedKeys)); EXPECT(assert_equal(orderingExpected, ordering)); } +/* ************************************************************************* */ +TEST_UNSAFE(ISAM2, ImplRemoveVariables) { + + // Create initial state + Values theta; + theta.insert(0, Pose2(.1, .2, .3)); + theta.insert(1, Pose2(.6, .7, .8)); + theta.insert(100, Point2(.4, .5)); + + SymbolicFactorGraph sfg; + sfg.push_back(boost::make_shared(Index(0), Index(2))); + sfg.push_back(boost::make_shared(Index(0), Index(1))); + VariableIndex variableIndex(sfg); + + VectorValues delta; + delta.insert(0, Vector_(3, .1, .2, .3)); + delta.insert(1, Vector_(3, .4, .5, .6)); + delta.insert(2, Vector_(2, .7, .8)); + + VectorValues deltaNewton; + deltaNewton.insert(0, Vector_(3, .1, .2, .3)); + deltaNewton.insert(1, Vector_(3, .4, .5, .6)); + deltaNewton.insert(2, Vector_(2, .7, .8)); + + VectorValues deltaRg; + deltaRg.insert(0, Vector_(3, .1, .2, .3)); + deltaRg.insert(1, Vector_(3, .4, .5, .6)); + deltaRg.insert(2, Vector_(2, .7, .8)); + + vector replacedKeys(3, false); + replacedKeys[0] = true; + replacedKeys[1] = false; + replacedKeys[2] = true; + + Ordering ordering; ordering += 100, 1, 0; + + ISAM2::Nodes nodes(3); + + // Verify initial state + LONGS_EQUAL(0, ordering[100]); + LONGS_EQUAL(1, ordering[1]); + LONGS_EQUAL(2, ordering[0]); + + // Create expected state + Values thetaExpected; + thetaExpected.insert(0, Pose2(.1, .2, .3)); + thetaExpected.insert(100, Point2(.4, .5)); + + SymbolicFactorGraph sfgRemoved; + sfgRemoved.push_back(boost::make_shared(Index(0), Index(1))); + sfgRemoved.push_back(SymbolicFactorGraph::sharedFactor()); // Add empty factor to keep factor indices consistent + VariableIndex variableIndexExpected(sfgRemoved); + + VectorValues deltaExpected; + deltaExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaExpected.insert(1, Vector_(2, .7, .8)); + + VectorValues deltaNewtonExpected; + deltaNewtonExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaNewtonExpected.insert(1, Vector_(2, .7, .8)); + + VectorValues deltaRgExpected; + deltaRgExpected.insert(0, Vector_(3, .1, .2, .3)); + deltaRgExpected.insert(1, Vector_(2, .7, .8)); + + vector replacedKeysExpected(2, true); + + Ordering orderingExpected; orderingExpected += 100, 0; + + ISAM2::Nodes nodesExpected(2); + + // Reduce initial state + FastSet unusedKeys; + unusedKeys.insert(1); + vector removedFactorsI; removedFactorsI.push_back(1); + SymbolicFactorGraph removedFactors; removedFactors.push_back(sfg[1]); + variableIndex.remove(removedFactorsI, removedFactors); + GaussianFactorGraph linearFactors; + ISAM2::Impl::RemoveVariables(unusedKeys, ISAM2::sharedClique(), theta, variableIndex, delta, deltaNewton, deltaRg, + replacedKeys, ordering, nodes, linearFactors); + + EXPECT(assert_equal(thetaExpected, theta)); + EXPECT(assert_equal(variableIndexExpected, variableIndex)); + EXPECT(assert_equal(deltaExpected, delta)); + EXPECT(assert_equal(deltaNewtonExpected, deltaNewton)); + EXPECT(assert_equal(deltaRgExpected, deltaRg)); + EXPECT(assert_container_equality(replacedKeysExpected, replacedKeys)); + EXPECT(assert_equal(orderingExpected, ordering)); +} /* ************************************************************************* */ //TEST(ISAM2, IndicesFromFactors) { @@ -255,10 +303,10 @@ TEST_UNSAFE(ISAM2, AddVariables) { // using namespace gtsam::planarSLAM; // typedef GaussianISAM2::Impl Impl; // -// Ordering ordering; ordering += PointKey(0), PoseKey(0), PoseKey(1); -// planarSLAM::Graph graph; -// graph.addPrior(PoseKey(0), Pose2(), sharedUnit(Pose2::dimension)); -// graph.addRange(PoseKey(0), PointKey(0), 1.0, sharedUnit(1)); +// Ordering ordering; ordering += (0), (0), (1); +// NonlinearFactorGraph graph; +// graph.add(PriorFactor((0), Pose2(), noiseModel::Unit::Create(Pose2::dimension)); +// graph.addRange((0), (0), 1.0, noiseModel::Unit::Create(1)); // // FastSet expected; // expected.insert(0); @@ -307,7 +355,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 +366,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); @@ -336,7 +384,11 @@ TEST(ISAM2, optimize2) { } /* ************************************************************************* */ -bool isam_check(const planarSLAM::Graph& fullgraph, const Values& fullinit, const ISAM2& isam) { +bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, const ISAM2& isam, Test& test, TestResult& result) { + + TestResult& result_ = result; + const std::string name_ = test.getName(); + Values actual = isam.calculateEstimate(); Ordering ordering = isam.getOrdering(); // *fullgraph.orderingCOLAMD(fullinit).first; GaussianFactorGraph linearized = *fullgraph.linearize(fullinit, ordering); @@ -346,539 +398,94 @@ bool isam_check(const planarSLAM::Graph& fullgraph, const Values& fullinit, cons VectorValues delta = optimize(gbn); Values expected = fullinit.retract(delta, ordering); - return assert_equal(expected, actual); + bool isamEqual = assert_equal(expected, actual); + + // The following two checks make sure that the cached gradients are maintained and used correctly + + // Check gradient at each node + bool nodeGradientsOk = true; + typedef ISAM2::sharedClique sharedClique; + BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { + // Compute expected gradient + FactorGraph jfg; + jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); + VectorValues expectedGradient(*allocateVectorValues(isam)); + gradientAtZero(jfg, expectedGradient); + // Compare with actual gradients + int variablePosition = 0; + for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { + const int dim = clique->conditional()->dim(jit); + Vector actual = clique->gradientContribution().segment(variablePosition, dim); + bool gradOk = assert_equal(expectedGradient[*jit], actual); + EXPECT(gradOk); + nodeGradientsOk = nodeGradientsOk && gradOk; + variablePosition += dim; + } + bool dimOk = clique->gradientContribution().rows() == variablePosition; + EXPECT(dimOk); + nodeGradientsOk = nodeGradientsOk && dimOk; + } + + // Check gradient + VectorValues expectedGradient(*allocateVectorValues(isam)); + gradientAtZero(FactorGraph(isam), expectedGradient); + VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); + VectorValues actualGradient(*allocateVectorValues(isam)); + gradientAtZero(isam, actualGradient); + bool expectedGradOk = assert_equal(expectedGradient2, expectedGradient); + EXPECT(expectedGradOk); + bool totalGradOk = assert_equal(expectedGradient, actualGradient); + EXPECT(totalGradOk); + + return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual; } /* ************************************************************************* */ 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; - planarSLAM::Graph fullgraph; - - // i keeps track of the time step - size_t i = 0; - - // Add a prior at time 0 and update isam - { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Add odometry from time 0 to time 5 - for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 5 to 6 and landmark measurement at time 5 - { - 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); - 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))); - - isam.update(newfactors, init); - ++ i; - } - - // Add odometry from time 6 to time 10 - for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 10 to 11 and landmark measurement at time 10 - { - 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); - 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)); - - isam.update(newfactors, init); - ++ i; - } + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); // Compare solutions - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Check gradient at each node - typedef ISAM2::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { - // Compute expected gradient - FactorGraph jfg; - jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(jfg, expectedGradient); - // Compare with actual gradients - int variablePosition = 0; - for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { - const int dim = clique->conditional()->dim(jit); - Vector actual = clique->gradientContribution().segment(variablePosition, dim); - EXPECT(assert_equal(expectedGradient[*jit], actual)); - variablePosition += dim; - } - LONGS_EQUAL(clique->gradientContribution().rows(), variablePosition); - } - - // Check gradient - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(FactorGraph(isam), expectedGradient); - VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); - VectorValues actualGradient(*allocateVectorValues(isam)); - gradientAtZero(isam, actualGradient); - EXPECT(assert_equal(expectedGradient2, expectedGradient)); - EXPECT(assert_equal(expectedGradient, actualGradient)); + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); } /* ************************************************************************* */ 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; - planarSLAM::Graph fullgraph; - - // i keeps track of the time step - size_t i = 0; - - // Add a prior at time 0 and update isam - { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Add odometry from time 0 to time 5 - for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 5 to 6 and landmark measurement at time 5 - { - 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); - 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))); - - isam.update(newfactors, init); - ++ i; - } - - // Add odometry from time 6 to time 10 - for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 10 to 11 and landmark measurement at time 10 - { - 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); - 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)); - - isam.update(newfactors, init); - ++ i; - } + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false)); // Compare solutions - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Check gradient at each node - typedef ISAM2::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { - // Compute expected gradient - FactorGraph jfg; - jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(jfg, expectedGradient); - // Compare with actual gradients - int variablePosition = 0; - for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { - const int dim = clique->conditional()->dim(jit); - Vector actual = clique->gradientContribution().segment(variablePosition, dim); - EXPECT(assert_equal(expectedGradient[*jit], actual)); - variablePosition += dim; - } - LONGS_EQUAL(clique->gradientContribution().rows(), variablePosition); - } - - // Check gradient - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(FactorGraph(isam), expectedGradient); - VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); - VectorValues actualGradient(*allocateVectorValues(isam)); - gradientAtZero(isam, actualGradient); - EXPECT(assert_equal(expectedGradient2, expectedGradient)); - EXPECT(assert_equal(expectedGradient, actualGradient)); + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); } /* ************************************************************************* */ 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; - planarSLAM::Graph fullgraph; + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, false, ISAM2Params::QR)); - // i keeps track of the time step - size_t i = 0; - - // Add a prior at time 0 and update isam - { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Add odometry from time 0 to time 5 - for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 5 to 6 and landmark measurement at time 5 - { - 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); - 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))); - - isam.update(newfactors, init); - ++ i; - } - - // Add odometry from time 6 to time 10 - for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 10 to 11 and landmark measurement at time 10 - { - 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); - 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)); - - isam.update(newfactors, init); - ++ i; - } - - // Compare solutions - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Check gradient at each node - typedef ISAM2::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { - // Compute expected gradient - FactorGraph jfg; - jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(jfg, expectedGradient); - // Compare with actual gradients - int variablePosition = 0; - for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { - const int dim = clique->conditional()->dim(jit); - Vector actual = clique->gradientContribution().segment(variablePosition, dim); - EXPECT(assert_equal(expectedGradient[*jit], actual)); - variablePosition += dim; - } - LONGS_EQUAL(clique->gradientContribution().rows(), variablePosition); - } - - // Check gradient - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(FactorGraph(isam), expectedGradient); - VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); - VectorValues actualGradient(*allocateVectorValues(isam)); - gradientAtZero(isam, actualGradient); - EXPECT(assert_equal(expectedGradient2, expectedGradient)); - EXPECT(assert_equal(expectedGradient, actualGradient)); + // Compare solutions + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); } /* ************************************************************************* */ 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; - planarSLAM::Graph fullgraph; - - // i keeps track of the time step - size_t i = 0; - - // Add a prior at time 0 and update isam - { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Add odometry from time 0 to time 5 - for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 5 to 6 and landmark measurement at time 5 - { - 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); - 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))); - - isam.update(newfactors, init); - ++ i; - } - - // Add odometry from time 6 to time 10 - for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 10 to 11 and landmark measurement at time 10 - { - 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); - 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)); - - isam.update(newfactors, init); - ++ i; - } + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false, false, ISAM2Params::QR)); // Compare solutions - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Check gradient at each node - typedef ISAM2::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { - // Compute expected gradient - FactorGraph jfg; - jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(jfg, expectedGradient); - // Compare with actual gradients - int variablePosition = 0; - for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { - const int dim = clique->conditional()->dim(jit); - Vector actual = clique->gradientContribution().segment(variablePosition, dim); - EXPECT(assert_equal(expectedGradient[*jit], actual)); - variablePosition += dim; - } - LONGS_EQUAL(clique->gradientContribution().rows(), variablePosition); - } - - // Check gradient - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(FactorGraph(isam), expectedGradient); - VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); - VectorValues actualGradient(*allocateVectorValues(isam)); - gradientAtZero(isam, actualGradient); - EXPECT(assert_equal(expectedGradient2, expectedGradient)); - EXPECT(assert_equal(expectedGradient, actualGradient)); + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); } /* ************************************************************************* */ @@ -894,8 +501,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)), noiseModel::Unit::Create(3))); isam.update(factors); CHECK(assert_equal(createSlamlikeISAM2(), clone2)); @@ -978,167 +585,57 @@ 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; - planarSLAM::Graph fullgraph; + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); - // i keeps track of the time step - size_t i = 0; + // Remove the 2nd measurement on landmark 0 (Key 100) + FastVector toRemove; + toRemove.push_back(12); + isam.update(NonlinearFactorGraph(), Values(), toRemove); - // Add a prior at time 0 and update isam - { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Add odometry from time 0 to time 5 - for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 5 to 6 and landmark measurement at time 5 - { - 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); - 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))); - - isam.update(newfactors, init); - ++ i; - } - - // Add odometry from time 6 to time 10 - for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); - 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)); - - isam.update(newfactors, init); - } - - // Add odometry from time 10 to 11 and landmark measurement at time 10 - { - 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); - 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)); - - ISAM2Result result = isam.update(newfactors, init); - ++ i; - - // Remove the measurement on landmark 0 - FastVector toRemove; - EXPECT_LONGS_EQUAL(isam.getFactorsUnsafe().size()-2, result.newFactorsIndices[1]); - toRemove.push_back(result.newFactorsIndices[1]); - isam.update(planarSLAM::Graph(), Values(), toRemove); - } + // Remove the factor from the full system + fullgraph.remove(12); // Compare solutions - CHECK(isam_check(fullgraph, fullinit, isam)); - - // Check gradient at each node - typedef ISAM2::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& clique, isam.nodes()) { - // Compute expected gradient - FactorGraph jfg; - jfg.push_back(JacobianFactor::shared_ptr(new JacobianFactor(*clique->conditional()))); - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(jfg, expectedGradient); - // Compare with actual gradients - int variablePosition = 0; - for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) { - const int dim = clique->conditional()->dim(jit); - Vector actual = clique->gradientContribution().segment(variablePosition, dim); - EXPECT(assert_equal(expectedGradient[*jit], actual)); - variablePosition += dim; - } - LONGS_EQUAL(clique->gradientContribution().rows(), variablePosition); - } - - // Check gradient - VectorValues expectedGradient(*allocateVectorValues(isam)); - gradientAtZero(FactorGraph(isam), expectedGradient); - VectorValues expectedGradient2(gradient(FactorGraph(isam), VectorValues::Zero(expectedGradient))); - VectorValues actualGradient(*allocateVectorValues(isam)); - gradientAtZero(isam, actualGradient); - EXPECT(assert_equal(expectedGradient2, expectedGradient)); - EXPECT(assert_equal(expectedGradient, actualGradient)); + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); } /* ************************************************************************* */ -TEST(ISAM2, swapFactors) +TEST_UNSAFE(ISAM2, removeVariables) { + // These variables will be reused and accumulate factors and values + Values fullinit; + NonlinearFactorGraph fullgraph; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false)); -// SETDEBUG("ISAM2 update", true); -// SETDEBUG("ISAM2 update verbose", true); -// SETDEBUG("ISAM2 recalculate", true); + // Remove the measurement on landmark 0 (Key 100) + FastVector toRemove; + toRemove.push_back(7); + toRemove.push_back(14); + isam.update(NonlinearFactorGraph(), Values(), toRemove); + // Remove the factors and variable from the full system + fullgraph.remove(7); + fullgraph.remove(14); + fullinit.erase(100); + + // Compare solutions + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); +} + +/* ************************************************************************* */ +TEST_UNSAFE(ISAM2, swapFactors) +{ // 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; + NonlinearFactorGraph fullgraph; ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph); // Remove the measurement on landmark 0 and replace with a different one @@ -1148,16 +645,16 @@ TEST(ISAM2, swapFactors) toRemove.push_back(swap_idx); 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); + NonlinearFactorGraph swapfactors; +// swapfactors.add(BearingRange(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); // original factor + swapfactors.add(BearingRangeFactor(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise)); fullgraph.push_back(swapfactors); isam.update(swapfactors, Values(), toRemove); } // Compare solutions - EXPECT(assert_equal(fullgraph, planarSLAM::Graph(isam.getFactorsUnsafe()))); - EXPECT(isam_check(fullgraph, fullinit, isam)); + EXPECT(assert_equal(fullgraph, NonlinearFactorGraph(isam.getFactorsUnsafe()))); + EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_)); // Check gradient at each node typedef ISAM2::sharedClique sharedClique; @@ -1191,56 +688,43 @@ 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; - planarSLAM::Graph fullgraph; + NonlinearFactorGraph fullgraph; // 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; // Add a prior at time 0 and update isam { - planarSLAM::Graph newfactors; - newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(PriorFactor(0, Pose2(0.0, 0.0, 0.0), odoNoise)); 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); } - CHECK(isam_check(fullgraph, fullinit, isam)); + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); // Add odometry from time 0 to time 5 for( ; i<5; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); 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); @@ -1250,19 +734,19 @@ TEST(ISAM2, constrained_ordering) // Add odometry from time 5 to 6 and landmark measurement at time 5 { - 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); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise)); + newfactors.add(BearingRangeFactor(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; @@ -1270,38 +754,38 @@ TEST(ISAM2, constrained_ordering) // Add odometry from time 6 to time 10 for( ; i<10; ++i) { - planarSLAM::Graph newfactors; - newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); 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); } // Add odometry from time 10 to 11 and landmark measurement at time 10 { - 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); + NonlinearFactorGraph newfactors; + newfactors.add(BetweenFactor(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); + newfactors.add(BearingRangeFactor(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; } // Compare solutions - EXPECT(isam_check(fullgraph, fullinit, isam)); + EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_)); // 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; @@ -1332,6 +816,21 @@ TEST(ISAM2, constrained_ordering) EXPECT(assert_equal(expectedGradient, actualGradient)); } +/* ************************************************************************* */ +TEST(ISAM2, slamlike_solution_partial_relinearization_check) +{ + + // These variables will be reused and accumulate factors and values + Values fullinit; + NonlinearFactorGraph fullgraph; + ISAM2Params params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false); + params.enablePartialRelinearizationCheck = true; + ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, params); + + // Compare solutions + CHECK(isam_check(fullgraph, fullinit, isam, *this, result_)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index 074693123..422e52377 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -15,9 +15,24 @@ * @author nikai */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include +#include +#include + +#include #include #include // for operator += @@ -25,23 +40,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: @@ -50,23 +56,23 @@ Key kl(size_t i) { return Symbol('l',i); } C3 x1 : x2 C4 x7 : x6 */ -TEST( GaussianJunctionTree, constructor2 ) +TEST( GaussianJunctionTreeB, 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()); @@ -86,7 +92,7 @@ TEST( GaussianJunctionTree, constructor2 ) } /* ************************************************************************* */ -TEST( GaussianJunctionTree, optimizeMultiFrontal ) +TEST( GaussianJunctionTreeB, optimizeMultiFrontal ) { // create a graph GaussianFactorGraph fg; @@ -101,17 +107,17 @@ 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)); } /* ************************************************************************* */ -TEST( GaussianJunctionTree, optimizeMultiFrontal2) +TEST( GaussianJunctionTreeB, 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 @@ -124,52 +130,49 @@ TEST( GaussianJunctionTree, optimizeMultiFrontal2) } /* ************************************************************************* */ -TEST(GaussianJunctionTree, slamlike) { - using planarSLAM::PoseKey; - using planarSLAM::PointKey; - +TEST(GaussianJunctionTreeB, slamlike) { Values init; - planarSLAM::Graph newfactors; - planarSLAM::Graph fullgraph; - SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); + NonlinearFactorGraph newfactors; + NonlinearFactorGraph fullgraph; + SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); + SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas(Vector_(2, M_PI/100.0, 0.1)); 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 = NonlinearFactorGraph(); + newfactors.add(PriorFactor(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 = NonlinearFactorGraph(); + newfactors.add(BetweenFactor(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 = NonlinearFactorGraph(); + newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0), 5.0, brNoise)); + newfactors.add(BearingRangeFactor(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 = NonlinearFactorGraph(); + newfactors.add(BetweenFactor(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 = NonlinearFactorGraph(); + newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); + newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); + newfactors.add(BearingRangeFactor(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; @@ -189,21 +192,21 @@ TEST(GaussianJunctionTree, slamlike) { } /* ************************************************************************* */ -TEST(GaussianJunctionTree, simpleMarginal) { +TEST(GaussianJunctionTreeB, simpleMarginal) { typedef BayesTree GaussianBayesTree; // 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))); + NonlinearFactorGraph fg; + fg.add(PriorFactor(X(0), Pose2(), noiseModel::Isotropic::Sigma(3, 10.0))); + fg.add(BetweenFactor(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas(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/testGradientDescentOptimizer.cpp b/tests/testGradientDescentOptimizer.cpp new file mode 100644 index 000000000..4f556eb0f --- /dev/null +++ b/tests/testGradientDescentOptimizer.cpp @@ -0,0 +1,106 @@ +/** + * @file testGradientDescentOptimizer.cpp + * @brief + * @author ydjian + * @date Jun 11, 2012 + */ + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + + +using namespace std; +using namespace gtsam; + + +boost::tuple generateProblem() { + + // 1. Create graph container and add factors to it + NonlinearFactorGraph graph ; + + // 2a. Add Gaussian prior + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); + graph.add(PriorFactor(1, priorMean, priorNoise)); + + // 2b. Add odometry factors + SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + graph.add(BetweenFactor(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise)); + graph.add(BetweenFactor(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + graph.add(BetweenFactor(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + graph.add(BetweenFactor(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise)); + + // 2c. Add pose constraint + SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); + graph.add(BetweenFactor(5, 2, Pose2(2.0, 0.0, M_PI_2), constraintUncertainty)); + + // 3. Create the data structure to hold the initialEstimate estinmate to the solution + Values initialEstimate; + Pose2 x1(0.5, 0.0, 0.2 ); initialEstimate.insert(1, x1); + Pose2 x2(2.3, 0.1,-0.2 ); initialEstimate.insert(2, x2); + Pose2 x3(4.1, 0.1, M_PI_2); initialEstimate.insert(3, x3); + Pose2 x4(4.0, 2.0, M_PI ); initialEstimate.insert(4, x4); + Pose2 x5(2.1, 2.1,-M_PI_2); initialEstimate.insert(5, x5); + + return boost::tie(graph, initialEstimate); +} + +/* ************************************************************************* */ +TEST(optimize, GradientDescentOptimizer) { + + NonlinearFactorGraph graph; + Values initialEstimate; + + boost::tie(graph, initialEstimate) = generateProblem(); + // cout << "initial error = " << graph.error(initialEstimate) << endl ; + + // Single Step Optimization using Levenberg-Marquardt + NonlinearOptimizerParams param; + param.maxIterations = 500; /* requires a larger number of iterations to converge */ + param.verbosity = NonlinearOptimizerParams::SILENT; + + NonlinearConjugateGradientOptimizer optimizer(graph, initialEstimate, param); + Values result = optimizer.optimize(); +// cout << "gd1 solver final error = " << graph.error(result) << endl; + + /* the optimality of the solution is not comparable to the */ + DOUBLES_EQUAL(0.0, graph.error(result), 1e-2); + + CHECK(1); +} + +/* ************************************************************************* */ +TEST(optimize, ConjugateGradientOptimizer) { + + NonlinearFactorGraph graph; + Values initialEstimate; + + boost::tie(graph, initialEstimate) = generateProblem(); +// cout << "initial error = " << graph.error(initialEstimate) << endl ; + + // Single Step Optimization using Levenberg-Marquardt + NonlinearOptimizerParams param; + param.maxIterations = 500; /* requires a larger number of iterations to converge */ + param.verbosity = NonlinearOptimizerParams::SILENT; + + NonlinearConjugateGradientOptimizer optimizer(graph, initialEstimate, param); + Values result = optimizer.optimize(); +// cout << "cg final error = " << graph.error(result) << endl; + + /* the optimality of the solution is not comparable to the */ + DOUBLES_EQUAL(0.0, graph.error(result), 1e-2); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/tests/testGraph.cpp b/tests/testGraph.cpp index f56efae82..14655a249 100644 --- a/tests/testGraph.cpp +++ b/tests/testGraph.cpp @@ -16,38 +16,36 @@ * @brief unit test for graph-inl.h */ -#include +#include +#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,47 +65,148 @@ 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)); - tie(graph, root, key2vertex) = predecessorMap2Graph, SVertex, Key>(p_map); + p_map.insert(1, 2); + p_map.insert(2, 2); + p_map.insert(3, 2); + boost::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); + NonlinearFactorGraph graph; + SharedNoiseModel cov = noiseModel::Unit::Create(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); - graph.addOdometry(2,3, p23, cov); - graph.addOdometry(4,3, p43, cov); + graph.add(BetweenFactor(1,2, p12, cov)); + graph.add(BetweenFactor(2,3, p23, cov)); + graph.add(BetweenFactor(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; - boost::shared_ptr actual = composePoses (graph, tree, rootPose); + boost::shared_ptr actual = 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)); } +// SL-FIX TEST( GaussianFactorGraph, findMinimumSpanningTree ) +//{ +// GaussianFactorGraph g; +// Matrix I = eye(2); +// Vector b = Vector_(0, 0, 0); +// 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[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); +//} + +///* ************************************************************************* */ +// SL-FIX TEST( GaussianFactorGraph, split ) +//{ +// GaussianFactorGraph g; +// Matrix I = eye(2); +// Vector b = Vector_(0, 0, 0); +// 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[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); +// LONGS_EQUAL(3, Ab1.size()); +// LONGS_EQUAL(2, Ab2.size()); +//} + +///* ************************************************************************* */ +// SL-FIX TEST( FactorGraph, splitMinimumSpanningTree ) +//{ +// SymbolicFactorGraph G; +// G.push_factor("x1", "x2"); +// G.push_factor("x1", "x3"); +// G.push_factor("x1", "x4"); +// G.push_factor("x2", "x3"); +// G.push_factor("x2", "x4"); +// G.push_factor("x3", "x4"); +// +// SymbolicFactorGraph T, C; +// boost::tie(T, C) = G.splitMinimumSpanningTree(); +// +// SymbolicFactorGraph expectedT, expectedC; +// expectedT.push_factor("x1", "x2"); +// expectedT.push_factor("x1", "x3"); +// expectedT.push_factor("x1", "x4"); +// expectedC.push_factor("x2", "x3"); +// expectedC.push_factor("x2", "x4"); +// expectedC.push_factor("x3", "x4"); +// CHECK(assert_equal(expectedT,T)); +// CHECK(assert_equal(expectedC,C)); +//} + +///* ************************************************************************* */ +///** +// * x1 - x2 - x3 - x4 - x5 +// * | | / | +// * l1 l2 l3 +// */ +// SL-FIX TEST( FactorGraph, removeSingletons ) +//{ +// SymbolicFactorGraph G; +// G.push_factor("x1", "x2"); +// G.push_factor("x2", "x3"); +// G.push_factor("x3", "x4"); +// G.push_factor("x4", "x5"); +// G.push_factor("x2", "l1"); +// G.push_factor("x3", "l2"); +// G.push_factor("x4", "l2"); +// G.push_factor("x4", "l3"); +// +// SymbolicFactorGraph singletonGraph; +// set singletons; +// boost::tie(singletonGraph, singletons) = G.removeSingletons(); +// +// set singletons_excepted; singletons_excepted += "x1", "x2", "x5", "l1", "l3"; +// CHECK(singletons_excepted == singletons); +// +// SymbolicFactorGraph singletonGraph_excepted; +// singletonGraph_excepted.push_factor("x2", "l1"); +// singletonGraph_excepted.push_factor("x4", "l3"); +// singletonGraph_excepted.push_factor("x1", "x2"); +// singletonGraph_excepted.push_factor("x4", "x5"); +// singletonGraph_excepted.push_factor("x2", "x3"); +// CHECK(singletonGraph_excepted.equals(singletonGraph)); +//} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/tests/testInferenceB.cpp b/tests/testInferenceB.cpp index 6ad070698..9b8127473 100644 --- a/tests/testInferenceB.cpp +++ b/tests/testInferenceB.cpp @@ -17,14 +17,27 @@ #include +#include +#include +#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; + /* ************************************************************************* */ // The tests below test the *generic* inference algorithms. Some of these have // specialized versions in the derived classes GaussianFactorGraph etc... @@ -41,34 +54,34 @@ TEST( inference, marginals ) *GaussianSequentialSolver(GaussianFactorGraph(cbn)).jointFactorGraph(xvar)).eliminate(); // expected is just scalar Gaussian on x - GaussianBayesNet expected = scalarGaussian(0, 4, sqrt(2)); + GaussianBayesNet expected = scalarGaussian(0, 4, sqrt(2.0)); CHECK(assert_equal(expected,actual)); } /* ************************************************************************* */ TEST( inference, marginals2) { - planarSLAM::Graph fg; - SharedDiagonal poseModel(sharedSigma(3, 0.1)); - SharedDiagonal pointModel(sharedSigma(3, 0.1)); + NonlinearFactorGraph fg; + SharedDiagonal poseModel(noiseModel::Isotropic::Sigma(3, 0.1)); + SharedDiagonal pointModel(noiseModel::Isotropic::Sigma(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.add(PriorFactor(X(0), Pose2(), poseModel)); + fg.add(BetweenFactor(X(0), X(1), Pose2(1.0,0.0,0.0), poseModel)); + fg.add(BetweenFactor(X(1), X(2), Pose2(1.0,0.0,0.0), poseModel)); + fg.add(BearingRangeFactor(X(0), L(0), Rot2(), 1.0, pointModel)); + fg.add(BearingRangeFactor(X(1), L(0), Rot2(), 1.0, pointModel)); + fg.add(BearingRangeFactor(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/testIterative.cpp b/tests/testIterative.cpp new file mode 100644 index 000000000..bfa3a8e79 --- /dev/null +++ b/tests/testIterative.cpp @@ -0,0 +1,154 @@ +/* ---------------------------------------------------------------------------- + + * 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 testIterative.cpp + * @brief Unit tests for iterative methods + * @author Frank Dellaert + **/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; +using namespace example; +using symbol_shorthand::X; // to create pose keys +using symbol_shorthand::L; // to create landmark keys + +static ConjugateGradientParameters parameters; +// add following below to add printing: +// parameters.verbosity_ = ConjugateGradientParameters::COMPLEXITY; + +/* ************************************************************************* */ +TEST( Iterative, steepestDescent ) +{ + // Create factor graph + Ordering ordering; + ordering += L(1), X(1), X(2); + GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + + // eliminate and solve + VectorValues expected = *GaussianSequentialSolver(fg).optimize(); + + // Do gradient descent + VectorValues zero = VectorValues::Zero(expected); // TODO, how do we do this normally? + VectorValues actual = steepestDescent(fg, zero, parameters); + CHECK(assert_equal(expected,actual,1e-2)); +} + +/* ************************************************************************* */ +TEST( Iterative, conjugateGradientDescent ) +{ + // Create factor graph + Ordering ordering; + ordering += L(1), X(1), X(2); + GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + + // eliminate and solve + VectorValues expected = *GaussianSequentialSolver(fg).optimize(); + + // get matrices + Matrix A; + Vector b; + Vector x0 = gtsam::zero(6); + boost::tie(A, b) = fg.jacobian(); + Vector expectedX = Vector_(6, -0.1, 0.1, -0.1, -0.1, 0.1, -0.2); + + // Do conjugate gradient descent, System version + System Ab(A, b); + Vector actualX = conjugateGradientDescent(Ab, x0, parameters); + CHECK(assert_equal(expectedX,actualX,1e-9)); + + // Do conjugate gradient descent, Matrix version + Vector actualX2 = conjugateGradientDescent(A, b, x0, parameters); + CHECK(assert_equal(expectedX,actualX2,1e-9)); + + // Do conjugate gradient descent on factor graph + VectorValues zero = VectorValues::Zero(expected); + VectorValues actual = conjugateGradientDescent(fg, zero, parameters); + CHECK(assert_equal(expected,actual,1e-2)); +} + +/* ************************************************************************* */ +TEST( Iterative, conjugateGradientDescent_hard_constraint ) +{ + Values config; + Pose2 pose1 = Pose2(0.,0.,0.); + config.insert(X(1), pose1); + config.insert(X(2), Pose2(1.5,0.,0.)); + + NonlinearFactorGraph graph; + graph.add(NonlinearEquality(X(1), pose1)); + graph.add(BetweenFactor(X(1),X(2), Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1))); + + Ordering ordering; + ordering += X(1), X(2); + boost::shared_ptr fg = graph.linearize(config,ordering); + + VectorValues zeros = VectorValues::Zero(2, 3); + + ConjugateGradientParameters parameters; + parameters.setEpsilon_abs(1e-3); + parameters.setEpsilon_rel(1e-5); + parameters.setMaxIterations(100); + VectorValues actual = conjugateGradientDescent(*fg, zeros, parameters); + + VectorValues expected; + expected.insert(0, zero(3)); + expected.insert(1, Vector_(3,-0.5,0.,0.)); + CHECK(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST( Iterative, conjugateGradientDescent_soft_constraint ) +{ + Values config; + config.insert(X(1), Pose2(0.,0.,0.)); + config.insert(X(2), Pose2(1.5,0.,0.)); + + NonlinearFactorGraph graph; + graph.add(PriorFactor(X(1), Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10))); + graph.add(BetweenFactor(X(1),X(2), Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1))); + + Ordering ordering; + ordering += X(1), X(2); + boost::shared_ptr fg = graph.linearize(config,ordering); + + VectorValues zeros = VectorValues::Zero(2, 3); + + ConjugateGradientParameters parameters; + parameters.setEpsilon_abs(1e-3); + parameters.setEpsilon_rel(1e-5); + parameters.setMaxIterations(100); + VectorValues actual = conjugateGradientDescent(*fg, zeros, parameters); + + VectorValues expected; + expected.insert(0, zero(3)); + expected.insert(1, Vector_(3,-0.5,0.,0.)); + CHECK(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index a91e6b576..c9bd43b27 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -51,34 +51,34 @@ 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 - SharedDiagonal meas_model = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); + SharedDiagonal measurementNoise = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); // create the measurement values - indices are (pose id, landmark id) Rot2 bearing11 = Rot2::fromDegrees(45), bearing21 = Rot2::fromDegrees(90), bearing32 = Rot2::fromDegrees(90); - double range11 = sqrt(4+4), + double range11 = sqrt(4.0+4.0), range21 = 2.0, range32 = 2.0; // create bearing/range factors - graph.add(BearingRangeFactor(x1, l1, bearing11, range11, meas_model)); - graph.add(BearingRangeFactor(x2, l1, bearing21, range21, meas_model)); - graph.add(BearingRangeFactor(x3, l2, bearing32, range32, meas_model)); + graph.add(BearingRangeFactor(x1, l1, bearing11, range11, measurementNoise)); + graph.add(BearingRangeFactor(x2, l1, bearing21, range21, measurementNoise)); + graph.add(BearingRangeFactor(x3, l2, bearing32, range32, measurementNoise)); // linearization point for marginals Values soln; @@ -180,7 +180,62 @@ TEST(Marginals, planarSLAMmarginals) { EXPECT(assert_equal(expectedx1, Matrix(joint_l2x1(x1,x1)), 1e-6)); } +/* ************************************************************************* */ +TEST(Marginals, order) { + NonlinearFactorGraph fg; + fg.add(PriorFactor(0, Pose2(), noiseModel::Unit::Create(3))); + fg.add(BetweenFactor(0, 1, Pose2(1,0,0), noiseModel::Unit::Create(3))); + fg.add(BetweenFactor(1, 2, Pose2(1,0,0), noiseModel::Unit::Create(3))); + fg.add(BetweenFactor(2, 3, Pose2(1,0,0), noiseModel::Unit::Create(3))); + Values vals; + vals.insert(0, Pose2()); + vals.insert(1, Pose2(1,0,0)); + vals.insert(2, Pose2(2,0,0)); + vals.insert(3, Pose2(3,0,0)); + + vals.insert(100, Point2(0,1)); + vals.insert(101, Point2(1,1)); + + fg.add(BearingRangeFactor(0, 100, + vals.at(0).bearing(vals.at(100)), + vals.at(0).range(vals.at(100)), noiseModel::Unit::Create(2))); + fg.add(BearingRangeFactor(0, 101, + vals.at(0).bearing(vals.at(101)), + vals.at(0).range(vals.at(101)), noiseModel::Unit::Create(2))); + + fg.add(BearingRangeFactor(1, 100, + vals.at(1).bearing(vals.at(100)), + vals.at(1).range(vals.at(100)), noiseModel::Unit::Create(2))); + fg.add(BearingRangeFactor(1, 101, + vals.at(1).bearing(vals.at(101)), + vals.at(1).range(vals.at(101)), noiseModel::Unit::Create(2))); + + fg.add(BearingRangeFactor(2, 100, + vals.at(2).bearing(vals.at(100)), + vals.at(2).range(vals.at(100)), noiseModel::Unit::Create(2))); + fg.add(BearingRangeFactor(2, 101, + vals.at(2).bearing(vals.at(101)), + vals.at(2).range(vals.at(101)), noiseModel::Unit::Create(2))); + + fg.add(BearingRangeFactor(3, 100, + vals.at(3).bearing(vals.at(100)), + vals.at(3).range(vals.at(100)), noiseModel::Unit::Create(2))); + fg.add(BearingRangeFactor(3, 101, + vals.at(3).bearing(vals.at(101)), + vals.at(3).range(vals.at(101)), noiseModel::Unit::Create(2))); + + Marginals marginals(fg, vals); + FastVector keys(fg.keys()); + JointMarginal joint = marginals.jointMarginalCovariance(keys); + + LONGS_EQUAL(3, joint(0,0).rows()); + LONGS_EQUAL(3, joint(1,1).rows()); + LONGS_EQUAL(3, joint(2,2).rows()); + LONGS_EQUAL(3, joint(3,3).rows()); + LONGS_EQUAL(2, joint(100,100).rows()); + LONGS_EQUAL(2, joint(101,101).rows()); +} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} diff --git a/tests/testNonlinearEquality.cpp b/tests/testNonlinearEquality.cpp index 94ab58831..2b580560f 100644 --- a/tests/testNonlinearEquality.cpp +++ b/tests/testNonlinearEquality.cpp @@ -14,15 +14,22 @@ * @author Alex Cunningham */ -#include +#include -#include #include -#include -#include +#include +#include #include #include #include +#include +#include +#include +#include +#include +#include + +#include using namespace std; using namespace gtsam; @@ -35,7 +42,7 @@ typedef PriorFactor PosePrior; typedef NonlinearEquality PoseNLE; typedef boost::shared_ptr shared_poseNLE; -Symbol key('x',1); +static Symbol key('x',1); /* ************************************************************************* */ TEST ( NonlinearEquality, linearization ) { @@ -239,8 +246,8 @@ TEST ( NonlinearEquality, allow_error_optimize_with_factors ) { } /* ************************************************************************* */ -SharedDiagonal hard_model = noiseModel::Constrained::All(2); -SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0); +static SharedDiagonal hard_model = noiseModel::Constrained::All(2); +static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0); /* ************************************************************************* */ TEST( testNonlinearEqualityConstraint, unary_basics ) { @@ -502,13 +509,13 @@ TEST (testNonlinearEqualityConstraint, map_warp ) { } // make a realistic calibration matrix -double fov = 60; // degrees -size_t w=640,h=480; -Cal3_S2 K(fov,w,h); -boost::shared_ptr shK(new Cal3_S2(K)); +static double fov = 60; // degrees +static size_t w=640,h=480; +static Cal3_S2 K(fov,w,h); +static boost::shared_ptr shK(new Cal3_S2(K)); // typedefs for visual SLAM example -typedef visualSLAM::Graph VGraph; +typedef NonlinearFactorGraph VGraph; // factors for visual slam typedef NonlinearEquality2 Point3Equality; @@ -522,9 +529,9 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { 0.0, 0.0, 1.0, 0.0, -1.0, 0.0)); Pose3 pose1(faceDownY, Point3()); // origin, left camera - SimpleCamera camera1(K, pose1); + SimpleCamera camera1(pose1, K); Pose3 pose2(faceDownY, Point3(2.0, 0.0, 0.0)); // 2 units to the left - SimpleCamera camera2(K, pose2); + SimpleCamera camera2(pose2, K); Point3 landmark(1.0, 5.0, 0.0); //centered between the cameras, 5 units away // keys @@ -535,13 +542,13 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { VGraph graph; // create equality constraints for poses - graph.addPoseConstraint(1, camera1.pose()); - graph.addPoseConstraint(2, camera2.pose()); + graph.add(NonlinearEquality(x1, camera1.pose())); + graph.add(NonlinearEquality(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.add(GenericProjectionFactor(camera1.project(landmark), vmodel, x1, l1, shK)); + graph.add(GenericProjectionFactor(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 d32a50fe5..c8824749d 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -28,17 +28,19 @@ #include #include #include -#include -#include +#include +#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)); @@ -71,8 +73,8 @@ TEST( NonlinearFactor, equals2 ) Graph::sharedFactor f0 = fg[0], f1 = fg[1]; CHECK(f0->equals(*f0)); -// SL-FIX CHECK(!f0->equals(*f1)); -// SL-FIX CHECK(!f1->equals(*f0)); + CHECK(!f0->equals(*f1)); + CHECK(!f1->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(noiseModel::Diagonal::Sigmas(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, @@ -254,19 +256,23 @@ public: } return (Vector(1) << x1 + x2 + x3 + x4).finished(); } + + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new TestFactor4(*this))); } }; /* ************************************ */ 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); @@ -283,7 +289,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(noiseModel::Diagonal::Sigmas(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, @@ -307,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); @@ -333,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(noiseModel::Diagonal::Sigmas(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, @@ -353,21 +359,22 @@ public: } return (Vector(1) << x1 + x2 + x3 + x4 + x5 + x6).finished(); } + }; /* ************************************ */ 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); @@ -385,6 +392,42 @@ TEST(NonlinearFactor, NoiseModelFactor6) { } +/* ************************************************************************* */ +TEST( NonlinearFactor, clone_rekey ) +{ + shared_nlf init(new TestFactor4()); + 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(); + EXPECT(actClone.get() != init.get()); // Ensure different pointers + EXPECT(assert_equal(*init, *actClone)); + + // Re-key factor - clones with different keys + std::vector new_keys(4); + 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(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(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]); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index 92e569038..f677eb0dc 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -29,15 +29,16 @@ using namespace boost::assign; #include #include -#include +#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 ) @@ -64,25 +65,32 @@ TEST( Graph, error ) TEST( Graph, keys ) { Graph fg = createNonlinearFactorGraph(); - set actual = fg.keys(); + FastSet 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++)); + FastSet::const_iterator it = actual.begin(); + 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; boost::tie(symbolic, ordering) = nlfg.symbolic(createNoisyValues()); Ordering actual = *nlfg.orderingCOLAMD(createNoisyValues()); - CHECK(assert_equal(expected,actual)); + EXPECT(assert_equal(expected,actual)); + + // Constrained ordering - put x2 at the end + std::map constraints; + constraints[X(2)] = 1; + Ordering actualConstrained = *nlfg.orderingCOLAMDConstrained(createNoisyValues(), constraints); + Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2); + EXPECT(assert_equal(expectedConstrained, actualConstrained)); } /* ************************************************************************* */ @@ -108,8 +116,42 @@ TEST( Graph, linearize ) } /* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); +TEST( Graph, clone ) +{ + Graph fg = createNonlinearFactorGraph(); + Graph actClone = fg.clone(); + EXPECT(assert_equal(fg, actClone)); + for (size_t i=0; i rekey_mapping; + rekey_mapping.insert(make_pair(L(1), L(4))); + Graph actRekey = init.rekey(rekey_mapping); + + // ensure deep clone + LONGS_EQUAL(init.size(), actRekey.size()); + for (size_t i=0; i -#include +#include +#include #include -#include +#include +#include +#include +#include +#include + using namespace gtsam; -using namespace planarSLAM; -typedef NonlinearISAM<> PlanarISAM; +typedef NonlinearISAM PlanarISAM; const double tol=1e-5; @@ -26,22 +31,22 @@ TEST(testNonlinearISAM, markov_chain ) { // create initial graph Pose2 cur_pose; // start at origin - Graph start_factors; - start_factors.addPoseConstraint(0, cur_pose); + NonlinearFactorGraph start_factors; + start_factors.add(NonlinearEquality(0, cur_pose)); - planarSLAM::Values init; - planarSLAM::Values expected; - init.insertPose(0, cur_pose); - expected.insertPose(0, cur_pose); + Values init; + Values expected; + init.insert(0, cur_pose); + expected.insert(0, cur_pose); isam.update(start_factors, init); // loop for a period of time to verify memory usage size_t nrPoses = 21; Pose2 z(1.0, 2.0, 0.1); for (size_t i=1; i<=nrPoses; ++i) { - Graph new_factors; - new_factors.addOdometry(i-1, i, z, model); - planarSLAM::Values new_init; + NonlinearFactorGraph new_factors; + new_factors.add(BetweenFactor(i-1, i, z, model)); + Values new_init; // perform a check on changing orderings if (i == 5) { @@ -54,20 +59,20 @@ 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())); } cur_pose = cur_pose.compose(z); - new_init.insertPose(i, cur_pose.retract(sampler.sample())); - expected.insertPose(i, cur_pose); + new_init.insert(i, cur_pose.retract(sampler.sample())); + expected.insert(i, cur_pose); isam.update(new_factors, new_init); } // verify values - all but the last one should be very close - planarSLAM::Values actual = isam.estimate(); + Values actual = isam.estimate(); for (size_t i=0; i(i), actual.at(i), tol)); } } diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index d1eb01f27..cb5e8f482 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -15,32 +15,36 @@ * @author Frank Dellaert */ -#include -using namespace std; - -#include // for operator += -using namespace boost::assign; +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include -using namespace boost; +#include // for operator += +using namespace boost::assign; -#include -#include -#include -#include -#include -#include -#include -#include +#include +using namespace std; 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 ) @@ -51,7 +55,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; @@ -75,18 +79,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; @@ -114,7 +118,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); @@ -127,7 +131,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); @@ -140,7 +144,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); @@ -150,15 +154,15 @@ TEST( NonlinearOptimizer, SimpleDLOptimizer ) TEST( NonlinearOptimizer, optimization_method ) { LevenbergMarquardtParams paramsQR; - paramsQR.factorization = LevenbergMarquardtParams::QR; + paramsQR.linearSolverType = LevenbergMarquardtParams::MULTIFRONTAL_QR; LevenbergMarquardtParams paramsChol; - paramsChol.factorization = LevenbergMarquardtParams::CHOLESKY; + paramsChol.linearSolverType = LevenbergMarquardtParams::MULTIFRONTAL_CHOLESKY; example::Graph fg = example::createReallyNonlinearFactorGraph(); 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); @@ -171,23 +175,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)); + NonlinearFactorGraph graph; + graph.add(PriorFactor(X(1), Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10))); + graph.add(BetweenFactor(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)); } @@ -202,18 +206,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(); @@ -232,9 +236,9 @@ TEST(NonlinearOptimizer, NullFactor) { TEST(NonlinearOptimizer, MoreOptimization) { NonlinearFactorGraph fg; - fg.add(PriorFactor(0, Pose2(0,0,0), sharedSigma(3,1))); - fg.add(BetweenFactor(0, 1, Pose2(1,0,M_PI/2), sharedSigma(3,1))); - fg.add(BetweenFactor(1, 2, Pose2(1,0,M_PI/2), sharedSigma(3,1))); + fg.add(PriorFactor(0, Pose2(0,0,0), noiseModel::Isotropic::Sigma(3,1))); + fg.add(BetweenFactor(0, 1, Pose2(1,0,M_PI/2), noiseModel::Isotropic::Sigma(3,1))); + fg.add(BetweenFactor(1, 2, Pose2(1,0,M_PI/2), noiseModel::Isotropic::Sigma(3,1))); Values init; init.insert(0, Pose2(3,4,-M_PI)); diff --git a/tests/testOccupancyGrid.cpp b/tests/testOccupancyGrid.cpp new file mode 100644 index 000000000..86678cc12 --- /dev/null +++ b/tests/testOccupancyGrid.cpp @@ -0,0 +1,332 @@ +/** + * @file testOccupancyGrid.cpp + * @date May 14, 2012 + * @author Brian Peasley + * @author Frank Dellaert + */ + + +#include +#include +#include +#include +//#include // FIXME: does not exist in boost 1.46 +#include // Old header - should still exist + +#include +#include +#include + +using namespace std; +using namespace gtsam; + + +/** + * Laser Factor + * @brief factor that encodes a laser measurements likelihood. + */ + +class LaserFactor : public DiscreteFactor{ +private: + vector m_cells; ///cells in which laser passes through + +public: + + ///constructor + LaserFactor(const vector &cells) : m_cells(cells) {} + + /** + * Find value for given assignment of values to variables + * return 1000 if any of the non-last cell is occupied and 1 otherwise + * Values contains all occupancy values (0 or 1) + */ + virtual double operator()(const Values &vals) const{ + + // loops through all but the last cell and checks that they are all 0. Otherwise return 1000. + for(Index i = 0; i < m_cells.size() - 1; i++){ + if(vals.at(m_cells[i]) == 1) + return 1000; + } + + // check if the last cell hit by the laser is 1. return 900 otherwise. + if(vals.at(m_cells[m_cells.size() - 1]) == 0) + return 900; + + return 1; + + } + + /// Multiply in a DecisionTreeFactor and return the result as DecisionTreeFactor + virtual DecisionTreeFactor operator*(const DecisionTreeFactor&) const{ + throw runtime_error("operator * not implemented"); + } + + virtual DecisionTreeFactor toDecisionTreeFactor() const{ + throw runtime_error("DecisionTreeFactor toDecisionTreeFactor not implemented"); + } +}; + +/** + * OccupancyGrid Class + * An occupancy grid is just a factor graph. + * Every cell in the occupancy grid is a variable in the factor graph. + * Measurements will create factors, as well as the prior. + */ +class OccupancyGrid : public DiscreteFactorGraph { +private: + size_t width_; //number of cells wide the grid is + size_t height_; //number of cells tall the grid is + double res_; //the resolution at which the grid is created + + vector cells_; //list of keys of all cells in the grid + vector laser_indices_; //indices of the laser factor in factors_ + + +public: + + size_t width() const { + return width_; + } + size_t height() const { + return height_; + } + // should we just not typedef Values Occupancy; ? + class Occupancy : public Values { + private: + public: + }; + + + typedef std::vector Marginals; + ///constructor + ///Creates a 2d grid of cells with the origin in the center of the grid + OccupancyGrid(double width, double height, double resolution){ + width_ = width/resolution; + height_ = height/resolution; + res_ = resolution; + + for(Index i = 0; i < cellCount(); i++) + cells_.push_back(i); + } + + /// Returns an empty occupancy grid of size width_ x height_ + Occupancy emptyOccupancy(){ + Occupancy occupancy; //mapping from Index to value (0 or 1) + for(size_t i = 0; i < cellCount(); i++) + occupancy.insert(pair((Index)i,0)); + + return occupancy; + } + + ///add a prior + void addPosePrior(Index cell, double prior){ + size_t numStates = 2; + DiscreteKey key(cell, numStates); + + //add a factor + vector table(2); + table[0] = 1-prior; + table[1] = prior; + add(key, table); + } + + ///add a laser measurement + void addLaser(const Pose2 &pose, double range){ + //ray trace from pose to range t//a >= 1 accept new stateo find all cells the laser passes through + double x = pose.x(); //start position of the laser + double y = pose.y(); + double step = res_/8.0; //amount to step in each iteration of laser traversal + + Index key; + vector cells; //list of keys of cells hit by the laser + + //traverse laser + for(double i = 0; i < range; i += step){ + //get point on laser + x = pose.x() + i*cos(pose.theta()); + y = pose.y() + i*sin(pose.theta()); + + //printf("%lf %lf\n", x, y); + //get the key of the cell that holds point (x,y) + key = keyLookup(x,y); + + //add cell to list of cells if it is new + if(i == 0 || key != cells[cells.size()-1]) + cells.push_back(key); + } + +// for(size_t i = 0; i < cells.size(); i++) +// printf("%ld ", cells[i]); +// printf("\n"); + + //add a factor that connects all those cells + laser_indices_.push_back(factors_.size()); + push_back(boost::make_shared(cells)); + + } + + /// returns the number of cells in the grid + size_t cellCount() const { + return width_*height_; + } + + /// returns the key of the cell in which point (x,y) lies. + Index keyLookup(double x, double y) const { + //move (x,y) to the nearest resolution + x *= (1.0/res_); + y *= (1.0/res_); + + //round to nearest integer + x = (double)((int)x); + y = (double)((int)y); + + //determine index + x += width_/2; + y = height_/2 - y; + + //bounds checking + size_t index = y*width_ + x; + index = index >= width_*height_ ? -1 : index; + + return cells_[index]; + } + + /** + * @brief Computes the value of a laser factor + * @param index defines which laser is to be used + * @param occupancy defines the grid which the laser will be evaulated with + * @ret a double value that is the value of the specified laser factor for the grid + */ + double laserFactorValue(Index index, const Occupancy &occupancy) const{ + return (*factors_[ laser_indices_[index] ])(occupancy); + } + + /// returns the sum of the laser factors for the current state of the grid + double operator()(const Occupancy &occupancy) const { + double value = 0; + + // loop over all laser factors in the graph + //printf("%ld\n", (*this).size()); + + for(Index i = 0; i < laser_indices_.size(); i++){ + value += laserFactorValue(i, occupancy); + } + + return value; + } + + /** + * @brief Run a metropolis sampler. + * @param iterations defines the number of iterations to run. + * @return vector of marginal probabilities. + */ + Marginals runMetropolis(size_t iterations){ + Occupancy occupancy = emptyOccupancy(); + + size_t size = cellCount(); + Marginals marginals(size); + + // NOTE: using older interface for boost.random due to interface changes after boost 1.46 + boost::mt19937 rng; + boost::uniform_int random_cell(0,size-1); + + // run Metropolis for the requested number of operations + // compute initial probability of occupancy grid, P(x_t) + + double Px = (*this)(occupancy); + + for(size_t it = 0; it < marginals.size(); it++) + marginals[it] = 0; + + for(size_t it = 0; it < iterations; it++){ + //choose a random cell + Index x = random_cell(rng); + //printf("%ld:",x); + //flip the state of a random cell, x + occupancy[x] = 1 - occupancy[x]; + + //compute probability of new occupancy grid, P(x') + //by summing over all LaserFactor::operator() + double Px_prime = (*this)(occupancy); + + //occupancy.print(); + //calculate acceptance ratio, a + double a = Px_prime/Px; + + //if a <= 1 otherwise accept with probability a + //if we accept the new state P(x_t) = P(x') + // printf(" %.3lf %.3lf\t", Px, Px_prime); + if(a <= 1){ + Px = Px_prime; + //printf("\taccept\n"); + } + else{ + occupancy[x] = 1 - occupancy[x]; + // printf("\treject\n"); + } + + //increment the number of iterations each cell has been on + for(size_t i = 0; i < size; i++){ + if(occupancy[i] == 1) + marginals[i]++; + } + } + + //compute the marginals + for(size_t it = 0; it < size; it++) + marginals[it] /= iterations; + + return marginals; + } + +}; + +/* ************************************************************************* */ +TEST_UNSAFE( OccupancyGrid, Test1) { + //Build a small grid and test optimization + + //Build small grid + double width = 3; //meters + double height = 2; //meters + double resolution = 0.5; //meters + OccupancyGrid occupancyGrid(width, height, resolution); //default center to middle + + //Add measurements + Pose2 pose(0,0,0); + double range = 1; + + occupancyGrid.addPosePrior(0, 0.7); + EXPECT_LONGS_EQUAL(1, occupancyGrid.size()); + + occupancyGrid.addLaser(pose, range); + EXPECT_LONGS_EQUAL(2, occupancyGrid.size()); + + OccupancyGrid::Occupancy occupancy = occupancyGrid.emptyOccupancy(); + EXPECT_LONGS_EQUAL(900, occupancyGrid.laserFactorValue(0,occupancy)); + + + occupancy[16] = 1; + EXPECT_LONGS_EQUAL(1, occupancyGrid.laserFactorValue(0,occupancy)); + + occupancy[15] = 1; + EXPECT_LONGS_EQUAL(1000, occupancyGrid.laserFactorValue(0,occupancy)); + + occupancy[16] = 0; + EXPECT_LONGS_EQUAL(1000, occupancyGrid.laserFactorValue(0,occupancy)); + + + //run MCMC + OccupancyGrid::Marginals occupancyMarginals = occupancyGrid.runMetropolis(50000); + EXPECT_LONGS_EQUAL( (width*height)/pow(resolution,2), occupancyMarginals.size()); + + + +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/tests/testPose2SLAMwSPCG.cpp b/tests/testPose2SLAMwSPCG.cpp deleted file mode 100644 index 439228c79..000000000 --- a/tests/testPose2SLAMwSPCG.cpp +++ /dev/null @@ -1,72 +0,0 @@ -/** - * @file testPose2SLAMwSPCG - * @author Alex Cunningham - */ - -#include - -#include -#include - -using namespace std; -using namespace gtsam; -using namespace pose2SLAM; - -const double tol = 1e-5; - -/* ************************************************************************* */ -TEST(testPose2SLAMwSPCG, example1) { - - /* 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 graph; - 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) ; - - Values initial; - 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)); - - Values expected; - expected.insert(x1, Pose2(0.0, 0.0, 0.0)); - expected.insert(x2, Pose2(0.0, 2.0, 0.0)); - expected.insert(x3, Pose2(0.0, 4.0, 0.0)); - expected.insert(x4, Pose2(2.0, 0.0, 0.0)); - expected.insert(x5, Pose2(2.0, 2.0, 0.0)); - expected.insert(x6, Pose2(2.0, 4.0, 0.0)); - expected.insert(x7, Pose2(4.0, 0.0, 0.0 )); - expected.insert(x8, Pose2(4.0, 2.0, 0.0)); - expected.insert(x9, Pose2(4.0, 4.0, 0.0)); - - Values actual = optimizeSPCG(graph, initial); - - EXPECT(assert_equal(expected, actual, tol)); -} - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ diff --git a/tests/testRot3Optimization.cpp b/tests/testRot3Optimization.cpp index df2471933..89b621ed2 100644 --- a/tests/testRot3Optimization.cpp +++ b/tests/testRot3Optimization.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -40,11 +41,11 @@ TEST(Rot3, optimize) { Values truth; Values initial; Graph fg; - fg.add(Prior(Symbol('r',0), Rot3(), sharedSigma(3, 0.01))); + fg.add(Prior(Symbol('r',0), Rot3(), noiseModel::Isotropic::Sigma(3, 0.01))); for(int j=0; j<6; ++j) { truth.insert(Symbol('r',j), Rot3::Rz(M_PI/3.0 * double(j))); initial.insert(Symbol('r',j), Rot3::Rz(M_PI/3.0 * double(j) + 0.1 * double(j%2))); - fg.add(Between(Symbol('r',j), Symbol('r',(j+1)%6), Rot3::Rz(M_PI/3.0), sharedSigma(3, 0.01))); + fg.add(Between(Symbol('r',j), Symbol('r',(j+1)%6), Rot3::Rz(M_PI/3.0), noiseModel::Isotropic::Sigma(3, 0.01))); } Values final = GaussNewtonOptimizer(fg, initial).optimize(); diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp new file mode 100644 index 000000000..4f9664e20 --- /dev/null +++ b/tests/testSerializationSLAM.cpp @@ -0,0 +1,594 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSerializationSLAM.cpp + * @brief test serialization + * @author Richard Roberts + * @date Feb 7, 2012 + */ + +#include +//#include +#include +#include +#include +//#include +#include +//#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; +using namespace gtsam::serializationTestHelpers; + +// Creating as many permutations of factors as possible +typedef PriorFactor PriorFactorLieVector; +typedef PriorFactor PriorFactorLieMatrix; +typedef PriorFactor PriorFactorPoint2; +typedef PriorFactor PriorFactorStereoPoint2; +typedef PriorFactor PriorFactorPoint3; +typedef PriorFactor PriorFactorRot2; +typedef PriorFactor PriorFactorRot3; +typedef PriorFactor PriorFactorPose2; +typedef PriorFactor PriorFactorPose3; +typedef PriorFactor PriorFactorCal3_S2; +typedef PriorFactor PriorFactorCal3DS2; +typedef PriorFactor PriorFactorCalibratedCamera; +typedef PriorFactor PriorFactorSimpleCamera; +typedef PriorFactor PriorFactorStereoCamera; + +typedef BetweenFactor BetweenFactorLieVector; +typedef BetweenFactor BetweenFactorLieMatrix; +typedef BetweenFactor BetweenFactorPoint2; +typedef BetweenFactor BetweenFactorPoint3; +typedef BetweenFactor BetweenFactorRot2; +typedef BetweenFactor BetweenFactorRot3; +typedef BetweenFactor BetweenFactorPose2; +typedef BetweenFactor BetweenFactorPose3; + +typedef NonlinearEquality NonlinearEqualityLieVector; +typedef NonlinearEquality NonlinearEqualityLieMatrix; +typedef NonlinearEquality NonlinearEqualityPoint2; +typedef NonlinearEquality NonlinearEqualityStereoPoint2; +typedef NonlinearEquality NonlinearEqualityPoint3; +typedef NonlinearEquality NonlinearEqualityRot2; +typedef NonlinearEquality NonlinearEqualityRot3; +typedef NonlinearEquality NonlinearEqualityPose2; +typedef NonlinearEquality NonlinearEqualityPose3; +typedef NonlinearEquality NonlinearEqualityCal3_S2; +typedef NonlinearEquality NonlinearEqualityCal3DS2; +typedef NonlinearEquality NonlinearEqualityCalibratedCamera; +typedef NonlinearEquality NonlinearEqualitySimpleCamera; +typedef NonlinearEquality NonlinearEqualityStereoCamera; + +typedef RangeFactor RangeFactorPosePoint2; +typedef RangeFactor RangeFactorPosePoint3; +typedef RangeFactor RangeFactorPose2; +typedef RangeFactor RangeFactorPose3; +typedef RangeFactor RangeFactorCalibratedCameraPoint; +typedef RangeFactor RangeFactorSimpleCameraPoint; +typedef RangeFactor RangeFactorCalibratedCamera; +typedef RangeFactor RangeFactorSimpleCamera; + +typedef BearingFactor BearingFactor2D; +typedef BearingFactor BearingFactor3D; + +typedef BearingRangeFactor BearingRangeFactor2D; +typedef BearingRangeFactor BearingRangeFactor3D; + +typedef GenericProjectionFactor GenericProjectionFactorCal3_S2; +typedef GenericProjectionFactor GenericProjectionFactorCal3DS2; + +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; +//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; + +typedef gtsam::GeneralSFMFactor2 GeneralSFMFactor2Cal3_S2; + +typedef gtsam::GenericStereoFactor GenericStereoFactor3D; + + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + + +/* Create GUIDs for Noisemodels */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); + +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +/* Create GUIDs for geometry */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT(gtsam::LieVector); +BOOST_CLASS_EXPORT(gtsam::LieMatrix); +BOOST_CLASS_EXPORT(gtsam::Point2); +BOOST_CLASS_EXPORT(gtsam::StereoPoint2); +BOOST_CLASS_EXPORT(gtsam::Point3); +BOOST_CLASS_EXPORT(gtsam::Rot2); +BOOST_CLASS_EXPORT(gtsam::Rot3); +BOOST_CLASS_EXPORT(gtsam::Pose2); +BOOST_CLASS_EXPORT(gtsam::Pose3); +BOOST_CLASS_EXPORT(gtsam::Cal3_S2); +BOOST_CLASS_EXPORT(gtsam::Cal3DS2); +BOOST_CLASS_EXPORT(gtsam::Cal3_S2Stereo); +BOOST_CLASS_EXPORT(gtsam::CalibratedCamera); +BOOST_CLASS_EXPORT(gtsam::SimpleCamera); +BOOST_CLASS_EXPORT(gtsam::StereoCamera); + + +/* Create GUIDs for factors */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); +BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor"); + +BOOST_CLASS_EXPORT_GUID(PriorFactorLieVector, "gtsam::PriorFactorLieVector"); +BOOST_CLASS_EXPORT_GUID(PriorFactorLieMatrix, "gtsam::PriorFactorLieMatrix"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorRot2, "gtsam::PriorFactorRot2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorRot3, "gtsam::PriorFactorRot3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera"); +BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera"); + +BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorLieMatrix, "gtsam::BetweenFactorLieMatrix"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3"); + +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieVector, "gtsam::NonlinearEqualityLieVector"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieMatrix, "gtsam::NonlinearEqualityLieMatrix"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot2, "gtsam::NonlinearEqualityRot2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot3, "gtsam::NonlinearEqualityRot3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose2, "gtsam::NonlinearEqualityPose2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera"); + +BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint2, "gtsam::RangeFactorPosePoint2"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint3, "gtsam::RangeFactorPosePoint3"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3"); +BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint"); +BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint"); +BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera"); + +BOOST_CLASS_EXPORT_GUID(BearingFactor2D, "gtsam::BearingFactor2D"); + +BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D"); + +BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2"); +BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2"); + +BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2"); +//BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2"); + +BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2"); + +BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D"); + + +/* ************************************************************************* */ +TEST (Serialization, smallExample_linear) { + using namespace example; + + Ordering ordering; ordering += X(1),X(2),L(1); + GaussianFactorGraph fg = createGaussianFactorGraph(ordering); + EXPECT(equalsObj(ordering)); + EXPECT(equalsXML(ordering)); + + EXPECT(equalsObj(fg)); + EXPECT(equalsXML(fg)); + + GaussianBayesNet cbn = createSmallGaussianBayesNet(); + EXPECT(equalsObj(cbn)); + EXPECT(equalsXML(cbn)); +} + +/* ************************************************************************* */ +TEST (Serialization, gaussianISAM) { + using namespace example; + Ordering ordering; + GaussianFactorGraph smoother; + boost::tie(smoother, ordering) = createSmoother(7); + BayesTree bayesTree = *GaussianMultifrontalSolver(smoother).eliminate(); + GaussianISAM isam(bayesTree); + + EXPECT(equalsObj(isam)); + EXPECT(equalsXML(isam)); +} + +/* ************************************************************************* */ +/* Create GUIDs for factors in simulated2D */ +BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" ) +BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" ) +BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement") + +/* ************************************************************************* */ +TEST (Serialization, smallExample_nonlinear) { + using namespace example; + NonlinearFactorGraph nfg = createNonlinearFactorGraph(); + Values c1 = createValues(); + EXPECT(equalsObj(nfg)); + EXPECT(equalsXML(nfg)); + + EXPECT(equalsObj(c1)); + EXPECT(equalsXML(c1)); +} + +/* ************************************************************************* */ +TEST (Serialization, factors) { + + LieVector lieVector(4, 1.0, 2.0, 3.0, 4.0); + LieMatrix lieMatrix(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0); + Point2 point2(1.0, 2.0); + StereoPoint2 stereoPoint2(1.0, 2.0, 3.0); + Point3 point3(1.0, 2.0, 3.0); + Rot2 rot2(1.0); + Rot3 rot3(Rot3::RzRyRx(1.0, 2.0, 3.0)); + Pose2 pose2(rot2, point2); + Pose3 pose3(rot3, point3); + Cal3_S2 cal3_s2(1.0, 2.0, 3.0, 4.0, 5.0); + Cal3DS2 cal3ds2(1.0, 2.0, 3.0, 4.0, 5.0,6.0, 7.0, 8.0, 9.0); + Cal3_S2Stereo cal3_s2stereo(1.0, 2.0, 3.0, 4.0, 5.0, 1.0); + CalibratedCamera calibratedCamera(pose3); + SimpleCamera simpleCamera(pose3, cal3_s2); + StereoCamera stereoCamera(pose3, boost::make_shared(cal3_s2stereo)); + + + Symbol a01('a',1), a02('a',2), a03('a',3), a04('a',4), a05('a',5), + a06('a',6), a07('a',7), a08('a',8), a09('a',9), a10('a',10), + a11('a',11), a12('a',12), a13('a',13), a14('a',14), a15('a',15); + Symbol b01('b',1), b02('b',2), b03('b',3), b04('b',4), b05('b',5), + b06('b',6), b07('b',7), b08('b',8), b09('b',9), b10('b',10), + b11('b',11), b12('b',12), b13('b',13), b14('b',14), b15('b',15); + + Values values; + values.insert(a01, lieVector); + values.insert(a02, lieMatrix); + values.insert(a03, point2); + values.insert(a04, stereoPoint2); + values.insert(a05, point3); + values.insert(a06, rot2); + values.insert(a07, rot3); + values.insert(a08, pose2); + values.insert(a09, pose3); + values.insert(a10, cal3_s2); + values.insert(a11, cal3ds2); + values.insert(a12, calibratedCamera); + values.insert(a13, simpleCamera); + values.insert(a14, stereoCamera); + + + SharedNoiseModel model1 = noiseModel::Isotropic::Sigma(1, 0.3); + SharedNoiseModel model2 = noiseModel::Isotropic::Sigma(2, 0.3); + SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.3); + SharedNoiseModel model4 = noiseModel::Isotropic::Sigma(4, 0.3); + SharedNoiseModel model5 = noiseModel::Isotropic::Sigma(5, 0.3); + SharedNoiseModel model6 = noiseModel::Isotropic::Sigma(6, 0.3); + SharedNoiseModel model9 = noiseModel::Isotropic::Sigma(9, 0.3); + SharedNoiseModel model11 = noiseModel::Isotropic::Sigma(11, 0.3); + + + + PriorFactorLieVector priorFactorLieVector(a01, lieVector, model4); + PriorFactorLieMatrix priorFactorLieMatrix(a02, lieMatrix, model6); + PriorFactorPoint2 priorFactorPoint2(a03, point2, model2); + PriorFactorStereoPoint2 priorFactorStereoPoint2(a04, stereoPoint2, model3); + PriorFactorPoint3 priorFactorPoint3(a05, point3, model3); + PriorFactorRot2 priorFactorRot2(a06, rot2, model1); + PriorFactorRot3 priorFactorRot3(a07, rot3, model3); + PriorFactorPose2 priorFactorPose2(a08, pose2, model3); + PriorFactorPose3 priorFactorPose3(a09, pose3, model6); + PriorFactorCal3_S2 priorFactorCal3_S2(a10, cal3_s2, model5); + PriorFactorCal3DS2 priorFactorCal3DS2(a11, cal3ds2, model9); + PriorFactorCalibratedCamera priorFactorCalibratedCamera(a12, calibratedCamera, model6); + PriorFactorSimpleCamera priorFactorSimpleCamera(a13, simpleCamera, model11); + PriorFactorStereoCamera priorFactorStereoCamera(a14, stereoCamera, model11); + + BetweenFactorLieVector betweenFactorLieVector(a01, b01, lieVector, model4); + BetweenFactorLieMatrix betweenFactorLieMatrix(a02, b02, lieMatrix, model6); + BetweenFactorPoint2 betweenFactorPoint2(a03, b03, point2, model2); + BetweenFactorPoint3 betweenFactorPoint3(a05, b05, point3, model3); + BetweenFactorRot2 betweenFactorRot2(a06, b06, rot2, model1); + BetweenFactorRot3 betweenFactorRot3(a07, b07, rot3, model3); + BetweenFactorPose2 betweenFactorPose2(a08, b08, pose2, model3); + BetweenFactorPose3 betweenFactorPose3(a09, b09, pose3, model6); + + NonlinearEqualityLieVector nonlinearEqualityLieVector(a01, lieVector); + NonlinearEqualityLieMatrix nonlinearEqualityLieMatrix(a02, lieMatrix); + NonlinearEqualityPoint2 nonlinearEqualityPoint2(a03, point2); + NonlinearEqualityStereoPoint2 nonlinearEqualityStereoPoint2(a04, stereoPoint2); + NonlinearEqualityPoint3 nonlinearEqualityPoint3(a05, point3); + NonlinearEqualityRot2 nonlinearEqualityRot2(a06, rot2); + NonlinearEqualityRot3 nonlinearEqualityRot3(a07, rot3); + NonlinearEqualityPose2 nonlinearEqualityPose2(a08, pose2); + NonlinearEqualityPose3 nonlinearEqualityPose3(a09, pose3); + NonlinearEqualityCal3_S2 nonlinearEqualityCal3_S2(a10, cal3_s2); + NonlinearEqualityCal3DS2 nonlinearEqualityCal3DS2(a11, cal3ds2); + NonlinearEqualityCalibratedCamera nonlinearEqualityCalibratedCamera(a12, calibratedCamera); + NonlinearEqualitySimpleCamera nonlinearEqualitySimpleCamera(a13, simpleCamera); + NonlinearEqualityStereoCamera nonlinearEqualityStereoCamera(a14, stereoCamera); + + RangeFactorPosePoint2 rangeFactorPosePoint2(a08, a03, 2.0, model1); + RangeFactorPosePoint3 rangeFactorPosePoint3(a09, a05, 2.0, model1); + RangeFactorPose2 rangeFactorPose2(a08, b08, 2.0, model1); + RangeFactorPose3 rangeFactorPose3(a09, b09, 2.0, model1); + RangeFactorCalibratedCameraPoint rangeFactorCalibratedCameraPoint(a12, a05, 2.0, model1); + RangeFactorSimpleCameraPoint rangeFactorSimpleCameraPoint(a13, a05, 2.0, model1); + RangeFactorCalibratedCamera rangeFactorCalibratedCamera(a12, b12, 2.0, model1); + RangeFactorSimpleCamera rangeFactorSimpleCamera(a13, b13, 2.0, model1); + + BearingFactor2D bearingFactor2D(a08, a03, rot2, model1); + + BearingRangeFactor2D bearingRangeFactor2D(a08, a03, rot2, 2.0, model2); + + GenericProjectionFactorCal3_S2 genericProjectionFactorCal3_S2(point2, model2, a09, a05, boost::make_shared(cal3_s2)); + GenericProjectionFactorCal3DS2 genericProjectionFactorCal3DS2(point2, model2, a09, a05, boost::make_shared(cal3ds2)); + + GeneralSFMFactorCal3_S2 generalSFMFactorCal3_S2(point2, model2, a13, a05); + + GeneralSFMFactor2Cal3_S2 generalSFMFactor2Cal3_S2(point2, model2, a09, a05, a10); + + GenericStereoFactor3D genericStereoFactor3D(stereoPoint2, model3, a09, a05, boost::make_shared(cal3_s2stereo)); + + + NonlinearFactorGraph graph; + graph.add(priorFactorLieVector); + graph.add(priorFactorLieMatrix); + graph.add(priorFactorPoint2); + graph.add(priorFactorStereoPoint2); + graph.add(priorFactorPoint3); + graph.add(priorFactorRot2); + graph.add(priorFactorRot3); + graph.add(priorFactorPose2); + graph.add(priorFactorPose3); + graph.add(priorFactorCal3_S2); + graph.add(priorFactorCal3DS2); + graph.add(priorFactorCalibratedCamera); + graph.add(priorFactorSimpleCamera); + graph.add(priorFactorStereoCamera); + + graph.add(betweenFactorLieVector); + graph.add(betweenFactorLieMatrix); + graph.add(betweenFactorPoint2); + graph.add(betweenFactorPoint3); + graph.add(betweenFactorRot2); + graph.add(betweenFactorRot3); + graph.add(betweenFactorPose2); + graph.add(betweenFactorPose3); + + graph.add(nonlinearEqualityLieVector); + graph.add(nonlinearEqualityLieMatrix); + graph.add(nonlinearEqualityPoint2); + graph.add(nonlinearEqualityStereoPoint2); + graph.add(nonlinearEqualityPoint3); + graph.add(nonlinearEqualityRot2); + graph.add(nonlinearEqualityRot3); + graph.add(nonlinearEqualityPose2); + graph.add(nonlinearEqualityPose3); + graph.add(nonlinearEqualityCal3_S2); + graph.add(nonlinearEqualityCal3DS2); + graph.add(nonlinearEqualityCalibratedCamera); + graph.add(nonlinearEqualitySimpleCamera); + graph.add(nonlinearEqualityStereoCamera); + + graph.add(rangeFactorPosePoint2); + graph.add(rangeFactorPosePoint3); + graph.add(rangeFactorPose2); + graph.add(rangeFactorPose3); + graph.add(rangeFactorCalibratedCameraPoint); + graph.add(rangeFactorSimpleCameraPoint); + graph.add(rangeFactorCalibratedCamera); + graph.add(rangeFactorSimpleCamera); + + graph.add(bearingFactor2D); + + graph.add(bearingRangeFactor2D); + + graph.add(genericProjectionFactorCal3_S2); + graph.add(genericProjectionFactorCal3DS2); + + graph.add(generalSFMFactorCal3_S2); + + graph.add(generalSFMFactor2Cal3_S2); + + graph.add(genericStereoFactor3D); + + + // text + EXPECT(equalsObj(a01)); + EXPECT(equalsObj(b02)); + EXPECT(equalsObj(values)); + EXPECT(equalsObj(graph)); + + EXPECT(equalsObj(priorFactorLieVector)); + EXPECT(equalsObj(priorFactorLieMatrix)); + EXPECT(equalsObj(priorFactorPoint2)); + EXPECT(equalsObj(priorFactorStereoPoint2)); + EXPECT(equalsObj(priorFactorPoint3)); + EXPECT(equalsObj(priorFactorRot2)); + EXPECT(equalsObj(priorFactorRot3)); + EXPECT(equalsObj(priorFactorPose2)); + EXPECT(equalsObj(priorFactorPose3)); + EXPECT(equalsObj(priorFactorCal3_S2)); + EXPECT(equalsObj(priorFactorCal3DS2)); + EXPECT(equalsObj(priorFactorCalibratedCamera)); + EXPECT(equalsObj(priorFactorSimpleCamera)); + EXPECT(equalsObj(priorFactorStereoCamera)); + + EXPECT(equalsObj(betweenFactorLieVector)); + EXPECT(equalsObj(betweenFactorLieMatrix)); + EXPECT(equalsObj(betweenFactorPoint2)); + EXPECT(equalsObj(betweenFactorPoint3)); + EXPECT(equalsObj(betweenFactorRot2)); + EXPECT(equalsObj(betweenFactorRot3)); + EXPECT(equalsObj(betweenFactorPose2)); + EXPECT(equalsObj(betweenFactorPose3)); + + EXPECT(equalsObj(nonlinearEqualityLieVector)); + EXPECT(equalsObj(nonlinearEqualityLieMatrix)); + EXPECT(equalsObj(nonlinearEqualityPoint2)); + EXPECT(equalsObj(nonlinearEqualityStereoPoint2)); + EXPECT(equalsObj(nonlinearEqualityPoint3)); + EXPECT(equalsObj(nonlinearEqualityRot2)); + EXPECT(equalsObj(nonlinearEqualityRot3)); + EXPECT(equalsObj(nonlinearEqualityPose2)); + EXPECT(equalsObj(nonlinearEqualityPose3)); + EXPECT(equalsObj(nonlinearEqualityCal3_S2)); + EXPECT(equalsObj(nonlinearEqualityCal3DS2)); + EXPECT(equalsObj(nonlinearEqualityCalibratedCamera)); + EXPECT(equalsObj(nonlinearEqualitySimpleCamera)); + EXPECT(equalsObj(nonlinearEqualityStereoCamera)); + + EXPECT(equalsObj(rangeFactorPosePoint2)); + EXPECT(equalsObj(rangeFactorPosePoint3)); + EXPECT(equalsObj(rangeFactorPose2)); + EXPECT(equalsObj(rangeFactorPose3)); + EXPECT(equalsObj(rangeFactorCalibratedCameraPoint)); + EXPECT(equalsObj(rangeFactorSimpleCameraPoint)); + EXPECT(equalsObj(rangeFactorCalibratedCamera)); + EXPECT(equalsObj(rangeFactorSimpleCamera)); + + EXPECT(equalsObj(bearingFactor2D)); + + EXPECT(equalsObj(bearingRangeFactor2D)); + + EXPECT(equalsObj(genericProjectionFactorCal3_S2)); + EXPECT(equalsObj(genericProjectionFactorCal3DS2)); + + EXPECT(equalsObj(generalSFMFactorCal3_S2)); + + EXPECT(equalsObj(generalSFMFactor2Cal3_S2)); + + EXPECT(equalsObj(genericStereoFactor3D)); + + + // xml + EXPECT(equalsXML(a01)); + EXPECT(equalsXML(b02)); + EXPECT(equalsXML(values)); + EXPECT(equalsXML(graph)); + + EXPECT(equalsXML(priorFactorLieVector)); + EXPECT(equalsXML(priorFactorLieMatrix)); + EXPECT(equalsXML(priorFactorPoint2)); + EXPECT(equalsXML(priorFactorStereoPoint2)); + EXPECT(equalsXML(priorFactorPoint3)); + EXPECT(equalsXML(priorFactorRot2)); + EXPECT(equalsXML(priorFactorRot3)); + EXPECT(equalsXML(priorFactorPose2)); + EXPECT(equalsXML(priorFactorPose3)); + EXPECT(equalsXML(priorFactorCal3_S2)); + EXPECT(equalsXML(priorFactorCal3DS2)); + EXPECT(equalsXML(priorFactorCalibratedCamera)); + EXPECT(equalsXML(priorFactorSimpleCamera)); + EXPECT(equalsXML(priorFactorStereoCamera)); + + EXPECT(equalsXML(betweenFactorLieVector)); + EXPECT(equalsXML(betweenFactorLieMatrix)); + EXPECT(equalsXML(betweenFactorPoint2)); + EXPECT(equalsXML(betweenFactorPoint3)); + EXPECT(equalsXML(betweenFactorRot2)); + EXPECT(equalsXML(betweenFactorRot3)); + EXPECT(equalsXML(betweenFactorPose2)); + EXPECT(equalsXML(betweenFactorPose3)); + + EXPECT(equalsXML(nonlinearEqualityLieVector)); + EXPECT(equalsXML(nonlinearEqualityLieMatrix)); + EXPECT(equalsXML(nonlinearEqualityPoint2)); + EXPECT(equalsXML(nonlinearEqualityStereoPoint2)); + EXPECT(equalsXML(nonlinearEqualityPoint3)); + EXPECT(equalsXML(nonlinearEqualityRot2)); + EXPECT(equalsXML(nonlinearEqualityRot3)); + EXPECT(equalsXML(nonlinearEqualityPose2)); + EXPECT(equalsXML(nonlinearEqualityPose3)); + EXPECT(equalsXML(nonlinearEqualityCal3_S2)); + EXPECT(equalsXML(nonlinearEqualityCal3DS2)); + EXPECT(equalsXML(nonlinearEqualityCalibratedCamera)); + EXPECT(equalsXML(nonlinearEqualitySimpleCamera)); + EXPECT(equalsXML(nonlinearEqualityStereoCamera)); + + EXPECT(equalsXML(rangeFactorPosePoint2)); + EXPECT(equalsXML(rangeFactorPosePoint3)); + EXPECT(equalsXML(rangeFactorPose2)); + EXPECT(equalsXML(rangeFactorPose3)); + EXPECT(equalsXML(rangeFactorCalibratedCameraPoint)); + EXPECT(equalsXML(rangeFactorSimpleCameraPoint)); + EXPECT(equalsXML(rangeFactorCalibratedCamera)); + EXPECT(equalsXML(rangeFactorSimpleCamera)); + + EXPECT(equalsXML(bearingFactor2D)); + + EXPECT(equalsXML(bearingRangeFactor2D)); + + EXPECT(equalsXML(genericProjectionFactorCal3_S2)); + EXPECT(equalsXML(genericProjectionFactorCal3DS2)); + + EXPECT(equalsXML(generalSFMFactorCal3_S2)); + + EXPECT(equalsXML(generalSFMFactor2Cal3_S2)); + + EXPECT(equalsXML(genericStereoFactor3D)); +} + + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testSimulated2D.cpp b/tests/testSimulated2D.cpp similarity index 92% rename from gtsam/slam/tests/testSimulated2D.cpp rename to tests/testSimulated2D.cpp index 3513927a7..165177a56 100644 --- a/gtsam/slam/tests/testSimulated2D.cpp +++ b/tests/testSimulated2D.cpp @@ -21,7 +21,7 @@ #include #include -#include +#include using namespace std; using namespace gtsam; @@ -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/tests/testSimulated2DOriented.cpp similarity index 82% rename from gtsam/slam/tests/testSimulated2DOriented.cpp rename to tests/testSimulated2DOriented.cpp index 64844cb2a..bce932235 100644 --- a/gtsam/slam/tests/testSimulated2DOriented.cpp +++ b/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 ) @@ -54,12 +58,12 @@ TEST( simulated2DOriented, Dprior ) 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)); + SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(3, 1., 1., 1.)); + 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_unstable/slam/tests/testSimulated3D.cpp b/tests/testSimulated3D.cpp similarity index 89% rename from gtsam_unstable/slam/tests/testSimulated3D.cpp rename to tests/testSimulated3D.cpp index 50171bc76..be9548a8e 100644 --- a/gtsam_unstable/slam/tests/testSimulated3D.cpp +++ b/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/testSubgraphPreconditioner.cpp b/tests/testSubgraphPreconditioner.cpp new file mode 100644 index 000000000..39c5e2b70 --- /dev/null +++ b/tests/testSubgraphPreconditioner.cpp @@ -0,0 +1,222 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSubgraphConditioner.cpp + * @brief Unit tests for SubgraphPreconditioner + * @author Frank Dellaert + **/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +using namespace boost::assign; + +using namespace std; +using namespace gtsam; +using namespace example; + +// define keys +// Create key for simulated planar graph +Symbol key(int x, int y) { + return symbol_shorthand::X(1000*x+y); +} + +/* ************************************************************************* */ +TEST( SubgraphPreconditioner, planarOrdering ) { + // Check canonical ordering + Ordering expected, ordering = planarOrdering(3); + expected += + key(3, 3), key(2, 3), key(1, 3), + key(3, 2), key(2, 2), key(1, 2), + key(3, 1), key(2, 1), key(1, 1); + CHECK(assert_equal(expected,ordering)); +} + +/* ************************************************************************* */ +/** unnormalized error */ +static double error(const GaussianFactorGraph& fg, const VectorValues& x) { + double total_error = 0.; + BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, fg) + total_error += factor->error(x); + return total_error; +} + +/* ************************************************************************* */ +TEST( SubgraphPreconditioner, planarGraph ) + { + // Check planar graph construction + GaussianFactorGraph A; + VectorValues xtrue; + boost::tie(A, xtrue) = planarGraph(3); + LONGS_EQUAL(13,A.size()); + LONGS_EQUAL(9,xtrue.size()); + DOUBLES_EQUAL(0,error(A,xtrue),1e-9); // check zero error for xtrue + + // Check that xtrue is optimal + GaussianBayesNet::shared_ptr R1 = GaussianSequentialSolver(A).eliminate(); + VectorValues actual = optimize(*R1); + CHECK(assert_equal(xtrue,actual)); +} + +/* ************************************************************************* */ +TEST( SubgraphPreconditioner, splitOffPlanarTree ) +{ + // Build a planar graph + GaussianFactorGraph A; + VectorValues xtrue; + boost::tie(A, xtrue) = planarGraph(3); + + // Get the spanning tree and constraints, and check their sizes + GaussianFactorGraph T, C; + boost::tie(T, C) = splitOffPlanarTree(3, A); + LONGS_EQUAL(9,T.size()); + LONGS_EQUAL(4,C.size()); + + // Check that the tree can be solved to give the ground xtrue + GaussianBayesNet::shared_ptr R1 = GaussianSequentialSolver(T).eliminate(); + VectorValues xbar = optimize(*R1); + CHECK(assert_equal(xtrue,xbar)); +} + +/* ************************************************************************* */ + +TEST( SubgraphPreconditioner, system ) +{ + // Build a planar graph + GaussianFactorGraph Ab; + VectorValues xtrue; + size_t N = 3; + boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b + + // Get the spanning tree and corresponding ordering + GaussianFactorGraph Ab1_, Ab2_; // A1*x-b1 and A2*x-b2 + boost::tie(Ab1_, Ab2_) = splitOffPlanarTree(N, Ab); + SubgraphPreconditioner::sharedFG Ab1(new GaussianFactorGraph(Ab1_)); + SubgraphPreconditioner::sharedFG Ab2(new GaussianFactorGraph(Ab2_)); + + // Eliminate the spanning tree to build a prior + SubgraphPreconditioner::sharedBayesNet Rc1 = GaussianSequentialSolver(Ab1_).eliminate(); // R1*x-c1 + VectorValues xbar = optimize(*Rc1); // xbar = inv(R1)*c1 + + // Create Subgraph-preconditioned system + VectorValues::shared_ptr xbarShared(new VectorValues(xbar)); // TODO: horrible + SubgraphPreconditioner system(Ab2, Rc1, xbarShared); + + // Create zero config + VectorValues zeros = VectorValues::Zero(xbar); + + // Set up y0 as all zeros + VectorValues y0 = zeros; + + // y1 = perturbed y0 + VectorValues y1 = zeros; + y1[1] = Vector_(2, 1.0, -1.0); + + // Check corresponding x values + VectorValues expected_x1 = xtrue, x1 = system.x(y1); + expected_x1[1] = Vector_(2, 2.01, 2.99); + expected_x1[0] = Vector_(2, 3.01, 2.99); + CHECK(assert_equal(xtrue, system.x(y0))); + CHECK(assert_equal(expected_x1,system.x(y1))); + + // Check errors + DOUBLES_EQUAL(0,error(Ab,xtrue),1e-9); + DOUBLES_EQUAL(3,error(Ab,x1),1e-9); + DOUBLES_EQUAL(0,error(system,y0),1e-9); + DOUBLES_EQUAL(3,error(system,y1),1e-9); + + // Test gradient in x + VectorValues expected_gx0 = zeros; + VectorValues expected_gx1 = zeros; + CHECK(assert_equal(expected_gx0,gradient(Ab,xtrue))); + expected_gx1[2] = Vector_(2, -100., 100.); + expected_gx1[4] = Vector_(2, -100., 100.); + expected_gx1[1] = Vector_(2, 200., -200.); + expected_gx1[3] = Vector_(2, -100., 100.); + expected_gx1[0] = Vector_(2, 100., -100.); + CHECK(assert_equal(expected_gx1,gradient(Ab,x1))); + + // Test gradient in y + VectorValues expected_gy0 = zeros; + VectorValues expected_gy1 = zeros; + expected_gy1[2] = Vector_(2, 2., -2.); + expected_gy1[4] = Vector_(2, -2., 2.); + expected_gy1[1] = Vector_(2, 3., -3.); + expected_gy1[3] = Vector_(2, -1., 1.); + expected_gy1[0] = Vector_(2, 1., -1.); + CHECK(assert_equal(expected_gy0,gradient(system,y0))); + CHECK(assert_equal(expected_gy1,gradient(system,y1))); + + // Check it numerically for good measure + // TODO use boost::bind(&SubgraphPreconditioner::error,&system,_1) + // Vector numerical_g1 = numericalGradient (error, y1, 0.001); + // Vector expected_g1 = Vector_(18, 0., 0., 0., 0., 2., -2., 0., 0., -2., 2., + // 3., -3., 0., 0., -1., 1., 1., -1.); + // CHECK(assert_equal(expected_g1,numerical_g1)); +} + +/* ************************************************************************* */ +TEST( SubgraphPreconditioner, conjugateGradients ) +{ + // Build a planar graph + GaussianFactorGraph Ab; + VectorValues xtrue; + size_t N = 3; + boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b + + // Get the spanning tree and corresponding ordering + GaussianFactorGraph Ab1_, Ab2_; // A1*x-b1 and A2*x-b2 + boost::tie(Ab1_, Ab2_) = splitOffPlanarTree(N, Ab); + SubgraphPreconditioner::sharedFG Ab1(new GaussianFactorGraph(Ab1_)); + SubgraphPreconditioner::sharedFG Ab2(new GaussianFactorGraph(Ab2_)); + + // Eliminate the spanning tree to build a prior + Ordering ordering = planarOrdering(N); + SubgraphPreconditioner::sharedBayesNet Rc1 = GaussianSequentialSolver(Ab1_).eliminate(); // R1*x-c1 + VectorValues xbar = optimize(*Rc1); // xbar = inv(R1)*c1 + + // Create Subgraph-preconditioned system + VectorValues::shared_ptr xbarShared(new VectorValues(xbar)); // TODO: horrible + SubgraphPreconditioner system(Ab2, Rc1, xbarShared); + + // Create zero config y0 and perturbed config y1 + VectorValues y0 = VectorValues::Zero(xbar); + + VectorValues y1 = y0; + y1[1] = Vector_(2, 1.0, -1.0); + VectorValues x1 = system.x(y1); + + // Solve for the remaining constraints using PCG + ConjugateGradientParameters parameters; + VectorValues actual = conjugateGradients(system, y1, parameters); + CHECK(assert_equal(y0,actual)); + + // Compare with non preconditioned version: + VectorValues actual2 = conjugateGradientDescent(Ab, x1, parameters); + CHECK(assert_equal(xtrue,actual2,1e-4)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/tests/testSubgraphSolver.cpp b/tests/testSubgraphSolver.cpp new file mode 100644 index 000000000..700f35261 --- /dev/null +++ b/tests/testSubgraphSolver.cpp @@ -0,0 +1,114 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSubgraphSolver.cpp + * @brief Unit tests for SubgraphSolver + * @author Yong-Dian Jian + **/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +using namespace boost::assign; + +using namespace std; +using namespace gtsam; +using namespace example; + +/* ************************************************************************* */ +/** unnormalized error */ +static double error(const GaussianFactorGraph& fg, const VectorValues& x) { + double total_error = 0.; + BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, fg) + total_error += factor->error(x); + return total_error; +} + + +/* ************************************************************************* */ +TEST( SubgraphSolver, constructor1 ) +{ + // Build a planar graph + GaussianFactorGraph Ab; + VectorValues xtrue; + size_t N = 3; + boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b + + // The first constructor just takes a factor graph (and parameters) + // and it will split the graph into A1 and A2, where A1 is a spanning tree + SubgraphSolverParameters parameters; + SubgraphSolver solver(Ab, parameters); + VectorValues optimized = solver.optimize(); // does PCG optimization + DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5); +} + +/* ************************************************************************* */ +TEST( SubgraphSolver, constructor2 ) +{ + // Build a planar graph + GaussianFactorGraph Ab; + VectorValues xtrue; + size_t N = 3; + boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b + + // Get the spanning tree and corresponding ordering + GaussianFactorGraph Ab1_, Ab2_; // A1*x-b1 and A2*x-b2 + boost::tie(Ab1_, Ab2_) = splitOffPlanarTree(N, Ab); + + // The second constructor takes two factor graphs, + // so the caller can specify the preconditioner (Ab1) and the constraints that are left out (Ab2) + SubgraphSolverParameters parameters; + SubgraphSolver solver(Ab1_, Ab2_, parameters); + VectorValues optimized = solver.optimize(); + DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5); +} + +/* ************************************************************************* */ +TEST( SubgraphSolver, constructor3 ) +{ + // Build a planar graph + GaussianFactorGraph Ab; + VectorValues xtrue; + size_t N = 3; + boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b + + // Get the spanning tree and corresponding ordering + GaussianFactorGraph Ab1_, Ab2_; // A1*x-b1 and A2*x-b2 + boost::tie(Ab1_, Ab2_) = splitOffPlanarTree(N, Ab); + + // The caller solves |A1*x-b1|^2 == |R1*x-c1|^2 via QR factorization, where R1 is square UT + GaussianBayesNet::shared_ptr Rc1 = // + EliminationTree::Create(Ab1_)->eliminate(&EliminateQR); + + // The third constructor allows the caller to pass an already solved preconditioner Rc1_ + // as a Bayes net, in addition to the "loop closing constraints" Ab2, as before + SubgraphSolverParameters parameters; + SubgraphSolver solver(Rc1, Ab2_, parameters); + VectorValues optimized = solver.optimize(); + DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/tests/testSymbolicBayesNetB.cpp b/tests/testSymbolicBayesNetB.cpp index e25cf33ca..58ba3060b 100644 --- a/tests/testSymbolicBayesNetB.cpp +++ b/tests/testSymbolicBayesNetB.cpp @@ -22,27 +22,28 @@ using namespace boost::assign; #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; /* ************************************************************************* */ 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); @@ -53,8 +54,7 @@ TEST( SymbolicBayesNet, constructor ) SymbolicFactorGraph fg(factorGraph); // eliminate it - SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate( - &EliminateSymbolic); + SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate(); CHECK(assert_equal(expected, actual)); } diff --git a/tests/testSymbolicFactorGraphB.cpp b/tests/testSymbolicFactorGraphB.cpp index 9b195e0c1..ddb53b13c 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 + +#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,11 +139,11 @@ 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 - SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate(&EliminateSymbolic); + SymbolicBayesNet actual = *SymbolicSequentialSolver(fg).eliminate(); CHECK(assert_equal(expected,actual)); } diff --git a/tests/timeGaussianFactorGraph.cpp b/tests/timeGaussianFactorGraph.cpp index 3c9d83b3d..f8d76c1dd 100644 --- a/tests/timeGaussianFactorGraph.cpp +++ b/tests/timeGaussianFactorGraph.cpp @@ -19,7 +19,7 @@ #include #include // for operator += in Ordering #include -#include +#include #include using namespace std; @@ -43,10 +43,8 @@ double timeKalmanSmoother(int T) { // Create a planar factor graph and optimize // todo: use COLAMD ordering again (removed when linear baked-in ordering added) double timePlanarSmoother(int N, bool old = true) { - boost::tuple pg = planarGraph(N); + boost::tuple pg = planarGraph(N); GaussianFactorGraph& fg(pg.get<0>()); -// Ordering& ordering(pg.get<1>()); -// VectorValues& config(pg.get<2>()); clock_t start = clock(); GaussianSequentialSolver(fg).optimize(); clock_t end = clock (); @@ -58,10 +56,8 @@ double timePlanarSmoother(int N, bool old = true) { // Create a planar factor graph and eliminate // todo: use COLAMD ordering again (removed when linear baked-in ordering added) double timePlanarSmootherEliminate(int N, bool old = true) { - boost::tuple pg = planarGraph(N); + boost::tuple pg = planarGraph(N); GaussianFactorGraph& fg(pg.get<0>()); -// Ordering& ordering(pg.get<1>()); -// VectorValues& config(pg.get<2>()); clock_t start = clock(); GaussianSequentialSolver(fg).eliminate(); clock_t end = clock (); diff --git a/tests/timeMultifrontalOnDataset.cpp b/tests/timeMultifrontalOnDataset.cpp index 874ccf8bb..5bc34b386 100644 --- a/tests/timeMultifrontalOnDataset.cpp +++ b/tests/timeMultifrontalOnDataset.cpp @@ -44,11 +44,11 @@ int main(int argc, char *argv[]) { else if (argc == 4) nrTrials = strtoul(argv[3], NULL, 10); - pair, shared_ptr > data = load2D(dataset(datasetname)); + pair, boost::shared_ptr > data = load2D(dataset(datasetname)); // Add a prior on the first pose if (soft_prior) - data.first->addPrior(0, Pose2(), sharedSigma(Pose2::Dim(), 0.0005)); + data.first->addPosePrior(0, Pose2(), noiseModel::Isotropic::Sigma(Pose2::Dim(), 0.0005)); else data.first->addPoseConstraint(0, Pose2()); diff --git a/tests/timeSequentialOnDataset.cpp b/tests/timeSequentialOnDataset.cpp index 9e1b986f9..03f33d334 100644 --- a/tests/timeSequentialOnDataset.cpp +++ b/tests/timeSequentialOnDataset.cpp @@ -44,11 +44,11 @@ int main(int argc, char *argv[]) { else if (argc == 4) nrTrials = strtoul(argv[3], NULL, 10); - pair, shared_ptr > data = load2D(dataset(datasetname)); + pair, boost::shared_ptr > data = load2D(dataset(datasetname)); // Add a prior on the first pose if (soft_prior) - data.first->addPrior(0, Pose2(), sharedSigma(Pose2::Dim(), 0.0005)); + data.first->addPosePrior(0, Pose2(), noiseModel::Isotropic::Sigma(Pose2::Dim(), 0.0005)); else data.first->addPoseConstraint(0, Pose2()); diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index ff42b33b1..6956b310b 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -12,6 +12,8 @@ /** * @file Argument.ccp * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #include @@ -30,10 +32,14 @@ string Argument::matlabClass(const string& delim) const { string result; BOOST_FOREACH(const string& ns, namespaces) result += ns + delim; - if (type=="string") + if (type=="string" || type=="unsigned char" || type=="char") return result + "char"; - if (type=="bool" || type=="int" || type=="size_t" || type=="Vector" || type=="Matrix") - return result + "double"; + if (type=="Vector" || type=="Matrix") + return result + "double"; + if (type=="int" || type=="size_t") + return result + "numeric"; + if (type=="bool") + return result + "logical"; return result + type; } @@ -42,11 +48,11 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << " "; string cppType = qualifiedType("::"); - string matlabType = qualifiedType(); + string matlabUniqueType = qualifiedType(); if (is_ptr) // A pointer: emit an "unwrap_shared_ptr" call which returns a pointer - file.oss << "shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< "; + file.oss << "boost::shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< "; else if (is_ref) // A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer file.oss << cppType << "& " << name << " = *unwrap_shared_ptr< "; @@ -59,7 +65,7 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << cppType << " " << name << " = unwrap< "; file.oss << cppType << " >(" << matlabName; - if (is_ptr || is_ref) file.oss << ", \"" << matlabType << "\""; + if (is_ptr || is_ref) file.oss << ", \"ptr_" << matlabUniqueType << "\""; file.oss << ");" << endl; } @@ -122,3 +128,4 @@ void ArgumentList::matlab_unwrap(FileWriter& file, int start) const { } /* ************************************************************************* */ + diff --git a/wrap/Argument.h b/wrap/Argument.h index 000e3079a..4dcf6b563 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -13,6 +13,8 @@ * @file Argument.h * @brief arguments to constructors and methods * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #pragma once @@ -65,6 +67,7 @@ struct ArgumentList: public std::vector { * @param start initial index for input array, set to 1 for method */ void matlab_unwrap(FileWriter& file, int start = 0) const; // MATLAB to C++ + }; } // \namespace wrap diff --git a/wrap/CMakeLists.txt b/wrap/CMakeLists.txt index 8feb5779b..14d9a1f84 100644 --- a/wrap/CMakeLists.txt +++ b/wrap/CMakeLists.txt @@ -1,15 +1,21 @@ # Build/install Wrap +set(WRAP_BOOST_LIBRARIES ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY} ${Boost_THREAD_LIBRARY}) + # Build the executable itself file(GLOB wrap_srcs "*.cpp") -list(REMOVE_ITEM wrap_srcs wrap.cpp) -add_library(wrap_lib STATIC ${wrap_srcs}) +file(GLOB wrap_headers "*.h") +list(REMOVE_ITEM wrap_srcs ${CMAKE_CURRENT_SOURCE_DIR}/wrap.cpp) +add_library(wrap_lib STATIC ${wrap_srcs} ${wrap_headers}) +gtsam_assign_source_folders(${wrap_srcs} ${wrap_headers}) add_executable(wrap wrap.cpp) -target_link_libraries(wrap wrap_lib) +target_link_libraries(wrap wrap_lib ${WRAP_BOOST_LIBRARIES}) -# Install wrap binary +# Install wrap binary and export target if (GTSAM_INSTALL_WRAP) - install(TARGETS wrap DESTINATION bin) + install(TARGETS wrap EXPORT GTSAM-exports DESTINATION bin) + list(APPEND GTSAM_EXPORTED_TARGETS wrap) + set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) endif(GTSAM_INSTALL_WRAP) # Install matlab header @@ -17,56 +23,8 @@ install(FILES matlab.h DESTINATION include/wrap) # Build tests if (GTSAM_BUILD_TESTS) - add_definitions(-DTOPSRCDIR="${CMAKE_SOURCE_DIR}") - set(wrap_local_libs wrap_lib) + set(wrap_local_libs wrap_lib ${WRAP_BOOST_LIBRARIES}) gtsam_add_subdir_tests("wrap" "${wrap_local_libs}" "${wrap_local_libs}" "") endif(GTSAM_BUILD_TESTS) -# Wrap codegen -#usage: wrap mexExtension interfacePath moduleName toolboxPath -# mexExtension : OS/CPU-dependent extension for MEX binaries -# interfacePath : *absolute* path to directory of module interface file -# moduleName : the name of the module, interface file must be called moduleName.h -# toolboxPath : the directory in which to generate the wrappers -# [mexFlags] : extra flags for the mex command -set(mexFlags "-I${Boost_INCLUDE_DIR} -I${CMAKE_INSTALL_PREFIX}/include -I${CMAKE_INSTALL_PREFIX}/include/gtsam -I${CMAKE_INSTALL_PREFIX}/include/gtsam/base -I${CMAKE_INSTALL_PREFIX}/include/gtsam/geometry -I${CMAKE_INSTALL_PREFIX}/include/gtsam/linear -I${CMAKE_INSTALL_PREFIX}/include/gtsam/nonlinear -I${CMAKE_INSTALL_PREFIX}/include/gtsam/slam -L${CMAKE_INSTALL_PREFIX}/lib -lgtsam") -set(toolbox_path ${CMAKE_BINARY_DIR}/wrap/gtsam) -set(moduleName gtsam) - -include(GtsamMatlabWrap) -find_mexextension() - -# get binary path for wrap executable to allow for different build configurations (e.g., ROS) -if (NOT EXECUTABLE_OUTPUT_PATH) - set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) -endif() - -# Code generation command -add_custom_target(wrap_gtsam ALL COMMAND - ${EXECUTABLE_OUTPUT_PATH}/wrap ${GTSAM_MEX_BIN_EXTENSION} ${CMAKE_CURRENT_SOURCE_DIR}/../ ${moduleName} ${toolbox_path} "${mexFlags}" - DEPENDS wrap) - -set(GTSAM_TOOLBOX_INSTALL_PATH ${CMAKE_INSTALL_PREFIX}/borg/toolbox CACHE DOCSTRING "Path to install matlab toolbox") - -if (GTSAM_INSTALL_MATLAB_TOOLBOX) - # Primary toolbox files - message(STATUS "Installing Matlab Toolbox to ${GTSAM_TOOLBOX_INSTALL_PATH}") - install(DIRECTORY DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}) # make an empty folder - # exploit need for trailing slash to specify a full folder, rather than just its contents to copy - install(DIRECTORY ${toolbox_path} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}) - - # Examples - if (GTSAM_INSTALL_MATLAB_EXAMPLES) - 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) - endif (GTSAM_INSTALL_MATLAB_EXAMPLES) - - # Tests - if (GTSAM_INSTALL_MATLAB_TESTS) - message(STATUS "Installing Matlab Toolbox Tests") - file(GLOB matlab_tests "${CMAKE_SOURCE_DIR}/tests/matlab/*.m") - install(FILES ${matlab_tests} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/tests) - endif (GTSAM_INSTALL_MATLAB_TESTS) -endif (GTSAM_INSTALL_MATLAB_TOOLBOX) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 6f6f91b0a..48fbeb6bf 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -1,165 +1,393 @@ -/* ---------------------------------------------------------------------------- - - * 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) + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include +#include +#include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC + +#include +#include + +#include "Class.h" +#include "utilities.h" +#include "Argument.h" + +using namespace std; +using namespace wrap; + +/* ************************************************************************* */ +void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, + const TypeAttributesTable& typeAttributes, + FileWriter& wrapperFile, vector& functionNames) const { + + // Create namespace folders + createNamespaceStructure(namespaces, toolboxPath); + + // open destination classFile + string classFile = toolboxPath; + if(!namespaces.empty()) + classFile += "/+" + wrap::qualifiedName("/+", namespaces); + classFile += "/" + name + ".m"; + FileWriter proxyFile(classFile, verbose_, "%"); + + // get the name of actual matlab object + const string matlabQualName = qualifiedName("."), matlabUniqueName = qualifiedName(), cppName = qualifiedName("::"); + const string matlabBaseName = wrap::qualifiedName(".", qualifiedParent); + const string cppBaseName = wrap::qualifiedName("::", qualifiedParent); + + // emit class proxy code + // we want our class to inherit the handle class for memory purposes + const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; + comment_fragment(proxyFile); + proxyFile.oss << "classdef " << name << " < " << parent << endl; + proxyFile.oss << " properties\n"; + proxyFile.oss << " ptr_" << matlabUniqueName << " = 0\n"; + proxyFile.oss << " end\n"; + proxyFile.oss << " methods\n"; + + // Constructor + proxyFile.oss << " function obj = " << name << "(varargin)\n"; + // Special pointer constructors - one in MATLAB to create an object and + // assign a pointer returned from a C++ function. In turn this MATLAB + // constructor calls a special C++ function that just adds the object to + // its collector. This allows wrapped functions to return objects in + // other wrap modules - to add these to their collectors the pointer is + // passed from one C++ module into matlab then back into the other C++ + // module. + pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, functionNames); + wrapperFile.oss << "\n"; + // Regular constructors + BOOST_FOREACH(ArgumentList a, constructor.args_list) + { + const int id = (int)functionNames.size(); + constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a); + const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, + cppName, matlabUniqueName, cppBaseName, id, a); + wrapperFile.oss << "\n"; + functionNames.push_back(wrapFunctionName); + } + proxyFile.oss << " else\n"; + proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');\n"; + proxyFile.oss << " end\n"; + if(!qualifiedParent.empty()) + proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; + proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n"; + proxyFile.oss << " end\n\n"; + + // Deconstructor + { + const int id = (int)functionNames.size(); + deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id); + proxyFile.oss << "\n"; + const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id); + wrapperFile.oss << "\n"; + functionNames.push_back(functionName); + } + proxyFile.oss << " function display(obj), obj.print(''); end\n %DISPLAY Calls print on the object\n"; + proxyFile.oss << " function disp(obj), obj.display; end\n %DISP Calls print on the object\n"; + + // Methods + BOOST_FOREACH(const Methods::value_type& name_m, methods) { + const Method& m = name_m.second; + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames); + proxyFile.oss << "\n"; + wrapperFile.oss << "\n"; + } + + proxyFile.oss << " end\n"; + proxyFile.oss << "\n"; + proxyFile.oss << " methods(Static = true)\n"; + + // Static methods + BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { + const StaticMethod& m = name_m.second; + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames); + proxyFile.oss << "\n"; + wrapperFile.oss << "\n"; + } + + proxyFile.oss << " end\n"; + proxyFile.oss << "end\n"; + + // Close file + proxyFile.emit(true); +} + +/* ************************************************************************* */ +string Class::qualifiedName(const string& delim) const { + return ::wrap::qualifiedName(delim, namespaces, name); +} + +/* ************************************************************************* */ +void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, vector& functionNames) const { + + const string matlabUniqueName = qualifiedName(), cppName = qualifiedName("::"); + const string baseCppName = wrap::qualifiedName("::", qualifiedParent); + + const int collectorInsertId = (int)functionNames.size(); + const string collectorInsertFunctionName = matlabUniqueName + "_collectorInsertAndMakeBase_" + boost::lexical_cast(collectorInsertId); + functionNames.push_back(collectorInsertFunctionName); + + int upcastFromVoidId; + string upcastFromVoidFunctionName; + if(isVirtual) { + upcastFromVoidId = (int)functionNames.size(); + upcastFromVoidFunctionName = matlabUniqueName + "_upcastFromVoid_" + boost::lexical_cast(upcastFromVoidId); + functionNames.push_back(upcastFromVoidFunctionName); + } + + // MATLAB constructor that assigns pointer to matlab object then calls c++ + // function to add the object to the collector. + if(isVirtual) { + proxyFile.oss << " if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void')))"; + } else { + proxyFile.oss << " if nargin == 2"; + } + proxyFile.oss << " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(" << ptr_constructor_key << ")\n"; + if(isVirtual) { + proxyFile.oss << " if nargin == 2\n"; + proxyFile.oss << " my_ptr = varargin{2};\n"; + proxyFile.oss << " else\n"; + proxyFile.oss << " my_ptr = " << wrapperName << "(" << upcastFromVoidId << ", varargin{2});\n"; + proxyFile.oss << " end\n"; + } else { + proxyFile.oss << " my_ptr = varargin{2};\n"; + } + if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back + proxyFile.oss << " "; + else + proxyFile.oss << " base_ptr = "; + proxyFile.oss << wrapperName << "(" << collectorInsertId << ", my_ptr);\n"; // Call collector insert and get base class ptr + + // C++ function to add pointer from MATLAB to collector. The pointer always + // comes from a C++ return value; this mechanism allows the object to be added + // to a collector in a different wrap module. If this class has a base class, + // a new pointer to the base class is allocated and returned. + wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + wrapperFile.oss << "{\n"; + wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n"; + // Typedef boost::shared_ptr + wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n"; + wrapperFile.oss << "\n"; + // Get self pointer passed in + wrapperFile.oss << " Shared *self = *reinterpret_cast (mxGetData(in[0]));\n"; + // Add to collector + wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; + // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) + if(!qualifiedParent.empty()) { + wrapperFile.oss << "\n"; + wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n"; + wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; + wrapperFile.oss << " *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self);\n"; + } + wrapperFile.oss << "}\n"; + + // If this is a virtual function, C++ function to dynamic upcast it from a + // shared_ptr. This mechanism allows automatic dynamic creation of the + // real underlying derived-most class when a C++ method returns a virtual + // base class. + if(isVirtual) + wrapperFile.oss << + "\n" + "void " << upcastFromVoidFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {\n" + " mexAtExit(&_deleteAllObjects);\n" + " typedef boost::shared_ptr<" << cppName << "> Shared;\n" + " boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0]));\n" + " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n" + " Shared *self = new Shared(boost::static_pointer_cast<" << cppName << ">(*asVoid));\n" + " *reinterpret_cast(mxGetData(out[0])) = self;\n" + "}\n"; +} + +/* ************************************************************************* */ +vector expandArgumentListsTemplate(const vector& argLists, const string& templateArg, const vector& instName, const std::vector& expandedClassNamespace, const string& expandedClassName) { + vector result; + BOOST_FOREACH(const ArgumentList& argList, argLists) { + ArgumentList instArgList; + BOOST_FOREACH(const Argument& arg, argList) { + Argument instArg = arg; + if(arg.type == templateArg) { + instArg.namespaces.assign(instName.begin(), instName.end()-1); + instArg.type = instName.back(); + } else if(arg.type == "This") { + instArg.namespaces.assign(expandedClassNamespace.begin(), expandedClassNamespace.end()); + instArg.type = expandedClassName; + } + instArgList.push_back(instArg); + } + result.push_back(instArgList); + } + return result; +} + +/* ************************************************************************* */ +template +map expandMethodTemplate(const map& methods, const string& templateArg, const vector& instName, const std::vector& expandedClassNamespace, const string& expandedClassName) { + map result; + typedef pair Name_Method; + BOOST_FOREACH(const Name_Method& name_method, methods) { + const METHOD& method = name_method.second; + METHOD instMethod = method; + instMethod.argLists = expandArgumentListsTemplate(method.argLists, templateArg, instName, expandedClassNamespace, expandedClassName); + instMethod.returnVals.clear(); + BOOST_FOREACH(const ReturnValue& retVal, method.returnVals) { + ReturnValue instRetVal = retVal; + if(retVal.type1 == templateArg) { + instRetVal.namespaces1.assign(instName.begin(), instName.end()-1); + instRetVal.type1 = instName.back(); + } else if(retVal.type1 == "This") { + instRetVal.namespaces1.assign(expandedClassNamespace.begin(), expandedClassNamespace.end()); + instRetVal.type1 = expandedClassName; + } + if(retVal.type2 == templateArg) { + instRetVal.namespaces2.assign(instName.begin(), instName.end()-1); + instRetVal.type2 = instName.back(); + } else if(retVal.type1 == "This") { + instRetVal.namespaces2.assign(expandedClassNamespace.begin(), expandedClassNamespace.end()); + instRetVal.type2 = expandedClassName; + } + instMethod.returnVals.push_back(instRetVal); + } + result.insert(make_pair(name_method.first, instMethod)); + } + return result; +} + +/* ************************************************************************* */ +Class expandClassTemplate(const Class& cls, const string& templateArg, const vector& instName, const std::vector& expandedClassNamespace, const string& expandedClassName) { + Class inst; + inst.name = cls.name; + inst.templateArgs = cls.templateArgs; + inst.typedefName = cls.typedefName; + inst.isVirtual = cls.isVirtual; + inst.qualifiedParent = cls.qualifiedParent; + inst.methods = expandMethodTemplate(cls.methods, templateArg, instName, expandedClassNamespace, expandedClassName); + inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName, expandedClassNamespace, expandedClassName); + inst.namespaces = cls.namespaces; + inst.constructor = cls.constructor; + inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName, expandedClassNamespace, expandedClassName); + inst.constructor.name = inst.name; + inst.deconstructor = cls.deconstructor; + inst.deconstructor.name = inst.name; + inst.verbose_ = cls.verbose_; + return inst; +} + +/* ************************************************************************* */ +vector Class::expandTemplate(const string& templateArg, const vector >& instantiations) const { + vector result; + BOOST_FOREACH(const vector& instName, instantiations) { + const string expandedName = name + instName.back(); + Class inst = expandClassTemplate(*this, templateArg, instName, this->namespaces, expandedName); + inst.name = expandedName; + inst.templateArgs.clear(); + inst.typedefName = qualifiedName("::") + "<" + wrap::qualifiedName("::", instName) + ">"; + result.push_back(inst); + } + return result; +} + +/* ************************************************************************* */ +Class Class::expandTemplate(const string& templateArg, const vector& instantiation, const std::vector& expandedClassNamespace, const string& expandedClassName) const { + return expandClassTemplate(*this, templateArg, instantiation, expandedClassNamespace, expandedClassName); +} + +/* ************************************************************************* */ +std::string Class::getTypedef() const { + string result; + BOOST_FOREACH(const string& namesp, namespaces) { + result += ("namespace " + namesp + " { "); + } + result += ("typedef " + typedefName + " " + name + ";"); + for (size_t i = 0; i -#include -#include - -#include - -#include "Class.h" -#include "utilities.h" - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void Class::matlab_proxy(const string& classFile) const { - // open destination classFile - FileWriter file(classFile, verbose_, "%"); - - // get the name of actual matlab object - string matlabName = qualifiedName(); - - // emit class proxy code - // we want our class to inherit the handle class for memory purposes - file.oss << "classdef " << matlabName << " < handle" << endl; - file.oss << " properties" << endl; - file.oss << " self = 0" << endl; - file.oss << " end" << endl; - file.oss << " methods" << endl; - // constructor - file.oss << " function obj = " << matlabName << "(varargin)" << endl; - BOOST_FOREACH(Constructor c, constructors) - c.matlab_proxy_fragment(file,matlabName); - file.oss << " if nargin ~= 13 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl; - file.oss << " end" << endl; - // deconstructor - file.oss << " function delete(obj)" << endl; - file.oss << " delete_" << matlabName << "(obj);" << endl; - file.oss << " end" << endl; - file.oss << " function display(obj), obj.print(''); end" << endl; - file.oss << " function disp(obj), obj.display; end" << endl; - file.oss << " end" << endl; - file.oss << "end" << endl; - - // close file - file.emit(true); -} - -/* ************************************************************************* */ -void Class::matlab_constructors(const string& toolboxPath) const { - BOOST_FOREACH(Constructor c, constructors) { - c.matlab_mfile (toolboxPath, qualifiedName()); - c.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes); - } -} - -/* ************************************************************************* */ -void Class::matlab_deconstructor(const string& toolboxPath) const { - d.matlab_mfile (toolboxPath, qualifiedName()); - d.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes); -} -/* ************************************************************************* */ -void Class::matlab_methods(const string& classPath) const { - string matlabName = qualifiedName(), cppName = qualifiedName("::"); - BOOST_FOREACH(Method m, methods) { - m.matlab_mfile (classPath); - m.matlab_wrapper(classPath, name, cppName, matlabName, using_namespaces, includes); - } -} - -/* ************************************************************************* */ -void Class::matlab_static_methods(const string& toolboxPath) const { - string matlabName = qualifiedName(), cppName = qualifiedName("::"); - BOOST_FOREACH(const StaticMethod& m, static_methods) { - m.matlab_mfile (toolboxPath, qualifiedName()); - m.matlab_wrapper(toolboxPath, name, matlabName, cppName, using_namespaces, includes); - } -} - -/* ************************************************************************* */ -void Class::matlab_make_fragment(FileWriter& file, - const string& toolboxPath, - const string& mexFlags) const { - string mex = "mex " + mexFlags + " "; - string matlabClassName = qualifiedName(); - BOOST_FOREACH(Constructor c, constructors) - file.oss << mex << c.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; - file.oss << mex << d.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; - BOOST_FOREACH(StaticMethod sm, static_methods) - file.oss << mex << matlabClassName + "_" + sm.name << ".cpp" << endl; - file.oss << endl << "cd @" << matlabClassName << endl; - BOOST_FOREACH(Method m, methods) - file.oss << mex << m.name << ".cpp" << endl; - file.oss << endl; -} - -/* ************************************************************************* */ -void Class::makefile_fragment(FileWriter& file) const { -// new_Point2_.$(MEXENDING): new_Point2_.cpp -// $(MEX) $(mex_flags) new_Point2_.cpp -// new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp -// $(MEX) $(mex_flags) new_Point2_dd.cpp -// @Point2/x.$(MEXENDING): @Point2/x.cpp -// $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x -// @Point2/y.$(MEXENDING): @Point2/y.cpp -// $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y -// @Point2/dim.$(MEXENDING): @Point2/dim.cpp -// $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim -// -// Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) - - string matlabName = qualifiedName(); - - // collect names - vector file_names; - BOOST_FOREACH(Constructor c, constructors) { - string file_base = c.matlab_wrapper_name(matlabName); - file_names.push_back(file_base); - } - file_names.push_back(d.matlab_wrapper_name(matlabName)); - BOOST_FOREACH(StaticMethod c, static_methods) { - string file_base = matlabName + "_" + c.name; - file_names.push_back(file_base); - } - BOOST_FOREACH(Method c, methods) { - string file_base = "@" + matlabName + "/" + c.name; - file_names.push_back(file_base); + if (!constructor.args_list.empty()) + proxyFile.oss << "%\n%-------Constructors-------\n"; + BOOST_FOREACH(ArgumentList argList, constructor.args_list) { + string up_name = boost::to_upper_copy(name); + proxyFile.oss << "%" << name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + proxyFile.oss << ")\n"; } - BOOST_FOREACH(const string& file_base, file_names) { - file.oss << file_base << ".$(MEXENDING): " << file_base << ".cpp" << endl; - file.oss << "\t$(MEX) $(mex_flags) " << file_base << ".cpp -output " << file_base << endl; + if (!methods.empty()) + proxyFile.oss << "%\n%-------Methods-------\n"; + BOOST_FOREACH(const Methods::value_type& name_m, methods) { + const Method& m = name_m.second; + BOOST_FOREACH(ArgumentList argList, m.argLists) { + string up_name = boost::to_upper_copy(m.name); + proxyFile.oss << "%" << m.name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + proxyFile.oss << ") : returns " + << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; + } } - // class target - file.oss << "\n" << matlabName << ": "; - BOOST_FOREACH(const string& file_base, file_names) { - file.oss << file_base << ".$(MEXENDING) "; + if (!static_methods.empty()) + proxyFile.oss << "%\n%-------Static Methods-------\n"; + BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { + const StaticMethod& m = name_m.second; + BOOST_FOREACH(ArgumentList argList, m.argLists) { + string up_name = boost::to_upper_copy(m.name); + proxyFile.oss << "%" << m.name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + + proxyFile.oss << ") : returns " + << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; + } } - file.oss << "\n" << endl; -} -/* ************************************************************************* */ -string Class::qualifiedName(const string& delim) const { - string result; - BOOST_FOREACH(const string& ns, namespaces) - result += ns + delim; - return result + name; + proxyFile.oss << "%\n"; } - -/* ************************************************************************* */ +/* ************************************************************************* */ diff --git a/wrap/Class.h b/wrap/Class.h index 875b3203e..0d2736382 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -13,46 +13,60 @@ * @file Class.h * @brief describe the C++ class that is being wrapped * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #pragma once #include +#include #include "Constructor.h" #include "Deconstructor.h" #include "Method.h" #include "StaticMethod.h" +#include "TypeAttributesTable.h" +#include namespace wrap { /// Class has name, constructors, methods struct Class { + typedef std::map Methods; + typedef std::map StaticMethods; + /// Constructor creates an empty class - Class(bool verbose=true) : verbose_(verbose) {} + Class(bool verbose=true) : isVirtual(false), verbose_(verbose) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name - std::vector constructors; ///< Class constructors - std::vector methods; ///< Class methods - std::vector static_methods; ///< Static methods + std::vector templateArgs; ///< Template arguments + std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name] + bool isVirtual; ///< Whether the class is part of a virtual inheritance chain + std::vector qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack + Methods methods; ///< Class methods + StaticMethods static_methods; ///< Static methods std::vector namespaces; ///< Stack of namespaces - std::vector using_namespaces; ///< default namespaces - std::vector includes; ///< header include overrides - Deconstructor d; + Constructor constructor; ///< Class constructors + Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag // And finally MATLAB code is emitted, methods below called by Module::matlab_code - void matlab_proxy(const std::string& classFile) const; ///< emit proxy class - void matlab_constructors(const std::string& toolboxPath) const; ///< emit constructor wrappers - void matlab_deconstructor(const std::string& toolboxPath) const; - void matlab_methods(const std::string& classPath) const; ///< emit method wrappers - void matlab_static_methods(const std::string& classPath) const; ///< emit static method wrappers - void matlab_make_fragment(FileWriter& file, - const std::string& toolboxPath, - const std::string& mexFlags) const; ///< emit make fragment for global make script - void makefile_fragment(FileWriter& file) const; ///< emit makefile fragment + void matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName, const TypeAttributesTable& typeAttributes, + FileWriter& wrapperFile, std::vector& functionNames) const; ///< emit proxy class std::string qualifiedName(const std::string& delim = "") const; ///< creates a namespace-qualified name, optional delimiter + + std::vector expandTemplate(const std::string& templateArg, const std::vector >& instantiations) const; + Class expandTemplate(const std::string& templateArg, const std::vector& instantiation, const std::vector& expandedClassNamespace, const std::string& expandedClassName) const; + + // The typedef line for this class, if this class is a typedef, otherwise returns an empty string. + std::string getTypedef() const; + + +private: + void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; + void comment_fragment(FileWriter& proxyFile) const; }; } // \namespace wrap diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index fda7db1b4..7d18cb8db 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -12,12 +12,16 @@ /** * @file Constructor.ccp * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #include #include +#include #include +#include #include "utilities.h" #include "Constructor.h" @@ -25,82 +29,80 @@ using namespace std; using namespace wrap; + /* ************************************************************************* */ string Constructor::matlab_wrapper_name(const string& className) const { - string str = "new_" + className + "_" + args.signature(); + string str = "new_" + className; return str; } /* ************************************************************************* */ -void Constructor::matlab_proxy_fragment(FileWriter& file, const string& className) const { +void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName, + bool hasParent, const int id, const ArgumentList args) const { size_t nrArgs = args.size(); // check for number of arguments... - file.oss << " if (nargin == " << nrArgs; + file.oss << " elseif nargin == " << nrArgs; if (nrArgs>0) file.oss << " && "; // ...and their types bool first = true; for(size_t i=0;i& using_namespaces, const vector& includes) const { - string matlabName = matlab_wrapper_name(matlabClassName); + const string& matlabUniqueName, + const string& cppBaseClassName, + int id, + const ArgumentList& al) const { - // open destination wrapperFile - string wrapperFile = toolboxPath + "/" + matlabName + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); + const string wrapFunctionName = matlabUniqueName + "_constructor_" + boost::lexical_cast(id); - // generate code - generateIncludes(file, name, includes); - generateUsingNamespace(file, using_namespaces); + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + file.oss << "{\n"; + file.oss << " mexAtExit(&_deleteAllObjects);\n"; + //Typedef boost::shared_ptr + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n"; + file.oss << "\n"; + + //Check to see if there will be any arguments and remove {} for consiseness + if(al.size() > 0) + al.matlab_unwrap(file); // unwrap arguments + file.oss << " Shared *self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl; + file.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; + + if(verbose_) + file.oss << " std::cout << \"constructed \" << self << \" << std::endl;" << endl; + file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl; + file.oss << " *reinterpret_cast (mxGetData(out[0])) = self;" << endl; + + // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) + if(!cppBaseClassName.empty()) { + file.oss << "\n"; + file.oss << " typedef boost::shared_ptr<" << cppBaseClassName << "> SharedBase;\n"; + file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; + file.oss << " *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self);\n"; + } - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; - file.oss << "{" << endl; - file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << args.size() << ");" << endl; - args.matlab_unwrap(file); // unwrap arguments - file.oss << " " << cppClassName << "* self = new " << cppClassName << "(" << args.names() << ");" << endl; // need qualified name, delim: "::" - file.oss << " out[0] = wrap_constructed(self,\"" << matlabClassName << "\");" << endl; // need matlab qualified name file.oss << "}" << endl; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Constructor.h b/wrap/Constructor.h index 4aba5b984..fe8a96ccd 100644 --- a/wrap/Constructor.h +++ b/wrap/Constructor.h @@ -13,6 +13,7 @@ * @file Constructor.h * @brief class describing a constructor + code generation * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once @@ -28,12 +29,12 @@ namespace wrap { struct Constructor { /// Constructor creates an empty class - Constructor(bool verbose = true) : + Constructor(bool verbose = false) : verbose_(verbose) { } // Then the instance variables are set directly by the Module constructor - ArgumentList args; + std::vector args_list; std::string name; bool verbose_; @@ -48,19 +49,22 @@ struct Constructor { * Create fragment to select constructor in proxy class, e.g., * if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end */ - void matlab_proxy_fragment(FileWriter& file, const std::string& className) const; - - /// m-file - void matlab_mfile(const std::string& toolboxPath, - const std::string& qualifiedMatlabName) const; + void proxy_fragment(FileWriter& file, const std::string& wrapperName, + bool hasParent, const int id, const ArgumentList args) const; /// cpp wrapper - void matlab_wrapper(const std::string& toolboxPath, + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, - const std::string& matlabClassName, - const std::vector& using_namespaces, - const std::vector& includes) const; + const std::string& matlabUniqueName, + const std::string& cppBaseClassName, + int id, + const ArgumentList& al) const; + + /// constructor function + void generate_construct(FileWriter& file, const std::string& cppClassName, + std::vector& args_list) const; + }; -} // \namespace wrap +} // \namespace wrap diff --git a/wrap/Deconstructor.cpp b/wrap/Deconstructor.cpp index 93ed724f5..b2355f20e 100644 --- a/wrap/Deconstructor.cpp +++ b/wrap/Deconstructor.cpp @@ -13,12 +13,14 @@ * @file Deconstructor.ccp * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #include #include #include +#include #include "utilities.h" #include "Deconstructor.h" @@ -33,51 +35,40 @@ string Deconstructor::matlab_wrapper_name(const string& className) const { } /* ************************************************************************* */ -void Deconstructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName) const { +void Deconstructor::proxy_fragment(FileWriter& file, + const std::string& wrapperName, + const std::string& matlabUniqueName, int id) const { - string matlabName = matlab_wrapper_name(qualifiedMatlabName); - - // open destination m-file - string wrapperFile = toolboxPath + "/" + matlabName + ".m"; - FileWriter file(wrapperFile, verbose_, "%"); - - // generate code - file.oss << "function result = " << matlabName << "(obj"; - if (args.size()) file.oss << "," << args.names(); - file.oss << ")" << endl; - file.oss << " error('need to compile " << matlabName << ".cpp');" << endl; - file.oss << "end" << endl; - - // close file - file.emit(true); + file.oss << " function delete(obj)\n"; + file.oss << " " << wrapperName << "(" << id << ", obj.ptr_" << matlabUniqueName << ");\n"; + file.oss << " end\n"; } /* ************************************************************************* */ -void Deconstructor::matlab_wrapper(const string& toolboxPath, +string Deconstructor::wrapper_fragment(FileWriter& file, const string& cppClassName, - const string& matlabClassName, - const vector& using_namespaces, const vector& includes) const { - string matlabName = matlab_wrapper_name(matlabClassName); + const string& matlabUniqueName, + int id) const { + + const string matlabName = matlab_wrapper_name(matlabUniqueName); - // open destination wrapperFile - string wrapperFile = toolboxPath + "/" + matlabName + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); - - // generate code - // - generateIncludes(file, name, includes); - cout << "Generate includes " << name << endl; - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabUniqueName + "_deconstructor_" + boost::lexical_cast(id); - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; file.oss << "{" << endl; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; //Deconstructor takes 1 arg, the mxArray obj file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl; - file.oss << " delete_shared_ptr< " << cppClassName << " >(in[0],\"" << matlabClassName << "\");" << endl; + file.oss << " Shared *self = *reinterpret_cast(mxGetData(in[0]));\n"; + file.oss << " Collector_" << matlabUniqueName << "::iterator item;\n"; + file.oss << " item = collector_" << matlabUniqueName << ".find(self);\n"; + file.oss << " if(item != collector_" << matlabUniqueName << ".end()) {\n"; + file.oss << " delete self;\n"; + file.oss << " collector_" << matlabUniqueName << ".erase(item);\n"; + file.oss << " }\n"; file.oss << "}" << endl; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Deconstructor.h b/wrap/Deconstructor.h index a5af4e327..a3b71b04e 100644 --- a/wrap/Deconstructor.h +++ b/wrap/Deconstructor.h @@ -14,6 +14,7 @@ * @brief class describing a constructor + code generation * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #pragma once @@ -34,7 +35,6 @@ struct Deconstructor { } // Then the instance variables are set directly by the Module deconstructor - ArgumentList args; std::string name; bool verbose_; @@ -46,15 +46,15 @@ struct Deconstructor { std::string matlab_wrapper_name(const std::string& className) const; /// m-file - void matlab_mfile(const std::string& toolboxPath, - const std::string& qualifiedMatlabName) const; + void proxy_fragment(FileWriter& file, + const std::string& wrapperName, + const std::string& matlabUniqueName, int id) const; /// cpp wrapper - void matlab_wrapper(const std::string& toolboxPath, + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, - const std::string& matlabClassName, - const std::vector& using_namespaces, - const std::vector& includes) const; + const std::string& matlabUniqueName, + int id) const; }; } // \namespace wrap diff --git a/wrap/FileWriter.cpp b/wrap/FileWriter.cpp index ae474be0a..515a5dbf3 100644 --- a/wrap/FileWriter.cpp +++ b/wrap/FileWriter.cpp @@ -35,17 +35,17 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const { // Only write a file if it is new, an update, or overwrite is forced string new_contents = oss.str(); if (force_overwrite || !file_exists || existing_contents != new_contents) { - ofstream ofs(filename_.c_str()); + ofstream ofs(filename_.c_str(), ios::binary); // Binary to use LF line endings instead of CRLF if (!ofs) throw CantOpenFile(filename_); - // header - if (add_header) - ofs << comment_str_ << " automatically generated by wrap" << endl; - // dump in stringstream ofs << new_contents; ofs.close(); if (verbose_) cerr << " ...complete" << endl; + + // Add small message whenever writing a new file and not running in full verbose mode + if (!verbose_) + cout << "wrap: generating " << filename_ << endl; } else { if (verbose_) cerr << " ...no update" << endl; } diff --git a/wrap/FileWriter.h b/wrap/FileWriter.h index f081b86ed..ecafc0c35 100644 --- a/wrap/FileWriter.h +++ b/wrap/FileWriter.h @@ -25,7 +25,7 @@ public: std::ostringstream oss; ///< Primary stream for operating on the file /** Create a writer with a filename and delimiter for the header comment */ - FileWriter(const std::string& filename, bool verbose, const std::string& comment_str=""); + FileWriter(const std::string& filename, bool verbose, const std::string& comment_str); /** Writes the contents of the stringstream to the file, checking if actually new */ void emit(bool add_header, bool force=false) const; diff --git a/wrap/ForwardDeclaration.h b/wrap/ForwardDeclaration.h new file mode 100644 index 000000000..2c9b6fa0c --- /dev/null +++ b/wrap/ForwardDeclaration.h @@ -0,0 +1,32 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#pragma once + +#include + +namespace wrap { + + struct ForwardDeclaration { + std::string name; + bool isVirtual; + ForwardDeclaration() : isVirtual(false) {} + }; + +} \ No newline at end of file diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp new file mode 100644 index 000000000..084f83be0 --- /dev/null +++ b/wrap/GlobalFunction.cpp @@ -0,0 +1,161 @@ +/** + * @file GlobalFunction.cpp + * + * @date Jul 22, 2012 + * @author Alex Cunningham + */ + +#include "GlobalFunction.h" +#include "utilities.h" + +#include +#include + +namespace wrap { + +using namespace std; + +/* ************************************************************************* */ +void GlobalFunction::addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal, const StrVec& ns_stack) { + this->verbose_ = verbose; + this->name = name; + this->argLists.push_back(args); + this->returnVals.push_back(retVal); + this->namespaces.push_back(ns_stack); +} + +/* ************************************************************************* */ +void GlobalFunction::matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName, + const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, + std::vector& functionNames) const { + + // cluster overloads with same namespace + // create new GlobalFunction structures around namespaces - same namespaces and names are overloads + // map of namespace to global function + typedef map GlobalFunctionMap; + GlobalFunctionMap grouped_functions; + for (size_t i=0; i& functionNames) const { + + // create the folder for the namespace + const StrVec& ns = namespaces.front(); + createNamespaceStructure(ns, toolboxPath); + + // open destination mfunctionFileName + string mfunctionFileName = toolboxPath; + if(!ns.empty()) + mfunctionFileName += "/+" + wrap::qualifiedName("/+", ns); + mfunctionFileName += "/" + name + ".m"; + FileWriter mfunctionFile(mfunctionFileName, verbose_, "%"); + + // get the name of actual matlab object + const string + matlabQualName = qualifiedName(".", ns, name), + matlabUniqueName = qualifiedName("", ns, name), + cppName = qualifiedName("::", ns, name); + + mfunctionFile.oss << "function varargout = " << name << "(varargin)\n"; + + for(size_t overload = 0; overload < argLists.size(); ++overload) { + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + size_t nrArgs = args.size(); + + const int id = functionNames.size(); + + // Output proxy matlab code + + // check for number of arguments... + mfunctionFile.oss << (overload==0?"":"else") << "if length(varargin) == " << nrArgs; + if (nrArgs>0) mfunctionFile.oss << " && "; + // ...and their types + bool first = true; + for(size_t i=0;i(id); + + // call + wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + wrapperFile.oss << "{\n"; + + returnVal.wrapTypeUnwrap(wrapperFile); + + // check arguments + // NOTE: for static functions, there is no object passed + wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "\",nargout,nargin," << args.size() << ");\n"; + + // unwrap arguments, see Argument.cpp + args.matlab_unwrap(wrapperFile,0); // We start at 0 because there is no self object + + // call method with default type and wrap result + if (returnVal.type1!="void") + returnVal.wrap_result(cppName+"("+args.names()+")", wrapperFile, typeAttributes); + else + wrapperFile.oss << cppName+"("+args.names()+");\n"; + + // finish + wrapperFile.oss << "}\n"; + + // Add to function list + functionNames.push_back(wrapFunctionName); + } + + mfunctionFile.oss << "else\n"; + mfunctionFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << "');" << endl; + mfunctionFile.oss << "end" << endl; + + // Close file + mfunctionFile.emit(true); +} + +/* ************************************************************************* */ + + +} // \namespace wrap + + + + diff --git a/wrap/GlobalFunction.h b/wrap/GlobalFunction.h new file mode 100644 index 000000000..37a70df2a --- /dev/null +++ b/wrap/GlobalFunction.h @@ -0,0 +1,58 @@ +/** + * @file GlobalFunction.h + * + * @brief Implements codegen for a global function wrapped in matlab + * + * @date Jul 22, 2012 + * @author Alex Cunningham + */ + +#pragma once + +#include "Argument.h" +#include "ReturnValue.h" + +namespace wrap { + +struct GlobalFunction { + + typedef std::vector StrVec; + + bool verbose_; + std::string name; + + // each overload, regardless of namespace + std::vector argLists; ///< arugments for each overload + std::vector returnVals; ///< returnVals for each overload + std::vector namespaces; ///< Stack of namespaces + + // Constructor only used in Module + GlobalFunction(bool verbose = true) : verbose_(verbose) {} + + // Used to reconstruct + GlobalFunction(const std::string& name_, bool verbose = true) + : verbose_(verbose), name(name_) {} + + // adds an overloaded version of this function + void addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal, const StrVec& ns_stack); + + // codegen function called from Module to build the cpp and matlab versions of the function + void matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName, + const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, + std::vector& functionNames) const; + +private: + + // Creates a single global function - all in same namespace + void generateSingleFunction(const std::string& toolboxPath, const std::string& wrapperName, + const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, + std::vector& functionNames) const; + +}; + +} // \namespace wrap + + + + diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 3d53956f1..e4def9bc0 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -12,12 +12,14 @@ /** * @file Method.ccp * @author Frank Dellaert + * @author Richard Roberts **/ #include #include #include +#include #include "Method.h" #include "utilities.h" @@ -26,45 +28,146 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -void Method::matlab_mfile(const string& classPath) const { +void Method::addOverload(bool verbose, bool is_const, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal) { + this->verbose_ = verbose; + this->is_const_ = is_const; + this->name = name; + this->argLists.push_back(args); + this->returnVals.push_back(retVal); +} - // open destination m-file - string wrapperFile = classPath + "/" + name + ".m"; - FileWriter file(wrapperFile, verbose_); +void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const string& cppClassName, + const std::string& matlabQualName, + const std::string& matlabUniqueName, + const string& wrapperName, + const TypeAttributesTable& typeAttributes, + vector& functionNames) const { - // generate code - string returnType = returnVal.matlab_returnType(); - file.oss << "function " << returnType << " = " << name << "(obj"; - if (args.size()) file.oss << "," << args.names(); - file.oss << ")" << endl; - file.oss << "% usage: obj." << name << "(" << args.names() << ")" << endl; - file.oss << " error('need to compile " << name << ".cpp');" << endl; - file.oss << "end" << endl; + proxyFile.oss << " function varargout = " << name << "(this, varargin)\n"; + //Comments for documentation + string up_name = boost::to_upper_copy(name); + proxyFile.oss << " % " << up_name << " usage:"; + unsigned int argLCount = 0; + BOOST_FOREACH(ArgumentList argList, argLists) + { + proxyFile.oss << " " << name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) + { + if(i != argList.size()-1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + if(argLCount != argLists.size()-1) + proxyFile.oss << "), "; + else + proxyFile.oss << ") : returns " << returnVals[0].return_type(false, returnVals[0].pair) << endl; + argLCount++; + } - // close file - file.emit(true); + proxyFile.oss << " % " << "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html" << endl; + proxyFile.oss << " % " << "" << endl; + proxyFile.oss << " % " << "Method Overloads" << endl; + BOOST_FOREACH(ArgumentList argList, argLists) + { + proxyFile.oss << " % " << name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) + { + if(i != argList.size()-1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + proxyFile.oss << ")" << endl; + } + + for(size_t overload = 0; overload < argLists.size(); ++overload) { + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + size_t nrArgs = args.size(); + + const int id = functionNames.size(); + + // Output proxy matlab code + + // check for number of arguments... + proxyFile.oss << " " << (overload==0?"":"else") << "if length(varargin) == " << nrArgs; + if (nrArgs>0) proxyFile.oss << " && "; + // ...and their types + bool first = true; + for(size_t i=0;i& using_namespaces, const std::vector& includes) const { - // open destination wrapperFile - string wrapperFile = classPath + "/" + name + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); + const string& matlabUniqueName, + int overload, + int id, + const TypeAttributesTable& typeAttributes) const { // generate code - // header - generateIncludes(file, className, includes); - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabUniqueName + "_" + name + "_" + boost::lexical_cast(id); - // call - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - file.oss << "{\n"; + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + + // call + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + file.oss << "{\n"; + + if(returnVal.isPair) + { + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + if(returnVal.category2 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; + } + else + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // check arguments // extra argument obj -> nargin-1 is passed ! @@ -73,28 +176,21 @@ void Method::matlab_wrapper(const string& classPath, // get class pointer // example: shared_ptr = unwrap_shared_ptr< Test >(in[0], "Test"); - file.oss << " shared_ptr<" << cppClassName << "> self = unwrap_shared_ptr< " << cppClassName - << " >(in[0],\"" << matlabClassName << "\");" << endl; - + file.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,1); - // call method - // example: bool result = self->return_field(t); - file.oss << " "; + // call method and wrap result + // example: out[0]=wrap(self->return_field(t)); if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << "self->" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result("obj->"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << " obj->"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Method.h b/wrap/Method.h index bcfac82e3..0b17e690e 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -13,6 +13,7 @@ * @file Method.h * @brief describes and generates code for methods * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once @@ -22,6 +23,8 @@ #include "Argument.h" #include "ReturnValue.h" +#include "TypeAttributesTable.h" +#include namespace wrap { @@ -30,25 +33,35 @@ struct Method { /// Constructor creates empty object Method(bool verbose = true) : - verbose_(verbose) {} + verbose_(verbose), is_const_(false) {} // Then the instance variables are set directly by the Module constructor bool verbose_; bool is_const_; std::string name; - ArgumentList args; - ReturnValue returnVal; + std::vector argLists; + std::vector returnVals; + + // The first time this function is called, it initializes the class members + // with those in rhs, but in subsequent calls it adds additional argument + // lists as function overloads. + void addOverload(bool verbose, bool is_const, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal); // MATLAB code generation // classPath is class directory, e.g., ../matlab/@Point2 + void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName, + const std::string& wrapperName, const TypeAttributesTable& typeAttributes, + std::vector& functionNames) const; - void matlab_mfile(const std::string& classPath) const; ///< m-file - void matlab_wrapper(const std::string& classPath, - const std::string& className, +private: + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, - const std::string& matlabClassname, - const std::vector& using_namespaces, - const std::vector& includes) const; ///< cpp wrapper + const std::string& matlabUniqueName, + int overload, + int id, + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/Module.cpp b/wrap/Module.cpp index dfd781016..aad533a9a 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -1,380 +1,664 @@ -/* ---------------------------------------------------------------------------- +/* ---------------------------------------------------------------------------- + + * 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 Module.ccp + * @author Frank Dellaert + * @author Alex Cunningham + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "Module.h" +#include "FileWriter.h" +#include "TypeAttributesTable.h" +#include "utilities.h" +#include "spirit_actors.h" + +//#define BOOST_SPIRIT_DEBUG +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace wrap; +using namespace BOOST_SPIRIT_CLASSIC_NS; +namespace bl = boost::lambda; +namespace fs = boost::filesystem; + +typedef rule Rule; + +/* ************************************************************************* */ +// We parse an interface file into a Module object. +// The grammar is defined using the boost/spirit combinatorial parser. +// For example, str_p("const") parses the string "const", and the >> +// operator creates a sequence parser. The grammar below, composed of rules +// and with start rule [class_p], doubles as the specs for our interface files. +/* ************************************************************************* */ + +/* ************************************************************************* */ +void handle_possible_template(vector& classes, const Class& cls, const string& templateArgument, const vector >& instantiations) { + if(instantiations.empty()) { + classes.push_back(cls); + } else { + vector classInstantiations = cls.expandTemplate(templateArgument, instantiations); + BOOST_FOREACH(const Class& c, classInstantiations) { + classes.push_back(c); + } + } +} + +/* ************************************************************************* */ +Module::Module(const string& interfacePath, + const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) +{ + // these variables will be imperatively updated to gradually build [cls] + // The one with postfix 0 are used to reset the variables after parse. + string methodName, methodName0; + bool isConst, isConst0 = false; + ReturnValue retVal0, retVal; + Argument arg0, arg; + ArgumentList args0, args; + vector arg_dup; ///keep track of duplicates + Constructor constructor0(enable_verbose), constructor(enable_verbose); + Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); + StaticMethod static_method0(enable_verbose), static_method(enable_verbose); + Class cls0(enable_verbose),cls(enable_verbose); + GlobalFunction globalFunc0(enable_verbose), globalFunc(enable_verbose); + ForwardDeclaration fwDec0, fwDec; + vector namespaces, /// current namespace tag + namespaces_return; /// namespace for current return type + string templateArgument; + vector templateInstantiationNamespace; + vector > templateInstantiations; + TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; + string include_path = ""; + const string null_str = ""; + + //---------------------------------------------------------------------------- + // Grammar with actions that build the Class object. Actions are + // defined within the square brackets [] and are executed whenever a + // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. + // The grammar is allows a very restricted C++ header + // lexeme_d turns off white space skipping + // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html + // ---------------------------------------------------------------------------- + + Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); + + Rule basisType_p = + (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); + + Rule keywords_p = + (str_p("const") | "static" | "namespace" | basisType_p); + + Rule eigenType_p = + (str_p("Vector") | "Matrix"); + + Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p); + + Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + + Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); + + Rule argEigenType_p = + eigenType_p[assign_a(arg.type)] >> + !ch_p('*')[assign_a(arg.is_ptr,true)]; + + Rule eigenRef_p = + !str_p("const") [assign_a(arg.is_const,true)] >> + eigenType_p [assign_a(arg.type)] >> + ch_p('&') [assign_a(arg.is_ref,true)]; + + Rule classArg_p = + !str_p("const") [assign_a(arg.is_const,true)] >> + *namespace_arg_p >> + className_p[assign_a(arg.type)] >> + (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); + + Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + + Rule classParent_p = + *(namespace_name_p[push_back_a(cls.qualifiedParent)] >> str_p("::")) >> + className_p[push_back_a(cls.qualifiedParent)]; + + Rule templateInstantiation_p = + (*(namespace_name_p[push_back_a(templateInstantiationNamespace)] >> str_p("::")) >> + className_p[push_back_a(templateInstantiationNamespace)]) + [push_back_a(templateInstantiations, templateInstantiationNamespace)] + [clear_a(templateInstantiationNamespace)]; + + Rule templateInstantiations_p = + (str_p("template") >> + '<' >> name_p[assign_a(templateArgument)] >> '=' >> '{' >> + !(templateInstantiation_p >> *(',' >> templateInstantiation_p)) >> + '}' >> '>') + [push_back_a(cls.templateArgs, templateArgument)]; + + Rule templateSingleInstantiationArg_p = + (*(namespace_name_p[push_back_a(templateInstantiationNamespace)] >> str_p("::")) >> + className_p[push_back_a(templateInstantiationNamespace)]) + [push_back_a(singleInstantiation.typeList, templateInstantiationNamespace)] + [clear_a(templateInstantiationNamespace)]; + + Rule templateSingleInstantiation_p = + (str_p("typedef") >> + *(namespace_name_p[push_back_a(singleInstantiation.classNamespaces)] >> str_p("::")) >> + className_p[assign_a(singleInstantiation.className)] >> + '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> + '>' >> + className_p[assign_a(singleInstantiation.name)] >> + ';') + [assign_a(singleInstantiation.namespaces, namespaces)] + [push_back_a(templateInstantiationTypedefs, singleInstantiation)] + [assign_a(singleInstantiation, singleInstantiation0)]; + + Rule templateList_p = + (str_p("template") >> + '<' >> name_p[push_back_a(cls.templateArgs)] >> *(',' >> name_p[push_back_a(cls.templateArgs)]) >> + '>'); + + Rule argument_p = + ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) + >> name_p[assign_a(arg.name)]) + [push_back_a(args, arg)] + [assign_a(arg,arg0)]; + + Rule argumentList_p = !argument_p >> * (',' >> argument_p); + + Rule constructor_p = + (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) + [push_back_a(constructor.args_list, args)] + [assign_a(args,args0)]; + //[assign_a(constructor.args,args)] + //[assign_a(constructor.name,cls.name)] + //[push_back_a(cls.constructors, constructor)] + //[assign_a(constructor,constructor0)]; + + Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); + + Rule returnType1_p = + (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> + !ch_p('*')[assign_a(retVal.isPtr1,true)]) | + (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); + + Rule returnType2_p = + (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> + !ch_p('*') [assign_a(retVal.isPtr2,true)]) | + (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); + + Rule pair_p = + (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') + [assign_a(retVal.isPair,true)]; + + Rule void_p = str_p("void")[assign_a(retVal.type1)]; + + Rule returnType_p = void_p | returnType1_p | pair_p; + + Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; + + Rule method_p = + (returnType_p >> methodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> + !str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p) + [bl::bind(&Method::addOverload, + bl::var(cls.methods)[bl::var(methodName)], + verbose, + bl::var(isConst), + bl::var(methodName), + bl::var(args), + bl::var(retVal))] + [assign_a(isConst,isConst0)] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; + + Rule static_method_p = + (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> ';' >> *comments_p) + [bl::bind(&StaticMethod::addOverload, + bl::var(cls.static_methods)[bl::var(methodName)], + verbose, + bl::var(methodName), + bl::var(args), + bl::var(retVal))] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule functions_p = constructor_p | method_p | static_method_p; + + Rule class_p = + (str_p("")[assign_a(cls,cls0)]) + >> (!(templateInstantiations_p | templateList_p) + >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) + >> str_p("class") + >> className_p[assign_a(cls.name)] + >> ((':' >> classParent_p >> '{') | '{') + >> *(functions_p | comments_p) + >> str_p("};")) + [assign_a(constructor.name, cls.name)] + [assign_a(cls.constructor, constructor)] + [assign_a(cls.namespaces, namespaces)] + [assign_a(deconstructor.name,cls.name)] + [assign_a(cls.deconstructor, deconstructor)] + [bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateArgument), bl::var(templateInstantiations))] + [assign_a(deconstructor,deconstructor0)] + [assign_a(constructor, constructor0)] + [assign_a(cls,cls0)] + [clear_a(templateArgument)] + [clear_a(templateInstantiations)]; + + Rule global_function_p = + (returnType_p >> staticMethodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> ';' >> *comments_p) + [bl::bind(&GlobalFunction::addOverload, + bl::var(global_functions)[bl::var(methodName)], + verbose, + bl::var(methodName), + bl::var(args), + bl::var(retVal), + bl::var(namespaces))] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>'); + + Rule namespace_def_p = + (str_p("namespace") + >> namespace_name_p[push_back_a(namespaces)] + >> ch_p('{') + >> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | comments_p) + >> ch_p('}')) + [pop_a(namespaces)]; + + Rule forward_declaration_p = + !(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) + >> str_p("class") + >> (*(namespace_name_p >> str_p("::")) >> className_p)[assign_a(fwDec.name)] + >> ch_p(';') + [push_back_a(forward_declarations, fwDec)] + [assign_a(fwDec, fwDec0)]; + + Rule module_content_p = comments_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p; + + Rule module_p = *module_content_p >> !end_p; + + //---------------------------------------------------------------------------- + // for debugging, define BOOST_SPIRIT_DEBUG +# ifdef BOOST_SPIRIT_DEBUG + BOOST_SPIRIT_DEBUG_NODE(className_p); + BOOST_SPIRIT_DEBUG_NODE(classPtr_p); + BOOST_SPIRIT_DEBUG_NODE(classRef_p); + BOOST_SPIRIT_DEBUG_NODE(basisType_p); + BOOST_SPIRIT_DEBUG_NODE(name_p); + BOOST_SPIRIT_DEBUG_NODE(argument_p); + BOOST_SPIRIT_DEBUG_NODE(argumentList_p); + BOOST_SPIRIT_DEBUG_NODE(constructor_p); + BOOST_SPIRIT_DEBUG_NODE(returnType1_p); + BOOST_SPIRIT_DEBUG_NODE(returnType2_p); + BOOST_SPIRIT_DEBUG_NODE(pair_p); + BOOST_SPIRIT_DEBUG_NODE(void_p); + BOOST_SPIRIT_DEBUG_NODE(returnType_p); + BOOST_SPIRIT_DEBUG_NODE(methodName_p); + BOOST_SPIRIT_DEBUG_NODE(method_p); + BOOST_SPIRIT_DEBUG_NODE(class_p); + BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); + BOOST_SPIRIT_DEBUG_NODE(module_p); +# endif + //---------------------------------------------------------------------------- + + // read interface file + string interfaceFile = interfacePath + "/" + moduleName + ".h"; + string contents = file_contents(interfaceFile); + + // and parse contents + parse_info info = parse(contents.c_str(), module_p, space_p); + if(!info.full) { + printf("parsing stopped at \n%.20s\n",info.stop); + throw ParseFailed((int)info.length); + } - * 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) + //Explicitly add methods to the classes from parents so it shows in documentation + BOOST_FOREACH(Class& cls, classes) + { + map inhereted = appendInheretedMethods(cls, classes); + cls.methods.insert(inhereted.begin(), inhereted.end()); + } - * See LICENSE for the license information - * -------------------------------------------------------------------------- */ +} + +/* ************************************************************************* */ +template +void verifyArguments(const vector& validArgs, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ArgumentList& argList, t.argLists) { + BOOST_FOREACH(Argument arg, argList) { + string fullType = arg.qualifiedType("::"); + if(find(validArgs.begin(), validArgs.end(), fullType) + == validArgs.end()) + throw DependencyMissing(fullType, t.name); + } + } + } +} + +/* ************************************************************************* */ +template +void verifyReturnTypes(const vector& validtypes, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ReturnValue& retval, t.returnVals) { + if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType1("::"), t.name); + if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType2("::"), t.name); + } + } +} + +/* ************************************************************************* */ +void Module::generateIncludes(FileWriter& file) const { + + // collect includes + vector all_includes(includes); + + // sort and remove duplicates + sort(all_includes.begin(), all_includes.end()); + vector::const_iterator last_include = unique(all_includes.begin(), all_includes.end()); + vector::const_iterator it = all_includes.begin(); + // add includes to file + for (; it != last_include; ++it) + file.oss << "#include <" << *it << ">" << endl; + file.oss << "\n"; +} + +/* ************************************************************************* */ +void Module::matlab_code(const string& toolboxPath, const string& headerPath) const { + + fs::create_directories(toolboxPath); + + // create the unified .cpp switch file + const string wrapperName = name + "_wrapper"; + string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; + FileWriter wrapperFile(wrapperFileName, verbose, "//"); + vector functionNames; // Function names stored by index for switch + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "\n"; + + // Expand templates - This is done first so that template instantiations are + // counted in the list of valid types, have their attributes and dependencies + // checked, etc. + vector expandedClasses = ExpandTypedefInstantiations(classes, templateInstantiationTypedefs); + + // Dependency check list + vector validTypes = GenerateValidTypes(expandedClasses, forward_declarations); + + // Check that all classes have been defined somewhere + verifyArguments(validTypes, global_functions); + verifyReturnTypes(validTypes, global_functions); + + BOOST_FOREACH(const Class& cls, expandedClasses) { + // verify all of the function arguments + //TODO:verifyArguments(validTypes, cls.constructor.args_list); + verifyArguments(validTypes, cls.static_methods); + verifyArguments(validTypes, cls.methods); + + // verify function return types + verifyReturnTypes(validTypes, cls.static_methods); + verifyReturnTypes(validTypes, cls.methods); + + // verify parents + if(!cls.qualifiedParent.empty() && std::find(validTypes.begin(), validTypes.end(), wrap::qualifiedName("::", cls.qualifiedParent)) == validTypes.end()) + throw DependencyMissing(wrap::qualifiedName("::", cls.qualifiedParent), cls.qualifiedName("::")); -/** - * @file Module.ccp - * @author Frank Dellaert - * @author Alex Cunningham - * @author Andrew Melim - **/ - -#include "Module.h" -#include "FileWriter.h" -#include "utilities.h" -#include "spirit_actors.h" - -//#define BOOST_SPIRIT_DEBUG -#include -#include -#include - -#include - -using namespace std; -using namespace wrap; -using namespace BOOST_SPIRIT_CLASSIC_NS; - -typedef rule Rule; - -/* ************************************************************************* */ -// We parse an interface file into a Module object. -// The grammar is defined using the boost/spirit combinatorial parser. -// For example, str_p("const") parses the string "const", and the >> -// operator creates a sequence parser. The grammar below, composed of rules -// and with start rule [class_p], doubles as the specs for our interface files. -/* ************************************************************************* */ - -Module::Module(const string& interfacePath, - const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) + } + + // Create type attributes table and check validity + TypeAttributesTable typeAttributes; + typeAttributes.addClasses(expandedClasses); + typeAttributes.addForwardDeclarations(forward_declarations); + typeAttributes.checkValidity(expandedClasses); + + // Generate includes while avoiding redundant includes + generateIncludes(wrapperFile); + + // create typedef classes - we put this at the top of the wrap file so that collectors and method arguments can use these typedefs + BOOST_FOREACH(const Class& cls, expandedClasses) { + if(!cls.typedefName.empty()) + wrapperFile.oss << cls.getTypedef() << "\n"; + } + wrapperFile.oss << "\n"; + + // Generate collectors and cleanup function to be called from mexAtExit + WriteCollectorsAndCleanupFcn(wrapperFile, name, expandedClasses); + + // generate RTTI registry (for returning derived-most types) + WriteRTTIRegistry(wrapperFile, name, expandedClasses); + + // create proxy class and wrapper code + BOOST_FOREACH(const Class& cls, expandedClasses) { + cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames); + } + + // create matlab files and wrapper code for global functions + BOOST_FOREACH(const GlobalFunctions::value_type& p, global_functions) { + p.second.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames); + } + + // finish wrapper file + wrapperFile.oss << "\n"; + finish_wrapper(wrapperFile, functionNames); + + wrapperFile.emit(true); + } +/* ************************************************************************* */ +map Module::appendInheretedMethods(const Class& cls, const vector& classes) { - // these variables will be imperatively updated to gradually build [cls] - // The one with postfix 0 are used to reset the variables after parse. - ReturnValue retVal0, retVal; - Argument arg0, arg; - ArgumentList args0, args; - Constructor constructor0(enable_verbose), constructor(enable_verbose); - Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); - Method method0(enable_verbose), method(enable_verbose); - StaticMethod static_method0(enable_verbose), static_method(enable_verbose); - Class cls0(enable_verbose),cls(enable_verbose); - vector namespaces, /// current namespace tag - namespace_includes, /// current set of includes - namespaces_return, /// namespace for current return type - using_namespace_current; /// All namespaces from "using" declarations - string include_path = ""; - string class_name = ""; - const string null_str = ""; - - //---------------------------------------------------------------------------- - // Grammar with actions that build the Class object. Actions are - // defined within the square brackets [] and are executed whenever a - // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. - // The grammar is allows a very restricted C++ header - // lexeme_d turns off white space skipping - // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html - // ---------------------------------------------------------------------------- - - Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); - - Rule basisType_p = - (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); - - Rule keywords_p = - (str_p("const") | "static" | "namespace" | basisType_p); - - Rule eigenType_p = - (str_p("Vector") | "Matrix"); - - Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p)[assign_a(class_name)]; - - Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); - - Rule argEigenType_p = - eigenType_p[assign_a(arg.type)] >> - !ch_p('*')[assign_a(arg.is_ptr,true)]; - - Rule eigenRef_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - eigenType_p [assign_a(arg.type)] >> - ch_p('&') [assign_a(arg.is_ref,true)]; - - Rule classArg_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - *namespace_arg_p >> - className_p[assign_a(arg.type)] >> - (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); - - Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; - - Rule argument_p = - ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) - >> name_p[assign_a(arg.name)]) - [push_back_a(args, arg)] - [assign_a(arg,arg0)]; - - Rule argumentList_p = !argument_p >> * (',' >> argument_p); - - Rule constructor_p = - (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) - [assign_a(constructor.args,args)] - [assign_a(constructor.name,cls.name)] - [assign_a(args,args0)] - [push_back_a(cls.constructors, constructor)] - [assign_a(constructor,constructor0)]; - - Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); - - Rule returnType1_p = - (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> - !ch_p('*')[assign_a(retVal.isPtr1,true)]) | - (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); - - Rule returnType2_p = - (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> - !ch_p('*') [assign_a(retVal.isPtr2,true)]) | - (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); - - Rule pair_p = - (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') - [assign_a(retVal.isPair,true)]; - - Rule void_p = str_p("void")[assign_a(retVal.type1)]; - - Rule returnType_p = void_p | returnType1_p | pair_p; - - Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; - - Rule method_p = - (returnType_p >> methodName_p[assign_a(method.name)] >> - '(' >> argumentList_p >> ')' >> - !str_p("const")[assign_a(method.is_const_,true)] >> ';' >> *comments_p) - [assign_a(method.args,args)] - [assign_a(args,args0)] - [assign_a(method.returnVal,retVal)] - [assign_a(retVal,retVal0)] - [push_back_a(cls.methods, method)] - [assign_a(method,method0)]; - - Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - Rule static_method_p = - (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(static_method.name)] >> - '(' >> argumentList_p >> ')' >> ';' >> *comments_p) - [assign_a(static_method.args,args)] - [assign_a(args,args0)] - [assign_a(static_method.returnVal,retVal)] - [assign_a(retVal,retVal0)] - [push_back_a(cls.static_methods, static_method)] - [assign_a(static_method,static_method0)]; - - Rule functions_p = constructor_p | method_p | static_method_p; - - Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>'); - - Rule class_p = - (!include_p - >> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)] - >> className_p[assign_a(cls.name)] - >> '{' - >> *(functions_p | comments_p) - >> str_p("};")) - [assign_a(cls.namespaces, namespaces)] - [assign_a(cls.using_namespaces, using_namespace_current)] - [append_a(cls.includes, namespace_includes)] - [assign_a(deconstructor.name,cls.name)] - [assign_a(cls.d, deconstructor)] - [push_back_a(classes,cls)] - [assign_a(deconstructor,deconstructor0)] - [assign_a(cls,cls0)]; - - Rule namespace_def_p = - (!include_p - >> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)] - >> namespace_name_p[push_back_a(namespaces)] - >> ch_p('{') - >> *(class_p | namespace_def_p | comments_p) - >> str_p("}///\\namespace") // end namespace, avoid confusion with classes - >> !namespace_name_p) - [pop_a(namespaces)] - [pop_a(namespace_includes)]; - - Rule using_namespace_p = - str_p("using") >> str_p("namespace") - >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); - - Rule forward_declaration_p = - str_p("class") >> - (*(namespace_name_p >> str_p("::")) >> className_p)[push_back_a(forward_declarations)] - >> ch_p(';'); - - Rule module_content_p = comments_p | using_namespace_p | class_p | forward_declaration_p | namespace_def_p ; - - Rule module_p = *module_content_p >> !end_p; - - //---------------------------------------------------------------------------- - // for debugging, define BOOST_SPIRIT_DEBUG -# ifdef BOOST_SPIRIT_DEBUG - BOOST_SPIRIT_DEBUG_NODE(className_p); - BOOST_SPIRIT_DEBUG_NODE(classPtr_p); - BOOST_SPIRIT_DEBUG_NODE(classRef_p); - BOOST_SPIRIT_DEBUG_NODE(basisType_p); - BOOST_SPIRIT_DEBUG_NODE(name_p); - BOOST_SPIRIT_DEBUG_NODE(argument_p); - BOOST_SPIRIT_DEBUG_NODE(argumentList_p); - BOOST_SPIRIT_DEBUG_NODE(constructor_p); - BOOST_SPIRIT_DEBUG_NODE(returnType1_p); - BOOST_SPIRIT_DEBUG_NODE(returnType2_p); - BOOST_SPIRIT_DEBUG_NODE(pair_p); - BOOST_SPIRIT_DEBUG_NODE(void_p); - BOOST_SPIRIT_DEBUG_NODE(returnType_p); - BOOST_SPIRIT_DEBUG_NODE(methodName_p); - BOOST_SPIRIT_DEBUG_NODE(method_p); - BOOST_SPIRIT_DEBUG_NODE(class_p); - BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); - BOOST_SPIRIT_DEBUG_NODE(module_p); -# endif - //---------------------------------------------------------------------------- - - // read interface file - string interfaceFile = interfacePath + "/" + moduleName + ".h"; - string contents = file_contents(interfaceFile); - - // and parse contents - parse_info info = parse(contents.c_str(), module_p, space_p); - if(!info.full) { - printf("parsing stopped at \n%.20s\n",info.stop); - throw ParseFailed(info.length); - } -} - -/* ************************************************************************* */ -template -void verifyArguments(const vector& validArgs, const vector& vt) { - BOOST_FOREACH(const T& t, vt) { - BOOST_FOREACH(Argument arg, t.args) { - string fullType = arg.qualifiedType("::"); - if(find(validArgs.begin(), validArgs.end(), fullType) - == validArgs.end()) - throw DependencyMissing(fullType, t.name); - } - } -} - -/* ************************************************************************* */ -template -void verifyReturnTypes(const vector& validtypes, const vector& vt) { - BOOST_FOREACH(const T& t, vt) { - const ReturnValue& retval = t.returnVal; - if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType1("::"), t.name); - if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType2("::"), t.name); - } -} - -/* ************************************************************************* */ -void Module::matlab_code(const string& toolboxPath, - const string& mexExt, const string& mexFlags) const { - string installCmd = "install -d " + toolboxPath; - system(installCmd.c_str()); - - // create make m-file - string matlabMakeFileName = toolboxPath + "/make_" + name + ".m"; - FileWriter makeModuleMfile(matlabMakeFileName, verbose, "%"); - - // create the (actual) make file - string makeFileName = toolboxPath + "/Makefile"; - FileWriter makeModuleMakefile(makeFileName, verbose, "#"); - - makeModuleMfile.oss << "echo on" << endl << endl; - makeModuleMfile.oss << "toolboxpath = mfilename('fullpath');" << endl; - makeModuleMfile.oss << "delims = find(toolboxpath == '/');" << endl; - makeModuleMfile.oss << "toolboxpath = toolboxpath(1:(delims(end)-1));" << endl; - makeModuleMfile.oss << "clear delims" << endl; - makeModuleMfile.oss << "addpath(toolboxpath);" << endl << endl; - - makeModuleMakefile.oss << "\nMEX = mex\n"; - makeModuleMakefile.oss << "MEXENDING = " << mexExt << "\n"; - makeModuleMakefile.oss << "mex_flags = " << mexFlags << "\n\n"; - - // Dependency check list - vector validTypes = forward_declarations; - validTypes.push_back("void"); - validTypes.push_back("string"); - validTypes.push_back("int"); - validTypes.push_back("bool"); - validTypes.push_back("char"); - validTypes.push_back("unsigned char"); - validTypes.push_back("size_t"); - validTypes.push_back("double"); - validTypes.push_back("Vector"); - validTypes.push_back("Matrix"); - - // add 'all' to Makefile - makeModuleMakefile.oss << "all: "; - BOOST_FOREACH(Class cls, classes) { - makeModuleMakefile.oss << cls.qualifiedName() << " "; - //Create a list of parsed classes for dependency checking - validTypes.push_back(cls.qualifiedName("::")); + map methods; + if(!cls.qualifiedParent.empty()) + { + cout << "Class: " << cls.name << " Parent Name: " << cls.qualifiedParent.back() << endl; + //Find Class + BOOST_FOREACH(const Class& parent, classes) + { + //We found the class for our parent + if(parent.name == cls.qualifiedParent.back()) + { + cout << "Inner class: " << cls.qualifiedParent.back() << endl; + Methods inhereted = appendInheretedMethods(parent, classes); + methods.insert(inhereted.begin(), inhereted.end()); + } + } + } + else + { + cout << "Dead end: " << cls.name << endl; + methods.insert(cls.methods.begin(), cls.methods.end()); } - makeModuleMakefile.oss << "\n\n"; - // generate proxy classes and wrappers - BOOST_FOREACH(Class cls, classes) { - // create directory if needed - string classPath = toolboxPath + "/@" + cls.qualifiedName(); - string installCmd = "install -d " + classPath; - system(installCmd.c_str()); - - // create proxy class - string classFile = classPath + "/" + cls.qualifiedName() + ".m"; - cls.matlab_proxy(classFile); - - // verify all of the function arguments - verifyArguments(validTypes, cls.constructors); - verifyArguments(validTypes, cls.static_methods); - verifyArguments(validTypes, cls.methods); - - // verify function return types - verifyReturnTypes(validTypes, cls.static_methods); - verifyReturnTypes(validTypes, cls.methods); - - // create constructor and method wrappers - cls.matlab_constructors(toolboxPath); - cls.matlab_static_methods(toolboxPath); - cls.matlab_methods(classPath); - - // create deconstructor - cls.matlab_deconstructor(toolboxPath); - - // add lines to make m-file - makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl; - makeModuleMfile.oss << "cd(toolboxpath)" << endl; - cls.matlab_make_fragment(makeModuleMfile, toolboxPath, mexFlags); - - // add section to the (actual) make file - makeModuleMakefile.oss << "# " << cls.qualifiedName() << endl; - cls.makefile_fragment(makeModuleMakefile); - } - - // finish make m-file - makeModuleMfile.oss << "cd(toolboxpath)" << endl << endl; - makeModuleMfile.oss << "echo off" << endl; - makeModuleMfile.emit(true); // By default, compare existing file first - - // make clean at end of Makefile - makeModuleMakefile.oss << "\n\nclean: \n"; - makeModuleMakefile.oss << "\trm -rf *.$(MEXENDING)\n"; - BOOST_FOREACH(Class cls, classes) - makeModuleMakefile.oss << "\trm -rf @" << cls.qualifiedName() << "/*.$(MEXENDING)\n"; - - // finish Makefile - makeModuleMakefile.oss << "\n" << endl; - makeModuleMakefile.emit(true); - } - -/* ************************************************************************* */ + return methods; +} + +/* ************************************************************************* */ + void Module::finish_wrapper(FileWriter& file, const std::vector& functionNames) const { + file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + file.oss << "{\n"; + file.oss << " mstream mout;\n"; // Send stdout to MATLAB console + file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n"; + file.oss << " _" << name << "_RTTIRegister();\n\n"; + file.oss << " int id = unwrap(in[0]);\n\n"; + file.oss << " try {\n"; + file.oss << " switch(id) {\n"; + for(size_t id = 0; id < functionNames.size(); ++id) { + file.oss << " case " << id << ":\n"; + file.oss << " " << functionNames[id] << "(nargout, out, nargin-1, in+1);\n"; + file.oss << " break;\n"; + } + file.oss << " }\n"; + file.oss << " } catch(const std::exception& e) {\n"; + file.oss << " mexErrMsgTxt((\"Exception from gtsam:\\n\" + std::string(e.what()) + \"\\n\").c_str());\n"; + file.oss << " }\n"; + file.oss << "\n"; + file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout + file.oss << "}\n"; + } + +/* ************************************************************************* */ +vector Module::ExpandTypedefInstantiations(const vector& classes, const vector instantiations) { + + vector expandedClasses = classes; + + BOOST_FOREACH(const TemplateInstantiationTypedef& inst, instantiations) { + // Add the new class to the list + expandedClasses.push_back(inst.findAndExpand(classes)); + } + + // Remove all template classes + for(size_t i = 0; i < expandedClasses.size(); ++i) + if(!expandedClasses[size_t(i)].templateArgs.empty()) { + expandedClasses.erase(expandedClasses.begin() + size_t(i)); + -- i; + } + + return expandedClasses; +} + +/* ************************************************************************* */ +vector Module::GenerateValidTypes(const vector& classes, const vector forwardDeclarations) { + vector validTypes; + BOOST_FOREACH(const ForwardDeclaration& fwDec, forwardDeclarations) { + validTypes.push_back(fwDec.name); + } + validTypes.push_back("void"); + validTypes.push_back("string"); + validTypes.push_back("int"); + validTypes.push_back("bool"); + validTypes.push_back("char"); + validTypes.push_back("unsigned char"); + validTypes.push_back("size_t"); + validTypes.push_back("double"); + validTypes.push_back("Vector"); + validTypes.push_back("Matrix"); + //Create a list of parsed classes for dependency checking + BOOST_FOREACH(const Class& cls, classes) { + validTypes.push_back(cls.qualifiedName("::")); + } + + return validTypes; +} + +/* ************************************************************************* */ +void Module::WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { + // Generate all collectors + BOOST_FOREACH(const Class& cls, classes) { + const string matlabUniqueName = cls.qualifiedName(), + cppName = cls.qualifiedName("::"); + wrapperFile.oss << "typedef std::set*> " + << "Collector_" << matlabUniqueName << ";\n"; + wrapperFile.oss << "static Collector_" << matlabUniqueName << + " collector_" << matlabUniqueName << ";\n"; + } + + // generate mexAtExit cleanup function + wrapperFile.oss << + "\nvoid _deleteAllObjects()\n" + "{\n" + " mstream mout;\n" // Send stdout to MATLAB console + " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n" + " bool anyDeleted = false;\n"; + BOOST_FOREACH(const Class& cls, classes) { + const string matlabUniqueName = cls.qualifiedName(); + const string cppName = cls.qualifiedName("::"); + const string collectorType = "Collector_" + matlabUniqueName; + const string collectorName = "collector_" + matlabUniqueName; + // The extra curly-braces around the for loops work around a limitation in MSVC (existing + // since 2005!) preventing more than 248 blocks. + wrapperFile.oss << + " { for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n" + " iter != " << collectorName << ".end(); ) {\n" + " delete *iter;\n" + " " << collectorName << ".erase(iter++);\n" + " anyDeleted = true;\n" + " } }\n"; + } + wrapperFile.oss << + " if(anyDeleted)\n" + " cout <<\n" + " \"WARNING: Wrap modules with variables in the workspace have been reloaded due to\\n\"\n" + " \"calling destructors, call 'clear all' again if you plan to now recompile a wrap\\n\"\n" + " \"module, so that your recompiled module is used instead of the old one.\" << endl;\n" + " std::cout.rdbuf(outbuf);\n" // Restore cout + "}\n\n"; +} + +/* ************************************************************************* */ +void Module::WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { + wrapperFile.oss << + "void _" << moduleName << "_RTTIRegister() {\n" + " const mxArray *alreadyCreated = mexGetVariablePtr(\"global\", \"gtsam_" + moduleName + "_rttiRegistry_created\");\n" + " if(!alreadyCreated) {\n" + " std::map types;\n"; + BOOST_FOREACH(const Class& cls, classes) { + if(cls.isVirtual) + wrapperFile.oss << + " types.insert(std::make_pair(typeid(" << cls.qualifiedName("::") << ").name(), \"" << cls.qualifiedName(".") << "\"));\n"; + } + wrapperFile.oss << "\n"; + + wrapperFile.oss << + " mxArray *registry = mexGetVariable(\"global\", \"gtsamwrap_rttiRegistry\");\n" + " if(!registry)\n" + " registry = mxCreateStructMatrix(1, 1, 0, NULL);\n" + " typedef std::pair StringPair;\n" + " BOOST_FOREACH(const StringPair& rtti_matlab, types) {\n" + " int fieldId = mxAddField(registry, rtti_matlab.first.c_str());\n" + " if(fieldId < 0)\n" + " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" + " mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());\n" + " mxSetFieldByNumber(registry, 0, fieldId, matlabName);\n" + " }\n" + " if(mexPutVariable(\"global\", \"gtsamwrap_rttiRegistry\", registry) != 0)\n" + " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" + " mxDestroyArray(registry);\n" + " \n" + " mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);\n" + " if(mexPutVariable(\"global\", \"gtsam_" + moduleName + "_rttiRegistry_created\", newAlreadyCreated) != 0)\n" + " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" + " mxDestroyArray(newAlreadyCreated);\n" + " }\n" + "}\n" + "\n"; +} + +/* ************************************************************************* */ diff --git a/wrap/Module.h b/wrap/Module.h index 3e97d9ba2..a1dfe88d8 100644 --- a/wrap/Module.h +++ b/wrap/Module.h @@ -13,14 +13,19 @@ * @file Module.h * @brief describes module to be wrapped * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once #include #include +#include #include "Class.h" +#include "GlobalFunction.h" +#include "TemplateInstantiationTypedef.h" +#include "ForwardDeclaration.h" namespace wrap { @@ -28,21 +33,40 @@ namespace wrap { * A module just has a name and a list of classes */ struct Module { + + typedef std::map GlobalFunctions; + typedef std::map Methods; + std::string name; ///< module name std::vector classes; ///< list of classes + std::vector templateInstantiationTypedefs; ///< list of template instantiations bool verbose; ///< verbose flag -// std::vector using_namespaces; ///< all default namespaces - std::vector forward_declarations; + std::vector forward_declarations; + std::vector includes; ///< Include statements + GlobalFunctions global_functions; /// constructor that parses interface file Module(const std::string& interfacePath, const std::string& moduleName, bool enable_verbose=true); + //Recursive method to append all methods inhereted from parent classes + std::map appendInheretedMethods(const Class& cls, const std::vector& classes); + /// MATLAB code generation: - void matlab_code(const std::string& path, - const std::string& mexExt, - const std::string& mexFlags) const; + void matlab_code( + const std::string& path, + const std::string& headerPath) const; + + void finish_wrapper(FileWriter& file, const std::vector& functionNames) const; + + void generateIncludes(FileWriter& file) const; + +private: + static std::vector ExpandTypedefInstantiations(const std::vector& classes, const std::vector instantiations); + static std::vector GenerateValidTypes(const std::vector& classes, const std::vector forwardDeclarations); + static void WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes); + static void WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes); }; } // \namespace wrap diff --git a/wrap/README b/wrap/README index 6e7acc863..92fd1967c 100644 --- a/wrap/README +++ b/wrap/README @@ -1,14 +1,17 @@ Frank Dellaert October 2011 -The wrap library wraps the GTSAM library into a MATLAB toolbox. +The wrap library wraps the GTSAM library into a MATLAB toolbox. It was designed to be more general than just wrapping GTSAM, but a small amount of GTSAM specific code exists in matlab.h, the include file that is included by the -mex files. In addition, the current makefile (Oct 11) is GTSAM specific. +mex files. The GTSAM-specific functionality consists primarily of handling of +Eigen Matrix and Vector classes. + +For notes on creating a wrap interface, see gtsam.h for what features can be +wrapped into a toolbox, as well as the current state of the toolbox for gtsam. +For more technical details on the interface, please read comments in matlab.h -The classes and methods to be wrapped are specified in gtsam.h -This tool will not wrap arbitrary methods. Please read comments in matlab.h Some good things to know: OBJECT CREATION @@ -24,7 +27,5 @@ METHOD (AND CONSTRUCTOR) ARGUMENTS generation of the correct conversion routines unwrap and unwrap - passing classes as arguments works, provided they are passed by reference. This triggers a call to unwrap_shared_ptr -- GTSAM specific: keys will be cast automatically from strings via GTSAM_magic. This - allows us to not have to declare all key types in MATLAB. Just replace key arguments with - the (non-const, non-reference) string type + \ No newline at end of file diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 2095abc5e..4f5a030cc 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -3,6 +3,8 @@ * * @date Dec 1, 2011 * @author Alex Cunningham + * @author Andrew Melim + * @author Richard Roberts */ #include @@ -17,11 +19,11 @@ using namespace wrap; string ReturnValue::return_type(bool add_ptr, pairing p) const { if (p==pair && isPair) { string str = "pair< " + - maybe_shared_ptr(add_ptr && isPtr1, qualifiedType1("::")) + ", " + - maybe_shared_ptr(add_ptr && isPtr2, qualifiedType2("::")) + " >"; + maybe_shared_ptr(add_ptr || isPtr1, qualifiedType1("::"), type1) + ", " + + maybe_shared_ptr(add_ptr || isPtr2, qualifiedType2("::"), type2) + " >"; return str; } else - return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::")); + return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::"), (p==arg2)? type2 : type1); } /* ************************************************************************* */ @@ -44,35 +46,98 @@ string ReturnValue::qualifiedType2(const string& delim) const { } /* ************************************************************************* */ -void ReturnValue::wrap_result(FileWriter& file) const { - string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1(); - string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2(); +//TODO:Fix this +void ReturnValue::wrap_result(const string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const { + string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1("."); + string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2("."); if (isPair) { + // For a pair, store the returned pair so we do not evaluate the function twice + file.oss << " " << return_type(false, pair) << " pairResult = " << result << ";\n"; + // first return value in pair - if (isPtr1) // if we already have a pointer - file.oss << " out[0] = wrap_shared_ptr(result.first,\"" << matlabType1 << "\");\n"; - else if (category1 == ReturnValue::CLASS) // if we are going to make one - file.oss << " out[0] = wrap_shared_ptr(make_shared< " << cppType1 << " >(result.first),\"" << matlabType1 << "\");\n"; - else // if basis type - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n"; + if (category1 == ReturnValue::CLASS) { // if we are going to make one + string objCopy, ptrType; + ptrType = "Shared" + type1; + const bool isVirtual = typeAttributes.at(cppType1).isVirtual; + if(isVirtual) { + if(isPtr1) + objCopy = "pairResult.first"; + else + objCopy = "pairResult.first.clone()"; + } else { + if(isPtr1) + objCopy = "pairResult.first"; + else + objCopy = ptrType + "(new " + cppType1 + "(pairResult.first))"; + } + file.oss << " out[0] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType1 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr1) { + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(pairResult.first);" << endl; + file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\", false);\n"; + } else // if basis type + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(pairResult.first);\n"; // second return value in pair - if (isPtr2) // if we already have a pointer - file.oss << " out[1] = wrap_shared_ptr(result.second,\"" << matlabType2 << "\");\n"; - else if (category2 == ReturnValue::CLASS) // if we are going to make one - file.oss << " out[1] = wrap_shared_ptr(make_shared< " << cppType2 << " >(result.second),\"" << matlabType2 << "\");\n"; - else - file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; + if (category2 == ReturnValue::CLASS) { // if we are going to make one + string objCopy, ptrType; + ptrType = "Shared" + type2; + const bool isVirtual = typeAttributes.at(cppType2).isVirtual; + if(isVirtual) { + if(isPtr2) + objCopy = "pairResult.second"; + else + objCopy = "pairResult.second.clone()"; + } else { + if(isPtr2) + objCopy = "pairResult.second"; + else + objCopy = ptrType + "(new " + cppType2 + "(pairResult.second))"; + } + file.oss << " out[1] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType2 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr2) { + file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(pairResult.second);" << endl; + file.oss << " out[1] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n"; + } else + file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(pairResult.second);\n"; } - else if (isPtr1) - file.oss << " out[0] = wrap_shared_ptr(result,\"" << matlabType1 << "\");\n"; - else if (category1 == ReturnValue::CLASS) - file.oss << " out[0] = wrap_shared_ptr(make_shared< " << cppType1 << " >(result),\"" << matlabType1 << "\");\n"; - else if (matlabType1!="void") - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; + else if (category1 == ReturnValue::CLASS){ + string objCopy, ptrType; + ptrType = "Shared" + type1; + const bool isVirtual = typeAttributes.at(cppType1).isVirtual; + if(isVirtual) { + if(isPtr1) + objCopy = result; + else + objCopy = result + ".clone()"; + } else { + if(isPtr1) + objCopy = result; + else + objCopy = ptrType + "(new " + cppType1 + "(" + result + "))"; + } + file.oss << " out[0] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType1 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr1) { + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(" << result << ");" << endl; + file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + } else if (matlabType1!="void") + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(" << result << ");\n"; } /* ************************************************************************* */ +void ReturnValue::wrapTypeUnwrap(FileWriter& wrapperFile) const { + if(isPair) + { + if(category1 == ReturnValue::CLASS) + wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType1("::") << "> Shared" << type1 << ";"<< endl; + if(category2 == ReturnValue::CLASS) + wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType2("::") << "> Shared" << type2 << ";"<< endl; + } + else { + if (category1 == ReturnValue::CLASS) + wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType1("::") << "> Shared" << type1 << ";"<< endl; + } +} +/* ************************************************************************* */ diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 859e00433..2bffef680 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -5,11 +5,14 @@ * * @date Dec 1, 2011 * @author Alex Cunningham + * @author Richard Roberts */ #include +#include #include "FileWriter.h" +#include "TypeAttributesTable.h" #pragma once @@ -47,7 +50,9 @@ struct ReturnValue { std::string matlab_returnType() const; - void wrap_result(FileWriter& file) const; + void wrap_result(const std::string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const; + + void wrapTypeUnwrap(FileWriter& wrapperFile) const; }; diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 3dd9e7c8b..d46fde81a 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -10,14 +10,17 @@ * -------------------------------------------------------------------------- */ /** - * @file Method.ccp + * @file StaticMethod.ccp * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #include #include #include +#include #include "StaticMethod.h" #include "utilities.h" @@ -25,71 +28,160 @@ using namespace std; using namespace wrap; + /* ************************************************************************* */ -void StaticMethod::matlab_mfile(const string& toolboxPath, const string& className) const { - - // open destination m-file - string full_name = className + "_" + name; - string wrapperFile = toolboxPath + "/" + full_name + ".m"; - FileWriter file(wrapperFile, verbose); - - // generate code - string returnType = returnVal.matlab_returnType(); - file.oss << "function " << returnType << " = " << full_name << "("; - if (args.size()) file.oss << args.names(); - file.oss << ")" << endl; - file.oss << "% usage: x = " << full_name << "(" << args.names() << ")" << endl; - file.oss << " error('need to compile " << full_name << ".cpp');" << endl; - file.oss << "end" << endl; - - // close file - file.emit(true); +void StaticMethod::addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal) { + this->verbose = verbose; + this->name = name; + this->argLists.push_back(args); + this->returnVals.push_back(retVal); } /* ************************************************************************* */ -void StaticMethod::matlab_wrapper(const string& toolboxPath, const string& className, - const string& matlabClassName, const string& cppClassName, - const vector& using_namespaces, - const vector& includes) const { - // open destination wrapperFile - string full_name = matlabClassName + "_" + name; - string wrapperFile = toolboxPath + "/" + full_name + ".cpp"; - FileWriter file(wrapperFile, verbose, "//"); +void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const string& cppClassName, + const std::string& matlabQualName, + const std::string& matlabUniqueName, + const string& wrapperName, + const TypeAttributesTable& typeAttributes, + vector& functionNames) const { + + string upperName = name; upperName[0] = std::toupper(upperName[0], std::locale()); + + proxyFile.oss << " function varargout = " << upperName << "(varargin)\n"; + //Comments for documentation + string up_name = boost::to_upper_copy(name); + proxyFile.oss << " % " << up_name << " usage:"; + unsigned int argLCount = 0; + BOOST_FOREACH(ArgumentList argList, argLists) + { + proxyFile.oss << " " << name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) + { + if(i != argList.size()-1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + if(argLCount != argLists.size()-1) + proxyFile.oss << "), "; + else + proxyFile.oss << ") : returns " << returnVals[0].return_type(false, returnVals[0].pair) << endl; + argLCount++; + } + + proxyFile.oss << " % " << "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html" << endl; + proxyFile.oss << " % " << "" << endl; + proxyFile.oss << " % " << "Usage" << endl; + BOOST_FOREACH(ArgumentList argList, argLists) + { + proxyFile.oss << " % " << up_name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) + { + if(i != argList.size()-1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + proxyFile.oss << ")" << endl; + } + + + for(size_t overload = 0; overload < argLists.size(); ++overload) { + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + size_t nrArgs = args.size(); + + const int id = functionNames.size(); + + // Output proxy matlab code + + // check for number of arguments... + proxyFile.oss << " " << (overload==0?"":"else") << "if length(varargin) == " << nrArgs; + if (nrArgs>0) proxyFile.oss << " && "; + // ...and their types + bool first = true; + for(size_t i=0;i(id); - // call - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - file.oss << "{\n"; + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + + // call + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + file.oss << "{\n"; + + returnVal.wrapTypeUnwrap(file); + + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // check arguments // NOTE: for static functions, there is no object passed - file.oss << " checkArguments(\"" << full_name << "\",nargout,nargin," << args.size() << ");\n"; + file.oss << " checkArguments(\"" << matlabUniqueName << "." << name << "\",nargout,nargin," << args.size() << ");\n"; // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,0); // We start at 0 because there is no self object - file.oss << " "; - - // call method with default type + // call method with default type and wrap result if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << cppClassName << "::" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result(cppClassName+"::"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << cppClassName+"::"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index f9cc14af7..9c1581400 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -14,6 +14,7 @@ * @brief describes and generates code for static methods * @author Frank Dellaert * @author Alex Cunningham + * @author Richard Roberts **/ #pragma once @@ -23,6 +24,8 @@ #include "Argument.h" #include "ReturnValue.h" +#include "TypeAttributesTable.h" +#include namespace wrap { @@ -36,20 +39,29 @@ struct StaticMethod { // Then the instance variables are set directly by the Module constructor bool verbose; std::string name; - ArgumentList args; - ReturnValue returnVal; + std::vector argLists; + std::vector returnVals; + + // The first time this function is called, it initializes the class members + // with those in rhs, but in subsequent calls it adds additional argument + // lists as function overloads. + void addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal); // MATLAB code generation - // toolboxPath is the core toolbox directory, e.g., ../matlab - // NOTE: static functions are not inside the class, and - // are created with [ClassName]_[FunctionName]() format + // classPath is class directory, e.g., ../matlab/@Point2 + void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName, + const std::string& wrapperName, const TypeAttributesTable& typeAttributes, + std::vector& functionNames) const; - void matlab_mfile(const std::string& toolboxPath, const std::string& className) const; ///< m-file - void matlab_wrapper(const std::string& toolboxPath, - const std::string& className, const std::string& matlabClassName, - const std::string& cppClassName, - const std::vector& using_namespaces, - const std::vector& includes) const; ///< cpp wrapper +private: + std::string wrapper_fragment(FileWriter& file, + const std::string& cppClassName, + const std::string& matlabUniqueName, + int overload, + int id, + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/TemplateInstantiationTypedef.cpp b/wrap/TemplateInstantiationTypedef.cpp new file mode 100644 index 000000000..b822f732b --- /dev/null +++ b/wrap/TemplateInstantiationTypedef.cpp @@ -0,0 +1,61 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "TemplateInstantiationTypedef.h" + +#include "utilities.h" + +using namespace std; + +namespace wrap { + + Class TemplateInstantiationTypedef::findAndExpand(const vector& classes) const { + // Find matching class + std::vector::const_iterator clsIt = classes.end(); + for(std::vector::const_iterator it = classes.begin(); it != classes.end(); ++it) { + if(it->name == className && it->namespaces == classNamespaces && it->templateArgs.size() == typeList.size()) { + clsIt = it; + break; + } + } + + if(clsIt == classes.end()) + throw DependencyMissing(wrap::qualifiedName("::", classNamespaces, className), + "instantiation into typedef name " + wrap::qualifiedName("::", namespaces, name) + + ". Ensure that the typedef provides the correct number of template arguments."); + + // Instantiate it + Class classInst = *clsIt; + for(size_t i = 0; i < typeList.size(); ++i) + classInst = classInst.expandTemplate(classInst.templateArgs[i], typeList[i], namespaces, name); + + // Fix class properties + classInst.name = name; + classInst.templateArgs.clear(); + classInst.typedefName = clsIt->qualifiedName("::") + "<"; + if(typeList.size() > 0) + classInst.typedefName += wrap::qualifiedName("::", typeList[0]); + for(size_t i = 1; i < typeList.size(); ++i) + classInst.typedefName += (", " + wrap::qualifiedName("::", typeList[i])); + classInst.typedefName += ">"; + classInst.namespaces = namespaces; + + return classInst; + } + +} \ No newline at end of file diff --git a/wrap/TemplateInstantiationTypedef.h b/wrap/TemplateInstantiationTypedef.h new file mode 100644 index 000000000..192d35324 --- /dev/null +++ b/wrap/TemplateInstantiationTypedef.h @@ -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 + + * -------------------------------------------------------------------------- */ + +/** + * @file Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#pragma once + +#include +#include + +#include "Class.h" + +namespace wrap { + +struct TemplateInstantiationTypedef { + std::vector classNamespaces; + std::string className; + std::vector namespaces; + std::string name; + std::vector > typeList; + + Class findAndExpand(const std::vector& classes) const; +}; + +} \ No newline at end of file diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp new file mode 100644 index 000000000..865015a6e --- /dev/null +++ b/wrap/TypeAttributesTable.cpp @@ -0,0 +1,58 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "TypeAttributesTable.h" +#include "Class.h" +#include "utilities.h" + +#include + +using namespace std; + +namespace wrap { + + /* ************************************************************************* */ + void TypeAttributesTable::addClasses(const vector& classes) { + BOOST_FOREACH(const Class& cls, classes) { + if(!insert(make_pair(cls.qualifiedName("::"), TypeAttributes(cls.isVirtual))).second) + throw DuplicateDefinition("class " + cls.qualifiedName("::")); + } + } + + /* ************************************************************************* */ + void TypeAttributesTable::addForwardDeclarations(const vector& forwardDecls) { + BOOST_FOREACH(const ForwardDeclaration& fwDec, forwardDecls) { + if(!insert(make_pair(fwDec.name, TypeAttributes(fwDec.isVirtual))).second) + throw DuplicateDefinition("class " + fwDec.name); + } + } + + /* ************************************************************************* */ + void TypeAttributesTable::checkValidity(const vector& classes) const { + BOOST_FOREACH(const Class& cls, classes) { + // Check that class is virtual if it has a parent + if(!cls.qualifiedParent.empty() && !cls.isVirtual) + throw AttributeError(cls.qualifiedName("::"), "Has a base class so needs to be declared virtual, change to 'virtual class "+cls.name+" ...'"); + // Check that parent is virtual as well + if(!cls.qualifiedParent.empty() && !at(wrap::qualifiedName("::", cls.qualifiedParent)).isVirtual) + throw AttributeError(wrap::qualifiedName("::", cls.qualifiedParent), + "Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual"); + } + } + +} \ No newline at end of file diff --git a/wrap/TypeAttributesTable.h b/wrap/TypeAttributesTable.h new file mode 100644 index 000000000..dea6d0bf5 --- /dev/null +++ b/wrap/TypeAttributesTable.h @@ -0,0 +1,55 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include +#include +#include + +#include "ForwardDeclaration.h" + +#pragma once + +namespace wrap { + + // Forward declarations + struct Class; + +/** Attributes about valid classes, both for classes defined in this module and + * also those forward-declared from others. At the moment this only contains + * whether the class is virtual, which is used to know how to copy the class, + * and whether to try to convert it to a more derived type upon returning it. + */ +struct TypeAttributes { + bool isVirtual; + TypeAttributes() : isVirtual(false) {} + TypeAttributes(bool isVirtual) : isVirtual(isVirtual) {} +}; + +/** Map of type names to attributes. */ +class TypeAttributesTable : public std::map { +public: + TypeAttributesTable() {} + + void addClasses(const std::vector& classes); + void addForwardDeclarations(const std::vector& forwardDecls); + + void checkValidity(const std::vector& classes) const; +}; + +} \ No newline at end of file diff --git a/wrap/matlab.h b/wrap/matlab.h index 2ef81f37f..5b438f1a6 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -1,456 +1,426 @@ -/* ---------------------------------------------------------------------------- - - * 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 matlab.h - * @brief header file to be included in MATLAB wrappers - * @date 2008 - * @author Frank Dellaert - * - * wrapping and unwrapping is done using specialized templates, see - * http://www.cplusplus.com/doc/tutorial/templates.html - */ - -#include -#include - -using gtsam::Vector; -using gtsam::Matrix; - -extern "C" { -#include -} - -#include -#include - -#include -#include -#include - -using namespace std; -using namespace boost; // not usual, but for conciseness of generated code - -// start GTSAM Specifics ///////////////////////////////////////////////// -// to enable Matrix and Vector constructor for SharedGaussian: -#define GTSAM_MAGIC_GAUSSIAN -// end GTSAM Specifics ///////////////////////////////////////////////// - -#ifdef __LP64__ -// 64-bit Mac -#define mxUINT32OR64_CLASS mxUINT64_CLASS -#else -#define mxUINT32OR64_CLASS mxUINT32_CLASS -#endif - -//***************************************************************************** -// Utilities -//***************************************************************************** - -void error(const char* str) { - mexErrMsgIdAndTxt("wrap:error", str); -} - -mxArray *scalar(mxClassID classid) { - mwSize dims[1]; dims[0]=1; - return mxCreateNumericArray(1, dims, classid, mxREAL); -} - -void checkScalar(const mxArray* array, const char* str) { - int m = mxGetM(array), n = mxGetN(array); - if (m!=1 || n!=1) - mexErrMsgIdAndTxt("wrap: not a scalar in ", str); -} - -//***************************************************************************** -// Check arguments -//***************************************************************************** - -void checkArguments(const string& name, int nargout, int nargin, int expected) { - stringstream err; - err << name << " expects " << expected << " arguments, not " << nargin; - if (nargin!=expected) - error(err.str().c_str()); -} - -//***************************************************************************** -// wrapping C++ basis types in MATLAB arrays -//***************************************************************************** - -// default wrapping throws an error: only basis types are allowed in wrap -template -mxArray* wrap(Class& value) { - error("wrap internal error: attempted wrap of invalid type"); -} - -// specialization to string -// wraps into a character array -template<> -mxArray* wrap(string& value) { - return mxCreateString(value.c_str()); -} - -// specialization to char -template<> -mxArray* wrap(char& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(char*)mxGetData(result) = value; - return result; -} - -// specialization to bool -template<> -mxArray* wrap(bool& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(bool*)mxGetData(result) = value; - return result; -} - -// specialization to size_t -template<> -mxArray* wrap(size_t& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(size_t*)mxGetData(result) = value; - return result; -} - -// specialization to int -template<> -mxArray* wrap(int& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(int*)mxGetData(result) = value; - return result; -} - -// specialization to double -> just double -template<> -mxArray* wrap(double& value) { - return mxCreateDoubleScalar(value); -} - -// wrap a const Eigen vector into a double vector -mxArray* wrap_Vector(const gtsam::Vector& v) { - int m = v.size(); - mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL); - double *data = mxGetPr(result); - for (int i=0;i double vector -template<> -mxArray* wrap(gtsam::Vector& v) { - return wrap_Vector(v); -} - -// const version -template<> -mxArray* wrap(const gtsam::Vector& v) { - return wrap_Vector(v); -} - -// wrap a const Eigen MATRIX into a double matrix -mxArray* wrap_Matrix(const gtsam::Matrix& A) { - int m = A.rows(), n = A.cols(); -#ifdef DEBUG_WRAP - mexPrintf("wrap_Matrix called with A = \n", m,n); - gtsam::print(A); -#endif - mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL); - double *data = mxGetPr(result); - // converts from column-major to row-major - for (int j=0;j double matrix -template<> -mxArray* wrap(gtsam::Matrix& A) { - return wrap_Matrix(A); -} - -// const version -template<> -mxArray* wrap(const gtsam::Matrix& A) { - return wrap_Matrix(A); -} - -//***************************************************************************** -// unwrapping MATLAB arrays into C++ basis types -//***************************************************************************** - -// default unwrapping throws an error -// as wrap only supports passing a reference or one of the basic types -template -T unwrap(const mxArray* array) { - error("wrap internal error: attempted unwrap of invalid type"); -} - -// specialization to string -// expects a character array -// Warning: relies on mxChar==char -template<> -string unwrap(const mxArray* array) { - char *data = mxArrayToString(array); - if (data==NULL) error("unwrap: not a character array"); - string str(data); - mxFree(data); - return str; -} - -// specialization to bool -template<> -bool unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return mxGetScalar(array) != 0.0; -} - -// specialization to bool -template<> -char unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return (char)mxGetScalar(array); -} - -// specialization to size_t -template<> -size_t unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return (size_t)mxGetScalar(array); -} - -// specialization to int -template<> -int unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return (int)mxGetScalar(array); -} - -// specialization to double -template<> -double unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return (double)mxGetScalar(array); -} - -// specialization to Eigen vector -template<> -gtsam::Vector unwrap< gtsam::Vector >(const mxArray* array) { - int m = mxGetM(array), n = mxGetN(array); - if (mxIsDouble(array)==false || n!=1) error("unwrap: not a vector"); -#ifdef DEBUG_WRAP - mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n); -#endif - double* data = (double*)mxGetData(array); - gtsam::Vector v(m); - for (int i=0;i -gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) { - if (mxIsDouble(array)==false) error("unwrap: not a matrix"); - int m = mxGetM(array), n = mxGetN(array); -#ifdef DEBUG_WRAP - mexPrintf("unwrap< gtsam::Matrix > called with %dx%d argument\n", m,n); -#endif - double* data = (double*)mxGetData(array); - gtsam::Matrix A(m,n); - // converts from row-major to column-major - for (int j=0;j -class ObjectHandle { -private: - ObjectHandle* signature; // use 'this' as a unique object signature - const std::type_info* type; // type checking information - shared_ptr t; // object pointer - -public: - // Constructor for free-store allocated objects. - // Creates shared pointer, will delete if is last one to hold pointer - ObjectHandle(T* ptr) : - type(&typeid(T)), t(shared_ptr (ptr)) { - signature = this; - } - - // Constructor for shared pointers - // Creates shared pointer, will delete if is last one to hold pointer - ObjectHandle(shared_ptr ptr) : - /*type(&typeid(T)),*/ t(ptr) { - signature = this; - } - - ~ObjectHandle() { - // object is in shared_ptr, will be automatically deleted - signature = 0; // destroy signature - } - - // Get the actual object contained by handle - shared_ptr get_object() const { - return t; - } - - // Print the mexhandle for debugging - void print(const char* str) { - mexPrintf("mexhandle %s:\n", str); - mexPrintf(" signature = %d:\n", signature); - mexPrintf(" pointer = %d:\n", t.get()); - } - - // Convert ObjectHandle to a mxArray handle (to pass back from mex-function). - // Create a numeric array as handle for an ObjectHandle. - // We ASSUME we can store object pointer in the mxUINT32 element of mxArray. - mxArray* to_mex_handle() { - mxArray* handle = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast**> (mxGetPr(handle)) = this; - return handle; - } - - string type_name() const { - return type->name(); - } - - // Convert mxArray (passed to mex-function) to an ObjectHandle. - // Import a handle from MatLab as a mxArray of UINT32. Check that - // it is actually a pointer to an ObjectHandle. - static ObjectHandle* from_mex_handle(const mxArray* handle) { - if (mxGetClassID(handle) != mxUINT32OR64_CLASS || mxIsComplex(handle) - || mxGetM(handle) != 1 || mxGetN(handle) != 1) error( - "Parameter is not an ObjectHandle type."); - - // We *assume* we can store ObjectHandle pointer in the mxUINT32 of handle - ObjectHandle* obj = *reinterpret_cast (mxGetPr(handle)); - - if (!obj) // gross check to see we don't have an invalid pointer - error("Parameter is NULL. It does not represent an ObjectHandle object."); - // TODO: change this for max-min check for pointer values - - if (obj->signature != obj) // check memory has correct signature - error("Parameter does not represent an ObjectHandle object."); - - /* - if (*(obj->type) != typeid(T)) { // check type - mexPrintf("Given: <%s>, Required: <%s>.\n", obj->type_name(), typeid(T).name()); - error("Given ObjectHandle does not represent the correct type."); - } - */ - - return obj; - } - -}; - -//***************************************************************************** -// wrapping C++ objects in a MATLAB proxy class -//***************************************************************************** - -/* - For every C++ class Class, a matlab proxy class @Class/Class.m object - is created. Its constructor will check which of the C++ constructors - needs to be called, based on nr of arguments. It then calls the - corresponding mex function new_Class_signature, which will create a - C++ object using new, and pass the pointer to wrap_constructed - (below). This creates a mexhandle and returns it to the proxy class - constructor, which assigns it to self. Matlab owns this handle now. -*/ -template -mxArray* wrap_constructed(Class* pointer, const char *classname) { - ObjectHandle* handle = new ObjectHandle(pointer); - return handle->to_mex_handle(); -} - -/* - [create_object] creates a MATLAB proxy class object with a mexhandle - in the self property. Matlab does not allow the creation of matlab - objects from within mex files, hence we resort to an ugly trick: we - invoke the proxy class constructor by calling MATLAB, and pass 13 - dummy arguments to let the constructor know we want an object without - the self property initialized. We then assign the mexhandle to self. -*/ -// TODO: think about memory -mxArray* create_object(const char *classname, mxArray* h) { - mxArray *result; - mxArray* dummy[13] = {h,h,h,h,h, h,h,h,h,h, h,h,h}; - mexCallMATLAB(1,&result,13,dummy,classname); - mxSetProperty(result, 0, "self", h); - return result; -} - -/* - When the user calls a method that returns a shared pointer, we create - an ObjectHandle from the shared_pointer and return it as a proxy - class to matlab. -*/ -template -mxArray* wrap_shared_ptr(shared_ptr< Class > shared_ptr, const char *classname) { - ObjectHandle* handle = new ObjectHandle(shared_ptr); - return create_object(classname,handle->to_mex_handle()); -} - -//***************************************************************************** -// unwrapping a MATLAB proxy class to a C++ object reference -//***************************************************************************** - -/* - Besides the basis types, the only other argument type allowed is a - shared pointer to a C++ object. In this case, matlab needs to pass a - proxy class object to the mex function. [unwrap_shared_ptr] extracts - the ObjectHandle from the self property, and returns a shared pointer - to the object. -*/ -template -shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { - //Why is this here? -#ifndef UNSAFE_WRAP - bool isClass = mxIsClass(obj, className.c_str()); - if (!isClass) { - mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); -} - -template -void delete_shared_ptr(const mxArray* obj, const string& className) { - //Why is this here? -#ifndef UNSAFE_WRAP - bool isClass = true;//mxIsClass(obj, className.c_str()); - if (!isClass) { - mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - delete handle; -} - -//***************************************************************************** +/* ---------------------------------------------------------------------------- + + * 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 matlab.h + * @brief header file to be included in MATLAB wrappers + * @date 2008 + * @author Frank Dellaert + * @author Alex Cunningham + * @author Andrew Melim + * @author Richard Roberts + * + * wrapping and unwrapping is done using specialized templates, see + * http://www.cplusplus.com/doc/tutorial/templates.html + */ + +#include +#include + +using gtsam::Vector; +using gtsam::Matrix; + +extern "C" { +#include +} + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace boost; // not usual, but for conciseness of generated code + +// start GTSAM Specifics ///////////////////////////////////////////////// +// to enable Matrix and Vector constructor for SharedGaussian: +#define GTSAM_MAGIC_GAUSSIAN +// end GTSAM Specifics ///////////////////////////////////////////////// + +#if defined(__LP64__) || defined(_WIN64) +// 64-bit +#define mxUINT32OR64_CLASS mxUINT64_CLASS +#else +#define mxUINT32OR64_CLASS mxUINT32_CLASS +#endif + +// "Unique" key to signal calling the matlab object constructor with a raw pointer +// to a shared pointer of the same C++ object type as the MATLAB type. +// Also present in utilities.h +static const uint64_t ptr_constructor_key = + (uint64_t('G') << 56) | + (uint64_t('T') << 48) | + (uint64_t('S') << 40) | + (uint64_t('A') << 32) | + (uint64_t('M') << 24) | + (uint64_t('p') << 16) | + (uint64_t('t') << 8) | + (uint64_t('r')); + +//***************************************************************************** +// Utilities +//***************************************************************************** + +void error(const char* str) { + mexErrMsgIdAndTxt("wrap:error", str); +} + +mxArray *scalar(mxClassID classid) { + mwSize dims[1]; dims[0]=1; + return mxCreateNumericArray(1, dims, classid, mxREAL); +} + +void checkScalar(const mxArray* array, const char* str) { + int m = mxGetM(array), n = mxGetN(array); + if (m!=1 || n!=1) + mexErrMsgIdAndTxt("wrap: not a scalar in ", str); +} + +// Replacement streambuf for cout that writes to the MATLAB console +// Thanks to http://stackoverflow.com/a/249008 +class mstream : public std::streambuf { +protected: + virtual std::streamsize xsputn(const char *s, std::streamsize n) { + mexPrintf("%.*s",n,s); + return n; + } + virtual int overflow(int c = EOF) { + if (c != EOF) { + mexPrintf("%.1s",&c); + } + return 1; + } +}; + +//***************************************************************************** +// Check arguments +//***************************************************************************** + +void checkArguments(const string& name, int nargout, int nargin, int expected) { + stringstream err; + err << name << " expects " << expected << " arguments, not " << nargin; + if (nargin!=expected) + error(err.str().c_str()); +} + +//***************************************************************************** +// wrapping C++ basis types in MATLAB arrays +//***************************************************************************** + +// default wrapping throws an error: only basis types are allowed in wrap +template +mxArray* wrap(const Class& value) { + error("wrap internal error: attempted wrap of invalid type"); + return 0; +} + +// specialization to string +// wraps into a character array +template<> +mxArray* wrap(const string& value) { + return mxCreateString(value.c_str()); +} + +// specialization to char +template<> +mxArray* wrap(const char& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(char*)mxGetData(result) = value; + return result; +} + +// specialization to unsigned char +template<> +mxArray* wrap(const unsigned char& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(unsigned char*)mxGetData(result) = value; + return result; +} + +// specialization to bool +template<> +mxArray* wrap(const bool& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(bool*)mxGetData(result) = value; + return result; +} + +// specialization to size_t +template<> +mxArray* wrap(const size_t& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(size_t*)mxGetData(result) = value; + return result; +} + +// specialization to int +template<> +mxArray* wrap(const int& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(int*)mxGetData(result) = value; + return result; +} + +// specialization to double -> just double +template<> +mxArray* wrap(const double& value) { + return mxCreateDoubleScalar(value); +} + +// wrap a const Eigen vector into a double vector +mxArray* wrap_Vector(const gtsam::Vector& v) { + int m = v.size(); + mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL); + double *data = mxGetPr(result); + for (int i=0;i double vector +template<> +mxArray* wrap(const gtsam::Vector& v) { + return wrap_Vector(v); +} + +// wrap a const Eigen MATRIX into a double matrix +mxArray* wrap_Matrix(const gtsam::Matrix& A) { + int m = A.rows(), n = A.cols(); +#ifdef DEBUG_WRAP + mexPrintf("wrap_Matrix called with A = \n", m,n); + gtsam::print(A); +#endif + mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL); + double *data = mxGetPr(result); + // converts from column-major to row-major + for (int j=0;j double matrix +template<> +mxArray* wrap(const gtsam::Matrix& A) { + return wrap_Matrix(A); +} + +//***************************************************************************** +// unwrapping MATLAB arrays into C++ basis types +//***************************************************************************** + +// default unwrapping throws an error +// as wrap only supports passing a reference or one of the basic types +template +T unwrap(const mxArray* array) { + error("wrap internal error: attempted unwrap of invalid type"); +} + +// specialization to string +// expects a character array +// Warning: relies on mxChar==char +template<> +string unwrap(const mxArray* array) { + char *data = mxArrayToString(array); + if (data==NULL) error("unwrap: not a character array"); + string str(data); + mxFree(data); + return str; +} + +// Check for 64-bit, as Mathworks says mxGetScalar only good for 32 bit +template +T myGetScalar(const mxArray* array) { + switch (mxGetClassID(array)) { + case mxINT64_CLASS: + return (T) *(int64_t*) mxGetData(array); + case mxUINT64_CLASS: + return (T) *(uint64_t*) mxGetData(array); + default: + // hope for the best! + return (T) mxGetScalar(array); + } +} + +// specialization to bool +template<> +bool unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// 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) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to size_t +template<> +size_t unwrap(const mxArray* array) { + checkScalar(array, "unwrap"); + return myGetScalar(array); +} + +// specialization to double +template<> +double unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to Eigen vector +template<> +gtsam::Vector unwrap< gtsam::Vector >(const mxArray* array) { + int m = mxGetM(array), n = mxGetN(array); + if (mxIsDouble(array)==false || n!=1) error("unwrap: not a vector"); +#ifdef DEBUG_WRAP + mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n); +#endif + double* data = (double*)mxGetData(array); + gtsam::Vector v(m); + for (int i=0;i +gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) { + if (mxIsDouble(array)==false) error("unwrap: not a matrix"); + int m = mxGetM(array), n = mxGetN(array); +#ifdef DEBUG_WRAP + mexPrintf("unwrap< gtsam::Matrix > called with %dx%d argument\n", m,n); +#endif + double* data = (double*)mxGetData(array); + gtsam::Matrix A(m,n); + // converts from row-major to column-major + for (int j=0;j(mxGetData(input[0])) = ptr_constructor_key; + // Second input argument is the pointer + input[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(input[1])) = pointer; + // If the class is virtual, use the RTTI name to look up the derived matlab type + const char *derivedClassName; + if(isVirtual) { + const mxArray *rttiRegistry = mexGetVariablePtr("global", "gtsamwrap_rttiRegistry"); + if(!rttiRegistry) + mexErrMsgTxt( + "gtsam wrap: RTTI registry is missing - it could have been cleared from the workspace." + " You can issue 'clear all' to completely clear the workspace, and next time a wrapped object is" + " created the RTTI registry will be recreated."); + const mxArray *derivedNameMx = mxGetField(rttiRegistry, 0, rttiName); + if(!derivedNameMx) + mexErrMsgTxt(( + "gtsam wrap: The derived class type " + string(rttiName) + " was not found in the RTTI registry. " + "Try calling 'clear all' twice consecutively - we have seen things not get unloaded properly the " + "first time. If this does not work, this may indicate an inconsistency in your wrap interface file. " + "The most likely cause for this is that a base class was marked virtual in the wrap interface " + "definition header file for gtsam or for your module, but a derived type was returned by a C++ " + "function and that derived type was not marked virtual (or was not specified in the wrap interface " + "definition header at all).").c_str()); + size_t strLen = mxGetN(derivedNameMx); + char *buf = new char[strLen+1]; + if(mxGetString(derivedNameMx, buf, strLen+1)) + mexErrMsgTxt("gtsam wrap: Internal error reading RTTI table, try 'clear all' to clear your workspace and reinitialize the toolbox."); + derivedClassName = buf; + input[2] = mxCreateString("void"); + nargin = 3; + } else { + derivedClassName = classname.c_str(); + } + // Call special pointer constructor, which sets 'self' + mexCallMATLAB(1,&result, nargin, input, derivedClassName); + // Deallocate our memory + mxDestroyArray(input[0]); + mxDestroyArray(input[1]); + if(isVirtual) { + mxDestroyArray(input[2]); + delete[] derivedClassName; + } + return result; +} + +/* + When the user calls a method that returns a shared pointer, we create + an ObjectHandle from the shared_pointer and return it as a proxy + class to matlab. +*/ +template +mxArray* wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string& matlabName, bool isVirtual) { + // Create actual class object from out pointer + mxArray* result; + if(isVirtual) { + boost::shared_ptr void_ptr(shared_ptr); + result = create_object(matlabName, &void_ptr, isVirtual, typeid(*shared_ptr).name()); + } else { + boost::shared_ptr *heapPtr = new boost::shared_ptr(shared_ptr); + result = create_object(matlabName, heapPtr, isVirtual, ""); + } + return result; +} + +template +boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& propertyName) { + + mxArray* mxh = mxGetProperty(obj,0, propertyName.c_str()); + if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh) + || mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error( + "Parameter is not an Shared type."); + + boost::shared_ptr* spp = *reinterpret_cast**> (mxGetData(mxh)); + return *spp; +} diff --git a/wrap/tests/expected/@Point2/Point2.m b/wrap/tests/expected/@Point2/Point2.m deleted file mode 100644 index 454d81399..000000000 --- a/wrap/tests/expected/@Point2/Point2.m +++ /dev/null @@ -1,18 +0,0 @@ -% automatically generated by wrap -classdef Point2 < handle - properties - self = 0 - end - methods - function obj = Point2(varargin) - if (nargin == 0), obj.self = new_Point2_(); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2_dd(varargin{1},varargin{2}); end - if nargin ~= 13 && obj.self == 0, error('Point2 constructor failed'); end - end - function delete(obj) - delete_Point2(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Point2/argChar.cpp b/wrap/tests/expected/@Point2/argChar.cpp deleted file mode 100644 index 017fe1761..000000000 --- a/wrap/tests/expected/@Point2/argChar.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - char a = unwrap< char >(in[1]); - self->argChar(a); -} diff --git a/wrap/tests/expected/@Point2/argChar.m b/wrap/tests/expected/@Point2/argChar.m deleted file mode 100644 index 3eccf4b76..000000000 --- a/wrap/tests/expected/@Point2/argChar.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = argChar(obj,a) -% usage: obj.argChar(a) - error('need to compile argChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/argUChar.cpp b/wrap/tests/expected/@Point2/argUChar.cpp deleted file mode 100644 index 341e4f8a7..000000000 --- a/wrap/tests/expected/@Point2/argUChar.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argUChar",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - unsigned char a = unwrap< unsigned char >(in[1]); - self->argUChar(a); -} diff --git a/wrap/tests/expected/@Point2/argUChar.m b/wrap/tests/expected/@Point2/argUChar.m deleted file mode 100644 index eedb50df0..000000000 --- a/wrap/tests/expected/@Point2/argUChar.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = argUChar(obj,a) -% usage: obj.argUChar(a) - error('need to compile argUChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/dim.cpp b/wrap/tests/expected/@Point2/dim.cpp deleted file mode 100644 index 454153690..000000000 --- a/wrap/tests/expected/@Point2/dim.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("dim",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - int result = self->dim(); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected/@Point2/dim.m b/wrap/tests/expected/@Point2/dim.m deleted file mode 100644 index 011eb28a7..000000000 --- a/wrap/tests/expected/@Point2/dim.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = dim(obj) -% usage: obj.dim() - error('need to compile dim.cpp'); -end diff --git a/wrap/tests/expected/@Point2/returnChar.cpp b/wrap/tests/expected/@Point2/returnChar.cpp deleted file mode 100644 index 3b7733862..000000000 --- a/wrap/tests/expected/@Point2/returnChar.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("returnChar",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - char result = self->returnChar(); - out[0] = wrap< char >(result); -} diff --git a/wrap/tests/expected/@Point2/returnChar.m b/wrap/tests/expected/@Point2/returnChar.m deleted file mode 100644 index c9334a503..000000000 --- a/wrap/tests/expected/@Point2/returnChar.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = returnChar(obj) -% usage: obj.returnChar() - error('need to compile returnChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/vectorConfusion.cpp b/wrap/tests/expected/@Point2/vectorConfusion.cpp deleted file mode 100644 index 90be4194b..000000000 --- a/wrap/tests/expected/@Point2/vectorConfusion.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("vectorConfusion",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - VectorNotEigen result = self->vectorConfusion(); - out[0] = wrap_shared_ptr(make_shared< VectorNotEigen >(result),"VectorNotEigen"); -} diff --git a/wrap/tests/expected/@Point2/vectorConfusion.m b/wrap/tests/expected/@Point2/vectorConfusion.m deleted file mode 100644 index 0db1db291..000000000 --- a/wrap/tests/expected/@Point2/vectorConfusion.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = vectorConfusion(obj) -% usage: obj.vectorConfusion() - error('need to compile vectorConfusion.cpp'); -end diff --git a/wrap/tests/expected/@Point2/x.cpp b/wrap/tests/expected/@Point2/x.cpp deleted file mode 100644 index 8df8c6bbc..000000000 --- a/wrap/tests/expected/@Point2/x.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("x",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - double result = self->x(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point2/x.m b/wrap/tests/expected/@Point2/x.m deleted file mode 100644 index 0a6e99d16..000000000 --- a/wrap/tests/expected/@Point2/x.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = x(obj) -% usage: obj.x() - error('need to compile x.cpp'); -end diff --git a/wrap/tests/expected/@Point2/y.cpp b/wrap/tests/expected/@Point2/y.cpp deleted file mode 100644 index 14e3663ed..000000000 --- a/wrap/tests/expected/@Point2/y.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("y",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - double result = self->y(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point2/y.m b/wrap/tests/expected/@Point2/y.m deleted file mode 100644 index ee5a55e1d..000000000 --- a/wrap/tests/expected/@Point2/y.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = y(obj) -% usage: obj.y() - error('need to compile y.cpp'); -end diff --git a/wrap/tests/expected/@Point3/Point3.m b/wrap/tests/expected/@Point3/Point3.m deleted file mode 100644 index 3e7a6fd65..000000000 --- a/wrap/tests/expected/@Point3/Point3.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef Point3 < handle - properties - self = 0 - end - methods - function obj = Point3(varargin) - if (nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')), obj.self = new_Point3_ddd(varargin{1},varargin{2},varargin{3}); end - if nargin ~= 13 && obj.self == 0, error('Point3 constructor failed'); end - end - function delete(obj) - delete_Point3(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Point3/norm.cpp b/wrap/tests/expected/@Point3/norm.cpp deleted file mode 100644 index 9936958d7..000000000 --- a/wrap/tests/expected/@Point3/norm.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("norm",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Point3 >(in[0],"Point3"); - double result = self->norm(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point3/norm.m b/wrap/tests/expected/@Point3/norm.m deleted file mode 100644 index bb6482df4..000000000 --- a/wrap/tests/expected/@Point3/norm.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = norm(obj) -% usage: obj.norm() - error('need to compile norm.cpp'); -end diff --git a/wrap/tests/expected/@Test/Test.m b/wrap/tests/expected/@Test/Test.m deleted file mode 100644 index b8e55381c..000000000 --- a/wrap/tests/expected/@Test/Test.m +++ /dev/null @@ -1,18 +0,0 @@ -% automatically generated by wrap -classdef Test < handle - properties - self = 0 - end - methods - function obj = Test(varargin) - if (nargin == 0), obj.self = new_Test_(); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test_dM(varargin{1},varargin{2}); end - if nargin ~= 13 && obj.self == 0, error('Test constructor failed'); end - end - function delete(obj) - delete_Test(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp deleted file mode 100644 index 487741c07..000000000 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("arg_EigenConstRef",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix"); - self->arg_EigenConstRef(value); -} diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.m b/wrap/tests/expected/@Test/arg_EigenConstRef.m deleted file mode 100644 index 76f190d99..000000000 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = arg_EigenConstRef(obj,value) -% usage: obj.arg_EigenConstRef(value) - error('need to compile arg_EigenConstRef.cpp'); -end diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.cpp b/wrap/tests/expected/@Test/create_MixedPtrs.cpp deleted file mode 100644 index 269bb990c..000000000 --- a/wrap/tests/expected/@Test/create_MixedPtrs.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_MixedPtrs",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - pair< Test, shared_ptr > result = self->create_MixedPtrs(); - out[0] = wrap_shared_ptr(make_shared< Test >(result.first),"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); -} diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.m b/wrap/tests/expected/@Test/create_MixedPtrs.m deleted file mode 100644 index 764ce822c..000000000 --- a/wrap/tests/expected/@Test/create_MixedPtrs.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function [first,second] = create_MixedPtrs(obj) -% usage: obj.create_MixedPtrs() - error('need to compile create_MixedPtrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/create_ptrs.cpp b/wrap/tests/expected/@Test/create_ptrs.cpp deleted file mode 100644 index bfd9f39bf..000000000 --- a/wrap/tests/expected/@Test/create_ptrs.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_ptrs",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - pair< shared_ptr, shared_ptr > result = self->create_ptrs(); - out[0] = wrap_shared_ptr(result.first,"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); -} diff --git a/wrap/tests/expected/@Test/create_ptrs.m b/wrap/tests/expected/@Test/create_ptrs.m deleted file mode 100644 index b1623b5bc..000000000 --- a/wrap/tests/expected/@Test/create_ptrs.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function [first,second] = create_ptrs(obj) -% usage: obj.create_ptrs() - error('need to compile create_ptrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/print.cpp b/wrap/tests/expected/@Test/print.cpp deleted file mode 100644 index e93f5f09a..000000000 --- a/wrap/tests/expected/@Test/print.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("print",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - self->print(); -} diff --git a/wrap/tests/expected/@Test/print.m b/wrap/tests/expected/@Test/print.m deleted file mode 100644 index 2adca017d..000000000 --- a/wrap/tests/expected/@Test/print.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = print(obj) -% usage: obj.print() - error('need to compile print.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.cpp b/wrap/tests/expected/@Test/return_Point2Ptr.cpp deleted file mode 100644 index 9ad2a4360..000000000 --- a/wrap/tests/expected/@Test/return_Point2Ptr.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Point2Ptr",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - bool value = unwrap< bool >(in[1]); - shared_ptr result = self->return_Point2Ptr(value); - out[0] = wrap_shared_ptr(result,"Point2"); -} diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.m b/wrap/tests/expected/@Test/return_Point2Ptr.m deleted file mode 100644 index 410081dcb..000000000 --- a/wrap/tests/expected/@Test/return_Point2Ptr.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_Point2Ptr(obj,value) -% usage: obj.return_Point2Ptr(value) - error('need to compile return_Point2Ptr.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_Test.cpp b/wrap/tests/expected/@Test/return_Test.cpp deleted file mode 100644 index 73c63a899..000000000 --- a/wrap/tests/expected/@Test/return_Test.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Test",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - Test result = self->return_Test(value); - out[0] = wrap_shared_ptr(make_shared< Test >(result),"Test"); -} diff --git a/wrap/tests/expected/@Test/return_Test.m b/wrap/tests/expected/@Test/return_Test.m deleted file mode 100644 index 2faa73be3..000000000 --- a/wrap/tests/expected/@Test/return_Test.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_Test(obj,value) -% usage: obj.return_Test(value) - error('need to compile return_Test.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_TestPtr.cpp b/wrap/tests/expected/@Test/return_TestPtr.cpp deleted file mode 100644 index 607e48cfd..000000000 --- a/wrap/tests/expected/@Test/return_TestPtr.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_TestPtr",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - shared_ptr result = self->return_TestPtr(value); - out[0] = wrap_shared_ptr(result,"Test"); -} diff --git a/wrap/tests/expected/@Test/return_TestPtr.m b/wrap/tests/expected/@Test/return_TestPtr.m deleted file mode 100644 index 7c40e76c6..000000000 --- a/wrap/tests/expected/@Test/return_TestPtr.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_TestPtr(obj,value) -% usage: obj.return_TestPtr(value) - error('need to compile return_TestPtr.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_bool.cpp b/wrap/tests/expected/@Test/return_bool.cpp deleted file mode 100644 index d700ead2b..000000000 --- a/wrap/tests/expected/@Test/return_bool.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_bool",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - bool value = unwrap< bool >(in[1]); - bool result = self->return_bool(value); - out[0] = wrap< bool >(result); -} diff --git a/wrap/tests/expected/@Test/return_bool.m b/wrap/tests/expected/@Test/return_bool.m deleted file mode 100644 index 76fc4363b..000000000 --- a/wrap/tests/expected/@Test/return_bool.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_bool(obj,value) -% usage: obj.return_bool(value) - error('need to compile return_bool.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_double.cpp b/wrap/tests/expected/@Test/return_double.cpp deleted file mode 100644 index 38770e1cd..000000000 --- a/wrap/tests/expected/@Test/return_double.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_double",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - double value = unwrap< double >(in[1]); - double result = self->return_double(value); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Test/return_double.m b/wrap/tests/expected/@Test/return_double.m deleted file mode 100644 index daed1d34b..000000000 --- a/wrap/tests/expected/@Test/return_double.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_double(obj,value) -% usage: obj.return_double(value) - error('need to compile return_double.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_field.cpp b/wrap/tests/expected/@Test/return_field.cpp deleted file mode 100644 index b5e067801..000000000 --- a/wrap/tests/expected/@Test/return_field.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_field",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Test& t = *unwrap_shared_ptr< Test >(in[1], "Test"); - bool result = self->return_field(t); - out[0] = wrap< bool >(result); -} diff --git a/wrap/tests/expected/@Test/return_field.m b/wrap/tests/expected/@Test/return_field.m deleted file mode 100644 index 11b5ebe07..000000000 --- a/wrap/tests/expected/@Test/return_field.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_field(obj,t) -% usage: obj.return_field(t) - error('need to compile return_field.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_int.cpp b/wrap/tests/expected/@Test/return_int.cpp deleted file mode 100644 index e2dfd25e8..000000000 --- a/wrap/tests/expected/@Test/return_int.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_int",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - int value = unwrap< int >(in[1]); - int result = self->return_int(value); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected/@Test/return_int.m b/wrap/tests/expected/@Test/return_int.m deleted file mode 100644 index a6783acdf..000000000 --- a/wrap/tests/expected/@Test/return_int.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_int(obj,value) -% usage: obj.return_int(value) - error('need to compile return_int.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_matrix1.cpp b/wrap/tests/expected/@Test/return_matrix1.cpp deleted file mode 100644 index 8bb9acff8..000000000 --- a/wrap/tests/expected/@Test/return_matrix1.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix1",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = self->return_matrix1(value); - out[0] = wrap< Matrix >(result); -} diff --git a/wrap/tests/expected/@Test/return_matrix1.m b/wrap/tests/expected/@Test/return_matrix1.m deleted file mode 100644 index 302f15372..000000000 --- a/wrap/tests/expected/@Test/return_matrix1.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_matrix1(obj,value) -% usage: obj.return_matrix1(value) - error('need to compile return_matrix1.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_matrix2.cpp b/wrap/tests/expected/@Test/return_matrix2.cpp deleted file mode 100644 index f1a22da47..000000000 --- a/wrap/tests/expected/@Test/return_matrix2.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix2",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = self->return_matrix2(value); - out[0] = wrap< Matrix >(result); -} diff --git a/wrap/tests/expected/@Test/return_matrix2.m b/wrap/tests/expected/@Test/return_matrix2.m deleted file mode 100644 index 3ed4d0ec7..000000000 --- a/wrap/tests/expected/@Test/return_matrix2.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_matrix2(obj,value) -% usage: obj.return_matrix2(value) - error('need to compile return_matrix2.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_pair.cpp b/wrap/tests/expected/@Test/return_pair.cpp deleted file mode 100644 index 8f6949d7c..000000000 --- a/wrap/tests/expected/@Test/return_pair.cpp +++ /dev/null @@ -1,14 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_pair",nargout,nargin-1,2); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector v = unwrap< Vector >(in[1]); - Matrix A = unwrap< Matrix >(in[2]); - pair< Vector, Matrix > result = self->return_pair(v,A); - out[0] = wrap< Vector >(result.first); - out[1] = wrap< Matrix >(result.second); -} diff --git a/wrap/tests/expected/@Test/return_pair.m b/wrap/tests/expected/@Test/return_pair.m deleted file mode 100644 index abb97336c..000000000 --- a/wrap/tests/expected/@Test/return_pair.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function [first,second] = return_pair(obj,v,A) -% usage: obj.return_pair(v,A) - error('need to compile return_pair.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_ptrs.cpp b/wrap/tests/expected/@Test/return_ptrs.cpp deleted file mode 100644 index 20d6c57fe..000000000 --- a/wrap/tests/expected/@Test/return_ptrs.cpp +++ /dev/null @@ -1,14 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_ptrs",nargout,nargin-1,2); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "Test"); - shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "Test"); - pair< shared_ptr, shared_ptr > result = self->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(result.first,"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); -} diff --git a/wrap/tests/expected/@Test/return_ptrs.m b/wrap/tests/expected/@Test/return_ptrs.m deleted file mode 100644 index bed198563..000000000 --- a/wrap/tests/expected/@Test/return_ptrs.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function [first,second] = return_ptrs(obj,p1,p2) -% usage: obj.return_ptrs(p1,p2) - error('need to compile return_ptrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_size_t.cpp b/wrap/tests/expected/@Test/return_size_t.cpp deleted file mode 100644 index 6b12a167b..000000000 --- a/wrap/tests/expected/@Test/return_size_t.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_size_t",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - size_t value = unwrap< size_t >(in[1]); - size_t result = self->return_size_t(value); - out[0] = wrap< size_t >(result); -} diff --git a/wrap/tests/expected/@Test/return_size_t.m b/wrap/tests/expected/@Test/return_size_t.m deleted file mode 100644 index 7cb2c6f0f..000000000 --- a/wrap/tests/expected/@Test/return_size_t.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_size_t(obj,value) -% usage: obj.return_size_t(value) - error('need to compile return_size_t.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_string.cpp b/wrap/tests/expected/@Test/return_string.cpp deleted file mode 100644 index c05a57fba..000000000 --- a/wrap/tests/expected/@Test/return_string.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_string",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - string value = unwrap< string >(in[1]); - string result = self->return_string(value); - out[0] = wrap< string >(result); -} diff --git a/wrap/tests/expected/@Test/return_string.m b/wrap/tests/expected/@Test/return_string.m deleted file mode 100644 index 5661df443..000000000 --- a/wrap/tests/expected/@Test/return_string.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_string(obj,value) -% usage: obj.return_string(value) - error('need to compile return_string.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_vector1.cpp b/wrap/tests/expected/@Test/return_vector1.cpp deleted file mode 100644 index 3710e5d48..000000000 --- a/wrap/tests/expected/@Test/return_vector1.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector1",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = self->return_vector1(value); - out[0] = wrap< Vector >(result); -} diff --git a/wrap/tests/expected/@Test/return_vector1.m b/wrap/tests/expected/@Test/return_vector1.m deleted file mode 100644 index 3746c4c20..000000000 --- a/wrap/tests/expected/@Test/return_vector1.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_vector1(obj,value) -% usage: obj.return_vector1(value) - error('need to compile return_vector1.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_vector2.cpp b/wrap/tests/expected/@Test/return_vector2.cpp deleted file mode 100644 index 72564f05c..000000000 --- a/wrap/tests/expected/@Test/return_vector2.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector2",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = self->return_vector2(value); - out[0] = wrap< Vector >(result); -} diff --git a/wrap/tests/expected/@Test/return_vector2.m b/wrap/tests/expected/@Test/return_vector2.m deleted file mode 100644 index 426c63457..000000000 --- a/wrap/tests/expected/@Test/return_vector2.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = return_vector2(obj,value) -% usage: obj.return_vector2(value) - error('need to compile return_vector2.cpp'); -end diff --git a/wrap/tests/expected/Makefile b/wrap/tests/expected/Makefile deleted file mode 100644 index a8959757b..000000000 --- a/wrap/tests/expected/Makefile +++ /dev/null @@ -1,103 +0,0 @@ -# automatically generated by wrap - -MEX = mex -MEXENDING = mexa64 -mex_flags = -O5 - -all: Point2 Point3 Test - -# Point2 -new_Point2_.$(MEXENDING): new_Point2_.cpp - $(MEX) $(mex_flags) new_Point2_.cpp -output new_Point2_ -new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp - $(MEX) $(mex_flags) new_Point2_dd.cpp -output new_Point2_dd -delete_Point2.$(MEXENDING): delete_Point2.cpp - $(MEX) $(mex_flags) delete_Point2.cpp -output delete_Point2 -@Point2/x.$(MEXENDING): @Point2/x.cpp - $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x -@Point2/y.$(MEXENDING): @Point2/y.cpp - $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y -@Point2/dim.$(MEXENDING): @Point2/dim.cpp - $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim -@Point2/returnChar.$(MEXENDING): @Point2/returnChar.cpp - $(MEX) $(mex_flags) @Point2/returnChar.cpp -output @Point2/returnChar -@Point2/argChar.$(MEXENDING): @Point2/argChar.cpp - $(MEX) $(mex_flags) @Point2/argChar.cpp -output @Point2/argChar -@Point2/argUChar.$(MEXENDING): @Point2/argUChar.cpp - $(MEX) $(mex_flags) @Point2/argUChar.cpp -output @Point2/argUChar -@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp - $(MEX) $(mex_flags) @Point2/vectorConfusion.cpp -output @Point2/vectorConfusion - -Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) delete_Point2.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING) - -# Point3 -new_Point3_ddd.$(MEXENDING): new_Point3_ddd.cpp - $(MEX) $(mex_flags) new_Point3_ddd.cpp -output new_Point3_ddd -delete_Point3.$(MEXENDING): delete_Point3.cpp - $(MEX) $(mex_flags) delete_Point3.cpp -output delete_Point3 -Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp - $(MEX) $(mex_flags) Point3_staticFunction.cpp -output Point3_staticFunction -Point3_StaticFunctionRet.$(MEXENDING): Point3_StaticFunctionRet.cpp - $(MEX) $(mex_flags) Point3_StaticFunctionRet.cpp -output Point3_StaticFunctionRet -@Point3/norm.$(MEXENDING): @Point3/norm.cpp - $(MEX) $(mex_flags) @Point3/norm.cpp -output @Point3/norm - -Point3: new_Point3_ddd.$(MEXENDING) delete_Point3.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING) - -# Test -new_Test_.$(MEXENDING): new_Test_.cpp - $(MEX) $(mex_flags) new_Test_.cpp -output new_Test_ -new_Test_dM.$(MEXENDING): new_Test_dM.cpp - $(MEX) $(mex_flags) new_Test_dM.cpp -output new_Test_dM -delete_Test.$(MEXENDING): delete_Test.cpp - $(MEX) $(mex_flags) delete_Test.cpp -output delete_Test -@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp - $(MEX) $(mex_flags) @Test/return_pair.cpp -output @Test/return_pair -@Test/return_bool.$(MEXENDING): @Test/return_bool.cpp - $(MEX) $(mex_flags) @Test/return_bool.cpp -output @Test/return_bool -@Test/return_size_t.$(MEXENDING): @Test/return_size_t.cpp - $(MEX) $(mex_flags) @Test/return_size_t.cpp -output @Test/return_size_t -@Test/return_int.$(MEXENDING): @Test/return_int.cpp - $(MEX) $(mex_flags) @Test/return_int.cpp -output @Test/return_int -@Test/return_double.$(MEXENDING): @Test/return_double.cpp - $(MEX) $(mex_flags) @Test/return_double.cpp -output @Test/return_double -@Test/return_string.$(MEXENDING): @Test/return_string.cpp - $(MEX) $(mex_flags) @Test/return_string.cpp -output @Test/return_string -@Test/return_vector1.$(MEXENDING): @Test/return_vector1.cpp - $(MEX) $(mex_flags) @Test/return_vector1.cpp -output @Test/return_vector1 -@Test/return_matrix1.$(MEXENDING): @Test/return_matrix1.cpp - $(MEX) $(mex_flags) @Test/return_matrix1.cpp -output @Test/return_matrix1 -@Test/return_vector2.$(MEXENDING): @Test/return_vector2.cpp - $(MEX) $(mex_flags) @Test/return_vector2.cpp -output @Test/return_vector2 -@Test/return_matrix2.$(MEXENDING): @Test/return_matrix2.cpp - $(MEX) $(mex_flags) @Test/return_matrix2.cpp -output @Test/return_matrix2 -@Test/arg_EigenConstRef.$(MEXENDING): @Test/arg_EigenConstRef.cpp - $(MEX) $(mex_flags) @Test/arg_EigenConstRef.cpp -output @Test/arg_EigenConstRef -@Test/return_field.$(MEXENDING): @Test/return_field.cpp - $(MEX) $(mex_flags) @Test/return_field.cpp -output @Test/return_field -@Test/return_TestPtr.$(MEXENDING): @Test/return_TestPtr.cpp - $(MEX) $(mex_flags) @Test/return_TestPtr.cpp -output @Test/return_TestPtr -@Test/return_Test.$(MEXENDING): @Test/return_Test.cpp - $(MEX) $(mex_flags) @Test/return_Test.cpp -output @Test/return_Test -@Test/return_Point2Ptr.$(MEXENDING): @Test/return_Point2Ptr.cpp - $(MEX) $(mex_flags) @Test/return_Point2Ptr.cpp -output @Test/return_Point2Ptr -@Test/create_ptrs.$(MEXENDING): @Test/create_ptrs.cpp - $(MEX) $(mex_flags) @Test/create_ptrs.cpp -output @Test/create_ptrs -@Test/create_MixedPtrs.$(MEXENDING): @Test/create_MixedPtrs.cpp - $(MEX) $(mex_flags) @Test/create_MixedPtrs.cpp -output @Test/create_MixedPtrs -@Test/return_ptrs.$(MEXENDING): @Test/return_ptrs.cpp - $(MEX) $(mex_flags) @Test/return_ptrs.cpp -output @Test/return_ptrs -@Test/print.$(MEXENDING): @Test/print.cpp - $(MEX) $(mex_flags) @Test/print.cpp -output @Test/print - -Test: new_Test_.$(MEXENDING) new_Test_dM.$(MEXENDING) delete_Test.$(MEXENDING) @Test/return_pair.$(MEXENDING) @Test/return_bool.$(MEXENDING) @Test/return_size_t.$(MEXENDING) @Test/return_int.$(MEXENDING) @Test/return_double.$(MEXENDING) @Test/return_string.$(MEXENDING) @Test/return_vector1.$(MEXENDING) @Test/return_matrix1.$(MEXENDING) @Test/return_vector2.$(MEXENDING) @Test/return_matrix2.$(MEXENDING) @Test/arg_EigenConstRef.$(MEXENDING) @Test/return_field.$(MEXENDING) @Test/return_TestPtr.$(MEXENDING) @Test/return_Test.$(MEXENDING) @Test/return_Point2Ptr.$(MEXENDING) @Test/create_ptrs.$(MEXENDING) @Test/create_MixedPtrs.$(MEXENDING) @Test/return_ptrs.$(MEXENDING) @Test/print.$(MEXENDING) - - - -clean: - rm -rf *.$(MEXENDING) - rm -rf @Point2/*.$(MEXENDING) - rm -rf @Point3/*.$(MEXENDING) - rm -rf @Test/*.$(MEXENDING) - - diff --git a/wrap/tests/expected/Point2.m b/wrap/tests/expected/Point2.m new file mode 100644 index 000000000..22dec9641 --- /dev/null +++ b/wrap/tests/expected/Point2.m @@ -0,0 +1,139 @@ +%class Point2, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%Point2() +%Point2(double x, double y) +% +%-------Methods------- +%argChar(char a) : returns void +%argUChar(unsigned char a) : returns void +%dim() : returns int +%returnChar() : returns char +%vectorConfusion() : returns VectorNotEigen +%x() : returns double +%y() : returns double +% +classdef Point2 < handle + properties + ptr_Point2 = 0 + end + methods + function obj = Point2(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(1); + elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + my_ptr = geometry_wrapper(2, varargin{1}, varargin{2}); + else + error('Arguments do not match any overload of Point2 constructor'); + end + obj.ptr_Point2 = my_ptr; + end + + function delete(obj) + geometry_wrapper(3, obj.ptr_Point2); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = argChar(this, varargin) + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % argChar(char a) + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(4, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.argChar'); + end + end + + function varargout = argUChar(this, varargin) + % ARGUCHAR usage: argUChar(unsigned char a) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % argUChar(unsigned char a) + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(5, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.argUChar'); + end + end + + function varargout = dim(this, varargin) + % DIM usage: dim() : returns int + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % dim() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(6, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.dim'); + end + end + + function varargout = returnChar(this, varargin) + % RETURNCHAR usage: returnChar() : returns char + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % returnChar() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(7, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.returnChar'); + end + end + + function varargout = vectorConfusion(this, varargin) + % VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % vectorConfusion() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(8, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.vectorConfusion'); + end + end + + function varargout = x(this, varargin) + % X usage: x() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % x() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(9, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.x'); + end + end + + function varargout = y(this, varargin) + % Y usage: y() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % y() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(10, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.y'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m new file mode 100644 index 000000000..3a90f1982 --- /dev/null +++ b/wrap/tests/expected/Point3.m @@ -0,0 +1,82 @@ +%class Point3, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%Point3(double x, double y, double z) +% +%-------Methods------- +%norm() : returns double +% +%-------Static Methods------- +%StaticFunctionRet(double z) : returns Point3 +%staticFunction() : returns double +% +classdef Point3 < handle + properties + ptr_Point3 = 0 + end + methods + function obj = Point3(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(11, my_ptr); + elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') + my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3}); + else + error('Arguments do not match any overload of Point3 constructor'); + end + obj.ptr_Point3 = my_ptr; + end + + function delete(obj) + geometry_wrapper(13, obj.ptr_Point3); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = norm(this, varargin) + % NORM usage: norm() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % norm() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(14, this, varargin{:}); + else + error('Arguments do not match any overload of function Point3.norm'); + end + end + + end + + methods(Static = true) + function varargout = StaticFunctionRet(varargin) + % STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Usage + % STATICFUNCTIONRET(double z) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(15, varargin{:}); + else + error('Arguments do not match any overload of function Point3.StaticFunctionRet'); + end + end + + function varargout = StaticFunction(varargin) + % STATICFUNCTION usage: staticFunction() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Usage + % STATICFUNCTION() + if length(varargin) == 0 + varargout{1} = geometry_wrapper(16, varargin{:}); + else + error('Arguments do not match any overload of function Point3.StaticFunction'); + end + end + + end +end diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.cpp b/wrap/tests/expected/Point3_StaticFunctionRet.cpp deleted file mode 100644 index 062194bd5..000000000 --- a/wrap/tests/expected/Point3_StaticFunctionRet.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("Point3_StaticFunctionRet",nargout,nargin,1); - double z = unwrap< double >(in[0]); - Point3 result = Point3::StaticFunctionRet(z); - out[0] = wrap_shared_ptr(make_shared< Point3 >(result),"Point3"); -} diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.m b/wrap/tests/expected/Point3_StaticFunctionRet.m deleted file mode 100644 index 433d3c00d..000000000 --- a/wrap/tests/expected/Point3_StaticFunctionRet.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = Point3_StaticFunctionRet(z) -% usage: x = Point3_StaticFunctionRet(z) - error('need to compile Point3_StaticFunctionRet.cpp'); -end diff --git a/wrap/tests/expected/Point3_staticFunction.cpp b/wrap/tests/expected/Point3_staticFunction.cpp deleted file mode 100644 index 6adfdbe5a..000000000 --- a/wrap/tests/expected/Point3_staticFunction.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("Point3_staticFunction",nargout,nargin,0); - double result = Point3::staticFunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/Point3_staticFunction.m b/wrap/tests/expected/Point3_staticFunction.m deleted file mode 100644 index ccf9b85bd..000000000 --- a/wrap/tests/expected/Point3_staticFunction.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = Point3_staticFunction() -% usage: x = Point3_staticFunction() - error('need to compile Point3_staticFunction.cpp'); -end diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m new file mode 100644 index 000000000..e493b9a04 --- /dev/null +++ b/wrap/tests/expected/Test.m @@ -0,0 +1,307 @@ +%class Test, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%Test() +%Test(double a, Matrix b) +% +%-------Methods------- +%arg_EigenConstRef(Matrix value) : returns void +%create_MixedPtrs() : returns pair< Test, SharedTest > +%create_ptrs() : returns pair< SharedTest, SharedTest > +%print() : returns void +%return_Point2Ptr(bool value) : returns Point2 +%return_Test(Test value) : returns Test +%return_TestPtr(Test value) : returns Test +%return_bool(bool value) : returns bool +%return_double(double value) : returns double +%return_field(Test t) : returns bool +%return_int(int value) : returns int +%return_matrix1(Matrix value) : returns Matrix +%return_matrix2(Matrix value) : returns Matrix +%return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > +%return_ptrs(Test p1, Test p2) : returns pair< SharedTest, SharedTest > +%return_size_t(size_t value) : returns size_t +%return_string(string value) : returns string +%return_vector1(Vector value) : returns Vector +%return_vector2(Vector value) : returns Vector +% +classdef Test < handle + properties + ptr_Test = 0 + end + methods + function obj = Test(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(17, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(18); + elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}); + else + error('Arguments do not match any overload of Test constructor'); + end + obj.ptr_Test = my_ptr; + end + + function delete(obj) + geometry_wrapper(20, obj.ptr_Test); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = arg_EigenConstRef(this, varargin) + % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % arg_EigenConstRef(Matrix value) + if length(varargin) == 1 && isa(varargin{1},'double') + geometry_wrapper(21, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.arg_EigenConstRef'); + end + end + + function varargout = create_MixedPtrs(this, varargin) + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, SharedTest > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % create_MixedPtrs() + if length(varargin) == 0 + [ varargout{1} varargout{2} ] = geometry_wrapper(22, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.create_MixedPtrs'); + end + end + + function varargout = create_ptrs(this, varargin) + % CREATE_PTRS usage: create_ptrs() : returns pair< SharedTest, SharedTest > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % create_ptrs() + if length(varargin) == 0 + [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.create_ptrs'); + end + end + + function varargout = print(this, varargin) + % PRINT usage: print() : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % print() + if length(varargin) == 0 + geometry_wrapper(24, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.print'); + end + end + + function varargout = return_Point2Ptr(this, varargin) + % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_Point2Ptr(bool value) + if length(varargin) == 1 && isa(varargin{1},'logical') + varargout{1} = geometry_wrapper(25, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_Point2Ptr'); + end + end + + function varargout = return_Test(this, varargin) + % RETURN_TEST usage: return_Test(Test value) : returns Test + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_Test(Test value) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(26, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_Test'); + end + end + + function varargout = return_TestPtr(this, varargin) + % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_TestPtr(Test value) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(27, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_TestPtr'); + end + end + + function varargout = return_bool(this, varargin) + % RETURN_BOOL usage: return_bool(bool value) : returns bool + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_bool(bool value) + if length(varargin) == 1 && isa(varargin{1},'logical') + varargout{1} = geometry_wrapper(28, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_bool'); + end + end + + function varargout = return_double(this, varargin) + % RETURN_DOUBLE usage: return_double(double value) : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_double(double value) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(29, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_double'); + end + end + + function varargout = return_field(this, varargin) + % RETURN_FIELD usage: return_field(Test t) : returns bool + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_field(Test t) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(30, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_field'); + end + end + + function varargout = return_int(this, varargin) + % RETURN_INT usage: return_int(int value) : returns int + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_int(int value) + if length(varargin) == 1 && isa(varargin{1},'numeric') + varargout{1} = geometry_wrapper(31, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_int'); + end + end + + function varargout = return_matrix1(this, varargin) + % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_matrix1(Matrix value) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(32, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_matrix1'); + end + end + + function varargout = return_matrix2(this, varargin) + % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_matrix2(Matrix value) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(33, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_matrix2'); + end + end + + function varargout = return_pair(this, varargin) + % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_pair(Vector v, Matrix A) + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + [ varargout{1} varargout{2} ] = geometry_wrapper(34, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_pair'); + end + end + + function varargout = return_ptrs(this, varargin) + % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< SharedTest, SharedTest > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_ptrs(Test p1, Test p2) + if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') + [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_ptrs'); + end + end + + function varargout = return_size_t(this, varargin) + % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_size_t(size_t value) + if length(varargin) == 1 && isa(varargin{1},'numeric') + varargout{1} = geometry_wrapper(36, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_size_t'); + end + end + + function varargout = return_string(this, varargin) + % RETURN_STRING usage: return_string(string value) : returns string + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_string(string value) + if length(varargin) == 1 && isa(varargin{1},'char') + varargout{1} = geometry_wrapper(37, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_string'); + end + end + + function varargout = return_vector1(this, varargin) + % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_vector1(Vector value) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(38, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_vector1'); + end + end + + function varargout = return_vector2(this, varargin) + % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % return_vector2(Vector value) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(39, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_vector2'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/aGlobalFunction.m b/wrap/tests/expected/aGlobalFunction.m new file mode 100644 index 000000000..cee69491c --- /dev/null +++ b/wrap/tests/expected/aGlobalFunction.m @@ -0,0 +1,6 @@ +function varargout = aGlobalFunction(varargin) +if length(varargin) == 0 + varargout{1} = geometry_wrapper(40, varargin{:}); +else + error('Arguments do not match any overload of function aGlobalFunction'); +end diff --git a/wrap/tests/expected/delete_Point2.cpp b/wrap/tests/expected/delete_Point2.cpp deleted file mode 100644 index bd8bd12eb..000000000 --- a/wrap/tests/expected/delete_Point2.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Point2",nargout,nargin,1); - delete_shared_ptr< Point2 >(in[0],"Point2"); -} diff --git a/wrap/tests/expected/delete_Point2.m b/wrap/tests/expected/delete_Point2.m deleted file mode 100644 index c6c623bec..000000000 --- a/wrap/tests/expected/delete_Point2.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Point2(obj) - error('need to compile delete_Point2.cpp'); -end diff --git a/wrap/tests/expected/delete_Point3.cpp b/wrap/tests/expected/delete_Point3.cpp deleted file mode 100644 index 9836bb25e..000000000 --- a/wrap/tests/expected/delete_Point3.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Point3",nargout,nargin,1); - delete_shared_ptr< Point3 >(in[0],"Point3"); -} diff --git a/wrap/tests/expected/delete_Point3.m b/wrap/tests/expected/delete_Point3.m deleted file mode 100644 index b52b898cf..000000000 --- a/wrap/tests/expected/delete_Point3.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Point3(obj) - error('need to compile delete_Point3.cpp'); -end diff --git a/wrap/tests/expected/delete_Test.cpp b/wrap/tests/expected/delete_Test.cpp deleted file mode 100644 index 6a22cc327..000000000 --- a/wrap/tests/expected/delete_Test.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Test",nargout,nargin,1); - delete_shared_ptr< Test >(in[0],"Test"); -} diff --git a/wrap/tests/expected/delete_Test.m b/wrap/tests/expected/delete_Test.m deleted file mode 100644 index 21ec790a3..000000000 --- a/wrap/tests/expected/delete_Test.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Test(obj) - error('need to compile delete_Test.cpp'); -end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp new file mode 100644 index 000000000..ad1df801c --- /dev/null +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -0,0 +1,618 @@ +#include +#include +#include + +#include + + +typedef std::set*> Collector_Point2; +static Collector_Point2 collector_Point2; +typedef std::set*> Collector_Point3; +static Collector_Point3 collector_Point3; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_Point2::iterator iter = collector_Point2.begin(); + iter != collector_Point2.end(); ) { + delete *iter; + collector_Point2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Point3::iterator iter = collector_Point3.begin(); + iter != collector_Point3.end(); ) { + delete *iter; + collector_Point3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _geometry_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_geometry_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + BOOST_FOREACH(const StringPair& rtti_matlab, types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void Point2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Point2.insert(self); +} + +void Point2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new Point2()); + collector_Point2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Point2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double x = unwrap< double >(in[0]); + double y = unwrap< double >(in[1]); + Shared *self = new Shared(new Point2(x,y)); + collector_Point2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Point2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_Point2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Point2::iterator item; + item = collector_Point2.find(self); + if(item != collector_Point2.end()) { + delete self; + collector_Point2.erase(item); + } +} + +void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("argChar",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("argUChar",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + unsigned char a = unwrap< unsigned char >(in[1]); + obj->argUChar(a); +} + +void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("dim",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< int >(obj->dim()); +} + +void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("returnChar",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< char >(obj->returnChar()); +} + +void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedVectorNotEigen; + typedef boost::shared_ptr Shared; + checkArguments("vectorConfusion",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false); +} + +void Point2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("x",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->x()); +} + +void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("y",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->y()); +} + +void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Point3.insert(self); +} + +void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double x = unwrap< double >(in[0]); + double y = unwrap< double >(in[1]); + double z = unwrap< double >(in[2]); + Shared *self = new Shared(new Point3(x,y,z)); + collector_Point3.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_Point3",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Point3::iterator item; + item = collector_Point3.find(self); + if(item != collector_Point3.end()) { + delete self; + collector_Point3.erase(item); + } +} + +void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("norm",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + out[0] = wrap< double >(obj->norm()); +} + +void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); + double z = unwrap< double >(in[0]); + out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); +} + +void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("Point3.staticFunction",nargout,nargin,0); + out[0] = wrap< double >(Point3::staticFunction()); +} + +void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Test.insert(self); +} + +void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new Test()); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double a = unwrap< double >(in[0]); + Matrix b = unwrap< Matrix >(in[1]); + Shared *self = new Shared(new Test(a,b)); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_Test",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Test::iterator item; + item = collector_Test.find(self); + if(item != collector_Test.end()) { + delete self; + collector_Test.erase(item); + } +} + +void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("arg_EigenConstRef",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->arg_EigenConstRef(value); +} + +void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + pair< Test, SharedTest > pairResult = obj->create_MixedPtrs(); + out[0] = wrap_shared_ptr(SharedTest(new Test(pairResult.first)),"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("create_ptrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + pair< SharedTest, SharedTest > pairResult = obj->create_ptrs(); + out[0] = wrap_shared_ptr(pairResult.first,"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("print",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + obj->print(); +} + +void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("return_Point2Ptr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + bool value = unwrap< bool >(in[1]); + out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"Point2", false); +} + +void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_Test",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(SharedTest(new Test(obj->return_Test(value))),"Test", false); +} + +void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_TestPtr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); +} + +void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_bool",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + bool value = unwrap< bool >(in[1]); + out[0] = wrap< bool >(obj->return_bool(value)); +} + +void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_double",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + double value = unwrap< double >(in[1]); + out[0] = wrap< double >(obj->return_double(value)); +} + +void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_field",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Test& t = *unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap< bool >(obj->return_field(t)); +} + +void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_int",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + int value = unwrap< int >(in[1]); + out[0] = wrap< int >(obj->return_int(value)); +} + +void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_matrix1",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix1(value)); +} + +void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_matrix2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix2(value)); +} + +void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_pair",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector v = unwrap< Vector >(in[1]); + Matrix A = unwrap< Matrix >(in[2]); + pair< Vector, Matrix > pairResult = obj->return_pair(v,A); + out[0] = wrap< Vector >(pairResult.first); + out[1] = wrap< Matrix >(pairResult.second); +} + +void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_ptrs",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "ptr_Test"); + pair< SharedTest, SharedTest > pairResult = obj->return_ptrs(p1,p2); + out[0] = wrap_shared_ptr(pairResult.first,"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_size_t",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + size_t value = unwrap< size_t >(in[1]); + out[0] = wrap< size_t >(obj->return_size_t(value)); +} + +void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_string",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + string value = unwrap< string >(in[1]); + out[0] = wrap< string >(obj->return_string(value)); +} + +void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_vector1",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector1(value)); +} + +void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("return_vector2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector2(value)); +} + +void aGlobalFunction_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(aGlobalFunction()); +} + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _geometry_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + Point2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + Point2_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + Point2_constructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + Point2_deconstructor_3(nargout, out, nargin-1, in+1); + break; + case 4: + Point2_argChar_4(nargout, out, nargin-1, in+1); + break; + case 5: + Point2_argUChar_5(nargout, out, nargin-1, in+1); + break; + case 6: + Point2_dim_6(nargout, out, nargin-1, in+1); + break; + case 7: + Point2_returnChar_7(nargout, out, nargin-1, in+1); + break; + case 8: + Point2_vectorConfusion_8(nargout, out, nargin-1, in+1); + break; + case 9: + Point2_x_9(nargout, out, nargin-1, in+1); + break; + case 10: + Point2_y_10(nargout, out, nargin-1, in+1); + break; + case 11: + Point3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); + break; + case 12: + Point3_constructor_12(nargout, out, nargin-1, in+1); + break; + case 13: + Point3_deconstructor_13(nargout, out, nargin-1, in+1); + break; + case 14: + Point3_norm_14(nargout, out, nargin-1, in+1); + break; + case 15: + Point3_StaticFunctionRet_15(nargout, out, nargin-1, in+1); + break; + case 16: + Point3_staticFunction_16(nargout, out, nargin-1, in+1); + break; + case 17: + Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); + break; + case 18: + Test_constructor_18(nargout, out, nargin-1, in+1); + break; + case 19: + Test_constructor_19(nargout, out, nargin-1, in+1); + break; + case 20: + Test_deconstructor_20(nargout, out, nargin-1, in+1); + break; + case 21: + Test_arg_EigenConstRef_21(nargout, out, nargin-1, in+1); + break; + case 22: + Test_create_MixedPtrs_22(nargout, out, nargin-1, in+1); + break; + case 23: + Test_create_ptrs_23(nargout, out, nargin-1, in+1); + break; + case 24: + Test_print_24(nargout, out, nargin-1, in+1); + break; + case 25: + Test_return_Point2Ptr_25(nargout, out, nargin-1, in+1); + break; + case 26: + Test_return_Test_26(nargout, out, nargin-1, in+1); + break; + case 27: + Test_return_TestPtr_27(nargout, out, nargin-1, in+1); + break; + case 28: + Test_return_bool_28(nargout, out, nargin-1, in+1); + break; + case 29: + Test_return_double_29(nargout, out, nargin-1, in+1); + break; + case 30: + Test_return_field_30(nargout, out, nargin-1, in+1); + break; + case 31: + Test_return_int_31(nargout, out, nargin-1, in+1); + break; + case 32: + Test_return_matrix1_32(nargout, out, nargin-1, in+1); + break; + case 33: + Test_return_matrix2_33(nargout, out, nargin-1, in+1); + break; + case 34: + Test_return_pair_34(nargout, out, nargin-1, in+1); + break; + case 35: + Test_return_ptrs_35(nargout, out, nargin-1, in+1); + break; + case 36: + Test_return_size_t_36(nargout, out, nargin-1, in+1); + break; + case 37: + Test_return_string_37(nargout, out, nargin-1, in+1); + break; + case 38: + Test_return_vector1_38(nargout, out, nargin-1, in+1); + break; + case 39: + Test_return_vector2_39(nargout, out, nargin-1, in+1); + break; + case 40: + aGlobalFunction_40(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/wrap/tests/expected/make_geometry.m b/wrap/tests/expected/make_geometry.m deleted file mode 100644 index 7baac182f..000000000 --- a/wrap/tests/expected/make_geometry.m +++ /dev/null @@ -1,64 +0,0 @@ -% automatically generated by wrap -echo on - -toolboxpath = mfilename('fullpath'); -delims = find(toolboxpath == '/'); -toolboxpath = toolboxpath(1:(delims(end)-1)); -clear delims -addpath(toolboxpath); - -%% Point2 -cd(toolboxpath) -mex -O5 new_Point2_.cpp -mex -O5 new_Point2_dd.cpp -mex -O5 delete_Point2.cpp - -cd @Point2 -mex -O5 x.cpp -mex -O5 y.cpp -mex -O5 dim.cpp -mex -O5 returnChar.cpp -mex -O5 argChar.cpp -mex -O5 argUChar.cpp -mex -O5 vectorConfusion.cpp - -%% Point3 -cd(toolboxpath) -mex -O5 new_Point3_ddd.cpp -mex -O5 delete_Point3.cpp -mex -O5 Point3_staticFunction.cpp -mex -O5 Point3_StaticFunctionRet.cpp - -cd @Point3 -mex -O5 norm.cpp - -%% Test -cd(toolboxpath) -mex -O5 new_Test_.cpp -mex -O5 new_Test_dM.cpp -mex -O5 delete_Test.cpp - -cd @Test -mex -O5 return_pair.cpp -mex -O5 return_bool.cpp -mex -O5 return_size_t.cpp -mex -O5 return_int.cpp -mex -O5 return_double.cpp -mex -O5 return_string.cpp -mex -O5 return_vector1.cpp -mex -O5 return_matrix1.cpp -mex -O5 return_vector2.cpp -mex -O5 return_matrix2.cpp -mex -O5 arg_EigenConstRef.cpp -mex -O5 return_field.cpp -mex -O5 return_TestPtr.cpp -mex -O5 return_Test.cpp -mex -O5 return_Point2Ptr.cpp -mex -O5 create_ptrs.cpp -mex -O5 create_MixedPtrs.cpp -mex -O5 return_ptrs.cpp -mex -O5 print.cpp - -cd(toolboxpath) - -echo off diff --git a/wrap/tests/expected/new_Point2_.cpp b/wrap/tests/expected/new_Point2_.cpp deleted file mode 100644 index a88076efb..000000000 --- a/wrap/tests/expected/new_Point2_.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Point2_",nargout,nargin,0); - Point2* self = new Point2(); - out[0] = wrap_constructed(self,"Point2"); -} diff --git a/wrap/tests/expected/new_Point2_.m b/wrap/tests/expected/new_Point2_.m deleted file mode 100644 index b0b655b5e..000000000 --- a/wrap/tests/expected/new_Point2_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point2_(obj) - error('need to compile new_Point2_.cpp'); -end diff --git a/wrap/tests/expected/new_Point2_dd.cpp b/wrap/tests/expected/new_Point2_dd.cpp deleted file mode 100644 index 7c7f062b7..000000000 --- a/wrap/tests/expected/new_Point2_dd.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Point2_dd",nargout,nargin,2); - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - Point2* self = new Point2(x,y); - out[0] = wrap_constructed(self,"Point2"); -} diff --git a/wrap/tests/expected/new_Point2_dd.m b/wrap/tests/expected/new_Point2_dd.m deleted file mode 100644 index 4a769ce30..000000000 --- a/wrap/tests/expected/new_Point2_dd.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point2_dd(obj,x,y) - error('need to compile new_Point2_dd.cpp'); -end diff --git a/wrap/tests/expected/new_Point3_ddd.cpp b/wrap/tests/expected/new_Point3_ddd.cpp deleted file mode 100644 index aa45dc71c..000000000 --- a/wrap/tests/expected/new_Point3_ddd.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Point3_ddd",nargout,nargin,3); - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - double z = unwrap< double >(in[2]); - Point3* self = new Point3(x,y,z); - out[0] = wrap_constructed(self,"Point3"); -} diff --git a/wrap/tests/expected/new_Point3_ddd.m b/wrap/tests/expected/new_Point3_ddd.m deleted file mode 100644 index 154dda1d0..000000000 --- a/wrap/tests/expected/new_Point3_ddd.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point3_ddd(obj,x,y,z) - error('need to compile new_Point3_ddd.cpp'); -end diff --git a/wrap/tests/expected/new_Test_.cpp b/wrap/tests/expected/new_Test_.cpp deleted file mode 100644 index 9c66706ae..000000000 --- a/wrap/tests/expected/new_Test_.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Test_",nargout,nargin,0); - Test* self = new Test(); - out[0] = wrap_constructed(self,"Test"); -} diff --git a/wrap/tests/expected/new_Test_.m b/wrap/tests/expected/new_Test_.m deleted file mode 100644 index 33c465f8b..000000000 --- a/wrap/tests/expected/new_Test_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Test_(obj) - error('need to compile new_Test_.cpp'); -end diff --git a/wrap/tests/expected/new_Test_dM.cpp b/wrap/tests/expected/new_Test_dM.cpp deleted file mode 100644 index e8a7c8de1..000000000 --- a/wrap/tests/expected/new_Test_dM.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Test_dM",nargout,nargin,2); - double a = unwrap< double >(in[0]); - Matrix b = unwrap< Matrix >(in[1]); - Test* self = new Test(a,b); - out[0] = wrap_constructed(self,"Test"); -} diff --git a/wrap/tests/expected/new_Test_dM.m b/wrap/tests/expected/new_Test_dM.m deleted file mode 100644 index c7009d6a9..000000000 --- a/wrap/tests/expected/new_Test_dM.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Test_dM(obj,a,b) - error('need to compile new_Test_dM.cpp'); -end diff --git a/wrap/tests/expected_namespaces/+ns1/ClassA.m b/wrap/tests/expected_namespaces/+ns1/ClassA.m new file mode 100644 index 000000000..f7dce6031 --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns1/ClassA.m @@ -0,0 +1,36 @@ +%class ClassA, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassA() +% +classdef ClassA < handle + properties + ptr_ns1ClassA = 0 + end + methods + function obj = ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(1); + else + error('Arguments do not match any overload of ns1.ClassA constructor'); + end + obj.ptr_ns1ClassA = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(2, obj.ptr_ns1ClassA); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/+ns1/ClassB.m b/wrap/tests/expected_namespaces/+ns1/ClassB.m new file mode 100644 index 000000000..df956a179 --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns1/ClassB.m @@ -0,0 +1,36 @@ +%class ClassB, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassB() +% +classdef ClassB < handle + properties + ptr_ns1ClassB = 0 + end + methods + function obj = ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(3, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(4); + else + error('Arguments do not match any overload of ns1.ClassB constructor'); + end + obj.ptr_ns1ClassB = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(5, obj.ptr_ns1ClassB); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/+ns1/aGlobalFunction.m b/wrap/tests/expected_namespaces/+ns1/aGlobalFunction.m new file mode 100644 index 000000000..a82518ad6 --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns1/aGlobalFunction.m @@ -0,0 +1,6 @@ +function varargout = aGlobalFunction(varargin) +if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(22, varargin{:}); +else + error('Arguments do not match any overload of function ns1.aGlobalFunction'); +end diff --git a/wrap/tests/expected_namespaces/+ns2/+ns3/ClassB.m b/wrap/tests/expected_namespaces/+ns2/+ns3/ClassB.m new file mode 100644 index 000000000..23c3dbacb --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns2/+ns3/ClassB.m @@ -0,0 +1,36 @@ +%class ClassB, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassB() +% +classdef ClassB < handle + properties + ptr_ns2ns3ClassB = 0 + end + methods + function obj = ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(13, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(14); + else + error('Arguments do not match any overload of ns2.ns3.ClassB constructor'); + end + obj.ptr_ns2ns3ClassB = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(15, obj.ptr_ns2ns3ClassB); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/+ns2/ClassA.m b/wrap/tests/expected_namespaces/+ns2/ClassA.m new file mode 100644 index 000000000..c7ab901ae --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns2/ClassA.m @@ -0,0 +1,96 @@ +%class ClassA, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassA() +% +%-------Methods------- +%memberFunction() : returns double +%nsArg(ClassB arg) : returns int +%nsReturn(double q) : returns ns2::ns3::ClassB +% +%-------Static Methods------- +%afunction() : returns double +% +classdef ClassA < handle + properties + ptr_ns2ClassA = 0 + end + methods + function obj = ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(6, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(7); + else + error('Arguments do not match any overload of ns2.ClassA constructor'); + end + obj.ptr_ns2ClassA = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(8, obj.ptr_ns2ClassA); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = memberFunction(this, varargin) + % MEMBERFUNCTION usage: memberFunction() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % memberFunction() + if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(9, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2.ClassA.memberFunction'); + end + end + + function varargout = nsArg(this, varargin) + % NSARG usage: nsArg(ClassB arg) : returns int + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % nsArg(ClassB arg) + if length(varargin) == 1 && isa(varargin{1},'ns1.ClassB') + varargout{1} = testNamespaces_wrapper(10, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2.ClassA.nsArg'); + end + end + + function varargout = nsReturn(this, varargin) + % NSRETURN usage: nsReturn(double q) : returns ns2::ns3::ClassB + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Method Overloads + % nsReturn(double q) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = testNamespaces_wrapper(11, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2.ClassA.nsReturn'); + end + end + + end + + methods(Static = true) + function varargout = Afunction(varargin) + % AFUNCTION usage: afunction() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % + % Usage + % AFUNCTION() + if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(12, varargin{:}); + else + error('Arguments do not match any overload of function ns2.ClassA.Afunction'); + end + end + + end +end diff --git a/wrap/tests/expected_namespaces/+ns2/ClassC.m b/wrap/tests/expected_namespaces/+ns2/ClassC.m new file mode 100644 index 000000000..19b709f5c --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns2/ClassC.m @@ -0,0 +1,36 @@ +%class ClassC, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassC() +% +classdef ClassC < handle + properties + ptr_ns2ClassC = 0 + end + methods + function obj = ClassC(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(16, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(17); + else + error('Arguments do not match any overload of ns2.ClassC constructor'); + end + obj.ptr_ns2ClassC = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(18, obj.ptr_ns2ClassC); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/+ns2/aGlobalFunction.m b/wrap/tests/expected_namespaces/+ns2/aGlobalFunction.m new file mode 100644 index 000000000..8b6a5993f --- /dev/null +++ b/wrap/tests/expected_namespaces/+ns2/aGlobalFunction.m @@ -0,0 +1,6 @@ +function varargout = aGlobalFunction(varargin) +if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(23, varargin{:}); +else + error('Arguments do not match any overload of function ns2.aGlobalFunction'); +end diff --git a/wrap/tests/expected_namespaces/@ClassD/ClassD.m b/wrap/tests/expected_namespaces/@ClassD/ClassD.m deleted file mode 100644 index 8b78750d9..000000000 --- a/wrap/tests/expected_namespaces/@ClassD/ClassD.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ClassD < handle - properties - self = 0 - end - methods - function obj = ClassD(varargin) - if (nargin == 0), obj.self = new_ClassD_(); end - if nargin ~= 13 && obj.self == 0, error('ClassD constructor failed'); end - end - function delete(obj) - delete_ClassD(obj) - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m deleted file mode 100644 index 806070a36..000000000 --- a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ns1ClassA < handle - properties - self = 0 - end - methods - function obj = ns1ClassA(varargin) - if (nargin == 0), obj.self = new_ns1ClassA_(); end - if nargin ~= 13 && obj.self == 0, error('ns1ClassA constructor failed'); end - end - function delete(obj) - delete_ns1ClassA(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m deleted file mode 100644 index 13d5846ae..000000000 --- a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ns1ClassB < handle - properties - self = 0 - end - methods - function obj = ns1ClassB(varargin) - if (nargin == 0), obj.self = new_ns1ClassB_(); end - if nargin ~= 13 && obj.self == 0, error('ns1ClassB constructor failed'); end - end - function delete(obj) - delete_ns1ClassB(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp deleted file mode 100644 index 8e5bc3960..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("memberFunction",nargout,nargin-1,0); - shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - double result = self->memberFunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m deleted file mode 100644 index 4523cba56..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = memberFunction(obj) -% usage: obj.memberFunction() - error('need to compile memberFunction.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m deleted file mode 100644 index 188ac087d..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ns2ClassA < handle - properties - self = 0 - end - methods - function obj = ns2ClassA(varargin) - if (nargin == 0), obj.self = new_ns2ClassA_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ClassA constructor failed'); end - end - function delete(obj) - delete_ns2ClassA(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp deleted file mode 100644 index 7c06bcfdc..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("nsArg",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ns1ClassB"); - int result = self->nsArg(arg); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m deleted file mode 100644 index 4893ece7f..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = nsArg(obj,arg) -% usage: obj.nsArg(arg) - error('need to compile nsArg.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp deleted file mode 100644 index c6714ee9f..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("nsReturn",nargout,nargin-1,1); - shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - double q = unwrap< double >(in[1]); - ns2::ns3::ClassB result = self->nsReturn(q); - out[0] = wrap_shared_ptr(make_shared< ns2::ns3::ClassB >(result),"ns2ns3ClassB"); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m deleted file mode 100644 index 2c900bc30..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = nsReturn(obj,q) -% usage: obj.nsReturn(q) - error('need to compile nsReturn.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m deleted file mode 100644 index 793e73e64..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ns2ClassC < handle - properties - self = 0 - end - methods - function obj = ns2ClassC(varargin) - if (nargin == 0), obj.self = new_ns2ClassC_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ClassC constructor failed'); end - end - function delete(obj) - delete_ns2ClassC(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m deleted file mode 100644 index 3997cd005..000000000 --- a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m +++ /dev/null @@ -1,17 +0,0 @@ -% automatically generated by wrap -classdef ns2ns3ClassB < handle - properties - self = 0 - end - methods - function obj = ns2ns3ClassB(varargin) - if (nargin == 0), obj.self = new_ns2ns3ClassB_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ns3ClassB constructor failed'); end - end - function delete(obj) - delete_ns2ns3ClassB(obj); - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/ClassD.m b/wrap/tests/expected_namespaces/ClassD.m new file mode 100644 index 000000000..453025961 --- /dev/null +++ b/wrap/tests/expected_namespaces/ClassD.m @@ -0,0 +1,36 @@ +%class ClassD, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%ClassD() +% +classdef ClassD < handle + properties + ptr_ClassD = 0 + end + methods + function obj = ClassD(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(19, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(20); + else + error('Arguments do not match any overload of ClassD constructor'); + end + obj.ptr_ClassD = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(21, obj.ptr_ClassD); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/Makefile b/wrap/tests/expected_namespaces/Makefile deleted file mode 100644 index c48a1b154..000000000 --- a/wrap/tests/expected_namespaces/Makefile +++ /dev/null @@ -1,76 +0,0 @@ -# automatically generated by wrap - -MEX = mex -MEXENDING = mexa64 -mex_flags = -O5 - -all: ns1ClassA ns1ClassB ns2ClassA ns2ns3ClassB ns2ClassC ClassD - -# ns1ClassA -new_ns1ClassA_.$(MEXENDING): new_ns1ClassA_.cpp - $(MEX) $(mex_flags) new_ns1ClassA_.cpp -output new_ns1ClassA_ -delete_ns1ClassA.$(MEXENDING): delete_ns1ClassA.cpp - $(MEX) $(mex_flags) delete_ns1ClassA.cpp -output delete_ns1ClassA - -ns1ClassA: new_ns1ClassA_.$(MEXENDING) delete_ns1ClassA.$(MEXENDING) - -# ns1ClassB -new_ns1ClassB_.$(MEXENDING): new_ns1ClassB_.cpp - $(MEX) $(mex_flags) new_ns1ClassB_.cpp -output new_ns1ClassB_ -delete_ns1ClassB.$(MEXENDING): delete_ns1ClassB.cpp - $(MEX) $(mex_flags) delete_ns1ClassB.cpp -output delete_ns1ClassB - -ns1ClassB: new_ns1ClassB_.$(MEXENDING) delete_ns1ClassB.$(MEXENDING) - -# ns2ClassA -new_ns2ClassA_.$(MEXENDING): new_ns2ClassA_.cpp - $(MEX) $(mex_flags) new_ns2ClassA_.cpp -output new_ns2ClassA_ -delete_ns2ClassA.$(MEXENDING): delete_ns2ClassA.cpp - $(MEX) $(mex_flags) delete_ns2ClassA.cpp -output delete_ns2ClassA -ns2ClassA_afunction.$(MEXENDING): ns2ClassA_afunction.cpp - $(MEX) $(mex_flags) ns2ClassA_afunction.cpp -output ns2ClassA_afunction -@ns2ClassA/memberFunction.$(MEXENDING): @ns2ClassA/memberFunction.cpp - $(MEX) $(mex_flags) @ns2ClassA/memberFunction.cpp -output @ns2ClassA/memberFunction -@ns2ClassA/nsArg.$(MEXENDING): @ns2ClassA/nsArg.cpp - $(MEX) $(mex_flags) @ns2ClassA/nsArg.cpp -output @ns2ClassA/nsArg -@ns2ClassA/nsReturn.$(MEXENDING): @ns2ClassA/nsReturn.cpp - $(MEX) $(mex_flags) @ns2ClassA/nsReturn.cpp -output @ns2ClassA/nsReturn - -ns2ClassA: new_ns2ClassA_.$(MEXENDING) delete_ns2ClassA.$(MEXENDING) ns2ClassA_afunction.$(MEXENDING) @ns2ClassA/memberFunction.$(MEXENDING) @ns2ClassA/nsArg.$(MEXENDING) @ns2ClassA/nsReturn.$(MEXENDING) - -# ns2ns3ClassB -new_ns2ns3ClassB_.$(MEXENDING): new_ns2ns3ClassB_.cpp - $(MEX) $(mex_flags) new_ns2ns3ClassB_.cpp -output new_ns2ns3ClassB_ -delete_ns2ns3ClassB.$(MEXENDING): delete_ns2ns3ClassB.cpp - $(MEX) $(mex_flags) delete_ns2ns3ClassB.cpp -output delete_ns2ns3ClassB - -ns2ns3ClassB: new_ns2ns3ClassB_.$(MEXENDING) delete_ns2ns3ClassB.$(MEXENDING) - -# ns2ClassC -new_ns2ClassC_.$(MEXENDING): new_ns2ClassC_.cpp - $(MEX) $(mex_flags) new_ns2ClassC_.cpp -output new_ns2ClassC_ -delete_ns2ClassC.$(MEXENDING): delete_ns2ClassC.cpp - $(MEX) $(mex_flags) delete_ns2ClassC.cpp -output delete_ns2ClassC - -ns2ClassC: new_ns2ClassC_.$(MEXENDING) delete_ns2ClassC.$(MEXENDING) - -# ClassD -new_ClassD_.$(MEXENDING): new_ClassD_.cpp - $(MEX) $(mex_flags) new_ClassD_.cpp -output new_ClassD_ -delete_ClassD.$(MEXENDING): delete_ClassD.cpp - $(MEX) $(mex_flags) delete_ClassD.cpp -output delete_ClassD - -ClassD: new_ClassD_.$(MEXENDING) delete_ClassD.$(MEXENDING) - - - -clean: - rm -rf *.$(MEXENDING) - rm -rf @ns1ClassA/*.$(MEXENDING) - rm -rf @ns1ClassB/*.$(MEXENDING) - rm -rf @ns2ClassA/*.$(MEXENDING) - rm -rf @ns2ns3ClassB/*.$(MEXENDING) - rm -rf @ns2ClassC/*.$(MEXENDING) - rm -rf @ClassD/*.$(MEXENDING) - - diff --git a/wrap/tests/expected_namespaces/delete_ClassD.cpp b/wrap/tests/expected_namespaces/delete_ClassD.cpp deleted file mode 100644 index 5284e33ba..000000000 --- a/wrap/tests/expected_namespaces/delete_ClassD.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ClassD",nargout,nargin,1); - delete_shared_ptr< ClassD >(in[0],"ClassD"); -} diff --git a/wrap/tests/expected_namespaces/delete_ClassD.m b/wrap/tests/expected_namespaces/delete_ClassD.m deleted file mode 100644 index aef8cb642..000000000 --- a/wrap/tests/expected_namespaces/delete_ClassD.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ClassD(obj) - error('need to compile delete_ClassD.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp b/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp deleted file mode 100644 index 17a25b523..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns1ClassA",nargout,nargin,1); - delete_shared_ptr< ns1::ClassA >(in[0],"ns1ClassA"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassA.m b/wrap/tests/expected_namespaces/delete_ns1ClassA.m deleted file mode 100644 index 343d5636a..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns1ClassA(obj) - error('need to compile delete_ns1ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp b/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp deleted file mode 100644 index 7302cc3d3..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns1ClassB",nargout,nargin,1); - delete_shared_ptr< ns1::ClassB >(in[0],"ns1ClassB"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassB.m b/wrap/tests/expected_namespaces/delete_ns1ClassB.m deleted file mode 100644 index ec50f3f06..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns1ClassB(obj) - error('need to compile delete_ns1ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp b/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp deleted file mode 100644 index 0562ee073..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ClassA",nargout,nargin,1); - delete_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassA.m b/wrap/tests/expected_namespaces/delete_ns2ClassA.m deleted file mode 100644 index 4f1b92aa5..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ClassA(obj) - error('need to compile delete_ns2ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp b/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp deleted file mode 100644 index ef57796b7..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ClassC",nargout,nargin,1); - delete_shared_ptr< ns2::ClassC >(in[0],"ns2ClassC"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassC.m b/wrap/tests/expected_namespaces/delete_ns2ClassC.m deleted file mode 100644 index 1db1ddc93..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassC.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ClassC(obj) - error('need to compile delete_ns2ClassC.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp b/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp deleted file mode 100644 index 0a6c4ce73..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ns3ClassB",nargout,nargin,1); - delete_shared_ptr< ns2::ns3::ClassB >(in[0],"ns2ns3ClassB"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m b/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m deleted file mode 100644 index 427359eca..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ns3ClassB(obj) - error('need to compile delete_ns2ns3ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/make_testNamespaces.m b/wrap/tests/expected_namespaces/make_testNamespaces.m deleted file mode 100644 index eac4146c8..000000000 --- a/wrap/tests/expected_namespaces/make_testNamespaces.m +++ /dev/null @@ -1,58 +0,0 @@ -% automatically generated by wrap -echo on - -toolboxpath = mfilename('fullpath'); -delims = find(toolboxpath == '/'); -toolboxpath = toolboxpath(1:(delims(end)-1)); -clear delims -addpath(toolboxpath); - -%% ns1ClassA -cd(toolboxpath) -mex -O5 new_ns1ClassA_.cpp -mex -O5 delete_ns1ClassA.cpp - -cd @ns1ClassA - -%% ns1ClassB -cd(toolboxpath) -mex -O5 new_ns1ClassB_.cpp -mex -O5 delete_ns1ClassB.cpp - -cd @ns1ClassB - -%% ns2ClassA -cd(toolboxpath) -mex -O5 new_ns2ClassA_.cpp -mex -O5 delete_ns2ClassA.cpp -mex -O5 ns2ClassA_afunction.cpp - -cd @ns2ClassA -mex -O5 memberFunction.cpp -mex -O5 nsArg.cpp -mex -O5 nsReturn.cpp - -%% ns2ns3ClassB -cd(toolboxpath) -mex -O5 new_ns2ns3ClassB_.cpp -mex -O5 delete_ns2ns3ClassB.cpp - -cd @ns2ns3ClassB - -%% ns2ClassC -cd(toolboxpath) -mex -O5 new_ns2ClassC_.cpp -mex -O5 delete_ns2ClassC.cpp - -cd @ns2ClassC - -%% ClassD -cd(toolboxpath) -mex -O5 new_ClassD_.cpp -mex -O5 delete_ClassD.cpp - -cd @ClassD - -cd(toolboxpath) - -echo off diff --git a/wrap/tests/expected_namespaces/new_ClassD_.cpp b/wrap/tests/expected_namespaces/new_ClassD_.cpp deleted file mode 100644 index 59ea4398b..000000000 --- a/wrap/tests/expected_namespaces/new_ClassD_.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ClassD_",nargout,nargin,0); - ClassD* self = new ClassD(); - out[0] = wrap_constructed(self,"ClassD"); -} diff --git a/wrap/tests/expected_namespaces/new_ClassD_.m b/wrap/tests/expected_namespaces/new_ClassD_.m deleted file mode 100644 index abfd419f6..000000000 --- a/wrap/tests/expected_namespaces/new_ClassD_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ClassD_(obj) - error('need to compile new_ClassD_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp deleted file mode 100644 index cbb82eb70..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ns1ClassA_",nargout,nargin,0); - ns1::ClassA* self = new ns1::ClassA(); - out[0] = wrap_constructed(self,"ns1ClassA"); -} diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA_.m b/wrap/tests/expected_namespaces/new_ns1ClassA_.m deleted file mode 100644 index 054aba2f0..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassA_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns1ClassA_(obj) - error('need to compile new_ns1ClassA_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp deleted file mode 100644 index d50cede19..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ns1ClassB_",nargout,nargin,0); - ns1::ClassB* self = new ns1::ClassB(); - out[0] = wrap_constructed(self,"ns1ClassB"); -} diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB_.m b/wrap/tests/expected_namespaces/new_ns1ClassB_.m deleted file mode 100644 index b92398a17..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassB_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns1ClassB_(obj) - error('need to compile new_ns1ClassB_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp deleted file mode 100644 index 81bae3198..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ns2ClassA_",nargout,nargin,0); - ns2::ClassA* self = new ns2::ClassA(); - out[0] = wrap_constructed(self,"ns2ClassA"); -} diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA_.m b/wrap/tests/expected_namespaces/new_ns2ClassA_.m deleted file mode 100644 index 88dedf719..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassA_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ClassA_(obj) - error('need to compile new_ns2ClassA_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp deleted file mode 100644 index fbee07926..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ns2ClassC_",nargout,nargin,0); - ns2::ClassC* self = new ns2::ClassC(); - out[0] = wrap_constructed(self,"ns2ClassC"); -} diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC_.m b/wrap/tests/expected_namespaces/new_ns2ClassC_.m deleted file mode 100644 index b3f711e16..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassC_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ClassC_(obj) - error('need to compile new_ns2ClassC_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp deleted file mode 100644 index ca9d02df3..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_ns2ns3ClassB_",nargout,nargin,0); - ns2::ns3::ClassB* self = new ns2::ns3::ClassB(); - out[0] = wrap_constructed(self,"ns2ns3ClassB"); -} diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m deleted file mode 100644 index 2696c2498..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ns3ClassB_(obj) - error('need to compile new_ns2ns3ClassB_.cpp'); -end diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp deleted file mode 100644 index 72559acf8..000000000 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("ns2ClassA_afunction",nargout,nargin,0); - double result = ns2::ClassA::afunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m b/wrap/tests/expected_namespaces/ns2ClassA_afunction.m deleted file mode 100644 index 3a1101918..000000000 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m +++ /dev/null @@ -1,5 +0,0 @@ - automatically generated by wrap -function result = ns2ClassA_afunction() -% usage: x = ns2ClassA_afunction() - error('need to compile ns2ClassA_afunction.cpp'); -end diff --git a/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp new file mode 100644 index 000000000..29739a2f6 --- /dev/null +++ b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp @@ -0,0 +1,435 @@ +#include +#include +#include + +#include +#include +#include +#include +#include + + +typedef std::set*> Collector_ns1ClassA; +static Collector_ns1ClassA collector_ns1ClassA; +typedef std::set*> Collector_ns1ClassB; +static Collector_ns1ClassB collector_ns1ClassB; +typedef std::set*> Collector_ns2ClassA; +static Collector_ns2ClassA collector_ns2ClassA; +typedef std::set*> Collector_ns2ns3ClassB; +static Collector_ns2ns3ClassB collector_ns2ns3ClassB; +typedef std::set*> Collector_ns2ClassC; +static Collector_ns2ClassC collector_ns2ClassC; +typedef std::set*> Collector_ClassD; +static Collector_ClassD collector_ClassD; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); + iter != collector_ns1ClassA.end(); ) { + delete *iter; + collector_ns1ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns1ClassB::iterator iter = collector_ns1ClassB.begin(); + iter != collector_ns1ClassB.end(); ) { + delete *iter; + collector_ns1ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassA::iterator iter = collector_ns2ClassA.begin(); + iter != collector_ns2ClassA.end(); ) { + delete *iter; + collector_ns2ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ns3ClassB::iterator iter = collector_ns2ns3ClassB.begin(); + iter != collector_ns2ns3ClassB.end(); ) { + delete *iter; + collector_ns2ns3ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassC::iterator iter = collector_ns2ClassC.begin(); + iter != collector_ns2ClassC.end(); ) { + delete *iter; + collector_ns2ClassC.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ClassD::iterator iter = collector_ClassD.begin(); + iter != collector_ClassD.end(); ) { + delete *iter; + collector_ClassD.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _testNamespaces_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_testNamespaces_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + BOOST_FOREACH(const StringPair& rtti_matlab, types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_testNamespaces_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void ns1ClassA_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassA.insert(self); +} + +void ns1ClassA_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassA()); + collector_ns1ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassA_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassA::iterator item; + item = collector_ns1ClassA.find(self); + if(item != collector_ns1ClassA.end()) { + delete self; + collector_ns1ClassA.erase(item); + } +} + +void ns1ClassB_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassB.insert(self); +} + +void ns1ClassB_constructor_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassB()); + collector_ns1ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassB_deconstructor_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassB::iterator item; + item = collector_ns1ClassB.find(self); + if(item != collector_ns1ClassB.end()) { + delete self; + collector_ns1ClassB.erase(item); + } +} + +void ns2ClassA_collectorInsertAndMakeBase_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassA.insert(self); +} + +void ns2ClassA_constructor_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassA()); + collector_ns2ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassA_deconstructor_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassA::iterator item; + item = collector_ns2ClassA.find(self); + if(item != collector_ns2ClassA.end()) { + delete self; + collector_ns2ClassA.erase(item); + } +} + +void ns2ClassA_memberFunction_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("memberFunction",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + out[0] = wrap< double >(obj->memberFunction()); +} + +void ns2ClassA_nsArg_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("nsArg",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ptr_ns1ClassB"); + out[0] = wrap< int >(obj->nsArg(arg)); +} + +void ns2ClassA_nsReturn_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedClassB; + typedef boost::shared_ptr Shared; + checkArguments("nsReturn",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + double q = unwrap< double >(in[1]); + out[0] = wrap_shared_ptr(SharedClassB(new ns2::ns3::ClassB(obj->nsReturn(q))),"ns2.ns3.ClassB", false); +} + +void ns2ClassA_afunction_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("ns2ClassA.afunction",nargout,nargin,0); + out[0] = wrap< double >(ns2::ClassA::afunction()); +} + +void ns2ns3ClassB_collectorInsertAndMakeBase_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ns3ClassB.insert(self); +} + +void ns2ns3ClassB_constructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ns3::ClassB()); + collector_ns2ns3ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ns3ClassB_deconstructor_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ns3ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ns3ClassB::iterator item; + item = collector_ns2ns3ClassB.find(self); + if(item != collector_ns2ns3ClassB.end()) { + delete self; + collector_ns2ns3ClassB.erase(item); + } +} + +void ns2ClassC_collectorInsertAndMakeBase_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassC.insert(self); +} + +void ns2ClassC_constructor_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassC()); + collector_ns2ClassC.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassC_deconstructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassC",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassC::iterator item; + item = collector_ns2ClassC.find(self); + if(item != collector_ns2ClassC.end()) { + delete self; + collector_ns2ClassC.erase(item); + } +} + +void ClassD_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ClassD.insert(self); +} + +void ClassD_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ClassD()); + collector_ClassD.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ClassD_deconstructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ClassD",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ClassD::iterator item; + item = collector_ClassD.find(self); + if(item != collector_ClassD.end()) { + delete self; + collector_ClassD.erase(item); + } +} + +void ns1aGlobalFunction_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("ns1aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(ns1::aGlobalFunction()); +} + +void ns2aGlobalFunction_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("ns2aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(ns2::aGlobalFunction()); +} + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _testNamespaces_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + ns1ClassA_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + ns1ClassA_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + ns1ClassA_deconstructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + ns1ClassB_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); + break; + case 4: + ns1ClassB_constructor_4(nargout, out, nargin-1, in+1); + break; + case 5: + ns1ClassB_deconstructor_5(nargout, out, nargin-1, in+1); + break; + case 6: + ns2ClassA_collectorInsertAndMakeBase_6(nargout, out, nargin-1, in+1); + break; + case 7: + ns2ClassA_constructor_7(nargout, out, nargin-1, in+1); + break; + case 8: + ns2ClassA_deconstructor_8(nargout, out, nargin-1, in+1); + break; + case 9: + ns2ClassA_memberFunction_9(nargout, out, nargin-1, in+1); + break; + case 10: + ns2ClassA_nsArg_10(nargout, out, nargin-1, in+1); + break; + case 11: + ns2ClassA_nsReturn_11(nargout, out, nargin-1, in+1); + break; + case 12: + ns2ClassA_afunction_12(nargout, out, nargin-1, in+1); + break; + case 13: + ns2ns3ClassB_collectorInsertAndMakeBase_13(nargout, out, nargin-1, in+1); + break; + case 14: + ns2ns3ClassB_constructor_14(nargout, out, nargin-1, in+1); + break; + case 15: + ns2ns3ClassB_deconstructor_15(nargout, out, nargin-1, in+1); + break; + case 16: + ns2ClassC_collectorInsertAndMakeBase_16(nargout, out, nargin-1, in+1); + break; + case 17: + ns2ClassC_constructor_17(nargout, out, nargin-1, in+1); + break; + case 18: + ns2ClassC_deconstructor_18(nargout, out, nargin-1, in+1); + break; + case 19: + ClassD_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); + break; + case 20: + ClassD_constructor_20(nargout, out, nargin-1, in+1); + break; + case 21: + ClassD_deconstructor_21(nargout, out, nargin-1, in+1); + break; + case 22: + ns1aGlobalFunction_22(nargout, out, nargin-1, in+1); + break; + case 23: + ns2aGlobalFunction_23(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index a287c44e6..54694a1cf 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -15,9 +15,6 @@ class Point2 { VectorNotEigen vectorConfusion(); }; -// flag a namespace as in use - only applies *after* the declaration -using namespace geometry; - class Point3 { Point3(double x, double y, double z); double norm() const; @@ -35,7 +32,9 @@ class Point3 { * A multi-line comment! */ +// An include! Can go anywhere outside of a class, in any order #include + class Test { /* a comment! */ @@ -80,6 +79,9 @@ class Test { // even more comments at the end! }; + +Vector aGlobalFunction(); + // comments at the end! // even more comments at the end! diff --git a/wrap/tests/testDependencies.h b/wrap/tests/testDependencies.h index 429bb5a2a..34a8056b8 100644 --- a/wrap/tests/testDependencies.h +++ b/wrap/tests/testDependencies.h @@ -1,24 +1,8 @@ //Header file to test dependency checking // class Pose3 { - Pose3(); - Pose3(const Rot3& r, const Point3& t);//What is Rot3? Throw here - Pose3(Vector v); - Pose3(Matrix t); - static Pose3 Expmap(Vector v); - static Vector Logmap(const Pose3& p); - static Rot3 testStaticDep(Rot3& r);//What is Rot3? Throw here - void print(string s) const; - bool equals(const Pose3& pose, double tol) const; - double x() const; - double y() const; - double z() const; - Rot3 testReturnType() const; // Throw here - Matrix matrix() const; - Matrix adjointMap() const; - Pose3 compose(const Pose3& p2); - Pose3 between(const Pose3& p2); - Pose3 retract(Vector v); - Point3 translation() const; - Rot3 rotation() const; //What is Rot3? Throw here + Pose3(const Rot3& r, const Point3& t); //What is Rot3? Throw here + static Rot3 testStaticDep(Rot3& r); //What is Rot3? Throw here + Rot3 testReturnType() const; // Throw here + void testMethodArg(const Rot3& r) const; }; diff --git a/wrap/tests/testNamespaces.h b/wrap/tests/testNamespaces.h index 644fdb3ea..2c12686c0 100644 --- a/wrap/tests/testNamespaces.h +++ b/wrap/tests/testNamespaces.h @@ -14,7 +14,10 @@ class ClassB { ClassB(); }; -}///\namespace ns1 +// check namespace handling +Vector aGlobalFunction(); + +} #include namespace ns2 { @@ -35,13 +38,16 @@ class ClassB { ClassB(); }; -}///\namespace ns3 +} class ClassC { ClassC(); }; -}///\namespace ns2 +// separate namespace global function, same name +Vector aGlobalFunction(); + +} //\namespace ns2 class ClassD { ClassD(); diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index cdee692a5..844281775 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include @@ -28,6 +29,7 @@ using namespace std; using namespace boost::assign; using namespace wrap; +namespace fs = boost::filesystem; static bool enable_verbose = false; #ifdef TOPSRCDIR static string topdir = TOPSRCDIR; @@ -37,6 +39,10 @@ static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not define typedef vector strvec; +// NOTE: as this path is only used to generate makefiles, it is hardcoded here for testing +// In practice, this path will be an absolute system path, which makes testing it more annoying +static const std::string headerPath = "/not_really_a_real_path/borg/gtsam/wrap"; + /* ************************************************************************* */ TEST( wrap, ArgumentList ) { ArgumentList args; @@ -52,89 +58,105 @@ TEST( wrap, ArgumentList ) { } /* ************************************************************************* */ -TEST( wrap, check_exception ) { +TEST_UNSAFE( wrap, check_exception ) { THROWS_EXCEPTION(Module("/notarealpath", "geometry",enable_verbose)); CHECK_EXCEPTION(Module("/alsonotarealpath", "geometry",enable_verbose), CantOpenFile); // clean out previous generated code - string cleanCmd = "rm -rf actual_deps"; - system(cleanCmd.c_str()); + fs::remove_all("actual_deps"); string path = topdir + "/wrap/tests"; Module module(path.c_str(), "testDependencies",enable_verbose); - CHECK_EXCEPTION(module.matlab_code("actual_deps", "mexa64", "-O5"), DependencyMissing); + CHECK_EXCEPTION(module.matlab_code("actual_deps", headerPath), DependencyMissing); } /* ************************************************************************* */ -TEST( wrap, parse ) { - string header_path = topdir + "/wrap/tests"; - Module module(header_path.c_str(), "geometry",enable_verbose); +TEST( wrap, parse_geometry ) { + string markup_header_path = topdir + "/wrap/tests"; + Module module(markup_header_path.c_str(), "geometry",enable_verbose); EXPECT_LONGS_EQUAL(3, module.classes.size()); - // check using declarations - strvec exp_using1, exp_using2; exp_using2 += "geometry"; - // forward declarations - strvec exp_forward; exp_forward += "VectorNotEigen", "ns::OtherClass"; - EXPECT(assert_equal(exp_forward, module.forward_declarations)); + LONGS_EQUAL(2, module.forward_declarations.size()); + EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name)); + EXPECT(assert_equal("ns::OtherClass", module.forward_declarations[1].name)); + + // includes + strvec exp_includes; exp_includes += "folder/path/to/Test.h"; + EXPECT(assert_equal(exp_includes, module.includes)); + + LONGS_EQUAL(3, module.classes.size()); // check first class, Point2 { Class cls = module.classes.at(0); EXPECT(assert_equal("Point2", cls.name)); - EXPECT_LONGS_EQUAL(2, cls.constructors.size()); + EXPECT_LONGS_EQUAL(2, cls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(7, cls.methods.size()); EXPECT_LONGS_EQUAL(0, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); - EXPECT(assert_equal(exp_using1, cls.using_namespaces)); } // check second class, Point3 { Class cls = module.classes.at(1); EXPECT(assert_equal("Point3", cls.name)); - EXPECT_LONGS_EQUAL(1, cls.constructors.size()); + EXPECT_LONGS_EQUAL(1, cls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(1, cls.methods.size()); EXPECT_LONGS_EQUAL(2, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); - EXPECT(assert_equal(exp_using2, cls.using_namespaces)); // first constructor takes 3 doubles - Constructor c1 = cls.constructors.front(); - EXPECT_LONGS_EQUAL(3, c1.args.size()); + ArgumentList c1 = cls.constructor.args_list.front(); + EXPECT_LONGS_EQUAL(3, c1.size()); // check first double argument - Argument a1 = c1.args.front(); + Argument a1 = c1.front(); EXPECT(!a1.is_const); EXPECT(assert_equal("double", a1.type)); EXPECT(!a1.is_ref); EXPECT(assert_equal("x", a1.name)); // check method - Method m1 = cls.methods.front(); - EXPECT(assert_equal("double", m1.returnVal.type1)); + CHECK(cls.methods.find("norm") != cls.methods.end()); + Method m1 = cls.methods.find("norm")->second; + LONGS_EQUAL(1, m1.returnVals.size()); + EXPECT(assert_equal("double", m1.returnVals.front().type1)); EXPECT(assert_equal("norm", m1.name)); - EXPECT_LONGS_EQUAL(0, m1.args.size()); + LONGS_EQUAL(1, m1.argLists.size()); + EXPECT_LONGS_EQUAL(0, m1.argLists.front().size()); EXPECT(m1.is_const_); } // Test class is the third one { - LONGS_EQUAL(3, module.classes.size()); Class testCls = module.classes.at(2); - EXPECT_LONGS_EQUAL( 2, testCls.constructors.size()); + EXPECT_LONGS_EQUAL( 2, testCls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(19, testCls.methods.size()); EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size()); EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size()); - EXPECT(assert_equal(exp_using2, testCls.using_namespaces)); - strvec exp_includes; exp_includes += "folder/path/to/Test.h"; - EXPECT(assert_equal(exp_includes, testCls.includes)); // function to parse: pair return_pair (Vector v, Matrix A) const; - Method m2 = testCls.methods.front(); - EXPECT(m2.returnVal.isPair); - EXPECT(m2.returnVal.category1 == ReturnValue::EIGEN); - EXPECT(m2.returnVal.category2 == ReturnValue::EIGEN); + CHECK(testCls.methods.find("return_pair") != testCls.methods.end()); + Method m2 = testCls.methods.find("return_pair")->second; + LONGS_EQUAL(1, m2.returnVals.size()); + EXPECT(m2.returnVals.front().isPair); + EXPECT(m2.returnVals.front().category1 == ReturnValue::EIGEN); + EXPECT(m2.returnVals.front().category2 == ReturnValue::EIGEN); + } + + // evaluate global functions +// Vector aGlobalFunction(); + LONGS_EQUAL(1, module.global_functions.size()); + CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end()); + { + GlobalFunction gfunc = module.global_functions.at("aGlobalFunction"); + EXPECT(assert_equal("aGlobalFunction", gfunc.name)); + LONGS_EQUAL(1, gfunc.returnVals.size()); + EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1)); + EXPECT_LONGS_EQUAL(1, gfunc.argLists.size()); + LONGS_EQUAL(1, gfunc.namespaces.size()); + EXPECT(gfunc.namespaces.front().empty()); } } @@ -144,13 +166,21 @@ TEST( wrap, parse_namespaces ) { Module module(header_path.c_str(), "testNamespaces",enable_verbose); EXPECT_LONGS_EQUAL(6, module.classes.size()); + { + strvec module_exp_includes; + module_exp_includes += "path/to/ns1.h"; + module_exp_includes += "path/to/ns1/ClassB.h"; + module_exp_includes += "path/to/ns2.h"; + module_exp_includes += "path/to/ns2/ClassA.h"; + module_exp_includes += "path/to/ns3.h"; + EXPECT(assert_equal(module_exp_includes, module.includes)); + } + { Class cls = module.classes.at(0); EXPECT(assert_equal("ClassA", cls.name)); strvec exp_namespaces; exp_namespaces += "ns1"; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += "path/to/ns1.h", ""; - EXPECT(assert_equal(exp_includes, cls.includes)); } { @@ -158,8 +188,6 @@ TEST( wrap, parse_namespaces ) { EXPECT(assert_equal("ClassB", cls.name)); strvec exp_namespaces; exp_namespaces += "ns1"; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += "path/to/ns1.h", "path/to/ns1/ClassB.h"; - EXPECT(assert_equal(exp_includes, cls.includes)); } { @@ -167,8 +195,6 @@ TEST( wrap, parse_namespaces ) { EXPECT(assert_equal("ClassA", cls.name)); strvec exp_namespaces; exp_namespaces += "ns2"; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += "path/to/ns2.h", "path/to/ns2/ClassA.h"; - EXPECT(assert_equal(exp_includes, cls.includes)); } { @@ -176,8 +202,6 @@ TEST( wrap, parse_namespaces ) { EXPECT(assert_equal("ClassB", cls.name)); strvec exp_namespaces; exp_namespaces += "ns2", "ns3"; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += "path/to/ns2.h", "path/to/ns3.h", ""; - EXPECT(assert_equal(exp_includes, cls.includes)); } { @@ -185,8 +209,6 @@ TEST( wrap, parse_namespaces ) { EXPECT(assert_equal("ClassC", cls.name)); strvec exp_namespaces; exp_namespaces += "ns2"; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += "path/to/ns2.h", ""; - EXPECT(assert_equal(exp_includes, cls.includes)); } { @@ -194,10 +216,28 @@ TEST( wrap, parse_namespaces ) { EXPECT(assert_equal("ClassD", cls.name)); strvec exp_namespaces; EXPECT(assert_equal(exp_namespaces, cls.namespaces)); - strvec exp_includes; exp_includes += ""; - EXPECT(assert_equal(exp_includes, cls.includes)); } + // evaluate global functions +// Vector ns1::aGlobalFunction(); +// Vector ns2::aGlobalFunction(); + LONGS_EQUAL(1, module.global_functions.size()); + CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end()); + { + GlobalFunction gfunc = module.global_functions.at("aGlobalFunction"); + EXPECT(assert_equal("aGlobalFunction", gfunc.name)); + LONGS_EQUAL(2, gfunc.returnVals.size()); + EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1)); + EXPECT_LONGS_EQUAL(2, gfunc.argLists.size()); + + // check namespaces + LONGS_EQUAL(2, gfunc.namespaces.size()); + strvec exp_namespaces1; exp_namespaces1 += "ns1"; + EXPECT(assert_equal(exp_namespaces1, gfunc.namespaces.at(0))); + + strvec exp_namespaces2; exp_namespaces2 += "ns2"; + EXPECT(assert_equal(exp_namespaces2, gfunc.namespaces.at(1))); + } } /* ************************************************************************* */ @@ -208,95 +248,44 @@ TEST( wrap, matlab_code_namespaces ) { string path = topdir + "/wrap"; // clean out previous generated code - string cleanCmd = "rm -rf actual_namespaces"; - system(cleanCmd.c_str()); + fs::remove_all("actual_namespaces"); // emit MATLAB code - string exp_path = path + "/tests/expected_namespaces/"; - string act_path = "actual_namespaces/"; - module.matlab_code("actual_namespaces", "mexa64", "-O5"); + string exp_path = path + "/tests/expected_namespaces/"; + string act_path = "actual_namespaces/"; + module.matlab_code("actual_namespaces", headerPath); - EXPECT(files_equal(exp_path + "new_ClassD_.cpp" , act_path + "new_ClassD_.cpp" )); - EXPECT(files_equal(exp_path + "new_ClassD_.m" , act_path + "new_ClassD_.m" )); - EXPECT(files_equal(exp_path + "new_ns1ClassA_.cpp" , act_path + "new_ns1ClassA_.cpp" )); - EXPECT(files_equal(exp_path + "new_ns1ClassA_.m" , act_path + "new_ns1ClassA_.m" )); - EXPECT(files_equal(exp_path + "new_ns1ClassB_.cpp" , act_path + "new_ns1ClassB_.cpp" )); - EXPECT(files_equal(exp_path + "new_ns1ClassB_.m" , act_path + "new_ns1ClassB_.m" )); - EXPECT(files_equal(exp_path + "new_ns2ClassA_.cpp" , act_path + "new_ns2ClassA_.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ClassA_.m" , act_path + "new_ns2ClassA_.m" )); - EXPECT(files_equal(exp_path + "new_ns2ClassC_.cpp" , act_path + "new_ns2ClassC_.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ClassC_.m" , act_path + "new_ns2ClassC_.m" )); - EXPECT(files_equal(exp_path + "new_ns2ns3ClassB_.cpp" , act_path + "new_ns2ns3ClassB_.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ns3ClassB_.m" , act_path + "new_ns2ns3ClassB_.m" )); - EXPECT(files_equal(exp_path + "delete_ClassD.cpp" , act_path + "delete_ClassD.cpp" )); - EXPECT(files_equal(exp_path + "delete_ClassD.m" , act_path + "delete_ClassD.m" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassA.cpp" , act_path + "delete_ns1ClassA.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassA.m" , act_path + "delete_ns1ClassA.m" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassB.cpp" , act_path + "delete_ns1ClassB.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassB.m" , act_path + "delete_ns1ClassB.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassA.cpp" , act_path + "delete_ns2ClassA.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassA.m" , act_path + "delete_ns2ClassA.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassC.cpp" , act_path + "delete_ns2ClassC.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassC.m" , act_path + "delete_ns2ClassC.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ns3ClassB.cpp" , act_path + "delete_ns2ns3ClassB.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ns3ClassB.m" , act_path + "delete_ns2ns3ClassB.m" )); - EXPECT(files_equal(exp_path + "ns2ClassA_afunction.cpp" , act_path + "ns2ClassA_afunction.cpp" )); - EXPECT(files_equal(exp_path + "ns2ClassA_afunction.m" , act_path + "ns2ClassA_afunction.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/memberFunction.cpp", act_path + "@ns2ClassA/memberFunction.cpp")); - EXPECT(files_equal(exp_path + "@ns2ClassA/memberFunction.m" , act_path + "@ns2ClassA/memberFunction.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/ns2ClassA.m" , act_path + "@ns2ClassA/ns2ClassA.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsArg.cpp" , act_path + "@ns2ClassA/nsArg.cpp" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsArg.m" , act_path + "@ns2ClassA/nsArg.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsReturn.cpp" , act_path + "@ns2ClassA/nsReturn.cpp" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsReturn.m" , act_path + "@ns2ClassA/nsReturn.m" )); - - EXPECT(files_equal(exp_path + "make_testNamespaces.m", act_path + "make_testNamespaces.m")); - EXPECT(files_equal(exp_path + "Makefile" , act_path + "Makefile" )); + EXPECT(files_equal(exp_path + "ClassD.m" , act_path + "ClassD.m" )); + EXPECT(files_equal(exp_path + "+ns1/ClassA.m" , act_path + "+ns1/ClassA.m" )); + EXPECT(files_equal(exp_path + "+ns1/ClassB.m" , act_path + "+ns1/ClassB.m" )); + EXPECT(files_equal(exp_path + "+ns2/ClassA.m" , act_path + "+ns2/ClassA.m" )); + EXPECT(files_equal(exp_path + "+ns2/ClassC.m" , act_path + "+ns2/ClassC.m" )); + EXPECT(files_equal(exp_path + "+ns2/+ns3/ClassB.m" , act_path + "+ns2/+ns3/ClassB.m" )); + EXPECT(files_equal(exp_path + "testNamespaces_wrapper.cpp" , act_path + "testNamespaces_wrapper.cpp" )); } /* ************************************************************************* */ -TEST( wrap, matlab_code ) { +TEST( wrap, matlab_code_geometry ) { // Parse into class object string header_path = topdir + "/wrap/tests"; Module module(header_path,"geometry",enable_verbose); string path = topdir + "/wrap"; // clean out previous generated code - string cleanCmd = "rm -rf actual"; - system(cleanCmd.c_str()); + fs::remove_all("actual"); // emit MATLAB code // make_geometry will not compile, use make testwrap to generate real make - module.matlab_code("actual", "mexa64", "-O5"); + module.matlab_code("actual", headerPath); + string epath = path + "/tests/expected/"; + string apath = "actual/"; - EXPECT(files_equal(path + "/tests/expected/@Point2/Point2.m" , "actual/@Point2/Point2.m" )); - EXPECT(files_equal(path + "/tests/expected/@Point2/x.cpp" , "actual/@Point2/x.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Point3/Point3.m" , "actual/@Point3/Point3.m" )); - EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.m" , "actual/new_Point3_ddd.m" )); - EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.cpp", "actual/new_Point3_ddd.cpp")); - EXPECT(files_equal(path + "/tests/expected/Point3_staticFunction.m" , "actual/Point3_staticFunction.m" )); - EXPECT(files_equal(path + "/tests/expected/Point3_staticFunction.cpp", "actual/Point3_staticFunction.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Point3/norm.m" , "actual/@Point3/norm.m" )); - EXPECT(files_equal(path + "/tests/expected/@Point3/norm.cpp" , "actual/@Point3/norm.cpp" )); - - EXPECT(files_equal(path + "/tests/expected/new_Test_.cpp" , "actual/new_Test_.cpp" )); - EXPECT(files_equal(path + "/tests/expected/delete_Test.cpp" , "actual/delete_Test.cpp" )); - EXPECT(files_equal(path + "/tests/expected/delete_Test.m" , "actual/delete_Test.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/Test.m" , "actual/@Test/Test.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_string.cpp" , "actual/@Test/return_string.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_pair.cpp" , "actual/@Test/return_pair.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/create_MixedPtrs.cpp", "actual/@Test/create_MixedPtrs.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_field.cpp" , "actual/@Test/return_field.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_TestPtr.cpp", "actual/@Test/return_TestPtr.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_Test.cpp" , "actual/@Test/return_Test.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_Point2Ptr.cpp", "actual/@Test/return_Point2Ptr.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_ptrs.cpp" , "actual/@Test/return_ptrs.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/print.m" , "actual/@Test/print.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/print.cpp" , "actual/@Test/print.cpp" )); - - EXPECT(files_equal(path + "/tests/expected/make_geometry.m", "actual/make_geometry.m")); - EXPECT(files_equal(path + "/tests/expected/Makefile" , "actual/Makefile" )); + EXPECT(files_equal(epath + "geometry_wrapper.cpp" , apath + "geometry_wrapper.cpp" )); + EXPECT(files_equal(epath + "Point2.m" , apath + "Point2.m" )); + EXPECT(files_equal(epath + "Point3.m" , apath + "Point3.m" )); + EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" )); + EXPECT(files_equal(epath + "aGlobalFunction.m" , apath + "aGlobalFunction.m" )); } /* ************************************************************************* */ diff --git a/wrap/utilities.cpp b/wrap/utilities.cpp index 7b82d9b9d..973778d71 100644 --- a/wrap/utilities.cpp +++ b/wrap/utilities.cpp @@ -12,12 +12,15 @@ /** * @file utilities.ccp * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #include #include #include +#include #include "utilities.h" @@ -103,33 +106,44 @@ bool files_equal(const string& expected, const string& actual, bool skipheader) } /* ************************************************************************* */ -string maybe_shared_ptr(bool add, const string& type) { - string str = add? "shared_ptr<" : ""; - str += type; - if (add) str += ">"; +string maybe_shared_ptr(bool add, const string& qtype, const string& type) { + string str = add? "Shared" : ""; + if (add) str += type; + else str += qtype; + + //if (add) str += ">"; return str; } /* ************************************************************************* */ -void generateUsingNamespace(FileWriter& file, const vector& using_namespaces) { - if (using_namespaces.empty()) return; - BOOST_FOREACH(const string& s, using_namespaces) - file.oss << "using namespace " << s << ";" << endl; +string qualifiedName(const string& separator, const vector& names, const string& finalName) { + string result; + if(!names.empty()) { + for(size_t i = 0; i < names.size() - 1; ++i) + result += (names[i] + separator); + if(finalName.empty()) + result += names.back(); + else + result += (names.back() + separator + finalName); + } else if(!finalName.empty()) { + result = finalName; + } + return result; } /* ************************************************************************* */ -void generateIncludes(FileWriter& file, const string& class_name, - const vector& includes) { - file.oss << "#include " << endl; - bool added_include = false; - BOOST_FOREACH(const string& s, includes) { - if (!s.empty()) { - file.oss << "#include <" << s << ">" << endl; - added_include = true; +void createNamespaceStructure(const std::vector& namespaces, const std::string& toolboxPath) { + using namespace boost::filesystem; + path curPath = toolboxPath; + BOOST_FOREACH(const string& subdir, namespaces) { + curPath /= "+" + subdir; + if(!is_directory(curPath)) { + if(exists("+" + subdir)) + throw OutputError("Need to write files to directory " + curPath.string() + ", which already exists as a file but is not a directory"); + else + boost::filesystem::create_directory(curPath); } } - if (!added_include) // add default include - file.oss << "#include <" << class_name << ".h>" << endl; } /* ************************************************************************* */ diff --git a/wrap/utilities.h b/wrap/utilities.h index 384ff3749..85a2246a2 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -10,8 +10,10 @@ * -------------------------------------------------------------------------- */ /** - * @file utilities.ccp + * @file utilities.h * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts **/ #pragma once @@ -20,6 +22,11 @@ #include #include #include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC +#include +#include #include "FileWriter.h" @@ -27,44 +34,73 @@ namespace wrap { class CantOpenFile : public std::exception { private: - std::string filename_; + const std::string what_; public: - CantOpenFile(const std::string& filename) : filename_(filename) {} + CantOpenFile(const std::string& filename) : what_("Can't open file " + filename) {} ~CantOpenFile() throw() {} - virtual const char* what() const throw() { - return ("Can't open file " + filename_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } +}; + +class OutputError : public std::exception { +private: + const std::string what_; +public: + OutputError(const std::string& what) : what_(what) {} + ~OutputError() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } }; class ParseFailed : public std::exception { private: - int length_; + const std::string what_; public: - ParseFailed(int length) : length_(length) {} - ~ParseFailed() throw() {} - virtual const char* what() const throw() { - std::stringstream buf; - int len = length_+1; - buf << "Parse failed at character [" << len << "]"; - return buf.str().c_str(); - } + ParseFailed(int length) : what_((boost::format("Parse failed at character [%d]")%(length-1)).str()) {} + ~ParseFailed() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } }; class DependencyMissing : public std::exception { private: - std::string dependency_; - std::string location_; + const std::string what_; public: - DependencyMissing(const std::string& dep, const std::string& loc) { - dependency_ = dep; - location_ = loc; - } + DependencyMissing(const std::string& dep, const std::string& loc) : + what_("Missing dependency " + dep + " in " + loc) {} ~DependencyMissing() throw() {} - virtual const char* what() const throw() { - return ("Missing dependency " + dependency_ + " in " + location_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } }; +class DuplicateDefinition : public std::exception { +private: + const std::string what_; +public: + DuplicateDefinition(const std::string& name) : + what_("Duplicate definition of " + name) {} + ~DuplicateDefinition() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } +}; + +class AttributeError : public std::exception { +private: + const std::string what_; +public: + AttributeError(const std::string& name, const std::string& problem) : + what_("Class " + name + ": " + problem) {} + ~AttributeError() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } +}; + +// "Unique" key to signal calling the matlab object constructor with a raw pointer +// to a shared pointer of the same C++ object type as the MATLAB type. +// Also present in matlab.h +static const uint64_t ptr_constructor_key = + (uint64_t('G') << 56) | + (uint64_t('T') << 48) | + (uint64_t('S') << 40) | + (uint64_t('A') << 32) | + (uint64_t('M') << 24) | + (uint64_t('p') << 16) | + (uint64_t('t') << 8) | + (uint64_t('r')); /** * read contents of a file into a std::string @@ -84,17 +120,15 @@ bool assert_equal(const std::string& expected, const std::string& actual); bool assert_equal(const std::vector& expected, const std::vector& actual); // auxiliary function to wrap an argument into a shared_ptr template -std::string maybe_shared_ptr(bool add, const std::string& type); +std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::string& type); /** - * Creates the "using namespace [name];" declarations + * Return a qualified name, if finalName is empty, only the names vector will + * be used (i.e. there won't be a trailing separator on the qualified name). */ -void generateUsingNamespace(FileWriter& file, const std::vector& using_namespaces); +std::string qualifiedName(const std::string& separator, const std::vector& names, const std::string& finalName = ""); -/** - * Creates the #include statements - */ -void generateIncludes(FileWriter& file, const std::string& class_name, - const std::vector& includes); +/** creates the necessary folders for namespaces, as specified by a namespace stack */ +void createNamespaceStructure(const std::vector& namespaces, const std::string& toolboxPath); } // \namespace wrap diff --git a/wrap/wrap.cpp b/wrap/wrap.cpp index f55927a5e..05763d892 100644 --- a/wrap/wrap.cpp +++ b/wrap/wrap.cpp @@ -24,36 +24,33 @@ using namespace std; /** * Top-level function to wrap a module - * @param mexExt is the extension for mex binaries for this os/cpu * @param interfacePath path to where interface file lives, e.g., borg/gtsam * @param moduleName name of the module to be generated e.g. gtsam * @param toolboxPath path where the toolbox should be generated, e.g. borg/gtsam/build - * @param nameSpace e.g. gtsam - * @param mexFlags extra arguments for mex script, i.e., include flags etc... + * @param headerPath is the path to matlab.h */ -void generate_matlab_toolbox(const string& mexExt, +void generate_matlab_toolbox( const string& interfacePath, const string& moduleName, const string& toolboxPath, - const string& mexFlags) + const string& headerPath) { // Parse interface file into class object // This recursively creates Class objects, Method objects, etc... - wrap::Module module(interfacePath, moduleName, true); + wrap::Module module(interfacePath, moduleName, false); // Then emit MATLAB code - module.matlab_code(toolboxPath,mexExt,mexFlags); + module.matlab_code(toolboxPath,headerPath); } /** Displays usage information */ void usage() { cerr << "wrap parses an interface file and produces a MATLAB toolbox" << endl; - cerr << "usage: wrap mexExtension interfacePath moduleName toolboxPath [mexFlags]" << endl; - cerr << " mexExtension : OS/CPU-dependent extension for MEX binaries" << endl; + cerr << "usage: wrap interfacePath moduleName toolboxPath headerPath" << endl; cerr << " interfacePath : *absolute* path to directory of module interface file" << endl; cerr << " moduleName : the name of the module, interface file must be called moduleName.h" << endl; cerr << " toolboxPath : the directory in which to generate the wrappers" << endl; - cerr << " [mexFlags] : extra flags for the mex command" << endl; + cerr << " headerPath : path to matlab.h" << endl; } /** @@ -61,7 +58,7 @@ void usage() { * Typically called from "make all" using appropriate arguments */ int main(int argc, const char* argv[]) { - if (argc<6 || argc>7) { + if (argc != 5) { cerr << "Invalid arguments:\n"; for (int i=0; i